From 5d86907da0491164a1116608f0a2e7f231ef27d0 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Pawe=C5=82=20Lech?= Date: Tue, 5 Mar 2024 09:36:15 +0100 Subject: [PATCH 001/304] use_sim_time used in concealer initialization MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Paweł Lech --- simulation/traffic_simulator/src/entity/ego_entity.cpp | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/simulation/traffic_simulator/src/entity/ego_entity.cpp b/simulation/traffic_simulator/src/entity/ego_entity.cpp index e3a056c2dc8..93c2ffb3033 100644 --- a/simulation/traffic_simulator/src/entity/ego_entity.cpp +++ b/simulation/traffic_simulator/src/entity/ego_entity.cpp @@ -40,7 +40,9 @@ static auto getParameter(const std::string & name, T value = {}) { rclcpp::Node node{"get_parameter", "simulation"}; - node.declare_parameter(name, value); + if (!node.has_parameter(name)) { + node.declare_parameter(name, value); + } node.get_parameter(name, value); return value; @@ -67,7 +69,9 @@ auto EgoEntity::makeFieldOperatorApplication(const Configuration & configuration : Configuration::Pathname(rviz_config).string()), "scenario_simulation:=true", "use_foa:=false", "perception/enable_traffic_light:=" + - std::string((architecture_type >= "awf/universe/20230906") ? "true" : "false")) + std::string((architecture_type >= "awf/universe/20230906") ? "true" : "false"), + "use_sim_time:=" + + std::string(getParameter("use_sim_time") ? "true" : "false")) : std::make_unique< concealer::FieldOperatorApplicationFor>(); } else { From 84c8b0c101b8e680ad6029d8702387e5495e2646 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Mon, 17 Jun 2024 11:24:10 +0900 Subject: [PATCH 002/304] fix(RelativeDistanceCondition): Fixed a bug where RelativeDistance showed negative values --- .../syntax/relative_distance_condition.cpp | 72 ++++--------------- 1 file changed, 12 insertions(+), 60 deletions(-) diff --git a/openscenario/openscenario_interpreter/src/syntax/relative_distance_condition.cpp b/openscenario/openscenario_interpreter/src/syntax/relative_distance_condition.cpp index 90e9b7be341..0e65facca87 100644 --- a/openscenario/openscenario_interpreter/src/syntax/relative_distance_condition.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/relative_distance_condition.cpp @@ -181,21 +181,9 @@ auto RelativeDistanceCondition::distance< if ( global().entities->at(entity_ref).as().is_added and global().entities->at(triggering_entity).as().is_added) { - /* - For historical reasons, signed distances are returned when - coordinateSystem == lane and relativeDistanceType == - longitudinal/lateral. The sign has been mainly used to determine the - front/back and left/right positional relationship (a negative value is - returned if the target entity is behind or to the right). - - This behavior violates the OpenSCENARIO standard. In the future, after - DistanceCondition and RelativeDistanceCondition of TIER IV's - OpenSCENARIO Interpreter support OpenSCENARIO 1.2 RoutingAlgorithm, this - behavior will be enabled only when routingAlgorithm == undefined. - */ - return static_cast( - makeNativeRelativeLanePosition(triggering_entity, entity_ref)) - .offset; + return std::abs(static_cast( + makeNativeRelativeLanePosition(triggering_entity, entity_ref)) + .offset); } else { return Double::nan(); } @@ -209,21 +197,9 @@ auto RelativeDistanceCondition::distance< if ( global().entities->at(entity_ref).as().is_added and global().entities->at(triggering_entity).as().is_added) { - /* - For historical reasons, signed distances are returned when - coordinateSystem == lane and relativeDistanceType == - longitudinal/lateral. The sign has been mainly used to determine the - front/back and left/right positional relationship (a negative value is - returned if the target entity is behind or to the right). - - This behavior violates the OpenSCENARIO standard. In the future, after - DistanceCondition and RelativeDistanceCondition of TIER IV's - OpenSCENARIO Interpreter support OpenSCENARIO 1.2 RoutingAlgorithm, this - behavior will be enabled only when routingAlgorithm == undefined. - */ - return static_cast( - makeNativeBoundingBoxRelativeLanePosition(triggering_entity, entity_ref)) - .offset; + return std::abs(static_cast( + makeNativeBoundingBoxRelativeLanePosition(triggering_entity, entity_ref)) + .offset); } else { return Double::nan(); } @@ -237,21 +213,9 @@ auto RelativeDistanceCondition::distance< if ( global().entities->at(triggering_entity).as().is_added and global().entities->at(entity_ref).as().is_added) { - /* - For historical reasons, signed distances are returned when - coordinateSystem == lane and relativeDistanceType == - longitudinal/lateral. The sign has been mainly used to determine the - front/back and left/right positional relationship (a negative value is - returned if the target entity is behind or to the right). - - This behavior violates the OpenSCENARIO standard. In the future, after - DistanceCondition and RelativeDistanceCondition of TIER IV's - OpenSCENARIO Interpreter support OpenSCENARIO 1.2 RoutingAlgorithm, this - behavior will be enabled only when routingAlgorithm == undefined. - */ - return static_cast( - makeNativeRelativeLanePosition(triggering_entity, entity_ref)) - .s; + return std::abs(static_cast( + makeNativeRelativeLanePosition(triggering_entity, entity_ref)) + .s); } else { return Double::nan(); } @@ -265,21 +229,9 @@ auto RelativeDistanceCondition::distance< if ( global().entities->at(triggering_entity).as().is_added and global().entities->at(entity_ref).as().is_added) { - /* - For historical reasons, signed distances are returned when - coordinateSystem == lane and relativeDistanceType == - longitudinal/lateral. The sign has been mainly used to determine the - front/back and left/right positional relationship (a negative value is - returned if the target entity is behind or to the right). - - This behavior violates the OpenSCENARIO standard. In the future, after - DistanceCondition and RelativeDistanceCondition of TIER IV's - OpenSCENARIO Interpreter support OpenSCENARIO 1.2 RoutingAlgorithm, this - behavior will be enabled only when routingAlgorithm == undefined. - */ - return static_cast( - makeNativeBoundingBoxRelativeLanePosition(triggering_entity, entity_ref)) - .s; + return std::abs(static_cast( + makeNativeBoundingBoxRelativeLanePosition(triggering_entity, entity_ref)) + .s); } else { return Double::nan(); } From 038830cc02a4d99f5742a1d219791bc93558ed4c Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Tue, 18 Jun 2024 14:15:11 +0900 Subject: [PATCH 003/304] Revert "fix(RelativeDistanceCondition): Fixed a bug where RelativeDistance showed negative values" This reverts commit 84c8b0c101b8e680ad6029d8702387e5495e2646. --- .../syntax/relative_distance_condition.cpp | 72 +++++++++++++++---- 1 file changed, 60 insertions(+), 12 deletions(-) diff --git a/openscenario/openscenario_interpreter/src/syntax/relative_distance_condition.cpp b/openscenario/openscenario_interpreter/src/syntax/relative_distance_condition.cpp index 0e65facca87..90e9b7be341 100644 --- a/openscenario/openscenario_interpreter/src/syntax/relative_distance_condition.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/relative_distance_condition.cpp @@ -181,9 +181,21 @@ auto RelativeDistanceCondition::distance< if ( global().entities->at(entity_ref).as().is_added and global().entities->at(triggering_entity).as().is_added) { - return std::abs(static_cast( - makeNativeRelativeLanePosition(triggering_entity, entity_ref)) - .offset); + /* + For historical reasons, signed distances are returned when + coordinateSystem == lane and relativeDistanceType == + longitudinal/lateral. The sign has been mainly used to determine the + front/back and left/right positional relationship (a negative value is + returned if the target entity is behind or to the right). + + This behavior violates the OpenSCENARIO standard. In the future, after + DistanceCondition and RelativeDistanceCondition of TIER IV's + OpenSCENARIO Interpreter support OpenSCENARIO 1.2 RoutingAlgorithm, this + behavior will be enabled only when routingAlgorithm == undefined. + */ + return static_cast( + makeNativeRelativeLanePosition(triggering_entity, entity_ref)) + .offset; } else { return Double::nan(); } @@ -197,9 +209,21 @@ auto RelativeDistanceCondition::distance< if ( global().entities->at(entity_ref).as().is_added and global().entities->at(triggering_entity).as().is_added) { - return std::abs(static_cast( - makeNativeBoundingBoxRelativeLanePosition(triggering_entity, entity_ref)) - .offset); + /* + For historical reasons, signed distances are returned when + coordinateSystem == lane and relativeDistanceType == + longitudinal/lateral. The sign has been mainly used to determine the + front/back and left/right positional relationship (a negative value is + returned if the target entity is behind or to the right). + + This behavior violates the OpenSCENARIO standard. In the future, after + DistanceCondition and RelativeDistanceCondition of TIER IV's + OpenSCENARIO Interpreter support OpenSCENARIO 1.2 RoutingAlgorithm, this + behavior will be enabled only when routingAlgorithm == undefined. + */ + return static_cast( + makeNativeBoundingBoxRelativeLanePosition(triggering_entity, entity_ref)) + .offset; } else { return Double::nan(); } @@ -213,9 +237,21 @@ auto RelativeDistanceCondition::distance< if ( global().entities->at(triggering_entity).as().is_added and global().entities->at(entity_ref).as().is_added) { - return std::abs(static_cast( - makeNativeRelativeLanePosition(triggering_entity, entity_ref)) - .s); + /* + For historical reasons, signed distances are returned when + coordinateSystem == lane and relativeDistanceType == + longitudinal/lateral. The sign has been mainly used to determine the + front/back and left/right positional relationship (a negative value is + returned if the target entity is behind or to the right). + + This behavior violates the OpenSCENARIO standard. In the future, after + DistanceCondition and RelativeDistanceCondition of TIER IV's + OpenSCENARIO Interpreter support OpenSCENARIO 1.2 RoutingAlgorithm, this + behavior will be enabled only when routingAlgorithm == undefined. + */ + return static_cast( + makeNativeRelativeLanePosition(triggering_entity, entity_ref)) + .s; } else { return Double::nan(); } @@ -229,9 +265,21 @@ auto RelativeDistanceCondition::distance< if ( global().entities->at(triggering_entity).as().is_added and global().entities->at(entity_ref).as().is_added) { - return std::abs(static_cast( - makeNativeBoundingBoxRelativeLanePosition(triggering_entity, entity_ref)) - .s); + /* + For historical reasons, signed distances are returned when + coordinateSystem == lane and relativeDistanceType == + longitudinal/lateral. The sign has been mainly used to determine the + front/back and left/right positional relationship (a negative value is + returned if the target entity is behind or to the right). + + This behavior violates the OpenSCENARIO standard. In the future, after + DistanceCondition and RelativeDistanceCondition of TIER IV's + OpenSCENARIO Interpreter support OpenSCENARIO 1.2 RoutingAlgorithm, this + behavior will be enabled only when routingAlgorithm == undefined. + */ + return static_cast( + makeNativeBoundingBoxRelativeLanePosition(triggering_entity, entity_ref)) + .s; } else { return Double::nan(); } From 9255d231659845d25aa9054d610603a63b63cc81 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Tue, 18 Jun 2024 14:17:52 +0900 Subject: [PATCH 004/304] feat(openscenario_interpreter): add RelativeLaneRange --- .../syntax/relative_lane_range.hpp | 45 +++++++++++++++++++ .../src/syntax/relative_lane_range.cpp | 27 +++++++++++ 2 files changed, 72 insertions(+) create mode 100644 openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_lane_range.hpp create mode 100644 openscenario/openscenario_interpreter/src/syntax/relative_lane_range.cpp diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_lane_range.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_lane_range.hpp new file mode 100644 index 00000000000..7108b45bf2b --- /dev/null +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_lane_range.hpp @@ -0,0 +1,45 @@ +// Copyright 2015 TIER IV, Inc. All rights reserved. +// +// 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. + +#ifndef OPENSCENARIO_INTERPRETER__SYNTAX__RELATIVE_LANE_RANGE_HPP_ +#define OPENSCENARIO_INTERPRETER__SYNTAX__RELATIVE_LANE_RANGE_HPP_ + +#include +#include +#include + +namespace openscenario_interpreter +{ +inline namespace syntax +{ +/* + RelativeLaneRange (OpenSCENARIO XML 1.3) + + + + + +*/ +struct RelativeLaneRange +{ + const Integer from; + + const Integer to; + + explicit RelativeLaneRange(const pugi::xml_node &, Scope &); +}; +} // namespace syntax +} // namespace openscenario_interpreter + +#endif // OPENSCENARIO_INTERPRETER__SYNTAX__RELATIVE_LANE_RANGE_HPP_ diff --git a/openscenario/openscenario_interpreter/src/syntax/relative_lane_range.cpp b/openscenario/openscenario_interpreter/src/syntax/relative_lane_range.cpp new file mode 100644 index 00000000000..c94ce16d95c --- /dev/null +++ b/openscenario/openscenario_interpreter/src/syntax/relative_lane_range.cpp @@ -0,0 +1,27 @@ +// Copyright 2015 TIER IV, Inc. All rights reserved. +// +// 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. + +#include +#include + +namespace openscenario_interpreter +{ +inline namespace syntax +{ +RelativeLaneRange::RelativeLaneRange(const pugi::xml_node & node, Scope & scope) +: from(readAttribute("from", node, scope)), to(readAttribute("to", node, scope)) +{ +} +} // namespace syntax +} // namespace openscenario_interpreter From 496feb07c12376d09387da18aecced496c914150 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Tue, 18 Jun 2024 14:21:59 +0900 Subject: [PATCH 005/304] feat(openscenario_interpreter): add RelativeClearanceCondition(empty implementation) --- .../syntax/relative_clearance_condition.hpp | 86 +++++++++++++++++++ .../syntax/relative_clearance_condition.cpp | 58 +++++++++++++ 2 files changed, 144 insertions(+) create mode 100644 openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_clearance_condition.hpp create mode 100644 openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_clearance_condition.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_clearance_condition.hpp new file mode 100644 index 00000000000..1255d03da93 --- /dev/null +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_clearance_condition.hpp @@ -0,0 +1,86 @@ +// Copyright 2015 TIER IV, Inc. All rights reserved. +// +// 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. + +#ifndef OPENSCENARIO_INTERPRETER__SYNTAX__RELATIVE_CLEARANCE_CONDITION_HPP_ +#define OPENSCENARIO_INTERPRETER__SYNTAX__RELATIVE_CLEARANCE_CONDITION_HPP_ + +#include +#include +#include +#include +#include +#include + +namespace openscenario_interpreter +{ +inline namespace syntax +{ +/* + RelativeClearanceCondition (OpenSCENARIO XML 1.3) + + + + + + + + + + + +*/ +struct RelativeClearanceCondition : private Scope, private SimulatorCore::ConditionEvaluation +{ + /* + Longitudinal distance behind reference point of the entity to be checked along lane centerline of the current lane of the triggering entity. Orientation of entity towards lane determines backward direction. Velocity of entity is irrelevant. Unit: [m]. Range: [0..inf[. Default if omitted: 0 + */ + const Double distance_backward; + + /* + Longitudinal distance in front of reference point of the entity to be checked along lane centerline of the current lane of the triggering entity. Orientation of entity towards lane determines forward direction. Velocity of entity is irrelevant. Unit: [m]. Range: [0..inf[. Default if omitted: 0 + */ + const Double distance_forward; + + /* + If false, then entityRefs are only considered to be on the lane if their reference point is within the checked area; otherwise the whole bounding box is considered. + */ + const Boolean freespace; + + /* + If true, then also lanes in the opposite direction are considered; otherwise only lanes in the same direction are considered. + */ + const Boolean opposite_lanes; + + /* + The lanes to be checked to left and right of the triggering entity (positive to the y-axis). If omitted: all lanes are checked. + */ + const std::list relative_lane_range; + + /* + Constraint to check only specific entities. If it is not used then all entities are considered. + */ + const std::list entity_refs; + + const TriggeringEntities triggering_entities; + + explicit RelativeClearanceCondition(const pugi::xml_node &, Scope &, const TriggeringEntities &); + + auto description() const -> String; + + auto evaluate() -> Object; +}; +} // namespace syntax +} // namespace openscenario_interpreter + +#endif // OPENSCENARIO_INTERPRETER__SYNTAX__RELATIVE_CLEARANCE_CONDITION_HPP_ diff --git a/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp b/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp new file mode 100644 index 00000000000..6506f879407 --- /dev/null +++ b/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp @@ -0,0 +1,58 @@ +// Copyright 2015 TIER IV, Inc. All rights reserved. +// +// 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. + +#include +#include +#include +#include +#include + +namespace openscenario_interpreter +{ +inline namespace syntax +{ +RelativeClearanceCondition::RelativeClearanceCondition( + const pugi::xml_node & node, Scope & scope, const TriggeringEntities & triggering_entities) +: Scope(scope), + distance_backward(readAttribute("distanceBackward", node, scope, 0.0)), + distance_forward(readAttribute("distanceForward", node, scope, 0.0)), + freespace(readAttribute("freespace", node, scope)), + opposite_lanes(readAttribute("oppositeLanes", node, scope)), + relative_lane_range(readElements("RelativeLaneRange", node, scope)), + entity_refs(readElements("EntityRef", node, scope)), + triggering_entities(triggering_entities) +{ +} + +auto RelativeClearanceCondition::description() const -> String +{ + std::stringstream description; + + description << triggering_entities.description() + << "'s have relative clearance to given entities ["; + + print_to(description, entity_refs); + + description << "]?"; + + return description.str(); +} + +auto RelativeClearanceCondition::evaluate() -> Object +{ + // TODO(HansRobo): implement + return unspecified; +} +} // namespace syntax +} // namespace openscenario_interpreter From 2ef0ef39a84f305387fde5a4ff7ef7f8f7f35a70 Mon Sep 17 00:00:00 2001 From: SzymonParapura Date: Tue, 25 Jun 2024 09:44:58 +0200 Subject: [PATCH 006/304] Test: [RJD-937] to Implement Unit tests on simple_sensor_simulator - Added unit tests to LidarSensor - Addede unit tests to Primitive - Refactored Raycaster unit tests --- .../test/CMakeLists.txt | 3 + .../sensor_simulation/lidar/CMakeLists.txt | 6 +- .../lidar/test_lidar_sensor.cpp | 84 ++++++ .../lidar/test_lidar_sensor.hpp | 84 ++++++ .../lidar/test_raycaster.cpp | 14 +- .../lidar/test_raycaster.hpp | 34 +-- .../primitives/CMakeLists.txt | 3 + .../sensor_simulation/primitives/test_box.cpp | 2 +- .../primitives/test_primitive.cpp | 250 ++++++++++++++++++ .../primitives/test_primitive.hpp | 92 +++++++ .../primitives/test_vertex.cpp | 2 +- .../expect_eq_macros.hpp | 6 + .../test/src/utils/helper_functions.hpp | 142 ++++++++++ 13 files changed, 681 insertions(+), 41 deletions(-) create mode 100644 simulation/simple_sensor_simulator/test/src/sensor_simulation/lidar/test_lidar_sensor.cpp create mode 100644 simulation/simple_sensor_simulator/test/src/sensor_simulation/lidar/test_lidar_sensor.hpp create mode 100644 simulation/simple_sensor_simulator/test/src/sensor_simulation/primitives/test_primitive.cpp create mode 100644 simulation/simple_sensor_simulator/test/src/sensor_simulation/primitives/test_primitive.hpp rename simulation/simple_sensor_simulator/test/src/{sensor_simulation => utils}/expect_eq_macros.hpp (90%) create mode 100644 simulation/simple_sensor_simulator/test/src/utils/helper_functions.hpp diff --git a/simulation/simple_sensor_simulator/test/CMakeLists.txt b/simulation/simple_sensor_simulator/test/CMakeLists.txt index e7f6401dfef..5db9f69e675 100644 --- a/simulation/simple_sensor_simulator/test/CMakeLists.txt +++ b/simulation/simple_sensor_simulator/test/CMakeLists.txt @@ -1,3 +1,6 @@ +find_package(Protobuf REQUIRED) +include_directories(${Protobuf_INCLUDE_DIRS}) + add_subdirectory(src/sensor_simulation/lidar) add_subdirectory(src/sensor_simulation/primitives) add_subdirectory(src/sensor_simulation/occupancy_grid) diff --git a/simulation/simple_sensor_simulator/test/src/sensor_simulation/lidar/CMakeLists.txt b/simulation/simple_sensor_simulator/test/src/sensor_simulation/lidar/CMakeLists.txt index eeb9c2f9abc..7d16e7f14cf 100644 --- a/simulation/simple_sensor_simulator/test/src/sensor_simulation/lidar/CMakeLists.txt +++ b/simulation/simple_sensor_simulator/test/src/sensor_simulation/lidar/CMakeLists.txt @@ -1,5 +1,5 @@ -find_package(Protobuf REQUIRED) -include_directories(${Protobuf_INCLUDE_DIRS}) - ament_add_gtest(test_raycaster test_raycaster.cpp) target_link_libraries(test_raycaster simple_sensor_simulator_component ${Protobuf_LIBRARIES}) + +ament_add_gtest(test_lidar_sensor test_lidar_sensor.cpp) +target_link_libraries(test_lidar_sensor simple_sensor_simulator_component ${Protobuf_LIBRARIES}) diff --git a/simulation/simple_sensor_simulator/test/src/sensor_simulation/lidar/test_lidar_sensor.cpp b/simulation/simple_sensor_simulator/test/src/sensor_simulation/lidar/test_lidar_sensor.cpp new file mode 100644 index 00000000000..2a225940738 --- /dev/null +++ b/simulation/simple_sensor_simulator/test/src/sensor_simulation/lidar/test_lidar_sensor.cpp @@ -0,0 +1,84 @@ +// Copyright 2015 TIER IV, Inc. All rights reserved. +// +// 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. + +#include "test_lidar_sensor.hpp" + +/** + * @note Test function behavior when called on a scene without Ego entity added - the goal is to + * test error throwing. + */ +TEST_F(LidarSensorTest, update_noEgo) +{ + status_.clear(); // Remove ego + EXPECT_THROW( + lidar_->update(current_simulation_time_, status_, current_ros_time_), std::runtime_error); +} + +/** + * @note Test basic functionality. Test lidar sensor correctness on a sample scene with some vehicle + * - the goal is to check if the correct pointcloud is published on the correct topic. + */ +TEST_F(LidarSensorTest, update_correct) +{ + lidar_->update(current_simulation_time_, status_, current_ros_time_); + + // Spin the node to process callbacks + rclcpp::spin_some(node_); + + ASSERT_NE(received_msg_, nullptr); + const auto total_num_of_points = received_msg_->width * received_msg_->height; + EXPECT_GT(total_num_of_points, 0); + EXPECT_EQ(received_msg_->header.frame_id, "base_link"); +} + +/** + * @note Test function behavior when called with a current_time significantly smaller than one call + * earlier - the goal is to test whether the function clears detected_objects. + */ +TEST_F(LidarSensorTest, update_goBackInTime) +{ + lidar_->update(current_simulation_time_, status_, rclcpp::Time(1000)); + + // Ensure there are detected objects + ASSERT_FALSE(lidar_->getDetectedObjects().empty()); + + lidar_->update(current_simulation_time_, status_, rclcpp::Time(1)); + + // Spin the node to process callbacks + rclcpp::spin_some(node_); + + EXPECT_TRUE(lidar_->getDetectedObjects().empty()); +} + +/** + * @note Test basic functionality. Test detected objects obtaining from the statuses list containing + * Ego. + */ +TEST_F(LidarSensorTest, getDetectedObjects) +{ + const std::set expected_objects = {status_[1].name(), status_[2].name()}; + + lidar_->update(current_simulation_time_, status_, current_ros_time_); + + // Spin the node to process callbacks + rclcpp::spin_some(node_); + + const auto & detected_objects = lidar_->getDetectedObjects(); + + // LidarSensor returns duplicates. To avoid them, a std::set is used. + const std::set unique_objects(detected_objects.begin(), detected_objects.end()); + + ASSERT_FALSE(unique_objects.empty()); + EXPECT_EQ(unique_objects, expected_objects); +} diff --git a/simulation/simple_sensor_simulator/test/src/sensor_simulation/lidar/test_lidar_sensor.hpp b/simulation/simple_sensor_simulator/test/src/sensor_simulation/lidar/test_lidar_sensor.hpp new file mode 100644 index 00000000000..54bf61a03b0 --- /dev/null +++ b/simulation/simple_sensor_simulator/test/src/sensor_simulation/lidar/test_lidar_sensor.hpp @@ -0,0 +1,84 @@ +// Copyright 2015 TIER IV, Inc. All rights reserved. +// +// 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. + +#ifndef SIMPLE_SENSOR_SIMULATOR__TEST__TEST_LIDAR_SENSOR_HPP_ +#define SIMPLE_SENSOR_SIMULATOR__TEST__TEST_LIDAR_SENSOR_HPP_ + +#include + +#include +#include +#include +#include +#include +#include + +#include "../../utils/helper_functions.hpp" + +using namespace simple_sensor_simulator; + +class LidarSensorTest : public ::testing::Test +{ +protected: + LidarSensorTest() : config_(utils::constructLidarConfiguration("ego", "awf/universe", 0.0, 0.5)) + { + rclcpp::init(0, nullptr); + node_ = std::make_shared("lidar_sensor_test_node"); + makeRosInterface(); + initializeEntityStatuses(); + + lidar_ = std::make_unique>(0.0, config_, publisher_); + } + + ~LidarSensorTest() { rclcpp::shutdown(); } + + rclcpp::Node::SharedPtr node_; + rclcpp::Publisher::SharedPtr publisher_; + rclcpp::Subscription::SharedPtr subscription_; + + std::vector status_; + + std::unique_ptr lidar_; + simulation_api_schema::LidarConfiguration config_; + sensor_msgs::msg::PointCloud2::SharedPtr received_msg_; + + double current_simulation_time_{1.0}; + rclcpp::Time current_ros_time_{1}; + +private: + auto initializeEntityStatuses() -> void + { + const auto dimensions = utils::makeDimensions(4.5, 2.0, 1.5); + + const auto ego_status = utils::makeEntity( + "ego", EntityType::EGO, utils::makePose(5.0, 5.0, 0.0, 0.0, 0.0, 0.0, 1.0), dimensions); + const auto other1_status = utils::makeEntity( + "other1", EntityType::VEHICLE, utils::makePose(-3.0, -3.0, 0.0, 0.0, 0.0, 0.0, 1.0), + dimensions); + const auto other2_status = utils::makeEntity( + "other2", EntityType::VEHICLE, utils::makePose(5.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0), + dimensions); + + status_ = {ego_status, other1_status, other2_status}; + } + + auto makeRosInterface() -> void + { + publisher_ = node_->create_publisher("lidar_output", 10); + subscription_ = node_->create_subscription( + "lidar_output", 10, + [this](const sensor_msgs::msg::PointCloud2::SharedPtr msg) { received_msg_ = msg; }); + } +}; +#endif // SIMPLE_SENSOR_SIMULATOR__TEST__TEST_LIDAR_SENSOR_HPP_ diff --git a/simulation/simple_sensor_simulator/test/src/sensor_simulation/lidar/test_raycaster.cpp b/simulation/simple_sensor_simulator/test/src/sensor_simulation/lidar/test_raycaster.cpp index f159ea9b575..d168ec0c80b 100644 --- a/simulation/simple_sensor_simulator/test/src/sensor_simulation/lidar/test_raycaster.cpp +++ b/simulation/simple_sensor_simulator/test/src/sensor_simulation/lidar/test_raycaster.cpp @@ -76,8 +76,8 @@ TEST_F(RaycasterTest, setDirection_oneBox) box_name_, box_depth_, box_width_, box_height_, box_pose_); simulation_api_schema::LidarConfiguration config; - config.add_vertical_angles(0.0); // Only one vertical angle for a horizontal ring - config.set_horizontal_resolution(degToRad(1.0)); // Set horizontal resolution to 1 degree + config.add_vertical_angles(0.0); // Only one vertical angle for a horizontal ring + config.set_horizontal_resolution(utils::degToRad(1.0)); // Set horizontal resolution to 1 degree raycaster_->setDirection(config); @@ -103,13 +103,7 @@ TEST_F(RaycasterTest, setDirection_manyBoxes) for (int i = 0; i < num_boxes; ++i) { const double angle = i * angle_increment; const auto box_pose = - geometry_msgs::build() - .position(geometry_msgs::build() - .x(radius * cos(angle)) - .y(radius * sin(angle)) - .z(0.0)) - .orientation( - geometry_msgs::build().x(0.0).y(0.0).z(0.0).w(1.0)); + utils::makePose(radius * cos(angle), radius * sin(angle), 0.0, 0.0, 0.0, 0.0, 1.0); const std::string name = "box" + std::to_string(i); raycaster_->addPrimitive(name, box_depth_, box_width_, box_height_, box_pose); @@ -117,7 +111,7 @@ TEST_F(RaycasterTest, setDirection_manyBoxes) simulation_api_schema::LidarConfiguration config; config.add_vertical_angles(0.0); // Only one vertical angle for a horizontal ring - config.set_horizontal_resolution(degToRad(5.0)); + config.set_horizontal_resolution(utils::degToRad(5.0)); raycaster_->setDirection(config); diff --git a/simulation/simple_sensor_simulator/test/src/sensor_simulation/lidar/test_raycaster.hpp b/simulation/simple_sensor_simulator/test/src/sensor_simulation/lidar/test_raycaster.hpp index d3e9beb511d..641e59cf104 100644 --- a/simulation/simple_sensor_simulator/test/src/sensor_simulation/lidar/test_raycaster.hpp +++ b/simulation/simple_sensor_simulator/test/src/sensor_simulation/lidar/test_raycaster.hpp @@ -23,6 +23,8 @@ #include #include +#include "../../utils/helper_functions.hpp" + using namespace simple_sensor_simulator; using namespace geometry_msgs::msg; @@ -31,20 +33,13 @@ constexpr static double degToRad(double deg) { return deg * M_PI / 180.0; } class RaycasterTest : public ::testing::Test { protected: - RaycasterTest() : raycaster_(std::make_unique()) + RaycasterTest() + : raycaster_(std::make_unique()), + config_(utils::constructLidarConfiguration("ego", "awf/universe", 0.0, 0.1)), + origin_(utils::makePose(0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0)), + box_pose_(utils::makePose(5.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0)) { - configureLidar(); - - origin_ = - geometry_msgs::build() - .position(geometry_msgs::build().x(0.0).y(0.0).z(0.0)) - .orientation( - geometry_msgs::build().x(0.0).y(0.0).z(0.0).w(1.0)); - box_pose_ = - geometry_msgs::build() - .position(geometry_msgs::build().x(5.0).y(0.0).z(0.0)) - .orientation( - geometry_msgs::build().x(0.0).y(0.0).z(0.0).w(1.0)); + raycaster_->setDirection(config_); } std::unique_ptr raycaster_; @@ -60,19 +55,6 @@ class RaycasterTest : public ::testing::Test geometry_msgs::msg::Pose origin_; geometry_msgs::msg::Pose box_pose_; - -private: - auto configureLidar() -> void - { - // Setting vertical angles from -15 to +15 degrees in 2 degree steps - for (double angle = -15.0; angle <= 15.0; angle += 2.0) { - config_.add_vertical_angles(degToRad(angle)); - } - // Setting horizontal resolution to 0.5 degrees - config_.set_horizontal_resolution(degToRad(0.5)); - - raycaster_->setDirection(config_); - } }; #endif // SIMPLE_SENSOR_SIMULATOR__TEST__TEST_RAYCASTER_HPP_ diff --git a/simulation/simple_sensor_simulator/test/src/sensor_simulation/primitives/CMakeLists.txt b/simulation/simple_sensor_simulator/test/src/sensor_simulation/primitives/CMakeLists.txt index fb424659262..b5ae088e7a7 100644 --- a/simulation/simple_sensor_simulator/test/src/sensor_simulation/primitives/CMakeLists.txt +++ b/simulation/simple_sensor_simulator/test/src/sensor_simulation/primitives/CMakeLists.txt @@ -3,3 +3,6 @@ target_link_libraries(test_box simple_sensor_simulator_component) ament_add_gtest(test_vertex test_vertex.cpp) target_link_libraries(test_vertex simple_sensor_simulator_component) + +ament_add_gtest(test_primitive test_primitive.cpp) +target_link_libraries(test_primitive simple_sensor_simulator_component ${Protobuf_LIBRARIES}) diff --git a/simulation/simple_sensor_simulator/test/src/sensor_simulation/primitives/test_box.cpp b/simulation/simple_sensor_simulator/test/src/sensor_simulation/primitives/test_box.cpp index c5b501075d7..25e64cf1022 100644 --- a/simulation/simple_sensor_simulator/test/src/sensor_simulation/primitives/test_box.cpp +++ b/simulation/simple_sensor_simulator/test/src/sensor_simulation/primitives/test_box.cpp @@ -19,7 +19,7 @@ #include #include -#include "../expect_eq_macros.hpp" +#include "../../utils/expect_eq_macros.hpp" using namespace simple_sensor_simulator; using namespace simple_sensor_simulator::primitives; diff --git a/simulation/simple_sensor_simulator/test/src/sensor_simulation/primitives/test_primitive.cpp b/simulation/simple_sensor_simulator/test/src/sensor_simulation/primitives/test_primitive.cpp new file mode 100644 index 00000000000..1f5b1330c19 --- /dev/null +++ b/simulation/simple_sensor_simulator/test/src/sensor_simulation/primitives/test_primitive.cpp @@ -0,0 +1,250 @@ +// Copyright 2015 TIER IV, Inc. All rights reserved. +// +// 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. + +#include "test_primitive.hpp" + +#include + +#include "../../utils/expect_eq_macros.hpp" + +/** + * @note Test basic functionality. Test adding to scene correctness with a sample primitive. + */ +TEST_F(PrimitiveTest, addToScene_sample) +{ + const std::vector expected_vertices = { + {0.0f, 1.0f, -1.0f}, {2.0f, 1.0f, -1.0f}, {0.0f, 3.0f, -1.0f}, {2.0f, 3.0f, -1.0f}, + {0.0f, 1.0f, 1.0f}, {2.0f, 1.0f, 1.0f}, {0.0f, 3.0f, 1.0f}, {2.0f, 3.0f, 1.0f}}; + const auto expected_triangles = primitive_->getTriangles(); + + RTCDevice device = rtcNewDevice(nullptr); + RTCScene scene = rtcNewScene(device); + + const unsigned int geom_id = primitive_->addToScene(device, scene); + ASSERT_NE(geom_id, RTC_INVALID_GEOMETRY_ID); + + const RTCGeometry geom = rtcGetGeometry(scene, geom_id); + ASSERT_NE(geom, nullptr); + + rtcCommitScene(scene); + + // Check vertices + const Vertex * vertex_buffer = + static_cast(rtcGetGeometryBufferData(geom, RTC_BUFFER_TYPE_VERTEX, 0)); + + for (size_t i = 0; i < expected_vertices.size(); ++i) { + EXPECT_VERTEX_EQ(vertex_buffer[i], expected_vertices[i]) + } + + // Check triangles + const Triangle * triangle_buffer = + static_cast(rtcGetGeometryBufferData(geom, RTC_BUFFER_TYPE_INDEX, 0)); + + for (size_t i = 0; i < expected_vertices.size(); ++i) { + EXPECT_TRIANGLE_EQ(triangle_buffer[i], expected_triangles[i]); + } + + rtcReleaseScene(scene); + rtcReleaseDevice(device); +} + +/** + * @note Test function behavior with vertices and triangles set to only zeros. + */ +TEST_F(PrimitiveTest, addToScene_zeros) +{ + const std::vector expected_triangles = {{0, 0, 0}}; + const std::vector expected_vertices = {{1.0f, 2.0f, 0.0f}}; + + primitive_->setVertices({{0.0f, 0.0f, 0.0f}}); + primitive_->setTriangles(expected_triangles); + + RTCDevice device = rtcNewDevice(nullptr); + RTCScene scene = rtcNewScene(device); + + const unsigned int geom_id = primitive_->addToScene(device, scene); + ASSERT_NE(geom_id, RTC_INVALID_GEOMETRY_ID); + + const RTCGeometry geom = rtcGetGeometry(scene, geom_id); + ASSERT_NE(geom, nullptr); + + rtcCommitScene(scene); + + // Check vertices + const Vertex * vertex_buffer = + static_cast(rtcGetGeometryBufferData(geom, RTC_BUFFER_TYPE_VERTEX, 0)); + + for (size_t i = 0; i < expected_vertices.size(); ++i) { + EXPECT_VERTEX_EQ(vertex_buffer[i], expected_vertices[i]) + } + + // Check triangles + const Triangle * triangle_buffer = + static_cast(rtcGetGeometryBufferData(geom, RTC_BUFFER_TYPE_INDEX, 0)); + + for (size_t i = 0; i < expected_triangles.size(); ++i) { + EXPECT_TRIANGLE_EQ(triangle_buffer[i], expected_triangles[i]); + } + + rtcReleaseScene(scene); + rtcReleaseDevice(device); +} + +/** + * @note Test basic functionality. Test obtaining triangles correctness. + */ +TEST_F(PrimitiveTest, getTriangles) +{ + const std::vector expected_triangles = {{0, 1, 2}, {1, 3, 2}, {4, 5, 6}, {5, 7, 6}, + {0, 1, 4}, {1, 5, 4}, {2, 3, 6}, {3, 7, 6}, + {0, 2, 4}, {2, 6, 4}, {1, 3, 5}, {3, 7, 5}}; + + const auto triangles = primitive_->getTriangles(); + + ASSERT_EQ(triangles.size(), expected_triangles.size()); + for (size_t i = 0; i < triangles.size(); ++i) { + EXPECT_TRIANGLE_EQ(triangles[i], expected_triangles[i]); + } +} + +/** + * @note Test basic functionality. Test obtaining vertex correctness with a sample vertex and a non + * trivial Primitive pose - the goal is to test transformation of vertex elements. + */ +TEST_F(PrimitiveTest, getVertex) +{ + const std::vector expected_vertices = { + {0.0f, 1.0f, -1.0f}, {2.0f, 1.0f, -1.0f}, {0.0f, 3.0f, -1.0f}, {2.0f, 3.0f, -1.0f}, + {0.0f, 1.0f, 1.0f}, {2.0f, 1.0f, 1.0f}, {0.0f, 3.0f, 1.0f}, {2.0f, 3.0f, 1.0f}}; + + const auto vertices = primitive_->getVertex(); + + ASSERT_EQ(vertices.size(), expected_vertices.size()); + for (size_t i = 0; i < vertices.size(); ++i) { + EXPECT_VERTEX_EQ(vertices[i], expected_vertices[i]); + } +} + +/** + * @note Test basic functionality. Test conversion to a convex hull of some concave primitive. + */ +TEST_F(PrimitiveTest, get2DConvexHull_normal) +{ + const std::vector expected_hull = { + utils::makePoint(0.0, 1.0, 0.0), utils::makePoint(0.0, 3.0, 0.0), + utils::makePoint(2.0, 3.0, 0.0), utils::makePoint(2.0, 1.0, 0.0), + utils::makePoint(0.0, 1.0, 0.0)}; + + const auto hull = primitive_->get2DConvexHull(); + + EXPECT_GT(hull.size(), 0); + ASSERT_EQ(hull.size(), expected_hull.size()); + for (size_t i = 0; i < hull.size(); ++i) { + EXPECT_POINT_NEAR(hull[i], expected_hull[i], std::numeric_limits::epsilon()) + } +} + +/** + * @note Test basic functionality. Test conversion to a convex hull of some concave primitive with + * an additional sensor pose transformation - the goal is to test the transformation of convex hull. + */ +TEST_F(PrimitiveTest, get2DConvexHull_withTransform) +{ + const std::vector expected_hull = { + utils::makePoint(-1.0, 0.0, 0.0), utils::makePoint(-1.0, 2.0, 0.0), + utils::makePoint(1.0, 2.0, 0.0), utils::makePoint(1.0, 0.0, 0.0), + utils::makePoint(-1.0, 0.0, 0.0)}; + + const auto sensor_pose = utils::makePose(1.0, 1.0, 1.0, 0.0, 0.0, 0.0, 1.0); + + const auto hull = primitive_->get2DConvexHull(sensor_pose); + + EXPECT_GT(hull.size(), 0); + ASSERT_EQ(hull.size(), expected_hull.size()); + for (size_t i = 0; i < hull.size(); ++i) { + EXPECT_POINT_NEAR(hull[i], expected_hull[i], std::numeric_limits::epsilon()) + } +} + +/** + * @note Test basic functionality. Test min value obtaining in a given axis with a sample primitive. + */ +TEST_F(PrimitiveTest, getMin) +{ + const auto min_x = primitive_->getMin(math::geometry::Axis::X); + + ASSERT_TRUE(min_x.has_value()); + EXPECT_NEAR(min_x.value(), 0.0f, std::numeric_limits::epsilon()); +} + +/** + * @note Test basic functionality. Test min value obtaining in a given axis with a transformation + * with a sample primitive and non trivial sensor pose. + */ +TEST_F(PrimitiveTest, getMin_withTransform) +{ + const auto sensor_pose = utils::makePose(5.0, 2.0, 1.0, 0.0, 0.0, 0.0, 1.0); + + const auto min_x = primitive_->getMin(math::geometry::Axis::X, sensor_pose); + + ASSERT_TRUE(min_x.has_value()); + EXPECT_NEAR(min_x.value(), -5.0f, std::numeric_limits::epsilon()); +} + +/** + * @note Test function behavior when vertices is an empty vector - the goal is to get a nullopt. + */ +TEST_F(PrimitiveTest, getMin_empty) +{ + primitive_->setVertices(std::vector{}); + const auto min_x = primitive_->getMin(math::geometry::Axis::X); + + EXPECT_FALSE(min_x.has_value()); +} + +/** + * @note Test basic functionality. Test max value obtaining in a given axis with a sample primitive. + */ +TEST_F(PrimitiveTest, getMax) +{ + const auto max_x = primitive_->getMax(math::geometry::Axis::X); + + ASSERT_TRUE(max_x.has_value()); + EXPECT_NEAR(max_x.value(), 2.0f, std::numeric_limits::epsilon()); +} + +/** + * @note Test basic functionality. Test max value obtaining in a given axis with a transformation + * with a sample primitive and non trivial sensor pose. + */ +TEST_F(PrimitiveTest, getMax_withTransform) +{ + const auto sensor_pose = utils::makePose(6.0, 3.0, 2.0, 0.0, 0.0, 0.0, 1.0); + + const auto max_x = primitive_->getMax(math::geometry::Axis::X, sensor_pose); + + ASSERT_TRUE(max_x.has_value()); + EXPECT_NEAR(max_x.value(), -4.0f, std::numeric_limits::epsilon()); +} + +/** + * @note Test function behavior when vertices is an empty vector - the goal is to get a nullopt. + */ +TEST_F(PrimitiveTest, getMax_empty) +{ + primitive_->setVertices(std::vector{}); + const auto max_x = primitive_->getMax(math::geometry::Axis::X); + + EXPECT_FALSE(max_x.has_value()); +} diff --git a/simulation/simple_sensor_simulator/test/src/sensor_simulation/primitives/test_primitive.hpp b/simulation/simple_sensor_simulator/test/src/sensor_simulation/primitives/test_primitive.hpp new file mode 100644 index 00000000000..3a09fa9e11c --- /dev/null +++ b/simulation/simple_sensor_simulator/test/src/sensor_simulation/primitives/test_primitive.hpp @@ -0,0 +1,92 @@ +// Copyright 2015 TIER IV, Inc. All rights reserved. +// +// 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. + +#ifndef SIMPLE_SENSOR_SIMULATOR__TEST__TEST_PRIMITIVE_HPP_ +#define SIMPLE_SENSOR_SIMULATOR__TEST__TEST_PRIMITIVE_HPP_ + +#include +#include + +#include +#include +#include +#include + +#include "../../utils/helper_functions.hpp" + +using namespace simple_sensor_simulator::primitives; +using namespace simple_sensor_simulator; + +namespace simple_sensor_simulator +{ +namespace primitives +{ + +class DummyPrimitive : public Primitive +{ +public: + DummyPrimitive(const std::string & type, const geometry_msgs::msg::Pose & pose) + : Primitive(type, pose) + { + } + + auto setVertices(const std::vector & vertices) -> void { vertices_ = vertices; } + auto setTriangles(const std::vector & triangles) -> void { triangles_ = triangles; } + + auto getVerticesSize() const -> size_t { return vertices_.size(); } + auto getTrianglesSize() const -> size_t { return triangles_.size(); } + + auto getVertices() const -> const std::vector & { return vertices_; } + auto getTriangles() const -> const std::vector & { return triangles_; } +}; + +} // namespace primitives +} // namespace simple_sensor_simulator + +class PrimitiveTest : public ::testing::Test +{ +protected: + PrimitiveTest() + : pose_(utils::makePose(1.0, 2.0, 0.0, 0.0, 0.0, 0.0, 1.0)), + primitive_(std::make_unique("DummyPrimitive", pose_)) + { + primitive_->setVertices( + {{-1.0f, -1.0f, -1.0f}, + {1.0f, -1.0f, -1.0f}, + {-1.0f, 1.0f, -1.0f}, + {1.0f, 1.0f, -1.0f}, + {-1.0f, -1.0f, 1.0f}, + {1.0f, -1.0f, 1.0f}, + {-1.0f, 1.0f, 1.0f}, + {1.0f, 1.0f, 1.0f}}); + primitive_->setTriangles( + {{0, 1, 2}, + {1, 3, 2}, + {4, 5, 6}, + {5, 7, 6}, + {0, 1, 4}, + {1, 5, 4}, + {2, 3, 6}, + {3, 7, 6}, + {0, 2, 4}, + {2, 6, 4}, + {1, 3, 5}, + {3, 7, 5}}); + } + + geometry_msgs::msg::Pose pose_; + std::unique_ptr primitive_; +}; + +#endif // SIMPLE_SENSOR_SIMULATOR__TEST__TEST_PRIMITIVE_HPP_ diff --git a/simulation/simple_sensor_simulator/test/src/sensor_simulation/primitives/test_vertex.cpp b/simulation/simple_sensor_simulator/test/src/sensor_simulation/primitives/test_vertex.cpp index 66da446cec3..c0fe3d57057 100644 --- a/simulation/simple_sensor_simulator/test/src/sensor_simulation/primitives/test_vertex.cpp +++ b/simulation/simple_sensor_simulator/test/src/sensor_simulation/primitives/test_vertex.cpp @@ -19,7 +19,7 @@ #include #include -#include "../expect_eq_macros.hpp" +#include "../../utils/expect_eq_macros.hpp" using namespace simple_sensor_simulator; diff --git a/simulation/simple_sensor_simulator/test/src/sensor_simulation/expect_eq_macros.hpp b/simulation/simple_sensor_simulator/test/src/utils/expect_eq_macros.hpp similarity index 90% rename from simulation/simple_sensor_simulator/test/src/sensor_simulation/expect_eq_macros.hpp rename to simulation/simple_sensor_simulator/test/src/utils/expect_eq_macros.hpp index c93387428cc..03346fdc438 100644 --- a/simulation/simple_sensor_simulator/test/src/sensor_simulation/expect_eq_macros.hpp +++ b/simulation/simple_sensor_simulator/test/src/utils/expect_eq_macros.hpp @@ -18,6 +18,7 @@ #include #include +#include #include #define EXPECT_POINT_EQ(DATA0, DATA1) \ @@ -65,4 +66,9 @@ EXPECT_FLOAT_EQ(VERTEX.y, POINT.y); \ EXPECT_FLOAT_EQ(VERTEX.z, POINT.z); +#define EXPECT_POSITION_NEAR(POSITION0, POSITION1, TOLERANCE) \ + EXPECT_NEAR(POSITION0.x, POSITION1.x, TOLERANCE); \ + EXPECT_NEAR(POSITION0.y, POSITION1.y, TOLERANCE); \ + EXPECT_NEAR(POSITION0.z, POSITION1.z, TOLERANCE); + #endif // SIMPLE_SENSOR_SIMULATOR__TEST__UTILS__EXPECT_EQ_MACROS_HPP_ diff --git a/simulation/simple_sensor_simulator/test/src/utils/helper_functions.hpp b/simulation/simple_sensor_simulator/test/src/utils/helper_functions.hpp new file mode 100644 index 00000000000..39adaeee487 --- /dev/null +++ b/simulation/simple_sensor_simulator/test/src/utils/helper_functions.hpp @@ -0,0 +1,142 @@ +// Copyright 2015 TIER IV, Inc. All rights reserved. +// +// 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. + +#ifndef SIMPLE_SENSOR_SIMULATOR__TEST__UTILS__HELPER_FUNCTIONS_HPP_ +#define SIMPLE_SENSOR_SIMULATOR__TEST__UTILS__HELPER_FUNCTIONS_HPP_ + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +using EntitySubtype = traffic_simulator_msgs::EntitySubtype; +using EntityType = traffic_simulator_msgs::EntityType; +using EntityStatus = traffic_simulator_msgs::EntityStatus; + +namespace utils +{ + +constexpr auto degToRad(const double deg) -> double { return deg * M_PI / 180.0; } + +inline auto makePoint(const double px, const double py, const double pz) + -> geometry_msgs::msg::Point +{ + return geometry_msgs::build().x(px).y(py).z(pz); +} + +inline auto makePose( + const double px, const double py, const double pz, const double ox, const double oy, + const double oz, const double ow) -> geometry_msgs::msg::Pose +{ + return geometry_msgs::build() + .position(geometry_msgs::build().x(px).y(py).z(pz)) + .orientation(geometry_msgs::build().x(ox).y(oy).z(oz).w(ow)); +} + +inline auto makeDimensions(const double x, const double y, const double z) + -> geometry_msgs::msg::Vector3 +{ + return geometry_msgs::build().x(x).y(y).z(z); +} + +inline auto constructLidarConfiguration( + const std::string & entity, const std::string & architecture_type, + const double lidar_sensor_delay, const double horizontal_resolution) + -> const simulation_api_schema::LidarConfiguration +{ + simulation_api_schema::LidarConfiguration configuration; + configuration.set_horizontal_resolution(horizontal_resolution); + configuration.set_architecture_type(architecture_type); + configuration.set_entity(entity); + configuration.set_lidar_sensor_delay(lidar_sensor_delay); + + configuration.set_scan_duration(0.1); + configuration.add_vertical_angles(degToRad(-15.0)); + configuration.add_vertical_angles(degToRad(-13.0)); + configuration.add_vertical_angles(degToRad(-11.0)); + configuration.add_vertical_angles(degToRad(-9.0)); + configuration.add_vertical_angles(degToRad(-7.0)); + configuration.add_vertical_angles(degToRad(-5.0)); + configuration.add_vertical_angles(degToRad(-3.0)); + configuration.add_vertical_angles(degToRad(-1.0)); + configuration.add_vertical_angles(degToRad(1.0)); + configuration.add_vertical_angles(degToRad(3.0)); + configuration.add_vertical_angles(degToRad(5.0)); + configuration.add_vertical_angles(degToRad(7.0)); + configuration.add_vertical_angles(degToRad(9.0)); + configuration.add_vertical_angles(degToRad(11.0)); + configuration.add_vertical_angles(degToRad(13.0)); + configuration.add_vertical_angles(degToRad(15.0)); + return configuration; +} + +inline auto createEntityStatus( + const std::string & name, const EntityType::Enum type, + const std::optional & subtype, const geometry_msgs::msg::Pose & pose, + const geometry_msgs::msg::Vector3 & dimensions) -> EntityStatus +{ + EntityStatus status; + status.set_name(name); + status.mutable_type()->set_type(type); + + if (subtype) { + status.mutable_subtype()->set_value(*subtype); + } + + auto new_pose = status.mutable_pose(); + auto new_position = new_pose->mutable_position(); + new_position->set_x(pose.position.x); + new_position->set_y(pose.position.y); + new_position->set_z(pose.position.z); + + auto new_orientation = new_pose->mutable_orientation(); + new_orientation->set_x(pose.orientation.x); + new_orientation->set_y(pose.orientation.y); + new_orientation->set_z(pose.orientation.z); + new_orientation->set_w(pose.orientation.w); + + auto new_bounding_box = status.mutable_bounding_box(); + auto new_dimensions = new_bounding_box->mutable_dimensions(); + new_dimensions->set_x(dimensions.x); + new_dimensions->set_y(dimensions.y); + new_dimensions->set_z(dimensions.z); + + return status; +} + +inline auto makeEntity( + const std::string & name, const EntityType::Enum type, const EntitySubtype::Enum subtype, + const geometry_msgs::msg::Pose & pose, const geometry_msgs::msg::Vector3 & dimensions) + -> EntityStatus +{ + return createEntityStatus(name, type, subtype, pose, dimensions); +} + +inline auto makeEntity( + const std::string & name, const EntityType::Enum type, const geometry_msgs::msg::Pose & pose, + const geometry_msgs::msg::Vector3 & dimensions) -> EntityStatus +{ + return createEntityStatus(name, type, std::nullopt, pose, dimensions); +} + +} // namespace utils + +#endif // SIMPLE_SENSOR_SIMULATOR__TEST__UTILS__HELPER_FUNCTIONS_HPP_ From b99f93e7251a0cec2613bb45b89e062720d3eef5 Mon Sep 17 00:00:00 2001 From: SzymonParapura Date: Tue, 25 Jun 2024 11:50:12 +0200 Subject: [PATCH 007/304] Test: [RJD-937] to Implement Unit tests on simple_sensor_simulator - Added missed header file --- .../test/src/sensor_simulation/primitives/test_primitive.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/simulation/simple_sensor_simulator/test/src/sensor_simulation/primitives/test_primitive.hpp b/simulation/simple_sensor_simulator/test/src/sensor_simulation/primitives/test_primitive.hpp index 3a09fa9e11c..3a752620be1 100644 --- a/simulation/simple_sensor_simulator/test/src/sensor_simulation/primitives/test_primitive.hpp +++ b/simulation/simple_sensor_simulator/test/src/sensor_simulation/primitives/test_primitive.hpp @@ -16,10 +16,10 @@ #define SIMPLE_SENSOR_SIMULATOR__TEST__TEST_PRIMITIVE_HPP_ #include -#include #include #include +#include #include #include From 706df6942119dab1b97d3871b7fca13634bcef7c Mon Sep 17 00:00:00 2001 From: Dawid Moszynski Date: Wed, 3 Jul 2024 13:38:19 +0200 Subject: [PATCH 008/304] feat(simple_sensor_simulator): add imu_sensor --- .../simple_sensor_simulator/CMakeLists.txt | 1 + .../sensor_simulation/imu/imu_sensor.hpp | 90 +++++++++++++++++++ .../src/sensor_simulation/imu/imu_sensor.cpp | 67 ++++++++++++++ .../proto/simulation_api_schema.proto | 27 ++++++ 4 files changed, 185 insertions(+) create mode 100644 simulation/simple_sensor_simulator/include/simple_sensor_simulator/sensor_simulation/imu/imu_sensor.hpp create mode 100644 simulation/simple_sensor_simulator/src/sensor_simulation/imu/imu_sensor.cpp diff --git a/simulation/simple_sensor_simulator/CMakeLists.txt b/simulation/simple_sensor_simulator/CMakeLists.txt index 4e3d828ec97..5c3eede4d60 100644 --- a/simulation/simple_sensor_simulator/CMakeLists.txt +++ b/simulation/simple_sensor_simulator/CMakeLists.txt @@ -35,6 +35,7 @@ include_directories( ament_auto_add_library(simple_sensor_simulator_component SHARED src/sensor_simulation/detection_sensor/detection_sensor.cpp src/sensor_simulation/lidar/lidar_sensor.cpp + src/sensor_simulation/imu/imu_sensor.cpp src/sensor_simulation/lidar/raycaster.cpp src/sensor_simulation/occupancy_grid/occupancy_grid_sensor.cpp src/sensor_simulation/occupancy_grid/occupancy_grid_builder.cpp diff --git a/simulation/simple_sensor_simulator/include/simple_sensor_simulator/sensor_simulation/imu/imu_sensor.hpp b/simulation/simple_sensor_simulator/include/simple_sensor_simulator/sensor_simulation/imu/imu_sensor.hpp new file mode 100644 index 00000000000..a34c873073b --- /dev/null +++ b/simulation/simple_sensor_simulator/include/simple_sensor_simulator/sensor_simulation/imu/imu_sensor.hpp @@ -0,0 +1,90 @@ +// Copyright 2024 TIER IV, Inc. All rights reserved. +// +// 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. + +#ifndef SIMPLE_SENSOR_SIMULATOR__SENSOR_SIMULATION__IMU_SENSOR_HPP_ +#define SIMPLE_SENSOR_SIMULATOR__SENSOR_SIMULATION__IMU_SENSOR_HPP_ + +#include + +#include +#include +#include +#include +#include +#include +#include + +namespace simple_sensor_simulator +{ +class ImuSensorBase +{ +public: + explicit ImuSensorBase(const simulation_api_schema::ImuSensorConfiguration & configuration) + : entity_name_(configuration.entity()), + add_noise_(configuration.add_noise()), + noise_standard_deviation_(configuration.noise_standard_deviation()), + random_generator_(configuration.use_seed() ? configuration.seed() : std::random_device{}()), + noise_distribution_(0.0, noise_standard_deviation_) + { + } + + virtual ~ImuSensorBase() = default; + + virtual auto update( + const rclcpp::Time & current_ros_time, + const std::vector & statuses) const -> bool = 0; + +protected: + const std::string entity_name_; + const bool add_noise_; + const double noise_standard_deviation_; + mutable std::mt19937 random_generator_; + mutable std::normal_distribution<> noise_distribution_; +}; + +template +class ImuSensor : public ImuSensorBase +{ +public: + explicit ImuSensor( + const simulation_api_schema::ImuSensorConfiguration & configuration, + const typename rclcpp::Publisher::SharedPtr & publisher) + : ImuSensorBase(configuration), publisher_(publisher) + { + } + + auto update( + const rclcpp::Time & current_ros_time, + const std::vector & statuses) const -> bool + { + for (const auto & status : statuses) { + if (status.name() == entity_name_) { + traffic_simulator_msgs::msg::EntityStatus status_msg; + simulation_interface::toMsg(status, status_msg); + publisher_->publish(generateMessage(current_ros_time, status_msg)); + return true; + } + } + return false; + } + +private: + auto generateMessage( + const rclcpp::Time & current_ros_time, + const traffic_simulator_msgs::msg::EntityStatus & status) const -> const sensor_msgs::msg::Imu; + + const rclcpp::Publisher::SharedPtr publisher_; +}; +} // namespace simple_sensor_simulator +#endif // SIMPLE_SENSOR_SIMULATOR__SENSOR_SIMULATION__IMU_SENSOR_HPP_ diff --git a/simulation/simple_sensor_simulator/src/sensor_simulation/imu/imu_sensor.cpp b/simulation/simple_sensor_simulator/src/sensor_simulation/imu/imu_sensor.cpp new file mode 100644 index 00000000000..be272519ad3 --- /dev/null +++ b/simulation/simple_sensor_simulator/src/sensor_simulation/imu/imu_sensor.cpp @@ -0,0 +1,67 @@ +// Copyright 2024 TIER IV, Inc. All rights reserved. +// +// 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. + +#include +#include +#include + +namespace simple_sensor_simulator +{ +template <> +auto ImuSensor::generateMessage( + const rclcpp::Time & current_ros_time, + const traffic_simulator_msgs::msg::EntityStatus & status) const -> const sensor_msgs::msg::Imu +{ + const auto applyNoise = [&](geometry_msgs::msg::Vector3 & v) { + if (add_noise_) { + v.x += noise_distribution_(random_generator_); + v.y += noise_distribution_(random_generator_); + v.z += noise_distribution_(random_generator_); + } + }; + + auto imu_msg = sensor_msgs::msg::Imu(); + imu_msg.header.stamp = current_ros_time; + imu_msg.header.frame_id = "imu_frame"; + + // Apply noise + auto orientation_rpy = math::geometry::convertQuaternionToEulerAngle(status.pose.orientation); + applyNoise(orientation_rpy); + auto twist = status.action_status.twist; + applyNoise(twist.angular); + auto accel = status.action_status.accel; + applyNoise(accel.linear); + + // Set data + imu_msg.orientation = math::geometry::convertEulerAngleToQuaternion(orientation_rpy); + imu_msg.angular_velocity.x = twist.angular.x; + imu_msg.angular_velocity.y = twist.angular.y; + imu_msg.angular_velocity.z = twist.angular.z; + imu_msg.linear_acceleration.x = accel.linear.x; + imu_msg.linear_acceleration.y = accel.linear.y; + imu_msg.linear_acceleration.z = accel.linear.z; + + // Set covariance + imu_msg.orientation_covariance = {std::pow(noise_standard_deviation_, 2), 0, 0, 0, + std::pow(noise_standard_deviation_, 2), 0, 0, 0, + std::pow(noise_standard_deviation_, 2)}; + imu_msg.angular_velocity_covariance = {std::pow(noise_standard_deviation_, 2), 0, 0, 0, + std::pow(noise_standard_deviation_, 2), 0, 0, 0, + std::pow(noise_standard_deviation_, 2)}; + imu_msg.linear_acceleration_covariance = {std::pow(noise_standard_deviation_, 2), 0, 0, 0, + std::pow(noise_standard_deviation_, 2), 0, 0, 0, + std::pow(noise_standard_deviation_, 2)}; + return imu_msg; +} +} // namespace simple_sensor_simulator diff --git a/simulation/simulation_interface/proto/simulation_api_schema.proto b/simulation/simulation_interface/proto/simulation_api_schema.proto index b2b4b409d44..37afc2d8c63 100644 --- a/simulation/simulation_interface/proto/simulation_api_schema.proto +++ b/simulation/simulation_interface/proto/simulation_api_schema.proto @@ -33,6 +33,17 @@ message PseudoTrafficLightDetectorConfiguration { string architecture_type = 1; // Autoware architecture type. } +/** + * Parameter configuration of the imu sensor + **/ + message ImuSensorConfiguration { + string entity = 1; // Name of the entity which you want to attach imu. + bool add_noise = 2; + bool use_seed = 3; + int32 seed = 4; + double noise_standard_deviation = 5; +} + /** * Parameter configuration of the lidar sensor **/ @@ -199,6 +210,20 @@ message UpdateEntityStatusResponse { repeated UpdatedEntityStatus status = 2; // List of updated entity status in sensor/dynamics simulator } +/** + * Requests attaching a imu sensor to the target entity. + **/ + message AttachImuSensorRequest { + ImuSensorConfiguration configuration = 1; // Configuration of the imu sensor. +} + +/** + * Requests attaching a imu sensor to the target entity. + **/ + message AttachImuSensorResponse { + Result result = 1; // Result of [AttachImuSensorRequest](#AttachImuSensorRequest) +} + /** * Requests attaching a traffic light detector emulator. **/ @@ -342,6 +367,7 @@ message SimulationRequest { UpdateTrafficLightsRequest update_traffic_lights = 11; AttachPseudoTrafficLightDetectorRequest attach_pseudo_traffic_light_detector = 13; UpdateStepTimeRequest update_step_time = 14; + AttachImuSensorRequest attach_imu_sensor = 15; } } @@ -364,5 +390,6 @@ message SimulationResponse { UpdateTrafficLightsResponse update_traffic_lights = 11; AttachPseudoTrafficLightDetectorResponse attach_pseudo_traffic_light_detector = 13; UpdateStepTimeResponse update_step_time = 14; + AttachImuSensorResponse attach_imu_sensor = 15; } } From aeff9d3af18e74ee717e3b93b11b95d1e0363c9d Mon Sep 17 00:00:00 2001 From: Dawid Moszynski Date: Wed, 3 Jul 2024 13:39:02 +0200 Subject: [PATCH 009/304] feat(simulator_core, api, zmq): add attachImuSensor, add update imu sensors --- .../openscenario_interpreter/simulator_core.hpp | 10 ++++++++++ .../sensor_simulation/sensor_simulation.hpp | 11 +++++++++++ .../simple_sensor_simulator.hpp | 3 +++ .../src/sensor_simulation/sensor_simulation.cpp | 5 ++++- .../src/simple_sensor_simulator.cpp | 10 ++++++++++ .../simulation_interface/zmq_multi_client.hpp | 3 +++ .../simulation_interface/zmq_multi_server.hpp | 3 ++- .../simulation_interface/src/zmq_multi_client.cpp | 12 ++++++++++++ .../simulation_interface/src/zmq_multi_server.cpp | 4 ++++ .../include/traffic_simulator/api/api.hpp | 4 ++++ simulation/traffic_simulator/src/api/api.cpp | 8 ++++++++ 11 files changed, 71 insertions(+), 2 deletions(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/simulator_core.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/simulator_core.hpp index 927d9374031..83faef8fc00 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/simulator_core.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/simulator_core.hpp @@ -333,6 +333,16 @@ class SimulatorCore }()); if (controller.isAutoware()) { + core->attachImuSensor(entity_ref, [&]() { + simulation_api_schema::ImuSensorConfiguration configuration; + configuration.set_entity(entity_ref); + configuration.set_add_noise(false); + configuration.set_use_seed(true); + configuration.set_seed(0); + configuration.set_noise_standard_deviation(0.01); + return configuration; + }()); + core->attachLidarSensor( entity_ref, controller.properties.template get("pointcloudPublishingDelay")); diff --git a/simulation/simple_sensor_simulator/include/simple_sensor_simulator/sensor_simulation/sensor_simulation.hpp b/simulation/simple_sensor_simulator/include/simple_sensor_simulator/sensor_simulation/sensor_simulation.hpp index 6927a364d4f..20f274f3276 100644 --- a/simulation/simple_sensor_simulator/include/simple_sensor_simulator/sensor_simulation/sensor_simulation.hpp +++ b/simulation/simple_sensor_simulator/include/simple_sensor_simulator/sensor_simulation/sensor_simulation.hpp @@ -25,6 +25,7 @@ #include #include #include +#include #include #include #include @@ -114,12 +115,22 @@ class SensorSimulation } } + auto attachImuSensor( + const double /*current_simulation_time*/, + const simulation_api_schema::ImuSensorConfiguration & configuration, rclcpp::Node & node) + -> void + { + imu_sensors_.push_back(std::make_unique>( + configuration, node.create_publisher("/sensing/imu/imu_data", 1))); + } + auto updateSensorFrame( double current_simulation_time, const rclcpp::Time & current_ros_time, const std::vector &, const simulation_api_schema::UpdateTrafficLightsRequest &) -> void; private: + std::vector> imu_sensors_; std::vector> lidar_sensors_; std::vector> detection_sensors_; std::vector> occupancy_grid_sensors_; diff --git a/simulation/simple_sensor_simulator/include/simple_sensor_simulator/simple_sensor_simulator.hpp b/simulation/simple_sensor_simulator/include/simple_sensor_simulator/simple_sensor_simulator.hpp index ce7ac052d91..8d3f168c768 100644 --- a/simulation/simple_sensor_simulator/include/simple_sensor_simulator/simple_sensor_simulator.hpp +++ b/simulation/simple_sensor_simulator/include/simple_sensor_simulator/simple_sensor_simulator.hpp @@ -119,6 +119,9 @@ class ScenarioSimulator : public rclcpp::Node auto despawnEntity(const simulation_api_schema::DespawnEntityRequest &) -> simulation_api_schema::DespawnEntityResponse; + auto attachImuSensor(const simulation_api_schema::AttachImuSensorRequest &) + -> simulation_api_schema::AttachImuSensorResponse; + auto attachDetectionSensor(const simulation_api_schema::AttachDetectionSensorRequest &) -> simulation_api_schema::AttachDetectionSensorResponse; diff --git a/simulation/simple_sensor_simulator/src/sensor_simulation/sensor_simulation.cpp b/simulation/simple_sensor_simulator/src/sensor_simulation/sensor_simulation.cpp index 411d5c28f9a..f6f3716f62a 100644 --- a/simulation/simple_sensor_simulator/src/sensor_simulation/sensor_simulation.cpp +++ b/simulation/simple_sensor_simulator/src/sensor_simulation/sensor_simulation.cpp @@ -24,8 +24,11 @@ auto SensorSimulation::updateSensorFrame( const std::vector & entities, const simulation_api_schema::UpdateTrafficLightsRequest & update_traffic_lights_request) -> void { - std::vector lidar_detected_objects = {}; + for (auto & sensor : imu_sensors_) { + sensor->update(current_ros_time, entities); + } + std::vector lidar_detected_objects = {}; for (auto & sensor : lidar_sensors_) { sensor->update(current_simulation_time, entities, current_ros_time); for (const auto & object : sensor->getDetectedObjects()) { diff --git a/simulation/simple_sensor_simulator/src/simple_sensor_simulator.cpp b/simulation/simple_sensor_simulator/src/simple_sensor_simulator.cpp index 95110509a6e..3bd61e6947a 100644 --- a/simulation/simple_sensor_simulator/src/simple_sensor_simulator.cpp +++ b/simulation/simple_sensor_simulator/src/simple_sensor_simulator.cpp @@ -38,6 +38,7 @@ ScenarioSimulator::ScenarioSimulator(const rclcpp::NodeOptions & options) [this](auto &&... xs) { return spawnMiscObjectEntity(std::forward(xs)...); }, [this](auto &&... xs) { return despawnEntity(std::forward(xs)...); }, [this](auto &&... xs) { return updateEntityStatus(std::forward(xs)...); }, + [this](auto &&... xs) { return attachImuSensor(std::forward(xs)...); }, [this](auto &&... xs) { return attachLidarSensor(std::forward(xs)...); }, [this](auto &&... xs) { return attachDetectionSensor(std::forward(xs)...); }, [this](auto &&... xs) { return attachOccupancyGridSensor(std::forward(xs)...); }, @@ -300,6 +301,15 @@ auto ScenarioSimulator::despawnEntity(const simulation_api_schema::DespawnEntity return res; } +auto ScenarioSimulator::attachImuSensor(const simulation_api_schema::AttachImuSensorRequest & req) + -> simulation_api_schema::AttachImuSensorResponse +{ + sensor_sim_.attachImuSensor(current_simulation_time_, req.configuration(), *this); + auto res = simulation_api_schema::AttachImuSensorResponse(); + res.mutable_result()->set_success(true); + return res; +} + auto ScenarioSimulator::attachDetectionSensor( const simulation_api_schema::AttachDetectionSensorRequest & req) -> simulation_api_schema::AttachDetectionSensorResponse diff --git a/simulation/simulation_interface/include/simulation_interface/zmq_multi_client.hpp b/simulation/simulation_interface/include/simulation_interface/zmq_multi_client.hpp index 1ecd65017cc..72a78f7d456 100644 --- a/simulation/simulation_interface/include/simulation_interface/zmq_multi_client.hpp +++ b/simulation/simulation_interface/include/simulation_interface/zmq_multi_client.hpp @@ -67,6 +67,9 @@ class MultiClient auto call(const simulation_api_schema::UpdateEntityStatusRequest &) -> simulation_api_schema::UpdateEntityStatusResponse; + auto call(const simulation_api_schema::AttachImuSensorRequest &) + -> simulation_api_schema::AttachImuSensorResponse; + auto call(const simulation_api_schema::AttachLidarSensorRequest &) -> simulation_api_schema::AttachLidarSensorResponse; diff --git a/simulation/simulation_interface/include/simulation_interface/zmq_multi_server.hpp b/simulation/simulation_interface/include/simulation_interface/zmq_multi_server.hpp index c9156cbed1e..dea00eb3818 100644 --- a/simulation/simulation_interface/include/simulation_interface/zmq_multi_server.hpp +++ b/simulation/simulation_interface/include/simulation_interface/zmq_multi_server.hpp @@ -67,6 +67,7 @@ class MultiServer DEFINE_FUNCTION_TYPE(SpawnMiscObjectEntity); DEFINE_FUNCTION_TYPE(DespawnEntity); DEFINE_FUNCTION_TYPE(UpdateEntityStatus); + DEFINE_FUNCTION_TYPE(AttachImuSensor); DEFINE_FUNCTION_TYPE(AttachLidarSensor); DEFINE_FUNCTION_TYPE(AttachDetectionSensor); DEFINE_FUNCTION_TYPE(AttachOccupancyGridSensor); @@ -78,7 +79,7 @@ class MultiServer std::tuple< Initialize, UpdateFrame, SpawnVehicleEntity, SpawnPedestrianEntity, SpawnMiscObjectEntity, - DespawnEntity, UpdateEntityStatus, AttachLidarSensor, AttachDetectionSensor, + DespawnEntity, UpdateEntityStatus, AttachImuSensor, AttachLidarSensor, AttachDetectionSensor, AttachOccupancyGridSensor, UpdateTrafficLights, AttachPseudoTrafficLightDetector, UpdateStepTime> functions_; diff --git a/simulation/simulation_interface/src/zmq_multi_client.cpp b/simulation/simulation_interface/src/zmq_multi_client.cpp index c8993841e3c..a905963f072 100644 --- a/simulation/simulation_interface/src/zmq_multi_client.cpp +++ b/simulation/simulation_interface/src/zmq_multi_client.cpp @@ -146,6 +146,18 @@ auto MultiClient::call(const simulation_api_schema::UpdateEntityStatusRequest & } } +auto MultiClient::call(const simulation_api_schema::AttachImuSensorRequest & request) + -> simulation_api_schema::AttachImuSensorResponse +{ + if (is_running) { + auto simulation_request = simulation_api_schema::SimulationRequest(); + *simulation_request.mutable_attach_imu_sensor() = request; + return call(simulation_request).attach_imu_sensor(); + } else { + return {}; + } +} + auto MultiClient::call(const simulation_api_schema::AttachLidarSensorRequest & request) -> simulation_api_schema::AttachLidarSensorResponse { diff --git a/simulation/simulation_interface/src/zmq_multi_server.cpp b/simulation/simulation_interface/src/zmq_multi_server.cpp index d5c0ee95298..e10bb68cbbd 100644 --- a/simulation/simulation_interface/src/zmq_multi_server.cpp +++ b/simulation/simulation_interface/src/zmq_multi_server.cpp @@ -57,6 +57,10 @@ void MultiServer::poll() *sim_response.mutable_update_entity_status() = std::get(functions_)(proto.update_entity_status()); break; + case simulation_api_schema::SimulationRequest::RequestCase::kAttachImuSensor: + *sim_response.mutable_attach_imu_sensor() = + std::get(functions_)(proto.attach_imu_sensor()); + break; case simulation_api_schema::SimulationRequest::RequestCase::kAttachLidarSensor: *sim_response.mutable_attach_lidar_sensor() = std::get(functions_)(proto.attach_lidar_sensor()); diff --git a/simulation/traffic_simulator/include/traffic_simulator/api/api.hpp b/simulation/traffic_simulator/include/traffic_simulator/api/api.hpp index 2f81a889404..38f5e7f4d65 100644 --- a/simulation/traffic_simulator/include/traffic_simulator/api/api.hpp +++ b/simulation/traffic_simulator/include/traffic_simulator/api/api.hpp @@ -251,6 +251,10 @@ class API std::optional getTimeHeadway(const std::string & from, const std::string & to); + auto attachImuSensor( + const std::string &, const simulation_api_schema::ImuSensorConfiguration & configuration) + -> bool; + bool attachPseudoTrafficLightDetector( const simulation_api_schema::PseudoTrafficLightDetectorConfiguration &); diff --git a/simulation/traffic_simulator/src/api/api.cpp b/simulation/traffic_simulator/src/api/api.cpp index fbf565729d6..975422e577a 100644 --- a/simulation/traffic_simulator/src/api/api.cpp +++ b/simulation/traffic_simulator/src/api/api.cpp @@ -192,6 +192,14 @@ auto API::setEntityStatus( setEntityStatus(name, canonicalize(status)); } +auto API::attachImuSensor( + const std::string &, const simulation_api_schema::ImuSensorConfiguration & configuration) -> bool +{ + simulation_api_schema::AttachImuSensorRequest req; + *req.mutable_configuration() = configuration; + return zeromq_client_.call(req).result().success(); +} + bool API::attachPseudoTrafficLightDetector( const simulation_api_schema::PseudoTrafficLightDetectorConfiguration & configuration) { From 0b3dc30d7c5c533b275c1534f93970f230963d65 Mon Sep 17 00:00:00 2001 From: Dawid Moszynski Date: Wed, 3 Jul 2024 15:28:29 +0200 Subject: [PATCH 010/304] feat(simple_sensor_simulator, imu): add gravity vector, tidy up --- .../simulator_core.hpp | 1 + .../sensor_simulation/imu/imu_sensor.hpp | 15 ++++---- .../src/sensor_simulation/imu/imu_sensor.cpp | 37 ++++++++++++++----- .../proto/simulation_api_schema.proto | 9 +++-- 4 files changed, 41 insertions(+), 21 deletions(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/simulator_core.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/simulator_core.hpp index 83faef8fc00..6bce97619f8 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/simulator_core.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/simulator_core.hpp @@ -336,6 +336,7 @@ class SimulatorCore core->attachImuSensor(entity_ref, [&]() { simulation_api_schema::ImuSensorConfiguration configuration; configuration.set_entity(entity_ref); + configuration.set_add_gravity(true); configuration.set_add_noise(false); configuration.set_use_seed(true); configuration.set_seed(0); diff --git a/simulation/simple_sensor_simulator/include/simple_sensor_simulator/sensor_simulation/imu/imu_sensor.hpp b/simulation/simple_sensor_simulator/include/simple_sensor_simulator/sensor_simulation/imu/imu_sensor.hpp index a34c873073b..9ec044b3801 100644 --- a/simulation/simple_sensor_simulator/include/simple_sensor_simulator/sensor_simulation/imu/imu_sensor.hpp +++ b/simulation/simple_sensor_simulator/include/simple_sensor_simulator/sensor_simulation/imu/imu_sensor.hpp @@ -31,9 +31,9 @@ class ImuSensorBase { public: explicit ImuSensorBase(const simulation_api_schema::ImuSensorConfiguration & configuration) - : entity_name_(configuration.entity()), + : add_gravity_(configuration.add_gravity()), add_noise_(configuration.add_noise()), - noise_standard_deviation_(configuration.noise_standard_deviation()), + noise_standard_deviation_(add_noise_ ? configuration.noise_standard_deviation() : 0.0), random_generator_(configuration.use_seed() ? configuration.seed() : std::random_device{}()), noise_distribution_(0.0, noise_standard_deviation_) { @@ -46,7 +46,7 @@ class ImuSensorBase const std::vector & statuses) const -> bool = 0; protected: - const std::string entity_name_; + const bool add_gravity_; const bool add_noise_; const double noise_standard_deviation_; mutable std::mt19937 random_generator_; @@ -60,13 +60,13 @@ class ImuSensor : public ImuSensorBase explicit ImuSensor( const simulation_api_schema::ImuSensorConfiguration & configuration, const typename rclcpp::Publisher::SharedPtr & publisher) - : ImuSensorBase(configuration), publisher_(publisher) + : ImuSensorBase(configuration), entity_name_(configuration.entity()), publisher_(publisher) { } auto update( const rclcpp::Time & current_ros_time, - const std::vector & statuses) const -> bool + const std::vector & statuses) const -> bool override { for (const auto & status : statuses) { if (status.name() == entity_name_) { @@ -82,9 +82,10 @@ class ImuSensor : public ImuSensorBase private: auto generateMessage( const rclcpp::Time & current_ros_time, - const traffic_simulator_msgs::msg::EntityStatus & status) const -> const sensor_msgs::msg::Imu; + const traffic_simulator_msgs::msg::EntityStatus & status) const -> const MessageType; - const rclcpp::Publisher::SharedPtr publisher_; + const std::string entity_name_; + const typename rclcpp::Publisher::SharedPtr publisher_; }; } // namespace simple_sensor_simulator #endif // SIMPLE_SENSOR_SIMULATOR__SENSOR_SIMULATION__IMU_SENSOR_HPP_ diff --git a/simulation/simple_sensor_simulator/src/sensor_simulation/imu/imu_sensor.cpp b/simulation/simple_sensor_simulator/src/sensor_simulation/imu/imu_sensor.cpp index be272519ad3..db5e2553cd9 100644 --- a/simulation/simple_sensor_simulator/src/sensor_simulation/imu/imu_sensor.cpp +++ b/simulation/simple_sensor_simulator/src/sensor_simulation/imu/imu_sensor.cpp @@ -12,6 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. +#include +#include +#include + #include #include #include @@ -24,24 +28,37 @@ auto ImuSensor::generateMessage( const traffic_simulator_msgs::msg::EntityStatus & status) const -> const sensor_msgs::msg::Imu { const auto applyNoise = [&](geometry_msgs::msg::Vector3 & v) { - if (add_noise_) { - v.x += noise_distribution_(random_generator_); - v.y += noise_distribution_(random_generator_); - v.z += noise_distribution_(random_generator_); - } + v.x += noise_distribution_(random_generator_); + v.y += noise_distribution_(random_generator_); + v.z += noise_distribution_(random_generator_); }; auto imu_msg = sensor_msgs::msg::Imu(); imu_msg.header.stamp = current_ros_time; - imu_msg.header.frame_id = "imu_frame"; + imu_msg.header.frame_id = "imu_link"; - // Apply noise auto orientation_rpy = math::geometry::convertQuaternionToEulerAngle(status.pose.orientation); - applyNoise(orientation_rpy); auto twist = status.action_status.twist; - applyNoise(twist.angular); auto accel = status.action_status.accel; - applyNoise(accel.linear); + + // Apply noise + if (add_noise_) { + applyNoise(orientation_rpy); + applyNoise(twist.angular); + applyNoise(accel.linear); + } + + // Apply gravity + if (add_gravity_) { + tf2::Quaternion orientation_quaternion; + orientation_quaternion.setRPY(orientation_rpy.x, orientation_rpy.y, orientation_rpy.z); + tf2::Matrix3x3 rotation_matrix(orientation_quaternion); + tf2::Vector3 gravity(0.0, 0.0, -9.81); + tf2::Vector3 transformed_gravity = rotation_matrix * gravity; + accel.linear.x += transformed_gravity.x(); + accel.linear.y += transformed_gravity.y(); + accel.linear.z += transformed_gravity.z(); + } // Set data imu_msg.orientation = math::geometry::convertEulerAngleToQuaternion(orientation_rpy); diff --git a/simulation/simulation_interface/proto/simulation_api_schema.proto b/simulation/simulation_interface/proto/simulation_api_schema.proto index 37afc2d8c63..a76df569687 100644 --- a/simulation/simulation_interface/proto/simulation_api_schema.proto +++ b/simulation/simulation_interface/proto/simulation_api_schema.proto @@ -38,10 +38,11 @@ message PseudoTrafficLightDetectorConfiguration { **/ message ImuSensorConfiguration { string entity = 1; // Name of the entity which you want to attach imu. - bool add_noise = 2; - bool use_seed = 3; - int32 seed = 4; - double noise_standard_deviation = 5; + bool add_gravity = 2; // If true, gravity will be added to the acceleration vector + bool add_noise = 3; // If true, noise will be added to every vector published + bool use_seed = 4; // If true, as seed will be used the passed value, if not it will be random + int32 seed = 5; // Seed for random number generator + double noise_standard_deviation = 6; // Standard deviation for noise (normal distribution, mean equal to 0.0) } /** From 08945706f1064b13f0d76c7e4c3ffd578a95e705 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Mert=20=C3=87olak?= Date: Fri, 5 Jul 2024 17:06:31 +0300 Subject: [PATCH 011/304] fix(simple_sensor_simulator): fix eigen variable definition --- .../src/vehicle_simulation/ego_entity_simulation.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp b/simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp index 9f3ee147026..80fd95ce565 100644 --- a/simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp +++ b/simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp @@ -445,7 +445,7 @@ auto EgoEntitySimulation::getCurrentPose(const double pitch_angle = 0.) const -> geometry_msgs::msg::Pose { using math::geometry::operator*; - const auto relative_position = + const Eigen::Vector3d relative_position = math::geometry::getRotationMatrix(initial_pose_.orientation) * world_relative_position_; const auto relative_orientation = math::geometry::convertEulerAngleToQuaternion( geometry_msgs::build() From ce246a194f6c4f8e3b65063d88442dc16818a21c Mon Sep 17 00:00:00 2001 From: koki suzuki Date: Wed, 10 Jul 2024 16:35:42 +0900 Subject: [PATCH 012/304] add Longitudinal_control.md --- docs/developer_guide/Longitudinal_control.md | 136 +++++++++++++++++++ 1 file changed, 136 insertions(+) create mode 100644 docs/developer_guide/Longitudinal_control.md diff --git a/docs/developer_guide/Longitudinal_control.md b/docs/developer_guide/Longitudinal_control.md new file mode 100644 index 00000000000..9dbd9b0a7db --- /dev/null +++ b/docs/developer_guide/Longitudinal_control.md @@ -0,0 +1,136 @@ +# Longitudinal Control + +traffic_simulator has various ways to control the longitudinal behavior of the npc. + +## List of Longitudinal Controllers + +| Name | Description | +| --------------------------------------------------------- | -------------------------------------------- | +| [**requestSpeedChange**](#requestSpeedChange) | Changes the speed of the npc. | +| [**requestSynchronize**](#requestSynchronize) | Synchronizes the npc with the target entity. | +| [**setLinearVelocity**](#setLinearVelocity) | Sets the linear velocity of the npc. | +| [**setTwist**](#setTwist) | Sets the twist of the npc. | +| [**setAcceleration**](#setAcceleration) | Sets the acceleration of the npc. | +| [**setAccelerationLimit**](#setAccelerationLimit) | Sets the acceleration limit of the npc. | +| [**setAccelerationRateLimit**](#setAccelerationRateLimit) | Sets the acceleration rate limit of the npc. | +| [**setDecelerationLimit**](#setDecelerationLimit) | Sets the deceleration limit of the npc. | +| [**setDecelerationRateLimit**](#setDecelerationRateLimit) | Sets the deceleration rate limit of the npc. | +| [**setVelocityLimit**](#setVelocityLimit) | Sets the velocity limit of the npc. | + +## Details +### requestSpeedChange +By using `API::requestSpeedChange`, you can change the speed of the npc. + +| Value | Type | Description | +| ------------ | ------ | ----------------------------------------------------------- | +| name | string | Name of the npc. | +| target_speed | double | Target speed of the npc. | +| continuous | bool | If true the npc will keep the speed until the next command. | + +| Value | Type | Description | +| ------------ | ------------------------ | ----------------------------------------------------------- | +| name | string | Name of the npc. | +| target_speed | double | Target speed of the npc. | +| transition | speed_change::Transition | Transition type. | +| constraint | speed_change::Constraint | Constraint type. | +| continuous | bool | If true the npc will keep the speed until the next command. | + +| Value | Type | Description | +| ------------ | --------------------------------- | ----------------------------------------------------------- | +| name | string | Name of the npc. | +| target_speed | speed_change::RelativeTargetSpeed | Relative target speed. | +| continuous | bool | If true the npc will keep the speed until the next command. | + +| Value | Type | Description | +| ------------ | --------------------------------- | ----------------------------------------------------------- | +| name | string | Name of the npc. | +| target_speed | speed_change::RelativeTargetSpeed | Relative target speed. | +| transition | speed_change::Transition | Transition type. | +| constraint | speed_change::Constraint | Constraint type. | +| continuous | bool | If true the npc will keep the speed until the next command. | + +### requestSynchronize +By using `API::requestSynchronize`, you can request the entity to adjust speed to stop at the designated lanelet by the time target entity crosses the another designated lanelet. + +| Value | Description | +| ---------------- | ---------------------------------------------------------------------- | +| name | Name of the npc. | +| target_name | Name of the target entity. | +| target_sync_pose | Target lanelet pose for target entity. | +| entity_target | Target lanelet pose for controlling entity. | +| target_speed | Target speed for controlling entity (meter per second). | +| tolerance | Tolerance for how much margin to accept to stop at the target (meter). | + +### setLinearVelocity +By using `API::setLinearVelocity`, you can set the linear velocity of the npc. + +| Value | Type | Description | +| --------------- | ------ | --------------------------- | +| name | string | Name of the npc. | +| linear_velocity | double | Linear velocity of the npc. | + +### setTwist +By using `API::setTwist`, you can set the twist of the npc. + +| Value | Type | Description | +| ----- | ------------------------- | ----------------- | +| name | string | Name of the npc. | +| twist | geometry_msgs::msg::Twist | Twist of the npc. | + +### setAcceleration + +By using `API::setAcceleration`, you can set the acceleration of the npc. + +| Value | Type | Description | +| ------------ | ------------------------- | ------------------------ | +| name | string | Name of the npc. | +| acceleration | geometry_msgs::msg::Accel | Acceleration of the npc. | + +### setAccelerationLimit + +By using `API::setAccelerationLimit`, you can set the acceleration limit of the npc. + +| Value | Type | Description | +| ------------ | ------ | ------------------------------ | +| name | string | Name of the npc. | +| acceleration | double | Acceleration limit of the npc. | + +### setAccelerationRateLimit + +By using `API::setAccelerationRateLimit`, you can set the acceleration rate limit of the npc. + +| Value | Type | Description | +| ----------------- | ------ | ----------------------------------- | +| name | string | Name of the npc. | +| acceleration_rate | double | Acceleration rate limit of the npc. | + +### setDecelerationLimit + +By using `API::setDecelerationLimit`, you can set the deceleration limit of the npc. + +| Value | Type | Description | +| ------------ | ------ | ------------------------------ | +| name | string | Name of the npc. | +| deceleration | double | Deceleration limit of the npc. | + +### setDecelerationRateLimit + +By using `API::setDecelerationRateLimit`, you can set the deceleration rate limit of the npc. + +| Value | Type | Description | +| ----------------- | ------ | ----------------------------------- | +| name | string | Name of the npc. | +| deceleration_rate | double | Deceleration rate limit of the npc. | + +### setVelocityLimit + +By using `API::setVelocityLimit`, you can set the velocity limit of the npc. + +| Value | Type | Description | +| --------------- | ------ | -------------------------- | +| name | string | Name of the npc. | +| lenear_velocity | double | Velocity limit of the npc. | + + + + From 36c15f8302487333eacf438338d8b5aaa138a70a Mon Sep 17 00:00:00 2001 From: koki suzuki Date: Wed, 10 Jul 2024 16:43:18 +0900 Subject: [PATCH 013/304] chore: remove unnecessary lines in Longitudinal_control.md --- docs/developer_guide/Longitudinal_control.md | 4 ---- 1 file changed, 4 deletions(-) diff --git a/docs/developer_guide/Longitudinal_control.md b/docs/developer_guide/Longitudinal_control.md index 9dbd9b0a7db..d4bc38b3738 100644 --- a/docs/developer_guide/Longitudinal_control.md +++ b/docs/developer_guide/Longitudinal_control.md @@ -130,7 +130,3 @@ By using `API::setVelocityLimit`, you can set the velocity limit of the npc. | --------------- | ------ | -------------------------- | | name | string | Name of the npc. | | lenear_velocity | double | Velocity limit of the npc. | - - - - From 5eefcc9c50384a7402715dc1e47cf17fd77a7ad9 Mon Sep 17 00:00:00 2001 From: koki suzuki Date: Wed, 10 Jul 2024 16:45:09 +0900 Subject: [PATCH 014/304] chore: fix typo in Longitudinal_control.md --- docs/developer_guide/Longitudinal_control.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/developer_guide/Longitudinal_control.md b/docs/developer_guide/Longitudinal_control.md index d4bc38b3738..052d1067486 100644 --- a/docs/developer_guide/Longitudinal_control.md +++ b/docs/developer_guide/Longitudinal_control.md @@ -129,4 +129,4 @@ By using `API::setVelocityLimit`, you can set the velocity limit of the npc. | Value | Type | Description | | --------------- | ------ | -------------------------- | | name | string | Name of the npc. | -| lenear_velocity | double | Velocity limit of the npc. | +| linear_velocity | double | Velocity limit of the npc. | From 1a6daf74ba98e06b33d8e5094d13215d5475c36e Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Tue, 16 Jul 2024 16:18:31 +0900 Subject: [PATCH 015/304] feat: add ByEntityCondition.EntityCondition.RelativeClearanceCondition.yaml --- ...yCondition.RelativeClearanceCondition.yaml | 234 ++++++++++++++++++ 1 file changed, 234 insertions(+) create mode 100644 test_runner/scenario_test_runner/scenario/ByEntityCondition.EntityCondition.RelativeClearanceCondition.yaml diff --git a/test_runner/scenario_test_runner/scenario/ByEntityCondition.EntityCondition.RelativeClearanceCondition.yaml b/test_runner/scenario_test_runner/scenario/ByEntityCondition.EntityCondition.RelativeClearanceCondition.yaml new file mode 100644 index 00000000000..9311a799ac5 --- /dev/null +++ b/test_runner/scenario_test_runner/scenario/ByEntityCondition.EntityCondition.RelativeClearanceCondition.yaml @@ -0,0 +1,234 @@ +OpenSCENARIO: + FileHeader: + revMajor: 0 + revMinor: 0 + date: "1970-01-01T09:00:00+09:00" + author: Kotaro Yoshimoto + description: "" + ParameterDeclarations: + ParameterDeclaration: [] + CatalogLocations: + VehicleCatalog: + Directory: + path: $(ros2 pkg prefix --share openscenario_experimental_catalog)/vehicle + RoadNetwork: + LogicFile: + filepath: $(find-pkg-share kashiwanoha_map)/map + Entities: + ScenarioObject: + - name: ego + CatalogReference: &SAMPLE_VEHICLE + catalogName: sample_vehicle + entryName: sample_vehicle + - name: car_1 + CatalogReference: *SAMPLE_VEHICLE + - name: car_2 + CatalogReference: *SAMPLE_VEHICLE + - name: car_3 + CatalogReference: *SAMPLE_VEHICLE + - name: car_4 + CatalogReference: *SAMPLE_VEHICLE + Storyboard: + Init: + Actions: + Private: + - entityRef: ego + PrivateAction: + - TeleportAction: + Position: + LanePosition: &EGO_LANE_POSITION + roadId: "" + laneId: 34513 + s: 10 + offset: 0 + Orientation: + type: relative + h: 0 + p: 0 + r: 0 + - LongitudinalAction: &SPEED_ACTION_ZERO + SpeedAction: + SpeedActionDynamics: + dynamicsDimension: time + value: 0 + dynamicsShape: step + SpeedActionTarget: + AbsoluteTargetSpeed: + value: 0 + - entityRef: car_1 + PrivateAction: + - TeleportAction: + Position: + LanePosition: &CAR_1_LANE_POSITION + << : *EGO_LANE_POSITION + s: 20 + - LongitudinalAction: *SPEED_ACTION_ZERO + - entityRef: car_2 + PrivateAction: + - TeleportAction: + Position: + LanePosition: &CAR_2_LANE_POSITION + << : *EGO_LANE_POSITION + laneId: 34462 + s: 20 + - LongitudinalAction: *SPEED_ACTION_ZERO + - entityRef: car_3 + PrivateAction: + - TeleportAction: + Position: + LanePosition: + << : *EGO_LANE_POSITION + laneId: 34462 + s: 5 + - LongitudinalAction: *SPEED_ACTION_ZERO + - entityRef: car_4 + PrivateAction: + - TeleportAction: + Position: + LanePosition: + << : *EGO_LANE_POSITION + s: 5 + - LongitudinalAction: *SPEED_ACTION_ZERO + Story: + - name: story + Act: + - name: act + ManeuverGroup: + - maximumExecutionCount: 1 + name: maneuver_group + Actors: + selectTriggeringEntities: false + EntityRef: + - entityRef: ego + Maneuver: + - name: maneuver + Event: + - name: success + priority: parallel + Action: + - name: "" + UserDefinedAction: + CustomCommandAction: + type: exitSuccess + StartTrigger: + ConditionGroup: + - Condition: + - name: "" + delay: 0 + conditionEdge: none + ByEntityCondition: + TriggeringEntities: + triggeringEntitiesRule: all + EntityRef: + - entityRef: ego + EntityCondition: + RelativeClearanceCondition: + EntityRef: + - entityRef: car_1 + distanceBackward: 0 + distanceForward: 9 + freeSpace: false + oppositeLanes: false + - name: "" + delay: 0 + conditionEdge: none + ByEntityCondition: + TriggeringEntities: + triggeringEntitiesRule: all + EntityRef: + - entityRef: ego + EntityCondition: + RelativeClearanceCondition: + EntityRef: + - entityRef: car_1 + distanceBackward: 0 + distanceForward: 9 + freeSpace: false + oppositeLanes: false + - name: "" + delay: 0 + conditionEdge: none + ByEntityCondition: + TriggeringEntities: + triggeringEntitiesRule: all + EntityRef: + - entityRef: car_3 + - entityRef: car_4 + EntityCondition: + RelativeDistanceCondition: + coordinateSystem: lane + entityRef: ego + freespace: false # True: distance is measured between closest bounding box points. False: reference point distance is used. + relativeDistanceType: longitudinal + rule: equalTo + value: 10 + - name: "" + delay: 0 + conditionEdge: none + ByEntityCondition: + TriggeringEntities: + triggeringEntitiesRule: all + EntityRef: + - entityRef: car_1 + - entityRef: car_3 + EntityCondition: + RelativeDistanceCondition: + coordinateSystem: lane + entityRef: ego + freespace: false # True: distance is measured between closest bounding box points. False: reference point distance is used. + relativeDistanceType: lateral + rule: equalTo + value: -1.5 + - name: "" + delay: 0 + conditionEdge: none + ByEntityCondition: + TriggeringEntities: + triggeringEntitiesRule: all + EntityRef: + - entityRef: car_2 + - entityRef: car_4 + EntityCondition: + RelativeDistanceCondition: + coordinateSystem: lane + entityRef: ego + freespace: false # True: distance is measured between closest bounding box points. False: reference point distance is used. + relativeDistanceType: lateral + rule: equalTo + value: 0.5 + - name: "" + delay: 0 + conditionEdge: none + ByValueCondition: + SimulationTimeCondition: + value: 10 + rule: greaterThan + - name: failure + priority: parallel + Action: + - name: "" + UserDefinedAction: + CustomCommandAction: + type: exitFailure + StartTrigger: + ConditionGroup: + - Condition: + - name: "" + delay: 0 + conditionEdge: none + ByValueCondition: + SimulationTimeCondition: + value: 20 + rule: greaterThan + StartTrigger: + ConditionGroup: + - Condition: + - name: "" + delay: 0 + conditionEdge: none + ByValueCondition: + SimulationTimeCondition: + value: 0 + rule: greaterThan + StopTrigger: + ConditionGroup: [] From bde54c62a5038fff57f4f72054bf41b1d09f6152 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Tue, 16 Jul 2024 18:07:31 +0900 Subject: [PATCH 016/304] chore: update OpenSCENARIO version of EntityCondition --- .../syntax/entity_condition.hpp | 53 +++++++++++-------- .../src/syntax/entity_condition.cpp | 30 ++++++----- 2 files changed, 49 insertions(+), 34 deletions(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/entity_condition.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/entity_condition.hpp index 19add645326..e1a4f23ccab 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/entity_condition.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/entity_condition.hpp @@ -23,27 +23,38 @@ namespace openscenario_interpreter { inline namespace syntax { -/* ---- EntityCondition -------------------------------------------------------- - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * -------------------------------------------------------------------------- */ +/* + EntityCondition (OpenSCENARIO XML 1.3) + + Defines a specific condition on an entity. + + + + + + + + + + + + + + + + + deprecated + + + + + + + + + + + */ struct EntityCondition : public ComplexType { explicit EntityCondition(const pugi::xml_node &, Scope &, const TriggeringEntities &); diff --git a/openscenario/openscenario_interpreter/src/syntax/entity_condition.cpp b/openscenario/openscenario_interpreter/src/syntax/entity_condition.cpp index 9577b8f9453..df89c5ba0fe 100644 --- a/openscenario/openscenario_interpreter/src/syntax/entity_condition.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/entity_condition.cpp @@ -18,6 +18,7 @@ #include #include #include +#include #include #include #include @@ -32,19 +33,22 @@ EntityCondition::EntityCondition( // clang-format off : ComplexType( choice(node, - std::make_pair( "EndOfRoadCondition", [&](const auto & node) { throw UNSUPPORTED_ELEMENT_SPECIFIED(node.name()); return unspecified; }), - std::make_pair( "CollisionCondition", [&](const auto & node) { return make< CollisionCondition>(node, scope, triggering_entities); }), - std::make_pair( "OffroadCondition", [&](const auto & node) { throw UNSUPPORTED_ELEMENT_SPECIFIED(node.name()); return unspecified; }), - std::make_pair( "TimeHeadwayCondition", [&](const auto & node) { return make< TimeHeadwayCondition>(node, scope, triggering_entities); }), - std::make_pair( "TimeToCollisionCondition", [&](const auto & node) { throw UNSUPPORTED_ELEMENT_SPECIFIED(node.name()); return unspecified; }), - std::make_pair( "AccelerationCondition", [&](const auto & node) { return make< AccelerationCondition>(node, scope, triggering_entities); }), - std::make_pair( "StandStillCondition", [&](const auto & node) { return make< StandStillCondition>(node, scope, triggering_entities); }), - std::make_pair( "SpeedCondition", [&](const auto & node) { return make< SpeedCondition>(node, scope, triggering_entities); }), - std::make_pair( "RelativeSpeedCondition", [&](const auto & node) { throw UNSUPPORTED_ELEMENT_SPECIFIED(node.name()); return unspecified; }), - std::make_pair("TraveledDistanceCondition", [&](const auto & node) { throw UNSUPPORTED_ELEMENT_SPECIFIED(node.name()); return unspecified; }), - std::make_pair( "ReachPositionCondition", [&](const auto & node) { return make< ReachPositionCondition>(node, scope, triggering_entities); }), - std::make_pair( "DistanceCondition", [&](const auto & node) { return make< DistanceCondition>(node, scope, triggering_entities); }), - std::make_pair("RelativeDistanceCondition", [&](const auto & node) { return make(node, scope, triggering_entities); }) + std::make_pair( "EndOfRoadCondition", [&](const auto & node) { throw UNSUPPORTED_ELEMENT_SPECIFIED(node.name()); return unspecified; }), + std::make_pair( "CollisionCondition", [&](const auto & node) { return make< CollisionCondition>(node, scope, triggering_entities); }), + std::make_pair( "OffroadCondition", [&](const auto & node) { throw UNSUPPORTED_ELEMENT_SPECIFIED(node.name()); return unspecified; }), + std::make_pair( "TimeHeadwayCondition", [&](const auto & node) { return make< TimeHeadwayCondition>(node, scope, triggering_entities); }), + std::make_pair( "TimeToCollisionCondition", [&](const auto & node) { throw UNSUPPORTED_ELEMENT_SPECIFIED(node.name()); return unspecified; }), + std::make_pair( "AccelerationCondition", [&](const auto & node) { return make< AccelerationCondition>(node, scope, triggering_entities); }), + std::make_pair( "StandStillCondition", [&](const auto & node) { return make< StandStillCondition>(node, scope, triggering_entities); }), + std::make_pair( "SpeedCondition", [&](const auto & node) { return make< SpeedCondition>(node, scope, triggering_entities); }), + std::make_pair( "RelativeSpeedCondition", [&](const auto & node) { throw UNSUPPORTED_ELEMENT_SPECIFIED(node.name()); return unspecified; }), + std::make_pair( "TraveledDistanceCondition", [&](const auto & node) { throw UNSUPPORTED_ELEMENT_SPECIFIED(node.name()); return unspecified; }), + std::make_pair( "ReachPositionCondition", [&](const auto & node) { return make< ReachPositionCondition>(node, scope, triggering_entities); }), + std::make_pair( "DistanceCondition", [&](const auto & node) { return make< DistanceCondition>(node, scope, triggering_entities); }), + std::make_pair( "RelativeDistanceCondition", [&](const auto & node) { return make< RelativeDistanceCondition>(node, scope, triggering_entities); }), + std::make_pair("RelativeClearanceCondition", [&](const auto & node) { return make(node, scope, triggering_entities); }), + std::make_pair( "AngleCondition", [&](const auto & node) { throw UNSUPPORTED_ELEMENT_SPECIFIED(node.name()); return unspecified; }), + std::make_pair( "RelativeAngleCondition", [&](const auto & node) { throw UNSUPPORTED_ELEMENT_SPECIFIED(node.name()); return unspecified; }) )) // clang-format on { From d085cea2f5ae53ce750f190decc6e68d37024ec1 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Tue, 16 Jul 2024 18:08:15 +0900 Subject: [PATCH 017/304] fix: replace freespace with freeSpace in RelativeClearanceCondition --- .../syntax/relative_clearance_condition.hpp | 2 +- .../src/syntax/relative_clearance_condition.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_clearance_condition.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_clearance_condition.hpp index 1255d03da93..1433fb11306 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_clearance_condition.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_clearance_condition.hpp @@ -55,7 +55,7 @@ struct RelativeClearanceCondition : private Scope, private SimulatorCore::Condit /* If false, then entityRefs are only considered to be on the lane if their reference point is within the checked area; otherwise the whole bounding box is considered. */ - const Boolean freespace; + const Boolean free_space; /* If true, then also lanes in the opposite direction are considered; otherwise only lanes in the same direction are considered. diff --git a/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp b/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp index 6506f879407..32ce5986d23 100644 --- a/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp @@ -27,7 +27,7 @@ RelativeClearanceCondition::RelativeClearanceCondition( : Scope(scope), distance_backward(readAttribute("distanceBackward", node, scope, 0.0)), distance_forward(readAttribute("distanceForward", node, scope, 0.0)), - freespace(readAttribute("freespace", node, scope)), + free_space(readAttribute("freeSpace", node, scope)), opposite_lanes(readAttribute("oppositeLanes", node, scope)), relative_lane_range(readElements("RelativeLaneRange", node, scope)), entity_refs(readElements("EntityRef", node, scope)), From 727d57dc93f29badb41661fcb8543c9ce7840392 Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Wed, 22 May 2024 16:58:51 +0900 Subject: [PATCH 018/304] Move entity existence check into `distance` from speceialized `distance` Signed-off-by: yamacir-kit --- .../syntax/relative_distance_condition.cpp | 385 +++++++----------- 1 file changed, 157 insertions(+), 228 deletions(-) diff --git a/openscenario/openscenario_interpreter/src/syntax/relative_distance_condition.cpp b/openscenario/openscenario_interpreter/src/syntax/relative_distance_condition.cpp index 90e9b7be341..8fd12515497 100644 --- a/openscenario/openscenario_interpreter/src/syntax/relative_distance_condition.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/relative_distance_condition.cpp @@ -73,31 +73,20 @@ auto RelativeDistanceCondition::distance< CoordinateSystem::entity, RelativeDistanceType::longitudinal, RoutingAlgorithm::undefined, false>( const EntityRef & triggering_entity) -> double { - if ( - global().entities->at(triggering_entity).as().is_added and - global().entities->at(entity_ref).as().is_added) { - return std::abs(makeNativeRelativeWorldPosition(triggering_entity, entity_ref).position.x); - } else { - return Double::nan(); - } + return std::abs(makeNativeRelativeWorldPosition(triggering_entity, entity_ref).position.x); } -/** - * @note This implementation differs from the OpenSCENARIO standard. See the section "6.4. Distances" in the OpenSCENARIO User Guide. - */ template <> auto RelativeDistanceCondition::distance< CoordinateSystem::entity, RelativeDistanceType::longitudinal, RoutingAlgorithm::undefined, true>( const EntityRef & triggering_entity) -> double { - if ( - global().entities->at(triggering_entity).as().is_added and - global().entities->at(entity_ref).as().is_added) { - return std::abs( - makeNativeBoundingBoxRelativeWorldPosition(triggering_entity, entity_ref).position.x); - } else { - return Double::nan(); - } + /** + @note This implementation differs from the OpenSCENARIO standard. See the + section "6.4. Distances" in the OpenSCENARIO User Guide. + */ + return std::abs( + makeNativeBoundingBoxRelativeWorldPosition(triggering_entity, entity_ref).position.x); } template <> @@ -105,35 +94,24 @@ auto RelativeDistanceCondition::distance< CoordinateSystem::entity, RelativeDistanceType::lateral, RoutingAlgorithm::undefined, false>( const EntityRef & triggering_entity) -> double { - if ( - global().entities->at(triggering_entity).as().is_added and - global().entities->at(entity_ref).as().is_added) { - return std::abs(makeNativeRelativeWorldPosition(triggering_entity, entity_ref).position.y); - } else { - return Double::nan(); - } + return std::abs(makeNativeRelativeWorldPosition(triggering_entity, entity_ref).position.y); } -/** - * @note This implementation differs from the OpenSCENARIO standard. See the section "6.4. Distances" in the OpenSCENARIO User Guide. - */ template <> auto RelativeDistanceCondition::distance< CoordinateSystem::entity, RelativeDistanceType::lateral, RoutingAlgorithm::undefined, true>( const EntityRef & triggering_entity) -> double { - if ( - global().entities->at(triggering_entity).as().is_added and - global().entities->at(entity_ref).as().is_added) { - return std::abs( - makeNativeBoundingBoxRelativeWorldPosition(triggering_entity, entity_ref).position.y); - } else { - return Double::nan(); - } + /** + @note This implementation differs from the OpenSCENARIO standard. See the + section "6.4. Distances" in the OpenSCENARIO User Guide. + */ + return std::abs( + makeNativeBoundingBoxRelativeWorldPosition(triggering_entity, entity_ref).position.y); } -// @todo: after checking all the scenario work well with consider_z = true, remove this function and use std::hypot(x,y,z) -static double hypot(const double x, const double y, const double z, const bool consider_z) +// @todo: after checking all the scenario work well with consider_z = true, remove this function and use std::hypot(x, y, z) +auto hypot(double x, double y, double z, bool consider_z) { return consider_z ? std::hypot(x, y, z) : std::hypot(x, y); } @@ -143,17 +121,11 @@ auto RelativeDistanceCondition::distance< CoordinateSystem::entity, RelativeDistanceType::euclidianDistance, RoutingAlgorithm::undefined, true>(const EntityRef & triggering_entity) -> double { - if ( - global().entities->at(triggering_entity).as().is_added and - global().entities->at(entity_ref).as().is_added) { - return hypot( - makeNativeBoundingBoxRelativeWorldPosition(triggering_entity, entity_ref).position.x, - makeNativeBoundingBoxRelativeWorldPosition(triggering_entity, entity_ref).position.y, - makeNativeBoundingBoxRelativeWorldPosition(triggering_entity, entity_ref).position.z, - consider_z); - } else { - return Double::nan(); - } + return hypot( + makeNativeBoundingBoxRelativeWorldPosition(triggering_entity, entity_ref).position.x, + makeNativeBoundingBoxRelativeWorldPosition(triggering_entity, entity_ref).position.y, + makeNativeBoundingBoxRelativeWorldPosition(triggering_entity, entity_ref).position.z, + consider_z); } template <> @@ -161,16 +133,10 @@ auto RelativeDistanceCondition::distance< CoordinateSystem::entity, RelativeDistanceType::euclidianDistance, RoutingAlgorithm::undefined, false>(const EntityRef & triggering_entity) -> double { - if ( - global().entities->at(triggering_entity).as().is_added and - global().entities->at(entity_ref).as().is_added) { - return hypot( - makeNativeRelativeWorldPosition(triggering_entity, entity_ref).position.x, - makeNativeRelativeWorldPosition(triggering_entity, entity_ref).position.y, - makeNativeRelativeWorldPosition(triggering_entity, entity_ref).position.z, consider_z); - } else { - return Double::nan(); - } + return hypot( + makeNativeRelativeWorldPosition(triggering_entity, entity_ref).position.x, + makeNativeRelativeWorldPosition(triggering_entity, entity_ref).position.y, + makeNativeRelativeWorldPosition(triggering_entity, entity_ref).position.z, consider_z); } template <> @@ -178,27 +144,21 @@ auto RelativeDistanceCondition::distance< CoordinateSystem::lane, RelativeDistanceType::lateral, RoutingAlgorithm::undefined, false>( const EntityRef & triggering_entity) -> double { - if ( - global().entities->at(entity_ref).as().is_added and - global().entities->at(triggering_entity).as().is_added) { - /* - For historical reasons, signed distances are returned when - coordinateSystem == lane and relativeDistanceType == - longitudinal/lateral. The sign has been mainly used to determine the - front/back and left/right positional relationship (a negative value is - returned if the target entity is behind or to the right). - - This behavior violates the OpenSCENARIO standard. In the future, after - DistanceCondition and RelativeDistanceCondition of TIER IV's - OpenSCENARIO Interpreter support OpenSCENARIO 1.2 RoutingAlgorithm, this - behavior will be enabled only when routingAlgorithm == undefined. - */ - return static_cast( - makeNativeRelativeLanePosition(triggering_entity, entity_ref)) - .offset; - } else { - return Double::nan(); - } + /* + For historical reasons, signed distances are returned when + coordinateSystem == lane and relativeDistanceType == longitudinal/lateral. + The sign has been mainly used to determine the front/back and left/right + positional relationship (a negative value is returned if the target entity + is behind or to the right). + + This behavior violates the OpenSCENARIO standard. In the future, after + DistanceCondition and RelativeDistanceCondition of TIER IV's OpenSCENARIO + Interpreter support OpenSCENARIO 1.2 RoutingAlgorithm, this behavior will + be enabled only when routingAlgorithm == undefined. + */ + return static_cast( + makeNativeRelativeLanePosition(triggering_entity, entity_ref)) + .offset; } template <> @@ -206,27 +166,21 @@ auto RelativeDistanceCondition::distance< CoordinateSystem::lane, RelativeDistanceType::lateral, RoutingAlgorithm::undefined, true>( const EntityRef & triggering_entity) -> double { - if ( - global().entities->at(entity_ref).as().is_added and - global().entities->at(triggering_entity).as().is_added) { - /* - For historical reasons, signed distances are returned when - coordinateSystem == lane and relativeDistanceType == - longitudinal/lateral. The sign has been mainly used to determine the - front/back and left/right positional relationship (a negative value is - returned if the target entity is behind or to the right). - - This behavior violates the OpenSCENARIO standard. In the future, after - DistanceCondition and RelativeDistanceCondition of TIER IV's - OpenSCENARIO Interpreter support OpenSCENARIO 1.2 RoutingAlgorithm, this - behavior will be enabled only when routingAlgorithm == undefined. - */ - return static_cast( - makeNativeBoundingBoxRelativeLanePosition(triggering_entity, entity_ref)) - .offset; - } else { - return Double::nan(); - } + /* + For historical reasons, signed distances are returned when + coordinateSystem == lane and relativeDistanceType == longitudinal/lateral. + The sign has been mainly used to determine the front/back and left/right + positional relationship (a negative value is returned if the target entity + is behind or to the right). + + This behavior violates the OpenSCENARIO standard. In the future, after + DistanceCondition and RelativeDistanceCondition of TIER IV's OpenSCENARIO + Interpreter support OpenSCENARIO 1.2 RoutingAlgorithm, this behavior will + be enabled only when routingAlgorithm == undefined. + */ + return static_cast( + makeNativeBoundingBoxRelativeLanePosition(triggering_entity, entity_ref)) + .offset; } template <> @@ -234,27 +188,21 @@ auto RelativeDistanceCondition::distance< CoordinateSystem::lane, RelativeDistanceType::longitudinal, RoutingAlgorithm::undefined, false>( const EntityRef & triggering_entity) -> double { - if ( - global().entities->at(triggering_entity).as().is_added and - global().entities->at(entity_ref).as().is_added) { - /* - For historical reasons, signed distances are returned when - coordinateSystem == lane and relativeDistanceType == - longitudinal/lateral. The sign has been mainly used to determine the - front/back and left/right positional relationship (a negative value is - returned if the target entity is behind or to the right). - - This behavior violates the OpenSCENARIO standard. In the future, after - DistanceCondition and RelativeDistanceCondition of TIER IV's - OpenSCENARIO Interpreter support OpenSCENARIO 1.2 RoutingAlgorithm, this - behavior will be enabled only when routingAlgorithm == undefined. - */ - return static_cast( - makeNativeRelativeLanePosition(triggering_entity, entity_ref)) - .s; - } else { - return Double::nan(); - } + /* + For historical reasons, signed distances are returned when + coordinateSystem == lane and relativeDistanceType == longitudinal/lateral. + The sign has been mainly used to determine the front/back and left/right + positional relationship (a negative value is returned if the target entity + is behind or to the right). + + This behavior violates the OpenSCENARIO standard. In the future, after + DistanceCondition and RelativeDistanceCondition of TIER IV's OpenSCENARIO + Interpreter support OpenSCENARIO 1.2 RoutingAlgorithm, this behavior will + be enabled only when routingAlgorithm == undefined. + */ + return static_cast( + makeNativeRelativeLanePosition(triggering_entity, entity_ref)) + .s; } template <> @@ -262,27 +210,21 @@ auto RelativeDistanceCondition::distance< CoordinateSystem::lane, RelativeDistanceType::longitudinal, RoutingAlgorithm::undefined, true>( const EntityRef & triggering_entity) -> double { - if ( - global().entities->at(triggering_entity).as().is_added and - global().entities->at(entity_ref).as().is_added) { - /* - For historical reasons, signed distances are returned when - coordinateSystem == lane and relativeDistanceType == - longitudinal/lateral. The sign has been mainly used to determine the - front/back and left/right positional relationship (a negative value is - returned if the target entity is behind or to the right). - - This behavior violates the OpenSCENARIO standard. In the future, after - DistanceCondition and RelativeDistanceCondition of TIER IV's - OpenSCENARIO Interpreter support OpenSCENARIO 1.2 RoutingAlgorithm, this - behavior will be enabled only when routingAlgorithm == undefined. - */ - return static_cast( - makeNativeBoundingBoxRelativeLanePosition(triggering_entity, entity_ref)) - .s; - } else { - return Double::nan(); - } + /* + For historical reasons, signed distances are returned when + coordinateSystem == lane and relativeDistanceType == longitudinal/lateral. + The sign has been mainly used to determine the front/back and left/right + positional relationship (a negative value is returned if the target entity + is behind or to the right). + + This behavior violates the OpenSCENARIO standard. In the future, after + DistanceCondition and RelativeDistanceCondition of TIER IV's OpenSCENARIO + Interpreter support OpenSCENARIO 1.2 RoutingAlgorithm, this behavior will + be enabled only when routingAlgorithm == undefined. + */ + return static_cast( + makeNativeBoundingBoxRelativeLanePosition(triggering_entity, entity_ref)) + .s; } template <> @@ -290,16 +232,10 @@ auto RelativeDistanceCondition::distance< CoordinateSystem::lane, RelativeDistanceType::lateral, RoutingAlgorithm::shortest, true>( const EntityRef & triggering_entity) -> double { - if ( - global().entities->at(entity_ref).as().is_added and - global().entities->at(triggering_entity).as().is_added) { - return std::abs(static_cast( - makeNativeBoundingBoxRelativeLanePosition( - triggering_entity, entity_ref, RoutingAlgorithm::shortest)) - .offset); - } else { - return Double::nan(); - } + return std::abs(static_cast( + makeNativeBoundingBoxRelativeLanePosition( + triggering_entity, entity_ref, RoutingAlgorithm::shortest)) + .offset); } template <> @@ -307,16 +243,10 @@ auto RelativeDistanceCondition::distance< CoordinateSystem::lane, RelativeDistanceType::lateral, RoutingAlgorithm::shortest, false>( const EntityRef & triggering_entity) -> double { - if ( - global().entities->at(entity_ref).as().is_added and - global().entities->at(triggering_entity).as().is_added) { - return std::abs( - static_cast( - makeNativeRelativeLanePosition(triggering_entity, entity_ref, RoutingAlgorithm::shortest)) - .offset); - } else { - return Double::nan(); - } + return std::abs( + static_cast( + makeNativeRelativeLanePosition(triggering_entity, entity_ref, RoutingAlgorithm::shortest)) + .offset); } template <> @@ -324,16 +254,10 @@ auto RelativeDistanceCondition::distance< CoordinateSystem::lane, RelativeDistanceType::longitudinal, RoutingAlgorithm::shortest, true>( const EntityRef & triggering_entity) -> double { - if ( - global().entities->at(entity_ref).as().is_added and - global().entities->at(triggering_entity).as().is_added) { - return std::abs(static_cast( - makeNativeBoundingBoxRelativeLanePosition( - triggering_entity, entity_ref, RoutingAlgorithm::shortest)) - .s); - } else { - return Double::nan(); - } + return std::abs(static_cast( + makeNativeBoundingBoxRelativeLanePosition( + triggering_entity, entity_ref, RoutingAlgorithm::shortest)) + .s); } template <> @@ -341,64 +265,64 @@ auto RelativeDistanceCondition::distance< CoordinateSystem::lane, RelativeDistanceType::longitudinal, RoutingAlgorithm::shortest, false>( const EntityRef & triggering_entity) -> double { - if ( - global().entities->at(entity_ref).as().is_added and - global().entities->at(triggering_entity).as().is_added) { - return std::abs( - static_cast( - makeNativeRelativeLanePosition(triggering_entity, entity_ref, RoutingAlgorithm::shortest)) - .s); - } else { - return Double::nan(); - } + return std::abs( + static_cast( + makeNativeRelativeLanePosition(triggering_entity, entity_ref, RoutingAlgorithm::shortest)) + .s); } -#define SWITCH_COORDINATE_SYSTEM(FUNCTION, ...) \ - switch (coordinate_system) { \ - case CoordinateSystem::entity: \ - FUNCTION(__VA_ARGS__, CoordinateSystem::entity); \ - break; \ - case CoordinateSystem::lane: \ - FUNCTION(__VA_ARGS__, CoordinateSystem::lane); \ - break; \ - case CoordinateSystem::road: \ - FUNCTION(__VA_ARGS__, CoordinateSystem::road); \ - break; \ - case CoordinateSystem::trajectory: \ - FUNCTION(__VA_ARGS__, CoordinateSystem::trajectory); \ - break; \ +#define SWITCH_COORDINATE_SYSTEM(FUNCTION, ...) \ + switch (coordinate_system) { \ + case CoordinateSystem::entity: \ + FUNCTION(__VA_ARGS__, CoordinateSystem::entity); \ + break; \ + case CoordinateSystem::lane: \ + FUNCTION(__VA_ARGS__, CoordinateSystem::lane); \ + break; \ + case CoordinateSystem::road: \ + FUNCTION(__VA_ARGS__, CoordinateSystem::road); \ + break; \ + case CoordinateSystem::trajectory: \ + FUNCTION(__VA_ARGS__, CoordinateSystem::trajectory); \ + break; \ + default: \ + throw UNEXPECTED_ENUMERATION_VALUE_ASSIGNED(CoordinateSystem, coordinate_system); \ } -#define SWITCH_RELATIVE_DISTANCE_TYPE(FUNCTION, ...) \ - switch (relative_distance_type) { \ - case RelativeDistanceType::longitudinal: \ - FUNCTION(__VA_ARGS__, RelativeDistanceType::longitudinal); \ - break; \ - case RelativeDistanceType::lateral: \ - FUNCTION(__VA_ARGS__, RelativeDistanceType::lateral); \ - break; \ - case RelativeDistanceType::euclidianDistance: \ - FUNCTION(__VA_ARGS__, RelativeDistanceType::euclidianDistance); \ - break; \ +#define SWITCH_RELATIVE_DISTANCE_TYPE(FUNCTION, ...) \ + switch (relative_distance_type) { \ + case RelativeDistanceType::longitudinal: \ + FUNCTION(__VA_ARGS__, RelativeDistanceType::longitudinal); \ + break; \ + case RelativeDistanceType::lateral: \ + FUNCTION(__VA_ARGS__, RelativeDistanceType::lateral); \ + break; \ + case RelativeDistanceType::euclidianDistance: \ + FUNCTION(__VA_ARGS__, RelativeDistanceType::euclidianDistance); \ + break; \ + default: \ + throw UNEXPECTED_ENUMERATION_VALUE_ASSIGNED(RelativeDistanceType, relative_distance_type); \ } -#define SWITCH_ROUTING_ALGORITHM(FUNCTION, ...) \ - switch (routing_algorithm) { \ - case RoutingAlgorithm::assigned_route: \ - FUNCTION(__VA_ARGS__, RoutingAlgorithm::assigned_route); \ - break; \ - case RoutingAlgorithm::fastest: \ - FUNCTION(__VA_ARGS__, RoutingAlgorithm::fastest); \ - break; \ - case RoutingAlgorithm::least_intersections: \ - FUNCTION(__VA_ARGS__, RoutingAlgorithm::least_intersections); \ - break; \ - case RoutingAlgorithm::shortest: \ - FUNCTION(__VA_ARGS__, RoutingAlgorithm::shortest); \ - break; \ - case RoutingAlgorithm::undefined: \ - FUNCTION(__VA_ARGS__, RoutingAlgorithm::undefined); \ - break; \ +#define SWITCH_ROUTING_ALGORITHM(FUNCTION, ...) \ + switch (routing_algorithm) { \ + case RoutingAlgorithm::assigned_route: \ + FUNCTION(__VA_ARGS__, RoutingAlgorithm::assigned_route); \ + break; \ + case RoutingAlgorithm::fastest: \ + FUNCTION(__VA_ARGS__, RoutingAlgorithm::fastest); \ + break; \ + case RoutingAlgorithm::least_intersections: \ + FUNCTION(__VA_ARGS__, RoutingAlgorithm::least_intersections); \ + break; \ + case RoutingAlgorithm::shortest: \ + FUNCTION(__VA_ARGS__, RoutingAlgorithm::shortest); \ + break; \ + case RoutingAlgorithm::undefined: \ + FUNCTION(__VA_ARGS__, RoutingAlgorithm::undefined); \ + break; \ + default: \ + throw UNEXPECTED_ENUMERATION_VALUE_ASSIGNED(RoutingAlgorithm, routing_algorithm); \ } #define SWITCH_FREESPACE(FUNCTION, ...) \ @@ -408,9 +332,14 @@ auto RelativeDistanceCondition::distance< auto RelativeDistanceCondition::distance(const EntityRef & triggering_entity) -> double { - SWITCH_COORDINATE_SYSTEM( - SWITCH_RELATIVE_DISTANCE_TYPE, SWITCH_ROUTING_ALGORITHM, SWITCH_FREESPACE, DISTANCE); - return Double::nan(); + if ( + global().entities->at(triggering_entity).as().is_added and + global().entities->at(entity_ref).as().is_added) { + SWITCH_COORDINATE_SYSTEM( + SWITCH_RELATIVE_DISTANCE_TYPE, SWITCH_ROUTING_ALGORITHM, SWITCH_FREESPACE, DISTANCE); + } else { + return Double::nan(); + } } auto RelativeDistanceCondition::evaluate() -> Object From 86f489f036e17b86acd2a6ceea33db5039be4841 Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Wed, 22 May 2024 18:58:29 +0900 Subject: [PATCH 019/304] Update `RelativeDistanceCondition::distance` to static member function Signed-off-by: yamacir-kit --- .../syntax/relative_distance_condition.hpp | 36 +++++----- .../syntax/relative_distance_condition.cpp | 72 ++++++++++--------- 2 files changed, 55 insertions(+), 53 deletions(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_distance_condition.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_distance_condition.hpp index 39926681b26..846eca5f40b 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_distance_condition.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_distance_condition.hpp @@ -90,8 +90,6 @@ struct RelativeDistanceCondition : private Scope, private SimulatorCore::Conditi std::vector results; // for description - const bool consider_z; - explicit RelativeDistanceCondition(const pugi::xml_node &, Scope &, const TriggeringEntities &); auto description() const -> String; @@ -99,12 +97,14 @@ struct RelativeDistanceCondition : private Scope, private SimulatorCore::Conditi template < CoordinateSystem::value_type, RelativeDistanceType::value_type, RoutingAlgorithm::value_type, Boolean::value_type> - auto distance(const EntityRef &) -> double + static auto distance(const EntityRef &, const EntityRef &) -> double { throw SyntaxError(__FILE__, ":", __LINE__); } - auto distance(const EntityRef &) -> double; + static auto distance( + const EntityRef &, const EntityRef &, const Entities &, CoordinateSystem, RelativeDistanceType, + RoutingAlgorithm, bool) -> double; auto evaluate() -> Object; }; @@ -113,20 +113,20 @@ struct RelativeDistanceCondition : private Scope, private SimulatorCore::Conditi // cspell: ignore euclidian // clang-format off -template <> auto RelativeDistanceCondition::distance(const EntityRef &) -> double; -template <> auto RelativeDistanceCondition::distance(const EntityRef &) -> double; -template <> auto RelativeDistanceCondition::distance(const EntityRef &) -> double; -template <> auto RelativeDistanceCondition::distance(const EntityRef &) -> double; -template <> auto RelativeDistanceCondition::distance(const EntityRef &) -> double; -template <> auto RelativeDistanceCondition::distance(const EntityRef &) -> double; -template <> auto RelativeDistanceCondition::distance(const EntityRef &) -> double; -template <> auto RelativeDistanceCondition::distance(const EntityRef &) -> double; -template <> auto RelativeDistanceCondition::distance(const EntityRef &) -> double; -template <> auto RelativeDistanceCondition::distance(const EntityRef &) -> double; -template <> auto RelativeDistanceCondition::distance(const EntityRef &) -> double; -template <> auto RelativeDistanceCondition::distance(const EntityRef &) -> double; -template <> auto RelativeDistanceCondition::distance(const EntityRef &) -> double; -template <> auto RelativeDistanceCondition::distance(const EntityRef &) -> double; +template <> auto RelativeDistanceCondition::distance(const EntityRef &, const EntityRef &) -> double; +template <> auto RelativeDistanceCondition::distance(const EntityRef &, const EntityRef &) -> double; +template <> auto RelativeDistanceCondition::distance(const EntityRef &, const EntityRef &) -> double; +template <> auto RelativeDistanceCondition::distance(const EntityRef &, const EntityRef &) -> double; +template <> auto RelativeDistanceCondition::distance(const EntityRef &, const EntityRef &) -> double; +template <> auto RelativeDistanceCondition::distance(const EntityRef &, const EntityRef &) -> double; +template <> auto RelativeDistanceCondition::distance(const EntityRef &, const EntityRef &) -> double; +template <> auto RelativeDistanceCondition::distance(const EntityRef &, const EntityRef &) -> double; +template <> auto RelativeDistanceCondition::distance(const EntityRef &, const EntityRef &) -> double; +template <> auto RelativeDistanceCondition::distance(const EntityRef &, const EntityRef &) -> double; +template <> auto RelativeDistanceCondition::distance(const EntityRef &, const EntityRef &) -> double; +template <> auto RelativeDistanceCondition::distance(const EntityRef &, const EntityRef &) -> double; +template <> auto RelativeDistanceCondition::distance(const EntityRef &, const EntityRef &) -> double; +template <> auto RelativeDistanceCondition::distance(const EntityRef &, const EntityRef &) -> double; // clang-format on } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/relative_distance_condition.cpp b/openscenario/openscenario_interpreter/src/syntax/relative_distance_condition.cpp index 8fd12515497..8740ef9761c 100644 --- a/openscenario/openscenario_interpreter/src/syntax/relative_distance_condition.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/relative_distance_condition.cpp @@ -39,12 +39,7 @@ RelativeDistanceCondition::RelativeDistanceCondition( rule(readAttribute("rule", node, scope)), value(readAttribute("value", node, scope)), triggering_entities(triggering_entities), - results(triggering_entities.entity_refs.size(), Double::nan()), - consider_z([]() { - rclcpp::Node node{"get_parameter", "simulation"}; - node.declare_parameter("consider_pose_by_road_slope", false); - return node.get_parameter("consider_pose_by_road_slope").as_bool(); - }()) + results(triggering_entities.entity_refs.size(), Double::nan()) { std::set supported = { RoutingAlgorithm::value_type::shortest, RoutingAlgorithm::value_type::undefined}; @@ -71,7 +66,7 @@ auto RelativeDistanceCondition::description() const -> String template <> auto RelativeDistanceCondition::distance< CoordinateSystem::entity, RelativeDistanceType::longitudinal, RoutingAlgorithm::undefined, false>( - const EntityRef & triggering_entity) -> double + const EntityRef & triggering_entity, const EntityRef & entity_ref) -> double { return std::abs(makeNativeRelativeWorldPosition(triggering_entity, entity_ref).position.x); } @@ -79,7 +74,7 @@ auto RelativeDistanceCondition::distance< template <> auto RelativeDistanceCondition::distance< CoordinateSystem::entity, RelativeDistanceType::longitudinal, RoutingAlgorithm::undefined, true>( - const EntityRef & triggering_entity) -> double + const EntityRef & triggering_entity, const EntityRef & entity_ref) -> double { /** @note This implementation differs from the OpenSCENARIO standard. See the @@ -92,7 +87,7 @@ auto RelativeDistanceCondition::distance< template <> auto RelativeDistanceCondition::distance< CoordinateSystem::entity, RelativeDistanceType::lateral, RoutingAlgorithm::undefined, false>( - const EntityRef & triggering_entity) -> double + const EntityRef & triggering_entity, const EntityRef & entity_ref) -> double { return std::abs(makeNativeRelativeWorldPosition(triggering_entity, entity_ref).position.y); } @@ -100,7 +95,7 @@ auto RelativeDistanceCondition::distance< template <> auto RelativeDistanceCondition::distance< CoordinateSystem::entity, RelativeDistanceType::lateral, RoutingAlgorithm::undefined, true>( - const EntityRef & triggering_entity) -> double + const EntityRef & triggering_entity, const EntityRef & entity_ref) -> double { /** @note This implementation differs from the OpenSCENARIO standard. See the @@ -111,38 +106,40 @@ auto RelativeDistanceCondition::distance< } // @todo: after checking all the scenario work well with consider_z = true, remove this function and use std::hypot(x, y, z) -auto hypot(double x, double y, double z, bool consider_z) +auto hypot(double x, double y, double z) { + static auto consider_z = []() { + auto node = rclcpp::Node("get_parameter", "simulation"); + node.declare_parameter("consider_pose_by_road_slope", false); + return node.get_parameter("consider_pose_by_road_slope").as_bool(); + }(); + return consider_z ? std::hypot(x, y, z) : std::hypot(x, y); } template <> auto RelativeDistanceCondition::distance< CoordinateSystem::entity, RelativeDistanceType::euclidianDistance, RoutingAlgorithm::undefined, - true>(const EntityRef & triggering_entity) -> double + true>(const EntityRef & triggering_entity, const EntityRef & entity_ref) -> double { - return hypot( - makeNativeBoundingBoxRelativeWorldPosition(triggering_entity, entity_ref).position.x, - makeNativeBoundingBoxRelativeWorldPosition(triggering_entity, entity_ref).position.y, - makeNativeBoundingBoxRelativeWorldPosition(triggering_entity, entity_ref).position.z, - consider_z); + const auto relative_world = + makeNativeBoundingBoxRelativeWorldPosition(triggering_entity, entity_ref); + return hypot(relative_world.position.x, relative_world.position.y, relative_world.position.z); } template <> auto RelativeDistanceCondition::distance< CoordinateSystem::entity, RelativeDistanceType::euclidianDistance, RoutingAlgorithm::undefined, - false>(const EntityRef & triggering_entity) -> double + false>(const EntityRef & triggering_entity, const EntityRef & entity_ref) -> double { - return hypot( - makeNativeRelativeWorldPosition(triggering_entity, entity_ref).position.x, - makeNativeRelativeWorldPosition(triggering_entity, entity_ref).position.y, - makeNativeRelativeWorldPosition(triggering_entity, entity_ref).position.z, consider_z); + const auto relative_world = makeNativeRelativeWorldPosition(triggering_entity, entity_ref); + return hypot(relative_world.position.x, relative_world.position.y, relative_world.position.z); } template <> auto RelativeDistanceCondition::distance< CoordinateSystem::lane, RelativeDistanceType::lateral, RoutingAlgorithm::undefined, false>( - const EntityRef & triggering_entity) -> double + const EntityRef & triggering_entity, const EntityRef & entity_ref) -> double { /* For historical reasons, signed distances are returned when @@ -164,7 +161,7 @@ auto RelativeDistanceCondition::distance< template <> auto RelativeDistanceCondition::distance< CoordinateSystem::lane, RelativeDistanceType::lateral, RoutingAlgorithm::undefined, true>( - const EntityRef & triggering_entity) -> double + const EntityRef & triggering_entity, const EntityRef & entity_ref) -> double { /* For historical reasons, signed distances are returned when @@ -186,7 +183,7 @@ auto RelativeDistanceCondition::distance< template <> auto RelativeDistanceCondition::distance< CoordinateSystem::lane, RelativeDistanceType::longitudinal, RoutingAlgorithm::undefined, false>( - const EntityRef & triggering_entity) -> double + const EntityRef & triggering_entity, const EntityRef & entity_ref) -> double { /* For historical reasons, signed distances are returned when @@ -208,7 +205,7 @@ auto RelativeDistanceCondition::distance< template <> auto RelativeDistanceCondition::distance< CoordinateSystem::lane, RelativeDistanceType::longitudinal, RoutingAlgorithm::undefined, true>( - const EntityRef & triggering_entity) -> double + const EntityRef & triggering_entity, const EntityRef & entity_ref) -> double { /* For historical reasons, signed distances are returned when @@ -230,7 +227,7 @@ auto RelativeDistanceCondition::distance< template <> auto RelativeDistanceCondition::distance< CoordinateSystem::lane, RelativeDistanceType::lateral, RoutingAlgorithm::shortest, true>( - const EntityRef & triggering_entity) -> double + const EntityRef & triggering_entity, const EntityRef & entity_ref) -> double { return std::abs(static_cast( makeNativeBoundingBoxRelativeLanePosition( @@ -241,7 +238,7 @@ auto RelativeDistanceCondition::distance< template <> auto RelativeDistanceCondition::distance< CoordinateSystem::lane, RelativeDistanceType::lateral, RoutingAlgorithm::shortest, false>( - const EntityRef & triggering_entity) -> double + const EntityRef & triggering_entity, const EntityRef & entity_ref) -> double { return std::abs( static_cast( @@ -252,7 +249,7 @@ auto RelativeDistanceCondition::distance< template <> auto RelativeDistanceCondition::distance< CoordinateSystem::lane, RelativeDistanceType::longitudinal, RoutingAlgorithm::shortest, true>( - const EntityRef & triggering_entity) -> double + const EntityRef & triggering_entity, const EntityRef & entity_ref) -> double { return std::abs(static_cast( makeNativeBoundingBoxRelativeLanePosition( @@ -263,7 +260,7 @@ auto RelativeDistanceCondition::distance< template <> auto RelativeDistanceCondition::distance< CoordinateSystem::lane, RelativeDistanceType::longitudinal, RoutingAlgorithm::shortest, false>( - const EntityRef & triggering_entity) -> double + const EntityRef & triggering_entity, const EntityRef & entity_ref) -> double { return std::abs( static_cast( @@ -328,13 +325,16 @@ auto RelativeDistanceCondition::distance< #define SWITCH_FREESPACE(FUNCTION, ...) \ return freespace ? FUNCTION(__VA_ARGS__, true) : FUNCTION(__VA_ARGS__, false) -#define DISTANCE(...) distance<__VA_ARGS__>(triggering_entity) +#define DISTANCE(...) distance<__VA_ARGS__>(triggering_entity, entity_ref) -auto RelativeDistanceCondition::distance(const EntityRef & triggering_entity) -> double +auto RelativeDistanceCondition::distance( + const EntityRef & triggering_entity, const EntityRef & entity_ref, const Entities & entities, + CoordinateSystem coordinate_system, RelativeDistanceType relative_distance_type, + RoutingAlgorithm routing_algorithm, bool freespace) -> double { if ( - global().entities->at(triggering_entity).as().is_added and - global().entities->at(entity_ref).as().is_added) { + entities.at(triggering_entity).as().is_added and + entities.at(entity_ref).as().is_added) { SWITCH_COORDINATE_SYSTEM( SWITCH_RELATIVE_DISTANCE_TYPE, SWITCH_ROUTING_ALGORITHM, SWITCH_FREESPACE, DISTANCE); } else { @@ -347,7 +347,9 @@ auto RelativeDistanceCondition::evaluate() -> Object results.clear(); return asBoolean(triggering_entities.apply([&](const auto & triggering_entity) { - results.push_back(distance(triggering_entity)); + results.push_back(distance( + triggering_entity, entity_ref, *global().entities, coordinate_system, relative_distance_type, + routing_algorithm, freespace)); return rule(static_cast(results.back()), value); })); } From a8c4ac20cddf20a173f26893c6dcdb47bf88eff5 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Wed, 17 Jul 2024 11:44:48 +0900 Subject: [PATCH 020/304] refactor: import RelativeDistanceCondition updates from feature/time-to-collision-condition branch Co-authored-by: yamacir-kit --- .../syntax/relative_distance_condition.hpp | 6 +++--- .../src/syntax/relative_distance_condition.cpp | 14 ++++++-------- 2 files changed, 9 insertions(+), 11 deletions(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_distance_condition.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_distance_condition.hpp index 846eca5f40b..8dea6e12dad 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_distance_condition.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_distance_condition.hpp @@ -102,9 +102,9 @@ struct RelativeDistanceCondition : private Scope, private SimulatorCore::Conditi throw SyntaxError(__FILE__, ":", __LINE__); } - static auto distance( - const EntityRef &, const EntityRef &, const Entities &, CoordinateSystem, RelativeDistanceType, - RoutingAlgorithm, bool) -> double; + static auto evaluate( + const Entities *, const EntityRef &, const EntityRef &, CoordinateSystem, RelativeDistanceType, + RoutingAlgorithm, Boolean) -> double; auto evaluate() -> Object; }; diff --git a/openscenario/openscenario_interpreter/src/syntax/relative_distance_condition.cpp b/openscenario/openscenario_interpreter/src/syntax/relative_distance_condition.cpp index 8740ef9761c..7ba516ba580 100644 --- a/openscenario/openscenario_interpreter/src/syntax/relative_distance_condition.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/relative_distance_condition.cpp @@ -327,14 +327,12 @@ auto RelativeDistanceCondition::distance< #define DISTANCE(...) distance<__VA_ARGS__>(triggering_entity, entity_ref) -auto RelativeDistanceCondition::distance( - const EntityRef & triggering_entity, const EntityRef & entity_ref, const Entities & entities, +auto RelativeDistanceCondition::evaluate( + const Entities * entities, const EntityRef & triggering_entity, const EntityRef & entity_ref, CoordinateSystem coordinate_system, RelativeDistanceType relative_distance_type, - RoutingAlgorithm routing_algorithm, bool freespace) -> double + RoutingAlgorithm routing_algorithm, Boolean freespace) -> double { - if ( - entities.at(triggering_entity).as().is_added and - entities.at(entity_ref).as().is_added) { + if (entities->isAdded(triggering_entity) and entities->isAdded(entity_ref)) { SWITCH_COORDINATE_SYSTEM( SWITCH_RELATIVE_DISTANCE_TYPE, SWITCH_ROUTING_ALGORITHM, SWITCH_FREESPACE, DISTANCE); } else { @@ -347,8 +345,8 @@ auto RelativeDistanceCondition::evaluate() -> Object results.clear(); return asBoolean(triggering_entities.apply([&](const auto & triggering_entity) { - results.push_back(distance( - triggering_entity, entity_ref, *global().entities, coordinate_system, relative_distance_type, + results.push_back(evaluate( + global().entities, triggering_entity, entity_ref, coordinate_system, relative_distance_type, routing_algorithm, freespace)); return rule(static_cast(results.back()), value); })); From 5cb4465c106002a392dacde80f95cfc2b748267c Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Mon, 22 Jul 2024 15:58:33 +0900 Subject: [PATCH 021/304] Implement HdMapUtils::countLaneChangesAlongRoute --- .../hdmap_utils/hdmap_utils.hpp | 2 ++ .../src/hdmap_utils/hdmap_utils.cpp | 25 +++++++++++++++++++ .../test/src/hdmap_utils/test_hdmap_utils.cpp | 15 +++++++++++ 3 files changed, 42 insertions(+) diff --git a/simulation/traffic_simulator/include/traffic_simulator/hdmap_utils/hdmap_utils.hpp b/simulation/traffic_simulator/include/traffic_simulator/hdmap_utils/hdmap_utils.hpp index 92a7e25c518..ef8f0cb5260 100644 --- a/simulation/traffic_simulator/include/traffic_simulator/hdmap_utils/hdmap_utils.hpp +++ b/simulation/traffic_simulator/include/traffic_simulator/hdmap_utils/hdmap_utils.hpp @@ -78,6 +78,8 @@ class HdMapUtils const lanelet::Id, const double s, const lanelet::Ids &, const double forward_distance = 20) const -> std::vector; + auto countLaneChangesAlongRoute(const lanelet::Ids &) const -> std::pair; + auto filterLaneletIds(const lanelet::Ids &, const char subtype[]) const -> lanelet::Ids; auto generateMarker() const -> visualization_msgs::msg::MarkerArray; diff --git a/simulation/traffic_simulator/src/hdmap_utils/hdmap_utils.cpp b/simulation/traffic_simulator/src/hdmap_utils/hdmap_utils.cpp index c6e24e9d1ec..8ef7a545d78 100644 --- a/simulation/traffic_simulator/src/hdmap_utils/hdmap_utils.cpp +++ b/simulation/traffic_simulator/src/hdmap_utils/hdmap_utils.cpp @@ -214,6 +214,31 @@ auto HdMapUtils::canonicalizeLaneletPose( return {canonicalized, std::nullopt}; } +auto HdMapUtils::countLaneChangesAlongRoute(const lanelet::Ids & route_lanelets) const -> std::pair +{ + std::pair lane_changes{0, 0}; + for (size_t i = 1; i < route_lanelets.size(); ++i) { + const auto& previous = route_lanelets[i-1]; + const auto& current = route_lanelets[i]; + + if (auto followings = getNextLaneletIds(previous); + std::find_if(followings.begin(), + followings.end(), + [¤t](const auto& lanelet) { return lanelet == current; }) == followings.end()) { + traffic_simulator_msgs::msg::EntityType type; + type.type = traffic_simulator_msgs::msg::EntityType::VEHICLE; + if (auto lefts = getLeftLaneletIds(previous, type); + std::find_if(lefts.begin(), lefts.end(), [¤t](const auto& lanelet) { return lanelet == current; }) != lefts.end()) { + lane_changes.first++; + } else if (auto rights = getRightLaneletIds(previous, type); + std::find_if(rights.begin(), rights.end(), [¤t](const auto& lanelet) { return lanelet == current; }) != rights.end()) { + lane_changes.second++; + } + } + } + return lane_changes; +} + auto HdMapUtils::getLaneletIds() const -> lanelet::Ids { lanelet::Ids ids; diff --git a/simulation/traffic_simulator/test/src/hdmap_utils/test_hdmap_utils.cpp b/simulation/traffic_simulator/test/src/hdmap_utils/test_hdmap_utils.cpp index 1ac7370e66e..cf9f2f53fc4 100644 --- a/simulation/traffic_simulator/test/src/hdmap_utils/test_hdmap_utils.cpp +++ b/simulation/traffic_simulator/test/src/hdmap_utils/test_hdmap_utils.cpp @@ -447,6 +447,21 @@ TEST_F(HdMapUtilsTest_StandardMap, CanonicalizeAll) EXPECT_EQ(canonicalized_lanelet_poses[0].s, non_canonicalized_lanelet_s); } +/** + * @note Testcase for countLaneChangesAlongRoute() function + */ +TEST_F(HdMapUtilsTest_FourTrackHighwayMap, CountLaneChangesAlongRoute) +{ + EXPECT_EQ(hdmap_utils.countLaneChangesAlongRoute(hdmap_utils.getRoute(3002176, 3002175, true)), std::make_pair(1,0)); + EXPECT_EQ(hdmap_utils.countLaneChangesAlongRoute(hdmap_utils.getRoute(3002176, 3002182, true)), std::make_pair(1,0)); + EXPECT_EQ(hdmap_utils.countLaneChangesAlongRoute(hdmap_utils.getRoute(3002176, 199, true)), std::make_pair(1,0)); + EXPECT_EQ(hdmap_utils.countLaneChangesAlongRoute(hdmap_utils.getRoute(3002176, 3002176, true)), std::make_pair(0,0)); + EXPECT_EQ(hdmap_utils.countLaneChangesAlongRoute(hdmap_utils.getRoute(3002176, 200, true)), std::make_pair(0,0)); + EXPECT_EQ(hdmap_utils.countLaneChangesAlongRoute(hdmap_utils.getRoute(3002176, 201, true)), std::make_pair(0,1)); + EXPECT_EQ(hdmap_utils.countLaneChangesAlongRoute(hdmap_utils.getRoute(3002176, 202, true)), std::make_pair(0,2)); + EXPECT_EQ(hdmap_utils.countLaneChangesAlongRoute(hdmap_utils.getRoute(3002176, 206, true)), std::make_pair(0,2)); +} + /** * @note Test basic functionality. * Test filtering correctness with some lanelet ids and a valid subtype name. From b27934db0020865289f494c4c346ee3990b78245 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Mon, 22 Jul 2024 16:49:36 +0900 Subject: [PATCH 022/304] Implement HdMapUtils::countLaneChanges --- .../hdmap_utils/hdmap_utils.hpp | 5 ++- .../traffic_simulator/utils/distance.hpp | 6 ++++ .../src/hdmap_utils/hdmap_utils.cpp | 32 +++++++++++++------ .../traffic_simulator/src/utils/distance.cpp | 9 ++++++ 4 files changed, 41 insertions(+), 11 deletions(-) diff --git a/simulation/traffic_simulator/include/traffic_simulator/hdmap_utils/hdmap_utils.hpp b/simulation/traffic_simulator/include/traffic_simulator/hdmap_utils/hdmap_utils.hpp index ef8f0cb5260..59f1c713991 100644 --- a/simulation/traffic_simulator/include/traffic_simulator/hdmap_utils/hdmap_utils.hpp +++ b/simulation/traffic_simulator/include/traffic_simulator/hdmap_utils/hdmap_utils.hpp @@ -78,7 +78,10 @@ class HdMapUtils const lanelet::Id, const double s, const lanelet::Ids &, const double forward_distance = 20) const -> std::vector; - auto countLaneChangesAlongRoute(const lanelet::Ids &) const -> std::pair; + auto countLaneChanges( + const traffic_simulator_msgs::msg::LaneletPose & from, + const traffic_simulator_msgs::msg::LaneletPose & to, bool allow_lane_change) const + -> std::optional>; auto filterLaneletIds(const lanelet::Ids &, const char subtype[]) const -> lanelet::Ids; diff --git a/simulation/traffic_simulator/include/traffic_simulator/utils/distance.hpp b/simulation/traffic_simulator/include/traffic_simulator/utils/distance.hpp index 3e354c32b80..f269ecdc0f9 100644 --- a/simulation/traffic_simulator/include/traffic_simulator/utils/distance.hpp +++ b/simulation/traffic_simulator/include/traffic_simulator/utils/distance.hpp @@ -33,6 +33,12 @@ auto lateralDistance( double matching_distance, bool allow_lane_change, const std::shared_ptr & hdmap_utils_ptr) -> std::optional; +// Lateral (unit: lanes) +auto countLaneChanges( + const CanonicalizedLaneletPose & from, const CanonicalizedLaneletPose & to, + bool allow_lane_change, const std::shared_ptr & hdmap_utils_ptr) + -> std::optional>; + // Longitudinal auto longitudinalDistance( const CanonicalizedLaneletPose & from, const CanonicalizedLaneletPose & to, diff --git a/simulation/traffic_simulator/src/hdmap_utils/hdmap_utils.cpp b/simulation/traffic_simulator/src/hdmap_utils/hdmap_utils.cpp index 8ef7a545d78..48fe67207da 100644 --- a/simulation/traffic_simulator/src/hdmap_utils/hdmap_utils.cpp +++ b/simulation/traffic_simulator/src/hdmap_utils/hdmap_utils.cpp @@ -214,29 +214,41 @@ auto HdMapUtils::canonicalizeLaneletPose( return {canonicalized, std::nullopt}; } -auto HdMapUtils::countLaneChangesAlongRoute(const lanelet::Ids & route_lanelets) const -> std::pair +auto HdMapUtils::countLaneChanges( + const traffic_simulator_msgs::msg::LaneletPose & from, + const traffic_simulator_msgs::msg::LaneletPose & to, bool allow_lane_change) const + -> std::optional> { - std::pair lane_changes{0, 0}; - for (size_t i = 1; i < route_lanelets.size(); ++i) { - const auto& previous = route_lanelets[i-1]; - const auto& current = route_lanelets[i]; + const auto route = getRoute(from.lanelet_id, to.lanelet_id, allow_lane_change); + if (route.empty()) { + return std::nullopt; + } else { + std::pair lane_changes{0, 0}; + for (size_t i = 1; i < route.size(); ++i) { + const auto & previous = route[i - 1]; + const auto & current = route[i]; if (auto followings = getNextLaneletIds(previous); - std::find_if(followings.begin(), - followings.end(), - [¤t](const auto& lanelet) { return lanelet == current; }) == followings.end()) { + std::find_if(followings.begin(), followings.end(), [¤t](const auto & lanelet) { + return lanelet == current; + }) == followings.end()) { traffic_simulator_msgs::msg::EntityType type; type.type = traffic_simulator_msgs::msg::EntityType::VEHICLE; if (auto lefts = getLeftLaneletIds(previous, type); - std::find_if(lefts.begin(), lefts.end(), [¤t](const auto& lanelet) { return lanelet == current; }) != lefts.end()) { + std::find_if(lefts.begin(), lefts.end(), [¤t](const auto & lanelet) { + return lanelet == current; + }) != lefts.end()) { lane_changes.first++; } else if (auto rights = getRightLaneletIds(previous, type); - std::find_if(rights.begin(), rights.end(), [¤t](const auto& lanelet) { return lanelet == current; }) != rights.end()) { + std::find_if(rights.begin(), rights.end(), [¤t](const auto & lanelet) { + return lanelet == current; + }) != rights.end()) { lane_changes.second++; } } } return lane_changes; + } } auto HdMapUtils::getLaneletIds() const -> lanelet::Ids diff --git a/simulation/traffic_simulator/src/utils/distance.cpp b/simulation/traffic_simulator/src/utils/distance.cpp index 307cb7cdcf5..d83391866a6 100644 --- a/simulation/traffic_simulator/src/utils/distance.cpp +++ b/simulation/traffic_simulator/src/utils/distance.cpp @@ -45,6 +45,15 @@ auto lateralDistance( } } +auto countLaneChanges( + const CanonicalizedLaneletPose & from, const CanonicalizedLaneletPose & to, + bool allow_lane_change, const std::shared_ptr & hdmap_utils_ptr) + -> std::optional> +{ + return hdmap_utils_ptr->countLaneChanges( + static_cast(from), static_cast(to), allow_lane_change); +} + auto longitudinalDistance( const CanonicalizedLaneletPose & from, const CanonicalizedLaneletPose & to, bool include_adjacent_lanelet, bool include_opposite_direction, bool allow_lane_change, From a9ae5733c62306bc98be64a4ca42b245e1874dd8 Mon Sep 17 00:00:00 2001 From: SzymonParapura Date: Mon, 22 Jul 2024 14:20:27 +0200 Subject: [PATCH 023/304] Fix an issue with an invalid namespace imu_link --- .../src/sensor_simulation/imu/imu_sensor.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/simulation/simple_sensor_simulator/src/sensor_simulation/imu/imu_sensor.cpp b/simulation/simple_sensor_simulator/src/sensor_simulation/imu/imu_sensor.cpp index db5e2553cd9..a57cbebb7df 100644 --- a/simulation/simple_sensor_simulator/src/sensor_simulation/imu/imu_sensor.cpp +++ b/simulation/simple_sensor_simulator/src/sensor_simulation/imu/imu_sensor.cpp @@ -35,7 +35,7 @@ auto ImuSensor::generateMessage( auto imu_msg = sensor_msgs::msg::Imu(); imu_msg.header.stamp = current_ros_time; - imu_msg.header.frame_id = "imu_link"; + imu_msg.header.frame_id = "imu_link"; //tamagawa/ auto orientation_rpy = math::geometry::convertQuaternionToEulerAngle(status.pose.orientation); auto twist = status.action_status.twist; From a1878f3c09607b809df488e77af55cbce3b85460 Mon Sep 17 00:00:00 2001 From: SzymonParapura Date: Mon, 22 Jul 2024 14:54:49 +0200 Subject: [PATCH 024/304] Fix an issue with an invalid namespace imu_link --- .../src/sensor_simulation/imu/imu_sensor.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/simulation/simple_sensor_simulator/src/sensor_simulation/imu/imu_sensor.cpp b/simulation/simple_sensor_simulator/src/sensor_simulation/imu/imu_sensor.cpp index a57cbebb7df..25967c51f7e 100644 --- a/simulation/simple_sensor_simulator/src/sensor_simulation/imu/imu_sensor.cpp +++ b/simulation/simple_sensor_simulator/src/sensor_simulation/imu/imu_sensor.cpp @@ -35,7 +35,7 @@ auto ImuSensor::generateMessage( auto imu_msg = sensor_msgs::msg::Imu(); imu_msg.header.stamp = current_ros_time; - imu_msg.header.frame_id = "imu_link"; //tamagawa/ + imu_msg.header.frame_id = "tamagawa/imu_link"; auto orientation_rpy = math::geometry::convertQuaternionToEulerAngle(status.pose.orientation); auto twist = status.action_status.twist; From f3d816bda70c4c31015a9a989ae9f56c9c4cc0a2 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Tue, 23 Jul 2024 15:48:38 +0900 Subject: [PATCH 025/304] fix tests for HdMapUtils::countLaneChanges --- .../test/src/hdmap_utils/test_hdmap_utils.cpp | 43 +++++++++++++++---- 1 file changed, 34 insertions(+), 9 deletions(-) diff --git a/simulation/traffic_simulator/test/src/hdmap_utils/test_hdmap_utils.cpp b/simulation/traffic_simulator/test/src/hdmap_utils/test_hdmap_utils.cpp index cf9f2f53fc4..31c18a22a62 100644 --- a/simulation/traffic_simulator/test/src/hdmap_utils/test_hdmap_utils.cpp +++ b/simulation/traffic_simulator/test/src/hdmap_utils/test_hdmap_utils.cpp @@ -448,18 +448,43 @@ TEST_F(HdMapUtilsTest_StandardMap, CanonicalizeAll) } /** - * @note Testcase for countLaneChangesAlongRoute() function + * @note Testcase for countLaneChanges() function */ TEST_F(HdMapUtilsTest_FourTrackHighwayMap, CountLaneChangesAlongRoute) { - EXPECT_EQ(hdmap_utils.countLaneChangesAlongRoute(hdmap_utils.getRoute(3002176, 3002175, true)), std::make_pair(1,0)); - EXPECT_EQ(hdmap_utils.countLaneChangesAlongRoute(hdmap_utils.getRoute(3002176, 3002182, true)), std::make_pair(1,0)); - EXPECT_EQ(hdmap_utils.countLaneChangesAlongRoute(hdmap_utils.getRoute(3002176, 199, true)), std::make_pair(1,0)); - EXPECT_EQ(hdmap_utils.countLaneChangesAlongRoute(hdmap_utils.getRoute(3002176, 3002176, true)), std::make_pair(0,0)); - EXPECT_EQ(hdmap_utils.countLaneChangesAlongRoute(hdmap_utils.getRoute(3002176, 200, true)), std::make_pair(0,0)); - EXPECT_EQ(hdmap_utils.countLaneChangesAlongRoute(hdmap_utils.getRoute(3002176, 201, true)), std::make_pair(0,1)); - EXPECT_EQ(hdmap_utils.countLaneChangesAlongRoute(hdmap_utils.getRoute(3002176, 202, true)), std::make_pair(0,2)); - EXPECT_EQ(hdmap_utils.countLaneChangesAlongRoute(hdmap_utils.getRoute(3002176, 206, true)), std::make_pair(0,2)); + using traffic_simulator::helper::constructLaneletPose; + EXPECT_EQ( + hdmap_utils.countLaneChanges( + constructLaneletPose(3002176, 0), constructLaneletPose(3002175, 0), true), + std::make_pair(1, 0)); + EXPECT_EQ( + hdmap_utils.countLaneChanges( + constructLaneletPose(3002176, 0), constructLaneletPose(3002182, 0), true), + std::make_pair(1, 0)); + EXPECT_EQ( + hdmap_utils.countLaneChanges( + constructLaneletPose(3002176, 0), constructLaneletPose(199, 0), true), + std::make_pair(1, 0)); + EXPECT_EQ( + hdmap_utils.countLaneChanges( + constructLaneletPose(3002176, 0), constructLaneletPose(3002176, 0), true), + std::make_pair(0, 0)); + EXPECT_EQ( + hdmap_utils.countLaneChanges( + constructLaneletPose(3002176, 0), constructLaneletPose(200, 0), true), + std::make_pair(0, 0)); + EXPECT_EQ( + hdmap_utils.countLaneChanges( + constructLaneletPose(3002176, 0), constructLaneletPose(201, 0), true), + std::make_pair(0, 1)); + EXPECT_EQ( + hdmap_utils.countLaneChanges( + constructLaneletPose(3002176, 0), constructLaneletPose(202, 0), true), + std::make_pair(0, 2)); + EXPECT_EQ( + hdmap_utils.countLaneChanges( + constructLaneletPose(3002176, 0), constructLaneletPose(206, 0), true), + std::make_pair(0, 2)); } /** From 324d7069a8ed4e0ecf06356aa9180b35ac6a5ac3 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Tue, 23 Jul 2024 15:50:02 +0900 Subject: [PATCH 026/304] Implement SimulatorCore::evaluateLateralRelativeLanes function --- .../simulator_core.hpp | 21 +++++++++++++++++++ 1 file changed, 21 insertions(+) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/simulator_core.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/simulator_core.hpp index 2e7e89f6558..b3fcab97860 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/simulator_core.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/simulator_core.hpp @@ -256,6 +256,27 @@ class SimulatorCore } return traffic_simulator::pose::quietNaNPose(); } + + static auto evaluateLateralRelativeLanes( + const std::string & from_entity_name, const std::string & to_entity_name, + const RoutingAlgorithm::value_type routing_algorithm = RoutingAlgorithm::undefined) + -> std::optional + { + if (const auto from_entity = core->getEntity(from_entity_name)) { + if (const auto to_entity = core->getEntity(to_entity_name)) { + const bool allow_lane_change = + (routing_algorithm == RoutingAlgorithm::value_type::shortest); + if ( + auto lane_changes = traffic_simulator::distance::countLaneChanges( + from_entity->getCanonicalizedLaneletPose().value(), + to_entity->getCanonicalizedLaneletPose().value(), allow_lane_change, + core->getHdmapUtils())) { + return lane_changes.value().first - lane_changes.value().second; + } + } + } + return std::nullopt; + } }; class ActionApplication // OpenSCENARIO 1.1.1 Section 3.1.5 From ab24644b369223117a212590e5e3c76a48997333 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Tue, 23 Jul 2024 15:52:35 +0900 Subject: [PATCH 027/304] Implement RelativeClearanceCondition::getRelativeLanePosition function --- .../syntax/relative_clearance_condition.hpp | 4 ++++ .../src/syntax/relative_clearance_condition.cpp | 13 +++++++++++++ 2 files changed, 17 insertions(+) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_clearance_condition.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_clearance_condition.hpp index 1433fb11306..e0db2617c1f 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_clearance_condition.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_clearance_condition.hpp @@ -79,6 +79,10 @@ struct RelativeClearanceCondition : private Scope, private SimulatorCore::Condit auto description() const -> String; auto evaluate() -> Object; + + [[nodiscard]] auto getRelativeLanePosition( + const EntityRef & triggering_entity, const EntityRef & entity, bool use_bounding_box) const + -> traffic_simulator::LaneletPose; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp b/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp index 32ce5986d23..e4701cb8fa5 100644 --- a/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp @@ -54,5 +54,18 @@ auto RelativeClearanceCondition::evaluate() -> Object // TODO(HansRobo): implement return unspecified; } + +auto RelativeClearanceCondition::getRelativeLanePosition( + const EntityRef & triggering_entity, const EntityRef & entity, bool use_bounding_box) const + -> traffic_simulator::LaneletPose +{ + if (use_bounding_box) { + return static_cast(makeNativeBoundingBoxRelativeLanePosition( + triggering_entity, entity, RoutingAlgorithm::shortest)); + } else { + return static_cast( + makeNativeRelativeLanePosition(triggering_entity, entity, RoutingAlgorithm::shortest)); + } +} } // namespace syntax } // namespace openscenario_interpreter From c61986aeca58c9c17a6b468f707b300ab18d20e8 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Tue, 23 Jul 2024 15:53:30 +0900 Subject: [PATCH 028/304] Add temporary implementation of RelativeClearanceCondition::evaluate function --- .../syntax/relative_clearance_condition.cpp | 30 +++++++++++++++++-- 1 file changed, 28 insertions(+), 2 deletions(-) diff --git a/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp b/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp index e4701cb8fa5..0065fe40cc4 100644 --- a/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp @@ -51,8 +51,34 @@ auto RelativeClearanceCondition::description() const -> String auto RelativeClearanceCondition::evaluate() -> Object { - // TODO(HansRobo): implement - return unspecified; + return asBoolean(triggering_entities.apply([&](const auto & triggering_entity) { + for (const auto & entity : entity_refs) { + auto is_in_lateral_range = [&]() { + if (relative_lane_range.empty()) { + return true; + } else { + auto relative_lateral_lane = + evaluateLateralRelativeLanes(triggering_entity, entity, RoutingAlgorithm::shortest); + return std::any_of( + relative_lane_range.begin(), relative_lane_range.end(), [&](const auto & range) { + return range.from <= relative_lateral_lane && range.to >= relative_lateral_lane; + }); + } + }; + + auto is_in_longitudinal_range = [&]() { + auto relative_lane_position = + getRelativeLanePosition(triggering_entity, entity, free_space); + if (relative_lane_position.s < 0) { + return std::abs(relative_lane_position.s) <= distance_backward; + } else { + return relative_lane_position.s <= distance_forward; + } + }; + + return is_in_lateral_range() && is_in_longitudinal_range(); + } + })); } auto RelativeClearanceCondition::getRelativeLanePosition( From 0a032632e9c447c5d4be3e46019ffb1741c1ca24 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Tue, 23 Jul 2024 15:57:33 +0900 Subject: [PATCH 029/304] Revert "Update `RelativeDistanceCondition::distance` to static member function" This reverts commit 86f489f0 --- .../syntax/relative_distance_condition.hpp | 36 +++++----- .../syntax/relative_distance_condition.cpp | 72 +++++++++---------- 2 files changed, 54 insertions(+), 54 deletions(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_distance_condition.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_distance_condition.hpp index 8dea6e12dad..39926681b26 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_distance_condition.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_distance_condition.hpp @@ -90,6 +90,8 @@ struct RelativeDistanceCondition : private Scope, private SimulatorCore::Conditi std::vector results; // for description + const bool consider_z; + explicit RelativeDistanceCondition(const pugi::xml_node &, Scope &, const TriggeringEntities &); auto description() const -> String; @@ -97,14 +99,12 @@ struct RelativeDistanceCondition : private Scope, private SimulatorCore::Conditi template < CoordinateSystem::value_type, RelativeDistanceType::value_type, RoutingAlgorithm::value_type, Boolean::value_type> - static auto distance(const EntityRef &, const EntityRef &) -> double + auto distance(const EntityRef &) -> double { throw SyntaxError(__FILE__, ":", __LINE__); } - static auto evaluate( - const Entities *, const EntityRef &, const EntityRef &, CoordinateSystem, RelativeDistanceType, - RoutingAlgorithm, Boolean) -> double; + auto distance(const EntityRef &) -> double; auto evaluate() -> Object; }; @@ -113,20 +113,20 @@ struct RelativeDistanceCondition : private Scope, private SimulatorCore::Conditi // cspell: ignore euclidian // clang-format off -template <> auto RelativeDistanceCondition::distance(const EntityRef &, const EntityRef &) -> double; -template <> auto RelativeDistanceCondition::distance(const EntityRef &, const EntityRef &) -> double; -template <> auto RelativeDistanceCondition::distance(const EntityRef &, const EntityRef &) -> double; -template <> auto RelativeDistanceCondition::distance(const EntityRef &, const EntityRef &) -> double; -template <> auto RelativeDistanceCondition::distance(const EntityRef &, const EntityRef &) -> double; -template <> auto RelativeDistanceCondition::distance(const EntityRef &, const EntityRef &) -> double; -template <> auto RelativeDistanceCondition::distance(const EntityRef &, const EntityRef &) -> double; -template <> auto RelativeDistanceCondition::distance(const EntityRef &, const EntityRef &) -> double; -template <> auto RelativeDistanceCondition::distance(const EntityRef &, const EntityRef &) -> double; -template <> auto RelativeDistanceCondition::distance(const EntityRef &, const EntityRef &) -> double; -template <> auto RelativeDistanceCondition::distance(const EntityRef &, const EntityRef &) -> double; -template <> auto RelativeDistanceCondition::distance(const EntityRef &, const EntityRef &) -> double; -template <> auto RelativeDistanceCondition::distance(const EntityRef &, const EntityRef &) -> double; -template <> auto RelativeDistanceCondition::distance(const EntityRef &, const EntityRef &) -> double; +template <> auto RelativeDistanceCondition::distance(const EntityRef &) -> double; +template <> auto RelativeDistanceCondition::distance(const EntityRef &) -> double; +template <> auto RelativeDistanceCondition::distance(const EntityRef &) -> double; +template <> auto RelativeDistanceCondition::distance(const EntityRef &) -> double; +template <> auto RelativeDistanceCondition::distance(const EntityRef &) -> double; +template <> auto RelativeDistanceCondition::distance(const EntityRef &) -> double; +template <> auto RelativeDistanceCondition::distance(const EntityRef &) -> double; +template <> auto RelativeDistanceCondition::distance(const EntityRef &) -> double; +template <> auto RelativeDistanceCondition::distance(const EntityRef &) -> double; +template <> auto RelativeDistanceCondition::distance(const EntityRef &) -> double; +template <> auto RelativeDistanceCondition::distance(const EntityRef &) -> double; +template <> auto RelativeDistanceCondition::distance(const EntityRef &) -> double; +template <> auto RelativeDistanceCondition::distance(const EntityRef &) -> double; +template <> auto RelativeDistanceCondition::distance(const EntityRef &) -> double; // clang-format on } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/relative_distance_condition.cpp b/openscenario/openscenario_interpreter/src/syntax/relative_distance_condition.cpp index 7ba516ba580..8fd12515497 100644 --- a/openscenario/openscenario_interpreter/src/syntax/relative_distance_condition.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/relative_distance_condition.cpp @@ -39,7 +39,12 @@ RelativeDistanceCondition::RelativeDistanceCondition( rule(readAttribute("rule", node, scope)), value(readAttribute("value", node, scope)), triggering_entities(triggering_entities), - results(triggering_entities.entity_refs.size(), Double::nan()) + results(triggering_entities.entity_refs.size(), Double::nan()), + consider_z([]() { + rclcpp::Node node{"get_parameter", "simulation"}; + node.declare_parameter("consider_pose_by_road_slope", false); + return node.get_parameter("consider_pose_by_road_slope").as_bool(); + }()) { std::set supported = { RoutingAlgorithm::value_type::shortest, RoutingAlgorithm::value_type::undefined}; @@ -66,7 +71,7 @@ auto RelativeDistanceCondition::description() const -> String template <> auto RelativeDistanceCondition::distance< CoordinateSystem::entity, RelativeDistanceType::longitudinal, RoutingAlgorithm::undefined, false>( - const EntityRef & triggering_entity, const EntityRef & entity_ref) -> double + const EntityRef & triggering_entity) -> double { return std::abs(makeNativeRelativeWorldPosition(triggering_entity, entity_ref).position.x); } @@ -74,7 +79,7 @@ auto RelativeDistanceCondition::distance< template <> auto RelativeDistanceCondition::distance< CoordinateSystem::entity, RelativeDistanceType::longitudinal, RoutingAlgorithm::undefined, true>( - const EntityRef & triggering_entity, const EntityRef & entity_ref) -> double + const EntityRef & triggering_entity) -> double { /** @note This implementation differs from the OpenSCENARIO standard. See the @@ -87,7 +92,7 @@ auto RelativeDistanceCondition::distance< template <> auto RelativeDistanceCondition::distance< CoordinateSystem::entity, RelativeDistanceType::lateral, RoutingAlgorithm::undefined, false>( - const EntityRef & triggering_entity, const EntityRef & entity_ref) -> double + const EntityRef & triggering_entity) -> double { return std::abs(makeNativeRelativeWorldPosition(triggering_entity, entity_ref).position.y); } @@ -95,7 +100,7 @@ auto RelativeDistanceCondition::distance< template <> auto RelativeDistanceCondition::distance< CoordinateSystem::entity, RelativeDistanceType::lateral, RoutingAlgorithm::undefined, true>( - const EntityRef & triggering_entity, const EntityRef & entity_ref) -> double + const EntityRef & triggering_entity) -> double { /** @note This implementation differs from the OpenSCENARIO standard. See the @@ -106,40 +111,38 @@ auto RelativeDistanceCondition::distance< } // @todo: after checking all the scenario work well with consider_z = true, remove this function and use std::hypot(x, y, z) -auto hypot(double x, double y, double z) +auto hypot(double x, double y, double z, bool consider_z) { - static auto consider_z = []() { - auto node = rclcpp::Node("get_parameter", "simulation"); - node.declare_parameter("consider_pose_by_road_slope", false); - return node.get_parameter("consider_pose_by_road_slope").as_bool(); - }(); - return consider_z ? std::hypot(x, y, z) : std::hypot(x, y); } template <> auto RelativeDistanceCondition::distance< CoordinateSystem::entity, RelativeDistanceType::euclidianDistance, RoutingAlgorithm::undefined, - true>(const EntityRef & triggering_entity, const EntityRef & entity_ref) -> double + true>(const EntityRef & triggering_entity) -> double { - const auto relative_world = - makeNativeBoundingBoxRelativeWorldPosition(triggering_entity, entity_ref); - return hypot(relative_world.position.x, relative_world.position.y, relative_world.position.z); + return hypot( + makeNativeBoundingBoxRelativeWorldPosition(triggering_entity, entity_ref).position.x, + makeNativeBoundingBoxRelativeWorldPosition(triggering_entity, entity_ref).position.y, + makeNativeBoundingBoxRelativeWorldPosition(triggering_entity, entity_ref).position.z, + consider_z); } template <> auto RelativeDistanceCondition::distance< CoordinateSystem::entity, RelativeDistanceType::euclidianDistance, RoutingAlgorithm::undefined, - false>(const EntityRef & triggering_entity, const EntityRef & entity_ref) -> double + false>(const EntityRef & triggering_entity) -> double { - const auto relative_world = makeNativeRelativeWorldPosition(triggering_entity, entity_ref); - return hypot(relative_world.position.x, relative_world.position.y, relative_world.position.z); + return hypot( + makeNativeRelativeWorldPosition(triggering_entity, entity_ref).position.x, + makeNativeRelativeWorldPosition(triggering_entity, entity_ref).position.y, + makeNativeRelativeWorldPosition(triggering_entity, entity_ref).position.z, consider_z); } template <> auto RelativeDistanceCondition::distance< CoordinateSystem::lane, RelativeDistanceType::lateral, RoutingAlgorithm::undefined, false>( - const EntityRef & triggering_entity, const EntityRef & entity_ref) -> double + const EntityRef & triggering_entity) -> double { /* For historical reasons, signed distances are returned when @@ -161,7 +164,7 @@ auto RelativeDistanceCondition::distance< template <> auto RelativeDistanceCondition::distance< CoordinateSystem::lane, RelativeDistanceType::lateral, RoutingAlgorithm::undefined, true>( - const EntityRef & triggering_entity, const EntityRef & entity_ref) -> double + const EntityRef & triggering_entity) -> double { /* For historical reasons, signed distances are returned when @@ -183,7 +186,7 @@ auto RelativeDistanceCondition::distance< template <> auto RelativeDistanceCondition::distance< CoordinateSystem::lane, RelativeDistanceType::longitudinal, RoutingAlgorithm::undefined, false>( - const EntityRef & triggering_entity, const EntityRef & entity_ref) -> double + const EntityRef & triggering_entity) -> double { /* For historical reasons, signed distances are returned when @@ -205,7 +208,7 @@ auto RelativeDistanceCondition::distance< template <> auto RelativeDistanceCondition::distance< CoordinateSystem::lane, RelativeDistanceType::longitudinal, RoutingAlgorithm::undefined, true>( - const EntityRef & triggering_entity, const EntityRef & entity_ref) -> double + const EntityRef & triggering_entity) -> double { /* For historical reasons, signed distances are returned when @@ -227,7 +230,7 @@ auto RelativeDistanceCondition::distance< template <> auto RelativeDistanceCondition::distance< CoordinateSystem::lane, RelativeDistanceType::lateral, RoutingAlgorithm::shortest, true>( - const EntityRef & triggering_entity, const EntityRef & entity_ref) -> double + const EntityRef & triggering_entity) -> double { return std::abs(static_cast( makeNativeBoundingBoxRelativeLanePosition( @@ -238,7 +241,7 @@ auto RelativeDistanceCondition::distance< template <> auto RelativeDistanceCondition::distance< CoordinateSystem::lane, RelativeDistanceType::lateral, RoutingAlgorithm::shortest, false>( - const EntityRef & triggering_entity, const EntityRef & entity_ref) -> double + const EntityRef & triggering_entity) -> double { return std::abs( static_cast( @@ -249,7 +252,7 @@ auto RelativeDistanceCondition::distance< template <> auto RelativeDistanceCondition::distance< CoordinateSystem::lane, RelativeDistanceType::longitudinal, RoutingAlgorithm::shortest, true>( - const EntityRef & triggering_entity, const EntityRef & entity_ref) -> double + const EntityRef & triggering_entity) -> double { return std::abs(static_cast( makeNativeBoundingBoxRelativeLanePosition( @@ -260,7 +263,7 @@ auto RelativeDistanceCondition::distance< template <> auto RelativeDistanceCondition::distance< CoordinateSystem::lane, RelativeDistanceType::longitudinal, RoutingAlgorithm::shortest, false>( - const EntityRef & triggering_entity, const EntityRef & entity_ref) -> double + const EntityRef & triggering_entity) -> double { return std::abs( static_cast( @@ -325,14 +328,13 @@ auto RelativeDistanceCondition::distance< #define SWITCH_FREESPACE(FUNCTION, ...) \ return freespace ? FUNCTION(__VA_ARGS__, true) : FUNCTION(__VA_ARGS__, false) -#define DISTANCE(...) distance<__VA_ARGS__>(triggering_entity, entity_ref) +#define DISTANCE(...) distance<__VA_ARGS__>(triggering_entity) -auto RelativeDistanceCondition::evaluate( - const Entities * entities, const EntityRef & triggering_entity, const EntityRef & entity_ref, - CoordinateSystem coordinate_system, RelativeDistanceType relative_distance_type, - RoutingAlgorithm routing_algorithm, Boolean freespace) -> double +auto RelativeDistanceCondition::distance(const EntityRef & triggering_entity) -> double { - if (entities->isAdded(triggering_entity) and entities->isAdded(entity_ref)) { + if ( + global().entities->at(triggering_entity).as().is_added and + global().entities->at(entity_ref).as().is_added) { SWITCH_COORDINATE_SYSTEM( SWITCH_RELATIVE_DISTANCE_TYPE, SWITCH_ROUTING_ALGORITHM, SWITCH_FREESPACE, DISTANCE); } else { @@ -345,9 +347,7 @@ auto RelativeDistanceCondition::evaluate() -> Object results.clear(); return asBoolean(triggering_entities.apply([&](const auto & triggering_entity) { - results.push_back(evaluate( - global().entities, triggering_entity, entity_ref, coordinate_system, relative_distance_type, - routing_algorithm, freespace)); + results.push_back(distance(triggering_entity)); return rule(static_cast(results.back()), value); })); } From a38fe070ec3cb7d20763282939aecbbba3159c45 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Tue, 23 Jul 2024 15:57:41 +0900 Subject: [PATCH 030/304] Revert "Move entity existence check into `distance` from speceialized `distance`" This reverts commit 727d57dc93f29badb41661fcb8543c9ce7840392. --- .../syntax/relative_distance_condition.cpp | 385 +++++++++++------- 1 file changed, 228 insertions(+), 157 deletions(-) diff --git a/openscenario/openscenario_interpreter/src/syntax/relative_distance_condition.cpp b/openscenario/openscenario_interpreter/src/syntax/relative_distance_condition.cpp index 8fd12515497..90e9b7be341 100644 --- a/openscenario/openscenario_interpreter/src/syntax/relative_distance_condition.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/relative_distance_condition.cpp @@ -73,20 +73,31 @@ auto RelativeDistanceCondition::distance< CoordinateSystem::entity, RelativeDistanceType::longitudinal, RoutingAlgorithm::undefined, false>( const EntityRef & triggering_entity) -> double { - return std::abs(makeNativeRelativeWorldPosition(triggering_entity, entity_ref).position.x); + if ( + global().entities->at(triggering_entity).as().is_added and + global().entities->at(entity_ref).as().is_added) { + return std::abs(makeNativeRelativeWorldPosition(triggering_entity, entity_ref).position.x); + } else { + return Double::nan(); + } } +/** + * @note This implementation differs from the OpenSCENARIO standard. See the section "6.4. Distances" in the OpenSCENARIO User Guide. + */ template <> auto RelativeDistanceCondition::distance< CoordinateSystem::entity, RelativeDistanceType::longitudinal, RoutingAlgorithm::undefined, true>( const EntityRef & triggering_entity) -> double { - /** - @note This implementation differs from the OpenSCENARIO standard. See the - section "6.4. Distances" in the OpenSCENARIO User Guide. - */ - return std::abs( - makeNativeBoundingBoxRelativeWorldPosition(triggering_entity, entity_ref).position.x); + if ( + global().entities->at(triggering_entity).as().is_added and + global().entities->at(entity_ref).as().is_added) { + return std::abs( + makeNativeBoundingBoxRelativeWorldPosition(triggering_entity, entity_ref).position.x); + } else { + return Double::nan(); + } } template <> @@ -94,24 +105,35 @@ auto RelativeDistanceCondition::distance< CoordinateSystem::entity, RelativeDistanceType::lateral, RoutingAlgorithm::undefined, false>( const EntityRef & triggering_entity) -> double { - return std::abs(makeNativeRelativeWorldPosition(triggering_entity, entity_ref).position.y); + if ( + global().entities->at(triggering_entity).as().is_added and + global().entities->at(entity_ref).as().is_added) { + return std::abs(makeNativeRelativeWorldPosition(triggering_entity, entity_ref).position.y); + } else { + return Double::nan(); + } } +/** + * @note This implementation differs from the OpenSCENARIO standard. See the section "6.4. Distances" in the OpenSCENARIO User Guide. + */ template <> auto RelativeDistanceCondition::distance< CoordinateSystem::entity, RelativeDistanceType::lateral, RoutingAlgorithm::undefined, true>( const EntityRef & triggering_entity) -> double { - /** - @note This implementation differs from the OpenSCENARIO standard. See the - section "6.4. Distances" in the OpenSCENARIO User Guide. - */ - return std::abs( - makeNativeBoundingBoxRelativeWorldPosition(triggering_entity, entity_ref).position.y); + if ( + global().entities->at(triggering_entity).as().is_added and + global().entities->at(entity_ref).as().is_added) { + return std::abs( + makeNativeBoundingBoxRelativeWorldPosition(triggering_entity, entity_ref).position.y); + } else { + return Double::nan(); + } } -// @todo: after checking all the scenario work well with consider_z = true, remove this function and use std::hypot(x, y, z) -auto hypot(double x, double y, double z, bool consider_z) +// @todo: after checking all the scenario work well with consider_z = true, remove this function and use std::hypot(x,y,z) +static double hypot(const double x, const double y, const double z, const bool consider_z) { return consider_z ? std::hypot(x, y, z) : std::hypot(x, y); } @@ -121,11 +143,17 @@ auto RelativeDistanceCondition::distance< CoordinateSystem::entity, RelativeDistanceType::euclidianDistance, RoutingAlgorithm::undefined, true>(const EntityRef & triggering_entity) -> double { - return hypot( - makeNativeBoundingBoxRelativeWorldPosition(triggering_entity, entity_ref).position.x, - makeNativeBoundingBoxRelativeWorldPosition(triggering_entity, entity_ref).position.y, - makeNativeBoundingBoxRelativeWorldPosition(triggering_entity, entity_ref).position.z, - consider_z); + if ( + global().entities->at(triggering_entity).as().is_added and + global().entities->at(entity_ref).as().is_added) { + return hypot( + makeNativeBoundingBoxRelativeWorldPosition(triggering_entity, entity_ref).position.x, + makeNativeBoundingBoxRelativeWorldPosition(triggering_entity, entity_ref).position.y, + makeNativeBoundingBoxRelativeWorldPosition(triggering_entity, entity_ref).position.z, + consider_z); + } else { + return Double::nan(); + } } template <> @@ -133,10 +161,16 @@ auto RelativeDistanceCondition::distance< CoordinateSystem::entity, RelativeDistanceType::euclidianDistance, RoutingAlgorithm::undefined, false>(const EntityRef & triggering_entity) -> double { - return hypot( - makeNativeRelativeWorldPosition(triggering_entity, entity_ref).position.x, - makeNativeRelativeWorldPosition(triggering_entity, entity_ref).position.y, - makeNativeRelativeWorldPosition(triggering_entity, entity_ref).position.z, consider_z); + if ( + global().entities->at(triggering_entity).as().is_added and + global().entities->at(entity_ref).as().is_added) { + return hypot( + makeNativeRelativeWorldPosition(triggering_entity, entity_ref).position.x, + makeNativeRelativeWorldPosition(triggering_entity, entity_ref).position.y, + makeNativeRelativeWorldPosition(triggering_entity, entity_ref).position.z, consider_z); + } else { + return Double::nan(); + } } template <> @@ -144,21 +178,27 @@ auto RelativeDistanceCondition::distance< CoordinateSystem::lane, RelativeDistanceType::lateral, RoutingAlgorithm::undefined, false>( const EntityRef & triggering_entity) -> double { - /* - For historical reasons, signed distances are returned when - coordinateSystem == lane and relativeDistanceType == longitudinal/lateral. - The sign has been mainly used to determine the front/back and left/right - positional relationship (a negative value is returned if the target entity - is behind or to the right). - - This behavior violates the OpenSCENARIO standard. In the future, after - DistanceCondition and RelativeDistanceCondition of TIER IV's OpenSCENARIO - Interpreter support OpenSCENARIO 1.2 RoutingAlgorithm, this behavior will - be enabled only when routingAlgorithm == undefined. - */ - return static_cast( - makeNativeRelativeLanePosition(triggering_entity, entity_ref)) - .offset; + if ( + global().entities->at(entity_ref).as().is_added and + global().entities->at(triggering_entity).as().is_added) { + /* + For historical reasons, signed distances are returned when + coordinateSystem == lane and relativeDistanceType == + longitudinal/lateral. The sign has been mainly used to determine the + front/back and left/right positional relationship (a negative value is + returned if the target entity is behind or to the right). + + This behavior violates the OpenSCENARIO standard. In the future, after + DistanceCondition and RelativeDistanceCondition of TIER IV's + OpenSCENARIO Interpreter support OpenSCENARIO 1.2 RoutingAlgorithm, this + behavior will be enabled only when routingAlgorithm == undefined. + */ + return static_cast( + makeNativeRelativeLanePosition(triggering_entity, entity_ref)) + .offset; + } else { + return Double::nan(); + } } template <> @@ -166,21 +206,27 @@ auto RelativeDistanceCondition::distance< CoordinateSystem::lane, RelativeDistanceType::lateral, RoutingAlgorithm::undefined, true>( const EntityRef & triggering_entity) -> double { - /* - For historical reasons, signed distances are returned when - coordinateSystem == lane and relativeDistanceType == longitudinal/lateral. - The sign has been mainly used to determine the front/back and left/right - positional relationship (a negative value is returned if the target entity - is behind or to the right). - - This behavior violates the OpenSCENARIO standard. In the future, after - DistanceCondition and RelativeDistanceCondition of TIER IV's OpenSCENARIO - Interpreter support OpenSCENARIO 1.2 RoutingAlgorithm, this behavior will - be enabled only when routingAlgorithm == undefined. - */ - return static_cast( - makeNativeBoundingBoxRelativeLanePosition(triggering_entity, entity_ref)) - .offset; + if ( + global().entities->at(entity_ref).as().is_added and + global().entities->at(triggering_entity).as().is_added) { + /* + For historical reasons, signed distances are returned when + coordinateSystem == lane and relativeDistanceType == + longitudinal/lateral. The sign has been mainly used to determine the + front/back and left/right positional relationship (a negative value is + returned if the target entity is behind or to the right). + + This behavior violates the OpenSCENARIO standard. In the future, after + DistanceCondition and RelativeDistanceCondition of TIER IV's + OpenSCENARIO Interpreter support OpenSCENARIO 1.2 RoutingAlgorithm, this + behavior will be enabled only when routingAlgorithm == undefined. + */ + return static_cast( + makeNativeBoundingBoxRelativeLanePosition(triggering_entity, entity_ref)) + .offset; + } else { + return Double::nan(); + } } template <> @@ -188,21 +234,27 @@ auto RelativeDistanceCondition::distance< CoordinateSystem::lane, RelativeDistanceType::longitudinal, RoutingAlgorithm::undefined, false>( const EntityRef & triggering_entity) -> double { - /* - For historical reasons, signed distances are returned when - coordinateSystem == lane and relativeDistanceType == longitudinal/lateral. - The sign has been mainly used to determine the front/back and left/right - positional relationship (a negative value is returned if the target entity - is behind or to the right). - - This behavior violates the OpenSCENARIO standard. In the future, after - DistanceCondition and RelativeDistanceCondition of TIER IV's OpenSCENARIO - Interpreter support OpenSCENARIO 1.2 RoutingAlgorithm, this behavior will - be enabled only when routingAlgorithm == undefined. - */ - return static_cast( - makeNativeRelativeLanePosition(triggering_entity, entity_ref)) - .s; + if ( + global().entities->at(triggering_entity).as().is_added and + global().entities->at(entity_ref).as().is_added) { + /* + For historical reasons, signed distances are returned when + coordinateSystem == lane and relativeDistanceType == + longitudinal/lateral. The sign has been mainly used to determine the + front/back and left/right positional relationship (a negative value is + returned if the target entity is behind or to the right). + + This behavior violates the OpenSCENARIO standard. In the future, after + DistanceCondition and RelativeDistanceCondition of TIER IV's + OpenSCENARIO Interpreter support OpenSCENARIO 1.2 RoutingAlgorithm, this + behavior will be enabled only when routingAlgorithm == undefined. + */ + return static_cast( + makeNativeRelativeLanePosition(triggering_entity, entity_ref)) + .s; + } else { + return Double::nan(); + } } template <> @@ -210,21 +262,27 @@ auto RelativeDistanceCondition::distance< CoordinateSystem::lane, RelativeDistanceType::longitudinal, RoutingAlgorithm::undefined, true>( const EntityRef & triggering_entity) -> double { - /* - For historical reasons, signed distances are returned when - coordinateSystem == lane and relativeDistanceType == longitudinal/lateral. - The sign has been mainly used to determine the front/back and left/right - positional relationship (a negative value is returned if the target entity - is behind or to the right). - - This behavior violates the OpenSCENARIO standard. In the future, after - DistanceCondition and RelativeDistanceCondition of TIER IV's OpenSCENARIO - Interpreter support OpenSCENARIO 1.2 RoutingAlgorithm, this behavior will - be enabled only when routingAlgorithm == undefined. - */ - return static_cast( - makeNativeBoundingBoxRelativeLanePosition(triggering_entity, entity_ref)) - .s; + if ( + global().entities->at(triggering_entity).as().is_added and + global().entities->at(entity_ref).as().is_added) { + /* + For historical reasons, signed distances are returned when + coordinateSystem == lane and relativeDistanceType == + longitudinal/lateral. The sign has been mainly used to determine the + front/back and left/right positional relationship (a negative value is + returned if the target entity is behind or to the right). + + This behavior violates the OpenSCENARIO standard. In the future, after + DistanceCondition and RelativeDistanceCondition of TIER IV's + OpenSCENARIO Interpreter support OpenSCENARIO 1.2 RoutingAlgorithm, this + behavior will be enabled only when routingAlgorithm == undefined. + */ + return static_cast( + makeNativeBoundingBoxRelativeLanePosition(triggering_entity, entity_ref)) + .s; + } else { + return Double::nan(); + } } template <> @@ -232,10 +290,16 @@ auto RelativeDistanceCondition::distance< CoordinateSystem::lane, RelativeDistanceType::lateral, RoutingAlgorithm::shortest, true>( const EntityRef & triggering_entity) -> double { - return std::abs(static_cast( - makeNativeBoundingBoxRelativeLanePosition( - triggering_entity, entity_ref, RoutingAlgorithm::shortest)) - .offset); + if ( + global().entities->at(entity_ref).as().is_added and + global().entities->at(triggering_entity).as().is_added) { + return std::abs(static_cast( + makeNativeBoundingBoxRelativeLanePosition( + triggering_entity, entity_ref, RoutingAlgorithm::shortest)) + .offset); + } else { + return Double::nan(); + } } template <> @@ -243,10 +307,16 @@ auto RelativeDistanceCondition::distance< CoordinateSystem::lane, RelativeDistanceType::lateral, RoutingAlgorithm::shortest, false>( const EntityRef & triggering_entity) -> double { - return std::abs( - static_cast( - makeNativeRelativeLanePosition(triggering_entity, entity_ref, RoutingAlgorithm::shortest)) - .offset); + if ( + global().entities->at(entity_ref).as().is_added and + global().entities->at(triggering_entity).as().is_added) { + return std::abs( + static_cast( + makeNativeRelativeLanePosition(triggering_entity, entity_ref, RoutingAlgorithm::shortest)) + .offset); + } else { + return Double::nan(); + } } template <> @@ -254,10 +324,16 @@ auto RelativeDistanceCondition::distance< CoordinateSystem::lane, RelativeDistanceType::longitudinal, RoutingAlgorithm::shortest, true>( const EntityRef & triggering_entity) -> double { - return std::abs(static_cast( - makeNativeBoundingBoxRelativeLanePosition( - triggering_entity, entity_ref, RoutingAlgorithm::shortest)) - .s); + if ( + global().entities->at(entity_ref).as().is_added and + global().entities->at(triggering_entity).as().is_added) { + return std::abs(static_cast( + makeNativeBoundingBoxRelativeLanePosition( + triggering_entity, entity_ref, RoutingAlgorithm::shortest)) + .s); + } else { + return Double::nan(); + } } template <> @@ -265,64 +341,64 @@ auto RelativeDistanceCondition::distance< CoordinateSystem::lane, RelativeDistanceType::longitudinal, RoutingAlgorithm::shortest, false>( const EntityRef & triggering_entity) -> double { - return std::abs( - static_cast( - makeNativeRelativeLanePosition(triggering_entity, entity_ref, RoutingAlgorithm::shortest)) - .s); + if ( + global().entities->at(entity_ref).as().is_added and + global().entities->at(triggering_entity).as().is_added) { + return std::abs( + static_cast( + makeNativeRelativeLanePosition(triggering_entity, entity_ref, RoutingAlgorithm::shortest)) + .s); + } else { + return Double::nan(); + } } -#define SWITCH_COORDINATE_SYSTEM(FUNCTION, ...) \ - switch (coordinate_system) { \ - case CoordinateSystem::entity: \ - FUNCTION(__VA_ARGS__, CoordinateSystem::entity); \ - break; \ - case CoordinateSystem::lane: \ - FUNCTION(__VA_ARGS__, CoordinateSystem::lane); \ - break; \ - case CoordinateSystem::road: \ - FUNCTION(__VA_ARGS__, CoordinateSystem::road); \ - break; \ - case CoordinateSystem::trajectory: \ - FUNCTION(__VA_ARGS__, CoordinateSystem::trajectory); \ - break; \ - default: \ - throw UNEXPECTED_ENUMERATION_VALUE_ASSIGNED(CoordinateSystem, coordinate_system); \ +#define SWITCH_COORDINATE_SYSTEM(FUNCTION, ...) \ + switch (coordinate_system) { \ + case CoordinateSystem::entity: \ + FUNCTION(__VA_ARGS__, CoordinateSystem::entity); \ + break; \ + case CoordinateSystem::lane: \ + FUNCTION(__VA_ARGS__, CoordinateSystem::lane); \ + break; \ + case CoordinateSystem::road: \ + FUNCTION(__VA_ARGS__, CoordinateSystem::road); \ + break; \ + case CoordinateSystem::trajectory: \ + FUNCTION(__VA_ARGS__, CoordinateSystem::trajectory); \ + break; \ } -#define SWITCH_RELATIVE_DISTANCE_TYPE(FUNCTION, ...) \ - switch (relative_distance_type) { \ - case RelativeDistanceType::longitudinal: \ - FUNCTION(__VA_ARGS__, RelativeDistanceType::longitudinal); \ - break; \ - case RelativeDistanceType::lateral: \ - FUNCTION(__VA_ARGS__, RelativeDistanceType::lateral); \ - break; \ - case RelativeDistanceType::euclidianDistance: \ - FUNCTION(__VA_ARGS__, RelativeDistanceType::euclidianDistance); \ - break; \ - default: \ - throw UNEXPECTED_ENUMERATION_VALUE_ASSIGNED(RelativeDistanceType, relative_distance_type); \ +#define SWITCH_RELATIVE_DISTANCE_TYPE(FUNCTION, ...) \ + switch (relative_distance_type) { \ + case RelativeDistanceType::longitudinal: \ + FUNCTION(__VA_ARGS__, RelativeDistanceType::longitudinal); \ + break; \ + case RelativeDistanceType::lateral: \ + FUNCTION(__VA_ARGS__, RelativeDistanceType::lateral); \ + break; \ + case RelativeDistanceType::euclidianDistance: \ + FUNCTION(__VA_ARGS__, RelativeDistanceType::euclidianDistance); \ + break; \ } -#define SWITCH_ROUTING_ALGORITHM(FUNCTION, ...) \ - switch (routing_algorithm) { \ - case RoutingAlgorithm::assigned_route: \ - FUNCTION(__VA_ARGS__, RoutingAlgorithm::assigned_route); \ - break; \ - case RoutingAlgorithm::fastest: \ - FUNCTION(__VA_ARGS__, RoutingAlgorithm::fastest); \ - break; \ - case RoutingAlgorithm::least_intersections: \ - FUNCTION(__VA_ARGS__, RoutingAlgorithm::least_intersections); \ - break; \ - case RoutingAlgorithm::shortest: \ - FUNCTION(__VA_ARGS__, RoutingAlgorithm::shortest); \ - break; \ - case RoutingAlgorithm::undefined: \ - FUNCTION(__VA_ARGS__, RoutingAlgorithm::undefined); \ - break; \ - default: \ - throw UNEXPECTED_ENUMERATION_VALUE_ASSIGNED(RoutingAlgorithm, routing_algorithm); \ +#define SWITCH_ROUTING_ALGORITHM(FUNCTION, ...) \ + switch (routing_algorithm) { \ + case RoutingAlgorithm::assigned_route: \ + FUNCTION(__VA_ARGS__, RoutingAlgorithm::assigned_route); \ + break; \ + case RoutingAlgorithm::fastest: \ + FUNCTION(__VA_ARGS__, RoutingAlgorithm::fastest); \ + break; \ + case RoutingAlgorithm::least_intersections: \ + FUNCTION(__VA_ARGS__, RoutingAlgorithm::least_intersections); \ + break; \ + case RoutingAlgorithm::shortest: \ + FUNCTION(__VA_ARGS__, RoutingAlgorithm::shortest); \ + break; \ + case RoutingAlgorithm::undefined: \ + FUNCTION(__VA_ARGS__, RoutingAlgorithm::undefined); \ + break; \ } #define SWITCH_FREESPACE(FUNCTION, ...) \ @@ -332,14 +408,9 @@ auto RelativeDistanceCondition::distance< auto RelativeDistanceCondition::distance(const EntityRef & triggering_entity) -> double { - if ( - global().entities->at(triggering_entity).as().is_added and - global().entities->at(entity_ref).as().is_added) { - SWITCH_COORDINATE_SYSTEM( - SWITCH_RELATIVE_DISTANCE_TYPE, SWITCH_ROUTING_ALGORITHM, SWITCH_FREESPACE, DISTANCE); - } else { - return Double::nan(); - } + SWITCH_COORDINATE_SYSTEM( + SWITCH_RELATIVE_DISTANCE_TYPE, SWITCH_ROUTING_ALGORITHM, SWITCH_FREESPACE, DISTANCE); + return Double::nan(); } auto RelativeDistanceCondition::evaluate() -> Object From 566086f4e4c04014c77e34c991ec4359b87740ce Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Tue, 23 Jul 2024 16:21:57 +0900 Subject: [PATCH 031/304] Update ControllerAction to support some new properties related to LiDAR Signed-off-by: yamacir-kit --- .../simulator_core.hpp | 30 +++++++++++++++++-- 1 file changed, 28 insertions(+), 2 deletions(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/simulator_core.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/simulator_core.hpp index 2e7e89f6558..5859eae43b2 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/simulator_core.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/simulator_core.hpp @@ -334,8 +334,34 @@ class SimulatorCore }()); if (controller.isAutoware()) { - core->attachLidarSensor( - entity_ref, controller.properties.template get("pointcloudPublishingDelay")); + core->attachLidarSensor([&]() { + simulation_api_schema::LidarConfiguration configuration; + + auto degree_to_radian = [](auto degree) constexpr { + return degree / 180.0 * boost::math::constants::pi(); + }; + + // clang-format off + configuration.set_architecture_type(core->getROS2Parameter("architecture_type", "awf/universe")); + configuration.set_entity(entity_ref); + configuration.set_horizontal_resolution(degree_to_radian(controller.properties.template get("pointcloudHorizontalResolution", 1.0))); + configuration.set_lidar_sensor_delay(controller.properties.template get("pointcloudPublishingDelay")); + configuration.set_scan_duration(0.1); + // clang-format on + + const auto vertical_field_of_view = degree_to_radian( + controller.properties.template get("pointcloudVerticalFieldOfView", 30.0)); + + const auto channels = + controller.properties.template get("pointcloudChannels", 16); + + for (std::size_t i = 0; i < channels; ++i) { + configuration.add_vertical_angles( + vertical_field_of_view / 2 - vertical_field_of_view / channels * i); + } + + return configuration; + }()); core->attachDetectionSensor([&]() { simulation_api_schema::DetectionSensorConfiguration configuration; From 28af722ef74928aa4ff43458ec1b69b93a3b817d Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Tue, 23 Jul 2024 16:25:41 +0900 Subject: [PATCH 032/304] Update `MiscObjectEntity` to display with a magenta bounding box Signed-off-by: yamacir-kit --- .../visualization/visualization_component.cpp | 26 ++++++++++--------- 1 file changed, 14 insertions(+), 12 deletions(-) diff --git a/simulation/traffic_simulator/src/visualization/visualization_component.cpp b/simulation/traffic_simulator/src/visualization/visualization_component.cpp index 6cea709f9d8..f1510972d8e 100644 --- a/simulation/traffic_simulator/src/visualization/visualization_component.cpp +++ b/simulation/traffic_simulator/src/visualization/visualization_component.cpp @@ -124,18 +124,20 @@ const visualization_msgs::msg::MarkerArray VisualizationComponent::generateMarke constexpr auto default_quaternion = rosidl_runtime_cpp::MessageInitialization::DEFAULTS_ONLY; auto ret = visualization_msgs::msg::MarkerArray(); auto stamp = get_clock()->now(); - std_msgs::msg::ColorRGBA color; - switch (status.type.type) { - case status.type.EGO: - color = color_names::makeColorMsg("limegreen", 0.99); - break; - case status.type.PEDESTRIAN: - color = color_names::makeColorMsg("orange", 0.99); - break; - case status.type.VEHICLE: - color = color_names::makeColorMsg("lightskyblue", 0.99); - break; - } + + const auto color = [&]() { + switch (status.type.type) { + case status.type.EGO: + return color_names::makeColorMsg("limegreen", 0.99); + case status.type.PEDESTRIAN: + return color_names::makeColorMsg("orange", 0.99); + case status.type.VEHICLE: + return color_names::makeColorMsg("lightskyblue", 0.99); + default: + case status.type.MISC_OBJECT: + return color_names::makeColorMsg("magenta", 0.99); + } + }(); if (goal_pose.size() != 0) { goal_pose_max_size = std::max(goal_pose_max_size, int(goal_pose.size())); From ea2fdbe045921943ddc9b0f6db477797a55b72b8 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Tue, 23 Jul 2024 19:21:21 +0900 Subject: [PATCH 033/304] Correct initialization of RelativeClearanceCondition::entity_refs along the standard --- .../src/syntax/relative_clearance_condition.cpp | 11 ++++++++++- 1 file changed, 10 insertions(+), 1 deletion(-) diff --git a/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp b/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp index 0065fe40cc4..6a7c556aa11 100644 --- a/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp @@ -14,6 +14,7 @@ #include #include +#include #include #include #include @@ -30,7 +31,15 @@ RelativeClearanceCondition::RelativeClearanceCondition( free_space(readAttribute("freeSpace", node, scope)), opposite_lanes(readAttribute("oppositeLanes", node, scope)), relative_lane_range(readElements("RelativeLaneRange", node, scope)), - entity_refs(readElements("EntityRef", node, scope)), + entity_refs([&]() { + auto entities = readElements("EntityRef", node, scope); + if (entities.empty()) { + for (const auto & [name, entity] : *global().entities) { + entities.emplace_back(name); + } + } + return entities; + }()), triggering_entities(triggering_entities) { } From 5d82b784a157eb3f4641a021e211494cddf005af Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Wed, 24 Jul 2024 14:56:22 +0900 Subject: [PATCH 034/304] Add a test scenario for `ObjectController`'s pseudo LiDAR property Signed-off-by: yamacir-kit --- .../simulator_core.hpp | 2 +- ...roperty.pointcloudVerticalFieldOfView.yaml | 259 ++++++++++++++++++ 2 files changed, 260 insertions(+), 1 deletion(-) create mode 100644 test_runner/scenario_test_runner/scenario/Property.pointcloudVerticalFieldOfView.yaml diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/simulator_core.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/simulator_core.hpp index 5859eae43b2..2b0f5081336 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/simulator_core.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/simulator_core.hpp @@ -337,7 +337,7 @@ class SimulatorCore core->attachLidarSensor([&]() { simulation_api_schema::LidarConfiguration configuration; - auto degree_to_radian = [](auto degree) constexpr { + auto degree_to_radian = [](auto degree) { return degree / 180.0 * boost::math::constants::pi(); }; diff --git a/test_runner/scenario_test_runner/scenario/Property.pointcloudVerticalFieldOfView.yaml b/test_runner/scenario_test_runner/scenario/Property.pointcloudVerticalFieldOfView.yaml new file mode 100644 index 00000000000..ffadea00e1a --- /dev/null +++ b/test_runner/scenario_test_runner/scenario/Property.pointcloudVerticalFieldOfView.yaml @@ -0,0 +1,259 @@ +OpenSCENARIO: + FileHeader: + author: 'Tatsuya Yamasaki' + date: '2022-03-04T18:06:53+09:00' + description: 'Sample scenario (with Autoware)' + revMajor: 1 + revMinor: 0 + ParameterDeclarations: + ParameterDeclaration: [] + CatalogLocations: + VehicleCatalog: + Directory: + path: $(ros2 pkg prefix --share openscenario_experimental_catalog)/vehicle + RoadNetwork: + LogicFile: + filepath: $(ros2 pkg prefix --share kashiwanoha_map)/map + Entities: + ScenarioObject: + - name: ego + CatalogReference: + catalogName: sample_vehicle + entryName: sample_vehicle + ObjectController: + Controller: + name: 'Autoware' + Properties: + Property: + - name: maxJerk + value: "1.5" + - name: minJerk + value: "-1.5" + - name: pointcloudChannels + value: '67' + - name: pointcloudHorizontalResolution + value: '1.5' + - name: pointcloudVerticalFieldOfView + value: '45.678' + - name: boundary + MiscObject: &BARRICADE + mass: 1.0 + miscObjectCategory: obstacle + name: '' + BoundingBox: + Center: + x: 0 + y: 0 + z: 0 + Dimensions: + width: 100 + length: 100 + height: 100 + Properties: + Property: [] + - name: barricade + MiscObject: + mass: 1.0 + miscObjectCategory: obstacle + name: '' + BoundingBox: + Center: + x: 0 + y: 0 + z: 0 + Dimensions: + width: 10 + length: 1 + height: 10 + Properties: + Property: [] + Storyboard: + Init: + Actions: + Private: + - entityRef: ego + PrivateAction: + - TeleportAction: + Position: + LanePosition: + roadId: '' + laneId: 34513 + s: 10 + offset: 0 + Orientation: &ORIENTATION_ZERO + type: relative + h: 0 + p: 0 + r: 0 + - RoutingAction: + AcquirePositionAction: + Position: + LanePosition: + roadId: '' + laneId: '34507' + s: 50 + offset: 0 + Orientation: *ORIENTATION_ZERO + - entityRef: boundary + PrivateAction: + - TeleportAction: + Position: + LanePosition: + roadId: '' + laneId: 34513 + s: 10 + offset: 0 + Orientation: *ORIENTATION_ZERO + - entityRef: barricade + PrivateAction: + - TeleportAction: + Position: + LanePosition: + roadId: '' + laneId: 34513 + s: 20 + offset: 0 + Orientation: *ORIENTATION_ZERO + Story: + - name: '' + Act: + - name: remove_barricade + ManeuverGroup: + - maximumExecutionCount: 1 + name: '' + Actors: + selectTriggeringEntities: false + EntityRef: + - entityRef: barricade + Maneuver: + - name: '' + Event: + - name: '' + priority: parallel + maximumExecutionCount: 1 + StartTrigger: + ConditionGroup: + - Condition: + - name: '' + delay: 0 + conditionEdge: none + ByEntityCondition: + TriggeringEntities: + triggeringEntitiesRule: any + EntityRef: + - entityRef: barricade + EntityCondition: + StandStillCondition: + duration: 90 + Action: + - name: '' + GlobalAction: + EntityAction: + entityRef: barricade + DeleteEntityAction: + StartTrigger: + ConditionGroup: + - Condition: + - name: + delay: 0 + conditionEdge: none + ByValueCondition: + SimulationTimeCondition: + value: 0 + rule: greaterThan + - name: _EndCondition + ManeuverGroup: + - maximumExecutionCount: 1 + name: '' + Actors: + selectTriggeringEntities: false + EntityRef: + - entityRef: ego + Maneuver: + - name: '' + Event: + - name: '' + priority: parallel + StartTrigger: + ConditionGroup: + - Condition: + - name: '' + delay: 0 + conditionEdge: none + ByEntityCondition: + TriggeringEntities: + triggeringEntitiesRule: any + EntityRef: + - entityRef: ego + EntityCondition: + ReachPositionCondition: + Position: + LanePosition: + roadId: '' + laneId: '34507' + s: 50 + offset: 0 + Orientation: + type: relative + h: 0 + p: 0 + r: 0 + tolerance: 0.5 + - name: '' + delay: 0 + conditionEdge: none + ByValueCondition: + UserDefinedValueCondition: + name: RelativeHeadingCondition(ego, 34507, 50) + rule: lessThan + value: 0.1 + - name: '' + delay: 0 + conditionEdge: none + ByValueCondition: + UserDefinedValueCondition: + name: RelativeHeadingCondition(ego) + rule: lessThan + value: 0.1 + - name: '' + delay: 0 + conditionEdge: none + ByValueCondition: + UserDefinedValueCondition: + name: ego.currentMinimumRiskManeuverState.state + rule: equalTo + value: NORMAL + Action: + - name: '' + UserDefinedAction: + CustomCommandAction: + type: exitSuccess + - name: '' + priority: parallel + StartTrigger: + ConditionGroup: + - Condition: + - name: '' + delay: 0 + conditionEdge: none + ByValueCondition: + SimulationTimeCondition: + value: 180 + rule: greaterThan + Action: + - name: '' + UserDefinedAction: + CustomCommandAction: + type: exitFailure + StartTrigger: + ConditionGroup: + - Condition: + - name: '' + delay: 0 + conditionEdge: none + ByValueCondition: + SimulationTimeCondition: + value: 0 + rule: greaterThan + StopTrigger: + ConditionGroup: [] From 487556437b448186e2de484f5130eb2b1d015e74 Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Wed, 24 Jul 2024 15:03:19 +0900 Subject: [PATCH 035/304] Add descriptions of pseudo LiDAR settings to ConfiguringPerceptionTopics Signed-off-by: yamacir-kit --- .../ConfiguringPerceptionTopics.md | 123 +++++++++++++++++- 1 file changed, 117 insertions(+), 6 deletions(-) diff --git a/docs/developer_guide/ConfiguringPerceptionTopics.md b/docs/developer_guide/ConfiguringPerceptionTopics.md index 22495fd1f5b..5954258932b 100644 --- a/docs/developer_guide/ConfiguringPerceptionTopics.md +++ b/docs/developer_guide/ConfiguringPerceptionTopics.md @@ -24,13 +24,16 @@ where `` and `` can be set to: | Name | Value | Default | Description | |--------------------------------------------|-----------------------------------------------|:-------:|-----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------| -| `detectedObjectMissingProbability` | A `double` type value between `0.0` and `1.0` | `0.0` | Do not publish the perception topic with the given probability. | -| `detectedObjectPositionStandardDeviation` | A positive `double` type value | `0.0` | Randomize the positions of other vehicles included in the perception topic according to the given standard deviation. | -| `detectedObjectPublishingDelay` | A positive `double` type value | `0.0` | Delays the publication of the perception topic by the specified number of seconds. | -| `detectedObjectGroundTruthPublishingDelay` | A positive `double` type value | `0.0` | Delays the publication of the perception ground truth topic by the specified number of seconds. | +| `detectedObjectMissingProbability` | A `double` type value between `0.0` and `1.0` | `0.0` | Do not publish the perception topic with the given probability. | +| `detectedObjectPositionStandardDeviation` | A positive `double` type value | `0.0` | Randomize the positions of other vehicles included in the perception topic according to the given standard deviation. | +| `detectedObjectPublishingDelay` | A positive `double` type value | `0.0` | Delays the publication of the perception topic by the specified number of seconds. | +| `detectedObjectGroundTruthPublishingDelay` | A positive `double` type value | `0.0` | Delays the publication of the perception ground truth topic by the specified number of seconds. | | `detectionSensorRange` | A positive `double` type value | `300.0` | Specifies the sensor detection range for detected object. | | `isClairvoyant` | A `boolean` type value | `false` | Specifies whether the detected object is a Clairvoyant. If this parameter is not defined explicitly, the property of `detectionSensorRange` is not reflected and only detected object detected by lidar is published. | -| `randomSeed` | A positive `integer` type value | `0` | Specifies the seed value for the random number generator. | +| `pointcloudChannels` | A positive `integer` type value | `16` | Number of channels of pseudo LiDAR inside the simulator used to generate pointclouds. | +| `pointcloudHorizontalResolution` | A positive `double` type value | `1.0` | Horizontal angular resolution of the pseudo LiDAR inside the simulator used to generate the pointcloud. | +| `pointcloudVerticalFieldOfView` | A positive `double` type value | `30.0` | Vertical field of view of the pseudo LiDAR inside the simulator used to generate the pointcloud. | +| `randomSeed` | A positive `integer` type value | `0` | Specifies the seed value for the random number generator. | These properties are not exclusive. In other words, multiple properties can be specified at the same time. However, these properties only take effect for @@ -161,7 +164,7 @@ this problem by setting an interval of the specified number of seconds between `scenario_simulator_v2` generating a perception result and publishing it. **Specification** - The property's value must be a positive real number. The -unit is seconds. It is an error if the value is negative. Since the delay is +unit is seconds. It is an error if the value is negative. Since the delay is set to the same value for each topic, it is not possible to delay only a specific topic. @@ -230,6 +233,114 @@ it reaches the receiver node. value: "3" ``` +## Property `pointcloudChannels` + +**Summary** - Number of channels of pseudo LiDAR inside the simulator used to +generate pointclouds. + +**Purpose** - The `simple_sensor_simulator` simulates a simple LiDAR, such as a +horizontally rotating vertically aligned laser, typical of the VLP-16, to +generate a pointcloud. The default settings produce a pointcloud that exactly +mimics the sensing results from the VLP-16. However, VLP-16 is a relatively low +pointcloud density LiDAR used with Autoware, so if a higher pointcloud density +LiDAR is to be installed, it will be necessary to simulate a scenario with a +higher pointcloud density to match the actual vehicle. This property addresses +this issue by providing a means to specify the number of pseudo LiDAR channels. + +**Specification** - The property value must be a real number greater than or +equal to 1. Zero or negative values are errors. The upper limit of values is +the maximum value of a 64-bit unsigned integer, but computer performance +effectively limits the value to much lower values. + +**Guarantee** - The `simple_sensor_simulator` does not simulate a realistic +LiDAR. For example, in the case of a LiDAR with a mechanically rotating laser +structure, the resulting point cloud will be distorted when moving at high +speeds, but `simple_sensor_simulator` cannot simulate such behavior and +produces an undistorted pointcloud. + +**Default behavior** - If the property is not specified, the default value is +`"16"`. When the properties `pointcloudChannels` and +`pointcloudVerticalFieldOfView` are both at their default values, the behavior +mimics Velodyne VLP-16. + +**[Example](https://github.com/tier4/scenario_simulator_v2/blob/master/test_runner/scenario_test_runner/scenario/Property.pointcloudVerticalFieldOfView.yaml)** - +``` + ObjectController: + Controller: + name: '...' + Properties: + Property: + - name: 'isEgo' + value: 'true' + - name: 'pointcloudChannels' + value: '128' +``` + +## Property `pointcloudHorizontalResolution` + +**Summary** - Horizontal angular resolution of the pseudo LiDAR inside the +simulator used to generate the pointcloud. + +**Purpose** - To address the same issues as the property `pointcloudChannels`, +this property provides a means to specify the angular resolution of the pseudo +LiDAR. + +**Specification** - The property value must be a real number greater than zero. +The unit is degrees. If the value is zero or negative, it is an error. + +**Guarantee** - Same as one for `pointcloudChannels` + +**Default behavior** - If the property is not specified, the default value is +`"1.0"`. + +**[Example](https://github.com/tier4/scenario_simulator_v2/blob/master/test_runner/scenario_test_runner/scenario/Property.pointcloudVerticalFieldOfView.yaml)** - +``` + ObjectController: + Controller: + name: '...' + Properties: + Property: + - name: 'isEgo' + value: 'true' + - name: 'pointcloudHorizontalResolution' + value: '1.5' +``` + +## Property `pointcloudVerticalFieldOfView` + +**Summary** - Vertical field of view of the pseudo LiDAR inside the simulator +used to generate the pointcloud. + +**Purpose** - To address the same issues as the property `pointcloudChannels`, +this property provides a means to specify the vertical field of view of the +pseudo LiDAR. + +**Specification** - The property value must be a real number greater than zero. +The unit is degrees. A value of zero or negative is an error. The specified +angle is assigned equally up and down to the horizontal plane as viewed from +the pseudo LiDAR. For example, if the value `30.0` is specified, the vertical +field of view is +15° to -15°. + +**Guarantee** - Same as one for `pointcloudChannels` + +**Default behavior** - If the property is not specified, the default value is +`"30.0"`. When the properties `pointcloudChannels` and +`pointcloudVerticalFieldOfView` are both at their default values, the behavior +mimics Velodyne VLP-16. + +**[Example](https://github.com/tier4/scenario_simulator_v2/blob/master/test_runner/scenario_test_runner/scenario/Property.pointcloudVerticalFieldOfView.yaml)** - +``` + ObjectController: + Controller: + name: '...' + Properties: + Property: + - name: 'isEgo' + value: 'true' + - name: 'pointcloudVerticalFieldOfView' + value: '45.678' +``` + ## Property `randomSeed` **Summary** - Specifies the seed value for the random number generator. From 6f034591b527b680c21831337745e2463aacc261 Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Wed, 24 Jul 2024 15:22:51 +0900 Subject: [PATCH 036/304] Update links to files on GitHub to permalinks Signed-off-by: yamacir-kit --- docs/developer_guide/ConfiguringPerceptionTopics.md | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/docs/developer_guide/ConfiguringPerceptionTopics.md b/docs/developer_guide/ConfiguringPerceptionTopics.md index 5954258932b..8708cd8e5fe 100644 --- a/docs/developer_guide/ConfiguringPerceptionTopics.md +++ b/docs/developer_guide/ConfiguringPerceptionTopics.md @@ -263,7 +263,7 @@ produces an undistorted pointcloud. `pointcloudVerticalFieldOfView` are both at their default values, the behavior mimics Velodyne VLP-16. -**[Example](https://github.com/tier4/scenario_simulator_v2/blob/master/test_runner/scenario_test_runner/scenario/Property.pointcloudVerticalFieldOfView.yaml)** - +**[Example](https://github.com/tier4/scenario_simulator_v2/blob/487556437b448186e2de484f5130eb2b1d015e74/test_runner/scenario_test_runner/scenario/Property.pointcloudVerticalFieldOfView.yaml)** - ``` ObjectController: Controller: @@ -293,7 +293,7 @@ The unit is degrees. If the value is zero or negative, it is an error. **Default behavior** - If the property is not specified, the default value is `"1.0"`. -**[Example](https://github.com/tier4/scenario_simulator_v2/blob/master/test_runner/scenario_test_runner/scenario/Property.pointcloudVerticalFieldOfView.yaml)** - +**[Example](https://github.com/tier4/scenario_simulator_v2/blob/487556437b448186e2de484f5130eb2b1d015e74/test_runner/scenario_test_runner/scenario/Property.pointcloudVerticalFieldOfView.yaml)** - ``` ObjectController: Controller: @@ -328,7 +328,7 @@ field of view is +15° to -15°. `pointcloudVerticalFieldOfView` are both at their default values, the behavior mimics Velodyne VLP-16. -**[Example](https://github.com/tier4/scenario_simulator_v2/blob/master/test_runner/scenario_test_runner/scenario/Property.pointcloudVerticalFieldOfView.yaml)** - +**[Example](https://github.com/tier4/scenario_simulator_v2/blob/487556437b448186e2de484f5130eb2b1d015e74/test_runner/scenario_test_runner/scenario/Property.pointcloudVerticalFieldOfView.yaml)** - ``` ObjectController: Controller: From 768f012fad66c6717d814b17ec4e769323fe7efe Mon Sep 17 00:00:00 2001 From: koki suzuki Date: Wed, 24 Jul 2024 15:25:40 +0900 Subject: [PATCH 037/304] chore: Update Longitudinal_control.md with additional details for requestSpeedChange API --- docs/developer_guide/Longitudinal_control.md | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/docs/developer_guide/Longitudinal_control.md b/docs/developer_guide/Longitudinal_control.md index 052d1067486..1e5deb617d2 100644 --- a/docs/developer_guide/Longitudinal_control.md +++ b/docs/developer_guide/Longitudinal_control.md @@ -20,12 +20,18 @@ traffic_simulator has various ways to control the longitudinal behavior of the n ## Details ### requestSpeedChange By using `API::requestSpeedChange`, you can change the speed of the npc. +MiscObjectEntity can not be controlled by this API. | Value | Type | Description | | ------------ | ------ | ----------------------------------------------------------- | | name | string | Name of the npc. | | target_speed | double | Target speed of the npc. | | continuous | bool | If true the npc will keep the speed until the next command. | +#### EgoEntity +`target_speed` will be set to the target speed of the EgoEntity only before the scenario starts. + +#### Other entity +The function will append the job to change the target_speed of the npc to the job queue. If `continuous` is set to `false`, the job will be deleted after the velocity has reached the target speed. If set to `true`, the npc will keep the speed until the next longitudinal control command. | Value | Type | Description | | ------------ | ------------------------ | ----------------------------------------------------------- | @@ -34,6 +40,10 @@ By using `API::requestSpeedChange`, you can change the speed of the npc. | transition | speed_change::Transition | Transition type. | | constraint | speed_change::Constraint | Constraint type. | | continuous | bool | If true the npc will keep the speed until the next command. | +#### EgoEntity +`target_speed` will be set to the target speed of the EgoEntity only before the scenario starts. + +#### Other entity | Value | Type | Description | | ------------ | --------------------------------- | ----------------------------------------------------------- | From a08cce8ba2759c5ee6422387aaa23f19cf8408f2 Mon Sep 17 00:00:00 2001 From: koki suzuki Date: Wed, 24 Jul 2024 16:15:53 +0900 Subject: [PATCH 038/304] chore: Update Longitudinal_control.md with additional details for requestSpeedChange API --- docs/developer_guide/Longitudinal_control.md | 9 ++++++++- 1 file changed, 8 insertions(+), 1 deletion(-) diff --git a/docs/developer_guide/Longitudinal_control.md b/docs/developer_guide/Longitudinal_control.md index 1e5deb617d2..b51be59f9ee 100644 --- a/docs/developer_guide/Longitudinal_control.md +++ b/docs/developer_guide/Longitudinal_control.md @@ -31,7 +31,7 @@ MiscObjectEntity can not be controlled by this API. `target_speed` will be set to the target speed of the EgoEntity only before the scenario starts. #### Other entity -The function will append the job to change the target_speed of the npc to the job queue. If `continuous` is set to `false`, the job will be deleted after the velocity has reached the target speed. If set to `true`, the npc will keep the speed until the next longitudinal control command. +The function will append the job to change the target_speed of the npc to the job queue. If `continuous` is set to `false`, the job will be deleted after the velocity has reached the target speed. If set to `true`, the npc will keep the speed until the next longitudinal control command. It will accelerate on maximum acceleration rate set previously. | Value | Type | Description | | ------------ | ------------------------ | ----------------------------------------------------------- | @@ -44,6 +44,13 @@ The function will append the job to change the target_speed of the npc to the jo `target_speed` will be set to the target speed of the EgoEntity only before the scenario starts. #### Other entity +The function will append the job to change the target_speed of the npc to the job queue. If `continuous` is set to `false`, the job will be deleted after the velocity has reached the target speed. If set to `true`, the npc will keep the speed until the next longitudinal control command. +When `constraint` is set to `LONGITUDINAL_ACCELERATION`, the entity will accelerate to the target speed with acceleration rate you set. +If `transition` is set to `LINEAR`, the entity will accelerate to the target speed linearly. +If `transition` is set to `AUTO`, it will change the maximum acceleration speed of the entity and append the job to change the target speed of the npc to the job queue. After the npc reaches the target speed, it will change the maximum acceleration speed back to the original value. +When `constraint` is set to `TIME`, the entity will accelerate to the target speed by the time you set. +When `constraint` is set to `NONE`, is will append the job to change the target_speed of the npc to the job queue. + | Value | Type | Description | | ------------ | --------------------------------- | ----------------------------------------------------------- | From 935d1f4e2f2e630f3e928672c974e729bc43ac85 Mon Sep 17 00:00:00 2001 From: koki suzuki Date: Wed, 24 Jul 2024 18:05:22 +0900 Subject: [PATCH 039/304] chore: Update Longitudinal_control.md with additional details for requestSpeedChange API --- docs/developer_guide/Longitudinal_control.md | 19 ++++++++++++------ .../requestSpeedChange.png | Bin 0 -> 333205 bytes 2 files changed, 13 insertions(+), 6 deletions(-) create mode 100644 docs/developer_guide/images/Longitudinal_control/requestSpeedChange.png diff --git a/docs/developer_guide/Longitudinal_control.md b/docs/developer_guide/Longitudinal_control.md index b51be59f9ee..f886d60ef48 100644 --- a/docs/developer_guide/Longitudinal_control.md +++ b/docs/developer_guide/Longitudinal_control.md @@ -28,10 +28,11 @@ MiscObjectEntity can not be controlled by this API. | target_speed | double | Target speed of the npc. | | continuous | bool | If true the npc will keep the speed until the next command. | #### EgoEntity -`target_speed` will be set to the target speed of the EgoEntity only before the scenario starts. +`target_speed` will be set as initial target speed of the EgoEntity only before the scenario starts. #### Other entity -The function will append the job to change the target_speed of the npc to the job queue. If `continuous` is set to `false`, the job will be deleted after the velocity has reached the target speed. If set to `true`, the npc will keep the speed until the next longitudinal control command. It will accelerate on maximum acceleration rate set previously. +The function will change the target speed of entity to `target_speed` immediately. +If `continuous` is set to `false`, job to accelerate to target speed will be deleted after the velocity has reached the target speed. If set to `true`, the npc will keep the speed until the next longitudinal control command ordered. It will accelerate on maximum acceleration rate set previously. | Value | Type | Description | | ------------ | ------------------------ | ----------------------------------------------------------- | @@ -41,16 +42,22 @@ The function will append the job to change the target_speed of the npc to the jo | constraint | speed_change::Constraint | Constraint type. | | continuous | bool | If true the npc will keep the speed until the next command. | #### EgoEntity -`target_speed` will be set to the target speed of the EgoEntity only before the scenario starts. +`target_speed` will be set as initial target speed of the EgoEntity only before the scenario starts. #### Other entity -The function will append the job to change the target_speed of the npc to the job queue. If `continuous` is set to `false`, the job will be deleted after the velocity has reached the target speed. If set to `true`, the npc will keep the speed until the next longitudinal control command. +If `continuous` is set to `false`, job to accelerate to target speed will be deleted after the velocity has reached the target speed. If set to `true`, the npc will keep the speed until the next longitudinal control command ordered. + When `constraint` is set to `LONGITUDINAL_ACCELERATION`, the entity will accelerate to the target speed with acceleration rate you set. -If `transition` is set to `LINEAR`, the entity will accelerate to the target speed linearly. -If `transition` is set to `AUTO`, it will change the maximum acceleration speed of the entity and append the job to change the target speed of the npc to the job queue. After the npc reaches the target speed, it will change the maximum acceleration speed back to the original value. +- If `transition` is set to `LINEAR`, the entity will accelerate to the target speed linearly. +- If `transition` is set to `AUTO`, it will change the maximum acceleration speed of the entity and append the job to change the target speed of the npc to the job queue. After the npc reaches the target speed, it will change the maximum acceleration speed back to the original value. +- If `transition` is set to `STEP`, it + + When `constraint` is set to `TIME`, the entity will accelerate to the target speed by the time you set. When `constraint` is set to `NONE`, is will append the job to change the target_speed of the npc to the job queue. +![requestSpeedChange](../images/Longitudinal_control/requestSpeedChange.png) + | Value | Type | Description | | ------------ | --------------------------------- | ----------------------------------------------------------- | diff --git a/docs/developer_guide/images/Longitudinal_control/requestSpeedChange.png b/docs/developer_guide/images/Longitudinal_control/requestSpeedChange.png new file mode 100644 index 0000000000000000000000000000000000000000..66a7e96bb5a6108d4b012c37b141f73613d364e6 GIT binary patch literal 333205 zcmb?@c_7ql-**^ADoUuVC1eRDAro4VUCF*iB5TOLjL~Ve71@_jD%rE|h6-7Sgsdam zSh9^}3}fcKess?JKF_(|`^j^kzjDg?UDx&9zn|~&R9jPd|K4MJckSA>U*+1>8@qNf z!glSV4W!!*{$`emxdZ$`<#t2)@~)gVj;UR{cy_5=y>!!y>gOQ+fU{1OG?_Dw&*b6r zvwUxZZ@6>?-?$l8I(WlWQ1ON8sII9{=*hUIb{3~&@6WZr`6AMEx1H~}gy5B=1Mc^} zQz*D8?_{jmMg_WaDG7}w1XQ)n5aoOge6tB=zS-`{J?nn@(Y2F#ny_?|j0^`BH^vuAEPJe%La+ z*7$Jnh#u0lYNeuBeft#XuqJm4gN8GB#sBd||MfJa41HF#b?*zq=+pV@nHCn{;-|hL z5w{Ij<3yTYhk~QdBVB94v9!o^n(4p`DF@!uOe>Tf*w??N81V1t_FqrgCbGBGjT5>!lK`Pf!q3(>o zQ|dsN0x$ASbr>cg{p9w+H72w|WJJHM$d4ocgRK1R&5z71#zmS%(_=-Fa?7VPhzFH9 zUWl2L-pg_OV5%HgL&qRu@WCQuzkzj>ZiGeiWnY(D(bgT0zSHe9;z>{CCG|C4*gmnH z5BV|H{Z69ztt^y<F+D^q{pO^svBj09nFb+M!|X5d^^svQ%3Al7=D94ITfX6Bq&c9 zaI27@F&2W+g+$ea2P~(;`<}Q~ys+-2>`U2nRijo!zA+2y3QiOMMe{_MP<>Wi-UG}I zna_0OD6%9*;94%4yiQ!{F_%wk>=r$tU~v|fQ!!UgYSapFJ>(}d7=1Otl2`l`@{Oiu zegFHH+lK(g<0+ndB(J%c@ARqnPb`dyG_$gSgY%n&h@nzL-)-fJtiX3;50(CS#E!R> zc;@)!enP&c!2U>k`ujZ3zbWSm{Sv2?b9$k9L81SXCHjAP3Mo0Sz&$$`*X0{(r=!e$ zrrzEO0fLcYjSLp6mJTmY{T>Ze`0We({nlP4u!!>Su8JNfw$BqUrhe;^5jgB}bVYE_ zuPgkX(LmB4@=}eqW@Hmk=Jpy!TFKIz)Y36cCe={w;dl?zbLgWSxJ26(hQU1M0{&_zIc^KIs z@reINdVzhmKE?fqc*GA-qc#R`5eh9L%}(>mS0=b%s?;hMIUake9o;sC$TrwB$~+5` z$uSvX)Xw;ce8uMF;c{ac-zy#H?26U)do=b&v(Yk+0Efbz)(plg_j} z3Kk304crL7t>Xys#Y&ny?WV{#2M&<4pVMp~XwgnxN7>j*H#b+KX17CIuxvIQQ>W6g zgu`$zb2t(N6fE|^L@R#gpFAP~ytywnv5W?J6;RS@!AOvLn{4f`6c#Df)IpIhk>)$} zZbzt)#^80%RV&>G(hMpR0sXxLKJAw}SsQB@Jt$5+`${A%M&ZVus+eETK#oxSX<^|# zHClIfc9eQh%>(c*M!B^V!x8YYNdt=?A0KYX2ZO+?OS<*14*hGMy{~sXyHlPqP*cBC z3NWgmW;&utMa6cyutsz0Z6MiEI$?L&i7h3gVHTI09dB3b+bMgD6l%WJyi2V(gIr`~ zy4Nu?VZ5#ZTXr5D{CtXYiygMcHEV^9la04_XpSF&FW>C%{9>vQs31&DE&8Z@7WGHV z6xPW5deZj$`LETi-9Pjwu<6>4MA*WQ7N)Mz4)apvYu5tQ80~inxz@Psyy^F2FnCMh zLIML9r=En2+>ZP${o9s0Kt`l06_pOJxQi((eaP#;z~H9yJ#A$ANvu-dkLNa9&u_m% zHQGtu|9Rl)4!=CdKo>jx;}16#=Gfcd&V$Y$-hPh;9E@P+u@>0kAPaSUnq%nOMD-mJ zBe3Q?tQUD(WN#y3!;0-2wRgRKyHPGJ0E|jtGN0H?lJco%!pbzw-mqBP}cLWtS7OVM={=d7$e=mixtl-Osbvmts zYS!rKO4~8}3=}Bm16rRQItYbT$S_!l)*ko;H{TtK+y!vsu8xE?=41Z6Y%ZS@`u4cd70D_ZR$IaJNqrsL3CikMtd=tALuEDSb4Ulm^tKDxmSL z))vE*)N9thoqDlDvA7OV!ZPx^bxh5Bh{oeNw?yzc2==J@%W_*pRX_n+G+2hDG41Te z{CYt9Q2eNh{YVvNaN)eorVocrDCh5nhT#uw5t$#z+o!YYk&HVe^27-qi;TuME|2M% zViSOpl$~qLnR*RG*(o&O@aCyTgxWiAci}G05IiytxA3@gcr7NBE^__c^ z4!-;|S^)2s%KSD-EDB*T_5FkA+>f3R=K{7!DO2Ler-5l~eX8K~ zz1xZ{36$gv$D-h&-_eb~eg_0&K;(+1#t)rPNIAtbY#HPe@k1nooV|8={g)!2w0ba= zH+?V6a_rg8goBEjg}U*Lt=nfH2<@k-sA^eG=a_CDZb!S%SVte&y224=aO;2rbpzXW z@3*xOglKfJ$08eNpIx%}4uhH8uPBQ)OQ2paxn+NN?D5t$_Za}Q-`erAbBDTpLg)8dI!7Je6=Ub$?|zau7!%K;}iAsshh4Wl~; z>7X2E-IM66lO=`e~hNlKA4whCF#O{4=~>8@=9@t8`*M zHCkn~lPbJzAbE$k2!lm5;!@AQG7g|;I${Q#1ZPpJ=$r|#jFqid^xgP*N;4A=@jhpu zn?vw1F%8JOjdr%}F}U$JTlH_HK>RK>hT}DLxPQ$zG6=$gRW%WVRilvQ`UQyybeT`>wbH6+;08$TV+69 z75^W?O{Q~LpDxN?x||yBAEu1*qoD;7Gl`U*E*<{MMhp1Hoc+^IEBmm~Bc z<$6%k?$3JaIa<@*EsILtwjMu|ediiuOg(y=?jzPaQRgcve=M3sA)<8k8X2XB14-nK zd1o(*3tW1sg+cytN@L_hE`~{L{i1c-Qo5Mw+N834JYww=cU!ph$dhQ*-dwW2!acQc ztJ|9EwTuDUy_nq6k!M6Kd9~z)V8bb!n+o?llZS{nlzi76rHWpW(h|FYp`Y<{W3Koc zf+1=)eeqn3p(nT9&2I;*HSZZjVyt^jJ0oB0;XDGDIOsEtlh&l42k-yxF2Um!D%t&o z_nLc-v986X)IuK?CgbG$*i($HVVnVLKUDlrzpLtZs*v1zc#OQBY+_+e*vL{G89wb; zLXrZ$Rnp6_|mqQo2OrHR&rZ2R$m zvC`2n_OB-4`o%DqC(gSXAC;S!-7J9ebM3rp)Au0`70f2)F6iv{mcO|jaIeCe9N=acsB6%?ch&94n zpVC^S5Dv#*tL{)@Z|&}}jyB{s_h0Fx^O3}v%=7xwYMVdaa{*NJs( z=J2$Juc3j%R$(%CGzoKcinv5K%^UijeRtFRu>J&%RZgGDS8mnrS@n7W+&Ck0#eB7_ z{Q6|-Qp3eL7s2%jG40^3npFPOBbf=>^bP(GZyEN-^fp-VT8Az zpDLw=p+{J9ubG_qFappxjn!;`TX|=lgvVqjP}NEh!dZf?BtPMO1DXWWS`yE8%QuhD zUGbe@{luGsU@s_<)sshgr-3B0_Y-Ht2znv zObhrp=es_YCa|KXa1ZxxQ1#Y3F<}x%az|w1zqQ(bca-AasDw4D3&j*o9 z^B~gK!~XS(_*)58s@laC-ZksDQF^M$&9!^D2hLAP)55SW4V=VO?#)TV$hR?O7tn+u z-!#2Gf6^$oe1$wI03V4ebYx*$KEWgXwTiqxvt%7(dcJYA*=#jmW*i7|hHd|&@=MWW zIeS4uH2cu;Io6ijs%|~b(@5bSjmYB(k%draKda&}Mbm!Q=F@3k%kfRZk(gIZDyTTClv>IfviG_LTPKqT9`LJ2ToFk@Bn0@* z1IZ^9c4{_TS$ER8ngA2AL}zE>+Q^qyy~`4aZ?orsO9Q-`^aH$jB@s)sZP2{9^39Jh z=!rp*m(#QcZPMRHH|d+Yclo7;o^LY8N5qVwHhXjPhA{oW)T|tQNFQ?MNs0; zZFEuOa55Mby!+>a%HPKLJQDp^dmFvQ{HN3+mri_HexDlFJ%vkZQYfv|4JH5J;l8TXK4HY18%ov~I}$AUTGZh~?QWv5 z+2XVG@`W_{&GhRx8uK19u<-{#9^57z0ASLT0i0Y+LxER|6_}8cF3zldeX(X44dK6tu1w%I7lX}P z=Ft?g%wSH>l=3@KGzp(xP9)*v<-?0ll2Ye#zy*n{#ttv$ORxbt)+U9v*PE>;&+$lC z5AYAYP4egyL^SCnpVggzefnAP{9P?yBXWFCCBOXmOC3C5OvN~Szleic-8(Pi{2O1+Gl|Yj8As~9{l?(^h>jqN#!59^o;qe z*NGTJ^4R!DuviE-;|+}L|ODlK_~%lGFC1Wp#)$n8D$Vl4g=<;J4OBd=3@ z_P?FMY+J#72?|-S*J7SMZEPHy`MAhX!Eq#Uz^0wK(AR|mT%6(%FHgoo);ntM_^9+m zG@Yi`+KjIcRIR?`Be2bqB@_j>_0j^baQU2L)u}&5FdRxv?ubp5reX?iepO)SY{c4n4i9 zJZ!UQ;O8U&gkt$k>0Wo37~6xW=1p6evq!lkRgKEjyr!(PQ(B+x&)KdANm{B!zGMRt|QX@5k zts)G`vV1<~UK)#1LXB2kSp3Y)KHhP-h}kydrShvk*U@uy1$zP9I}_5^z;kO%rZo`2hERwaw15$5NYO0eJ* z-tCN~eL5z$nHVyd>l;PmWTjha<~T@4SG`!zo|ey+c~wb4Jae9v}PH=m!1qd$2(ai)apSU#CxhN zRta{DwS?|~=pJXKK!QmLBZ!zAH=hxlmWl2l!n(QZe!<4-g-rv~5|YTV@d_^yJ-5)| zMWucd>L45jCBLF5UFTc0F4Omc?yF;QR5Ltgoo)1|0bfN|WfaD@zkf(iDq-^g@cXUJ z!uBys{gVWP^fLH6QMMe8pOmV3f9Gk#DE(Qd`zYyEKpB~E-H^w(GQZ4BhUSdL?l6Hv z?k%i%X6bThgVr$GvFFlU@ZJ5NIA(Kjx4uya1!rC+_aHX)@qU)>`6JJ~LqF8>@pv_G zdaCa`Vf((4)BW4^Mwx^67ryX@ztpl{^A)2Bl3&dW=OYFy{Gk}kD%paO<~V$><5DwR zE=JRVvYM{tpD|Gd*~19L!9@U|G zyVCan*k&>8?MRIX`;qmvh(GAQhWJ80Oo#Av*GG`#yyahTACJ;+%dMDu?~SYdvlpN| z-uUYC@7$npn~unfxP8VvuY9Z}FAk-PGy}0dZ){O4nm0`P^*eYTZxAXNr>I~Ii)w=% z%_;nF}tF=*3XyG48dRJ$SE2iot7@;5nF+`UKow z;jHH-p135>iR)Uyck9?ZKYQ`%bvarGFRFU$j;@`3jxV0cso*C()y=`>L-CH**Qb>Y zo1?wTDFl6B@zc8kdG8h5bxlI{e7|%5%(B*nsW_@W+u2{30`i17%4!KZ z$!DTtD66R3ND>FRsr}9EP6`WA`etzrF-H#1T=ENOR5Ob}`QaON9NVF+sEfaD<7n;L zxSJH#Z|PladQvyqwmLqWW+vN4M=OM@(8t_(M^_>j(g{c8*!*qn-dlNG(aQ2cVI zzuvXoB}+uE)2xjo5~iEE?VzUR($>B{b?s++mv`ts96f0q07$Fe^_ZJ9yoczE-57#b z!(RX7x>OrlJSp|8=Z_93hU@hQJKU?uwca!hGNjS!Zd^&^W@>{5dQ#%IF*MJ_7uy>iR^?QqF zvI;a^2RE=3a(Qc=@en?GY+x(RIsTaA>w+Acxu1)M_V?m`r~U=C!_})rxqJjekP*yG zq(^{#!KA*COX|Qp=uCAMh!e1_`@I1?@7FMc`Y=?tcX6kM$ zUHTZ_?|GGVO>gR!PMnfmpYtfDi$0xuj+CKal`%J6_#&XIsTs(#*|?)`QUGi|=7Hs? z8dVO+N}5QY+m0|+PiZ)-{``1``tywAEDWan+|iHz(qiw`i^PubfSY2(^i5z`1{}o6 zEk$|xuBq9b>z<&1dXgBjp~Q3VjChG3CBdm&FkH+nw$X}Y;?^peX3~sfMTnU*BRfKi zGhBRA35!q+8Iks-#~8cb4Ii5IG0yr3cOI&YpE>cRWJvG8XB7SJFi*Llz!}FyTIF$z zq0pUAcj8PB}|a2Q^dW9@M@bFwq($azacONgJB1B1U7$K3LL`M{_`$M{uJ6#MI?! z^MJ{XWd|p}wRLCWDImakZ}>t&FEQbdY!l~x+nB@)X4K3*Xw!SOv?{)Z^~dbTAmm}H zC_H7Dt|ieMal*F9E{1j_!{jMt&oTh$cC5e5lxLgrhjDJ?f?pS!8 zE3>m+wb^a3iE8kAa>nVQSFV9SI+VFh-R%bb50cD8oJnRZekSTX^*Zd%l`gJ>!Dh>^ zM+6H{zDeXZ+4;mVUie)3Oiu5H)Vg-H2Z(jEeSKu9YN3Q85`G%M5jw(DJsOqwh8I3D zYUPBMAI`*e_g~0HoCy<=qZn*fM9t#lDc-K8Zx%mslRx};TeXiatgG=;hCwu)gR^z; zy2*jzuys>sUw{z47!a5{n%RqTYm-?KjTA6!e70##A z+4rZ`TwQTaOZKtD4=LB&mFe6z+$k@C4C5cY#n#@8)c95btvw=vtNI=sKCO6 z6k4WCPVZ87NvNB`y)02g^XZar!an(w;RlSGEhpM5hPpAhC4l6KV|`|_m-e6kZed4@ zg&e6_vE3?^E2_jLgI+MDx0LKtS~m{iA^%;n_0Gc+gIwGM*=EX5&=KA&NuBH68fx1ImN!K+Ya0)i+v?0 z_D;Z9HmdQ1hc~lqE(#+?m{G9}dpq+o+%x-iQ0w2`B!=oa zho5U6pPtxT`kI3NT;2>)jpA;83R@_%{AtVNcd(P1FOg>)cFlxSk%i0 z&X6QvxSUsC0j%Z)#-Qi}spTU`r&sNwqw-|TuFD@gr+6T=4C4Oyu08|Bq6A~z=ek*+ zzqbJ+7NUF6s;e<0+awv_)g{w~@%|v9X%=qb0(ifq_ft+?VHgF6AlrB?f@OD%8A zpAEN6`ZgJ(QCdW@uD1|MV#(L9Ln$viOrcT9Sca$Idez;RZ7q4O7VE&rOSrwq<3Rq4 z%1Yt%Mz4(o3u8{tliDB4y?iN2ecpJ`vTnRp3JVV(CWEZ~ba>zwx?Q49RhkqCqlloa zbQ|a9lUbH-l1ca&G+bqL)*0bTe3_0l-cMHz0`kb^5$^%7(a@;7-Tg=B?eh+tH!3Ub zU&&4Kd`lXK`~J*Rt~#MHJ8!LU?_1q#LwJuz@mj>w{BbC(YC4$#%&0pW|8XkG*db3b zq9@#Mj5kzszB%vp;4IKol-0^-st6=DS+HvA%? zyfhC&G(JO)&)KNYm3+b?-EIRo_2+LmGb z^JibKE-sq5uenDUJwND4k4wMkE2pZ5~%Iy$6OMHk;>& zxOKG|XcSMfprAmnE3t1LrxS@h?*YsL_FB_&Yy0xhh0+S>&k@^amLXIqYzgr*uYv!rL)mzA)LT1A zp0(#!4yb(X2jRF-r+wklbY`yR*C(qEpot_Z=6(TLcPOQ{?FfzqOYvTskd&_Q6oxgd zRabs>gRPcSQ~}gny@}asC?lJLi9`5uNdc%viK)%$h%J;Ros+#-vc{1n&q$$DJ+RX} z(+Fvn_1YluiRpoTqFgig16H)n%ny`?KAo-V^Et}IQENQT(@Qt@o^9bm6ICq$vUG2V zS>*?0UG8zH7>_o_8|39lcTo1ouU#r=eix=s3uEh?T6W7C(qobCzA>S+{AO>#D@QNu zEHP^4PPC$L6-ZeH9IwO5>e$##093+>?oj4*zZtP=WS=dWcCMK!WJOPx8y7e{>1;HZ zvHlKp4`xo_1LRTh`wH_$`>|w?8!>tYw;n#ykD)mWfd!IqbVn`7DV7?mc#o7tiM2lA znX{zigRE#GFUYwdJCWd}IXK{xM9#>}iGR6)Amb2yZDat4#=kk}0g@AKjSJbkVe`PN zs`$)im0on~v=!s!uCp<6?!x7}2&_0ykh94m;fuWOMIGIlEJ29X0u-O#57v#o!6soN zC}Yc3e+^iI{5Bl4z4ojS>kNlvy|0oDQ6>(Oz~2S%*{gw;O7F zvmGG~z^lb5Yu|)f4FMd?5xp_*hm(!GpBf6EuUzUQmvm~%@=bkXm|zDC0*$@}))Zh` zJfG^rF`%&#Fv*q5l5bSYe_DrVZ@$q7ua-VZ&5T<3LtyNnx*?hEQmMqs*??kpCXP#0 zZiD9s?{|(t$9Sr#)UDkCX{ct-#gQkx$IL1$YJ57=Cz35tZX_FqLAA8Rfq$H>@hwN(6`p@bP77O!>7r#8Jfe<0a& zRB$lW`+g#I&?r5}{q{>LoKQRTlEKlEN_SqKwOFe#L4p1yEQFfE^#p}AYvjkCUoonl zhoH5wKE4=}vuI#@;?1zLfgmW6lcs=3u6?l>=y8C^B8?5eQfJG7J>?{;h!l)(q{T1>D@ zT;@F^sPROl9TbafO;hfCbqE)@T5i6FDm}T?LSVmCeEY?WhWgVyULCI$C8^{=%`(#) zo(gcn%#SSnNV>_Y(J)!NCVgjRn9s`x@DtJ{y?QK619l3_094j-!+@kKulIBV*=tc| z9sa#I332`d;WRa^Rn!W8dTu4TaeXEi#qGb`K?JNakir0KX8%>QTP<^N69Zl(G!M!X zD3NW_!$}LDAoQd+>Ouzq7)sx~t#UsVgwVjiGV6h#x%53&HW;HW^^ z#rQH0ZICknw-`x+I$U*cY7jO-kG>{A7)${;B-ukxcRnB?eQAHd|3cE=$NlWHIGgH5 zyQHbgxn>q^Z5)k#7;iXi^}%WY$oz}X86M*{Y{E3GCD(y;MV)Q7o>?Yl*E+nM;R{B3 zG=xMzQ~axexv8{c>A(xUn%xb9LSkLrcR#8DuY|*S>h-2?%i<~lYLM-V%?KP+6D@l) zN1WxFbYJgaEwt)rE7QGH1Q;kk=Mp}nQauDblCE43Fg~)t_~1&0d}iWF^+Iz{HEIb( z8WZr&`s@eVsc|k&-u(#5W~BWd79eW^Y$#{H-p?k*0LYV75%^j;5pQo7afr!5L@&$P zU9M!!MkZ~mQSNsQ4%;a$564Yan?sZ6nkFz~k|ohwY!ZXRZx9MZeDz)#s2r0lsA;fh zklqbzu=4)IKJ*-3A=zUhL76e9T-f+*$@jzcV*Eve#aEqy-=CfAA6i*LQ7ZW{<7Zn| z2zM^=CPhkHXb=f^C3d!QQU_7edqI*TkJ9=U{x;f3D4kKu zZ-iM`e?2RM`2iiBXzslWI#}7wqnGLrdYKp1sSb`W^X@7%HqPyYOrjkgYpXb>+1zEP zu&|rm;rZAMu#a=g-TQOrPx7pdMQUl{kF5ZY=<#J9KyHr+i89h6RJG=7AKC1huCx4< zkDT|BM+58D^=7F-o}4$aOixdjTyxw|Sy8knDeREjPI@U*RBQgI6JptTq&qz9T5~xj zfO1KY$?F}dapSrKgWo=n5PN_)Rb>_T*)=Zp+o1gKpuPhG5z7(m^UZeV98dA}zHF|3 zFePG-A9%Ztg2rTSoiD#mhWbXlvziQAmY`bKBLXMxf#TySjKpjhDpD{7k-7A-;aPf~ z&jQq=Q^>tI1P5&lxne|tId@jtvSOE{T3pqC~=z^uC9H2iT8hP=4n6Uz7EQp<{D%uKXS50 z^Cv-eekIF>kLUyHF{Y7vQl9q@F`1CRM!$ayW)_kc>~5!Z-^R;3$L@nh!{6@#nPrIm@Vz=tcsFl*a2GSeKmZW> zkH(EN5-NU)0bzj9@KmUP+PLKVEtM)0sPVpBWF+*u0a+6v_r@ zCI^zU9};A$zr3m}cc_%rH}kf3U7;69d|oJV@MKRjWP;p50yl?S>b1+vjwt`I)FxY^ z%W^!(^RAoR8RqesaW1}@ArDFgObNJ*N#W)9gZyHw~ z?A@x`MEG5e6D^;7?dp+0CLRrUfPk?i;XwLSN zEicBB;ohnFZK{dz&bA0w$=@_U5F(Uf1eCyz&G)g^@Fy1Lm(43BU0B3R>s~kGQD1hkQ*K56>hA2D2KCF3KrV zx<`V^?N=DbXR=GozCPjriE?8X)ZP|3x)?AB^65sIL6Rb1ljJs=1PM|Q%+&9*Eavxv zA+r42OyDrUc=*b&AWKM)2Y%Xdyvz#^m90)zd9eXtt`frN%$HxY@!^!r`g-R;a!LwE zkVb!^C+CBKeG0djw?wZ4fU4SSBPYN~l1DnoF4+4SuD96{Fb!%Li||uQ7OPzN7+r9T zsxI8S#VX?5Zr~ZLNKj`|WAm8?j!sv@JDLM`(~=_2O-Cs!EO;@tO&FBFnQJ+-KV~Ps z;n-fFFV7olj~_HR)0~e!EYO8nTMY^kg*(pBpyiH@+1*pPfyCI1MMlSOF8;-G~mp+XT7k*-tubkZ|^g#v= zBUFoyF%4jF1)!-!zfNGmD6kY>JOE=lLr~v+My-B}1A`!%@&6zUF_kMzYpyy++ zjM0V1nEb$l`QCN(fD$9xxc9w^4PXrjx^wOE-k>R~`;ECXgov5D`B&}gi#umoG(93c z3EWDu%uS-i`m+(@A`z69bjQoaqiU^IMm&n&6UN2%XAng9(j{k683(^T-P6S?=5}l+ z8stvJ%xYZXIx!5ByO|6dnwXb&k^tuIP2)yK+im=H8P5UG;3fl{Bc7j$|=|K)bmCbY1vG)z2{v9 z4Mix+xHyjnOyi;0_vBen;cp}W<%ClgN1F!_Nsu4u&t0=OTZ(_P`QB)A5d!L5+dzzq z)w^ePTc|HxziL{S_*5V{77H4J+?NcYD(qe3-t}L7Eh1r{E3)b5Ccs)W+JZgqLdXYB zZ`J|mL(Xi^(o+`0V8_{4kGYJZR^t5+7FGg0OrS^Uf|^*>{noNNPPhGELe9yNelQ9U ze3w(Xldz!UrEUzjEJJ-Xc=z>3P}82|-MR`xxR{)Bij8nT1l_yM?w1;P4k4?V)ET3L zjyAFzKMR(iRtDl8xdkMNw1mM}74>Fh1AAIpOnN8^FkD~V2zSCDG^F`1!Rf+Eo#5g_ zAp}6FW|C!l*4c#L$DsV-oqEN#?9GJGLQBO-2nJjOuER35Gp!o_I&#J)T#$z9f4Eo-X3%x=+e-}E3(i}&6pt-Cuk$ZUB8>gSj z$64_#sGo@>q)Hq5naB}9<*oAnf^JO)ZRRkMq6$TYhR)>G!m*)##}d=(I#%P88^_-E z&jx;1A_#E@2NqgdT*>;VFLv#%pJM@5s`qx}$=R6d<+lKksvsRaRXE_<%tsiqO%0tW zG_tjRq-fa1TwrGQbQwwsThn!g&8l%1 z=hJ0!hr&|B0IK&pHFOQr zd)bgB>`tY(T>ZOZ_J4i|ifr7VLa!3P$k7JEocIm>*(WT?lu>yyZ&~$q*)u>8s20Xq zTt=Jk$2%^Hwq(^C2k4&%1>Z+85Gb$J#3Brr>gzK+E{$gqHes6~0WUFdqrwk3`H69{ zLr*;34Ds`Lx$bswe0eV2*U)Ky#WZ-Wv>( z9@d(gbjvzyc+LRy@dVpPUH`KeK5jL$PZrxQ3fRvNCdS6!IL&_G0Ri~>Rj_ch# zO<;p&I;Tw|loecw{s7QNm=H*DGysf$e1=DQ-}<880U!tQHcLtKel`;azmcHY|I(Ue zh*xq4AsJ*9l08spnOo*`r@@5gtkrmrE9d$TMuc>vLxa3I86P7s1! zO=P61wZ{Ppn9*_tW)`jgGt89)+O;#_=$@&D7>1WLms0(qhMwzjsJNs>Yl-n)T@c(v z+$3P--Bj@fNrA&4Ugi-)&wy4!hpiEJl>(C5w>sAkcVQkq#w=1fDErM|dn?6dOHLE_ zF5M-(5T*`JhJ<~8iWwMC#7An$f%4K2N-6UwbSteks9#=aW~}96KRsQTeFk-2YO7(P zZHIbi!Gga#^*0V_^jC7X3V;+x)|AL-Fx zobc*A zlBJNAgw@2q1P*`E)?K*n^3~V+U7DvJ?Ps~sqnODr=}l{0xdHAGp|0%?u=JvW_&X5> zbz*rZ%wX>hb3*W2yhLV`x$}5seDKWACp>Xb@KELntANTJS#EV+v!d|~rLlKi1*UPI zSDg=<9Lb!F#v-#zhAvRPD9c4aS%VHTmd)heCGrDq5|2E2ZFEVhdNGvPB%EvFrjck2 zYW3B4p-C4E-Ey!P_Y>U<5YR=kk>4;3s6T2mwrI^T9(8<_#0G|7_tSKpxR=YJz>(>w zWMMFNQO{}+fQEMYpjY41fF@{T(eHJ*@SZ11@=J4`Xy55FsM1FS#iAJH=gwJsNuVZh zr+BMXUI*h))TNg&$hL9|Buf|ss2Ho$s+ob}dZSyCy~3R=6B9q~*If0}9|rqg`_(Ov zy1``i9rtkF*KRF4IB--rD*(W9jp*gKV&hQp{$`RH*hgU3=HF~QbR+8L&uX(Y^8@Ok z`SmeLpJQh}GixR89S-01gKkWI^}AJC6H7y|-1Q-lN;sd#j57jr)lhWso=MJQ7c}TR zI~$&|LYEQ-H@)AXs8iixc6eq)eJDP=5At8$aNq%%AC%%oxd^53p$Edbm0OS^p0a_a zG(+u>n%PEhW@#?-9A-z`moEG$33=Wx(m^$#!q%5Q6C4IDG_Y$6XL<99H(9N)L%kOD!q_IfH|OTgBDi4(a=KFkEaK3c5DV4TyR zZH9yYudE)O-@Q9GydzQav#!7eUI#AFm4EHYyvUxDk}jI?=_KFj^fbMUeHVD7^@M`E zPR@*1obBwC&7`)RdE41YraO_)d*aA@j>O{4)qV`eTpxx)!cf%JKTd+sL-lK}5F!m2 z&IcJ$k|p0QgX1>@;*Lg|3r#nwSB&Cr)2ZL5u-2A>y0FRD)ti;f?%~S2oM3(D`%f5n zf-a|w1kD0pr37ElLoZpOL5_&2eDmYt39p>Wl}rj}ci`~CWW$mS=w3Z0mymH`0W?Ls zt-4f!7&F(`9|mVFDTCcsQgD??fm5?ql+}5ip#BkT?LRJTZb)D~$YBmI>B8jt&)U!A zd^fE$%V9_nIZ5$IABqL*H>yF8LrbG1o{cKMwYcmX z+A`kR>l1rllQ~Qiif2%&C#dgPNlv`BUUY-4vz7q6mNi!<(NkwPD`8v#XfTKcjV|#~ z;Wl5LRwaTyTSfi2lK{e(BOi(kn_LH-mR!?zvJ@j8O4J9w9DQ)`Nf-0H)7e`ai6YI( zJ)eH^%_|qE{7ChxG^bLzB{2zX%oUjEw@jVTWOH2whpPJ*dd>IIkwKkUKe8vTCRoYa zkzkPZ(Xh?UMYs4`ZUzZ-LWUK30+PpXaJzmvKFew~)+Uxf_`n&tyZ~l--|4r81ol7k zeD$Nc6_jYFn_))&Q@qcAg5vm1v!eLBRlZO`8D(@dzf0H1inax>nqOB)3+q7`ZFFjiZ%CJtW(j1I-0sp z>&x&+i)I<|m3rlZUmWFHq?J1OojsG2trK)rLS4^z2C+(ULE|cO7>p6S%bw2lW{&-p z=X{1caTglEUAXwZ9@R-^JQthge?43eCOQMSSJgP2T8a1y;9Wz-U0S+>cFP<<*)qRQ z-ZwwPQ<{jO(+;)>HFJOpL(Gw!9^a3bY3LFwKzd810<4d#D+S6l!+Ek?hJ>b7%QhD` z*1*KUUNHiIbfdVzAPN!eNr-m_;~U;EHl>9-unwibiAaE^rn7kQ(#->-uK1&ARZi64 z0}lmce)02VxMU(U>XXhg8e`@&mF}zf;XBkJ1VvwMyxM1iZuSp4fl@{Kj1^xuU9kz2 zAwm!|;s=AdL0P#CdL4Vq?0Bi|zzog}l%8>r&8`N?h!(B0vi6;<8=RT(Q1nF1Yv4*y z=E^9B9+45CRAUYAH<*$P(%{{dUs}Zeyv(-ab){b`s72pU&$mZG_3U)djPHc2DSoM^ z>p7s(*%H8h1j5(L0p2^Y*mgB=87jav2z?Sr_OgW5Zb+%Vo69pxisw%7@bMJ(U0hDPw^%)=3D{(aiec=U0Rp(^pW6&gPa(79!Bm~gONy-IRKGZM7 zK%E7UAN^)Zzb=a7(iZ`h#*1}(U9fBUv7kHE z_Pn{9;c>6k5jX}+h{Zwxqs}Y>X4oJL*NI6D_a-l)P+QHcVpYpuN31pE8R)pMNTWS` zYGkd>OBY1>{yqlt|NWb9EaJEFL_=w44jYI_90@MPLW>o?0JrdEj8-1Ofr|}4kgC&|fSZ|Lq^NN7M^hJwv#EnZ0=_)%YWASJo zxAJOYpGuU2qg&#~N2cF&-cFIPu=M%I&w)0FR zMF2XK=gfa{sF!)PHJgp$>PO_n2uez8D4Zgt+XuA<-G>gPGg>3tT%vUM+K<|8JNJ~w zVD6lg@jxV+`+j2lj^-a&K%S$Q@?BCJ*}BJvusi``(@$kR5nw^fM=-(mO=L z2ZD*q7Ghj;iXM!i!%t|C1KM5ec2c3GyGa-O!2oH=hP;a$+dT5NaR9FxSaT0-SNOH6 zU_j%Kf$dcV)eO)X7u4$YIn(%e0OkZLJPf1{W;x{ndRVRvg;!&~cwC`|)q|=1hXGsT z$9ayXheNjdCtEZiS?n-8TRkl;xf3iLCInMA$Wq7)t|?T&2eddE6+!d)+QK};m*pia zs5Xsf?eA`Hs)@A)bL3&lHjQf;qu);cf0gQA;PCI6fSys;iBfk`1C+g^;1f&oE@TcE z-ruHFcbAlr~Ml=7H8bznhaB{w3QfpC<@h?iH%!!L&Ko_%s+>-9({Xt%+C&TuEq;%HVX>d4c7 zGNb>t)FsvJ*_zSx;x1+ZhzHIi7sK#=@-eOrm zDM7FrVp)QQwH>XYYL%L}^^6q7e?&DpM&Nc((KaPLFpy!hC6IR6Sp$1RU|Xgd4}s-9 zUiYIzaxZ9VY@5m7^8m=b01_6~{&_ks_a#n47!$!!qwfg*@TB}I!p=ZEaG5ud_1)B{N*_NzZ{|vo8 zoij8xqhmVa_?IbBs-Sy1GK_@1qn#7hd{#YQ zy|I3drQZ>7-3Do^_RLW&+M1!L9JVg<{9CO{0QTjtRf)D5Dd*(C=EUraNFc~VZ`*dV z)uoUh#IE+5ZSm?z`NIN=STHW1-TKA@I7ZkpIupd^%6K)QywSlj$|sOoh0{UXlyiIA z8I1pG${GSYg`wfd2pP+cT~=i;KmU;O6j%q1 zK#pWvq%)g^vv}`*m^2UR3_B-s$kEg8C@1+ITp_Lcr{FW793*_kO1qhV_$6EY#Y{N#V z&V^scvTX0i!`$@(&S~OhQ1I`*6tdPDApCTo9$UD|;9!<`xa#9x;jIxHYtbS%@EL8v zg&G>hF{qqZHa~d(uj7S2I(q9r$a54_ETX^y*u!7}EGQ8Y zLB*gCKV~NYY-Jg>)Zl%c>OQ;7sEvNKwIQoxaA*w=EMi@{%sDOMmugD@%Fi1e_xg{- zjb5Fh@-_UD547LGxpJ{Sj@TIha?cbcp1vob`21m@r+&V|&Xj(iHcxt_BumeMZB4Tn zfi+REoWs)AH=UD0a+Qjh@Y{jgZwdRp5-94}^c!<3g&h#qihybdcu?!RJ;EO>EKWt; zO4}w+A^o}SSKx8x-N*#`!`G&*m->G0`*nc=*rEGMnzg1 z7V@2^egN)shoP%a@R#z(GQ6aqWWOMro(#zzH4n8tx|6kDM_fT*{Fp@5IMhy`m1y1j zmL>A-5}4AJf!0(n8^zSK>Zs>lbpZtgMGsCp$UhT>6dkR z(sP*?nuLBW6mGwoVky$!Q`>lC0CD8w<-Vdyw_-nEH$^~(CtC;Iw)XJPfFDH-hVEy5d zGvG+&pUB3!c6#{5=KNqQVeF5C+M3%HfQ0`3F_ZxW8s{UFsK?*_ETU4b+9 zZ6DX8Iq@MEt+pSD)SRjL5N7pA(%gFfR%@Ey4*V{_^gfQz$-@n~Rgt=&)7CoL zT0mnD9R;khm#05m?2~mtJlcJ@O{6&|E}%y%F@T`Y)fBDrj_wWh_#z5R8~R^%y}wD_ zgO+3-?ot2ZvaPVclOd*9fj7(YZ?DJO$_W09QEFfeYa4wqc|XPN#hAb2<2Db8=e_KW z`Lh?`R-XCSxxa6+6%V5(SDz2l(vABq(*@lM>@bb}Abp$h>MvmO&r3qgRZ^|N_9#ue zGy=!{JC_8%b3_B;^io;l-}@75?$Lo~--GWd`yI8|{vE5+fQ<(7W)J_qbaFB;5S_bn z!~p-BHv=D3h>rX4p7p=*Vq1n|E5Nr}2iu}{@U38|^Mh{u+`pg<3*dqtfG~fXYGCU# zAX~+Zpyc1ahHN~vKqzYT8B$gI9jV*;o!ub(8d3N@_;=Z}P=}HH9o4zsSpEwt{A;!# zZ?S@SJr)&K`FHi(2hnZ+26Ke`-|qeYd%O5tDUz<<325=jpPq-JvP_m_XD zhXLmsxs(<4_ot?804{X<>j>@uedYsPP~!>s7sZbDN8qJJ$nhOC2U$3Qm$tRG>i+k4 z0@7RtiuLW+hVS2DYYGm0Yc=uv{{KcY@TqzO@U8l_A40$1&v=9tyz}w6%9p=yzppv9 z7x3VeoTT^f=aRf2lN@<+QM~u>bORen5$5a}4aX(^1rh%K7U*v*;I!%n9GL$@+k3}T z-T(jNIUORDR7z5kku5~_Y1@=dM&Z~I+1V`(vK>1a*_&)y*0Hnam6cug_Itd#uHIMP zZ`bvCU*FH?_fI!*&TBlM&&R$$?vK$VrT_fO#sQFp&GSX1e|5V4BYh6p^@CK*tKZrF zV2c0c1DMCi0XY?2``^0}?jx`b`~p@)f82jyOK(PQAU$NM(kE&Wj+#^=XLB44y?S#J zr*A||m{c{VCcXL>jjSTyD!;ENLJ`xs{qc_r>VDY>^Ltw~1!fn)fB%m}*slHT@h|*5 zcKX_01-F^@z2Bl+4F3BIB6rW?DBu08lPW=Mhp)NcryN+zy)P6xPxucW6SK?x_~8Nf zkH(E^%DAkcxdOrW>iTJO6dYJ+H z&m?n|Xon{yK;MQ#MfFfp3QtfX8EQ|iMTni=;d`;t zAgaxbl7c^o!nuEqhBIB z_0mVo`PxqB_%DA)Ck?M3!f2FqVTX@YNh3>I`(7$xCpGrhzpLUPIH8759lT(=(`TLr z!|NYTAG~6EV8`Y8@gUJp2*tz*JJi}0dfyAa68g3bl$}=wxZE55b?-kO#l85%?pd6x z3Ik;UKcyF6bx{$G&;v}*g?*pW#`MVcMn0^@?{ zW*1s{$DIWC=i{;L?HO_$=wH7gHSavpmf8wDBI#GXk0%1JAngJWOeT`k@Smaj^?A>T zp=PPI#cIm{$=KAe=t)F=1KOox7fzJFz4p?H2tF$zS1wZN$M*2%j{ABj9yy64cN5xo z{PXYIu1h?5!0R#-&HmL&7hfLB0n9m@aiv_~sQ7a5H;nYJN0{!GyKESLB8y`D8z5Ar zw-whdkhf>1^itxTX0d;^3-z54Kga5_@5aBJi*0vxJ6*nH>Wxm{_RF99|NB=IGEk2% z)BDbF>|aUFt{0L{Rm-IRjSj{0>jg32kGynp=WP&axnEx6u%*R7>FY!SD?!XP5H4PC zx*Q&Rc?U@cK^%2DH+uNMugm-I(it6%F6>6RBdie%&=g6vMNH)QbMt;YH47;q^!7+i zA23_m2Z9^!QRo?yO&rUl8+k1;@aml%ue}%1uzM%$TQqn4^Y048k|f9bGJQAx@#@;b zM1t*9SD;nnF2ZfEy-8dpdNEzQ1phd7sH8{n_*7wo?qLG-Iw9V=N}SPYCq+boDL*u@ zc24oZ(%-E)1!@fxkqwsn8`4T6et>iy{Zl}Y1#0HB1o(5<{+rcK1^FEbbknh48BmEJ zd-5i6zBIpn^5-MCze8NLcS3#hf9I;u`%1Ke;wzvgyWg&57bmLbhT3-4w$PB$-#7P) z&7q6|j@XDd_-`n9S!V9D!oPm-&&|dhgqMBcDeyNh`*H@w2oisY_vl-@nZA`HaTuSU zPmR0@ogNBsosla8fyGgvUWXz*!G)PbjX3DZe^l9d`!YcCLuDVD|J_aVQ5$u-18u3A z$+W_@`s@mB9>2Z--4;5}ygS}oY}IJ)H#UcUVT+mguSZddq#>g+lo{BOF^{q} z)GmS|H;2*=#Y{L}zpl>Dl{N$K4y$-;Cq?*EoQLAdA5QD)sz(W0V?TMK-~9aQkIT)f z>UQNAkL*^P-Sj9fejTGo9LuR2$(0x^L9*j29`Z)CSbb)E!j6CbAti@$FzVK}1Dslg zLl#OX(O-RC_Y{&GlST$d^jfJ zgmOHFd$gfBsSSmGL;UM9&8iLz`iS$NeCM~s%w%mESSB@}LP5wr>gJH9=9fY8>qq}w z+xzHcm%2TV>i+uu=w9lePWKX2Kr^}RDY0j=QNKPO-6a(8pe3!)wLQ_llgRT~x>sIN%l`cKG zOkYP?l3IglIYa4Ae=y^@>)i27hFb@B7KmjC^g{QOh5dT9UvB(E`d!gPMJH>vfbBqC zfBz-Lv%g+xC>>MjO3;d(HS%8V;K7nq zRx%bx^)slT?-r4#gBZ*%{@Zf>@!yl+LeIJ1;{A28el=X65{7)r>FqGz-aRBG9qu$; z_4=tLkdLV!g2{N1E8K0xmo1XBI&LOiq#OLdx#j+8w*jEp5gXhus<^j6Fb^VV-cRuSs z+=iFTC{2)A&HOvEEwAeiZTAh=88dFZCxYE2_v%yJP(Ef_K>sqayjLbLjO|YIzS?Dh zh6B=+{C}aNd_W_vlxI-?x_5u7li#)MHO$&W2~N@DvYNmCg{}9{%1WH? z$&zZNfjjXvb&NK(1MSld9BZ8qe%+ow-)<906j{7Kv7<@&{SH+J38s$F7tCAong1GX zxvx`JUB*}@$VJ2~@eS7m)^erXZU$hz!)0iTx|`|BYgj*TzLKJzeS0a&uFoOCLa5VM zqQISS_?uj<-QKfN`lu0(;mjSk!TloQYFrfRn*R%11rO$qI^5`T%I|%HR14p)4}WF^ zHMWnqufRGXNh8-}KJt;2>`?N?gCu7u$ES){f%rNt6eN(9Xx7P7Rzp z59bbWe*avlfBVUSE_&l4!@{*t7)tc({WC~og@5o8Wv)@9Jf=npauz--%D6+dWFB(0% zsg|giAUA1$fI4+#6$jW zi=@6iE)T-new7!@T`CD6Qh?sjnBMnlHP5G_gltTnPk`({GY=LyqHTZ6tUrK7@iTP& zr<;6!^GYh<%qx?&6zXn6O{6Qd707y$9p}Hk3Kg(OgPy$o%6Vq$%BA-ml=JUswHDf# zBGlSRg4QD)Sx$KyFyu$0dlj7bIN!yE$xcP2fivm$$EQg$I3AM*(Iq8d_Q*LVbnlHu ziDPb%SYH^UbkG}ww6|-Ni2T?aR^_BOH{zrcr2<)59QwiZ*+2{08Ob9S1&C(KgEsSt zOm^sbe3r-cRZUW-M_Qp^`rgPY%;QbE`r=qzz0d@^4Yc{bfs=ftWGLjRPX3+V&zJU# z#;T-h7+`Zt5sJlJvF9`boI!UW_8cEeh*HrivQ=J~Xji2S;M9xOE^!)m7qy?x>lCSoc+4&t5{82t_wiZQ(cJ9xDRuUOooMR zs*m~>GVJQ;9C10Um-$^&pRAxo8nfISC;dA6Vp0B{)S29NZIh|4+(=e-Pn~3_#Q&8C z$ORtYCjaD)qW=4$x{DkD4f4g|B98o5wdIBhMYCV-FsKRe ziVNP=3~cb6i<`g)as!Fq##@tv{d8|xQ;Ry@V^5vGgmPoVEQ3U=f*2)t<(dX}71|`P z!mOe|^owa|^3rg`v79&ZRd=C{s*ey(CfH4MxnDI&Ns|18h+18k0GEajzOcxsiQWcC z7Fg^~RCgySv-Pvq14W$Lil2&yXO#UHk_F&>J%iIy4YHYNW5KN~0vG;uAV16x+QjoV z^gvs5XdhzcaTrlP*t)47yR3d&rLsv2^n+=N7X6 zugtfab#d`eEWi&_9?2Zgxh(-g94lE)n^WK<`l_2Xo7#&A9n7U8X1mprrX|dn-6mB& zm7HE`LX}z)tcwH<0zs->2H(hi6N+@v|NQu zSY>kv8yKS2nqXVWk`a2|g+k9)VSL6h3~uL)d_@p`!Ib+XZb5Du)+97F4PrCct$~20y)!<7t?H&h$6K z{<}=AGs#>yeEtu_`aTA?-9}>y(F`w}mxCM413SGh@AhC^Zco&~9tv8xJNOCr(Xp>q zCR6EaHD_NEdV;z-<1e>80a$!eRr}?})Dq9TfE)*6PkP&&_*5E8OO9 zvN}JeaSS)ikN<-AX1kCF!~M!axo>$eYhK^;gULdp9|;!ZY0PO5doXO;6!VZn{T>#( zlo`ALnlA}@>feX=UiBalK=fWTy_$|ZBM*ljuGO^Yc9_u z;^Si}DcH?{4(k%0K6Qq1*}6Vl&}4o2yUG05rg1>#=EU;~$l-Xd6!i;%2UN$9xrD`7 zHbjc*t$C>2Dci73^?r5fv7=wvVwb5#XvT%?8;u~~f%un``G*WJ-+=%B)q*s3qqo>0 zTSqZ>3f4^VoN3$VSuTwn3F*@o0LTKHeD|~-9ljatDn~jRTXdv$xxHEQf9cwHab51& z&z$YO%`=Hrq-#fcAXH!XY#S8YMx$KQdM$Dx{owzpQL7vsMdz=5B}GA7prYo6VAh>7t}hP4_?NwW&|}w@tt0w z{v1HvGRZWKzXj&Xo}$+iJf?S2HF9(AA?`(UsZwwZ8S!*Wf=^oloLTW#(^WFn(`P%& zTwUc|c&p-C%UHA!91)T=a+FQXHC*%XPB5Nf(srslKmFVckoCsI`HO%% zrvw)8*`gjYG`#NE%>aUm%H!70+Y*2zvbM{v>;>>Ega(yedb}?(7S8u*eT1m-IzQPl zJ_)uhXlQQn`&1;JKWV7=ovQJZ=UTBrM7i!CWuJe&?(bEg-~UTZz5C-@H-pCC)-Bc0 zIeTv8CipvScTZxkm(MDM4O4w|_3sQ&!V=3dd~Hiyf|*B3JZ$C=pyjTekuFPFdryRJ zPf>449QAPTb|@e#9fvXp5j|r9`s2*>9Tz4POo3|ncW`yg}&0I za#@eyNm{YYOQ+!h0jIE@R_=c zEPwU3hdv!W)0qD1EC1hln%QoP&(iGo^JQ@?ydnFHb_)rtpBjee!J@@K4{@o)Au-sJwXg z_PAHVA9I(SSZof@o4XbdUV^G*hD9+WFbDUV>tthJIBu?tD)*NoUT77>!g!ld zVQI4xI9_28iRIdW1CeR_P~ErFCt|ZYnL{_sO?M`k*i2FbLt`NseDUh9f#=^u$p4Bl zce#5UhLtCuYveQD=HPaSjgvl-dXvTJ-2;-y7+C3LAZu*tLIPjMt|K|W z0Y`cBtle}^r+<&gql74zLgp9!kKni&4~xS zrEVC8-+h$Lwx|J047>Jd|H%`ksv&`(`?V&b=0Dy9uGZNZ_Sr;&F8kU9@1`UFe8DG) z;mJbxi_e|d{$#;!!sl&~+>|I*IP2`CZ_l_&-}LfE0E+^a_kO?KM4N1_W)I3k;7-pQ zIRA$y-V^LOJ}_o_9SC|?hWs=0s_lhCXdh1wtv(pDGd>rlJBz4ZLWv2#}Zm5A6aLrF#vjK=fabg(EU5N>AX5vEEMK0VC# zX;w;*O*L&^{}f%v8Y4>6kLt;beEm(ji_N)y{|x+sEH0e|Vgz;+L&yS8w5OjeiekAQ z^8m@W>q@i1S(XMdtSir{mm`U_$zOx{W%q1XO7HX)t8W0QW8ilK8V>7%C zGMg;SPj#y%>#fWVOPPg>-2~E-uFYrxNx|`Iww$g!7Y~R{*oDC)=kJ%mr{ugI{7wV%l z#)+)?Jy#ssz{Dig1aZ)q`V0kI znUVfHp-)~E=%=|>T**GNO)UN!B^FJAY_s`(Og8zp?@By&6Sfz?xt-4@2ZyY6+7RKT zHRApXIfBpOg4Un$INn_LYNFmqkTDHW2ws&fN>{LESHHlgS#Vye*pgKEiO>A?)fb;F z$~NNnfraOo0T$VKhLQq??mTXS3dMMtrY^cgpwjX1qth~8f@)?=T_+^S=1a^h`b$fK zuB|S>*sPE`m0P>*pe-UjkQwmDy6Xt!fva@+;)|2wV&lU~6nQr#U8@;`jSPZ0wKNc> z@^N6!(ZOqAeS!wGB{h?jSU5Jy-FHWrh^C{_N8Yv5t53YslEOJCucvnYX&cJsg`O@2QrA-Vf*Yz?1QpHk5yEy!;0mg?zPbM1#C$OsycLrVPYz)1L}o~c z<-Q(byqn=B$nUB6|8VMe5nMu~eQutYX1nF)BMG^H`&1&?lb?r8(J9l`0@}7Dh`^<= zo`K~WxZHf{V9s&G?apGLxi@iW7HnH0@cb&$0vC=HmH_I=_i{>M_811q<-!5g2DhqK z@`Td{LBuaR^>9-#wKL>Uc2qv#37TQd( z;>Oglje+IEAY<2T#y?9UQ>3N3Xe}fe=+tULg=~_>K{ehB(*N#HH-XTrB>^~LJXpuY zOF7u6K<*PrWgH3i5W2KfQ!ayZ*wf;N{*5qa zM(3U3>79^?|C4ZRF-MEOJhsfhw;f{PehAHTfFk^&b=6ah?_RaifW{w{BBf%&^QC_U zg57r3{{5UrS0TRPvw349)?eX#?!{Debm!Ceb45ril+T*G*}C5O5eb%m=jf~S`THnu zn`!>zJ+E-W>x2%>)iV5g7XtJ}QVNRWp-&$W(&?`7V}8b61Itu1gV!duC29ZmE&j+@ z(jNiuk;Ba}ZH)fc5akf`PC=`we6AqN|JhyYsuN<35B++Vp@(o6hr36|E<=K}pU7xw z6jJuAeW>I8{}beHyW;y}`4omwUAq&F9n)~Pw+R#h^kr3?pyWT4;Wpg8YihFxa=afk z-3B#_eNLusU)=5A+tD|CdK08Jmm=z;cCJZasE9)rV*EdU`|W)z)I?*_Phay^f=XCq{4##^<6!;xdyT-2jtjHc4V5s!?f|d zH{)C5TCkbwIw#Xs&Ij?+;{0juOW_feLrzUsjwFHxbF5k5HEE8OiQl#mMFZfK~t4`SusgLa9m60%i zmaDaMQ2Q}9c$%JL2l)q$LjAsw_Qx@WVoWWIO0$za1&ZfPK35HPrR$U_J$(_T>ahmy z^=mnyF$U$t8;tTBBL$~t;v%f-k$&VmD_#uCKn)$^`s51?RKEen%ey;>l2Pgnu#bzZ z?m0H(qrs51zSwPXw>E!4w8`AXJgb%KLI+OGtUdVh+5xVOyOp$~-SbKl!I=u#SlL!6 zl^~JaIsGb%1(;`)2=35I8?MG10znpPO>9)<3z{Q^YR2g}am5+KhR7-7;5w1MhEwvV z(#TEQQoJI=kjft`I7x3xX#qZH@@=4kHPF#~)a!iB$uvnD-1)mPZ9dUw!%ehYRyg$N zUum8$v+DH5+&z>*<}!6W_eVJ+|12YZS?e=_#bBk6 zYF+5LmQ^znDdHZk3mJsLg&b59l)jczhMM>@$bn%_;ys7lPlxo?zjM|t04xgM%$m~f*=uMAc z>FLxy<<(h!ZG1JInY zITQzOkRIVAOJbcCBU$y|H8?w5%iJ3Terpmb=Ua@V!rhRMT#b!wl}dRlxgS-;VXVvp z@3M6QZ|11`JX7u!04j{gr3C^1E*u^?wE`*V(H5i>Jmh1<;B-R5GIzZx7~(Jc@Gs^W z5zNir5O^hlgUheISiXTq@0raw=$=BVR=S@%T^PVGte-%m-oF3MNa$DPyQ2!-9!nld z!#o6-W9{@V&zOB=Z6_q^<_|VrIsA>u{jg!ALwsAi{%(=*`;-}P?Z1C{P=((VHfT-N zRF$Oh*SbMY-1qkGYavigE#r#d{o25M1E$Z6nwD=kq66Fp%GAuU^>3vXm9dXppc1{A z#4r?^%8@rX%2^*&X}kn&*~4<7-y9*x6W^Fu?6;1E60a0WR#6>4ap@HrT}xI{e^x-} zBse@u5~2>ODQd60p|;e&ieDXs`b`g{KPwgGL&#ea zzyItjajfi7$2iPw&verrJ)dLRE|;pAU+*LIY6<`^%DJZPi=qNz@bC)5!*E=HvXD9g z*LhcNK^aRGB!28v_N&KQW}{v$`*0jWfsln&ny-3>StVrG@d|0b4ak?ndY~}RirMpR z_geo8g{i6ga!z+^x_$p?Ux`Y3x~3BnvRkL?9lfp`__hdDz_t3lH?#C5Z8~l}PMkgN@dYAj;Ss^4+Kc4?uIS3GvkBmh|Xp9SDmz7Cz$ zK}M_&d@5S(^0;J95C=uF2#66izq%?XDK&NFgCToR&*nZf!gK2#I#pzB4yIk;^(9MA z@|%UIzjk zWm+arM2?14=}k2F@gs7PjmU98AjS@o134`!4$gxw1Sn0Sa2>^Bhc05iL4`Tc>3C>7 zhei%J&d;R`YM%Y-?u;4vU}VOpi)K`Sb~!8btlri6@SrF{y-IIoRUPNtE=Y*x4o-{xSL>acRUwie>Bjzb|^nKI-&L=9hUR8dc^0pcBu?;y=v7Wc=^o6#Ss zjLx_Y(EFO2gyguGXS7Dux#eJsx zw1cDiA&6Qsztlks(R<4{cf%E2wGh5J+pwXr6w)ls;{m2FYIc%KUV^?7}ktgE!D zAl;ZSlhiD!@5@R09v_`Ti5K|Ih<+e@FFF-NV&dyr;}bwA;M` zTrQjgekJ`zHtn}XIFm`RhbGR43`x*I(SgIY!CS3w-ExrvMK9PU1g#XARTIpWF1Gsh zwOfzt6liU+O-i>}@P#%5&%5X9@AeQd>!2WiVw?Z|`&iTK$E%QYyqJH{qjeqI7f_zZ zEuG{p;$pMDG2`0qtqGy#y5FO&$O(c99#5-~VL(DWA*w(I>6BiW0g+bWk$cBpeOz4g z#FG8w=S0Pjq*UW(Y6^A&JMcB0zIY8M{0y&~+@?K-^_he7nFnqIr!GDEAT#{7AA-Jd zV1)Uc=e+*CGBM-oTurVEKw&=D1g)C+Q22gkrkvY&rr?Wym zbYe7%b7~F7KE8(IO_d)GrIuuXxJp&yKVtgEkeH2TJr6{bD zp4CBi>f4h8r*jt1oBNj!gH~pmCo8k6^Aj)rZOE=nO5t0YR?!#R7Td_TwZ0Qqva&B7 zq&OZ7>`eN~<+FiL95yl-ZYiFn0uw#xd9CFiM-LU#kJnx-;Cv-wFHt>#pon*4-a2o0 zpWON1(5bGs*?EiW!UcH~(>9@a($;y8k$Vtoir$*>MO!>`$>>LKeVoAY{0ur|Fi4LH z;52GjH=A~@3Cj6(kk?S<2aa49IHBgW5WoVHaFf%&1o=wQ$t(N@7H(|4UyS5QF^t{G z*~M*WcJFKBg{h9r(|1n6Ui12>iCH!L!~)=}CL_JGg zpheHy>($SL>TOA8Z)V7BW+8>YKK zkVJQ$bSR(j7^Dcfo!^j+EXaP6N+PJHG-ItOsDJCPT7Zq`30w7Jl+KwAFYkf8qe?et z_CUOKb)1_nZmNB~^K{;9rJmo)O(r==W@QCA0K)2n0bfH4%&zF-Rm{P&M&SMS6I7_b z6_44AetH8_v`A%e>5cGdu>8+6Zk+jthM(>wt$Pi$Ql$#Nd7l+IR;~-~mp+P=vf97S zEg#bT8WUk1Qr|iu%Ew9giyAW$D|qDN^%yUl{!W#>MY*n$YoeT*qG?fbPWx=+Mm5;$ zNmuMi1~mOi7zWw*x=1w1<9`@fGWaI65Q?a*Fq77!oh%bO46_)gK%nft`+1?Y>3J4H+ zO*!B`kKMg5j)z1Aoc8R59)$Y3Eic6V(U%LDj6l}m7qDw7isZyWS8>_?(gn8+-{jfU zkl}%O-t=|#376$t<~Jo3OoWbPYco>_1`3&td>6Y`mC|D+OL1+f%rvclDKP%>oLmU^ zh3b^vX{%wMJs(W{9U}AY^lBhE8ny%|PmaTr$-jMpMjMVY`Djo`T)+soE1r3rQovIF zy{>NXV)B0xpKkkzdm~Dq&=ZYnW8{A8{Po6r=Fi|zoKK>wAnV*~@4u_labeup*}qfR zKVqeAawPPesS9q0@alI^lHtKfk5Uv)mJFjg5hPZBJvKb*F=V$%YgtZU0<{!(1DtT3X%m=1L#FCwr-Y5P_HTBa zv6tz#2yc%rPg^r=Io(tf9a^Sp`yQXaQ%dM>e)sY*ibwjJMcSS(b$c$?EuD-NZyl4wSRQ2*t$TC*wTNCUB>Noc2eo)A8}Kb< zu3JWldDJNh@=D4R3d>CNDOLTTn|6X(k$Cn=m)5!{aUB4~$dFU>T;_nf2bcQ2 zBK!%nJOhZM-5n@9SHMhP-lBN_2V!(Mtd)!}fd2r+WNl#czPVMVwlQLmS;_KzClTOx zza^R5THF>k8mjKIwi>MTFioa_f`Z+BgR*KSFGb?af6nfJJKmt6O-JBpI)abLfASSMVUnE%=V1epdpzjyD=DNB1dS8+2BF5u? z%2xizUMi3gK6<%Es!q8N+Fw8?PB*BOhY8NM)A9 zE9Z>zu4Qk*oGJ4h8Qcqb)R&%07f238uCDVlz;v=?RjyRdL@3b~xO_A;FXFI=qQ8~< zCV%!lba*xX3FX(XC;WLz86~PMGIJUGzVpsib=(Vr&P2szSIE*T^0d9@MAi+bTG#1U z*J%LGvsG#Y#LMRLumT7Wta`A~ zS(b!g@y&sKZb2@&0Jj;o@@FZB&B>#n2!F1>E`li3mb=bDp+$BxX)nx~b@^P9=MOzT z;rK?S9yDP(qdg2a%h_m6R#kbYnC zqO3(^0<@t%kE1<%`+-W(y4fb^7rnK?RJh%vBIc(Ux@=UJU}R^~nG$03`O+(Ha)JM` z3)=(W|A>(>g@lw5j2#;kW6z#DL z6+6OAaDq}~Fh68Nr|_OJ`xuOBNeE=j_AWHUKWEHIfqlAJWNV(vi7VhdLZ$glso1TV zdy0Q|e(!~ZTeD%tOfn(SE7f;>1ccwHKk8qDT%NIkG`C6PZC+{B^3IM-z1%zrad7(w zyN_#XexViTZ4ev{Kgg!zaRvbs=Kl7H#^U*uPrjeG+W?T^ODC7XsJTd!BODsBalYjZ z;F~)&f9%$U{X9pfmZmzAQo}P?SWso7`6+ykt7&c#!d|aoo0_lf=~3#kDt$A17!bMiV;gOprvdfJ9}jVO)dLz)!}{Z?WF+i?;vNIqNQdBJkF`8U zZ;QP6l$_tZBPSZI19?A<{-LAQ=R|vJAy29VsLm+j+w`8uZc#^RnG|NMl$D`v^Iz4f_v4_Fnay^8C^S;+m_^^_rED)$(48Z|G1_}lpLzLVZ3)sK-RRI5(U;># zL|&#%brRbb0c18;%%~~qWc%jECNl`3Bwvp7Z&~6SC)`OW7ui&#}Rz>rb1$>!vJeS5N@T__#vFe z3D@!Ozhsyf+rp%1mJ9@~qQUQ&(YWx;J-LzfBh>dfo^Mhs%I2X{-r8%bZO#`tCMq zBt6|*qum~LZXCG4W(!HgOEkNXVHH`0FQ1+mgb-)E{dvct(r%9;n~C^VmeKhBS-@jD zc}!@#tQeFHwM~sIRA6t_sXgZhTm*(UP!H~YqyIz?R4M@;KP5a#pDkNdiH8B^)cmFZ zrksqN&I^a3D#q!j&D^okuX3Kb4P-ca#qp+F+%{h;h>}QzjQ91~N|K(z#5=u(Qdn|1 z{j=hvpVM`8rg{om@`>m6^Hw!HQaUm>Dh;J_MUESt_zkgZ>(GK1`Z}Z!h!a`zE7IMd zy~cjr393UW)pc{9sVIt#TbLTy7jLC;K=0D`2nMa%BLs6AzFZqIC%2f(zZ)?8hq?Km zoCpU71yR{-bkRwk2q56_CgHY9$R%QowbtWD^)VcMM|(yQqQ!f*6^d<8E>3P`=AB;Q zz;2nlUx2KtzaM|mnk5+6)x*@ikrJ2;YF*|92?ZHWb}#fSL$fvs{XM6}@m4n9$;cc8 zBU|I2#n^b3wic>fIayFp>2e!@(b-o_edcXIb+@H4A?nTLLdMA3RF%|F1pA*lWyv2; zNl|Rl3Tj4)C3Oaz1M8=GrGSA`lt%i5OohrIsH$jq$K`srqYq%UbzejDyh+UR)-yez z=wal5$WysUeLcT`SJ6O)>?l22sWK7Y{nKB*VP*Z zX`kizK-$;WeA=38&zD4b?>3zZkXsXI-DvIysJ_`%P(L%j`hFT>!By* z+;(nPkG1#Dks#T38xKOBh0qsn`H<5waW?6BdpExDAjc9Ir`Ba)&|NG zLD2`QgAkOvwOmGdq!-UhrJ9lC)ee!>s1QfJ$QxiO!)@GunsJATuA_$1yNe-wGIn7226;_zr8%PTmKuj@KfR#IwXIrVAeg?A z3m(MCO2oJm%vKl50w2PxL3l>Q=Hp@22de@AKwxwoidE0XMwZ);o@eA$L}&n#Uq}|H zaA@XDra#hb(?717c;iYf^M!Yb?0|$7aoxP1Dt=oCiw{vMJQQLF_77ZPR3=Cs7o8gG zBxDj*((pO#m9-Y9=+0l8UN#~^ZGt;E74=;7qY|V-W%eJh`Q}#Y_r^v*Kk4VLk$K_12_#IUiYv({ls`amGlv%~4iRgl-Uj%^ zrj>OL{&;ZN(S#M?6|}YleIKk8ZgtZ3hvbCYCgArqlPB`J@5}{QbknudEIC;A+O&82 zspsR`AJdVV5(t*w1qe&%3-l2p!c@Ut-%k17crbMP&m|W?YP9`xjG7sEB$nDr&!~;Q z=E+tH!5C;-^|{rceL4wbE0<0|N^T=L3*838M`fnMO#tuurU&L9x(CgGRV5B=;JVI9 zg!Z8ks826ovCt`VDH&m|w1UcEn^oN$-x<1PNCK)r<>s-+t8<2uwSQf)$Lpq*5X!vaoeVE;*C?m6t>s!hcRxvP|ihY0VqR2fmSX_3W#Xx&cM9syFXGwCQ1@q38iqmAVeFDz(~t zbI2H;3`9>BbT7Rl*$mZV?@;$*fYsq@@ycru5s&K3%eIZyV9i?;N+& zp`la{#%01Ny(_t(O!dPK*4aTTtf}60kEvna%N=o`9yKj8qR7#GjgcYtm<8Clt%uYjdnS`IvE-+ zZez%inEu^K78Oy9e(`h{dLITKI~9@ngA}5phy(dFVzt zjQDg(Nw40zf6npNY4OP4mGE5lHg!A?0lUAyvn11I>WubrQQEQ zsIS2}ff1V4O8H$FXOQCdq};gjX2>M~R_9nTc8K{711P9v77W@)yP!q;VJaI;2D(WF z+BhfVp_yzD@jLRqb34rHn>vg*90P;4*SA3$LG!PkuB-)2`v`%-Qp44@XCLh)Hp7Ih zMq=D-BkDgAH8cGYd{q^?t*p2$rS+@cZMeZct$sB7x%!Wum6t1LUoPxFqx9sjTup_e zsQcAXD_kpQKb`N@8%UL4uzI_Kc}UIoa(W4?pu~jg`{Z+SCi56CR;I9slEVTDno?Lg zTj9mAmdbq2?5$fU&v^N$v_LMKlJ(hI4O%ZeRNqcdFV?KSJas8&ws~O$yoI*$8kjE$ z%|_A_!AI+%Yn8)nqxFc$^HXyeuo@Zb)OrfC3J-Z3pZl z+I9}VCIcK7DLzZ>iP1iUFA2TuiZ2gqK497?VLm~nOY8%JT@yTE^4&8&a ztLcVs0|oTQHjdNLg*;B|)r(xXefGrOLCufv#^P)vIK%I>DE_fs#1!1(C%;AZ6Y~5? zp{MKpKgt|I=}Wmj?{MM}R4WigJt7ke-vBZ^3)%$-v0i<~P|BabFF z&+$V}0;>O7b@J?xDGsH|f$^ORY?|ISjeaKO>I$7aV!eZx+dQ#va&j3J!IRK6CBpRq zB2B~YM|iqHdFF7Agl>t$osbRr#f?@~9a<%udr=O~Rl!g_=d3Oy9QGfCj&2Q|cF5^} zR-A!qz*v}=zc3_VUF0>9p^-8wW14x8+4zJ;uUW3x(4~XZHNzDn3o$)gKkV`u*wpUxwJX2y=AQ9@kwKLQ`by?J-$l^l|WJoZF;5 zP0^8flZ~yV>{u;if6)nVX~Bqv`*t3!>s&*a9#jCCR%^5@_+J<;Muu>1Cc zS$CdnH?#A84ahl7OP1+Z`$e-$PSv)%4M2~!{W^k^kA04p0eDh#O;9JPXOPnFdXJi* z0m&r?hKXlKxEAYfn@Y!{JmL<3EGD;=BDf;(3@f|r-jfR$tql^QYtQnng{3W7ZAwL} zG$N_sQ*>&mBZyu;+YVFE8-kU_(-afDRqP-i5{RFStiR&HzXc!_LMoQEx=e;q$HF58 z-nGy17r?hXGeu8#UV?qaInVTVN7R~JDqtt)pVM{*eVqjc3RWDh>-gg_M{(E9^~+%a z2f|oPPiB~a${*RNXk9}5Ov>D--hR>T?Uuh} ztE$ccPfS}u+xad}%vs8+50m8wol)+zR8#A9^A>GchrjXPU$#uunSI8Kdv!MA8Cna+ z8({mj@l?j%>@6=e(F0>iN3R94`KB6%dP1oB@T{J6p3)!r-QgM6ts-GB!``+a86vbrZ=o_R za4~7n2-{5`Hw~udKF&q=7U0(!>O8ey0FDy!xeTWKO0h}TXTs>@vdp|r6+lyoq0#b@ zBAtVc;B&^x46Egsb>3i;_rBg}_5I@!)3M?6BH%7uP^au`hq8{*w_a+)@K;nE8be`a zNN|?Ne)DakfOCxS&}tL3hkQLZ6l$7w9my`_5`$wZLrk1^Bd)l~R#s+cw3JU5DXu9e zt8{fFLO1;?H_%;;^fxw*5eOEXalP7HTB@f2oZ)ClZCDN8is z8J?1BG<2;Wx;~tfxf_tkHcp{{vtS}gGe6Cb#{hR$?@^u);JJdHsQw5gt|6gB&3+k$ zpICr@3oBMmM>~ssE4i+}=MSgz&~vx7qTb$#mAUH2k$)MW4+Q`-$V9ja^@|J9_9Q)K zD}+7{E)Si>Stz}ZQ^%}nIN&yAHS$n>E*lG~%E0lFYQe)h1V*Q&?IZYnro*+FG~zDz zbyu)k2g%9CJ2GFZB%qC?C_>n=bjAvo7|P!O)L%m#_Wdc57kXIwo=zzd`q`ytR2+O| z2nOH0zf|-(J;w%8_y}at8wdPuQ*($#^8rh25X%hL+X0lkW+ae0Xf}87Yija9M0Xge ztw!P~5U{7Y|H@+m4@g>Yw-j%BpAZ#l%hy-I)0Ns^P=!by*n;E*hY!^uu;Hd%mHHx# z4IjJ?=FSdC3x)2&G(At z4L>aVuwgV_%7hb1uR*d?kwtXIy#2#v*J){KeHF(Q>Z#{64x(eR{uc#qY}$LE3kv6! zCOdiWxoE!o(ME`Loos-sofli$Z3Q~!m>tBh#?A+rS6=TM(+J|!O428C%HM(sLdVpK z9U_^IQLsmO)I{KfafJ45ZxF2mCy#i`^XULwr5~8>hG>)zuIHQ0dC58lQx$Nk^KA!Q{@x{$xmp$Vi(1m%A*1AqfwpW zGJV$y9Q$kg!>A_@&Zr?ByBdNw;?cQ~=;7CHYg~gSja#YS_7|A{s4pBl?cQ=H+dg~x z5z8C|`Ykm9vj$Y7`bS9in)MYIsKg&PHM}ZbW@V1`@@C7Pgo!tDrjO^RUj;bW$GjI{2LXDiR()xT_@uGV2L!O+)=wo5^?SCLX}wRRLzX>90l zfQPu4`yD{>OGD(L5&SZ*U>?m2Dl#r-8bK@lkd#cm0>~^nE|@U3-(Mk0S<+)URArjCDP zn1PC*gPp_}#qYX+g>6j6!jNp0y;DH8kJ@2!#&m~ri&&e%U!ps6v_AKlb7TM zYp%t{+fv3>iv??L&jcugr;nzQQ0zNVg zna`wPXOPzjiT97ZgK+^I?hLm8aaD~bsy4I6x|tT)PJITIn6$tv;{HuVWyyxas$waO93o4H=(D@y)KJT{v+uba(2rlxfV8BUbJ)*!sU_>1sK#H`1O_) zqhlm;!HXf47}QNqkK+-0&9K$a*+}?lxOLqUXq(eOR|~chmUeYf&Op(|kK7{=gKhZ+ zv2-c-RL%fZe9-jm(`u;!O{yMJeGF$s==ulD`NhuK!5H@kv7jOoD&-lLQoadbL&wOS+qpt5?x*L5wkCde5B^Rp&)h<~X6x|e1n1=qBOVUq8Z)8;Km@+2(_JusYIUsV zJajWFOTR@~%LP;CHDN4S+04kCfWn+#AiUvE?YiOR*l%vt$vlMgURD}g&yC^ZvqS)^ zC)z_tlCLZiX-x+eiwdU)QhP?t50^sgp{?88mCw*S#O1D7t_q2*dGP)5ymwBZ^UGk9 z_-?`pDelY&g4ZO9S*I5Rrhjzv3J;h<+y-9p_uww*FWwUG8+Qr^-X)xK5%Vrg251-XLG?&P2x%`bLG5TDAU+Z9^o&B>Y4B!5;p#&;l`XIEUKvJFN+q7 zarsL0r&EHtK?E_SIT`!uIQq%MO0otn`^Lq37cmaVHG=;BW;|xF7HS0CaA05w-2DE+ zG4$;1%TdtTl1ACTOS14xEZsj{9Vc&2E)yB;#sg4oohPLN8RwMz`?3(0ou*yWF4-=2XGIG zQt4@;qyf-!mHO~j$?akx!oG`k18W*?bGfgeSXSB`++5}#v}sEIfjo>0MScxLXCld> zZueLgbO5hE1-7cTO9NFq+Olg^ zu&Pg@vdyY_hCdS#q{1!h4V$j#7=_J^j-fk2?l>HyxB-O%TK}B{eX|t2oPS_QPg_U z9Q`OtFRF(uenZA)?Hx3V41d{=J7jnpLOW!48uvl$aIvz2aF`nZKNE;=i6VeRNWl{Pxwetm==+0^+A1eq?0kh}qh5y)Zbw zD9Ae@3?^6*5uKuHUe|Pw=Ux(v30rLpn=5I_t}!vUR%@8Dv~$(uG5Z4G@ld5H+IBTbO#j&!qtf2a&&^pQut9>o>c67DH59m8AWKX#30 zw@6n)^{iI{1N7GfhGQ`vs}Z(o2BH^!cLv#$sWZrerGOKO^d00z-u1<6ne0$Wa@5Z|fD}}bMwa5lt$7Cto zRI;))4RRT$Br_w>?*wP_PciWq_&#>6^gC$FM`77j1A`wrxqLT~^l#aqqYpY4RCNGp z4zv=FYvBb=Ql75*un==hfCHG!$F#f40FFsP%6~OOQ8#TFj{(GxKwJNT`32+FIQjjH z8|{)ki;x{TQoMGxAULsBCl+PSbiREyAbmle6*deaYLK6+-_QFDQ0V3vQDJ>2g#b2*I(f8 z7uT7oJ=gGlptkQO5A3@L!dYxtrNygSW8$X@wK!?=bh~QluXGd&ai;W5>&TOWyQXK%!rYwtP}2JI&k^JjHK{uEuq`H)rdGQvYxQDNqWuFSj)-PQne`+J)x5N{EU@ z8in;1?c3h$r90OO_Iu3=AzIMKv5P=NM&|@kNPRGa;>ljAJf^>~QFI=sHFY1n9TRBD zrgwMS7?U*Su>_WbEq?_hCSSJUf>H~a>I6GDq5i+p%h-%=9{9}I-f=RxKFe(F>6 zW}x7+Rr-+Ha|O-jpxIIEv67v}K?}@ithVUK;v*AGmZpQCB*L&kh-qrL$ONrS{dH}q zHxM%_dwb95ri}}20Ly7KTUsnJGYC9YR@Hlkd4L)(57*+1dy=wm<77wlORb%pdGsbG zf*$?GQBQZb;(iqG(J)uE8j*a9=Z~A6h7X&aZNd8N3WJ8HsfNYZ&$zZo_H;tCf=W)V z`N-K4gWJT8IOs041BP+5DihKQC3tpA0z1U@`3ixO!i2&w6)mOZHp}Z)``*?DE>X3J z0qz~)!N3rr{_5KaAsgVO(e6vl+YT62Nbo0cd44aAr8uW>i+t#e5;(9bLBr4S?RUty zshgvn~mx*U;A~=>R!aN?Z%Ge~o=AfM$&TsgizlCeVyD zL3*-Yt1~<^hWxyR^F!;hQ;c>dP{9iUFw&0DEiwp9GB0R~5Uy$+Q83u$n{E>dkA>R&R-t zjaoM?;OTojlAp^?ly+#%pW+65kaX~9^}Xtmh28?pMKHht$lwa_#C34j(7etlTUJ|w zbEcP9k&qIRCVei|QF`C27j>J)^ul^E{h(o2gr1$^+(6k;w!5JPmQEqiHxb%+>jM18 zWq7wO4VxpAXAN5&ctmHmR4zZCG;ptX|LOm%1{gCz^?}(MJ*TJes_ZwIhqS!X^#_A( z5(FAHRkH7Wc<&q_O(mIfO=gef2eH=d!riBamC0i%fu3R@4qvWMK;rXX_7uj{Z z*}v_WOr_$<9z|pH8*-G2`#w6o%Sn4@qoQfP#j&ogm-mbOu?+;gIyYp!5%f-m{>f#C zIXz2Gqoy+W-talZKYZT#y`Dcwj2695Xc1KB({6TT$nM7#BpY~dw zb;=X-9-rVOzs*1%d#ViGRN8DsaY=~8^}QX1TV|+gK7Wm;-@z_?7Cyo1vY!*hQFudH zXs`3`fE9$d;eH+KT{<=UtFx)y0|)B=K9$;;N~;Ecsc33-9aYI7Qyhn-An!CGJJ@? zY&s-3cmLw8TGYCm+A$l_ae{bbl*(tb5zN(?@pC10|e?PvzmS?RWp4KMAbD zv!y=2>Oawk1IRyGs7R(5C=hrW5zo-SG%?0ma$4NGO|UmA9ZTHj{*m$}n|KPj1m5hL z$P1VeEmN_nbpar3|Lm zJ&HfV@!4;u_Ak~-`aCC1?7Sd~2!1V1&}aCa+0*j79_N^9NSqiNO}Q3+(JtO1ztnd^ zS?{-f-n)iFcVN9|c@IUL^1xg`=WP_8w|sirbo<)96vC!FJ~Idk&(f5)6FYy? zsEe+5vxwt_vP3(|(}?f|PU?b*1jk!g`FDX#^gAbh_;hR&X_4MP!;J_DpSN7~!|wUM zzkQ_JRLH8A<+PLHp)cT>Z;erIL$jDtG&I>0XeTr`{TbTlCK|(za$(fAX?0{N9t}=X zB?4a#p(HqUnj4-(p0;mFbl2^Qzpyjm#M2i)Z&f^rN?Y&m-9^M_t(;4wZpp0u?KNPFb9BIcRl%nQSNQ$VGc(uNViHw@DjN`}H$ zlB4Vbu>L0~#}r`6ri#ET1#qZQ}CcnY-QktnA!AATzX$9I9qKg%>Ur$erq$OfGae;3RX( zd#(1lhfX}WaEO@?BB}`2TKqwf4i6dJzF9Sw7$%n?_4`fTbIymfF(qMN#HiI7Juqmv zVf<74l}Yr!MUxC9ns~BdQpog?Xi`rRZ($5K+c-O5_b96%@5$S;)~Aw9Kr2kS=6n1l z(pcvMzyFUX?1nrKm~5D7Q)xrT-R<7`CjV5^s;lX z*gg+*eIM+#vc>$sr*W?}(0+(6bGz$|9%k2>qgu9!>{atM&&74PabDZsoga!*iVjgRwH97aJt#7h@{A zgSs&54g~$hJF;m7bsfZ2pj}dboa=}P+wiB2{HSondAg$+CEwJneKleHK~+I-T9H%v z$Hc>>e>z4$UJ~&Pr0*%*5TMm+9)*Ds-IO1fwHN4n>+WPcWY(Urn+HjHTPk}p z3JyHYqXxSXvl;pf{10E>Y2c%49Y*CxoCgtY8BztTbL42Kb?&vc>~lBO9QvK9pWp)bL7dW zjHie&5FY};G{>ahd6XCU=)O(?G&#@^Qp0vco4lZv@!0vt*8m@^e>^J&lf_ED?)n)g z`TfK(En<{cZm%I2y+5)Sfvo>|8&l68M{f9=%9gxHTEgdZ0z;G8XiSG(lP)$EM@cvWEzmhh3s`JT8P2DxpaAM~8Ht=U6#+3~8b z+Z+_#gC_hI>c}v$3dpCHFErSXCVLe4=T99kBR)kgj@)3crPtD7aD&5E15WJZ0|H1s zaIajc(VPKeef#mOq6Zl@+yoch?pC%DR)76@lFrJ z0SW6!Ixl~eEVAFt1W+)0_W!Sz*~caQEZg7>u$e~erBeXgL`pxz%hv=f?r#C}<`(p& z6cNXuH_*`PcqQ?))glGWf;c@)!5{$zax1p6U@mPf&|9m6?m#OAs*fp-4QG9 z{r)F5dvd*8?@G;60IE~Fa}86Gc?bY%vb5Hh8_s#d4^fb$wNrSNA%kVVA7|?xHo3{| z_+2O6wd}!?HCOFOn-2+93L>MRbs7ywf#MLkXhbC4p$Ml9ypF?;PXmiMO!9CYJ>pi7 z8btFtl9U@6ZJ~e^T{u4%t{N)VT!1?tbAJb5KsYGQB`VcpXuA=%aDpv9e+%UL@-S~8 zH&EBdvEg&Tea@O5kWNU&o8V4bmIerH$_y%`t0~sqH!SS8zXR5Rx3|{1D%xSv#2vM| zP@pe=>^U`}RqeUq@0y)AlDFtQ&(;1gm$p~yj2y$y|8X_;{HN!6bR+%XyV@WTh^PFh zo=x>6{^}(Dy${`0Z4WV{h9(KR_+x1v_O4o4>9NCFs2`c32V-_(z^zgw9IYwa*6~44 z@#!0A#wbFkFTbEj17|!aQ+dxHBT94(`oVE?)?i4Q3eGIAp=%MKF=-y7cjEikux$A$ z;5K*l2R z;8p*$FqRIS?sGwwRGj1+ys8Cyg4&<5iVhPFIXQ*s?`}Y-iSBIXV!G84ruF>pg1uDt*shxj!x0GTy~nEs*u^OU;~_U`geRc3G%XJE@VeDpC;|az>xIzm*R9>A6B* zW4%QduPctjBRf^hc)tMUr61A+#4(el4Uneg8PuEPHa}>nPoES8&u-P^&ajx6t{l`? z#L&(pySrIT9d4(}M?k??m6Wb7jTl+n0T^NloO=bHI=FJMWec^{pL>_{!~||kUdya` zDay<8%_K|L?5u4v0<9aiRIbae_}OmzeFf&t#idj%3RAb_NShmz3Vsu4tD71JdP2tB zmRaQuwwm%*y4wc{?M=6UjyQo6JLUT?hto+-b!xSNPadXDv*`)JG&iU31 zm4D+DW-Foc3)@a{^h5!vi=CH3Hu@|8qD$YjF6%0Fvatig3#;n9Ju+|t41P?;8^fkx zjpcI~lhgX9OF8?D6QhFBe?7Rwq|##E(Tt2N$>zxpo(D!gQ$1qLCiLa6qrqwSCfRjs zXdP@dFDWQZZB%UGD&ALsT*TDa9w?lFb2H{lKbu-cwtHppoXE-NkczF}>b*9#4zvSi zbLE}`wms&740$lnoEP=hw9cbrq8sjc4f4+h+ zg|06(*lrP?AQJ%_wzv^*8ZN|QZ|VCx(lbh-nvhfu7g@t-ixeRDjlSfZ0<#=g)|93$So9UWcX!dDD`6s44HN7*{RD9o{~+U) z9DfNi(wk}f)(5vXm9O`H_yWJCt5i=|^@tk;s3~9G=Ci9e3W6|SU=qef?&XK1^ckZ9 zQ+e2~!0PGSaLMCx{c7YbdFPOUI-}0roE^myHn%{= z>4A}gOMNorq-Oj6UpXF%itObFTSJ>(1#KzBQ@dj!P{*jS1|+Vr<_=AKT}9^Dh1`mbSxYrK@+5wM z?^-V8kSC#ig?i6j)bcZ%h)LZ%L{4V*96uW|Jtt3Hc_0Y7lC3+?RE!-zmpTU~I<0Jv z-;6vL&YQ)p%w_8JU3UVK(j91LpQX;_$$*wZ<`^?Bwydl_hG!YerJZ4JSRPQR%=C2|*rP$h&JmF2WU4a%mln?ww?UxrA4s2FbQeYpOB!*j04ig~T2 zJw+v3`Ar!osA5vED`WE%ApX4Q_1@-`=2#gdWNQ7)j+S5mS{}|IUe&DVa+2R-Cj5qy z4qxUe{djdTQlbQQXeMB_lsJ|j#2x+q72CB#F=Q)6UPg<n@rY!)$r*Za&@UDZ6Q_&j z%yFvaomC8xE=OE@^7C3blQX-nC^0(}XlgagPec4(k(OU5rbU}3WHR68udOpG}=-*+m*KEe&qg7zoZiXOXlxMNcci* zR5Dgt0lMuj#74NeWp%mI-?cAqDXi8{MYz%qFXs3(k)0*p-jt`WK1sAom1xgSFq%Bj zig=KuuR6ls5N@g3X^7R|7_#Qf!Tn{}@OGc~W!n8YmJOnt1^TMG>~2u#~+;cGj7@lks~ z`XL2s$x&KL5g{G7qHGvd z`@3EAgts)7GY36}kQtXY$tu~eGBLM%n-AUy=}=*={XBb$O;Q+#(SjeXxdFrli- z7eSY@?MMjK>N(YCDyU0$(!FLIhaR7a{#cI_5r!vssuwCyr!1zy##E`@4;Fq{|EVxpWu#BJbt$z5iAuldgIr= zL$m6R{NIZ%@;y(=5HFsBvcbwJczD=|lA#O-1GbFhm<<*bM-N4TAA6HpWe`A~6d4pOK8EBPw!met}n&lakx(E;WROiYZ@BaCkhwCq0e}U@zde zzTxAW%q2R?!j!LBofRVq9{72Ah=-{u56Y`BSHN$!S4+~4?n>Fcv;OCPKAa;wtb6eM zFJ%j+8gnoab79YjRL@tGAKl(_nGl`u!+at7!+itTlX%W6;KYOi00S+?b;qzI(DK05 z3#()867^Nxiy|#$-3N{mHXJ`2&7D=1lh(`85U7hLMFX-*`}A$uTD^q@XfQ#kAP6tt zT-i$sAy5!=Y#~-s^zQ52w>HTcR1PuwC6t8-0Y5#WcbSloPQWVGa3e}vN;s;9-)RFn!b1G>F6J2* zzbQiH+e;)jog}A~bh8wn@CW0^r+Y3(Yc;0S@Jim{f0GE$;iKm*_Z^Gb$8jyz3O{ed z0hi9A^?QTl3-R{@=046}q?&9PV>M$Y;;s_c#qZmQ(43WFZ%~`Fj^^%n(iRbq{lVvI z{v1#6+K;AhFCXW6CPStrPb4HuiALZijLSMHBqa&S9UH8sAO zeShTI1WR-#^VgoRwN@xp#ky2mh@oD2#jk~iCQLw9p%OSo67h%+7E#G6*J1-QqtwOFdlM(DC4Ops(4T_0|M?NDewnca1^Fapk*3R=)31C*|(Mqnx9K7$=^dMS9PwR248i8a`77Jt(g!>fXqsa-Z| zBdl&31Uqk*y{XCipeF5_mBv}YjJOowOG+z!ZH|jxB__-O`Hhk#QPPcxyBXEaRrpjz z2D&iQ2+aL5dYxR4L!1M}T^+LWu(1Mbu4H60$|g8_PMmf51Y5B7Rg^&`DW1*;+I`oy z+O~GD2ZL^9B>k~Z?T-@nNtI(dy!bW=O2>+T`qAop|F8PTc@LT;p9jab?n_9N0S% z1*6>u32zvNOu$*^XMG_OwRSz+1qjK~;P%__q{+`ZA_5{ZDdoz8KTnbQV$S~)X3i5du8O}|JlMK7hGQ;3d;h?vG{$^LWJ!^p z9gdds+;3gjY^1d)l2QNjxMu})^lfh4I|D1(8&4WO5e&Y$Nf3Vd3MOuy0C;4Qr11s! zl{)UXA{HuGJME%}EY?>TvOF$ww$YD$l3IlqD-|#YHliEp;EmdOF?8c*-IF8)5=~!c zO^lQ`c~B@KgKK2_$`j;)Oq4Z<&wvAFmmfgd;o<+Z<#CNQfSq{ZrA1cyvF zL3n0QH9FuV8zZV&H`P1-0%QcK51?&?pwGcGK~Uq!*4ram&&dS}s7lTX_gaB5NWPo^20m7o6C4S}MircQ78*2bBJGiN?8MOA5-9ul zJ}0fIdGRrtoI|@@q;ultiHG}8UkF{6I+Py|U76t4>*bCY7kGHqS{ymDVuXfqlDwfn zbYM{;9RMzE-o=JZ#QcXvaSbdy+6zp<$6E*0dzp-0g!eX zY;I2)!**cztTl*I#d$-@5x2h=X=++wFk~sKOt2F%_#2CvY68s7KUh?o4Gm2!`BWLu zH{4O|Un~LHl*y_F43o;}4adtyqbo+I^xVLV+^k8NWWD{g_FU7#?i z3q}su_AhU3&TR!2JZs~7IZ5VdFOEXI36>hi@9pHHRm%VFM)J3SJE$L3!fmWvd*-eSwZoa%0C`eRqvg$LvlQ zA`9DZiQ--@dA=^?*P(I&cXqW)%;%Mr1mq?LVQf}@Y1{^Ac8W|%kl7jLY&H4NZz-{e zXnwd;?3`h61hQs$a&M7rO)HxmWV~G(HqVs0H0`@3%=?Nyr6$F-Aj7-jLkq^C1&how zoN9$OQrsGL*%KXD|D?HDw;Fs-=)3gL=(#w-?8{lx=j(6}o3l%Qi>rjb4F501RfB=} zCXR-lVUf^-Coi%WOvoZ(wfpFCP)az-Vs&MnHj>^M^}y)hnX?;Mwo9^20OppAIIWxW zd#@nQ|Fh15TZT4EH2{Qz!DFyO4PqN}dIkZcoan&zG-DO%X7$()pI(~B`G-8z_mRWJ zq#d9BHy*%xq`(Nc+cvIn+9TOtmN$b@8?Yl=r@8@Y#n_chCPd`@;BkXM>Vn9@?E;1j zCZ96+K~j0M;k2SNAtCrB)PAn-D&YD1nY-ti<4hO^&HujLlg+$Ra0&lCe4maD9hfv) zCdt2C=?4dIe7c%)Y|qQ@fmz4*6*CAjJwivwkfjL+Z*Y@4^ByB+%U~d2>wdH(lgiM_ zpu68zT@WP@E54#2&A$yF`l4ThgQ43C#sg>+%sM^)qbl0_AYyx{XV)C-SMG{4F{cNs zP^=I75Q1m)jsu)qSRe;tS|Y-4;CiW4fxL4NAN3VDh|bzKJB%(tH!VDP0u&sGh#=n_ zgfd}yQC$bfJ!aVxp?%kr@asUT?0YV{X4Di9$#S^N3rmQuqJYQeJ&1N&n=DUdNwo!+ z`&%+xx~Cw01=A3z{Jl}Gg25Enup3r6T; zVGfg9f-R@P@9ojn zB}z!^)$|<<)Q;qN7Q;0rCLB^A9mSfq*p4>d{r0#6L>c?4bk@3iMXlnVAi%zNrPANwo5YrmcIFN8bj z?tGE#7hN!NuN>f-nRs>e(f!x6Zuv2~eeG!%W-$|jSH1k096b=-I;1IRittoZHEahb zo8);OiAwd#Xey@YHrkfr8!JuxgGNgkAhuU4FbkVAsXg}wj9^o-HSn%sgWX^RV9!M! zs^b@oZnfHL(fdMPE2CX#p~;;3`puL9Ef74;!_TF%uxI~^m+48vG<_6Bx zE`Xw`U+JzJyrKECafjbMB<0E{h7$7)%nI_wDlPEP!#xN^P$)-8*ASjS__MgBlaDx4 zXTm42AD&W0whSUaGN|4UR%*bE@v>%xvCJd*1eUI zq~AQr-b+C_PGX;3-6?Sf3Og#z>5)O5HU3=D@()gj1);yCYil3J3cJMR35})jn(-rH zv?)^0kT`yD+*DgCu@5wvYN^h!NQx;G*JgRZ*(1Ht^(M-$Z1c4r(x+#W9N(YAn62)S zrujE|W5Bje?z(tp4o^|n6;xo9%^@cQgmpI0SO$rRIS!(|qs7S|B!!r6sPx+TB7nfI zmHMz!{p2`1mrF<$14xlA|W1>MGLV?J?vChHCX6$pyaA@bXlTELcGz^?yCl76Z@gC+z@< zh#=d+$zN~u%e!H_EqnFmf1x9)q0P3@SLnbS<7?Dt5|Dw9MOOZtA8FEEB>8tYC|hsj z>D7@lr+yV`X<1P7lCdoM^7qwSV?g?E2cpDFEfCr;<9ZPbC_R07-e+i?2bc6Z+JLUX z9B&M;#0eg~N8zC9VKlm>gmwjR{iygO1D%(_4lqYCUSnQaDdK{1Q%H!PzQny`T*c-R zmmTEIXHr-_TMSOVjgH8(9Moca4Vs#atK@Me83pWirZCrx(Mk=)0^xd(71yzFputngo5tGu#E1C9@axmqP`*KySYB zbHp#Y0LeQOpze`P(S_DPFxu4}+|5m3`t9QlORxl#MlH{lhcZ|aC0qhlql{?K9E=N1 zW4RIeLS+^Q{oAf7TD`5TqXZ!0xsbzX2Y)YL=z8S@$Q!~1qNT`wfPyzo&&O1i;&YQm zPcf)AONcXCRu2+pC}&0oiq?p`d$JbgBNPtZ}CVPqvCD_{A{6#YwEXNzYoWM)NM^^ zGGbQIR~i|7-iiv#JENgOt6X1Qgwy2Jcvvy+8d5|MEar2?sb`=^q{&_`($J3Pqb;w; z0wICunk|Xj5B1I?k~A;D;#yga8{t5)f=>7Gg1-l^VK=z~n`io6Q5b(BntqV=rdL)! z9r?#zsNmveqwH**IjXwJr8Ij^!`{Dg_lA&2+^~ULAvH4*mbtYCD*QXG2GD;W5%=nx z<=GISx2`=Utuzu+1L)3Zn9>3tz1s?@uqJRVuAiw&w%GdQ5mSIvY9^4%*w06|7+_|g zQlBeM@1@GI&dwEuTJC-?`+Qh?U9tJ`%zh;ju1=33#0@ZhP5QgrDN&7T={=akp4hq@ zPyYjRXr%9bttx|5$`+{UNdA!Z_1jlZ4G6q${x=nbV5yB)+-ardtb%3kVg&w>PKigc zpV`*m%J<1)-Fc@!%tcQ4LkY@RafVM?a-XNlb}2WWy_)*(`jgzR0oIvcFuG5urOi#N z(75dyq7*KVU}uvYfHw!BS(P^ghS(rBjQRQvl-gs+ENl}{X)QNugFT94J|fAwh)A+B z*S*b{x>~?rv8%p#CZ|Cp7no)A?Eph2#yxji_k%QV36}A}xS?ABkcav!#6b|YjPQa} zpe;}?`$4n%?=-hJ22Ce~Nm?dk_j@tx5`D!g8p=#BLej!YEe5loxRP5y7#pOdlD~ML zgm5|6JyRx=VO zpCPf$pI5g1f1GFT-xY(m&{69$3eEnX)wOKcZ^@z-uvlj2O=#1_83s_=J^UX=S7GMy z54(54&-VVgeVz;`AVc%I3#(Ah$#AGWglEi#o+uKJh>-&_@y<)`Lhco7aD==gy*^U{ zSZzh&KXhs$`$JCJAdj#@zzNSvRL^l++9dpimuX7pfKmkT8R7?&0`O(Zy$??w@9O|} zvJ`OYV^SJI_NxP0U=jAIOdl73;Gqndha8$0xi^US`Rz`C^8yJEmkfE4059-TJX7t3 zuOl#kN-3}$L~JQ8s|$#7?{S9%;u`(;LF!kCE$&hn%@wdOI+k}_yBATbsi{KufH$^{ zBM6!1+z*QiormZ0h&^dw$J2OPavIl<;s>?~g&bgY#F3oY0*u0fHU54N9r1t;FT@I$ z;4saLosXd(!6!8T)GOi{tzj8uzvWhjfUf zv99+J!W}5cicUZcqE_xwY+A-tsfl`_?_+H2H&ckXkiCJ%(aoX27q%PE$+~eH)n1{CP88+Ja%Lub-#wdJTq(HDYzD9_GRm;1U? z5 z6Q#))px77b>wG1(7b196QVDdCroqGGf7{)@B1-uFYGt3~y;k<{Y&nn3CbP3fZui9u zTSXykMtLk2&YNfQ3ai1%&_P8GS{IhwA>Szq@lRE*U-+!|B>f%5e_|J8-)6k~_MT0K zK}7QFqWt&55e$QWC2w^CbS;n@AH4yt9I-+-P3)l<1j>KwYREY!eL3m z`-l{W&bQOah2y=KLDa!J&E3THZ9=vO%I4yuR+|^gXYC9m+2l`?$$BiRf3tUx-XSE! zGN50?5Jbpk+Z7?Wy0{M7llxbv)q`87ne=UxtN$;fqn)p#4w|2+x%yk8C_*%O(MP8{ zld;~1&;7^B4SDQ8eBNDHfa_xj$;s1X?r`}ZyFY!J>H`$=jr3KDPHO)isJ?^oBP*T( zKe^j8yxo|{%I)a_p4Xcl?AiYS-gu&MQ?k^t!2bqU!K+vAH=pbyM-VAc+zka_Ijs}T zd@D^>NRXw@hhj~nujhZ9yi^Yj-P-)W7kfai7qy|8lSP4&I1Otk(e|Cu`0Pf6s-&sg z{Y%=doN)NcJh;U|bPtgN%cgRbW2NL0^G+E?W(=ROIP%GDEbD)!5tWf*-+##ox6dCj zvV5AKqxG#91r;oB!(LURuQWuRR<)T#w1>EZ|<4Bo12-{?9~oI z^A-Ehx~5C-bmMa+$R%Fvn&ycjcV@_l`ZYRumK6HNh@1sZPuq?iNO1JkG=@@~W zv7GJ7D)c*4hAzU#19tNGmrhEF-^xx6e3+DaYtg|wV!w7i^uK;r=?=1<9$$(1uC1?9M%fD_5?u{sC4|)QL zuzS4;GvKh`Ui=nIc_&+zJz~?tEEBj{lvI$Kgpg-o&h0_w=`V2+)B_u;ptUBpG!L&C5`c z`U`-x#tr684$ch9){3yD!tu~=PLC0png^@SCQEep%O~y70vlR4_!hhy#9-VxM3m^8 z0Ss6F`=vN_<5KN!O=?C4M2LlPO+tZo?acWaC+}qFHB5DByK^k4TU?;u8;@I$`~-!z z0vO@Kht#?;C-0*`c+AJ6xZ;?^>!(Qpu)R^~tMN8kjECT17-AV(zqI#m@E6hswd_0t zXYauVSFzkNqy0nQ#>$X>^tbGO6$#4|B|O1?`%uOtG&%!1LNK(e1MmaY_l14G56eYU z_?tcg&(w$tidtN!v39yY+4dcg-FrvAIz666Dhw{X#g*^7x#+$L{>-SLmYu@mto;AZ zA)F*xZ!4{{1%q$O$=QqHze&s{32XWOa?-r3+FAR9>yFf8%xw^2%H6*3=Fy4kkePLd zYYR=Vv?4LV0>x?5`A=~9e{2D%NlGmSjF5cg>Cb|ba(mxDyb2WHL;UWi{Z}&eTtY4r z5Wd&0>~k0%93D0~1yR}E)XlBsx*3882easG9{%?bD)ro`U)gzdkA>}9Y^z*kCI9Q} zf5v5o_sIuTe`|1py6$A>kt9+@0CF19ChFKFu|V%Vjr?_9G-9-xU8LM^={h6m+&J6WIIgt zjr#_`2xIZsHQwJ!><|x)leK(az4_kys)>Kw7+>bxzTET_doQ;T*F3_4A-h_se>kH1 z6B2-q4y{w_J=9mW8N$}$Pt1Dpz%WsB@W|~?ADmd3V5k)9kh0v>|}S~rf;5+H={29??mUj zA;aizA7S+v5{+^h5v)=5h>@9UClx1u3^}eGO#l-|mQ3b{KX8}LUd!E^^kUGIoEk}g z1G^jw9sSM2LoQp%`l{B4svueNA`)0R?bLJ{6g7~YC9mFBLRi6X$*oqKgmYh0Bp)GU zf#*9dD$HefV;{o>(+OfNIK0gu_+P8}qFhqz-%=VE5_ljNHL2^N22Uew&tf-CXgGA% ze9IDuLnkg6`G=ps>-7LMFC73y#z9d;71V2aVGmi|bC^t}?19}qPBEZ|^SQ16d{0vW z)W@E_!I7RJ=7yXU{jn#1$sT!B0oDJ9iVq(;F2iHG*}48?#7veAvV1CtWIg{xvOR&Qe?WAeQ!Kz~OoAvLdZTMHO zP|{Hn%pBNm{4+e`W|&Y>Wxmy1Z2gT^SGCgzt3P{U`Fiv^XaRN5jZXSi3XxAB`C#yb zdMv7ZHoUiQ&Z%XIc~6IC`v=83)_ANdIflayHC4hov>rY0_i}RVa!L}oMT9N+jw@r_ z8{`z>n+>BlSL*()ix}N}V;}6+9%}!8u7Yp3ByU3w0Yp0>6RT^oRQ8Y>xZKP-`Ok;3 z<{=o3T*vCGD#O>6JbuPy0pg?Ak@FLS_;>D~13OG(qTt?TdYcVDL8TkxD&ySPl@BM4 zt_-%V?4dziH9wg4d6^!+o)1L|$+T=`Uj=W&v-aEDh02j8t}b_fIVZT%+IXRZh5vq$ zVQ0se`a54Fj(Kmk^W+lYOh!az>-hBSvU&28{=b%w9`O@M4Gg?f_;1`z^!&F@<+mN%|GW!0e8k+3vaXcGQt@9L#uON&E zV4NCqp69bq-)+e0Jiqni{d$84-C}g?sXa6qU?6yA)l^QIckQ$0z%W={3sqpchB{O{t+>AFA`5u!!imilcjEM%|Z-RhzNVCZfv8Il$@uSa7fccq-MeRk) z0h+4tnnY>N3gdrsz7G>tmt}S?9ihbD?L6lEkqWP>%4^_>Yw1U~Y7*G9p^F5Bgqx-r zIez-8Z5k|ZdPsF$TIlI{f0c9$fx0>=`l{(~H&$Wb5C&+?t|KKSM72F)b>eofaKq{#xS=o0W_YQIK zxJ)b=ZpGK-ZgFtxs?UOQr{1dqXrzW;Fn-ltKj#SJU&O10Ad72VNQVep?bJhUJKZVQ zP~yDuZCRPQ1+?g)1#%bNV{F+f;utx(z=4UvZop|G84MlPQgp!vvIChV3CK?zSQ&l| zJWa39IK*>ND&!g%V{fd#ltur|ke;OYk~Z7~njw5Nxm=WB`ri1iD>k+xF-CA4!xm2p1tHgmvTf|GcJSP_T>rJ5sZ(aL3Hs#gyY1a z$D%=Q>PwSmYqPkwUkf#!k&2Ch4U3g|Lyo~4S&O4$e`|tgtn}tYBM4aEoABJ!-T7^2 z6+D4{o{C7iGy!hvdB!%PvH410l}~pi_uwHYiEJt)0Ug@?Xxq#B>mTbR-*MsYsh9h5 z$Z&-aebfv4N9r7Ovc{E@RzAH_nuG3`Nk%iy36bDj>tJSZ6dnX*upQW8!^X3=E4T-s zR#OCr`T;G%%vMS(Zm#z>2kj2C-0IFr3+Y`G9fUdb*{5bbWiRjk_D9c<=j>?73p3iV zRaU&J2eBaNd-E`+lD}a7qWZ#G5ObINGy6;#9b->4_S+kq*+4h-a-9v6@w&IO zVS*FrG>AhVr%&~l6s`dQR+rZ)@zl=7zrT%X?qIdBaMxAEMov3{7|R7M&FNCu^kt-t zN9{jHzhaj0;e6n#SJ_|Q!YOYCDI4~80lv-FHM;gC?Fx-$>R7295J1y=?mncI)(G(0#`$25I`<0Wg^}0-uMkfu9%r8Uk$$QUybwceIRa8^hAs*K)0KS zV4W}>aQ?mfn{{B^rh@wS&LtT3^EkvK-U4Z?ro^;o0~m@(3ZwNGeZ=raj-Tlid2&T3 z>(dH2>HMs^vFgj^Oq&oL!;{vu$7k4u z?N?eCKE)yX_y) z;D!5%rMkCy$+}rgfVd**)&Y2YRVw>xc$@wI+nwbsBc7Y~QwKvT>#gSVTW;^>wNT!f zjpAL#Zu8}-*o{u`pS})ydS%{_q4qED3NsZLU0ooRPtc@Bd4&j#ztFv)%iRw`)AmR~ zn^tQ?R?rR-KmXtfP@<-|fetHgfhjX$$ySbb9v_5_VpCMX9H3v}D|!cD-(i94aF7WSKSm|o`840+@sh% zG3F@iKfieIAv!C%y&5sF8lBnfrm3qAG}Sn>0|aL$%)Neb0ZiSvi}bNwEHDsDV$lp{ zo4pc+u+u4;34C!iNLSVDIF_N+efRTcNpkVeKvR`#XuFXI!;KMJg1A!s4|nM%iC%0R zo4a!)ofn+~rAKbVajS2--G>j_V?zcQSbiyt-b+{NTilbq>v&T4e_0c$B~^&dil8<4 zb*u7?`%CxUszV=Od==oFHya<%m>2d_ral&Wwp)IF#z%Sta{h%;II#kD8Mlu^kQV!} z>3r+;=_NM-d!7Gyy}lvQX=S{aJ^LeWMSsy!P-H+x=X)i4rHR`Iw@i+B$sdbp>5l*olv%l4m zqI8>lraKjPcPhF!<93C+pt8(JqDJ>P&WD$L^5(2va8Ke`wDbZpc=8oT$u|x4+1`|} zDd(yAsZS->k`8H?jg|O@ZI!8)5C|spR;l%L#FS-J_u1;d&2;P6JgN^fpl)}h=jIBP z-VwHY7faHyCF*!xW~5NAVO&n}^h1rb!;@JRCMxcQR|gbR6+pUamezb}$#H3|?P#9M zpyRk!dPb{3g?^pAc9T2jC+x^`k*j=zuLDvvQxibwp>dCWrr(9su7{|<VFKUxf8)if!~*Hx~sh0>i&ePBBqeB65hhs}GpS{4>s>ONh3 zfPAU1!pb z;&{YEx^^W#a|Lb1OeH?*-b zmTO~LSE+1AtcPX1QDe9b4sGLUvdYL*9@65B^tptsW=~nPHSICbWv6AD{byL^i<1mp zNt|4=M`S_+jWv0h|GdPk`a5F*6SvL(5A5&n>n!1kDnZ3}YS=1&U5pK|HTUxu-4o&& zPjoIxdSh9L^YeCPKd~&>JIp}^?r1C2I8<{NELt+oVn7Wr3r7kx`D6}a5ntJtoOWkK zmrt@hz#5cXVW0i%8@1C{$bCR}W?lx?oZcVH9bSP#ZGbV34ygx)klLOt_G_n*vM@hD zKS+x&wkOAuy%>jC&EN|0Xs|P%Vl#moC?z{LVVb52R)L33Hs5w8fa>lCs>%kcaLJnY;LY~q17UUuOoc&aAM?uKDB{|yS!{KN5uyxP&Ies?| z%*H~bYqz9j(`3CD$96@EF{~1s^}&(}q^z4?OAY=V6ut%zKNMAzF}NTrSr=8}7den) zO1dhfDIR6T@NM8{dwlJMhg1!OpiizZX`-`iAEc3aSv;KkbyknCz)@&$X!{oZ(aE*g z6h{zlBB7^e75&FDjaYKx&x=H?quE@BZ-{){)m4HL_ZhQ#_ecyJYAU9W6*#Ui!>Ok{#jUi*(PFA}ge5MfxO&)WHMW$t2HT%}N>NK? z^nT-ecynpunW4n!J$!cctEd0?_t-A{v}D764-F;cyJCS8?qNCAmkM3wqdiSvEM_|K zXzb)MOM>8}d7a~!_YIASA{dO`psS~l5Ikm28}KqPeE53wECu{JkOYY_$DWl;j!vQL zWykR=qm^BE@v~Gdf*Txvt*dFVn8g|hoA4pab|u7u#%m<~YnIl`LE@H|IG3l;=f+FZ z+x^?tRIX;`u7~BS_?MdlFTW_Oa z*lv$kQyJhS#C~c7Teg*t!SaQCGII0xu=+*WCXgVLQ*4l;9YR0x+;X{R&@D-V!4y?> zmPfu96Gr=;r#nj3$M{&f({pjNvH*5=a)<}TG)Y8jmZr4VH$;flM;^vC>d@d!y4iGm zPhB3zEL$ikFt^OPbM9_7JChYpcWk@D&JL41Lq^o9UEnPxBV6i9XzF%!2MF|`ErUT8 z#;(hzUJcTV(}X?+c#$>A^2|PIy36Bfjp7b(3^DYDi)jb2DiPAM60j8Y>;VG|$m~Z) zuRc1Nr1y>!12gVFM)-(QfB|$N4?Q{Ouu(3dJ^0(*AZOcw9WBc z4VSA=Pt7^L$^jds^$OAqj0X280xO$s(jVYl)6+#-{C>h0hAsl0?y4jwT~vV`LRqGwar7jJs4 z1HnI)Z-VExVEk`q3ZUPAx1PNBt|&f&jv>joeU6=XP0&;~arztE!UzyKdJT@qD2H*D z=Aj+XRx(Eb6rgh|a|GG`;6Ela`CP&`m~tZJ`()ytaJ7ioGoWYn{(G**>iSkbpfCu& z{ahh|;ak+QGKHKe0RkwP+fFOQn;xG!=S>lw~$;h{u?ZiSUVApleQy9;gU$W?@C9jop)RnY1cRV^{x?+cs^@AC+6?U3JWyckU#U~XXI^P}4q3s;F4TNPKzn@xmnRvDMKEh8Z-lV?5UN3W2r z!scmR<57PYk+TEM<n6i9v8{4KD%4=6VAC%lU$v9}`NiUbhwtihqu*-;RhV%F?>U zSoy7xX7jc6>QIx}@H*oX^9r|VDQe^HSlOdvDgo{EY_TJo;}&{nrjF6sh)p$n?Ggm{ zfUb3aS^0!`zx`4r!s{0;dwCDr@X!tKy(RJ6QFe6sKh^WJWy@nudOS^5EE*DikEGl? zc!yqU)3`$uViZcLwW3%rURo@yUMRNn^Lg}1Ry76$$!7qd1i~{M0ph>-(>}czz`7>x zv1A#?=4H#ZXy7FM>k9OhYwZgB$CUruHT8LnDqikZpvw^?TzmY!yom7L9lnb@ddb`P zTs2upAz4t_A=djd3LGujN`%OyAS;MdF1VoEe)%m51JF-XD!%Fh zhdPy_Q!D?@IK2qT@oB=>|~rz4vMx z5faLGs(S^VB_BkoqTwtVd%g<>)aiz15zVNu3y$K)LU~2x7m34KPbjB!|1baUG@;I)5A%(3Ff{8#N2Am_vVtGG7 z>JW(TatO!dF5@2~n%Nri)5(rew2nZRNAuw09sBr?1Tq%Iavba*Aw z%R|1|ubvPn>^v#T6q#V|7cNXt3(WMg>UJrl>gShjDlW%`Zhy43PU^A{;u7rnteSWQ z$?XP$E<1X_Po7&+pUz z_Z-H2g+k&bt1863zkLAPb1ftF=djCvaD~uUbHAP+-@)lA(_kD=W!(>#Fu?gh${C>Q zXdd>zHrg|&MtfH$>i6xoEHC3Y{c_HActX>h7X*K-n+4`(W>8rLDE40$K^MLKwGxsy z0=U}*hQB801lMgdwg3fx*@y66GK!L|0-{Z*8MQuii+{W_o|T9{m&6@LUV@qha4 zUC?rp)Z_B&F$Nqv;b^2s8&p?QGSdSN~pK&qRY6(?S# zS85nwG5N@-;{##`2sDNunUigOQI>HQ55%PY@M$5kO|*f0c~@c<4mscze{##Sj9i=O za+z7nocZlv*WY6(@}-dDTjtc995}?lo(y{)?%V;b`|Wo^pzLh|fA@_E z&D|u`dbdyiS>B?2k$EWQg5_# zHjaZ%M*{tn!XS>?xhWdPs3d6~w47PkSP_<;7{_fN3Y`u=SR}^jjE#OtyjRI!5BQm* zY<$4HOdS!lO!mmQn`rj;Ibigv0!+421fW&xU#|h6I0TC+L)AzqChOSt89rzi)SHYO zl!*u*Jy>UpIz*M%gq7Y5ja8aS&mAvoBqsNt&XQh z)B>ZXxr3_RhPlKJ&3JNnH9#kz*%q&hBh-o;a;O0_z8n{a;mL65cXf%9+3Sz-^X{DM zeR1(OPqujV9359;HXNUV|Gj0+fC|BQuCB&2ou}3p%l=ZhCxO@`#YhP~Qw3u!)!kCv z%1xGCGP7T#Ubm+k-e0zK+-hWf6z4R^9?6WZ(su;hT*}yBm!m6F*NIp!&)DQQxEJBt zHB=Qxy6n!YY@pGpIbCVK@~Dzl({I@8jT!k#N1ET+Fm@XDZe#S&zg*!ghD&oQ)rNg4vh(U!Mc1y6!qCQwo!LgMkH1_Vp2>qrT}A73tB`uLF*&IMy%?fXYqfcj z2$^;?Z%o^Oj-<<>t9H(~tG;zg zB%vnGc@_7}5l2ta_bU#c%axh|c76LcRZ=qqzt!7W$IA(5ohWj{^GkftSa%7CXgkiM zvhO??n#Kxe5>fs`A~utL4LzU#&?t`-OTChMbFO`&G}gae`4n0hv9-*^o+=+zU#_Dx zdsCdrf3-SFH_30`dvP2y77aUO>lA^>Ky?=p?2#<)*8O-}tP?lM-auK#++d(3?{62U zOhz8Ck7m{KUUSs>drcs9UU;tFQ zE;km~R_HbR@w!ktxL6$u!L;y1#jlwk^}snCz)Vm2P`)f|m102Bc5o;e40y7#O9fcK z1`E&>ROCac+q{a7TLlt#Z`qYj+CgDyoK;Y5vSAO*DuWLV2C=7>c$t6>*<)DZ_I_nOSI^B1&+Ro^W7!$SvB<@R1djv*%t{zQ zGj}WcU1LwqqZ`h>6qzLZbtTPN6Thgo2KK)@#R^LFjG4#c5Gq47bN%uq?+ciZmp)K`%&>&EVCOBchZ#qg;_RU1kIQEPIe*4V-Q_aN?vI0?6^r%(^4+3nWojSXTRv!b_d`$9Po5Qp?J zU0^olRTk8!EciP&rL&AJjy*4cTYTjmGk5Edn7}Px;IWqnD{$#_CMVF}E%*-iv~RJJ zU3d5`UiQQFH(Olg)0*Eoj}vA(Y4VooZbJMLv%S(9%@9A?_E-4xX1q>TRNlFk9zK}O zJLp0>uUtx)a9ljadI2_+Zr$u^1c+PZVEh$Vo=X*dbWue9$46M|Kns$c(xq@ST9LE>AjWEUO zyu%=Yo~Pu!INVDeJ{c=EvY*Fw+GUOQrr>gZP<@B{MHtZm!%%1(45~y5NnlqQQlY-_ zJmqTdD9=~lCz`FGpYfc#D;np{Wi>JWh(=g)Po1V=hfH^X!oYY(F!1y(o`B`AyK>dT zN}M)0-#Z5flsNTX%C^elPn{7Q`#I@~P$xlKF04~UHXfWTm+S6XmM5k*;A!E*k(-RS zg+~b6rfPLoYPhhA926ZpOH3#oyau6;vG6%N1bh_?Fn)6|idi}mC_MYgRwW)BGQC6> zG$_vG?HW|2A%q*zN&va3Faf3vx?H4fMf6xmLh)j^S;GYDoFoSw{HcYEz|^4^H{LSZ zu=_LK$MDu4X#=GFZ!LXvPJ_LzmEea#K{FYd!$X1cprwiBS!3THirak-ckgDciG7?r zSw+b`5plea*1`UK8Pg6dCT3oY5&Y*R^F;zo-s8}e7zoG>`I_f9v;039OA*LO zqBl5EU$h;GS<-~6%X&j({^hlWy>@6J5_zfqnz@*L&aUIpghPu_$q>yO+fXsBS7HEY zC-wxZPmaa|055;>`QeM$YOpTsKrEnw(F_zeU%SMyD7O$7OWo1|EE_q`J+_~H6lm8) z@27S{hfK>#uSrw($O^_63y*mp<3vd~5u5@Q{J86|)h@8sIzN#K#+L7fpul2|bA8Qs zE}BvPUCSOi_(E6wpB?)l%TOsTUh@LWa3#lPr81o8_imWSb#Khdbs^#QPfH^lCHI7$ zz;Rre#h$(`9W10JTWG7{jwD4+k4k^E9De)FQdOy#MJ|DZE0mPe@@zPuKo_IA(Nk=; zvT56b!Y0AVcWy@XDT}eqOtsIZNbl3ZfCfe1xyjYH>IWO1n)0PfeX^-HY_aTxnK8lR zBNaNc7j)Ry`@_!d{y{rLS4BGy9|#n1{z|3&%B5Toob_t0ML}es9^1G1HMid|bXjhh z*xKota!&P%Blh|7ETwSs63wi8uD|4I(9X_oP3o-s^&|PGPKHAzkY;_Jjs7G~{&e@f zw|DV6@W;Qux;bo>8#^{EYu6=(e81a;oTgkPXBZpwo>6Bp^VbwF&yG+92go5i5;;Y( z7arI1w!xA$OJVNKa>Z@AF9;iWHvtp1cuI=SMMT0&r`fSiESKi9uebx-@_t8TMdd`` zGXCfF)CVZzu={1pFz`-Wzlcp6`$*xUh`z4SG|;dZ6+aV1<-5;|6ZOZxyu9zCd3b(W zC4!XS6|C_2nA(G^vjkpbRTbZXUdp&5KUfb{Ul_|(ZdIL9AcoAkEPlFOOetg^yx198 zXBaQ@ErLpz?M#_+DJ28$^r@4a(dG5IV%bPNlB5^Ncc4$am;*Z9l_JuBXSz0#42&(` z4JAG@3S^|x!Pf@EaCtIaa0g`Y(7SlK(y0=K_(w6sCpaZSV$+euLY-gNiS4cbFByI^`E*|5F-W%gzWg zhB?g%OTGP*T3RynMVH-I&ia3I0ql-0PI-KKPion@REDt2J+noH-ju$8v9ovX^%f*( z+05oLiz>h!{*Q;;7{VPQ#s2WKSKzSGTK}7W9-Ma*9D10s=u2qi59Pm;;a)Fwzz`)1 zao-j>30e0T7b7Z;{i9o16lRz>C?R^L*zzsmoo-fx48uwr&V!E>MbkBM#huvTC z@{;F+(U;9JMEOF*u8vfe1;_?|1Ckn)t82bBh;v;8NI=DZ{3waSpE(R%d>}HkqS&^{ z@yUx73VEbDdok1KnHp!#W@FlCcdZax=mQT6HP#n(zxd8g>v8gmpj`}(MoZ#P6}1P* zU1?9$6t14vT~Z#972-RN&@lg3cXR_ zZ<}@EpVaaDg{)6Vtr#yl{EgA<Vz}ay|sWQxPRN_)NXrCDUD@$2!Z^L zy!U!%GkL3jeoza>dH>pJJrMeehGq_9b=5u{=uD?k)7!=S{vEz)>Cp4li`6hiKFhqX zoDO9XFJ^qtLjPGJlwhxXS1>aRX%M6jSNQ90|8vRz`$qq{M4H~B5Jt1*t+?uiqjn*{|(Uz5%8i3KIhHcBW|BtFfgP_Y2fEJ zXuC;XR+?P+YE^Eis$pM>7u%O^CJwRlTL+=JHQJM&HY;3G6&)BuTm61NLrzd=wt&*@ ze)|S&b2S9pcU6JLX7dpYx`=7mP1xFgj;DLSj-P{QkE3w43e*cEOuCR}KbzXg=XoNDE1QDPt$eOlS784aH0g#i$Sh zc6aTh%Es}tL`u^BaeY6s6e3l4&bJX7Q5bjGQjq2)?yjzHWiVSs!?x_JZjxA~gBXEs zuI6?YWT)qlpVWwnHC^;k*{8#7W>f#?;Sj&v^W&X6yTPCqALj@@IDYdike2{Q26D19 zonN8l9wMqKpeG#ZVR-w_1ub0e-_OaMg!iGvJ$)A;R-CudV{Q=JODzV1b;daDb(*fH zcxjeSpQuIO&9A77O1_5!q2DjZdTBI976u=30FU z>JQUA39VBfU#SO#fm5-uP8?^8#H$%}(6w)nqy%Y#X5ysuR}aSgHX^38noSD?8N(NM z*e?fd;JgLO$B#j*A6!1Ebco|wW0s%w?03+$w(3!oEU~1A2Q`YVE87_rbH(%1MUrof zJ(a(#H?HBt)4>-pv=v9#+Bclrr8tb7jZ+kDWoF(txq^!r#14^wH1Xcfz0m@O1^nZn8!EulG)cs$e>TGrlX!n~%<|CD&z_s1K(8hPi0_A@wt z2~nyCKElUoqm_^>8G3OnRxq`M^DpTfqyPy8^kluTkRXAW@TQ;xS3H_XN4gSC%Pg<9 zFR;}@LP!LSI2RxVky4y#C>a7^_>pELg@9rn-%>pgs`_F#HRYcxsMp{wH;F=ulX4>r zE{P!Ygf3e#nxrhRCAJV%1CMT`Y_uKvp2&&eKfD1ns}QDy(*32{r*@WN&ea17=tx8b zPF69ai&qg7gnymQ%+yl)eX}er2F})0jmmnX3qKrXx-NeJ0+!ZLqOfxjBh_tRP8pCM zhT^^ZG+HSIY||1UNieA7z&Uxq9>Xw9<6&Hma@WrLEKwf6{cNZKw2R>qaR6)N=o zUNX>cq9d4uOYQ6CXps}!CEIJEPJQ?e+4HVe?$$GzvkBba--M7iJ z6j)|62a(lWK%;A*stvFExox|BRvet*zVL=_>h_Re2{bVp?@Mp$iN6Jt?k1Neq`7u_ zj~Z9meDGlahe&eUk6K#6`@3Vc5>x~F6EL35RaCNwy&8BWPwe&{QD(25_e_(qSZX|u zO<6&clJ2&Si+w41l!Qg+r zF;-kWf(Ae8m;?^a9*iP0XbtBZ`K1}vwN(I8m#@`44&AJxbpZmLBot{b3pnb_4iwn@ ztt#c0)|J2;*7`eNvXq30%Yug2^`3|WHe}wzD%B5vJoCqqQJ&dB6iDe^ICG2a0k`wQ z_M|^OSe`JidxQXD6rAg?@hv4=?l45bAcA5~f@G(pAAbJTnNvH*jQd$R0~${AM2cK~ zwL4CQ@@kz>55vF!+joAD4=AF^X{M41{ZtW}0H z+c!hD1jNX#k(W4FyKNz`{BH|TVhA3UZT%Z2Y!kez>TbsxF;APX1T>EKV`(*zl!%+! zouX~XZrYgUDt-zi##lb#b@%aG^qJu4QM`JN3rC-H`Nw$2R)^HaOut1H%7+}+F#uNTw1 zK3#bpR;aj*;JSHVlMSx6oXYKZ7`+2Y_}}Tj=?R*LJN{8cgheaaFK2Y{+lF{H*8}vZ zA%{lIch7PftlO^X0nON!?n!zBohvApW>hquDqUkT=uRqRY|9aLn+_smuMeXd$ns;2w?)VxUuEdqM z$ug&8@=R18-MvGogO6*|=w$3v3v)bnlcUc44&_TN%e=34CGkx=(^j%QJ8$u&#+Dsh zWWweLql3fcxLq!vRt7Z;OI;!!hlBDe~CH!oqe~las1i}4@sbAQUPwbdpqKn;Up$d_T zK)?qELBDyZ!v#|Ggq$myQe}?&0iw#LD%g&2UxV4t`^za1?5UHB;u=`~k>Z z6}qtGLye!gC#@!)P0fpyV-p2SJ#@30^vmMz#NnIG0)ZtzGY!Wh!kEG5<3pa0xojVO zI_JRtuNzy2n6CL?Mu3(3ZC|U>y@xoNjA%)vfkM`E;JduCY*65KZG>Qrp>$ z>d@ci9{18avm5Q3$0=2|-F=Rad%t{U7Z8dOhGB$BrZg&@^fK(^kY@Rr?>cW^Cg`j#w~Y>L0@NX8@&`?7O__t%*s>7(*vQWOjF-ey6315> zcPD2_wfZ%h(oAig-sqcBTp1E^JIA_wXhK`k5KUih7T2ZTU-{O=)Dfr{*RTiQ7V4Pv6xba{9+!z#nd7fdNH_ zwO1Yav8SbzRTOSz?BSq>j8b6Lco)&F$?_MFM2n^bIog-}0HLbC#`{&8{ zdfoRU$5f8~W%z3s$>2H=LpVrDG7M|3m4udw_CcdBlr3x#|GVcd1Rivc%07JYQg4ZK&a>wY@QfQD8HRhmKI_|^x1SguHpm^UVM`~*wjGrhMzBd;_$ zxj;lS))UW_zW1DFtQCA&(Co|@fnua-s6 z#wc7Kev8EOO>NzOPkHM?ZVptDkr5cI*e7^aK#2FdHY@hMbDWl=e?>i;)X@iP>Iof| z8<_grWSX$hHTUnq5#Octr?s=ZP6hH)Jz1$lUEjuX7ju2x8p(^{#y|WaC$ z%=Oq@2?m@pB*H0$hRW9No1sLyQilxn2USnJOs;1sI-&`UG z1vwjj^;$+)tfw~E1u6v#jn&ykxWhp7l+hZ1v6SMJ&m?WNGjS!*&7ONNsyKX!9lWrl zK-Iom1k^QsV~W9RFF)SCPYW06zUotKA`7HF{RxYFaqSKz)|zs8I)mH}%22-g`V!8Y z70SN9nXEFcTtE^}OXfJ<5cgD(4FH>f8c_P(%A_6v9g)&$CxAqP%FDoeuRKTez5w?U z)bb)HL+gS>&K>*xE4Rz>#3|Ft zMtdQy()qMwAe5HOs`|s{XQB0++~#EE?kres7bX<(J)w&lzFqwZk5vwQS*|;kW*s?_ zdU0E9Ty7;CJ{M1D{nELI&K}hI2(Fxjyc%y5y!K>_1h6gX9?=&6w$f@tZd(xcP1A~T z{3(EVeK8K|7BJJdP#d004mVL0oX{`)L8{^(#Ixjo42Z=N(h%`jg;WN0T2A*|l7HIxo@)@v2rq$xhLmM@)jhCeRfYyg3i<&_zc86SbEI>z zl;_y)<#-e9XQzDmsi}EzpfP%zePjY)c<$^4T-teH8AU;vs}0^BmLFEGuhJFG*zSiX z#sagRHn*UV;zjwwkO51UpK0QaSqgyWK#0o6pEi#TUxSDO2sXH3!4H-@Ta4UANU0;{ zUyWPe@&oN#ND#HF%ugEsxQltP)MG*#HztA~1x*z^ng86*0BSD}{_UoNslgVGaH)r% zJXms~BZIPgz5#Ga_L)9#<%yp?zr$560h+?r!4|-rl|R}>sIT9+bSQj%-1X=lMsvgm z7eB~Qgg5_6Q@O9!%Ke|PKZihE^Pdykg)3m5!Iq$Q3i~eZVaPt}dJ~t!xzK*+!ARL% zia=U2=25^~!!? zGbOQgDqU6ud0lw@!7kLJNLhNsy_`3N>`0IH7$@AWCDa_PDRnVsPyN%K#Rcj^y3{b=1cx)n*uVn3}A1z$c@3WE+KFP62V4_BKgLTLlrgEV|hX2`{lPewaIaffBF? z)S!+xIBH?yk9qYxf>9xei!G(S12>uh1Kjo*1MYnBOed|iUr9e#8W?+lDx+i^qj_fh zz8^$H&00@b-BRP=tIKj?5Uvs|TV_92#XdxJSMiB|gli2gZy@s5tDaf@g`{P$Nf$0c zAy8n&s#U|w*uICjxE=hy@qEv*bmeM&VHR(ev0t>@{ITV1{!l4s{?eXk9<$Eq|SMxCwhUhdBktUgWOa5Ws;UNMjOR9fjGKE-5bIR|(c)TrC0MIShc6YJ zc1WP^1)B+Fk|;*Ar1;w}V*eTd7!)Pam=#1AI~dSzaC)l}9Yzrx{Z}ODNsP(|L#y4; zYdv%zFOXtvM+e_KuaVRa$7}E2P6v_6uKW}%(7yn>7O^h&53D2UTu#mh5iT7Q^%nc! z23#t8x@(VF2^j_CD}N6JhSJ7x!~F(%bpC?A)qBW9$vNsIe*H0Z(hCk0jtZ@@gyFtK zXNdBL?9D?H1_h^%Ie(e2cW1z@Hj8^rx?_BP9>5v*5^B!8*xVBaHkdDzF#UJ`= zJb0*-v*$F%{j@mZ6m$XfRKm*HE|y;_X|BK~UWNd}?*^pt%v;v^8qVqmT8;i>;Vpx@l`4g1E4$oo}`S zOQtM5jyFd8@ssLUP05aL3C{(buUOPE_7=YhD0@`T0CseCaUo5*8_NZJY!ow-`#!gX zX0D!Fe=K0BsjKIA!VlsoKniyha5SYkxq9n5Kk8+tZ^qkkd z7r6*BdZ{`NFLlSs&)q8D=MN5{ zt2jPD(>$z~{{He)8vuU@xx@T-g6OdM@3vz30MB2meL2H;zR?DdcnpEh`oho8^d|OG z7ZOc@Q13`yrj+-PIS;FZR}@icS$F6^|9pWq$+^1xJj{du6sHrif6RE#|3TaD!037d zkSIcwu(UBRMspDl7>i_Lpe32gct5|7`X*%_sIgJ>t0(Ya> zdWX6Q6H@G8RiiBOY+5pEmJ6NfcEcRAVt7za_wrY4yA?h>p^iR9NuJXdi}iNW5r>Ka z4hoUfmi$8i5|AIG7x%A-ZY@Hw`8Nr4zc;@@eq+nYqG=W0hm$L{TjH6VhwRK33dMhW zO$wo>aq$k6Hl8MxFJAbY3!r;NXtU9pl!qKJcoX^WV-c{mKWp10(`UIHamN< z+}vr?UE}16&X&7kw5IH@mJPwAvX+Ywu8n|x6%gvWaN^`5YP8Y#ka^dp=b#>x&D&3v zYQiU=1)${gd~-XF8poYv8S52z&pD+D654IJE0UJ;HF$etDLc0V=7;zo~@CkFtbyGm%akT^16k&kGpcTFGJ3oP-QNP(YuzqjKeXa?O{t_svF#;zodZ66= zA(1Hb_}IP5cTP#{OsW*kQMugY)#8JO%*X@*eC%B?F8iQ_Z;srV)(W|0f|4=Ha$mt1 z`P6&-S(^Hh4f(~liF^6mby@X+tH(H1Eo{>kgZdIDE zehT)0EUgF5c(~Hh{;h%G1PNFqsvva=jU?#1s3YDD?hKk`dM6;NhnoF)uPV6Q=Ty!3 zBG@=n6FB#A+LyejO#{$$`VKt#Z;S`Q*k=Ji>$rFwUzk}mXdAtAx-4q-*k)V}D(3GG z<8trPu~<%(z*wTh(|)F05TOkuBshOyR2y((eK%7g3h6oN^MJzFroa0MmQSu{0F)z8 zpS0yQ_EzBCTFJ}3uC3gZU;!`yUcSk?SD3_tT&~!Ts4DVQy1baLlgfdSQaqCnw)+H4 zfJ3Fu%Cc}jA5dKt-=}GK(p5R8Qs)lWz5q-#40u55yN2*VE@kz-Z@7{LG0uj;?#lPD zHR*SU|dby*3Y)nuhXI-RQ&^%~ZkPUEO1rWPOWiKh!T|FB>Ep5j#L zD;4FMH_+CeM_Zg)wf=M)FB^wme0fEY=ey7R@>;#bJe%AGZ=Myh)JGu@eBxHVJ11mo z*3+>tpI#MQEbcn2Lh-Bti=Uei#eOtZFE%W}@+t{>O_pj_Rh+UZ^eX3o5)d^8sRv2+ zaBnrX1l%U`z`zXyth|b4>uoKv0ig=!oQkDQK!O^OITZ6>98U9;pnX-+oy1%$nn!@W9@q0SYE(jR2gB9f zU&)OB9j?m%*$_J$P5uTXCSz^;&BCfsz+6kJiW6f&6Mwq}(zG+27BY!Sxd* zdD8avmvk~P2V$}N@ivcucy=T4XKGL>&mZW9!SZy~j+1)}k}#Z3eBn(B|Dw~3I&u;x ziGl|f&ne+>p2a5W;GpBad|F_YAs&$(QUMqaX36S6vdeP3L{dptNctN8ZW6!2qb{Ib z5X*Dk1w;!-?nb(3`1=Mtc1qHc zw;uC1eEJV9?5{Tx-ypFyO%e`<3k-9q5`!Q%Xs6DK*+Ux#_ z{TD+lQ*AUo^&k1f(nbjogltvj-DG{1Sz5rCZ<+;iv+?tP;jXlOsEhcF@+(iiB|{X^ zpWt~x3&Uh3({kJUkdX;1kK(u2dbKA9C*;aIQW{yV$tddO#slAlx7;ec69CXQE}rjt z&uk?-V_FArHy7FU3NtY=)BS%C3vK*gomi4eB~1)Exj4mziiY~-*n2Fv26<-O{^h5x z)o|d{L+eU24`!B(C%d!USf!$Y`qjW%L2e4j#7zVSFzXLvZW#=Nl?`L zyazaD`6Ey)6@MRTErFzU908?Nkp-~pfe(BiiWtADOY(?N^(_0383(6t`}ewo z6guO#USrI!goMm!NXSa};o%K8dLX__)Wupuz}xenX-c7DRO2M^5K>`Enfhdk*RM(E z-Lw}`h}2i(=YwY#@iLvplz-EMjezMvz~Zna**9aAc-co{zcIv#Oc{#>*$Fo=Q$3bV zAHqFNp4IS`hVRX=jU8{9DU}r6%*w;`tbBa+Z#2$Tne*Z!z=yAa`tU{gO$Yz`;S>D% z;TJU(cwU{e8bt$_@0v0g_*@5F_WUnERmrvwY~qsL!d%`a#7a`#_-_);B>{9o%=N3SAUNZ=y|G~bUTih zSx)fok80V3gb*@^60@tZAX5~9U=(%MCAgPWcfS%#?k#o2SPhSGZ%`M|jlvKtU=k40 z{O^+h+Slma$?v}jJ+dRP1wO_1;M@cuQ#)MmXwze_4Fsh7El@c$3fre-Rtf9C|9yro zPSeHYE;FD9GZ2{VJVB#rJw$STj_48mJJ)sqw!*PpX53R*#y-?gG4rc_$VqnO+V*M0 z?~G?PL)|y>AhtCL_%I;k4l3eyflkN>pC^{rJH8;tSCTvk??@}!`~eXUcW=7*A-iE0 z%l?din&fJRKVjw=A5Gu`SIf&Z0ont0iz@4BHlSL_f`1LF;&{P5Y>ou5s@n+jx2xR) z#vp8VAoE&Lyd{MUBnb@gCwtlf6GOT4TUhr-{DJ}5lGOkO-~l482~NUK3~>m`qgs~1 zV$3cTx6Br{5T8pc2&e`{A}{GtwsmYUloAtc`5S5=i23gWK_3YmmP2o!m9{q7 zCMqA~^(+OCf7A0R47|s&L*kaqUC_^{8$duy+c+RR>_BmD65&jT5Tp@%pH z^SfH;SMkb!9XQ$)99#FV5c-O}S2AD!#EpM=2k*y7e@vuuEZwU#ZJSFfBB6RGaR14V zR39)!yo35mo*qgXL%PF{h{O0L|@{B^i!@;;g#*O3ji=MCtp#X`!A2}o3~)LA^Ejcrq;=XGD6FfS3ATXWTZU8!fm}6E z^bP}!TQkAvWg)!nvQlv19mvR(j2y)h|=fuwEU*C$rP<#mECd;0D1 zC^dSnFaK{JKJ|`o0D;^(4J>8}E`yry9Q3GOJuKJ+@qxJXm zCyO0MT0IRgC*xI^oJSnDmfY6GNo%zu49r0@P?UNIAG*|T;x^rL$P9@k5Wt;~7hn*n?^>>?d zdyN3UI9{TRRuF9H#a}3r&dF*h)+wcl!6ef>&&?Pq7n0o%x-vjeG6W1I6qJbrz1#nT zw%U5S7Isowa|$j>Xw{6XJZdDjhZ+Im*-aQHgrN4a&QP%M8>dE$W*}2%XH;|_6WVk9 z1c(JAs)-<2S8e*||NOB3^9?==nlUxcujDU+IGNOFSzhCc(T5LF_z;7HgeR8sg5Ys# zRE1z1&K{D}$Fqm!uYVrZ4`Row<#e45MA02jme8`$jGt|ygxJsIiP$qP2mU|K-a4%6 zb?X8ZTnMPZA_VC!K|&OeMnO^#gKngxC8S#rNogbn6@%^$DQN+vr9-;A?p$u&=X~Ej zp8MVVtn-J@evZic{oZ%ZF~=Np%+s%a%sX*jKP$51URl4&k|BC-G)btD8+W1JEfLZ1 zsKJAYZ7XQsZ17#uuHn%^$kukdl+|<4E5vS=1B$#DT|6bcC1(($0FhL7V_}m z>(lH;{?mg`mj+9Pv>++SjI$kI_+O2nxOe-mqUr`=G;kn2|h{7i&Sk!P;HR*t*83w zAHJiVNMsESl+0En;z@RrJ`ccVJd1Q`i?_^+Thd z7jyU2s5TZE)>b5bim9e4eI3D9mlla*;?xm;7 zLoAdbp|Y#AjM01?5Z(wznU7@X*u`_=)?mV{9#o2KkNUDGd(61zb5*jnCm_5U-8W1| zoi?v60LgEyeJxNeQ1DK8r&{5v_J!uC3XxxU^qkfo5=fzu!VpN z%i28{#|x2w&2m(C<$Wh=mW?5d289X)MQ0qDZ=!B;ZB?tu@0*+jH@W?bl3qBG2Fc-_ z^IM|aL~0L%8#FkBh@l;ret2TAQ4u)8sa=rcIF;lPU@#>5M*1qv3lpTpKFkF?!(1s- zBVrE|RgcM?C*65;U-)+0OM&Pu3SHrQ$b`aK6{H*Ex9+bXj3{DB6w<<+VJG=bK6|>L z@9)z5a0-Fu+oj1Duxp@%kN4JR5aSBA&heUdOUM|2XfK)qBt@-f4uM@k_nwD(RQ63g22b%FXjU9F; zS9IBvoW%ZFNz@&b_VnD-zBkz9LC1~2-j(vKw!+@jxb=%R^|E97>tK1%YKi6@m!6tR|o0f#npmAV$L*Vn_QbqjqgmAe?4mHgL7o!I@ZlSpP zgAw!%UhS3(;pF<9oJlC>O9XpG1!u zBx{Qk(WV&9eQ8f=tp!hZxU(_kAdPwsRShz?d40%LoUOgy3Y__0gvwY55WLTLPQs># zfQr4}NROHVH#SMQ1Nuj$?o3ceCS2?tGETIQ4nI>dFt6co*4thK@)s>&gOB||`>rtM zwv_@WcNL6biClnOos&I(-lqw6O4q;f*H!s`TW{vlng4ciW8vZ&g^wj6GT`RwIjzy8>;{f+)rP{D8a2UmPx_Br=MBtAFJ*{=RGzdv`&aelyeRpEaX zm30!Fqxt*z()?7J9yUU2C2|c5Q3S5yieL6mBvE{HxTP05#_^M$hOS(LCJC4riMp!$ zv5GN*roUhbShl;1%fJdbv6bP;A%z}KNjF4``<#)qc=p74GMMj@&CdXJ!6-|g3;FxV z{_ z&~(*Wy@{ss=v;}aM}}w-+Fu{hL3ndD)=vr5N!L5E17&`_QOm!AFrTgp#D^&EW=M8g zaphnqy7rkqRN`dpg6hbn`|na-m%AT1?>V$h!tP7?01enRJha-(f+YgOE`YeDz8*tD z(=dnc>$=g-C$%It^pf8uwSl<&9LU%RpvirA;x2OW1K*`K%?4eXUoYmLF@^>$0tj?@ zg5e0yC`fIKGuuwVKk+dwa{It^VKP|dN&*CBg1M5Qo4cx8%j+_ z_g0*nZ0OXlkJzJPc#WRpXPFDScc}@8fBrNS;HLeFUq?NI0S?`3WPl0JP_`a_aBZ%S zhx|j34e+Vu2%r8I%Z@?fd1?{O01%Jp42_AO^*(_O^SO3&ceyQx`E$V~b?7jW0~YnZ zS2_TW&`vIAkpQ6>&)cpa`2Fc@k_*S9>H(&oFWlZTiw?N`F8NBqyeo>X_ncu&Obp^|P1GPdM=$k4 zsDF3b;&BEd~F>}0=x1y4B$lQnuHwZ*Mm3&6K1H!?guM?zeEa_k}> zxC2ZUT>KK^mykw-8>6_o=K=I(Mlb3ioO8ttvS;k!IE1=TyIzFqrn{k7 zfxmNt8tQ0mVq;c!-qwh}X7)Bnj*QQ8k!3^}hP-}2SRkO9b3Fj0&MLmKQs!Zn{c6%aDRUwxU72&zbgX zZcCk>lM-eNda|4;5KV1aej(37Hj$V8_FqPqk?|%ar}{BuNhTR{66D zwjnT4%ZCt}dpQJ>7eqxB>~H=az76I9;Lhh3<~;_A83`=n#Z<#Jw?7=eP)H|vUxT^sF%-pDT9nM7LJq7Mh4)b4|b2K>QIufooe0q8=ZLQ7cAps&=E&moPo9{64 zp$B*uoaqEk5hxQ@0^RDn>v&w$Ot*h$)&JG35JR7nhF~zK`jI_C2bJYIx@>4N&Ne^nV$rBq7Q<@=Fi`^rF$R9mVK`mN_Ty#?8V%U{1ujyVO&%Q0CC zG?InTttQ@@pPw-)a^UkWidx@bYd^-;v-wTCe1!g-m&o|oPO0Sz3U6bOXr=@ynVVl( zzRAB2owqre{v>)$=$L7~2|Pqetza>Setfhmw~08{y7#P(qnyKp?vo=p$Hd@t8Fssn zBFz;!J=oB6tr}7L*%4aS=v3~B>sPXMoTj6cxVa`O;oKG3Jf7{KysUTy+gpza@ulqZ z0Q+bF2rb-2rDLgn2l0OZhg}$M4c%mZ@b(7!oH%5XE*WPkRE7~F#x_~$TFn^0g|0_{ zy0!;gX}`E|u`+x>4sEY4ZggY+@TL}(kdXJ$zxo?D6nTBMJiWhrY7$ey`6NQkJ*!V}pQL#?JV$w%I(8@f99n1LXUAV5NP_j~B;&B(P%yF~wgp3T4i z%Np$8yevZR_gNDP0~UF*S$xxjA?p6@S?rkxli%^({Pg?pXEwp5gD2t3 z*`rZ}(NCHU{$}%EBYJ4z!&glxv3KQYejF1yoZ!3?YWuqf{*RRXi6Nyz6pzPXMiQM> z3=Z;f$KB1v;NMz+B%W*V6y=#}b~IR5&xMUJt?yippcZ2n{PkV?QDC?d)1z5i;Ll*# z(T`A__q3Dtuc{Y*+)q?^s`+6ryUPqd*8iuGF|o7AJNr^I?W_6q@Quas#||=yb}^)_ z2=@+%@6Q^Q{d$05sVIVLrB){|MuFsTmzGYSj3_M^C+FAawZqQ{)Cmzt@?;=o;P+!E z`dN)2r0-1YmNA3{A-tCr^>#*)Ep_a_V$?sLpEQj;ddtBE7mtxPLl`>5#}`4is|ApA zX|7?f9x0zaM1NfzaOfu2E`^!N^jF#MRf7fe@`z9ML(W8w-B+G$g&3L{qP^6=z_cf| z1!M|cp*rl$nqx}cPrtv>%fHkMH1A~slq1CS|9|~%{p{BbP&mXh>eQ&!n;K3r=lIW~ zd}hT{7k(wT&nA%E-tLTX4#=hds^XsiqlybMhAOV>Brj)`Ah^eOX#j z##_LNM2r}b#SS7i-3c}k(vNylw;0BP|F8Finebotq@q292b^3^VFNz;*K3{`7IyMS zpfg(cX+2>*%7)>dkUcHO@u#vVwK>1v?HO`RJgWOGUZXXjGiS_iW;GiEF*{K&pl*eM zyo4tsPO@q+^%;|AD089i`o9jzpD=xr(y@$mlo#(3gBK09`B2eq-7C85Q_T|)@rWR1 zr8sVONj1P)Zbog_HOaLuDe3@JJ4u=_*1;2=O%k>D7{Ks=hCq@)kUKnwHQAadg+mYw zwWGXVE7lsx^}%v`Vs*R@JLb9fm~R)izW1+Z=WTR_4Er^MSIWV?{v$r$b*^)Ntm&{K zJlBtf+JfRpuwS1782NgNK{yx=oU|;uYjqTQ^{F`vI*-xt^=7fOD_*BCYEQJPZ;M-V zWhQ!$>6RGDe)vDWb=H%_oP>~{quIdP(r1;3veO>vw^Tp#I8Hr0QHHf z6{tJHk6B+(oLT-}u42l@+sQEv68=&NXrR=?Mph1}8`x3%!@2c7A-t{`4%>ObK?~b>tUlZCbx6@(kQ++BYEA{rOod*phLbSgfTR(W3IIsLk(Dc{tg7|-FTbs<1>fP*|Lz(d0z{^R%b+r zRw)AVU2tG0?|O9;)23U7nQ_?iISD5RmD3cy&D3Xn6(SZaho=Evt_&$V5h>{cu2&Of zUWj!Q{@=pqj}?zkZShVo#PSIFX*$JSj<6ngD~|PuL3B5#^)wDRG!KxVJBT>alRki{ ziS9G`Z|J#t%xPDloqDT}qHGOD+L0N;Ly->3z)7r)`QV|{dxmlY5sW={_y`xZYUkB4 z@i&)K5=%@yn(rFB_lt|?Jb6Bw_#~;@5-uAF&kHaC=iYZcZDl!v-7i$vV|l6`oskpm zSGVU*P~$IbSi>7O_%r@7q#Z_#xqWWE$PjjffUf!lizbw6%gl#KF^L`gQ%Hk9?qFhx zKqrd@DrkB@%S@}^M1+G}L$ddlU@pY|_^N<~=rIFzz_Mf{7mor}d{!FA0UH*?cR4CGa5_M-OlUrS{6 zS+RJNT~y<-^x*3IPtGKVpwWb2sBCcdVj6RR^RtPY*Jv!aLHL<~zO9c&PB3GcCKd6P zUGE|RXv{m*z-Val<7O(u;aYT$Z^?*P5(HEgVOgzc6(Sn~YML%_r#suHe& z8wQ%!41_>)nKS^S6JK84e0-IPnG`KQtG$w3e06QIN%G|Q=<=4uTO}AK>&n&<^~yei zrC2H%P_03uj2V5&9L9H2A$-$;isArvE)5C0r zDyNf>Aywb|ds3+N2?crS`nQ@dVJX-hJ-XEErNisbh_&51a$kNH7Hoxx*s@?LWSnWA z%`e!wQlzU&@R{Jh9QGW1%FW4Ga_rY+UZ6&lF|D(N8Og?7)zCVci1TnT`udgXnQnsPQ` z1djae1b%MP^l?){sCk~_JMPb=Z;g)dRfr^9OhV*Ii<$bc_C7VS^hUVv&oRFlfzp1G zbjHXBQ3iobE(Z9*4uoGk4DyDkW_}mEzcAXr70vG@plE)7U!&lfIeOje zCsL?`j#l|zKM($|aS~(UavWVAF8+Q;)&}mRitxDNzMfnu&DeL&Nx`VSV)o338KN9) z^mtt$9F*SzSHt~y&-gljs3KBYS=^d#L4~LC?o#gx%B(Riq@j3y1q@4^itZp2E~@W& zj1o4Hit5sNu0o6BPjx0eq2X9^e@;xUG|d6l*DNiKpJ#5Lp$+y%zj%X=S_+nnc7$4- zrzRWm!iOFnmOi%kcwsTnVbS~TA4q<{9-lz?4OP3fN*}+msAa_}YWNh0M)2i8#_=9$ z8z5j9cHLhI#FM##{YTXD`65`rw8nlg5+|g&BjxTN35VSVROY8fRk=;!zS=Qc|M)^{ z)54nmqq=gIY1LJqhyYfwzrlIyQf;tzEH_p(WO;91SYA9w4HGUXF$7kn#TwO*AP|}W zuE~gN`QINH%<2|lw7tA0=ahwdQdU2olp3iS7Y8;>`Tm)x&}2D%QtwweqF;HiTrQim zu3|u2RSxK&0W|~#P|(0PVnuM;4w5vtaR-GBO1lS^yQDV+>p4MV%nu6*B>@06xb1vr zh91p$r0>TC5XxLA9)29i50tnhussq$X-STMdMXL}iw01%vP841rM~tNGHgWo+5s<% z%xxLBKHr&dSq$j1fnYS4t5;t1ygMc?1rl!2haa%J5j7M%{(uiGap*uo)7ZCsNhOON zg|n8cPu!v8cka2`N>wzUp`Y0I;X!NoEf{H!y6OzlKkUirPbkMlXd={ujE92;_joEo zu^zO;hVk_vv5l+%U3{kR0Yo8$P-hY#Xg}lyi}O0CGn6x5dSVXD^`r;F_>5G*s9)r=G0#7n;Rbxbl&#HAuMTt^rEoTEt|VQp$TM<0VrAlt#d1jUpDAxh2ME znq4r{zB_-;rrdtv?dzBy*hwULm!Ta=jKbv>k3r(;&`j=Ik1R{8^g-LdAoRfJ;98$1 zJy&zY4+-unf$KIC5|C6wf8^s8O}v4j=QlyKqYy8w3fML=iiZyOHlo&x&H5Aq_5rnD zTuKLZ_fKlgX`(cQQxD*NgZ|X#7y7UjNS30QdH1rIN5gApXsieE`WQPw$0K-@rt)aA zl%el}yIF;~BU8-?AYLq?g|o!$CXtw_s}Rr0s@d|5J3H=MzU%r<@#TXUi0)9<&!Koc-N70VI`Z$c9g;?u6j06FP6wCC%r7t|i z#Z3JJie}{l{kJ552#PE@TyG7w*Hx7ZC=^yLegFu5lB`$ob}W~8jm?eJ_~eC7JMs71 zhf0HJ%X*2472}$r8=F0ft>Qw|C(wgv+*cOGPzI8j zeai_sZ-&kZDjM#GpOI@Y%pPBBu)J01l-qlDVT;eGEjHG)l@Eq5bu(Ja7xP-r$9LVz zM~?eXkYA={=vCJw`ff zROhT;>JB(IU7{RTt4AF?RxLO9idNi@FfXy`mq34o4|(YiEX^6F7E!cZ|Kj7}2GRD% zRj?N93W49d3lmyAOimhL@u>mb^W}VjSKhv`>hsmtb4*Ni zgCouhml>^|rR9qE3+UFILKPLPJ4^hpDmm2)K1VdiN;|`fP|dzNR10L)Fh_#vA#L|! zPkJb=Y+=4m^%q9C9!T4IewoH!hA; z4n-v9qTl>H{6>xhHS?WoH7e4S0{8ERvH9*Zbf%q$7JOi0Q4sa;YKk;<6pK<6iT_=G&Ar zN1kfk8->j$HXAoi$p`V8^~wjZrKeFRI}DoM(y)$ltnsoNx)I;3dkgZcJMv4ip!@6Q ztA8eM?t$Fm^1Vkdr{yDS^4DD$Tu=46rW3C&urWbu4>LmKgkVf?@1b}|CWd`$eIbI+ z=xA>!->Ru>RPw9xJ>8N}4Slnv(`1_=TsH1UuAdd$jf10q6vx35Z0vCn2GI^c;#=S- z=buBk!13K&Jp1ITg{LDaF57UgFh#^6=&z0JhTOh*>+&1dI*&NoUmo@UOuR6dP?V9S zbNfEB!gf}nZVpl3msgn^0+jX-=fw9Nrm!F33_8DyO}PVE2S4bfW_&rEg~3`*VcI{I zBE&)8rct>51Ue{bh7u=FrTMfyYB%ty6`mD?G&?lxWXED&=-f@5Ta0K{KczLA?=O$( zALSnZZqy%|plIl{bJNrpPWdBG{Pan$qiM^|cod<28EVuoz@O7{_0Yr#HsGb`FeL}U}{EX{aQ~zaTCdu zzLRL*)sD3i&u@;J`a5WL{+|W7MkBN(%bcdAtd?^-LzYWu#r38(w zPGx(8Od>ms;^uQj)N%y%T;nHuUI=F@P=Ra5eEzu)69HDRC&%vEO^N!eEVq7>BD&<#OFvuV zTuR4tSVpQDZ_B`(gi+Bk6LtEd%y#|BPNZvX-$l?|9Fem>z{gA?Ct+9Bb-j)gaTE5I z7p)oQK{tzad_3UWT(ZM}zGLRs4X=0RAhGmQy>MdAsZsQE7XJqB(EEGLUZU5R-zlX{ zy-sWTdG@?ASTx2IT-sJP{$A^39-c=4ugV^$7pWDV>T<}(Q^2x#TK>1h@ z5U-8B=&1;;q#~Kq^}gA0x=F9{wJX&2Q5E2f{?K*2wICf9zfJ(?B!oTHB(Yy_l4EeX zZgrkFSf+gzJiE44<8>N6)qp3Y6nc_x$4g1=b8IGWrBTu7O2mJwB&w5JM)gKiyq37< z>nsUybPnPL>_5ElAJBo+!c24O+7kB;AXt3BVR^SlE1qTJd?L&wZ5oE(t>Ko)Dn$@y z{y3XGvLm%UPH!xeOxv*Cb}^BO67b(6MvB21=%+q>i9e5Wajv|P@hCbCl&9#OB+p{k z+FYQQ8jMHqqf^+I`l`tt`Jviscm!Pq?Lssne$2CwK6-W^(^OPW)|~|d?!wF+$0Tps zt9(6;R1yBWWvQ&Gm+!v|qpg<|0I#__1o2B-YZCoIiM$ zJOL0p0l|j^I==X;Rhl3_Hlc!VUF^whJfQ426jFE_N(=1Jl3f9Mru{pj$!^|8?2jE5xI6e`hw5h@@CLr* zLTiw-hSwbY#KNn(M*j>X0@ItP7D~-U&=pr|utlRuxdRcAYdV8=1*gt-7g=aLz0ez> zTS?r@-5$pyRa1Mq_gFU(ueVoMIHKwpF>YWXo+aw@#K2bT)$;vQ3)t;0GgJ$~Q#e#U zTk9n@`ZVd|cIOq#$|3?mMIng6m*t;(Oh~GCTNyTrvKuy$abz&o39x3^yY7zrM{VUZ zv1Oq73VfjMfKe-Cs{=> zEAsXl&ASm(M004Nh7$K!2s5-KMa7*}`JQckTpiBfsS{{a#g%}n8H6j;Zhl%QZ_Rz6 zNt`y51{_ZIW~s|Rj9&}z)Rt1CFyj*Vf32!KOxel%X?^cJu0pbH&wpzz@yotBo?Hot zPHMwHMQPNiBjNpPug$V2D^we;cR^5*b4ZWTMNbrAfW`vv?u-KiwuRz_TOKRow?jFfg zx@F2I!?dfRHeuxToq6rCNbZKr)f@9)i&pVU5~UWYgq`cJs+>5}Fcnd`ZFa?Oo#GtX zk7?&3{iyi3h4iMx*%!H*yz(E!Pf?oH`Mw;`X)6J?_t^zWF&0z5Ydff+X9J3Y2HKl` z7j0-%dpB$e5OuZ%aU$EGS;{h?5+D77Q48sZ$GkOyIh6a=e57do$c0Py@3eSr6Pw+@ zjPQ6|Y7->$UUe%}##GHQm>*eefZk*3b4sNHb0iQnV&;=%OoRq*_+K*=uZu9XCh%g# zOy}?~e|hCIX>~?~;R_6t(c@OwEa(W-H{mAm%Ci`B`6N)g&+=N0ED|-0eN9)SX2hMi z`87!^-uxuMK#`E(JUBXsWdf@tQ$$wR_UBaAfJ$Wzmx5-D&UvMRLv-??$a^3S2DWXc z7oC$EUEyyM(0guStV@+C3dtRVjgMoIHNDp&O-j%Sf!V+u^*IHBsZsZ5%-{J9yzUTD zcg0K!WHO(#J&LR9z@BJy)Clv|oyrVE#l(X zRJDa)Bv(}VNX;xRR}8freI+{WgDp{`FoXipHhyT#Vz~*Q7}8**$^+~Iai~-~vG4{Q z$P+?;m?@2)YSrX(2U`2AV`S0L@m976YelU{uX?Scx9)X3w{|WOs+x8|v{KOo{*Dmt zvm0%9{)?uGOJ*?**1p?T-)1L{MMA?KXmXdY8&J?1%7-)|Fuc*#Kpw*E{Uu&nb|%?8vmOjorLcgEZ5ra*vyA>WT*p(~^Hz~# zQtpW*uiFH*6By!ka?e8;G0i<^^QCb*^hQ6UXFwi!_pq+5VMwLpj0Csm8F)038rQo; z8?0ZTTAX&A$?eIf*t=+bUc}*V@{Val|B%dq@M!1UKL@BZ3;98yP6W8QWj6Yk#SVhCq+iW&l^@TV7=N=uAE-Ks-=jvsjpJXfFD$vV3K`=Wef3r|8 zvDO>@;9sL2iiy{~PYk2<3&(aZW`Hu^%CP7JtIEv&V7suSp6Ji}4>-X?_M?4Br_e@F z#Pt??{%qi#vk63d_odRe0xajrlWgq;4Kfw~LS?jzPw79X#wVs*=6J@8sFL@-iVyLX zcc7OFu?xB(o7C{lfl_H9zi3#;;_oK*NP^{(SJm>71 z(~0!qGbtvYScu4o)yyA4wO|{Vu$l~@wF9 zRNA8G(d8M6+izh){dmA8$YIJzquRZawxV|ue#lz6*D<@l$H7wZ_lJhQ;saaQrdXNz z1`(~+6Z~6N~|4~#zkV|*iyH}!&yr$JSEIpdT1Nk9U} zY&+Hpj%}d_A?q~ueGi;8izM}mMRHLZRlTi1RgcWT(8OM5I?E4O-c7)vkbHY=sY0Bg zbOhuEyWZA06-}F`cSTnlQNzQF5=$Et~ z<-ELRcFZZ3kcNu%yn=4r9jv6!CZTc~t_x>ZJk_$>`T zyF1u<-QOKIt8upqkbn1?SM2av_M=rIt~=KGRkKV(KTJd8Q>og<8{CjZ@G ze5m`Xfm`3 zc(h|};C!gR0n>fU6t&|a9G5C!?HW6+Rn?vm91E@1R-;+HuW;a^Y53*cS0BAE&Iat) zaqd%z9%0;_TsfjovaStZI$Sce&+Ji9`OF=Hs3p=J9Ab(&|apdfFegv)1_MeCUKf_cB@fB;Mn03T+3Az_iyerX&k@QKelJ72~i;gD^LU6`DG3Ee! zxCZP%;Ekte=c+Sj_MS^K+~uE6_GT9oKynSe&c!QEf309yW*Z6A0QNJSqrp#_9%tes zl#u4d(eqI%+Db_O(qmhgw2&RGaqR4fd#0b#6v2h4rMgXk>M`71hAy@M(+kMAFie>7 z;A>MqGTHe%hz#Dmo@Ds?t&bU6+TZRem+?)iE)d=mN1pe}kH=ZKu;ok!OVQ)sp)b4# zudj9RE52}7=XA5Z?F2t%qY(Se=O|goA825|Yb~NgRUv+q1o`nLIS1i!TAQ7sCz`n= z+a55h;~;LJ?SiTh?O+k4DfTF8>QNr-z}WTlwLEuJT^VJK78&Ty$ssA2M4!o+eSP;T zlA2EOnOZg2_No5R9F==`gHd?`wI&YLsmBmn237U_T&*mr@=0iCo)yf^NJ>tmafAt0 z=bTvZH%l@{#Nn zB0qqdOk?&@RKuY48L-nw6ZABot3 z()YnyuBFOMph0nn@t5l95@ed71rb8<1@>~8CLeQ1ge(8ejqZT|5}Ov&4sYTQf7$h5 zHI_sGEzaJc-H(Sq16$67j%w+1H5~+VA3|3-OBMOF_b{cRWl@a{BEZId8%UEKxYwY zXUEOR6m35Obdqul<;v7ae>q{v!dqvXF@Jg1jmYbF!emXu&*HpIz2bXi<>cgvbEiw^pmFj>!iJD>zf1DUv1?Li z-1dlB=8CpUa$#S-yYY9sp4*fMEN8JoTxWas*JG-MdX}ZOovP}V+O6C-#7viRo2X=* z_HnR6%3Og0eQ47j)KQZzdNik|*{47APh|t;=C6>D2bl+lna)=vHP|$?#M%@Ps`& zToTEprX2UH`@X2Zb%@Vb(BwO%#AZtx#G4Wm!aP0AItC%L_7m9%rZ#9 zYzz4cr;R&n%{VhCikoIvN_1bz-^x8T(I(_1Xe}?(fFhLJ(!9TwAKlwPzK<2=9wnWM zV4;qA#BJVYpym_J-$W_TUpye59H-iPC&f6ObYE=M{a`6(DorKFBzuw|!nlCC={Dc@ z0_&~A-Fj({FvGC5fCpGuB4eJX_c`3lt%OdFcdAGGiq?E&mWH+k8qvKE=qTr9mzs=@ zH?97>VoLzuyWFu+k;poB0j(U8@E`N*XSZY0_>zPHk^qtx}WqpQwW8b!~EJ4f*d6FKnsyq zxeq%yXsI-bJV*Bq6i`*vQ3UmsE&rE6+RsJcSg0BQ_Y+be3ll@Z|vc@ulk7R3(ao% z$9Wvc4yg+{%BSFdtvGjo?Vra8>-+cFxidjP`YBxKFqpiLj z#w)0E)D{Wn2s$*1^ZFNc9yc>)vhz_lT|efbmL}tA$8{k!6k7%M?WH8?I-%y~hjPi} z=_als@;0NxN7X!t71+8iAVhdX=<-0GPJr&Q|X+t=YRBd^1QAKQ(|7g&{{p4WO7!(~=Mg97Lj8sd! zOPvM|Gm7r(5d-j&zEs7B%;wMCnd@(6AALsZYcTWma`A9pj=XV#&8_jI4YXPqmvS6; zt{iDwp9yC_wpqJO|;s{O}4zfjpUOAN`OadcDTa(U7-r* z&qK8ADzx0TzDbrps^V+*98-P^LfaRMVK;H-SmY=UQW>e+$Z>r*ph^*!a^}`}bg&*C zQ}Nm$k#16aG*GPTFt1ydEtny*xN^xt<}UtWe5aKXmsOt9a>MBHc5&5CZp)>Q3=56y zz3^7QjT3tjlsLP(`yBJ#&iN!u@a#g$A z5&h966CQ}ym#%sqJQ4XZ1y>+(pVi^78 zE*IWsD?dl|GX@}0M)I7Wn{twZ=xBCfTKm%ZGa+#{2EFsp5f>^4m3Ut4d%i~ZnV58u zt@q6~vG?Ijm79r%I`r%LyDA?zyL}PIWIS*ho}^MK`Cih{|<2eS}-)qfQb_^H3N8+VX zuw~@j2=8@)=ETvy?9t4XIOeI<{dVny&MkP=<`v9F~$(sx7se=^P9`Ox%6Y zsB{^0VA|om_)-+y;jf=(QH~zY@L|d>D0=MQ3-7aDB)(q(Z5yTqk$I)i7P@zC1g#|k z!y-GSos5RK$-DNoU{F<=tslcp!+&BH+C*V1uVZMcV+zq%QS*7$v<>b|XRDRlg2qz$ z`>z|WYL~u|)8!+urn03Z{==a_{?HLSQ9n`cW%va#zKYYBo;-MDEfsL(Ag20|Q4ln0 z`Fs`QIBM?fY6ll1+j)oB1F0TVKPuD?F2^K1STIVjZfH}bhd?=@v)MR9vBHKoek7)u1APQ>9Y`h#qbqXp@_N~njKO{b07mYBOP zsAzHzNGT!J7LBveYWuWZEW#B^>P0qM`H$93J2wT;uNiEQF$>ShP#QXI=O=5GIK`oR zcV3@O2ysRE+EVUupz^xH_gtmrVAm#XiWP`XJZcM+D~?j($;LvHq|LK+uK1LN8&;0- zp;jITL;j@)7zdXG6wf4H-y*5rl??Cu{G=GLgU)@S`FCl=Q^u-_6DpX%ejO*3ldJf{ z;wkfpU7>MoMV3Y1mFNM~br`5R&x6P=op~vfRHo%$9>qG+d2-gYO9Xtyk{A--X@H@F za`yM={rqiP@Ny%&=0@~XYzbq%FKv)S6%G3z01@lFlGw>0l6&d-ueg5)&Fl4%%6u)w zg%(ZuQv`%L^$%(GxLG6#^MlL|)dF+O(Q1v8oQ(W?m__%Rl^sZgLTnFbtB)6|nVjZ{ zrORk+^Bu1&dXAyuk_PmgBV18g`t&rrs7?KABPK~GvWGsoh-^#a_CY?}kwSeWznjg9455Y>dtddmv%v8@YoBgfCz2WCT zc8NtNe=i!cNiq|&rbrVvo^3aLQrk*5WaTeM@17scN%*_+M1 ziCOMn_9ax1?hPQ#mMWA;S95VcBdoIDu432U(AK(Sdcodxdr(Ko_%6KCc&n=G8V_Gc zhHolE*k(5>rs^fAJ?z3RZ6q^$$Zcy;>=v3rBsZdR>CJbU92j z@RAlm9P{6o;O{?hxuYGKP4dOi{VEG|!_j39tm^By-&*dVX4RpMS5eQ;q~-+F0b!sG z+*C$&xT%K>xPcsHCd3AP>vCNe87hIQxdv&Gc0he12z4 zWrE9csmwr(no(Sq%v3A2ef}t;Xh+s)9v0TJisO}q>CgoR@=M)Je}9!b3}M5oL1_a* z5RtJ)G~otD2ze~qCX>q)0sk?|kO-nz#}vDDz6cxJFPEQXu#B+_SnX?xz!_n73N8Q~ z-89!{H4@nC0vvZf47c*J_SiI0_T|o}pw)UDPEyA=jWuw(+Z1&OEL`3302buQ;uBu0 z!&QG#`E~N9F^KruOrtpqkqOObq(`e$)=gE7g5!;mp>3vl6Oo5W06@XvKjSJ zeG5-6J@{D`%20wzPDY!4^gI0BCQhejIe}h}R*jJ>cV2#14#Dk)^(DLmCvZ~xyT&Pp zW(5;)g;r}U%P+fn05*~CcIt^A`I)-$D>^7Jj|kECPuof%70l zaJfGd>*-4J;}%w#xKD3}3SD8i?RIbQ%8L&iOS7AYvyv8AEBG{b6uhR??{~1bT=@4o z@vngI)qVDd4%^bJ7u>%}$Qo%x__of2Ca1{jqwv$Tni!C%@+6!+)b>z~LG!KW*hRru z>huj%A-rZ zxKa)3c+3ip$`pl8UU~01CdX0wnx6CM%*&z{qDjJy$;|R7V~R;ajXeV7As#kbZ6=vg zN7JFb6T@YsAmiVsf(z4Y>a7h$`+O-N{^NC?JIi^k9Q4iG{vw;N>Y0p~jsUm~KT*fG zj;W^oK`h|_N99QdIp5|H#~w|Abg{(0C*pMo?f*#I z_=q!Y-*x^QK8^5mL+JD>v>ZpK3mK+7Oj-*vW*BO+nZJOfNQ~W6vo(m%c3Uz#{YIl; zU2tSAB&5Pl@YduH>%hF3g;i9(O3fgtdUCkd^u%1p&vUE}SCG9~<*<8{rdnBzh-hR< z{n!i7l?MLx8B`s3uCnFWsEVWQRifTKbVMU31ck=r3ZnlI^zW-fE`NiU+(!6|FgQaj zJ?LRb-N`+7*uY;Sj?S*JXK{O^i!3xe`L%AsWG9`XAvRV>&5y&2)v?&y;3I3=WiJHQ z$j0)xxxgPX&o(JZQGR=oY-v@G;L4n&3{`ZUAQV)lbP!u@g0sNT{!LjUlfGTsY7x>@ z^Y)7sOSFRAWbvl#MqV4-!t(kJ=uv#2*WiB3KY!z(4AxJCF?Qsm!Z<>hi@9Qt>-a*9wlq(BZ}5o+vgb*6;)bPOp>*FJ9{`ei zv_kEqS<(G&fvhqS1qqtf5j(zP*=DyKbJ5R8!R}tV#2xA+pXZK<-OjI<|0IbP2v@af ze5Y0C_)4JX4`Y#yxB-~Ah?5+fOlj42S&DL`ux;a}EN7X&6QHKxav47*wps~=fLtuD zOd3Po-ser~uW>K}bkVtDsQyDvHN4|FVn?Mb!Sxf-lMT_Q@m1qER?@w}ViUX5mEzH> z&U11)FB8EUZ2*UF_=|lHTz63!vz5x7Vq`+R|twkukWk|m;8v0G5 z&pJDPC1&Mxf8W->|8U0z@=~E_{n_6M9u;avznszjY9a;Q4a*{s8}K$cG^n;i_t9mn zJF{&5Lx63UeEKAr2XR~{fabP5p36`NO5OFlc<EE&3PeI}JVRZECk3|mfNe-G zlpUYsZ}cc4=)nA(1;9_MskpGnRCpO|^<@T9ai@O~nG}xkZ6e z;JZniz{^F_A%;O|OGQ&nICuhjO2tPCLkCNHWV9%!vI4{+@cYw_H_thE|;mEJALC|@oE3P8>tVu4Pe^6in zlx5WMk;Gm;mC;zsZB~7W%!UCWQBWLYsVIeaqOhSkG~E@p*B~G9s4;8T z2eoIe7g0_2p}Sn>wp{{;o&W4dfogP(vMp~kQr|M^gX0JCN({XCS-{CY5Tzqj8r#wa_$!A`R;aW|6f3T%Y_7fsfYJ{|{?# z9TsKR^$iOS3KpO!7=%hl2}nwg0jMBg(5aNtDBXjXqLNBCf(R%f-KEkX0s_)VcQfR` zw@xYV=i+<5`*`2)4>)FqVV`@iz1G?*e|w2Hs$m>CP*d!EQXegKOgbDQ6&T&B1@Mn2 zw@4nBl%O!oXwji;E5&jWpt`_pY-tF?rg<1fQRUBuPFA0z$?NJbJ#AdAw)lnIVvN}V z-QB96G@cW@YD(S5S1PseOVg9KhVWM{8^hesP9`OpCK&iKS2nFRk1D}2mCGH}x z`OKkyEJMncYCt61%vN+6MK}jaReZUtI%p@vy5lPiQOob&dUub(Yt=Emjqmki2a(do z^h|HfGqNadY_1*bjdX_k!&h`E6x0Fg;Qq4IcR&opTX3FpcH}d@^Z5wQ(!C|una2~S zR~2h*n%wX*dnwji_<2N+ahw4&BEd6PxRjP~sk=3j=*$aBk~6(~Wzw1;Ij%?^T_+XB5)fuehcBqdObqM!R9DE2EkNmpd0Mb+^pD>cdLuQFjC zTd+<$+RIkD*4Gl-L`@dKm9Bf!lnVirFh%#1mdc<9#g=T%E5&|HLNK?$Ln>R^e&n8N z!)uSyfZrLuVuE6W<8d)zt>(dtG~c7`bnmXd?UR*PZ8XnyTpM(hs(+QXHr}bfkG z_AUEpvx@@TckgIFC8ib!FphrdqO!#)jo8#jt;c2|rfz&9^pWV5Rnn<5oa18R5~B*4 z8SZ6-U-IDubxkSg&d;m601S}4dZ-lw9Cp~?u2r2Y!ZXqjU(Czx(O-4Cx+Z^u95ixb zs!;8GZbX+;cllGZ>WtvBS;B#fIf>tv>o8r*zLk7sz57qKW=@*3dQywLoXxSv#R^Po zlI8nNm9M8hNJwuQ8MXPTUzm!E7h0bU_b<3|{uzpph2%!!m4lu0|NJ}rw+G{ZnoF9G z(xTi{Uub(oRU4Ek{VY{ z&6U!EMyWMC&wC46Ir*ExK{Co=bS2^kbnJZEaXDe0c9XATP!z2%oiaLW>b7n`R{+|} zqK~)qgvDt~bGYup+^x?2rtxb(Fe1yc%C!Aec`A%03G4LZwG=W+k4=D=spycW?N&3M z0pZ~h8oc5+Mh;J2Q?Lm%xHUl${^PRCr{@zdkQB;hAVGvV6l(pNJ%kuJ{L;-;UzNpn zaol;O&5p77x>P&bFmvbVma4`m5z-!BFAmC0RklsMqLFZ4eW_BO-r94YCF(&wHa*F3 zU!DWlu#fi*g+Bd$S#i}_xjkU;^bo*)+E_sJCc~m-nj%y(K_e4u*xOumE{n|pcTwkx z(C~ZjAkI9oZaw|{06ISEtY6G8S)3=%k))*CkD9g_X4dq`=bsC>T+cuK?N};w{aF@E zhLM_`EcOP7P>YmtFb=xzgkgEb#x0@BhJ5X{s@cRDFm`G*&7dnu2O{B_DSToaQ4^ok zaU&i_0!>~@`5RTy2OGTg5x`G|{-a42XZiCH0y>@UMa5V;XP&6p585G)ZYQ5<^0X)n zI_*7Der|}z`4L~hIxP+d>j-S7fA+KR0OvC4Vxb0bSlpyumluPQOZyviFx}I-9 zloPDEx*9G4Llm#L?gLvYu-#6HWk*Vho+2f)g}OVfx(dG}iR85-0%Po&F}fjbOX%`n zJm2##+%v<9%4mfILr9Q3Xi)DHXM&I;XU(k@m^u@O_X|vDDB7 z?==XGeFvCpj~UUTrz+1L($5bCtif>?WUu~@lRq;>BBhLLM?PfwP;|(|s`rz18Trm2er{<2pfKn(<8`fI^^dx)M6$mM`uCjp)bWJf9WKg`FneCeli(&duQ)>t{Z66lvXF?%~Vn@sY8S* zNRtW4M-A|`5`s71n+2w{E-8gt+93fNzIwi)h-dsWr!+5V9#U{qcSU2FlkzSJV1H?* z@;M~*k{lEMMv+P((PWb}PqE^btj*yt0iKTjT_50|Bd17K!C&BjkVzx|44FCom~wAt z4@W6S+2z3S(95OR5{f#tDkPFi1#Wn+_`Y+KsW?~k#Of0;ap;XW96q-uRnU8VqSng_BH=8PfmBoF@|+>^%(7DtU}-mcekTkSyM?Dbo~^y z_+EQN&;?7`+(eyplr?Q521(~AFwZ$zNzG2+6+L@Dn-(L)>ROZmR`}%>qYuHckta25 zqfg^$C7e_^PmyBZ5m?D{q>zw@HHb7_C_Fz*yzCp|jE1=kJ)>ULxH}Pv6Wycd@G7F) z)2{FQb4;}8%Ftl`P*IiTVqZheev~-Fwbi>S!rdkx=FWLxT|`zNI4nF*ii-M}Kdbk_ zeo(}-s7bBxNORbuK1O`s*_EM%c}Y&H%zA$CJ_PVDz?Id`&onFcFNw?86jp)e@GoKc zx%7P`u>Rt*paXkEm%4eiC7-+Ai*Az(BP2KMevPzL2WR*w z6V64`$`E5#(_^Tj?;hBNk$VwFrqYeu^4u!Vd8Mt>bBIMTJuc-7a-OEOFC@pjL(Vw2 z63Vj0R0!KWEVUDN(qFktMj}Y=`HP4C*{cepoSKZbFz9ASZ2NjQr%q_deJYlkCoY*t z>Md!eEJjMwZiw$|*V(FGb{$PRby@-yKe$(~t=au1O{@O~o1J-FqIE5wKKXI2`q~my z*oE7#v~?NPKKVUs>LJYnVckL7AI-nL)jx34EJEZ~`9xX1{{uIdw7C-(rkEviMTNHv zJrp4q!CNuM$$@bb;ZQK@@`Vqfiee{y;g05L)-tcYXAXA-2tl7g4O%Td^QY>sU zE~4{w6+FxOc0qi`w&qYqQ2oOXEh-(H4{J7kC(JTrCH<#8Os=r-61QGqxp?P0q416{ zaqAxPy}C;0&`$xGK)N!lOBV!Jzi`^sn8Ve?jBg-wbkH0{fy6!(&5mMI`}R7Y|IF(* zH1tZHakMe;XQgzt-l^29#3|p_qSlak*!y!jv`qF=uUlcKz7i9^z5kTHqZx8F_Km%A zfnhT~Fq5Z=*i8ORlAr zT2riJv9S!W=*=Ry%36M7i}n(0nXb0Zc8pu2!CcbqHHvb)tq5lb65+i5m0d5jEr7@hNq1BqC=H+uFSE*mFrg5*RHMrlFBKn) z3$4XJ^6SQ?xLu;*qbIcn4hZW2R9yRDGiB4Cy&}rPrIP6!r=Pev>RXOr1xw3IepRbg zAtqYB$m(z6=c&iZ`^{Y_Ey|4mfr&Pl9ae1AB!WYWjV%z28h9ujuXuug?{4A{`8pTgg&BipO6(=Sb&AZEpYQ3pBWfx|p1Sv^rAz}#e>HzmLmFYTaRBTVrC$;&H2G0)jJX&+UYi4wv<}r%1V8T49>LLiV zR#&a{_oqj@AlIRMy6m=9_0=56MH_qXcTtWTTbC zb=bCBlVDFS`#K#$% zWS#YJnp|{M)Qh_KjisI!>T4u(%g+&B!uKME@?#c$-kyL`VXBp1WjwPKoRs2DW3UMS z@vL4C#p)l+;9GJaAPTzemMaIAz}|LTIhq<)%92g$M8$be+{EfaYzGe?V|aY#j~#**B2aXBPF#JTMMPZ-%Y;qfB+wL>%5mr>Md{PlUt_8mgWZa zCvzAgIE{Q#Pi}6eXej*9^=r&kS?-qx&(r(AoL1u~Wp!rMT)pkK?mB&!V;@6lUWr07 zSWP7@;=(g;#w-h0I^tb9N5C|BPy~)Z$C+ctHE(NHE4p!aKp-G>m6kR&@GM{H{^z&d z7+pz|Usfe+MYzX(Q;unZld<&9!NrqI-d{~YN#?mX#RoxQYI6Nn<$^@3f#@JDo4M-28lE59mH_yyItiI?d)>F?^fbGQ?+KXe=ZlfQNroz>L{t}*wv zNR0IC6)oI8R4wD3)BZ{{)Ffv(tCa{zE@Yw|_F*3nku<#H{;1=RJ4)e-t}mdLcztxY z&7g+On7{0I>+0ra42gq{=xd8|Z71C@Z+c1C9a6&SeayE{E_%j@Yx@6K?!$K$f2mxj zdXO-22;)5-cjBe`3j???Z8SbrZ?aCUbE%f0MeYp`9{w{T+UEFTo^*J*y@t&fm^gAc z+2>{VZ0cu7*4Q`jr!p` zkJ@PYeoDkg60tKvCn<#>oujGhnj4|QpT_hn(pwvUox!Wn2-n3Bwz;PNmxw&Qrk=f5QkB@&?I=ZY#U zq6vgoT55HW^jqqn(4=*Xl751(efM7KpVHtDft<-$ZXRPdLZOX*m*J^IT?o`y2AwTExmK@S;FhTi5-W6 zQq|XH{9BHNFMiX?rSnrbm%B6&oNIJ1hS=%w)zabvov5E^DyhDf(Sljr;g z?Yei|nWer7M3M?Lj<_Hb3tH)a6ENZ~5Rl0{OUrMI;dLQx&db_+)yI3|lc9?mt9>DD z@)p|>Z}x|Hlu8|KvrpHqqo+cM^fUM36{iclKX9KEg8;6zKn5?sZt%ESs~K(;>K_ts z+;s7-!4D?o6(0-RgE@PkFG>4ad%Ef_tRI^XoZm|QkYKAegBG!X_@XY3J>Qs2Y>Lyg z_f6%Bo!vZoVCcuG-;^#+-K0HoX3hA{%r@OxxhL@9)RnTUR?Cs$pYu^!35#Z z9=nVL+Z0`Ai0{6{_dd$=K zXr#lJGQQ+&>>FALkw?=i>AJ0*<|akt(U$Z-@bwTJ;VW@v1yjCD7*J8uhRw0g2whl5eqKG7!#mITOQ-rI{L5LVv) z_g-rF!CvYR>2hvrHMA%J2t#2nQ@r@bmw(EG?s}auqP4Y3c2SUp5nGW+tv@T#kb}1$ zV(DUI&B<=GE|{}KT-s%mDBi&)k@mE5Zz;fkkWG?%#$s@N^D(#JF-J3g0ckhCLId=W z{iICtd_&D_liuY2()f7z$4Pz^%3+?- zZV554DD8ORS>nRa0vq236%R*VaWr0kxt!+dn&;OAxZ-j^?^r3>s6llECCdu4Bvvr%VmBYi`?^`J+{gW~o- zEkCpQpcC*Q@wUYj%k2kc9|UDum4LbahyBpzK)0HFj5aZf{sIt=A%OViR-S#EKM6@< zBS9Z9QE^*u6}VKZ0awfFYPoC~0#QfV9iCthGb?Wy283?nU>U?t>>Km{!@T$J!&|FU z5AL32KZoeINUpK1^XM-U!nV#OHO`kak#8Iuicg+tiB3+RQu32c*~smYefM%Ag2v>bH1S)q7@*9l#;n{P;b@d zRo?~;_t@Yl6X(`Uls1ft%nhX&8|ri>Hc!_6&Z|8ykWDEC&AHD4hx*+`HTV|GB z7y&j_JvjHB(AGjf(s~)MTX#HS*Z9*{fRv5DH;=ewc-nfq79{{5^S)SZa*95BLr_u6 zq$DJQ1gvP$_*8gO($g!x?*Cp;5h17p_dSglx5S<9M0w_Vp48q5t0^d0-l$u?)$a9% zdwY9^$!?q)#-WH5T{eb`&2)0=9yTCjGB*T6&ff4=G|i^4{k^c#^AV1Qg5U3MsaPLT zny$53rS9OZs@I4keWPf_R@RvvlQDwPi%VgYvh%&!#(-!Me0=BhqeSwg(O`CKbVTHk? z^7{_s%OXdBY-Lv7Zi8cB@S|r?ivRoI3drF3UxR%%59=XuG}^>8sv;M~geYa^x4Hm4 zzjK0ZPD^ZMh3TW;bo-U;K3iBz@t54-j+o7A>Py_Ph)kPdaD+Iwl-y# zqa}g`_^9#;ZQm|O^%nKP%shhWqYnC?!r*~@%S(9wCh{Q0-kDqfUVQ`#2ES!OqP1xi z?X2&wMeM;mLgH|vY?%iC-jzR}ye5Fbn*{Q14sTEl^3PDR&l{8{5pfQ& zN6%UN-QHz(+K^n3^E-c*`rowp>k~6V+Vvk}3^&R*?IJYv0--F^{PV6v+(HJwb<$sc zm%-@}W7qi^&B4Eh+R+qSdrx){29LM2@~+=>0B}f4iV>H!KUx$~%%U?a!MhAlc@A7& z7V)cpB^CZXHpvi4R*cXP)J9DVGe~Vu|29D+>yJ*JM_i}ss$iS+O9z$ZC`DqU1_Pa$sJ%$0XDd3z54CpBkPBW5%w?QGs{C-h~4nL(4w zPZ@WN`<<0lGQxsF%0v_Y#qvAfAtZr0`)BS)0T^vR?%RRwvn;MC+Fvb*ddw{D#4$X4 z-=pQ>Uwtd{s&~<$0iQvK5>fBjFeG6XLi z2KgM`^LAIA&_u|Bh*B>|{5{9boxQ~j3rcelEB#*=v}k6FM&Rx{rQ^Le!)%zK181I; zpIs`J3a?i=hlaSp($lQFf&PlS@Yt~v5JUUDm&SURzwOK^=V0DDAsVYH*39_FR^AV{ z8O;F7sNgY4!<}wZ;1AG|0o~}TBUyHFMK2@(-Rh}MZTb^CWB(J}Fvx_iVC1jxYr7>s!J|iHvmo zGX*S-tg7t)YE?8S;a^lFc@X`cKgPMOzI5u0CgMPkD3`Y?LR>Cbr;gm zUjQr0dGYO**}jXUg43geF>KrG+`9yr_bRC*3?-Ykfen!gQ!otL0U z`LJ%#4alM0rE$C{pF(nJw-CrxI1K4gY`byg&ZC#ff5i#W@P(C0Voq$ZXv7*m(r@D6 zbT7}rXuXC||0s>jIn3&kN@RS+fq%;*rXCa!Gw$r$EB`BpU+oqczfuh0XDJIvqBM&f zxJC5G^eZAe*bbSD7AQXsr0zDud>{q&aJ)Rc)|d6A+b$kffD@t~A|!TmBDN=oDJJ02 zCnoe5ghC{9BxfmU8sHPT;h8QU_-45Z7r)Fr3+|aOea3s<;EEIaCh&&Y%@n%RJA~QZ z3Z}E5CXTw?q~FC<-Qg2L4DrA-XQT*cS?ns~#%={X#4LK$I!^MQa*yJA1>RvAdMz)} z?15I;-~6!g$f5vn=-f}LJlSOi+fyN|zTN%S&g91f7fPOz-*;bcM8!t{4E>$Uz<%zM z(e+T}V_%w3gg$5*MZKE9$k|-3^J!%gjKHvaV%3(r_ z-OuJ-U*0|UXOkgT21P`UC%T50CYQvbrdO5>_avOfM}1`V5-I$odMbOjo)tB)Fnj0y zPHjJ8w-?t)ti+<~tZ1lN(je)k?Fj9&F&7MO-T6a%s8Q!t0TsUKpe4SkTSitdqIjehy(pCWSbr&W<_=mz(*r>m7&uF73A;Qa;d9p2=RLc0>m z{$JM`(U{a^6Tf>_{co;w7wesdpVr8TZYwtYXT$ws!wO6`c{*#Bd8J_4&cg{lInNYYzfI>9fy#U#o?;J>sGgc!7OJOGrXdh+Ye!c0BTas|qrEIDaj8~pz!S6M&d+_^EBm;)T-OlQ?t*osu6*sg@wcM1CX6Dt z-HE03^@x@vklnFxF6Yke7U^3*F~P8$(bMi?b}q`Gj55({r5`$@WjCFm|FGM?9tW#M zMcOu44I>M!;VuO0ay{!Wmqx>y_thOvJ#yX4MCD*lkj7b=TNt%s5#eKJJ|M6R8(sHz z_TOrG`6iD4;Gx;D>Vo#(Pg{SOkKg-L?;vX{^d5teAq+jp6Guq~s4s7$I>e0>h0Yd6 z_2w$kOoapq^3cmLVpiRiqc5>R3+umjik=0|>@WM#Grr^s(5!5i2TLAYe-XW0_+YJd zz+7lQ#&;=eEg$~!9`=d*%hibc`1tuKo1K6~k)(OVeRuM}zJ+R|%Ybc>+ zczGJ`8ujlINnk$&Gx#c#=J}Y6uRxw=3Y>tTP_W5bh#eQdjzL?uJr;fmrGn={jp2)N zT*&RxM!NPb;Jytlq=b8Ig=-xyip-N?dI}!H6}1*td7U+iZ4PKq-9Iz_>`BJMzK^B& z6}Wr$6K8xkYmfsH(8cTOdhKL)xpvHj1_m!PLMioW-+;e0)W((m0Q_FD*gfG#!EkEB4QvTcT@ih;Nj`Z)oV03{A^Yh?HPRXJv6s5yePedGRiRU;C? z55d!DpxiUCD6qE8r7*=;JaV+c?)V9|9|km^8z0o(jB!%Dg-L3BNOpf;y~B5U%rMEO z44(sH{~;-VzM#PcN=2+!FKPaGR+a|MEeq&v)&f+q6|WaLzYgQ!%br+-(y+JVh3jie zlg&+|t|PYA_ftL+_U&~*ITNAoZ3P5>LMkGHY5deuygPc-A#O>bf8~nx=2`mUyv&qi zKr5FW*{H78PoXCjvM3m7#0DBon> zY)Y0`UlJ&UUXhqprH_lpPL%IoCB#35`b(OZu*LrbGrtWN#`G1$$??88uo+gWz7-K6 zZN98@SH(TrA=|dxih&trNcIt{D2~bO+aG~6K$j!lr{ZCqWU%=f z&YFy;H|rn<;#w|`S{ZlARgH7V#$C~HF52OLnl9mh8|OtM8(6&BId7MBMBd$WA@fl) z>z;uFFW#o?7>%(}==!q?W%x|sa{kX5VMw7Z^7Pq6)n+k`P*ArrD|>v9Mv|3rW5+iA zyw|lb@gHQ1&|2eN!X1S>b!j~)MaMAl?SZ?D7`q}*8ulw1TYAfh-^-Z#{zudEspcd% zCj8rPZF#j%?Bo9U@7o3zbg{p`_F1g|F4@24gNNS>(FmR++K=z6cKcw98IVq03&34F z{RSwGDImC*KUdF^NIBm87H0eWqxzZt!k}I06RX24p2!UJVV<{-(%y{MMr7b;JN$ga ztgyWwa00+Jac32xo-poa)te#}4lXHNA6cgQ;DIJ9-QL%ZTz;SN%z(^o52lVNZ&Y=% z(s8gfT^q-wPScUH$7v{NxFi&)% zee;!W;_uE9XCEQIr5)>s7VZ`&37}!$I$F?_<(b4E z8*|>Yog$=NxM`lXaBttnf;Eir$JhO#JmgtZ*twnKuAGRL(mA^}Zx=<5j>rV#qElEn z)Cg14wm*~wD*aln5eso;-eJk0M{9f}m;eoF08P)ejtfTo9sWwu)S0_ZsI)`)P3O;p zv3DHzvh(~Whh(31Jt9Q)VTkbmQ}rn&oX$?bpr3eh4F+En*c_9I z?Z;Z-NxWk2N8^k;(NRnY!YnJ*61y@BxTK@wy$!=B_zLZRR3Pm`mBf*E_TZ!F*-W7G zcCgU4Hf%y7q25!OhI;Bep(IJbj(yeFw!haX{D$!e!CTw+6DEHk1<$qhY7=$ zGtR+C8;i%BIsm)F%@TfYH`6Z~cIVDWt7RjB!%yL%J}CSC{l2W|M))4gDMA&~lH)*+ zNm<-O#`VUdyJ_Al=}Np$l=ou#sN(iz+HYl0tM6>=ivEw*d#J5>;Nf2e)xy3IxRsFo z52l@ikV8{jSxf_~iRMa#H(;cjdR$X50QV8Yf^@TcuTS7=%+&RK9olzQDHN6~*KO`W z>)82h<1IE!TQ?R%PyNh1jJGzEJ^!gqDbem3RZR77Q0~oU)>Wg{h=`wV+@HTDC$d_?kwrQ zUhE-L7FWppviIZfOS`?`U-e!hoOqEGMNcTXWy{JSR@==?`S&8`_{-`aR;d)HH{5PD z^!o76^!>-T%`=Tkgv5-@xjnnkIN%d-efELYg75ehOK+&XdXPM@4zmVYIkb?!Qaxk0 z)6=I=^t=oAu^;P~+JYt8{)iF;S^v)$`_oLt9ipi0c>m?j9?N3$rTrr^7gC+p8shYc znb@}^sK^IV!1v@VO15*t+lK@VyF8fEPmibBhZ4MOT+bpyC_$U`tjq#(xFak{&Cr-UsK%vFQLEZjyGYNKC1tKB3Y;K4oLyo{8%aM&UwCX#I+koR(+%W=+JIq_ zYWo4Y|6Jz=q4Pm?%wwmA%|Lp}?z?B)QNTxuF=?RN%p9{NbLMt65|P&4dkhil+V3qR zEH>g~AK|UpNb9o$+ZHQQ(dyFe2>llJvt)(zg(<# zzO^sg9~!ft1y#YVKhC(B4@3-||L*L%@!gZi-4-z_xXIWf408%q=v9|@lOD;O{ByWC zke<6=SJXr|O7otQ{&3_sAHPDd?STedf)m1|vNADihsU<{$N&=@+=S5Zw%+0E(B+Md^GZ8Bun^r8zZCTsCx1|;=^6?*Ivl-QSTF#zMR8udkSb`4 z2ZsUyCMxLQkRxNU{l|^U z1k5EO&`{Q+($m{y1k-YuB*fDjWcEJ{xICOxAEu2GsIH8 zU%lKw>lH$Mjk@lk3uuZ2eX1QR#pRFLh^ELFkTdx+s0>TQdfGsONXcdq z3?WH?4Z=<%+p=>V4gqJinb`;WB&6*o zy%&^ML>=_lKzgUzZYgh^eM$#`*!C;ZJ9t+gR1ji6IasnATg3ufT`7qdxeaV}XS9y{ zfVfkU0>Pn2!5@;|&iHcgs+aYP%kR_>%oV!Ld)$BcX9pvo>P1?=bNQa&7HOd<9y#aL z_HJ7?J1;QB5UV&mpgj)Nf8RZ4h~K=q1~Kt-|J_ofnRrvdl|e=;r3GSR$3?bFe@OzM zx(#HPl`MScX&V9u3OEAs^pB^maS?%f3@FXM@nR1EdVomF&s45Nz3Cb@Y=X?n6A)Mns21yHzJ`xx>7No^=4A3xY zqy)y(#`cRWUaZB}n2vE`s(`@&K2~fP3@QSrRzWG|~y4G+YV@NA-o3V=aAcx|fHpN}aRQ6!R zuB`_t$?#xqOZdF&Tcud@@*8gJ1y4LU)U5ty3ry38wP3O5m2vT&@PWaDYhP96)s0du5Ze0xk2YJLuHSWBmnU7%Z*!XG*-0n*V=}I zJLf*Ur@CI)gS7L#8!t?cI&GA7*3~|E#=tQ^8{_PhLM?geJOvpxMUs&>-a<5uj@50hukbB}FX)-3k`ql&8 z4aqK64pxev4YRXIbA>?9%kwD#s#$I4XsojEDv*|03&`>5I0Dj0?i*Xj6Ziz?g(!bP zMF2^9T+oF=#avOvcfLn_#qsH^Ro?)$mUzL_!m-bL)x+(_US{eF4h~$tSm-U{U^N?1 zVw&3<Rs63|l!yBKQOo@^@joH)(m7f;2t(-Cb;IncHwYHwqe=f1i(n0DSlWF*d+V!{mvB zkMRvj?k8l$xd@8Zv8q*#Fwql=w90@Pms%z?VcK%3ilu?$tC$0hJg=Len?Xl|G*Qz1duQ#buLv7$cybrvrXhd_%|Bh=i2-j{!wn zcUb~IIoi)={m1>)P1+q+@>9=bzCM$AN!1mF(w~sMAHg-=kg*auFmE*_z@q%~js_57 zt#EQsSjUP|9&NG;G58CaYY0vc|BQT&WSc>1jdRYiX8%Tc_54B4gGZEpxllXsDMJR! zn+xtI;T$XnyuhZ1)*8Etnh1Ki2f7|l8Di~`M`0L71VKlm*SJ&zkcsrb89OBDa0 z(XRpCW!I+ZT?(J^@JoR4UaRH_C}J$r56`^hw;5hvx9vow_=He5p1OE1ti52RV^Zo& z@2`t_Q(szK)#f6{5ZuQUK%~gfl}w zYF0ngRMnVn07?Bx{k9vuZk*qT%D>7Nwx0CLMd~r~YaM1BkOtBBZ8lLCaGxD&^wk<> zCyystiDm#8hz{xEO02lh$FFoDa;oNyV{mJoF&&_o;xF0oVn%~$8P3bR-jMDXM7kyM zEM%*zUWrrZbPE75EcZy0xqoF0xR`4UIUz75nLP8Uz70W*tMAw4;cA4-;H|#B>~X` z9?p2wy+;m7efJzWk-9M2{)@6+E+@JxvGETh3dF-QKxcp@HsPm*0UU6frvif2l z=|K<0RMtl?G&pH%AHLASE56r~_(|fOM4fO=7xnG0LhmkNPXL}rftQ2GLY+Kk;z?)Q z!S)z!k}T-QN@Wg%|d_-m_u*9s|#AZH`e8B0)h3q4h> zrmcLwOE^}dSK{)HO+m8g0(Ws{EV(;g+&)eJdNIcaPOl@gzK48w1kf^Jc^L`ZOKX-( zG3O6xw(R?M|E$PTaRBL0fwq%6aEZn$i?dVPXbC_Cu3qK<{K=XHNN_XSR^AJH8{o2z zw8k!U{)pi`kk;J0R9j|p)BE~O6#W_wn$`~kGC_#Vebzmh21^~?uSQuGJIP2?+;h^` z3m&6gPC9=wZLhSLI7oQ$CbI;O4m0~S_VL=@t$;$+#upUtJI%r; zhwrS5WokPG=@*03{2AL;H!xiY!gPlME)3$mW!|z%w@nPpU8EXk{&(O=wNM5iIA?48 z5VsAbG}kb(Rnk69eDBq28gb5R&86k$LIw0lxI4AMjMP%kix42Nxs{ef#rI6xT@=fQYAe@2 zcLUBK_aLn>^xrd>b0(?-@X39p<7^A$%E8=$;^Z;fI4- zwWF}JM1ZQFf<|PQu{j}O!CJ1a4zx3`UL}Ej#O(4X`0@vwOz}t`8ET+?@kx`tFHPUOUW$!-QQx-R$bMkV(6=b zbNCrW)o6F9fik1xl0cujy0@x*#jwzVFWc7-!K+pI0!ZA8t4>JA7K?vTb`MGgpVd;&O6}j&uk6N+$1wH*UFpUGej}!um_g zytB!C-Q2eH;pEYEYXBl<`Xtpz*tSYnYcw(6CgZ0jbwj+metgC)tXoWcc>b^~Tg`X= zrKlGB!u-5J2kN}vuW6|{DN|#N=H7>`=+|l%*7mlq_pNjV=9@K-r^d!4JQW$4cv5w- z!){Vt?XxO24gfrIhg}BeeAjxLRahCD`*lOpG;&wq5}*O=smRbw{Z`hcA-bS4{q(W~ zAH%gd_n`S<-7Z1H;$@s)lzsjK%5bdx2_etk1^0WxZ$xpg_$kXo64gyr)pQdYQw@0> zl~M)oh`44Yx##+KTHAGLpme#3Z+8)V}{`aNhQyD z?{tnScf&Oyl^1h{B3X1;?Y}<_^G--EJ=Jnog4I{lwgv z|LB#ZW(22A0E?U~UGs^Sbk-fvzt2BYZ_^8Ikxt44R3+e=#A^^d5-vFNa4ENWT4L87HDRlL47$@%RtT6i7JLrcwz-vu0cA1rL3g??f?F~M$z9tFFiW)c6SD`L zQ?3VsgOOkW4d9QOo&&m9PIDr^u&Yg@8gU{ZQxc3KV8(xZnuM&L*DcOi{kFm6hws}8 zaG)av^lRn5!0lepqsUjLqjZja-shfF1r`bb4SL;qzso6V`x?MaaW#HW3O#mH+U9QR z8EU|UPDLyZ&T*zCyNdu~)LFJf&BF^lvvht zr|vZqPm#4nKy~EE|NY|ha@#MZ=lJ7;C98ua@>eFCWD%7qdxUVUp_Z*0+qF1 zyi=CWgn!0y0hh#ZMR`f%Gt}jwQcC%WyXJ6+Pt$cMD3~#UuoE}n?>QMLWt)?^-V@y7 zu(B$lzG4(jiAiLjvVWxh_&SY-ey)|u%?9CBS%a zbNc$MbLL|~B^h3&<7&lHjs1G9Zo|opa}l}9r^YA6i)Qq(tqGGkB*jsG94h0~L!Cy_ zxws|vz0QSeOP<_&V_ZGNGZ((3bUD=}3<`0_ktaA+5T9A~>%++@jpKbC*FLh+VQFLZ znTU{?R%lJqs^74>(iPC#z%1wArX|x;q2Ex6F%6s-`wyYMtOP6s|@M3+HfnQ z!2BY(-7{2Z`jxa~;!W$W)louW_wjv-J>soR%51oaipfmed}`Qy{1}3+-Ap@jiX?>i z25x}2u!U<8xpHG1Sdd0 zpIJz4K8&FIIFGv`_fzoIznYB~V#~+Jxz04&OscQXt9#=Rp!)<*!S7ciZ~@hho#|(L z|8Bkb$l%qEmStOcvYlkuiN``E5>#YYvP}!4jxbUzzDdelYUa?KnqB_2Ao+=QCA1{K zH?E6T$LEoV14nFvq$@~|M=4yf%W&`cy#w%tOW2d!|dUEDTL)l|bDNye%XWc1<{^XQ zJTc)@7#((#>K`3zYm&8^IwKCcwA3Zjj7-YaA(UlLKje|yQ_T+^3>S=yq9Tia+E%-k zIjoWvZZs)0Or+1NOS2x+z69=`!{JOu#=38<`P$X&L78I<=4qsGv*OT6 zJWZZo>t&sxMO`x3b!rh``>v}^MiNXCaX(dgj}zUwNjLs3^7d6FS|1+Y$hX(i-nB=H z8oj@8wS6K|^!)|1*#>&0`zq_}gY5(QiTXO<1212OE$Whu*yQF1 zLR7+bRuRI#RxYG21DM*N+?}umxTCgl#EU(tI%UjyRj-{W~WpKZ%EVcdI8|CCyeH{&cH5vt-V84?XT*gE&PaZ1@b~V#H55K+48clY}bgHtd z@V<5_=hYs3LK>$(zt9eZ0qQcdQO$El@lYh_J^$kurVqJF{IZA7TYgML>d#+gbGdJB zyf;4^q{CLVQc2c1O~wa^A6(b61N7kj!muhA+&+wkV~-K%$9T2;)~-sHex@PrEIC!7a);&0d|iu4O|3$9N_3-q zmDx`yRmSAt`6Oz?=8j@H~Qfdo1Dx2Pj^4N$*RxNyQ_?T zcGkV*I#GA~)a53DkJAt893-hluI39F#=rH7L;XrDc<;(|FULo7$%>P}ajuEXFqGb< zS^kp#=i~8Y#6-HcE+>hsynJgT-d@Kr@_4=^hfOgu>!{-=Vz|#i#WGtiJf8XNw^3V_ z2(2b%BEL$OXwME#8A@w~d}nR#(pH9v{OIoNc+2GqhHvru^KER|LFEQNys0QpB@8w^ zZ}=H0&k!pu!r&(rGn*)8&xgIv!O*&O= zIpmf^(VmW0pMyC2P1C1*P3sKl+J=AWi1YdRJIzm?_T#I}SP*y4mRowl*7gAx$Do%~ z@yp98+3h$dNuFiZ0XmGH?a7%eshW{nU-FN#t8qJiRARRe$w}>!t$Px$ZJhfqccdvh zG-Dz^Q z4PRCL7e3au^Jq@w$~Gp<7g7(t(Rgk!D*j^rUXs+QI2|DoCjN}?BC~1EIOj&k?1d+( z&7qa!nn~hRxj6K*>gtQBl2urLQyLL6n%=8AZ`fp0{?TE;`PT+2CN8Py+{+Xw*Ccu< zBG~s~NLUoh>Z%?}f{Sm{O%R@)lk9F_{7gZ>Ps8cnH@wp$@(>6wl6Vs(Sw2o^#KCaOil?^=k(r2D7kMGeB z8gAoG!Fect|K!Uo|M4WJPAr7#MF5?3M$Tzfb+60J0ty__g5R8Cml*JpKal2 z2A8q@3bwJydo8Aio-?|&ja;Ap&TQVVx#0%c7^%<$O~!SRqGtOP1MB2<+I$Vq8);Yh zu_}~))Gu2Zjq+$xdxLrv zOY_?dn-f(NIj4{dD)}`NtGQOezz`Mjt`%O1e`|U!{BYIX32nI!wt~ek35(9n&ikBK z7ABJ#&(4=CczYGv>Bz?`yhE<&9&+ejTbZ;xoLE)eUAQ_UapiP7)eUwmT;ON~p3| z(^+r#VUwpn6~XycrRgcr#I1<>0uR(={KEKx4voUqQaWsc?QFWg^>?48hQWirLL@qk zbPulDE@8`hsm{DlzuA;++s%E;*$>-4=E-}}@f!C>b$Mm!FXhQPQ$8{u8mY2H(ku=) zX5GOJ=^s7Nk)xNWYhSOsk~5?5#RSXKLY<^O^YN|M2YbpuJVmukHeDgV7RCLo_}`9x zPfucgC#tVFtM(sHQdv_+d_QEbjV4Kqd7Tga$))>!(?MC{ex<& z(Y5LM6z3lw`el-gZqsqzEK`zqE^eA>!o}w9|E41TWuhtN2^&UqG#iB;H-DX;R@1qU zC{DRbdExE{<#NR)Z<+*d=H%)K)?zb#p={6N0joW@z&fyht%3HY^TJL1LM(q@az}B2!2_x)hhjC)YP~^*2qqCT4Tplf(%iA!F>{3n8vhSp z?;Y1v)_o5Pf`XtRsE9~WDN0p3QWcdhDxJ`j-jUt{QtU_(Y0{J`C3F&6C?X&b2uKfA zks1P05+ot;J8_=EeBWo@{~Y{`mviqvd#}CL+UL;wH_6XB>K=AXjdaFgHT}QG(~1R^ zunrSWdTn~~;Z_0-A?U{fSeG4i)8Kj!hclGrIqur$$^GEKNO;5Gr3>IRBD0mHU*ASa z$KWxjJMJ=3QjH7}i4ST^0)k^{JMK$flcIK%Q>qRP`FRa7Lk(_P9VDoVK;ZhIow7!S z{|q97Bg_k70ut{7C-d$O#ay$6Xe6VL4c5XCw%uoZfXmU@N8R6xM8LVdRc6DlZ_2l09;c1u{@@O8Tu; zS*^L+n{#tR>5Ev(9m(+MNPU=iNz+~+>~8tvRG3lwhsdWe{7(zJffIp2;0n%a@t^)~ zv+Zw6+O}3FArQmQjo@CU&tKQS{@V-i1XF1rgWcHp@uTf^_V>Ub`MFJY?5<<1O4;t& zC+yb~$zOmNqBzbgAiT_5|pY7KO|zs%I8{K1+yv0vfw8xw9U(TQbc$hFf#hTfCU z+ZbrZyJeJF#oeqY>-^SAs&CkBobaR^30j4>Z9>63s0r7~*B(1Xhg?2=a8rJ}_yPJ- zQ;Xr#se?cLHxdb3IX$y$N^q+WcB(}^s2rH1X7<``4{E&1@-pq*p}Rt*9!aG?*Dx^C z>Tl;^xKWT<7K_h<3vG2cP5>OT1#VJmgdevhWE!*a5{0Cik}8yr!bykf`OoxR2&>wK zN*q=$U}WRVc1d9$BAC2XN=#9oO%SPUdynm8Oq&n1;~6zwh;CHm?0%08K|V?pv}i~+ zL?8CsS~o*8e$se?79POWvh%-_-gDlt&cJrLq!=o%Y_s%As%F?hSw<7sui>zrsJwa4 z;mt-P^BfVO7PQow&bHZ3gh=Z#ms()S{BPF>P-_$qye}kgQ#=}QBcBU z{J1UI@=+vTt~UKrU5|tC+?Qk8@4wrokYx;$2c|;2CiB!Jf2~*=15kBi%uOK7Feuep zQMv=V?PgzFA|&B9j*abL(O=(Wk83WgT|LfKDWnC_nbmjYPQhasg}Pm4f~3X#q{`&? zYV2-!6P$vYh+8Z3wNsDPI1AX%PtEitD>qmT@kzkOv1MEx=cb42QheRHxPSJopE0NB zk4>D_!&X{PE^H&(W{^qDIjBIVolbIoX2^2Uhje+r!gEqi4%oV<=WY3orPPjM6Scx-fKa3>!K%DNQV87(E?s475S8e_Am`RAY`c$5A(ZL7 zNT>|O@&1xpuLVr%?9M1-Nv6kV`i$-_4!aM;verF6g>&BXhLvfTqGd1IA>G`$z>PDe zO?(qL-+16#q>p5r8P_vh90ftdat&#emAiQ&RlTVQvL+gC* z9V#>!7*5*koj4|7J(A1CAzlSzbX9>L{3E`uKi@wnH_$^Av(X= zT$Jre^6bc(S5u1>tl_hH@4L1+fVDW9cp5x$Aw%pd1Uu$ zz~qh?C)=ei_zy!_s!fTR+J)IS!OV2zwN&=somDDt$1+~md-v@A1${gWw{sWeu!RH3!4|Tv>6<^ zC31tEv>}lZ@YTrtTL}BY?N{e>U~5udeqeKW&Ho5;Lk|0e+8mj;NXjT$MdGeY1)vm{ zmAx#z%|}F-gU5C_&69k_d*>Uq?JoMIA{9_L>t0O}Qn|bG7WdE0M<|R)e@hU@tRcQWY^bsBdFPkU|G8Cm<;NV+?nq)TRua_yPB$H zTroMg4jbt~9t6l>7RS%a-h0C?aR&)bdn~E+>=Gy7cw3MZ1mq{Bm#5u7oHVA)_hs3) z8?RD^y12Z+uf(U7I5?3JxO`>Apmjn?ymB4f8J)$eFI1`6jcN-)&mutxn1*I`ls4`D zzz78Ni`)~rF#17;UU0indqA^dN-A>=?r7G{iB9Rz$g7 z3Z8>5@m|r`KF>n~IfQfcZA4kg*7v1+Joo!JZkFGC?b2|f$Tk>P%N_2u>v=ym9j$cN zmd98y_OUBsgA@P-_cv7G1q}*MdEIeW>+o+eXl@iCC=wL>zaKvs@?VvxaIf_VQkiEi z{nf1=+$D58v4&K=rMU^2U5DxP)xQb15Uw>{W_ei^)qjLkQNot{D@!?yJLLC`luA^c zS)bmF2%AoNznwVdf4F3uh`V8K%30P({v&3^Zp$b z97_I^ewjIqpsg%TIO#lZJn#j*d5gNmuGX!0UVM17`n5$r@luGTNKntf7ZK(a83*T( zyEgob>6Q%(CP_nguomIF@TP$N4vVnP`lA-vA`pP?M%L{UKnkoSUomC3kZ65&nr;<3 zR%;r>JA)lw{oF8rhR$MxcxxK3erR~&PNuN`Sb0eDc)m{e8Pn7TJ2ir5JUg1t#(ix> zh?UEGYpIjuK9Cp(onp#F&Kma?ad}N�R_qDx&yzpUvMq9WhOd7A|3ZF}k=+y#SO* z@)O7tX?5cfT~}AkqO$NeWRRb7(P`mLunX=)WD{I*Qkw;kP-&OZd-oDYA{wD2Cz2O^ zVcrkQg&lc!$fA>8oYM2w$9O&)xP` zaMrf%8IxZVJ?`yM?6hknD37aTXz|srXA|#zg02k1AR|&gv1fiHres7+pnjD{=IyWT z@1d*dn!;v6$V5k6(q@Txwrgx^lvjONln!DXr~<_zBlUjnh&D6JR0;cNr~a&`%Y7ds zD7T>{R6z)w1W4iG7AEE0vf({rWeY3!5pdg0F3b;1b&pQZKMn`*2(k8f<`${3*e(K#tW+bd#-~Hurcwolb zb<{oVH65mHWC@aUoy&51mb&NW&0Y&^4Xux5@S~cA4LdoZy%3;vz(Xg z&XjgFov9G3QBlrFFnKxYR(l>~SEpDAparUMn5NLsj^&5$;Q9>ehB7G07pA;1W?Ac* zYflgQNV~kLYUiYdjq)jfVDPD~(*i6+2yrRjxaih230!7l@buW}Dj%d>hdJCO1)df> z9XsX|F~Qql1~Zj{olmJ9$IZ(y2Y=H5H}`_U)Z1=tZNWNr%!sujzy!@FQyH~q)nJme zY%EU}T_`v~qxHMap+C!%+s1Ik7y;6xs>WB$)SB_^bwiVee1=h-ZN(GbS6e^-n_Q$s zYU~&_hOGeQCJ0kK5ZC{SaGqHj*`~zDsgXz8nAO{ar3mOJ?2PcHe9JeVD{s<&MTuTg zi`Ey9cxi@O@O&JDbry#tnKAxe%FjGg7~(t^Oi$DOv{_v5ZgJ>{Whk-^%(v+S)`XLd zXgZ!BusOdB5(oTujacLpTc`S%a_lTjfte0Z!8sa!hprfs#j{IsURi>Mm)S1ooGx;~ zDoQY$WfNP%md|=+DybUJ-oYP+xmRDBf=(BSeiOc4?Yi_QMFTz$E+0IQ*-fII6fnjB$m`z2orO~AJf*1 z9a7rk)n3UzK@y*jq5tZeH1-JB{dE>pvD7_s-rME|q$P_lr}T#;BB50-+BXHawK>5^ zlR3QnTV<|mLG|VjK%uxa+f6=n%{17|cXEyM?Tn#I#=YF$Z5%Hh>2k#W@a%fo;ne-r zp3kC|u+7(CR-DXre*N4u0WXd#2R-r84omNAaFtIT`2=W;!u%OC6}#_}oP5Hvz+l=e z5%#{i)U>+mK7q|L_@U^T?H!=}!fRHx}adbz{HXz;Gtz3nFH|am+i=g|e&B4GXsxMyu3>EyK*3-6Ua_%!X zU*)|hPI+l{sgiC=U7e_{tOM5{yxq{X<9O+lDmNfEo|XErZ-lpj)7voK7>C;44kuPB zgr>$z9?1%wMm6i^(Y{^5EsbCw;oNV=9?C|h8OMN}72g^`8`z=bQ9pdA3GnLzy&;dQ z&IJ!76nc^L-fh8Jrk#qMjv5&z2qpUMN<cMk*KxW0qb0Iu63s3Exq3#0} zPuH#&yFNMsMN+q@$vEZ=4dIL7PAyxH!}f;?Kce9Y>Z5~B^#PetD!FA z%WP=lcXmRQ0KJY;fqu(1ew0<-ial#kF(RB+l~9BKCltKKKJRQT3Y^4 zV(>?JlyK;p>j>>s??6Y4$Gh1x{Ktiug^#ql*ADmdFJ+?63rL*RYPM+K0zCKcDbYmO zL~587yDDLutdIzeg>vAR#&m=(p>UhaIdP_t9CP=^tJi-S$3lydx>8I9g?J6KWo}a~ zNM7ig*7@!)n-aK*cE1MkZ{)^+U@O1bYaLlv&L2(-)%cb)3)q}bm})$^rh4+HLN_>7 zs+eEreU7x-#Mzp5BTJvXvgb52XM~NJ7pG@hBC5$SBV+NT!!5uarNguDHd*Ir=N2|o zhKL!XV%O7ESdUyDDl*zqn?EPxR=hk|kX@)>z@pe8FpDPI_ht!NORDq8I()#mVEK~F zvI2hjdo?&zqNY4Vy!ryJ3Ev+WIcltgc zz=`3Q`@LXz^yBGGa7BY$;#j%$bGY`y%*c~;(%4w;PZL#+@%95^O}n13=@^BL7Yh{) zC$*c;Rl-SI`!Rwd2ZJ~)hu*<5@2#OA?S=mdueqt`ccd~{pV>0{M}=7>6_t5sQ3HC` zAQMVR2?RAJTSEMuQ2ui@7q&wM^sM~6raIn8kczlNcOQSmu-nYp91V9KD$Kp}=3Fje zWsEh4U6@0ySt&X|yZPeEHLD{b-#ArX88o48I&I7CtaZ?waBLH_oRT=)(jhH>@g64# z(|Q?EgYAhxSIHU2HAr6v_=$XzKiaQp_ei*yEXmuIq+TPFf!Ns_O7iaS`gM$k+qC`} z-0YrM=^S@mrTdI@Dzq$vjh}hpGgTyJc>&K8HZzs9!xUu*d!VriJYw_B zZpX1h{aqdm+L}BVU1e62_8xweN?BC=$HReF=udrdYKq*qJu@DsO1hF_GIq{#eYFQP zvQe`z>qaqUZ7X*O;7=TFBWs}AF?>~!%Iy{;H2H(mXN@M3S$P{so)fhUtgxcWM1k)Xz-t)u}V@;AIMSg~d_>_2Bh6<&cKAR)srq!X_0tn1%qa&r-~E!(#ek28Hk5vIm-0IeY}S z1l{5L{sY+9BpzBCZk@T>A&$nEzff~h1SzxbuzLBjGQyg}b$a?EUL#D^w7e^6`!gd= z=>F1pf69~iYwZ#jm?ze&LLJ5zeu#2XyJwEO^@+XT2106OH-GEBE_GhXC8<1?<21_T zKF&h*xCqJaTcm|Efz_BG3jy*buY?C=t*xG-NDV7FdNufF1nuXX3XlgZR(w`8sEVPH`(8zk6A2T*p#^c?Iau)=DznviqokszA`S zvt0MvRBv|Xc(w-jC@7U}Kkq0|lx`ha!jg4f z`Td~Z1@>*Hudx^U*-gk%uve#r1nCRhrW+?Kf!w0zOp;ZeBbv{HG~zj^#pAF1GE>E4 zbX?6;K>3G2i(1pT+_2{jJG#}8(&>;i8g41qLhktX_tgP2&0(h8pn3U~T2G0R3XY{X!__tFEzk4KG!4(?Fdt^f)R?ZXwca?Le`g-_FAO<-2z zY?zhfLf=Q#>c+1wXg3+JXRE#G^7SI^&h*D>g73cF$jmwwez3bqx$ptH-WA2)f9xPD z@ShY`afcE%n+nJ4>&(pJ(AEzPd08AEzUTFyJXXY~VYSekUI-Mo=*I!zNJm~X)kd1| z*0hhZ-`~X93%w_?Wyq@@O3wMhOWf{Z+>KcSW^4t6zFD>7@LsEu!|oB6b|=9s+2|g;WCG`(AY%>#2C}&4kt9o z$=07XoT4Cnc8P`4Z|sU5tZXYw51;J^OJ)SUIs)KZXn5u=35@|oma@9&bZjL$9*ugMYq zH{MlpoMBeo){{Tj`^P@VxKEAxFec-af$FIVudQwja3@Bq^9(wzX4m<+m#GiaV!{m8dEenoT2pZ8&*o6`Luzeee8+bTC1TpffQ-7Gv?%b8Tw|!B10VxQuduU z;%oyMemIN)M5!PBwAKRLXImXuECBG`59dULO(#nc-SoD2YK=*+o~~jp%>79C>oX#S z$jm5#hqS;FMs)6wwXAZ8%Vq%fq>u9#sUEs@vR>^l8{RDyI)1RZrm_UBiJ+x(8S_EJ z_b+3_pEy*JKBoWT)@I2JWsGKsohm@wtH(>Z2r?^dRfbo+Mfp3%{g{Kwfu)1b+AzbqVsvm&5$m|{8> zD@2)>*9)MQ0x`9GMpkQ6NT<231Pbp~XkPDIXw&%?qtv~j3{0tmRgMGa6PkeE60^|{ z-Izi~&%MP{hs}`Rf{*>sEfb`4Jqnf0!PNGeE#?_|8-XF+=cfq|-P^G@$kS$rF~#%i zcuEEW0Usm2Q5#3-r~?Bm2AJ!hAVydFf1KWArL#b|r4RG(G&F$`!Z7R}I7RmSoOb$k z1EB>l6yzm*$(la}0Z_{~yUpiUg7C|^KDX^`#LVlwZ)5`3xfS0HPY^w2drD)g`0Ude z2Z54`A;YQQkCehTl>Tx3e-<`MEM-vpjfw7EMIUFI-*LG_=OU#dB=IMD9@5y{u_DP{ zM!B%kgfmp~86&O&5(u^LZc;zd(8%D5w5Xz@s0#?Y`4J4v&$Z29XRT zkfUxLfCZepY!ASxshqfc$)o{S_kvss;_Bg+`GDE31R>`z%N;7(pimOnBB+uFi4Wed zDLF@f`?okrAu)KK)1V^u&M%)czwy854a(0(1!7-~IquD!q=ENUZ=%hf#@951{*%>m z%veuUvdYqhFUEF$=9b(1Q}YMIKwM(EQfS3l`)Sx^8Wd8qUm=CuIrV$`+hRstG953f z2fizb(cauA*&PY_Ovlb=+OhbZNIP`<^_lwsDex48m0bmzV)nv~qntTpsK1SIlL~ne z*m7LS+H^Ep4!w=a@*8D=VMN~9A7wz-`Q++$9lhMowOV4eVca4BXJ?lHv zZ|CVFF^Yub;V0G3BTj2-+nq&5&fUD5^dODA|0|6Eo4Pp%gZQQ8)yev88QI=!V6Ab) zb{lJ|@%(OOQueM=Jr5fPaftnGCT!U_5jeg%rC@)B>YM)5E={=YvtOQbTihw^z|=Qm z*OQLjy_N+mG1@}*K*l>U0!CqtAbDlF08w_kG>Nz4NNPcJL~xzb&{X`MmsZJ>$&hJl ztnt&JgAfK>sfp7vII;Cy^kB6)2z}^eX`j`Z9eR|(O&|r|aj2R{pma0JFa5jCLRe@2ms^Q`~e|*|d!CeU{&qd!12*c8U*a!kf&N z)2=KbQ)W3`uZ`O&CaHia&s?e3AfRHPDoix*1Wi6meR9CJHcW4=$y6(K67a`pw4PuZ z*WR%!_H2A3D>#7Ac~}cHf-s`wZlbdk>$-*kPYq_V-f z3U7G|q31hiy=lU83k1?U!iN(nm$rX6nynTyJVm*enPKWRenxqJCkCFeRa&O3aJEPZ zbX_L(J)3QmKUT~my8ZG^iQ zruTGj))FAeVO9lxzz=2`Dhhfd2QR?%3K#&87{2{Lk)vvoCzETu<6C2gTZc%)vxCuO zB6#mt?yJLl!js{W9RJ~7|DLd3h}`36dAYmjN%bNiM0RSkRw<&{(79@3W9d=qX9E6> z%v9fs&3K9gir4hH9O)*2X)Gd|C+Y4cN1tZ6GE<>kNsymdNK!G~qeum1ht+N@$MY1+ zSOca33$vtRtU7N&t*Y%13r%0}bgbMKs%nepVS+%A; z#Rb}F@;QK1qw&b_Jh#g4C26FrwYmnE_?^H$m0xn4TMV0GtKVAuLic_LrWEQ`*0qWm zgw23%-O(ojc&_?fCe6`KMKCezQ6c8tW=?38t&ov0x5NBTo^eUQySiH!vEi6um zHNW?gjt}|{OE}1f?EVhlex&#t7>*NYY;kj4OdNU3cJNIwA>;|`N*gn=W0a17mk41j z-jTzRmXxB3nU! zJCqvt?XQRB(=)eFz>ZeP2_XhQ{D6mf zHUJt3;HIHRiSE6cg0n+KE}QtU5%Urg<5^X^A?c**jLZ>@rWc{jQb~cL&M@oA`kp6( zr6y|~bxG^qz{Dtr!2%tMxv+LOGR}`!*zMFYQK0+DI+gRI+uDGtNU&|%+e6j(4Dyr+ z^LgG|&SKrza#V%TxM{mZ+{L2>Cg>PX*ViM&4dR8NLWhtIc9|qU1{x+{)wP!MQpE1m za^lzfSH3r+><0JX*XsRWoOuh1XWba)KvWd^nmv}nK-ik^eX z5DB=V>T=Jyu3?Av$O#8S9dPW zc2eN>s(D$-yZcQcWQQk%P{(Z}d7tGRo4i#(Tz+zI+-Zki$bC1hQpWC-;M>VW^&1JZ zY_jOIpAwHFy<`=rE7=1%+p(K+JhtZYwim~>N0D&A{`znho#tmYtM_$P3kb20UE(D- zdE0J+z1OTXPf&z&R{UZ(L!@AvW?h#eW;w6`w#y zBcR>!>glPn7;907O5fT5zfAZazk+$or6znG?MZUvT|OFzrdWuQvl~@A*hrxvmD&lS z1`kLa^Y(eOoX%{8tU#VJF9jAI46!Fwa)YtxDTr2A|M?{%<2?gGgL}%sglPNmV%(~9 zcAiVNao9|MtNSpc&CWeoh(jkiKjDs z)U7P(AI|Za{>-w8J711gL;O`GCu}lUO?DtovyBu+@4rH z$zIuO-OUk##3Es;>50BTkfj--J@L{!F zG49fAKBk4(s7t&8>O(c(FcOvQ+AH2fbhS@5?Ye6JFmZu}@W!CA!4De4ASu&*b@+F* zkzL)CObpY;>er|fuT?N$&!D4yEWegQ0uaRMJ%Ws@B`^bs(TXpQmS@BFVlSwk$Aab< z0-Vk|kh`B>Y(#j3xQR2ktp6Y~byDUhe1^bK|J@?B_BLQ`GfS#&N=5^*0geX5YpE*- zeK#>Bfe3B~-@89?Z|ELoD0fV|jjC$0+8(Lcd;k?%z9)m0=ckm9}3^D1&7(1G+dU`=g)pzVP-& zb_~lW-+J6=xoU!_xhXax(%zQv(-?sRGG3uUkrQ?j90?z707RdB-I35mfJh%`5?QzS zzuO1x+xps&$~SiwGP$eN6Su(x{`7Y8CF#G_lnYe2Zo?D!*Cqdmg>PMqFc;muie^Yf zFQ{FNOVnr{=)wo2AA5~s{XH9_Jor)|;}d%q{2e==&7C*^em^M&5x#7_eO+Z(Vpd?| zdpyOpd_>T|THkONQOKag8U>YOiw9~s3Zvn;Y z`j95zx5$u~cm`hop~6~SXP~MPANNp?GF7&BdTYPnTCtrypam#s1%US^&Tb6}f+o-WDeXW?3Wa4&o zaQN#)Z&e-SZ(K&;+oG}Y=GOM7D+Wj%CqOED##G}A>~@!DXI8*7?P z!0!YNFc1zWnvYas>Pqa7gu||L43!oQiw3s&a28k+ROekL=eiON_qW#}8Q92bXbzO+ z34-W0*&Wq19U|LN39ZOLQM)}Gol~P~K&eeCHdk|vh1S3>eYDwOG;tL_ZvDm`u_69l z3ZN*`37ErU7MgFq!A{V`Vv;_Tse8zi8)V&Za@<+XnFrJ^>*4Mcgj|OeB|jJXdDN#N z#9!xT`ml5bm`0ffo;YcK9N;R?OO&@C>(lV)Ti*`o`;hGOHFXDgD)ye2LwQGCU4yWV zmQ5iU<9B+GpExJ!u)mJ2dA$6qm1(3aHYEb-28<4XU|ImWqALZ~6W)(3v=sGh5T!=U zvJ);C%1j4W5^;!W1tZp?@2$_-j7=IT%HP6uz}$L<45iH(*)>iAY-PX0LIC$k7jZ)4 zOxmm`??iits3`!cdI<37Gj$k%fd;{u3%Ns=DrMX$Oh$05$}e!FM)0UfM92q4Po}Yl9nKsZqR%d9=cYdQX4Ig&5T3$AGmj;!+H}Wj|L#CX5^G z?~#WnJ|!ChotGUQsV>RPQ)6O`@5lG&pcXU&!W>j8Gy%n(eBqv ztYtB_e-$2|%;7(UhxMlVI)0UTcj#{Qx!x>FqKox{g&oDwqB7lB$okX&>iXx(fV4_XAB zL>3l8W{_YO_JIR#Ol{gpU)h*4xAZo4C7&U`AQT;N<4x_F;n3ELBedNXP>rNT>B?;( zuo0KvHm2OTZ_?D(|7J+lk6^%ZB&lzaGOe}1U9V;Cvo5D;rvZGaF=SMqO8^m>H1k1D zs2as6^06iV&O`~<`C#iRMZ(5}9U3>W2c|}C?o1r#ZYY^bU$3g83~*4F8!Geiid8bD zUYLH%_o~QV?YJJxsF~dMZC6xk_mSf?TKhI1sWGizSK&* zJsm$&Hz&L;p3!JVEOZV9`lrj`o$pj8x^|tofbV0PcI9Uz#zxeQ&F#SKsKOf{M>%s6 z_G2G;w+DM@KTcf3)fBU)`r?W>uuIsgW>;7sW^ zIjN3aFCcGTim9b#jg9@tUU8}eP$0L^ zI3<&giw~4g3>^@Jn|a?IFH7D9Vb)rW*kN3-L;7`}L2w8|o<%6x2M-YUr(CV1Lg22w z-I@HBJ*bB`UhT{#G0F|R(d5|Xa+Bw2sR`(4Fpvc^&9!-EJ(lPh4F~j4^c-4lA+3gY z<8W+#n&&HP^8zfew(EnV0ct4jzpTn@eoNnOpB6D4EMEcRS!P&z7P`dEZ_#V^xms%5 zp}LCrcY(lTmQ4~Jc@@P5sPZ|7Y~wD*-i_H~6Avy~MH`(M`x`Tgph1b5)(*)BMjXsj z2cYiH(q^8d*Ged_&l|hxyhp=C9>Yoo&4%BSa>3`+GY7ZVz0XDCmg}O;E?<5)>Mt?* zI}W%+%#y*_%XopFz=$Xdov&?Y4VyW%=k99{`D?8@{(8_e(FPR=eOW z-yrHGlk*W@CTw}6WsgtK0*h>QqVAT(d6Z{_LK3&Me-OqP?VB7n1AM;R#}kiES|p`U zUpptgJ%GLnkEv3%``Ac$waH2-f?#8lD|sQ%geD1=LnkUgUN5%rhWqY>9VP|(O-_t^ zK}_(r7$mT9aX+`&`oEu`+5=XHOzd&~uNw+wsU6%I`J`e80V!*cmo+6^^DfUYbe1doy>12Ml4R z1(~6Ha+-2riW2QAG>35qEMmS+>iig2>Agba8;cmesO2*m(Q`JTrC{4>+U33RVK@ig z6w0Ip=hGe}tlV1zj3&l9g8sU_M>Bmfju~(ZpH3!J4edHCJOXgC=@PxNm+UyQrqRWp zttYyfIBTlqh8ah$y_yxtq!yirtFm!j{ExkW=ZOlOA=$F30;ycZeXs#L7_Kv+l>@;G zp8e0sX}@;WdA|uhH73*rTjYIyWI-*y`4n~WyEIlc4R?O>M1r8f17y&)VXCz2M&ZR@ zSeo#|@#Qz)(wMaeAM>+4mHv=goMdYHmt&TJx6KJXY~VGNz~&SEOwe3O4KwW;(4>lu ze-~+Boxo0UaDG_vS*nfpt;658D>QS7WX@L#C|#&qVx)OpiZTsc*60X?qnEQ${(_a) z*QRPD>&$Ho?Xh5tPDZt?TEuqPps<^(rIwR~MJnT$a8&~4C&9fzAWqzw6ftH6ULnO3&;*MwKvJRe5z8n{{6Bc;~ zpI*6O0=>GX_3m;>$=c&EOu6sJHKk7B5jTmRRNL;&=zOxO>%L7$l}n22SR?8KM-Z`O zV5-AgNjio}eC7Ac`5Z$Y9MA;Nz>k=i+zh}Kb2?6ZF(AolsIcJiZ2Ogzp@B7>oA2J7 zlln%0&ihs=i`~zPd^_gqw=(*@=omdecWCfR(>_f&@`@f3YGXGJ#*n^D?%jTM>b}gB ze>M@AXc^84g+1^(;^17IbBTEus4|~`%}bu>39=#SMAI4XUVolSKQMJmE(BeF^ae~R zbsO|_27n^nzz1l9w5;=P>H^xg$j{;`ulNSkRuD?r|D>;ipz8bxM8dl~WI{zwYfTh(3;liNrV zL#?WA4{&#P>I*|1MEE4^yM(h0iu50ZD#INmJ&3@E)%e*M6jIpUp8e|UWgsRQ#J6IF zQd*2fZ;C?ls@|sXi>+ZakmBE47Ne4fHwZ!WrzmjFAkX^>;JL5yNmyEV5SE;|hU;vFOsdJspGMd!pw?6RbYbtgNp1C18HFU}>FD2v#;_|Cm@@#h5fM`%~(+*221vZpkX~kV0Z)k@eYTk z9Rp0SGSJ(s3;ve<9Un7RO1?ZYIG3BnCc&eOhMn)j6^RR4eZKeyjt+fYC~eOg19`0S+CFMaBtuBPzIzb7D>oMTMhPU8>cz`W$8Knv_BBIp%KZHLL604`Z}q4EpYx~EMZn}lN2|-W+1#E`fGZB&*%-e zvPGv$24$e#w>OtEiOrLb8Vv-K5}!ctCGmYzM4SVbR=PCZ6e`(3G0891a?Pl$_M zOTK2EB~hj+YYf*df7F&Wz6i)Z10d`nFl7%TranQ@HUu;J7hqIfp4b|;ap?&-4KMB7 zb?;B`;Ilw{e(E>z_&LGPjG!UT>RsXHDXMSBu?oCalKO%Rifx7d>p%L@`B6)N7c|w$ zR5I6iF}fzwuTu6-O!?5SVTgMH)!`$zl=Uh^eohqc7J8$L%Z&$sQlKHGjJOWi z9<{@5Y-S!|*TIRj`oKz&5ZMMJM{Yp@E_DLvc33cjBJ4lt1HyQAV@1qca{S8C+$Qme zbpRUYO_Fxnfyi0>CZ6@KY>Qdsg2tJvF-&IB5B=#6*1`&771G;;Hu8t10|@Q!jLbgk zW%if1LcD8dW+#CU#_5GRW@mxd5`FVAu=#gTi;@t`ey;incfz86Q>c4!spMPrd+9z8 zD{jHZbc`&EIo-`4x1_ZMevlm}z0<(S0CS2-t3*M16`$8O4q*Os zF-f1Un}tQmDoHhQ&#fEXu8XFi$k>n6fZG{ttXCp$4X|UrO*ke71T(K*V5$C_Goz5U zO3b97Bx>Ve#{8Sy^+434=y7>R5al$JE@vOZ59y)3=~|A9^we}Ykmk{j&cw;l@X- zH7xGtJpte2$2As%zkLrnV6=iUFK7R6A0LIA7^G*6x^?mOrMRz-1x26zIzeRFSfFm2 zfK^OWoAu2HDW_>M*!@|B-squ|So^z+;+*4;_PTWosYc8Sd)@pht~a!Nq)gqBPW%>0 zR=O)c{1!S(5`NZO#8 z90HaN@q(9f<7YO1H*dapCUX!~@(9r$YjnWL|3-J+?Q{4?X6BR1CZlIxukyl5f|NHS z70peynQ%BGX5jhAyQn`h*xQpAv!Zs7XDI>;DrWr~)zR}G644=|Zljw3P!&)lBUlhf z+CNGua=*x&{p?D(K(DTZq5U|{sI>h$UNk2unPnoL@k8CpAZ1<8a z*Oj8h}KLKHSnyvaCKQ-OY{6lP2a|_%F+Dp~!zb~Ac zW4!(F$Mh}gk3eMTi%#LaT=&Bg9dtw~)U1-{dUjc@SlT*DH3M6wv+EwOZ-U&%NML*u zaeiQMrEot)vcsz$x;N!LRA#~Hiev$Vi^%>?(!%uur_holEgo5NW}FMRHApad=MjC; z4JZ5d41X>lZUz1sz>d|R28%>q2f3xXNf&4h@;}iWbQFfd+om zDse5E9a{V@QEq<{$=GziKD<&SRT+~b4M3EMSK1+3B`Ws~_o zc_MEfSiTC6BK3Sy$yQak>A{~K2m~q`PaUxS^HaH^gOP`*YelWh_8ptHTR9lg*SCvjr zBLH7}l-V>5yw6`}RN3Drrcz_36V3LO)c61FJaOF*KvKj^U&P8s`6&DUnn5{xMyfoKN9Gf3RRs)$_UPn*MQfcbd}pX0#g|vccK5((_4Di^7b)XVRZ|`&IZ6b zGwTKxH2MAb2?KESQK#?S@4i4otRWi-DhZ7l<{kVwFV`R2#J6%8&bT%=XtdllHhpB`w14^hiq25Y+8DkY{5T>5f?|N1C1 zqVGg)3&BU}gg3L`dRF?zxh=)?+!eMzEra&7kiw3(BnTCP^Fj(hlT%0;DAI{>_z-C3 z4-fPmyjtx{zDS*Qh4Domv2tVfJ+0G^OR9rU)5i-gF%{*50lWNHr{vTV1Wj&IveNbM z$^3;t%NR-(i!uyC6k9>^{XxCyU4dE`D#vtQo(7+GaP}-Fp^|!dJ8Kad9dbMe@@GBl z!hLx<9F*uZ$WcFO&=?%xv(>LwbR*(OfljKltw)hpy?9(XbleWyatQoH!IeR#Ys$Io5h6)H3 zA0rqIZ}L2*>TQbLdHSyIublstnyNRGKg6o-{eS;yI-7_mzBjLOoYUs`$0)0~Nl6p5 zBVYS&(J+5y0ad&ERTGumxH`ZdPlW0Zo4F{%xvigEYd&km$ZO4*+;LPci04*^xWSW6 zF_R7RM7zHd5Od<81zibz*&E*j#W(gmB_KRs<(&Gb>O)0y5mehUQSXmj;OS8C^jR_O z>$G5YLj2~fcQ?+y`SV=L^2Zd90AS2Yi`BSqN<-1oK_4avy zH!lm`{3Zss5qS2WSN~a-|KkZ77wWXo&Kh@^B;B8dg>8Y=5BlbOIq22#q&z-3f}E{& zAQt}~|4S!9)aP$+usNw63NvE?QNOh^Sbz@&j~8ISaIuRgsvQK}pSTZO;W`WeYKIP8 zq;T_2k{R){mgQeBQav23T~+B^_Voktb@NQ$UAkvxGD8Of@ozbZ?q>-F0nm?>-J_v= z`P1Ox6Xe#ogul>vdYlm{HmGk^3=nqkwT=|gBjOyb0 z|ABkjrzq*>$8D)C(1Lxt1Wrgysp&>%N~eTzQ=5%(&O9QOlmGP#@UT-J|26Z{rNH+W zz-QM$8|gXyHN?PUO$%0kLCsO}@PFew>=Y&F_4JRn9SFt$^XfAxuim;e>f=Lzu6+Qy zP7DpbCtlF;PoMn;KWBYkVgobSa>LM~+?Kxu zH~RaZcxov-e$Zm-Cg?L`btw;@NSDf`Wxe`O-<^47F+BI=<*GvqmK#e9*PwqbzWF(L z^$gJ9+f)ZWtW6aq)n-F9XAf@jziqk-4Y1`_X3w2IL-A_|(^Gal`N~%${QW=e_*y@j zTQTBh;LA5QYE=AdRAlE;^UeUHa$t7AfybYE09J4OwZixxSAU4=&yH74!u08Z;o)ik zd`;?2RtGMCX-GN`TfZl-aUFzzm6|Y{C`zH>?6^FbGD7+C_@sMXf8`RMZc5ybbUgFs z`hV=bc|4VC_XnKacG_`-WC%r6GGr+8xKmLgBJ)_=kdS#Ewym57AsI`iLS~s|)vlTl@cf>h=l6S__mB7Ue$GGV<2c8CU-!D!@Lk`vu50}%T~6^?Hq}Y5L z!2tu#)}&e=h7kX$_gFa$;%uLu6-52Hq-}zSR(X0fINRaE@4n*HSXL2IusZsUGse~| zA1WwGGRF4UWUYVpf(W~5b@v5~4zd_e2JJcCpbA0u+n}bQ+Yev=3I!3q>6!TBEte*F zD?^lvZE)0rd}b@OnqFt6z_7d6C^YMDI_pKjq${4%_|DFfC&9tE8fH zP=a{K0X9F}{c^~C{HK9#X5HoP#%*5kw%wc8HoOL z`lFhkd^zB7ZKLq@r@?UgX5fvlpaX1C6F2MX-qo@rd+&~Y7&yS`Su6P`){*;1tTP*6 zbnQ|A`L*7lrd5CcjvwaEN`t;X``j+A;&-k1A@~24B$k@IKE8*u7ooe`DjR=+&}T=0 z`$!^*1@mX!oE<+!TmL)&&WtbJ*+_)Oxqy%X!{uwzKg4kORK*7V)yVK+pIlaeFU;5>W z;14Wf^sDhAf<|PeCF8`=xs&IXH==?ze%w;z-4sB9LEFFBVu;v@-4VOiU$&iggGA_` z>&SyWghvb5sn1!smwR@BG>_$0KyTBHjowz7=B%5~>epz0>LMSM%PY)DDxo@@<7M%~ zPj~##%y(`itHe4g%*AGE#+EJN;DIax3CTv|eojcN?JaEf`gk7NF>^N97{wug4AYCk zg=`;)okddRPU&;P-9JSMr-}kKlVm0lsSFca<;Z^sp0yjbK#V*@^~4$c7Q>%r`oHp9 zSo_tp9I!ze(E6iUlzB7G3zX(6p}W{Q6_Sxh#DW&VC;E(etWz?e#Xo_}%p!-Vvb`4$ zaQcbcxjp9mxrF{8AIdle`kl|N{NYE7U@;~b^iZ9^p#y&% zRD8#dY}dj0$c!y}xILuD8}xCm`f}u5Z&8KIG;VvDkToDuXF(xX`=n^3KVBy4D93w= z$WdUv|J=6bp6!Z0^uUf}-2Gu-rY6rHM{&h?jfnXDs7g*5x@V{@PEVE|0eJ=zv_DtBO|*yRV85`-NnNzkf?_^-af%o1}q?ww(yuyfs|(0fAdr^xHwhi42r zp|3%=6E1tOJX8Ebw|POg-&0}gzdXYh{gvuHC_r`Wt}IcH?ccJQTm8WfRPx?N)7`xK zMY%e8*VUc$rA}KwG)hOoY5B|0Iw(j~_G>4o<+UYtMf_Y+R}U&q9YwvTZ!F_Zn6G6D z{bBeJ1i{)iNa&Aj5ebk=uq4In3|2oqA@*)J;U388_BtvA3X7>oCi})$0Ewh0bd8{i z1Sts)63y0`@18O4eMLcN{At9#*+{99#NSJrJ9**JIz?dX5B!Z~0NV?^@>`#W%;k9E zU!r*lQ~=e7w|km6w(RRRM@h&fe`03fZTI=g?PR!|;+E|=xg%iaFtT^jPoc4UkZAIL zme;&D^`m#mzwl25yA&KG^iAJsU$?&?B;W)gL|~sTpZbwq zZQs7%7k}p92|n3mt*obR(5w*b@`(KGA#ZF3hDWbZ<-PQ)F6%RFL93r**dAQ`c~pz4 z=K2&Bj_O!U)LXuIPUa6UWlIunpW^EJ;LP(aYkH@Sm|%v}L$9AEH1Ya<73U7mWVjxx zLC)U6Xan(isN8UPIg(qjd1LD_mc3>Aa8~#N(nCH-yz+i_Iq2M(g(F>5=OPg*tRl3V zgg2k1Gw?^Y{ZIhOwQ~<7so0j0UF(gq8>~Ha;D-hgZjpW<-hSV9^YF?R41~=7OORIm@I=&*YM!0CChKh@2Z1xj+UE?6lO{)aw+zmv)0h zeeH(cz%y(EC$B2YvCruI+(t)l9ube(LozC%HYe>~PTOSnhkFh4t|eB+_cI`n?=LvW zdKTH?eJ!W5{!+z%{OL34(IUMEsy1aSa9~DN?fFG@#6qFd-!VIb5XTG-n2G>+CfT1! zBn6qsczx#Edj;v)tcBfRNhO}UUg6M9oIi)vf9`(ruge|sC;!-ee-!VK&g=~9-HTgp z9DI<9ELU&*@cI_=@UO4gj0U0vFL-ZYtuN=Gt3|Xt8-vkC38VMFxH{3_e}px*93|I=C^!9$GqY0MUxeDn2QHaW&8uCyiF z+GeQWD`aEOAKt62cr2oV4<6Nb;uktOHtKeHo71e%&=|>K0*B<(k93}-%G>@|<4=|3 z{_l5@%&y2puTsii@umH-fN!-7?{4GRR<`1o9vBl~Jd@b(@K3MlMf8mohZdJ(3rgT6 zU}u?y8(w1l1Rkv7unVNw%6-3K<;bYq?0$>pue|jqo3z64?%hoW#?V@nhjRV;~s3{+e{Xf=awtOSSO*K4CA^BdwZ)UZQF$ta1@{Cz0+n*!y^bp1cL*>%6Q`x1j@(-GWWQbu(^nRZSTJ?yL z0kPU%7WX3`L72A)9IJZup^z>2jPF31Q}ubvP<%(2)GeF!&pg)u>UZ9TB&bTS1g(F1 zZTZiPdYcTk=>$O#iAOud)whJB?ZDxGwW>eAtxwY%`@)bjY|FO%{N?|CxvUf@v`@45 z#nAsZLYS{y`6-6rGNAS073b;2mH^?0C{Mjdeom{o$`i zd7qxUr4V;GRN!>D;(jhRHMe1*%<|shG5a>7lXVCzC54Jq1JygdC{ed zv(dd?e~vnKV`XJ6-1R->FxGp=pR;@agCA5hVKA;f=kT8o{tthc!@_eY8`aPMcgw-X zW_Ww|6{$8+!yL)~=EJ@d;5i3lQy=~}4?$*G>XVREIwr(#nV^`zKc@EmvV42AzO0Q Ku1zEx-Il!z<(=eN;De1xI;g5 z%cxLfmgxWau_I(KN}Bt~f&b%Y{Nrm02Qe@^nxu$p_kXmCzpUsJEftlXrh@o?D`zPx zDypuX4(faV6QTUI9I7O4a2y#S4*&SU|5tha?STHZ1pjtG|Jrc=c0m8yx&7^c{*CMZ z+X4OUfc~4H`nLo6+X4MoSn6*F^tS{0+X4L(9r!y1`zJ#AI|cjKLfPVq|K@=HO=SL? z1Nzr&#orF-U)$Q>9MHevCjS3ULK6;>TRv13mrig{R~XI@X}ZaoFr(EcMAKH$XSmbW zx>{;uG^9y@Gr`|oav>>tdm{dcmLD&)G`n{&?8$5KHt*%sqGwMX){m+Tt%OyHerL3y zDEvilX9h`|w?&0e-(UY)!K%M=U6}Y(YMW{{o{3#E$vJptGi5R*8x^sPi<@_)V? zSqgt>Cc$);b%AC}pz+4W><%e^vY}M7uc;O_5DgsR?RaL;#V|b`Og9NYHQoLcvT0MMU068^Wz5s z`)i2uU-B%TdQe1^Gd6tZQhrWa)0W&;#ruyt@Yf=KS!et{=W%al8@Fxr5M5)49*}ibt8+jBh-b`F2_$1?nE#(oyFptU-<>>IQag*po?+TIHU_o-;LL;Yk zlkoYEf)5kn5BX3q+R&B`cgD5r9OwGtJ_brh!nUWcsDV_<6@R_9i$Frfk8g?D`BH;o z_r5{(U42eXXZ}$t*i*4zt*aDQxB1cvZ_K`p*KXL3v`1*neY(%ZlBZ7Ms_u_LODUJ) zSC>=XI|wBeQO-S&N(Y59Iq`IN+5{3mZxgC_g)vz~c@3U(@yU)&fgH7G&}cnOwr}vV zh5m=V|D!OtaxQjlF)>)w`suMPE98DVDDX!w0EX)O3+xw}Gzq=%ue+(f->=20LxQ@=3WE!Fg~-sn`J8RXv5VhioA<291tk%}(Cq9uXS4&XNXc*U{;6T( zE4+?7Zm=l*kIM8u^bFo!e9c2;&?Gl_tKKymAQEXd*tvsHNwehUb=7qGEqwz_08f7P z#-AQ`Ac=kI4UMv~A8*mMW&6suU#zu0UEQ+Ru)il^Hyq0%E}ZtRhyWW}v2=*(spI_c zEWmYIVXLuiI;QU@32VJkWEk-7`fkd9*-%B_ZbWyd9%sHqCze*k%+j3Xh<3Reqr|i+ zi^EfSnV#uuFZ(vkWol5{q)fOAD$5xEp2X@%;}E?6sQBSpne!-L*H6;rR)T@Z$F3+E z!HqY*i$P1o4W=7~aSb}jV(4Ek^!09x_mVBPbix(Ol_M29@>{ipy*ZSEL77zcz9V)g zd-t7xETH=9R*zbASS5mLTs11?5Z1^J-P)jB^8v0FYKL3(4Ik%EBNgv?(rB2jFlNH% zuDzU7DIR>%nA3Nw#L?oh_a>pbO z@tZ@Xn8QEY=~PvA$K}0He~h&zox!_vu@=g3#OB`H`rJA+IO%Slpmk8XgbMoE;1e*t z#IyI}L30LBCiWL~!kr;9Ow6s}?6Gp&RJwu{0|I=)Npk!MKR*cYmn%y#Ggdqw;`V%~ zdlrWnA%9}UV~Y%JhJNC_A<^-JHhPc*P4kKMNH4dSCECkM9-n%sSTt(YUQj|AR?k7vLTs?5T=aCPR?@3;BN*f!L_`C)?sc@X#~`X!|s zCyo|xtc>ou%66U|Oxl`|no*Rp*4{U=^7>)OHdls?Wi{GJDSu9q8&H7-<>k7cV=yNd z%YR$^fyhHSSiKP=h8d3Iu=mfe!nIa9QWJ7m8^Ob<@fl(?+%K#%9-Kr(N5e#VOR!az zm#s7S*VGNxrSq*D7IXV7gS`9RizQ#+$$IlH&!a(V@xJyoFJ`}?s%(MxhY<&7xI09q zV9xa3+4OCT;y*|Tx?A#v&$*xT^g$HbjeV+mE&c-wajClOF@F;S3jK>(-$d~wFYHIL z$mu6K+dQrj8KOcThDp+oHnxEZB~}!_?sJagzunO$a=!|+&4`g4MlAEP_dAx8qLurb zPYe`oq+5Ghd=vL8?_CY`&`ql- z-S>_-o?Ontvi6=!YKspra@)P{=xm~9+k99>1-WEoOo%HW0e3N(_#1$j?o@nubh0*v z!gSBtwd9@KzPXVbK}W`ASP{%zFj%4i#qdZS#9Wot;f+Q*L{XPy2m@idH;hZ@sMhej z(MlN=a!gi&c2RG8t@U8)b^BOOgLJla&{?|orge{nUWRg6g+TAirNdT}qT{*Eav7b4 zVWj8+rDHq6hx~Gpm00lnb%VVcOZ2u*0;~)0*j}=T zsRKei9T2&<_@I6ofCmM=8$$Ohj35><_QvwG#qV~(GmRZOGrF59;ujR9)SSwdG&(9t zii>WPMN8$x)pFla9*tcAR{j1Wykmjb3%X{|I-=a=4En*NR{%cdMhY6fcdpobIq!TV zhbq;U_o0h;RU$r&x{Y%k#u~Aqd{+y4IUeK&LcpNr{~{3-r){vsq%lJQ&Fr2~)wcN$K_Yb#J^J$Ua`s zbwXmU@pKN1*0q&X|8>9>{723vE;k9+&u%MQ$U8m%0d4?qf9l8kIKA-ez4r38+Hzz0 zgRaI-a39=#ZFw=)7hh*(udGQ=mdwh9z8rjPLD#f4TD~!wBuLXOV9}Z;d*EX|61TEH zBlhT2P(zVBnn7d&CYG z!_W(I*A7>KM?=rmOKnS|?CZtaZ%fa`jZs*;ynZ(?3{zzG=#$s-m3z<)v1Rybt-qXb zf{T6W)_SG`obMZZ0;bMZ#;-KDbET%8Fs2(ig!ednC79#mU?KfXn|8m!5_s7sXFF%B zuL^y6|M_Y6^Jus0`OOz4Ouz+R&;NYYkD`Tk@dKkpT9D_`YnFO1_=hQ9$<(XDlu?Ie zP(i(gn=EUrop8f(wqvU{hpy=(li${00{h08P^PO={zo|`69gD7)EaJNr!Rz05|N#; z8Yo|#D84p}7dll3RS{K?xYWXX>UK3s%( z0u8VunI@U|_0b$sIxVAP`Ws8nn_&A9P6I+a?XeA*D0fjg_AIXXTtLC zkuZj$UyvLu&Q_@Ev4-vwzcnH8)>#IYSzQU7wzOgYGO{soWhJBflZ-`_&(^P$O}!#F zJ8AmiUC&&ih)K+9*HAWhM&Z+-gx3CFm@HMkw}D2ey>lK2)iiYn@jg)RdOcl6=UC<1 z>)58Bvvle%qzhROs>wme71as%vdSBt<9-J-e+D5&l<)Z$RTl$6$!}r5Y(%BdD6gFL z#x9a7F70{a?k%^~#~4u|nHJHalySErIXJzWQ*`_Zo!{53bnXj^pEq(NJ45wFvuq}m z2i45gV;wosX_-@(4H;;e{Pb4mTI`3 zVpR72XypAlqD1fV#r$_{e)|G6=f!+TVO+%bAP>iAhp%gwTbSB9spXjk_IYTxETni+ zFD<=S_Bz4D{aIk7_}jw^WYX52qq?^rQ&VSlbIZ z@9gbPuMJqnp6*EM!U(>C_SsNP1F_ZR2E0LW^u=%%in}cP@AOTWTJcWyy7c?!z|Dz8 z8Z0%7_-^k$Oa!rSmyGDXeL5NCBaZ0FgHE5Xv_o`V6zHTqRlaC3D%lP?wwWz$CQy9fywCubwWqFtbx+X?xhKX(#- z;15OD(CDirTd&9(rI7EN=;ag}jaLJYe1=uzV<&@I;)+WO9tmEJ5`M%!6d(vZL?uj83sil^IH*;uc7`x(JKWnr!0ho;*W&Im zvl#cIl^#v|#&AkIi)_qgbxA&@XdByG1TH5o;&!f5MbzKf{69#9iM{=^%NpW&T zPAH!?@b0qhS#Gvot38WlnxY2@C5}GlW=#a6<;%2=OZ0||H}o^!Z85Iy5ZCuYSIF^O zLFHVaz|X|hDupEU(xrcarU&Sjp4PH z^Wt8Deb)F@-GrzpkYNNDiniZKWJu%F*}ozM#9bPyW6DlSvB$Il)MX=f#zmvFa>^S! z33le>DyWHcJ0=!jpQD^5)F zuxJV|yUfu0b=@f;RHH_E@nwSvxSAUaeuiso#Um-H*@#2YMu*Gso1w1_^oA3MV>USb zyqiorgO#Npr5BB)_(}%h{e@Z?$R7HM-vICz=XOzQ{*z_#cs>*D5+flLJm63gmudZz zM{jE~r>)!cosWOYf;|jiwupCyfnM^VSxBUrIqN-VY@L;D)x#6rYx9~SwB^i{y|fiN z_iak0KkI8G&UJb&cHh<@DTVoV*^^$2#qHtcYXg=yDTI%G^E)vJu6B$MzkI<&%0DVf zQpR7LF%TG+p(J5&Cz&4>;Bx)3`zPz)dCdgJ7-wY6g9XXi zh6aM7SRHB*A5A;yU^SpL1YwN_RfijBD4c*;I=`U9U}Gknenx7k@22+s;N@&O@Bwk^*|@ipGjs!) zfLeU#f<&rPw30>ZtwITX7QA_avGwa6<$;`~*l@T-4qOf7ER+QX&f4Hw za`#&~gjCE?-|2gc$*n7|o&ZGLPR>`-xc898i{qIKOOF~n63wHDi^L7XxB$$Y1RN69 zZKX*q3ERmn((Ta9gW4ZyHQ>g^npNLwO;QQJQmY(o$@Fr}@3@{yG48jc0K;pU?>V9t z!}ZPIo{2j+zoX_xl(f*5)FjUwXGa@Pg!syGWbazy18JX+ zy^Cdw@QfB2Tu+eAMX6uA5W+&JP1i6e1vr%hmwT5#;PWwM@ml&)BmJfx zd>#8cVXs@Py_1*>WG-=J7|X7!c>{9%UhI=YFv>B^^=X$}hs*tG-h=Gl#Waf7M-7SM z56eeZ{QBBFHe3!8D$=XUA;vj>uV$WE4%4}w%!6`?w4!EsqRi5OGx@5aD?w8Eu?Ldv zG!=QRXpfoq=_&87rfI>j1M+3I2gT~0`MqANvMX}@HWBhvHaX*LD zKUKKspsXw4$xYN!7@p}W_t#OejBpQJQS@`LO^ULsK2~$(cXcsBAxr{}3(LLx*C*JC z;#0UMk1AA-a1-)L8QZ!W`zyM!km2kgkP#q3AM(wzdVeI`lF>%1{@|%f>WFq1d_ZhV z%5jYyR`KSNUekVtX$s=k4bvFJ+Vt#cXR1@)*5%t7jmG|huC7U@NL}j(i#5O)r`x%J z=gFqk(29G2huQ7$N4c4iLqp9m8xC>$S@%Ys1xk11TKVs!=4U3vx%%zgBN}V#@(Cvv zE1of`MJnh+s7;LusOd7UhUr$qxgB<86kxBE+-matIB9*!K;f3|t1Y85DG7i^8zb7E z^@Nv>nfMl!Px3G@#E7fBw8sc&YWiVURKX^Q;(yBU0qC)7Iey`q4M|^ zBu`i4ul^Kwq))t4vwWpRwnyuLxQ{vP^!=#vUo`Y=-^Qt1;}Rytb;bCLZm77XO+;pj zL=(Tu%UstndA`%995|Q2>kVz?8}o_d?^y~*Gm7Q9?FFhtI@z%0U5i?E8!#!%D$K+f zpQdP7&y;$$6G0d1q%}B$&K&j=+X!Q91Aq=~DT_Pzc2ix`jkO_OY`M#^&W4R$MIH6% zJQ!#K`eH+Bs>~@RAUUxcGeMkPO73$1q(xG>-ph3ScapLBH1O7o<*lhfKuNyy6uEZ) zWHat^ORX36H9hCkfz4kNo6kdlEU6fN9%I1J$<~(}HQslVvi_@K+5*EVO?47H%TmQI zGRHJnnWQ`7UWhY3d3kW^BCUk0xkXWl!zYmd}iqmMTFjc{j?tJfaM zsR~QD+M8Kt`J{$Q_l@H5$3hmLHl!B2avGnDlzgFh)+Fd8NS?F-IJ4$x&bNJS zIdI5!y{-K!?RU6LTUZz9jN3lXh9FwTsr!z8^A}7_%T|b+&`2$C7H2KYQm}sg6(~-t z+SSCaY8arD*%7EqbQE zdurC}k@Lqr+dMtP=~(`|LUKB{!KC>RRzdyf<2g8(*FzpLHJ({%U;$1)seX^;!|9c@&B0c!JHWW%tm36T@R-oR&1FJ?tc!KROVsd-(P~_1? zYF7SnbUlRaSD)!pwJr{7&>GWn3*_f?1CsC+u1bl<&H9k@ z9*cO(^@zGrtEb4*t7cv^FZoI0^a{|-;K4P5tn$@K(VC=H!nKBZ<;=f|x85tIJ{&_F zVx zooY2@24}BXi^b-**Yr8=^vQ%2TsHD+SC@T*6fXZrOf2(0WZ2daC4F>wXYchcE@R7? zr%~=EuvNTskc>H7sa_Y(t+Cw@Pwzj0B;(6L996?Jbg9?n%V!5}Uy;ytT?@><>XF)! zg7TRx><>tZ4_$3VaIY?<*tZ8Y4o;AW8F690RS$j{dYMeAyp1`FjUgoq)>`jUv0}#> zg&^>fELd>`XgWOR5ALVp6Yb}dB7>Xuw`MfqvH3%S?C4~>6Wxrjl>1#Ap`DxXUrn4^2cE4>-E$n%q{n~+y=6c}j$2IK<>vJD-`>p%u2(be1;HG&Zmq1vE6Ojfyn zZR-ZgxjFao#SAKDZo8pQU_ar$qC_imCsvJj_2JDtDh15&Ut|k%LN!nJz+-NO@}hSMMrn20cR4;!Oq%OLP%u-@28} zZOY>u*x0*RbZ17%OpWjKai6XpkdztJ4eW#U=ABvWKM43{heN1dd1TL70Cb707;&0~ z7$mWRSAK4XodSw!27ll{zjpj_{0+CIFSq3fMi!R$w|EOXJpq*OD}A=nJSUxtbqUyF zubgkViQX%>50E)llNCDVQ+j?s?dt&v)J8=6*D~&y;>a6C<{vy9X&j2yu35ZXhrc)L z9`ui2{Yqc1bH>J0FQl#hUZ?-c)siOws>ufQTn9q^U;9?uVQtbr zb)}EPo!%~S{?y+)EJuy8Q{iQE39=GMK2Q@{6PcHuRbKLRUIHkjs<>A;F;>xuPN)1C z&x3>(sAD6f#*Dk82*>}(wrGwi7Ad72d-+GUwT0FAk!^L;E$O@!)m+jGl_+z~uq7W_ zkYAy(tL}NMx?-y^oE6gK$C)5+SDg~g8=~4FlrWbb(xe2xQB!D$4>3&$*?6M50-YC0 zAx)#HCp5<*Ge6}AE0{m^e4Y?8agI|eRMky5VNOM1xF)12j&I)Nz3NJqK?XD@SQa)c z!e57}x=AO@87pua7|y7=OUJ0*bHG{2hj*0e^S-{CfUB!l8w)J^R-iF3*c=+e2WzrX z7?$8n=u}mpq;!8PMo~U%DBiFd9}>oCW;x@Qs>;$6d_lxn!Mq@($(J)hrflCg=2OGA z6lumgW zq*v#gfj~^fVyI@P zl?ZELl=p~-#OqQIyvL|+Zw-g}${GSrl4c|(QdX-gD37~}HwZkTI_*yrJy z24H|MjR(?}c9u@!&JM{D`?J~ucYmV57+9p|kqw-kGAp*aH&@G(qZs#uxG_o0_{O&j zjUe*S;gK;91mdx5Ox@OwIKw|SYOq+uqfzc3+FZMMzJzzz@kK6H7od@kX{AE~;aDWW zRR>iIgJWh=>isc5= zbd-)#_Nb+GCLYImpdpc$usGlBOQ}B~A1Wk%a-4 z*P@n>t!ya8K zDlfD0vBn~^y*?B6)^{zd$u_lbqVV~QXJCr~hdogL)y(#aaqG)vigU|QK$p4q^agf{ z&5x%Ew7_Gk@>$0|2?+et&&bCu5hl4&p@K%pZ>^LJ({nvFoovwBy|c695W{&U8QCCb zt*dvB$OR0cP@<9a&-0&X{zK*@Q8lr zuI@)x|1OlpoLzM3G~c|doC2pto4-|1h-#Y0>T*cadcvF;<#SG%PZVALMU3ly)eRx! zT%{RMl=L(D>d{V(_Apj3PyaI8bWD7Okz_zQw8^mJoXT{e7pGNWuVBe!Sx8g$Z#!?% zD{_|Fi5@HFvRRwDmp%S_8`MqK2l&8r;@iu}QS|$VwknIiZJ@ZKcf}_v7f4yNA>TOE zX;*tZ2L?75@Gq#B(3^3m=c+nEl6~39>-GUBhLd>pN4RnK?ok6x?HKPq{0ngB;4#Gd zym!j!Qvz}{%ZF6e6d^gC09u$)7p?*V_ZKe*oNaK(x|pOg-N!~=UAUwl$qzn>wK{4q zE}iFy`jl1^$GYkvW?v_y*__)irm_bUJvIZgCzk>ue9x<^I0Lu;mfo<0eSGB`hm5u> zBd83$fy)(>qLe7=J7r&fV+y!#opx~@XsDw|p<%Ok&V3~LIhST2Z)Q?ws&`+K2>!Tr z)>}ID?gRF{W-_bovSJr_UmBYnB&iJLLC|}wDyxh%rOf1D*S(_cxDkcm#@!+8+$5-O zdccjLIl`N8pBWP9Vwu>~pdEzh-MLIulH4M48-fY@Qd{LJ#wDu1pF*$p1lKaf^e-^6 zH<0m>{vva!X7)Ea*O^l(lzVnD%U2A~9G|f?;F9T}oewL}N)}=H)wAsaNe*>I$8|r+ zwtyfImLaSsIc!ZC9#Vq%|%wvV2}) zc)+hxPzK56PdAQHoRm4#Zhbm*2{9gm-HQ6yf9@(#XEOhJ^Ut6 z+eOgMF*QNpsR~tx+h}@t9Rv;EtQXTg%&FErw$%roor6*$C2dpra-H?TP}3967|h0P zQ`nXp(J_V6Y)iSeb#HKKW$u9JTZ_?n)X$P=36y48?yuncO91b#I4e zRF!BW-~+fZR(2Kl!37e$>T4}aln@>a5Ta{b94f8VhUWfHXm(?y2SU`yto$ulHQJC0 z<@HZbOxE{Otwk@EJZ}s{YRGvVh8J@iq*wRV++~SN>OiA4lRpFNMYvA5*C23HLhaeW z){qckitMF%t8@1e{_jYY+pVJtsch%+8NG6D>^+zpvx6Xv?x4T~^z~Mmz0kTO8eRTe z&NHjYlHE{JIz(5!Kz(72>`l<*3%a|rR(`ozHRBz}n?&}kr+vy_6yEdgV6UD6O=?$b zJ7a3U+=KCPK2nUeeo%57No6_DycO}Du*Ud`4QDTf`rY3&P3vP;UA(Ln%n3(_nTm(- zoYy=|lLHc%c1dj(^#~+;kCjm76Dib@jQ=uuh%|S#7LL79iDc5cr692s;59qpHj9_b zwfR0;O}#AsqgC#6M$F}3S7C>mHt8ci_C>>^XdFC(7mFrk_fB$CPtwX6Dq7B)yd!FnR zyhQt2HB^^Xiz%0HW%;;lMC-tfy|cIFqscJ`hjf7ADvkLz1=%8|VCCKl5%-a22(`LitI;T{ODdEUWjEr7Id=CY_M0q%gdbGvR>6 zpu2^+;)a2r2SAQyo%lMIl>*fRw+AWr$n=(lB;IJWG&Veuu#fw&NT=I=suH_o!>o}> z$vQ@z4jD~_;ULuwAqDfV14Rjfw%u=pRLqLwLqt$HR=>mbMo7+E)_8gMlc2_TZ{4Hu z?rc>WR(@a7XwQZAw2~sr5@jes)cG197}+=Lq|Z0;m%G7;Zv1XU6vCflZH^k@ zWLpp6fd~XY)j&70S?$M2ADAphoS;gNy!1>^%|cqNAdCi3^?9 zEG-)|h5XS@BDKf{Ap}S6Xw;;KSq>YA2@y~%`;>El*x<3;`FHGrmZ?gRKA0TBXQF({ zp^~$&LjdY*W&qtibUp9B8OXvx^FkWWX{^l=Kcsw?w2!~MwJ!OvZUpP* zHvQfQx{>}QFAM2E?5E=Y()s11?ld5-;EFRleHKS;%rrRt-^*BEG8AKVsiiZYy?xcU z9~2DJc--3hSi*A4g;d%GgNuUoZKc0rHm)Tb_TI>$Gz*)VycARp>5B)1O=5aZ)MYMw zvG}9--`hPrk3Jwi5eTqO%7$z|Rws5&TkH=!oLVL{4$%KG88TVD9YUKX0~4ezne>8Q zvyr{~0;=6z(@Hv$m9SGX#-qQWooCm0ipR2jExx>Xy~kqogiEb%kLtVL_uhSw86VXJ z^g%XX3KW+`YU#k6UCcJvxDx0!kV(}M6G0tCSU=egAfJo$^qSlF%9gIuagz-Z&+fqE z00mtlz9Q$-yGG=E{-i0%tBD2PCa+?(QTzr0(8_MQGo%4flUgh%dd5Y49E2_cHbaNn zA!?P93KaRin(yk^sey1qgKP401JD*>Rl5*QSv9Xy79Ak^^^RS3TpP-VTYC(+T5#|i zQno)qM9M{5DxBLkY2c%tBW#kY(Nmye$J*bIwgloOe(9% zSwa_mdT6$K)^zbHWS+(epngT)<$S+T$kwP zNScHA^PUFGrY=qoa+x_TWJkyYa@J=PLh{dXdU7Sq8FD6^R8{Cz=G4Eu;;e11n88G~ z=D;+5FZ9-I40rj*!;{qt!)y)YoCz^|7IAg98H`=E-hGB4D{~7+J+1TIS5-GIaPJM< z>BEDY zfjP_uhs7FcUACO940SszXB))R-1i56(Uo+f=2Q{V7K8N2UK-XJzvG<`zZO`n5-AH> z|3Zns_BdBhvs+ys>O6I_GHfp_vkNeVy!fz}0OYt*@2U&dnzI*XOlXL(iq>#PI*zQp zxtF#q?Fo!xMoSb%rw2#}a@S{1FoKr(N}nc`tliY&%G5RW^R(5i#`!Ys){5FnGfv>e zl1}=>u{Rdf(`C30rG(l@=zEF9y48yfefav=(oEvpgVWiVTLCRb)IKj=X^^JG_0{BtqtMp^O^W`1>s!l5|YX+AGeLQx3ft5iMiDB zP66StQUA4cR1NOPu$^a?f^BL#6nm@2J(juCUdYm=ZnQ$yZB-z(aImp#G{HcD4)*VMOF?r$&gJbNaS2iJMNKhVOIiq7P~*0 zg(T3f0Z%ui66UT3=bv3=xxg6}sk(AbVK`K1B;YXOX04L>GBeu;<+7D7EN7ZCzmo#( zD36p7ZdD_x#O)S?LydiQ~3<##*R5G-PG%uKT4cmrT|2NeFGB#{_(!m5bQP6U%11B zFZvpmNxw;tA&F-zHg!U6_qljiXcuuCIg?=bVP|a|QpdmCW;y7nd=N=Evw;*v-1#Og zevQb~yHwR7gSHvZYcu6@Z?7d=2Av+fw0`HnI2ygl+Mam52-!*!PeI8^AC=zu3}@Pz zf|W1cc19CWlGozRo^gEAKl76KioQ(ck#PCRdh@ly({srlP=1ySTnm((ITxoKB%`5r zBQFn1gTSNvbCpkUP1{;S_X4x;n&C=Q_+w!utc@DuE(EYEuoCy;g3yd|ReyumLQeh)o2?Y#o_+H=^+kUO@!tawg<@aIi?Rw1X)@%l`dqWvestLF z02TAP=LLn~j-%tXi$^plHz3`p!?DhvU|lLxl`)Wz)2+ST#ywD8`lK&`HU?@tv7a|v zY!1+CJ?|I#l*vk5j_nC=BDtU*O}sXLyMkuC!?=#c3Y<5Mm4e3n?ecUoPiU$nZ<8Ii z{}g|~qUAU7>XgAsgoWZkQ60@z$|Yv){R|C$A#YO*kU9Zf+bcK;B;|1MXj8_idR<$J z7M4fx%$ETj-}Gp{E&&If_^3#7mKWQ!Jg1RfmWc6yP=SJW(@3b5f3nJ-!KEcV%H)Wy zzV~K&IlGgv^_R?k96$NHu1iwKxwCqh_$x*H!P~hB&=TX?Rzm? zwR|_!pth|706_2Dr!%ooySEYwF+)z8@RrUsU0TLZ-DJ58CnY4ji@13vp<%+;ZSav< zG;(w)HSKwKl&whFl1iDrr5q2m$YQo+Og$)4jAw5~pq_Qw zo#;s-(v#W^?LA7J4BW@6Yl?%+UJiuSUKAS$k=-c7KTbDgCV4jy+qsic@`bs+Z7jI0 zCZyEjyKu&nBgVt7Rvam5AZ_S;-*h2C%UL>f&s2ArIdAqg&85MM662SXtTRg&u4{y@ zgZ?nM5Y|>dOwFE(I@xq%GphWkz$i)(UL9`D9WC8M!(fSoyQ!0kQe)T_JX%B1g|?*H zy@UzshtPS%p>%TNbnaShj(-_BCR%W?j62CTz&`M%l+JbJ+}mSv#lyfytGk%R15wYU z*>C^0_qJwrw`4-DqJlXvrIrbaWkn&+Sx`PqN_yN0b1a+*OjTM!qAPAX3g*#rRZTd+ zEtAKWGYqbGYVo!44G{Iu{z6hod&~(zwb*LX1!d0lnFPG`xQh}_Qzb%qxR|dZxG{Ey zg_=?pYvb|TU74Ebcbh6(6L}45Ic%@_rKpAlG&U>XtoOM!YL~K-s@W9Ui7GBWe2Ln6 zpv(gqAV{*IVV29VJJ+R0RODrKmi%GPU-XgIn!;kohdT%cySo6MwnKs-GLqBy8`F)5 z19tBYosMB)r<#S%64!;-EF1h1UvAN4Q+o96YzHtY$)%jy@Ob*ANsGGXfzTnO3t<8H z57TR*^$?T9S0PkIMM0C+=@`ea@|Wx;mrpk!Wv4Kij=hz)1|+G!dBD^L6F7hKwGr1s z7Cg|fnCUUVo#R~6e}HDi85)!5FIu#i4V#kqsuKhCMPh}x)}d}7QgcWn&??`tf9=iC z1n7QwV+JOr3#xCo>sOI(wy}DN$q#JrL^MbPj3%mHTBaQi@KrvCU26uK zR+xr+T-IO3d03SLoMz&5J`p_z_U9}8hWK7H-GQ0Asccxunk(L4T7H%7&JxrRYcI;I z&y7LK!c10pKepjF&Hibq(_40YgN{(zNq8a|q*3$<+UZ9RIu_qouTg- zT{Tkezws8QUXkzJC;qSrSr8olc|++hDY+)yGFs8M=00HLDVEXRVOLQRi$?Rk{Ps{A zogCnty7IbL!^Dw`HGj@EO`WDnQX_9hiJ^GoR)dYqraM=6B4%xlvpRQ&x)IOUlmeIx) zuCZzwiNmbKoLz;p%BgvGpe?Htq8QWwZ8oI9*N8Oqe#K`i$~d4+RP-y@ZRoxWqO(zqz3Yj&|2yoKi>p2n5*VE6Q&>H{jf{bH@;Utye;T?rm zXIFK`JK{o!U+=vcuwUv%(#Qh_T=;O)-QygaQG^z?E2Kw0Ly^p2M9`>^*C)Qg zA;!f^X|i*G3=-6-j|ZyH%lH^wJ)0>`yegEv*~?=RsxGJDc|A9MngM@JI%=?nalKy3 z$xTwt3y*QZTZnato&%ckF8Q0GyO_ed(&|>XvQ`}n6Pfj4WoR#zR<0r|MGjA=&peZY zb6RJd0H>N|JvEOShvJ&~N;_u_*tlL6(-4Qo^?-(MoW2G5@!ZD7k+|j7s*%J2Vvcpl z$^9giK&Rh;uC^3Mj(ic|UVYuZN~q?H1CH2VWJafFQz;uQS6&+kdCN@WNPb-n_v9pS z4Tk8HjNB%LybhN2yDYN3kgaiPUgRynLu13GDhTuZbKRmE$-GR$?xoNaV+IwRz#63_ z52=qpbU-6&l4o7V!`|{&WZcFB74t}m&b%B5cV(G%hkQ_A5hWH!B|%ov2UkOI7Xnv|gd28jR*4EP+s# zbe^HS%F(4w3ddfDT$fyXfAwILg&jFh_gxM<6{*laV%_ombXrj)o_HX{yHAdunEGkM zo^h95Amlu}1(RwoomyO1tP?iQ8rDR5_hsK{Lu{t;I6>>|^mLQEx<|%$CnKAU9K|oi zLzi6z-a*F4sJ>tr+n|1)s-2979H*n_i=|;4vNBo^r$uI}4iMY4< zNS#d=teM;@U{wlcuX|dEThjLH7F21@&uKvDcPOl!huT3IRUsTd%U)W`ftD~c>RWdcQyTDCrGU{~tH484{Sig6SCU3wcT)2rz*$S}X( zGEMMizO2o`gyx~4jn&D9J<>~kn{9Vu@>vRwY1bKt#-Wqdt=Xs%GJeT8`XIS zD(5pj$1QG8gu{8`V}2}Bj1AC+*S}f=U_lDRH6i`Ow-FzAf%#GYh zFdL8$)>ml$H8Pp@qZDpOV~`cpu2HwbrJduF+@JjB9Sje9##=#^46 z0m%2nCP%Oo8G(5hfVZ`NtHqouNgP(jUl%mLrpOzJuhWoVc^~4w*W|6#!9nU{J%wTY z>qos_aF>O%IDWcx8ej0RR(KG}q4%B#??s>{%!u}MaKrl{NuCu=2zGfn|PUK)6)Fra;BtN@9Yb| z5|BYi)Bwg~mys&^Qww0WOi{I!`sNaBjQyq>XK2*^<^uow1Tc0Ua#iIpXKal-_-WdA z29V%Y4p#?6{$4ELm|R*g0(kf|S3v6S-)z+=Wb*c$BB3tBy;I;*v4Pr=Up+}%uRu8g65pHDarflnjGcgO zI6itd9yCkFhrwG#3iJ41aWNYePq>d)1IoMVuYsB&t|mbE(s>0;i+$*i!hn7^x*yOU zJ%vwa5{rgJtKJ%(&$O|r`z6A6wz5qh5lwC^Z7)wL}niD5}PXUqbTPYF@z~+5Q zK)Gl?WjZb9lU#fWI>n)y(jdeZn-MXooQ@rNx9XCuErB`rAbgMZ5NDp$$a$LNRW^r3 z=Hk>&xL5wcUccU8vw-sb#m2{#?6WVqHbXyIKN`cNxKut$n-%0p!J2PR@Aqt|@yv$h zCv?tLBr(~6p2(&}rN3Ha)Z~+*u^@+)Ac-rHJRcjj2&7Ap#$Wa2_qWwm zQ4@KaYkCI@lr-fUM4D0AMuULy_9lVSW5xoY(D?HdMDro#{Ehb%r zJJfOMY-r0t%ST-iJOs0{Q&#!Q^*z_}bC|3lr0UkQ=30^bYErfzOSlJ5k;HrMPtJWF zda1~*x4lpuC;%GDFRw*8qU1CVbR644JXhSR9pclAzLBOmRXX2ajMa8!@`zL^Ackf= z&iUo7P|5+5{JP<^3Pu8kKP@@Ck;k@IPsz}q-AF0!xI?Z9l!AUopd>ZM4P25gnD#2& zv`$}8VL|MJ3b6~L^I{m?P_pp;mZ2TUVen8u(Piv z^H-n#g!i6+&dAqnyc*n?`HO}N>eN|5MHMU7)(IF;_cFx+UF6-?SCX(0Yanr;8@@<| z22^S)eGJ*(`uf_)%UdXZIcs|a&9Abiijr@Nhe*}y;|Z&%fGk2JmjIl zp}cLGW1pL18h>N>y`%9Z`(m@Jr72y;RECeZ^7kz40u2_ab&%}T|}mS z=DlQHR}VR0kYvf{VePiy$ZzQ}ylxznDo{wmQ5KoQVhnr5$aLWAb{owN8@cW&UjDKyDIR5MoCSQMJ zPpiqUkfuxRR%mY;r$KKk_ojdGK;$co$?1)bI0k9n9{Ii7mi?_+t*`}Jx~4^Teha!2 zl9!ClI;OTadcAm&qE#EUl8_GNlKOK&HTvi9a$~P#F+72E->}}1m&V@rUI4!a_&i{O z^#vx0E_AHNG@V4=4M{K7!|2%SS)r$VNiVW0*n=Zwv6I)vT^6ub^;6e88=NV4)Y$W{{}&0zt$WH77Yqgx80R_Qv6aK2nr049L+pbQ zc_r1BL}~B*LO$c>aH%JbfOKN112gcQhQLeV)p`@?1Z+wOK{%k~J_Vn}9O{aS*@))f zL*x-KJY>H6d}kq|%vgSyw2Y9M5UOfvsxYg@IayF%g&=0 z@1tv?Ud_KdvrzQ-`#LA{|5)B|sqc{DD$Jfcm+7y~{KuC5v8zpTi66!F$#x(zwuIV665y9DeFlHA|Y_gJ+OBOyaFKv5S%1se>BCf(N;UOPA zKWYvryr}QYrkbGql5XMqnG&_S#?_Nc1lNS5u^dkB;9TU3%ACyVie4m=UI#NCpQ0+j zm7rM-tKG@|^Lu?N%8omhuHo0E*T+g6Dq*eT?!UwvkQ?jktO~Jn{R9uXTp6Q5sfm(SPkx zx*Atz79ly^_j@HA|CUH-Uar;IkKsNwnm>5rSr-VhlKU@kPIboJ>?&vt)PaqCxJ{H&B<+xT|O zwy`;Qxus_~3ENO{!gmTN>z@bSh6THn0-C-+XcJKQ&T4vLSHuN=0x~0IJ^`(N?rsK8 z@CNw`I`p5*f!nKBAod1wkH(dGeQTETkd+EeaxgN|;#B!U>(Rn2^q?Ue0?d{cG|TEG znt_E#Z($d>M?P?KuFcXw56r>jPfyjbLJNOXnb{FJPh@J{+yD~hqgDlNF^&CtqexSZ z8!XiaT-@*C=KgU||2(t-J|JV>822+2{`c?P3@jUoSP!}=9RO5OkkTYpJ38l6Gk7ah zMUY}xZHuyn6-ITy;AMz~1;S|69&g-nf^gDSwiMPpCD#x(u0~Z0{r4lh@LaiuDIe0+pJc70z}7G@2tgxzkrRmk z-4C|R&O5<02EO!u2pYI`-4L4$9nfTd7ECCN1Dc3fwMI~}G|hLoWP=NrHIY!elVWXR zG|q>J&w0~WQX}9ULuj3OlR;)?gt}SzeN$A>cw!Cy>;Hu%%pk>j)FY_ZWBzS*$^o%g z{~1W6zMK!|VcJBd(IKCmU%x$NAEpF@dK1ZUl3`AS?D}32P={Zl zI>24k`MUzo#)_#uhDp%4kv-t=pUHZ&^4`_G3LvdF8}jkJ?n z-R?ZZyI$$$_{V~pv?u8#$VNdO8uXOM@hpRBzDU(XzWE#QL;TblZ>^R0zASyis?<}v z3S?r208N_L`Ex-l!R$=KOhZs_D(zE>vFMpfRmK7@;XOf2$bWVvZezZOkeJ)BusUyS z(HbBAk4SGOsY}dq=Z*~i1}m1SWBzs|+`HhEw#)icEoT%*uJ45it8t+E{LsGuW@0fy z_qT{X3FWMuJl}eWnGTv zzar!B_{bc-d=ha!SaPB&-gNO_k%T1BbGI%E-Fk`tHt@umx}QLM;Sm(KCS~-W@VOuI z5u-i!r-^Xp7p$WsC~UFys8Gl%nt(K-tGjX>(n$@m95QsDc8KpCIajytA7yp+e}CMk zjhPXCpfxADL4K(zda;-o{pc>RT~lkl^%GP^$xrlhNYEg?zI!Z`_l~gQ*%0=_KFC`F z67zCG0Nn_pj`t(ofNp)(^ahI~eg6CJ2@b0A)``aRMG==DB9Z@&10Za$OXD-HM1B0B zg|RL71s=8Y|4O2oG@Xfque-jR6^^>y?j3x8xr(KjEvks= z;u{1_IOt@lW@d_kIn2vtUT29cx;`l6 z&$BbzMw#%}|4^701QFDalWd@;*-YKv>ju+9P$PX&`D9_8;;_)!VqfP%jQYwkx;^2# z#Jr8cA5-pR~bUR zOj-(rXZPXs>eA~={poVxpcNc0j~3bFk`!5wri$M#+q54hF|3%`J^BI49EBDKO^TVic@{(LsSYQNvVHB1z5 zHQS`(Rq9GVm=0t9cdqd|1KF23e+FI=A$7?sQ4QUXf~Pj<3r>8!=|=P6mX{$FIIjne*z0GbpdLY{KM<&S@ALAt}k*gw?*@0iz`cD<9!$d z3S^g$;62&eCApYMFj*pf49r;CzOUu?KIokp0kf<1paj?1qEb5`BB%SD5+ok~eBhN1 z|C4VN#U3pF8dvC>rjOOWox~2a{h3Yw{%Z%k2bnc@LY;rlA}=(Y@?QmMxThYz8{>vT z;HkV68*gF>o!jD%htd<2dSN7OqLmS0bdT>}3Jebd1`=Pv#QzN*1qHxe%vMy?5`3h|%W0(OP4 z;PWy9S~-StnOFSD>EE)uy%TlJKhoWy#UKW*pUZx#6erZb8R(v6H4e;#k{dL@{;fyF zaZT{H{RE90^Ti~+y_L~Hj8(>(Mk7B6YDi6pa8*O;r##z#hl*b(spMBUx!K+BK9a#~ z{GV_#6%E44aYT~jd3lyIjM>BfH!A#io%E#)uo$&0Ary_xH7`SINHX)oLv4qYQuf*M`Y2ptk$HHKn|$iidv%5#7OTB5HgE zI?ebES8q7eDq6p980@;Ner8Cmp8HOeS?z7 zndq8l+HwEY9%z;2H&VVhz@=eJ^V!>;p!0%Fr5}vL@F|7f62rjpI&JJ$zHwgsC$Rbh zib*{nw)NmzRuZrd6Ivdk!Tb03KoHdzBhFyIM?uK&vFGXhOfD2K5K_ytb8y}$+TtgZu!;U=k}J@H_bGw)%>Fw zoj=2gq?c6&+o_(PjJ}42b!G5u`g0B_8U#<)_7iL<{jEU24G+CM@#6|O*Mlj2xt29Y zg$a3-%B#IK-%(I}>*cCdh|rHs9QTs+IOV?P2o9X=uX+5mRFVw6SpuTRaD;?CD#&QT zH1@AY@%I-@jJVXY*Pnkf{QplaSXl8yE}!9Ux?&b1StV;ogFe@U{0pxbd9>%j*=7m% zLt~}+!0TCGmmGivg#zuT18=~0o%Hdyrz*wC?kx2eJU2e70QyU@x*5R5m{T@1dRtv= z?Y?om0sp<`kz#lbI!`vGpucjSe4;+_*yr-e*sbW%9oo>@e2NdUn#VcLc4{Pst6lK` zp||$hDkl#~+P7`|7|tWe_?l*I4ouW~vc_v?P(vWRx=CvMYZ zG{kPvBUr<)KFmPtQ%}tV@eGWFSd{_dN;lW-85@A@%l+wWrH;$+!%5(Vzk)HD=nD4) z>%~{ygVz0x5fY7|G0SNY9Kxjce$oSPgloEDmRstPXRw7eaXe?j}-yY?%|zk z?KT+M?=42n|w_GFx$5()BYMxFi1~q-+fbO<^bFphdPAz<`WlCBq!GJYqk!Sc+*t#lwDIF!E)9s%4G*S3 z;2UWC1O#0r?18|s`Q%>P9-uI_sSiw9?@6(&109ySWfPLBEAFQ9PQ;GL(ftAFB@nNq zf}uD#(c3rx|<&XgpA0WeEDz;&P zN0u5kNi55m!6pNgH~y0#*A=SW7^ejruvTY%#|aT+5}z`>Egk179qZT(sKBG(Mdn)# zKeoJ8=XY+)Hvp}#7h^d6inbCJ{b>8{AKP&Tk}vq=Ri6IFADe;X&6y0gtitlyFAhWC zJU?$X*zM0Z+~~A|Cq+VP*pEKmdy_BvWHh?vPDLTHVL#U3T{?OSptFzPE*wydcEs>8 zv%CX>ngecyzV5uxf zO}cva1GgWbyL*Ka!2Gac&?A7HQfvVine$*eKX@Nla@GUZs$KWgy!{;37X*0twJ)GV-=0oH~s&IGsw zM4xT^E-I&8ROZg#!S1iuDB>8NtL5BQeC*5qI}Sy&!h)@$#RFIDE6>(LA|Qai!u3j7 zN69O%ecvMj#SL4W)DPw2>E)M~C8;wW>rqY$e>{yuTVk@@^2wG1OEq9S z7$;!t^2&%#@3VpuELhY>kXmbWGfgiJF#x|?xTh+OjqMV3Try^1+PJ0%GOhqCKqo!r zqpb`Wgj0XolO%8!H4iUbSEI&dY>a=g4ss+=M z5yRa~t86yW&^-TcuL5C*(xbX&a0u=PdYUNm`!VQ7{7D1ZRvOd(0p;0k@uL9M-*Q8* zW8eMf-goF$=Sh0R$RmA&dk9f{%m!EOhmd=7uca~;ZbCiwhK$0#jcI@^_B!MdSBYkx_aRQNVGtCsQ+t?+VR(S%+V68Rcg`1>83b)LrM|CCX%dYs3t#LJf{*3CWs^$AB?0s&)Sbm=!an(<^#5 zp1;5Dl9=qcP}5MQNHaFc&vPl?-Jlv^;xV$6EUEw9DiPi&)u<<47U;*H1m z3N1NqitU^ES?h{zHZzZ-*HO(7b|^WKS$N6kNP?O~cO30{atcZ!(og5L4ReC|oX0jf zT0a&XUTZzi+xssdE2jY9yPTF|yOS5p?7MI$52k}M&&I_5Bz;y``Q)@HK|!NHSZCMT zDGryu@u{%E=G=8Kn>W8f-#x0Y1G6kjXx~2yDt1}?!Aol|`01M#WBh|HwoIljsuKQs zE*J3|Y5a5ivIL;@E-0L%Q-L!T{u$Bp0qAP5D(|gaVJSpl7lu$>xTY%aceCj!bPW(@ ztiU<>We#XVn!&RbtBNPU{;dzZa2;*zg<@t6&qO$VYkrN7L0Ru4w1@|E<2n-g)SF!P zigD5|0l`ws1DOT8gGq8h!M#~}Rh96IBetW3*8G7s;Onc6$16nQuDgn_NRxDTlrNBd za)QhBeNkbHZNkA{A)b*6x7{eW5Q@uZbRkT(;5MDBql3(0V&~bd;>DikVeDtIj>~E} z01dGoq#2#><1RyKNVf?Vi~b4;25TbhECyx}AhNvAeeWSuq$q zMiC$WP1kwu!bS}dLx70GJTyOVy3U^z`5+USlO*UiUg`)c4!3Dy&IG2rUBMd$-yr%N z>V>zQwM(CyPr0=xNJ_F?srR>A0gWUwItI?n*5l?`pctSOz9M+0e)9%59qAKT{Mv@J zN#mA2d#ix`pmj5hty$o4E{bHCYGG7LR`dHJ` z$V`DA=5X87>HO2>r&RtZTrE&df%k0xkj{7U4|X=OkJxN^y)jyI5{bNyN6foVE#u|b_5e%Cl1LCrJc`)l9{S0(hon}RP<(bQuN>K@O$ zHlp!ylOD%4*!K|-%?cOCuVw;20Z@y9Km9<0-V&EE`|30uSDkCpmcRR?6+NXm@OV+G z$YxS^_LfO2wGsje%7sXZ?2kcjy1c0p5yHa!{IaYLuP@!@(A`@d*P=apxVsWZMP|Q} zM3+3d!m&zS;Bsv>iFfZ`v8mw>h)oS@M(s9?luok4WPC@D!HR(_>=*DyfN>Q`hyCxgEG30M;--zg7TIkFf@q6aGv6sN3~y!UCT!*MN(8N{6~Tt$&$CvUQapN<+5%=@ z5h>&4;BTm%F}(tOKTOgkCpgdHgDK+o1259lv$+A*oG)9a6|#bXZjQ>0P*83MbiTXA zmdz+kzG)W*Jb9&QgSzhm9X9#of!!8xw<2QQ@)0Igf@!nQdecfy?6KN{aAL8N4iHXk zR!aHzT>!LJi4htag}kYv@p*c?|7@vHDS zzXyy>L{@!G4*t#`fY&5JfG;9Rmxzg*VdRw_hVmUfDqYSDoee(KAsa)q%~&k@R7}_H zgYUc_?P=oHW?yV*`+MyJSn#aHue6=defawfg^T01`uI(2Ogz}?R`_F8ttd}ZG7U-7|(DA9Q5n-V?hM)GX(R3iu)=FY~q*MVEkgB@sI>+ zgd~$T4Ds?SXcfrE&;W5uVj!)|1?^+oWS+i(=_Ca3078KYZUA|Go$}ipU-ASu%j9@ z8)tLUJDcHLIZ~=`GeC|`xi{%ib;cWL=XtvCJ|u#jNz$#xch&}>Fx)H?RWl84cA*6K zaC{sB!eF@qi~jSNT7-|U;G=Dvz?CC?6On*bMS&7H2q%V6%|P;P`15@OHl>RBC63Dj zEL#^Jtq3YZGX*V0fHK^q82?28Pt+n?fgl1!>%OVd&8Op zO6FIn0vzBF29R-Xrj9~V@sPp=Um>hneK1RhY9qNSNk=V9Tca;sU6~HtQGjorXhTT( zn*6eWywNSIAzm)apo=_k*bPP$GF$E~SX3qC+aCj&aWsM!k(QFZOu5?a@5OI*>lyT; z0Ps~_uSHIzD$(N9m8tC)iY8prG3t>w14zqwaE%~M)K_lM1zNqO@creIum~t3fD{Y1 zG66vBw_BA!2q{AvRJ_oYkZ}HrQOaBH&V`P+=jL#$>+O()WA`>Z3UK?X3ah> zGH_Ry+%gU*q~*7N4D*)=)sGOOk3da!b-*81ZLoUhXm1&?Y^ifpX!m{t-8$_F(CLvq zc+EO5nbA-Kbyx$~vkx)iOk>HxB{OFT;OZ;Kpw`{lFv$n|)h-u|N)E{!6luuu-81xf zFACXAh>6%t>6}^K1|tdbVA}Qi`<1%u3?-oqvy%X6Qk{GRTjAA z@VC@q(U}P09|xq)O?Q?0ggixbL~R?z$kO}SC6B*!rAThk%xkiYmOw293fz!-5IZNL z`eO7BtFS(24N^1DRH?hzZnoYDH@*-A93%)|3FW+hytM<8yyY|~@#(uknwIsbDI;n` zetfk@P@Yf)t{d?ha1Nkzc>R{O@lNnr15v@#+^q~Dh5Ni%wYw}x6g>8y%pD>ObcQ1C z?kkp>5m$?1hhHA+hLK1^Icv<#{Yr-GigEEN&eJ3q*Mj;hqkF(Wq2Mt#{}=4_l#z<# zQ8==WO97<=^bG(&k*_hI4iK=BW5OD*k@p*Q#*&@K28V#mc@HJDi$9(&x||)2pqU}@ zX`;yN=Y6&?*A{&d>+_vOxF8A-O#zh{pLw!&dy3fdmF@ncf++a_3Q)LdI{+3WRz{Vx#>BAnUv3C-&)=jPX6+MIJh6DDit}L zZ-@R$GV>WhUYiJRWkhVuqO{`Y#RD=Cu(5Jyhj8QbC`R7zLpjN65BO0#mt`hiQLzy| zSOEW~0`zTvvDE^MUn-b@sQcp*5!1Ds{<+Kx5qcoHgBp30QnsNjErG1NZSZ*AH zVfe;q=y#$|@%Dk3thYqYnZPG_^HOMY0z-6qUuP6 zom(?sKBRF+yMQyqsatP4oLe?V*SzH^40CXy=|Sub7Dh9S!3iCs?rq^XQUw@UH`9O< zGJC&;>R2j9^u-UPR^j7S1G*=(4gP{3y}w_^x7jIKq1ze_pky}YU7=~zydU(iga%Me zn4500cO5-Ww-O2#kVnR|SX3z>svgf<(o&6iBd##)Z!Fu>OKxrel)xst{mfZt?dA8c zj2j!5Bu#iH%c>{C+WL=u^E-C^DK1t^vy*J(Y3TAu+j0+FJ2(%-$R~TR!scRTGg@v} zJR8hL1}M5%Z898>!33NKFwFf6e3@;vSxdCI1gL6x53720EJ4@^$ z14WcFQGq3h_FMm~+@v-@;dXDM|B^$z2YxJ)=*qP4gOl*QtQ|eQGU07m9EB$VwXM7P zt@~~FA1(3vD9^$xVU~=4HQbsbJcaZQomf&X;?nuL94OK>LOaRcb9p_SF9Ly@IKZ-h z_ZYAY`%7oB0$=>R3$6#m>6<^U;OQEN)a-9;;#`@}G1ryS8<^kIysi*!9^h)A)5XO- z>K^b20T;oQ+qRF_O;cmRBc?t^eDst0+SuGBZhKcti8QzSkv}yecI2@X6 z3*-1=ep`wlJq?SWI-&fMoH8PAs)ds%qfSORmixh|!!}>ONfr6Pf#R}9p_BCUv!ibgM2 z>Z69LO}PfS!f3XPoxl3=5?T*orKt?+X3`k^u`wzpZo)}CquLUXnv$jKz5){R16b-% zKBY|3ss&igA?3Zdv-lY`0P_v*`D+-XfYX3Lto0x>Cyl~S=`ffm1%reb%POEnk$D94 z3Vp|V;3`&*gBv!$HGxQTn6cK|dkAi#GOO_NG|c0;E?7b?JeHe$RP!23PcAK%FtgF$ zMRgq5gMSilqKRy2x(j2gC7`TsbMs>4#HKoc&~K@{H7k81Y%vsRIbFxTs10}@?Jhl< z=>E-`Lq6?jZk_z2p0GHCu)1ZG8x+lG)z~Cp9P3TD@nDtpRDIOH<>DG8a<<57_{PIh znDy-Vcy=8!14G1+OWga#F8bZmGQGzZ(*=hd1+{tQf5qNEUL4>G*yGKoOAU9=40w4I zSoy`c6A#7#ln-+%qPw7?z~A0+rBMzr{UZ=gBkfQ>zB>xPbpvurfMK}kcrV8JH{5Kd z$DzxWB5MpzRIP|Zm*dqPG47O56BI3g6L1P2O4K+oT*~yN=hgT0WRWSbsea502^JoK z)W8ylIJ>8b8ey^0+eP{{_!~ewL45rA1a}oopeLB!l!R~SM=5pCc0SULGy*Q(_>xn1 zT=bI;<=*bA)Rk(;25Q3SE>r;~;L&wSWOc3pible5NtMra_lJ*QHx7RpEDlq@mj7un zI#TLrS&OErcc+j%#=ru@AbZ;(3H0DmkWPoSH55|0<0?)?2bM+w{rD7fChnp79LYj0z))I4ft!YSUVvSW%g&PKIO59o)A}P&X0c^#Cb`Qz zBuKZPCt|9;Fc4G`uW=F90^|UkvD}A*vbES%vhG#@nK=+vXgTv?p}8CYOmy$DK(Y%d zLC#s?d3Zi!Q~)wMaJkJE>64Rf*d0PIut( zpsAtyA!_93MmOH*zIh{sL1`=Df*G?=^aEHhulRAKq zeZzYwx_Jz|+-iM@Umd80?!cm6EcJ2t@*G;1hLy!IFzzp6;-I&Hwzg# zWgI$7bx?CIxSO4Srsguq;sg+X*XGy162_`kH(9G*1X(OZ`F-+(J~yLt`l;uF%I5Dv z9{NkuFA;9VzrE6#qgz|n@Vz^kYKw5bk-t;8&Z6Ve*qC%0T&W`J6-X@C&Tz*&vJlG-Aj15j#=K1%Y&D zZ^Q;6RMpzllkc31wO*#QbdKw{$i81{U;Hv{wy7lf|Ynr-QJy79;z zsdK#my>X$O${Hdb-mql7r11~reVbEs?(Nxm6$^%|(6(6Ttpa8lnYsK2)P1uw;=Lh?6{liE+zl|`(8;` z6EmBFav^`oyuZB%xodZ=~3_Xi+hlg>#^DH}>)(pPb_U2RgsM&!5^To?Cxozm;sX?50saauy;&IV2B4%=EEdsEL|-`?8xmp0Gzj) zpxQ&6d5u1|)inNc%+6mhe#O5>+Q)ytyEIn0esMl&if9`1mJRCK^9mlW7x1&4q2#u# zrGv8gP9%nKI$d+xYyQ!#O6~ZOS+(~eI!TCMJs-2}4P&4LezFr>A z`(&wx*!Pmx%_Is47;|b3Kx{@@BmL;boUm?I;xaJ?fjNkgpP=oTd1^;BQw>0+R2xGN zKY_Ld1dFi35HHHaugxRwL=32QNG!5I)iOUb=>dAKO6$Bxl}#YstrtIHrU>mgeFUG8 zGcg5N7>mz9H?YzCTxQ;sKKFFV9ZgB15MmqlF!L`5qVq9E=NY`J#REQkowp`udZK|6 z6yvlg6$x%j(~G~|{DalW_va5j3Ml7bV!@gvjcKdVg^;>&mWYcxj_?qJ%#pcfa z&ai*!(wZ6ZD#O3QxRXQay`B$v-4qRVcnOiwCstdolD_%;djhUD8w2=KojgzMH}B@j z2FRe*#Wxhc#RG}YiOsfBMqSz0a6GisLy)eojlW8fx__nhm~gqmLd$RNPE{wh7j8`c zRWag<_Ylv!JPqdOR3mTgq^-#8qTlYdykU!*h!{*OkoEBjuU5jwl3n#N-FTwZrX&kb zK?q+%VN1VY=$VMXKNE6W-_Rj7rWSD3cHb~^(>=%Wju$y>;&SBHt6b&a84(aT4*2= zUs#T^7jY0W2$($_5tx!LSPj~Sg+*gqSPNx}pU*gaB=}GgtL#Qy+fn24srAg(gVG#2 zLvbXRYF&#%Q4ZZ=+=__0JD&LpnAy@i1>&JqKZNrnwWf^f)psHiJ1e8=687R(z<9pq zm2$|!0T_+wtX;kCDi@ihqIQV0azPa3 zwq8rUkpS*2%5uol+9Y4cxwHDmZBB%j| zqe*Jfp9et?H&(7t*NDp))mLMgN#a#G^2|1rLZ||$S_by}!ir`qqIr zGiEZ;{N&39=H12SLWOSQ+v#yhErR@iX-WR*%)>~5p7NEPU@nZ3GRABeBF%u7n{owG z75YaK#y2#7DwTQProds>sW+Y`8UK?_5bvBK{!C3`oQzkawa9{Yu2&(Cde?T%bftHi?;bZhO4UhDamR$D=L`6G66-0a*w?Kgh1^e&?6A$?E&rz4q zI#0BHPUq$jZ}}y2r~8#RS)k-)zcPTRV3Ysp$&u?5tyX@O{ZPK@j#%>#l8SEyS~|*J zcmQ6Q!@XMw&ZSkTxJ9(#0V4{U!oD~Gw}u1)daYE`Q*fd9Ia+_43(C5YLj%3htqznW z)3+>BecN%Qg(WPVZ8tv^U}V# zVMEHp`{5_1-m}6UVA4?epe2HN>$R|p^~CzGoeW{rzqGa~(9WmvJ0q~0;o2*S4z2Bf z3hPgyW?LrVFI5hIX=8bCRoG;8XCxIQ_x+@z!kzwf^*xJCjxH-E-YOZn(XiJiNTMhF ze1Mh=!OKWJU9Y1^i>?=uRkHBl0$OXEpicqS`IuM5W3tANh|$U4h)ADYlZ3j}y%-Ke zB36O9pVs60&lZ*aTOefyg0>Shz-a1YYH@Z_vKgshGQz1>VRJ<2 z;xV{LT2VszrTtF7x}`b2`*!yL!c-K7m1$lYbX@F_Qy`ji_+w{FW*mMgx07()wHi!{ zJ>Bqv_8N#io;?PIk`hmgrGvPqEg0Fe-YjvB0AvaGFFveLv|5xcfWOHlU<$NNo`%%Y z1tEfWZo!8+uPY}=h_lego#6>U-e8f5rj;hBDKtX|zs3zu4ivfUty%}&0JT{RuCUNK ziK75!_$*vpeP6V6^K=wi@|E5%a_)wL(z1=&Cm1DHf$J&22imTswI_(p+`a(j$u3~u zjsX=_z5j*w9Z)Vv0$7)ST<7uv=70Rw-EQ++%K-Z^2|78x%4!8jT?^sO_Pv?bTIH&D%5`!#hS4P~EwNB4A7Y>e+u@_=0)-~N4M6T1B>KVTbvXS3@eI(^UE^fF)7D8V!|-xU9zE9T?fOL9S4bpFW7CA*#tX34T#Q zL|O~mmvRI1{*W4JPBNx)pXnyI-LFbpBSbrOG~4q#Y1+6>Jv2lFRL| z41#mzKlh_xSiPKL&5f*dD@pg*s=<*XDFhz^J7O8wJfE~8$eBzEI;O^~Im6O;nva1* zMQJLT&f>IO)(IFIhs^JROAs-SSi-OYS&jZ8lN}%E(@?z~ZvfU=Nqevgew~G|DN>#N+TBU`qsh)!G zeD$^Hq*rV3vsz1lwkfN|8r=dqIJNy%2l_w`s;Mb|5p5MmYQ(hzOzpy%D!^>&@}YwFw;~qV%Ev3%I%t(V5!A zW2CuiEhz|^<@=6`)g^;>g~wX0P@GLlpDjtyaRTNu@RXfO^9~vY(~V^-OQ(Eq-uRaA zQE@Ngm=#`I2-zP1;%{GLan)$*H=3+SsKE8nNzbOvAPU`89OZ==4)m{LpNXR%CJ)>eT*XshN^PU)T*|KMy@ucBR zh*b~``g+jSP4oKwTGlsl&GU}9W$}QKzIEZ3AciiHT9_(%DaQ#}_ce`(WVp5E7Hd@e z{PspU0yR|xhN3j-mgGQ5Bv^%gzdE9%OOT@2}(R)>bsYIR-4F?#`3!A=fs9t z)07^%psy6(!c|7EIlkT15}OHNKF?svyHJK$Oh+ZdAviC>%SHjqWARG7#M6a(PpO=L z0#(ewltD&Hr|>LUrWMw6xk>sVchgn69L)WNc0Q8ndC+v^j#*m(WUKR&w%{$$M?UCG z*meRvZL6YVDVWDo zTbp;mI}r-tKN69!ht0JRMgP(2n?H2d2p5bX-hl zFn{*j++bhl+dQ*BZ9l+;$t<9sm@|T;Mr)sMb^$$n)dKpuh-a|q5a^HA>)Cxh6ToE; zB8!&(2?i*V8jPqE-pa5+KX{8GbsuY#{N98V8DOweDDyaiz{d=G#uZrVuq=VQez~N( zS&#i04ebO%6`QXD9TiLCx&+^GU4q2PW=b30y4)S({nxF`}2LCKc4H?b=}u}={U~W@4eSvd+oJeuh+V5V>Y+9 z66clTmg)WYzb^s@^}Q@qbEyZNq$zxG1W#Od8MTG!9rQc>f&kgi>5UP8G5Jk9tfG7J4Z7pMl* zv8jV?b$RTQvia_%hMOdZy_ImOefk8SqeA-O`wvR!RS+k5`b5Bac9`k3?`Shs4}Ny? zpt{fDqicX@Ax0@G?z~*@e5@@ni1Cyiw>4!(lHMn~VlQ1g&YMqX7bBDUpoOenpjs><(hTW*u9a8S5V`zYfvXLaaAdA zGsZ;|8ucm$Mn(*ob634YB{Tsb+{EIX#n3c;f(NQiH_r(WtvTkGCk&6EvsN7A31<{VI!v z>)S(|;bV)nFEtFqYn=c~n2K6Oc|DGW5OQB>TRiuz>@(c>C4;AOT63)!siaGbP2A|s zsH2bKmq>T@fRskxV}8?pjC}e&T+x_`=Qd$6Lmrh+U)#oiR*n&D=Fkv=xo9AjI>uGwlT@k(R@ZsTXDb@!YLZe-n| zKzOwsOa5jJx&k7h;E`J`nb!h=31-T9k$Z57;uQT|^n8-dmk)5xq&Rsl;)U%*R0quR zSe0W_ot0ywy>x}7P5C_s-Ui{W0><)a?K6{xPgfs~WVdtyu*HhYBXKIFrxVa8X^P+( z8b5kz2qd`xwmVC>eQ^Uy)KQZC#9o1}d2A;g8C@qap06*Y1uE7NOQX$i4;WMg5nc&4 zlFY3oI5&@;d83t_Y^6*F z^JZw|^I9zq$fdbX3K~VKZJOM8&8DT%LRQp^Oo1Z1lAToQ_!b@&=3gpP?fW2$E&wy~ zIixF4t60~^gsRX4HjA8Q+X!4^Z;6bHNbGvdpQ@G?HMv_d1Q2X9aql&;92em5WPGYp zy>BpY{4t3;p8w4NX;%xt0t;7tGLV_I=Y%VtfnMf9!Ofy-#~7f%uN z++{)BuFTm-UhO{Y-HImT&pc<|r~X5<;q4tbBlR_&bDn>Xu3xt5-oO7lR2-ygBAtBj zw@l&PZSXR6+(-Pj`2v_PyXyxP!kbk(kryyn1XkGQ^jL!^Y;JYeRBG#OL}p%U4NHYb z@RG<0fZN6lJ$-EA=UV0&B}sox3stCj+%PVelqN5wU8FLpo+n5f=LlKb!Hpi9V8 zRu-gy_wb2#K}l5l=r<@xaB&IorSGi}yXk+KD_5O9QMH4~;6bEiPIDqHxB7ts@Mo9H zu^EB{4NZ_3;sD@QWX8I2<_B|4IxakE-cgOT8EBNW>jjzX6RF@b!LU;;G&MMgoV(__ zZr;W0h=Ba_l|GO=ch)>FkVXa-;qwZ%EA!(CNbN5QPM1%sU$}b@pyXPJ3|&1{RkAIN zj%0{_%_z%qbe{iel2S^gXZfPyz|kql%J?H}poef&7je!sC7qLb?G_EExPDtiHhbbjw#&H0M^;8x1M^y|?h z$IuR(_Q~L(Cne{%jLqjP_Tf<(WlsdKirfLDNFZl&s4E}I%P?_5#^hEB$+`BE5KtZE z!XsGYvl8^`MmmjFOS)@3SQOPqMygGdx;_*s4xoS-k}n%>z-# zOcHF)SH2gtXhmtDvhq%#@v2?z$6Hl7WI+DuEfk)a7!QZQk!P4q$Z>xs=V5eJa*#Ed zjnAlJA_A&g7S6JJVm4?9S+Ymv>2gkdCWZ+iMfeIP(TVAb&{d zyg3=uxH9M%%0ZzWC*hXG@6E?qC%t2|a!&%&mn?@M2dYm3K=A3)-#mjkdXE6c+1Q)v3R z)dv81gN!qrI!I{ML_IlmSFs%wFkX~OpZyiy?c2@jB z5(J8Of5)c9UnQLMeR4G=7C&U?&a{nui}pzgWa04+VM)7aYtWoHTV_Como?`|MaciX z+`@JOpvrW!YoY6iWnhCLbh%|M=dT_Hp^G9#4dAN!n%dJAl+ML9hpgA4?u5181UX~f zMg`+$kX5}I7G^^CS@}f9$E3k#)&nwPz&oYk(tPsN`xwQuk%azhi80^yHhDAWzW^}L znM>_&zxWlOL*P(dZGOGJbX;6G;m+?cR9e8gbBW64_TF?rtwPy0LFRy?crNia=@-nJI zlu}>q!Rd&h#d=I_A;1vXO-^Ldg;m?HUPx3t{eA;*_w;J>7kZ~QJxG-t7>eeha4+4U zX4AM5$Jl_ejyJi~%22#ZZRkfFhhs0~gfj<^4l6y-YjG-Yu(H+Jo3_?3A(Hq@qF^gj z^?=mXdqz%2Ih=Ai$X5MUNXz|_h ?{>Y?^m`Ut3_Ud*XH@^NqD`~SmlJiT|a3hma zw5XIWKiq=y0?2OKQ&PP%FX-JB)52yz6^=BND)mrukBueeUFP%AOpYTTpB6O&c6j0Z zM{tdg`-hIt_*H_eqIQ-=n;HkX&u2k}3^1Z|r}QovA{dTrvByQv&c>LAo<&77X=L|D z?#9~UCS1(6P=$<7d3cMmcTQI*O5DkHC%l zrJulA|GH9J^b89*>E2^#+I=0pw@>(hS3j1PYHX0fIoA9rMD6+clYx)XcqP!+@lMz? zkWpLWI$zoafQ0NxZ3Cx^ZY64-n}zEkx@!;b&N_TNeb}UqSNo~mpvF_pAm2SQ_9Xe> zS{hG=J2GrpO~!m`6Ta+Az(SN$IrR1s3euEoTvceED1-wpG4$k~%9JTQ3OuXMf=k%l zIaSM$BUXK^;NspJaM-jbPzx;vsQxrDgcpg9Gg`jp?$`q~?;QRZNspp1?$N8@IMs?H z+iUDsbLRBxvlZ{yE>YmI6tNAZn?u}^j)W^n>x8VF0?_;pK-hNjbF8aTVK?5~n6M0H z>GJAkRf;km*bn$afjDWa{cSPjJVp@i14`4sTy}wyr#gbGQ#-i`dj8Ga=P6 za51|&>K}O^DSB%ba4}vCE0H3b342T_Gawy^4_~e!+;llR2&t$5Gu!u5?HT@S=3i^>dI`nQHGC_iB(rF}z!J!W@SUoVX}J_`v`gDZMRf#yUpgesbj z{g81qr+m0XVgBBS(Ruh$XqNevg#N=bVeh99g$>Z2YpluwY0}W7t-I%gBt$_#>nnhq z0u~{+Js#?KG;a!;SD7xIbgPRzdic1R5Ug)N(?(qt`yn z#&Do+rKqMPmY=HuGD$XQklj{eu&%3szE<{{uHdcr2v+As9RK{1(4J5KEvoDEV-KnR z=j)J{=c1Eno?>y+c%in^4!pp7ijrR`i{ZNZi`m6WxaBvI)w8aCc=jqLzA$S1y~X$g zD`{(3q3r1*(3XEidujjYqKgjNw_Lcz+6rO|90S%IbRAgXpM%i!5 zu!t9nM=nr3B(vN01u{#3u*Q$MVDw$EZu%4;tRJW=$0D(hlp4gz4~j7{?1zy$Xa^w2 zH0jecvxz<(eg%84t4RE$3ZLuZq}0gDoEVS=(jKCdUT7D#T3I&~dw6h(Ef+=mo5MAS z-F=G1ruf4uh2)mwIy^(RGom&>-SwM8sF#+AQLB#-IDE(=??H=H3EPlV+j4WFlc##= z58yN+srHk{;4EwUm=Es0_Nq^<=`q>rJnIay=8y(!W|M)XOn5k{I2& ziar4;_tX{yb`zGqSHKkS74{mXTYm7sxjFpH(tIHiCpv&)aR!T%r?#JjB;kHU$Z0%r8hzq^P>Xe{WlglDD z=u&vbVp{%{N-NF4Z-8fua!ncns@b^@I&geE)N}jATSW98&$)zA9qVhs_udB}DieC7HSW8J%Nb7AqCtm+* zH9Uv+hr*3VWatSM{G{n+X)|br0O0-d`p9`RmFUGXr3hWQ9X*ds@1C2srM%nXa~mMH zHW>%aZ_(e4g);6UV6Dd9W$bAL%|*n=jld z3$G;lZ2-9@m|irIrc*3oVxv*f0(ed{N6=ZqIhjQ#NhTQ^Zt{+W)4P?P)A@`Ob7<&y zEP$l&{OITE!P>b_VDas?{{kTg=2#Py?&jXOE=`9D`WNkaEB$Gg5u|2zqsvm7mOnXy zMo8iVLi=xn>ZCVkK+;`{n3#10uLN}in(ICF@t)*wbnsrcB)Wbl9G6U(DgA($2HV9p z;+WaeV&Z-R6vnFOv z_Na%4m1E6`O$%>;c((Brb81TnsD)l5HG318#zd>8*_fAvpR&ZjsJs6a9KV|4CASK6 zZj$>R171II*P9zw&E0u}#5;L8%VVue32~Zkw`H01frBM@d@7`=3YX#`zyx$>X@st2 zsz?F{UudG$E%m69zD z(P1XD>xtNWm?@kSI+EYuqWkev&?pF~7rb+Rm*w;QJ?KHMAK zN^-anAV{Z5>asrEKuCj}GR_Z9x*4q-7wDJYLYP8OYhMERPzqlP@EbLaGVT%g`1kv; z$Ub^!$4Z714K02(1Icaj11c@NbQc%QMw(XnBxR%FB+W7E$Qlg3&NRHx$Al-oHrtqO zn-`Fb?t-Sj2}{0@xp;~+Xu6u77t8-s*Rq;Z8-c$rR;71apkEtbHE7n)lI24}RPho(G4)o$_(&Xn6 zmVjxoYGwQ{@x zlYsM+Zayza{D#)0)EdDXWQj_z87LWxS__QfhQ*C`TVB)N=D;x{6=o2Lxi`Gy8S zCAD;c;P&8$m}reR$!l+GTa$I9d1++@w(b8aKMg(wUYmrbmrYBEOc$>t(LlBYUl+4i zfh3D0l8|3M3)t_qt4Dh(S5>@~{3nj{mpyJJulgV^B(uot>#3H`uI%LfPvf_hhaf=2 zr#k60Qza;Mn|*DbyobDppA~{m`jE~bz~Lh)4Q}MZa)qeecC+9K$NoDcCErJ*x@&WH zfY^Ha35GN}Eft(cHCBm9JHuYA=9{0?l_#K9s4cnoon>Aw1euoesTvZKSlkzv zatV(xA1n(gvmh%~TovByv=X{iuFz_ z11=C9gv}ew1u|*qs#H>sQSc?Mevrzz@b(cxh#o!Uv<}Q06W4R=pvok^)IN@9ankTm z9ROU}v>ki!cVg5<30`u%l|mBS0b|gi?|SwJLn1HWl^=l`U8ujoaQ&kfJxpZ9ppSat zV?GE!Xk`+W5T<^pn(jf_%mFu`XYVfZ`XZ%<9jVQ=AWtmN4qwEjLM_0h!R~EbUM)?f zf9n;52K|}@N&6c2vZl_p;=SP4LiIht)_lDW8BhNqI0W{vg=k7Rk#U5fA4*5)QBKKR z2^PcNOG-7Pqdw&yg}`4TwZ`~}C>Sc_FB~If-Y5IelB_ok(AkGxOF5d}=Aw;mzmj8z z0R#DX^Ny~2ota?nJ?FfVk}?x>^fQ%I>xqqE7G{AlE5`dHtpIc^0$84 z3A#b5XyZu6cT$q`w&x~&dDV0H==rRI86`VKi;|sAdI%1kPAx~0*`F^@)7xc7orRR4 zc%!GG>gNsaH(w7FNciKXq)i*p3d1de+voC_pngpv8Uyf+`eCZH~B0?xRT2%Q4U9M_m?EgDo2YmhJ`C-DA*up z{B~6Awl}w-za|rbOVf8?OMwPMOTjx-L%S#V@~Q9|N}uVQclLQeoDy*sB$u+UPA&oQB{1w14+Wj$~<36Qq+ClLh+$WUKajFZrEh3rm%Ly&0h zB`-f-$ryW0e{RJ`+|$H*j31qVC%ikM1N1Zkp#1`8i2{+>XWONhKE^3_{W_O{B4+N5&r@89EwKaO&9he$8LZq|m~(c7AK{45vE$C)ve^o-#o zKcPD2r1CF#HX;%XJD8uFl&g^9HpDV=6rA&)#Ol?@OS2EiMEm&D>mTu7mR#({odR4T zYnpa~7+T@6WK`erSmv`Dp+0jbK9}Z?2qk4NLc4(eG+?H)8_KvHU`)d8r&#L-Hg^N3 zP{P;gKH^v33My=^v$7km%;H~e>wsFq`6~7q(wA3NnvuY3QFmO_AJ7zX1;#G?6T8pe2&IlZz4(17=)rlgl%zvGT<}FJL<2Jxo+86I6(<(6=m!!m;xl zr5PHoM3=ebu`MRVfEv@WLmuciTEJHCg%ac*Xb3?Gx{LDkd^hwuZw@zcQVv=OT_d_o zkptK6fIJF2szLYE!Y49OMynvs;i&I=8F0>CQ=9ai`cN;28gY$~R@pmfx;}&5v^o^p zqR~38=H=-yX0lgdrOOSg)^CAh+9!0mXtl?H^vJcEM>*MK5;+(row-1}e)0qQLE}ir z5`8Yu1?o%>EYE0F?SQEJ6Jm~UM(Zz)%3AlVQQPfqt%T-)2be;0=PtV*8~}#G4GupP z%*w%YH99Rh6Ku^#ba!9pCOU%hV=IK?oZVt)AB99aQ!|@zZw%#_>C75IUr_TYCY9T+ zfc6nEOMHN^247eR4&!E$8x|>@f5n`g&whyr(T&*3+iz#@wNaD42YJ3kvJv{6(0!TD z-ZwW;6CW);s|>8Qe7qVSo#VGN*+MA-zw25^t)eE~MBVMHc5jyhlp*Qz^i4VT-hHVL zu*Z+AmPGOGVvR2(H){RDoO5v_jv(PuG52MP2t@*%T^i{ZXDIps2rkK(>YG$bg?*wh z1c(PJwB>amUsdafQbd}xaBGR8BTk#8C!)RrRV6ejwUTXd6ZXE;_@L62Od%94;v`~H z-blic&iwABh`-lF-Vg(Zv0kCLg@Ku04L>C3x{@@n?5zw5BOhj;$ySLk z9!+z87O3O)&CvIYBFO=#=wZ3wy72-~NazLiZK20m+A^qN>X5cIK7$IBMw42cj0(kD z3(zpYo_WrGMZIs<^)2vW(5?g>@KBihO8!Xt#G1_C;k)DJo&sN?+v>ZX|S{7rh8 zI)zRiN%r`xe?7-e8ZFH`y^Bw$e*HEd$%n6TBNetj0m(cE`IA<0OP*9+5%++sB~{$| zS-#37o1~#6ZziM$0CxmirOSi3ULv1Qepdf*z5uVX*0D+5gdy zBLdDIxhVJM^NX)wAz%lmYRY6; zRzHq&8D<%2T7g`I?!B=kj<)&z1Dg0^ULQ`vEAqI-k+aL)chp@xv!{V1pJ?{Mi4t#P zNOI$}Ngpu{w_>zTF$1SLj@6w|#~qpOXXpt6!N7h^BBKuhDMR*jw8>qm*La<(LWYwk z6-AMY^}Dbg>t(0+U#72&-1Duz{0kD4A#s@?UX936L41Sny&afj5w!07$(SC&bB1T6To@Hio=8|py=CPBO{+^9u`_+I_F$fyNL|6x15cctW&2*N9fr48$SL7hv=6IM)QKP!jP39~7XLDKJ z%8$r$nM%~F>vGkFERrUS0Xv@6OD4l&P!DMKrk{#FFt@%jQLt zl(4(!(Ij-Ui}`#YJ54MDTL4toV7k{|R(rLfhtj+LeO3j`P;uaCUVZN>a|M^<$;U{q z%=?wGu1;k2%{O*&O`A03BppCLBFI$g0y_ZEK-o=i;(2<@0TU2P#cjpn>0 zD=zWwx{Z%8V_5W|xa+5Cq|rqy*%JE(G_oAVTYa8>if4?(5}F5GE`E^X6fyki72ITbf{AxkwdO|Z9)G9RB;imRNu()^&=cpcuM$q?L zhrYb$L?d77Me2YpWOqqX!qF9Jcw9H% zndvO|HRmY+1Kxr#PPzM3MTQ39qd|!1IGG;$#sj62dv~40iuno0kv-vUM^R|K2b3nq z%$gLXcz4+_LN~Uv2i8IE&a4DlL>LF>>QK70631Nzjds^Fxeq81b=+h9I5$`MNtE%>evCXk-v_8#^_Bk8Ba29T_3?5XuU_I!4xazWGj~-5m^E7Hx6AB z@+OlKdVSMS@>0z#o~#y7DP%A(6+4zdA3y&_LveSeOlHs@|l-jVzy{&v;aZa5t+@tEtx#a7Tj^3g3H_wGW+ zltyVorgXOfZ>w} z8Z;(=sStY5&J48g!kABV7K#s<2Bm3aGEZncE3GmE9kOh4)~j&3m@?CXG>j%uUxdgD z-P^UkE}+MA;iGM|-PL8|>b}Yl<&3wYS}z{)T0N3@dG@Vq%t$LMqyoOVBJu7RVUU$Z zV?xYhr7Hf};RY6F2l7{8?=GS_^9J?Tt8(0`3r@aNyK90U8OXl}uR4o29ZIH0UaH+x zxsqd8;L_{1gVF6ZSdOck@ac*GgCe|=oBJIin&N87xsse}`rGNly{tk)T~TT7XJU8l z{4EsPK`4vV1@875=^sQN!9;&jqFcSWZ&Pdks=^MPJL;9xl{UM4MQ!=`x7~q1`A)kJ zLCWtnc5lCc3W1x=E4Opk9KlIY!5$~Fx?`kBhwSVNdrds|p;?nxUZSs>Lv28cWNN|m z);k~?^eHD^S1=~>0?9EJXft7slgLEvrN4RhefK&ya2ADq^L0GQGg7bQeH544rTl5J z`oqyqHueTj&HWG9aH%)RzS~D5aylv_f-;9E6~pjOFj?QpXZPOtT0uj;*{g%;0uBIi zm0ahvkVCaa(r4<{x$hS}dO`^9Zf95VZwGfu5Zpx;JvmAb3<3mvSjvz{r{f2=Hfb}1 zIVVar9Xi4*U{x!hfK_oS`5=3m=@<^j zr{G9X0k~N-RfdB1ow_N@P?PV#_jO_1Y1bK~LwM=?3n)Yl@XR$c%%MY= zhm??q7sfqm@IK0OULwMxOsEau0cquMFA1~AdP%4(ZEc>+pXH^3rr&!;P8R1bS|iK& zuAo)#0x1;C0uNfSp7n^|x!iXpvsV0W$V3l4MQ%_#Iz)o`mgc<-+MHgx_fhGmnHKOq zh>meu#3qA+74&IvYxRK~?GeCvCHn41$g9?~zYO{5nQj19BhXmo7jdRdsqBd4*u!oW z54$tc)}wJN&c72LE4;P}@DwvuSD9S+O6_~$ld(Vl;%g*b;-Fu#gF#yOkv!lWzr;RIK z`F6b78e(rM;7Ns0zd(}a<+t{{&|Ca5XxKlISP%w338n|zadE28&dk_Lo7INN(0fwUP7Y>ny`qfG^3e{u}KxcytR&7#LJ zar-MvzMR-n-G*uI2Jo07`<21=oIALKt~dj09Ll<5*X>a1bu@q=i54A6@X4zY=-k3;vC1R%xqZnV6i(XCFN zmcm|U@M2P$Ilr?cUKYD}hW0H1AvK+V&(2+^&uh@d1Zd)2-*u{7cNZIl0IT%lfDnp3 zw|2893CrH|kEh(lk5k0tcm7t5zh{VX(7CH;e=ugBfeuT4m_7rE7~PqeIb>8PLU zSg>j8TiJM1x4fVo=mI&MaAo)D`%l+{7ig|nOFO++&_0j!#j7nUUYGFr(Q!4A_@T?U zyx_S;2+f7p_8njT+8brrJHgQDH8OW+@6_m=Jn8KnKYHb2uHz8hyUr}|=q}MiVH*RZ zo}uOU%I>y#5C$I4Uwcf4gU3(wso8&iBhsZYyWi)owt`ah=3ko!dpbLtWx4WfepJ$t zg>?STE4+tsN^rjEIIRpnmwL?bb-J?qXxx%w-;U2fP0$$iE;U&1lbVcpEa~=*3{UyS z)Fqq-9N>w0I5h-ne{v)@pE#%Stq%B!=Z=M|icZnS+QiKd z*Q#36p5^K}A5WcceVvOd!23(P@M%Ie`RVdcK@}X<+AFNJK%5xdU|@8VYR|9LYw{AF?WexdkC~&CX_p?TZ`Xbym#by zId5V|62Y7Gp2hl`5}%AW0F}p$;EtO+ND{>fya*_h1@#&M_oIpV;s#FF(uW&WP?~v@<(}NEncHrwAY2zJ z(9ZjAxO3T**T6mF5zl32JaNpd|pIeFA9Kys^nGBymqb>it|ci)Na(Xf1m_&5T=j{~$i8%y=VfaY6JFrS^yrLOH{*aA9tp9Ed+eYe2)PyzN6*qF=AU0#dnF7mB#{9)gyej1fK{UI;uZY$`z zsj3Q{&AW5~gyD2L*S_5dhcxO9B}>{7pB)%?LSQP05A2_CJaq}saw~-%Q+@lAlUwbt zgeztq+O)2tgq%e;x!1)n7-&QPcbH+hgWwj6E$L`UF`XzdfrJ}gJ<9ek$*wHE5t5YM zbz<{PKSzSrc!UiVPb@1o$jmuv+|H=k_F_)%=XzT&QC1iREp_5ErgYH8-9K818GfrBJjZgN@>0(3tSqY*2{Li7l!#%>e zFn=$2r1LC|okct2Xo9rGukX-(3Vz_hnI#FFGD=4aRaJ7OJe$V#yagLoK3(1>`Y$S~ zs%~kMH@BAUi!)|^S#Rv}B+=H!1FHVQ)mF13jMV`SWI%T+ObEdl7n^%&7EXT$*H((` z-A)lEf_~2*|KOdaAMO*6kO+Cce?lVU^Ox^4T74YX^*a^-9#Eb&p6N8TN+WaqZbws9 z)#l?=U$N=%As1}B^ASV#`EJOgc%K?m>}HN^j;5a4dZS7%Z$7`O(pI03puN~shtI8@ z22)Nympk_0#~6Ma(49jB%eGyHY<A9r2;KOLp-^)SsI1ww*7g1+R51u|;#n^!v1=tS%gE9Xrez2*n3js!qyf?n&#s zv6&ZUf0z{*5mv=6eqzC3S+L0A;fkO{AM?*8WP0i8b40(6CMR>ZUzb|+ zP*t7NBJf?C*AThGPq6+xIoadOZ0358lH|(Rvnw>Nx3-o{BL>{Hy`}caO`FI8JAXiG zH*OymGBfD2qJBC5z_POr{*~})?eMp1<^w;M>iab5ri#=zukgCikaaFfxQ-|V-8 zFzMNw%ul<2afJW*Y48f|EzdO^nSfB6-9Nrto(&9%_Tq(K2JN{6W4&|ky6{V~@5cAX z4}*`8n!x)?Gpr>~;{RjVSVugngM9(nkw3ozdE*V7(UEVQ*|NV4`wt)McR;rot8&2b z;m_agCITzl^*Qvn!7yEs65oF|75C@N{QQGo-&lWq=L)_v&2HSE&&SKK6aT%VzD441 ze^C!ckbhi(i{i)3{P_pWBh(ij-cWhE!#^e);{*P|M_S;}Z-YV6s3_m09Q%KIVASkc ztUIRD_pRs8VF#U(lID-qh-Uxs703_Q568!T`*2?2w_*P@wI5#u{&Jp}AF?C+ng7y%H~&CI6U}M;c5GOQtB{|+G&pcUgpUP z%*DIFkN;bKn+eSwA4_()Y3DEBD~&VmTv3_Q_4WPjm_JvO;9LIq2o(AM>Jc>mKYWDI zNG6Tnruet?&-Qf}Bfpb;mBl_=>9=2Ag2K)v7BlUicj9T{q-)caUr7F=i2B-~UF zVB=|y?~;@S#!hEtS$cT63dt6|BYupYws&u3#4lNUM_PU1pJd3}+AC@*K+8 zyEy@x%6N_v@rHS#L&4h%V`-Hr^T zL)O4!#x>)-rNQWGPBI~K2mV?YtKBbECjcd<0sUx)E*yZG8%ZOKWPm$)+16mW# z>Ukjjq5h__d<@7t8Cda!_DpNiFCZ?|YBpXTvT+Sr(6@0d_|!@?8?lAu6xsC>lYKkB zye9VyC|<1IoIbFy@wpQJFuBB5a!k4XT4@(9H!*3<*41}dUbpIKgnO!Hkk`+2(x)ntG`a#8x!Wvyc}p4dD12n{tH zl=HF+JGECAqaqX4JmJPKBgm&VZbyI3w;BJ< zU+lm<0W#JTi~tw%RuqMBd~!1B{e3FHlg+h-)_B~xI_1q^${9@7NcWTFC_X3Bmg`C_ zJpH!>Zp*dB_C?sA$~0$Ov_aJ{^Zuw+#}`Tr8@D{7!{OLtoI3H~-nQvrnhHNTr*)J6 z2nTlJ1R&N$SzCSam)#7WOX>+&*Ln3ev<-xXcThgJ%oGWE7Zg#2uX`&|8#f*4)k%=nz4YNA96`gz}%KG-W$qfG| zDI5&rAhJ1)wG)4_GsMOZfMdOz-^z-to+1tbY_|IT!TXsXL^;M;_ffJ)F`exWI{Lvl zy=2U+x+Ic2!b~_kXJD^``09&R0(W{GJCx!NdZ%$ZxnFTFpEri^SQ8LOBg3|i7GRSp zO5AUmoxpHek!-rmZ67j#Oj7uYoDR#@uz$=|81Ok2sMe)7w@BC?$Bq7q`_PCyrTs>i zn@r1510c@L%6G@Qd}9ZNLl>9*>z#(_Qbmi_I2M&RS0v)%4j>)^9U-Ip!|6)7xbYei z_FRC+1xsgmVB@zv4K=5Ar}KhvOYTvL5X9ay$MvUxf-1)aLa^ka`yIYKDx{V?){3+mH5_ErSjK~38h4?4+b^flO^t;WqlH-Dd(SA`W z7I~{0+a$sL=(9+}pvyMMd}U&x!$_NUVBDKhvwK!6ky34w*L0@Rxrnm<;Frv8qUHt6$VOXNji%W4lQYy2u7V(GAWY+L^aCYv=Q21--i3>`zsM{gvw0n&hHpXV zWi~gzM)w4)Si9>??Mx@`V-Fykpj^M%#hJla;ub~s3S{T#U6f>Rv-pDxlFvi&KbIhe zJw{k1abf$3ji@$9VjUN5Q}L66u4|7Iyw5AetTg4v-rD>DI}AJQF>xLtV)ED{cts+4 zBmL1`tAjz8H3}ZWTs>{KsoX!Fy|_Q+wM6jRA&at?F6N(C|76EGrZzp%gf-l-PAU7g zHvCSU`*lY2s93j`Pk({axKSdGx~)5Cn?(M7sb()qiFY(&X{nJpnmyB9@?PmMxx`|; zmN2p*E_H)wl|_2_#Q5h2R>Gb17W-IS>tMj z(PFVDAN^$O2Ax8VGOO_u(jGmEhTQhIdiNI(Z0+y({38hJ!sxEshok9(z%D zG*|G|u0Odxxg0V6jwNJS3fbF9e71};BHDB1*^Ev+-A@D&Mjlf^TJr98)(?Z(@_xI4 z-%N?$xOrkQDaKE^i{!@eh_XsC#US6Ule@2ZDDv{YOSt2>l4KYWykBDIW&)PW43Xbf z5!ZGdKb~;gQC#NgULRSdF_!!3U75}!rumBH7gvWY14b4OOWBfRdywfsQ5qNMSkB$v z!-LpH8R|>D;Eeqn8@JfJ?7ISgbgZui?v8xWiGNw-5y4;eY}@Hm5We;h-N29fzE$9p z{i(nLg1*Xc9)G_K>Mk6L=XjNTktr+1+dC1?(rRXqjEBM_-u`ZzppV$^Sb+b@ILNsx zk120?3=%2qTH_K=ebBZ8foGC>0?u9c>Z#2$4>7v!%^U!GBEZY!2=W4&wcfFq9?L){ zb5Kf`2}dxi*0sa(O58O|i>su6@>W6SPFM41Xux?AoNuCI-TG8C+kd|RyS`a89NUS* zLYeW%VsOl%Z&}RFjKwS-LQ7`eo7mq%%d6EajWNYi25yqCrt7b7Pd_`(x3~`;7$dwN zkB1z6LU=64KMMZx%6eQNA?hWyU}jzjqB^g z$5^)ijo1-8L|wEkcXPgb#_bt80Ec&iZWIwRW*j-6ur<7YV{4~Wc1Io9+Cdrk|BE>%Ub)~J z30A{F{Vx{0xVN-QX!|x~g5NF~vw>5K`tHB*P_jf2D#|%LvG}>~5PQ2LFC`ws7Lm9a z^6KFPFH~n8H&YDSff1njH{U&oA4Rt9T{{04D_+<}VIYNvB2oJnE54>nERMUa2qjAS z-|w>HZSND9Au{ICm1(PK9Rs5W#N!@FG%<_MvSVvP<6jDXxz1z1 z&O!al7MF@YikVL+&h!)bN0w+eF&yXw&7Y9nkMc4#Wq{v;&DDG#gy`I;+RzXc&F_+ zhJ)t6UvTvz)$$v#VRW7Tjc=<~zfiO-J`*JU-#<8g8S6efh#xHQ%#EX$@;hEj)U~(1 z+iT3YNVmeAu~0Ba8tf`MJ90DhWpqTbHwL+^V$!NHEOBxfQ@=>38J(=igQs@b8v5fNo1OzHRvj%F?UTB4m?7~Ar{F7M69qFy<}WvRibs=E z_S$tq)^A19nB_|LpAJPi49)-GU{Wu%D<^(NgeaP|L-u39E{_ zr>j$p8#Yc|E1l}li{jOEIgk5GM0x9i&cuB@KhA&dw7M_kZX)Oc`ltc`rrh)LEjY9V*sVdO`T-(WM(;M;U*rN z-*=JW9Y+_i1_)N3W%Vc$Tyx$$i1YpkcU101v$Yz~gaxSrC zJ0slC#qShA>!>hz&zp8=TStEC+e`{N;@-+kUKMF>^L(~G>gbZJs_F*RHjWO8YY=!v z-^`~+Svm{P3Po2|c&zG+ERa466)IfspMD`!{9^K9tzFtGxATGsF<(lb!-7Tgt+w2o z6uH?|ArEHZ3SOWtw5$VqXgn!N0|i&d@woGc6Q&b|3Qc;7kt9*zewd4s3FlnP!i!f2 z=GVM@S2VSh*B{z_Xi1HWw#+CXI5n7lss?pB)x+w<1s=u+5m|bNN<8m3v%rL%mn<&g;1m&3-BCi6*UGS^PT} zbaIM9XKo2lIo233%w#SM?OF9}&K5;q*&uHm#jOh5SQ|bisVTEZD^0c=0zx2L?Tk+QSD`P|^T+=`7tQSXK z=HyV>n1B0zA$bf$(VDA^4h#m~H=u2@jARI&hb>`H_VV_)V4L{`?bTkIa0TwXC$4iT zIvwU0IuR{R-?C?*fxA)-T{VkZ#>NECiVTE4&s=>hx%}7`G+EP!i=8vIIhw18wI{vy z6y|*E1Mk;mPQtjcI7na{B08G1CpYijOX&C<89n!AF~DT4xhdVToFi;);wg`ti3oI5 zKjSue19HwCHBTK{L7cF9+M+bF<}2 zO!uJPS=bK@ZlbzEZ(q7D#$4mkilav{$XRx{_w7;OOG$4a!y{+0bbBKqj4nu2po_8R z=w7cTv5yI_AZ&+Lp|uM`4Es^HqqD=_>|TWBYJC^y9K6u%vDU05pz{J+r`NU?Lo3JQ zW*$#TgQuh>&sb0wPr$lNo=>GmX^<6om2;mU1))zb43ms~7kb**b-O^tN=RW&z9 zi2Lm0eN&EaSs2bqfCQwa>hW=_^)HnYP0&$2@3?x#`>c)+{gsVm{q9TEI^kn#Pr?4l^LRMpHn|up%|EkhW%ENQgYo!y*B;zegdyt#kuM5Vpn!GGCZr66sxYD^^wpA(aJxQx$*}yE@oJ0t{#qx z+PnsD-D5W$G%wr|Y190WpgW!g(-rrs$6#u0?5L{hn(3)E&gL3@4`Po63z-^pMPp~s zCB{*$ajS^6PtPP&M`f`0ouqWtY1W%mPX&wTfX}^Pt807q5rH?%6N7^t z)9aCjTp0(My>%VAT5XGQ;gEa`YIh#IKps`FPEFtiM^=&6K6=z`9jOuKi(p`eDMC6A zZ(>0xw`Oo9vkNU2!b_50x9qOA;=#F?lUrypD1!9&4Q@|0TWPa=V=?HU-sp*2Qk~M_ zw$KqwZ_VWBlr90iatbr+@$Xjrl4sDkjB&se<`j$0e$AdZVUX;>GI^B*nt88A`nfhL2|b`ZEBxr8+kDFavT-5A zP_I(8a^vJ@-FUUZLhEC( zg^X*VjmmB&c>`A5TpS|2O%iC=MIQ0&sr+T@?v`}7ffH}wBr7t{?Z_EuI6jdz*`^cX z(QtR5c)e#Le5J_2txtesBzHa5%41~Iw>j?mDsgoqnMlT`@rjHw7Mj872=N;{${tm9 z;awsluWhGXK5#8`*_7Q{S^V^L!lJ)1ePeWHZ~9t~WZ9Bh8%%To1|&@C>R$K*5B6CIoCYFM+nxpfUs#v^=+?+kf$^WgKz zjp9G1xqJU9opZ zepuqw*~z{hg01m>gn4VpbYiN&Fu7{0W7%)FszXDLNr!-2C^@%(oC?T)Xq4Ev{=+i1 zjJ(CuUN}tJFSV~&c=5X*Nx+pXIr%O2$MQCi^OVR1OuhpyjLyYmmZEaZghM`g?;WPz z#54)BH}Ix?mbt9epIEfaY(yRuOnKtBrY*p8L_EMewZV|d_fyGr=kxoGou14t_aDR^ zjxC_;t=R4(=dc*9l)bmU9sFSvo@^LqOpjTIfFyoub7^wFa8s9&q~JN#eJ$30H+yo= z(2U98Jyy_fx~-$~zUcR8avd3aR94ma`EbZd;D%cYKY3-irVe-Db}m(XBQCw&dy?Qi zXK)|sEK529Wlw0{Z5ClvyXu zY-#2iVo`z%gU;Vmt`x;jx*ZnP@2M#zOS`EKZ=lhL9k=~gq+LEaiRJinTe({Q5!R9%Ck*d%XvKozc3+daB^& zWM}Y%f4dA^m>+Xs{1YhW>K{aAf}Dr+ETgYERGS9lhwbe_jOXTZ&&%(E!nQ7jevj5c zvU~4e%OIB&i^&KfZ|D82nWJ zU(JP86San#iN1y1`EAw6MJ0s(K}vp6ZQh^e3S`FeDlHGA(8H5Ycg6P)xTQ8w`2@q2 zJ&^V0P_B0rV!x>7dwU0DMDri59+i6Vuj?u=AF;R!j7LU2oO?nYD8j@>mqr&MUIT|P zP@z65vAtKk8Eq>Pt|TU_rFdWLmvP#S3z(owHRhzF9;vP>JzEPx3N{w&-Q%}5oIgA^ zg!e>S4i((%S|BF5#em?L=;Q18Zy_4%^Ni{$N5Sz)?|vM-X9MCDa^LqAS;8POMB`N? zD&ue$b7X`E2OY{ABxJtN1JMa6_Y`pW*&Oa|D5k+IH^Il3oFL+qwlvXDXVaS|o7The ztZYP}5!oxtm}}jib^2;>#$>Xue){9{h1MXoI?sJPe#jQ_Jv37(ws!MJLu|KWlmF?W z(#!mYajF`>G}^!2y|~4m_x1!O>xq+)2PY_KU!9C{^KN*g-ZKQ{hy2T!3{<7^ow%Ej%WU}>*m{eSt0QR3heEM={Lr;VGP+k`*=eY5 zHGO!Hb0LW-$F9x+TKnOem)R#VIK*lpvJi3ue~`-TYx(fS@A}mWf#zSPRRo?6%Y|Ls z`>FMV2}uep2gRIYOt*X#Y3!@lTRx~Oad28fz<=(X>Kfe$BV593`Ce=eqVJNU__F(| zCCDW1W8dX`+iy&o_E3F#h9QKU-X)cQ81V<)&-PF^&Q0|6SJlJ--{IL&&-s$Ab{)zn zSoaYrH~=NZa58(#>xifO;=pilwq)8UY4!vkx{S#M@wP-Qq`s?a1ti^Jj@Bz$8U*}# z%f|g$VRVh_A@qX>=4HP25oG9eUKtIvt9?H}lbh>pX}7I05tae{y!@TPC30wX`!u%4 z{U~luJS^2~{X+}O>vbEZT%s~7b0U%w82Jll9*eb%|v~TFqdd6H`*7Ps@Qm2dY|3C zD`ByR8C{BZ0U7t&ARK735LV=GqWSUQU>VK*mk+q3JYRWUCzGC`~(7vs{6W~wLyO3n6|D_W^@@i ze6X=2Su$U++y;bmP8Vbo|FJb#PrMeQwmO$1)WLe~pIhe7E1w1+#VPz1%&o@9JL#K} z$*a~tmU)*>iI|`!e3?n9j>FZ-f+(NMs2kHO()&4uAN?TyZ+5;13pD2Jq;KcKZRca9 z{@xkq9_c7Bm>xX8bM+`MkR{GNzLoCIUV?Jyz0=YfK_R6Yf$-BYzr##x6w13!3#hC! zfF$%Og8fD149VRA`iFy@X$@7`((?vkT@PRvl(c4x-A5J$)|_nG#WJqDdtnt@baIbA z*Ey==?8-vjyW+cT5ql%{U>khdY%vRiXgl;9UFCdR5JrQM?ci=!!+5Q1DOpIQ1f5tJ zoX}bzHy%wWQexfp;vLF3AgL!^lZ7mvgX{B8_dl^t;$3Kx(mhN$e?G}`J{ z26c6L*cx(W+_#S~tLaI$OSvK_!geMGGTyzFOW?fg_A}^L&2JU~9EWq|wq;(Ww-Mu! z=Qi2E&~Hk+=cwVx#=lHg)NjGvag+o4`tZgq`5|r6qFunDC+rI`c02av>2OV0$U&%X zZg&Th6G#WXiT`L-OxG){?P)wb7xrE9;CFh8TZ=ZWPc!vF!o#=2bbQ)rEnasv#krxe zNRY>?=H4Ayv&3R~ok0F1^X4ITs$3=Qzz>8TxN9`xKnqXtmzGEC~u(LUQ*TLu&sn>326~2SI$;a)H=f|7ZO^;D^MW8!#M@iT~H*<2PPcLro;FS22HMK3=;UoV3D< zp<7q(x0V*TU-{$|Gk0WuR@a9*>E#US>ZAQQo9X6&#>Mo;SF9p`IiZ7YfsjYz;?9gs zjxSX9S3)|EI`TsKuEfTqQZzrNb|2-1z9DAdR-Rp=43@XezP>Dag@bTW>XRF6X?f4v z@kyBEi~QQzgATgh7hT>32L$cGg>#7YOK(9eJ&MM2_!Uq4l1;g$@8Ir?AiaMnBNvVK zlVNSfv@>X+NIBSj_c_Mt>-Fd$Z&{Oi*LjY6 zwwr&snWdhipBu48*Bwd>HYic?t>K4_63QE#(b#>weZbi{`d(+w(ru)LM9~D2baSU& zlYLOdSK!I{Yb#TV0#d)9o2=nTY~<&$_Kuu0g}z3WlfJk6%V_EfKH1Z4t^KE zbxd|{)-a#-x5wC#szsN(&5uNu!+p`xKUu@EobBb?n7!ABpHFO@L%|T4&YYpiBLche zdPSbRy#vWi&k=7&cE?<`pDBlzm``lY((Tp?+U!uvRk@8TLHzrZGd~LSP`*5xsqy0Z z5V^I`9>`7i+FdP7c{xLU&zrE)LW~1}#JSY;Tsh2=UN=w&i%h%E>&w|k4)pBL z!Z2T;wbJ4=H~+PP^x=JaNzYVg4$@-9Y^+(tZOS@#?P z|3q-Zz8~p3H1eE_)|V=gW|T%nE!iPT<ne~;gbJ#mv))S&lTsXuq~})En&EbK9N{(R(QuO{ZEK=uI=TZG zD0lHV-TX&OPy~HAW~|JyVJGGQfNQ$hFMu*wylEKwV+u6zE_&DM-Qj4z5ps)dt~+S^xkWSAlt# zRwPFg_A$y~W#udAC{=w)JHy=^D}fwSziP~-do(%o0{?NqouDjLcwhiGFEeTP|JUO` z*fkDd*S|dYvt*93E8FWt2`TdJRP(kE{S0Sp&EFjw2mDgJDbQqJVKYd_BGTS!x=;43 zaGYz8zH+ZaNrH!^hAz7)>Ihh&##&t?|;o$r&0| zw)XUQEb{6x$dY2^a%-27LWM`1;Te&045r1&6B8HeDiD1VF!!o{fN+BeC6EWnZf9++ z6U)xSo>cYY3~u%-{o>t+%iGFv#z014%2iu!!to}X{r9tP2$mKGwUG`Lmm8EuF_J`O+dYzexs*GoJZv$-`02{6vXS?Y}S@NA{O$G4h^nXBb2(hri+D9)kMU_ z^SymalCWn-b7h{5Oep{)my*M+wpHJ?9g5Q<+Rcq!{62o&zbMNnd~yPFY4L2iS?h;U z5m(R|=dt+hvE|+?Es~xIVlVfh>m69TZyh1ksvOcbUdtJ3NF3Bf)i2qSch|lvQKY;FpgAs&pr0g_h0l{KKNmB4&-1n!q#bM zwPUk*lrKlKNf{#W{Iz*Y)fu0K?&Jyy*prHm>Xp)tapj zY-L8XZPjS!>v&#v+4#n2Yc0DX{&L-{8Oi01y!x1y7fJKw z()A9J5{s^@lfnvb=Rn%1O{F}MA9LtDDd9W~^urf(;f;}-^?tAqmrIKK3HlW_o*zte zDVw@CySyJB3S)uh+uc9P8eaePkiTL32_Gh;MTg?A~Bqt~pW5KrU!+Y}{Z)EilN)E-YGhr7WbS~)S&0=HBuR|$b=@?t2qN5yE zK^CbE6W-4bTWSuw^}W=*WAhA^%!}LG*-6gthXUzH+*m49lOi8pi{Lvo^6sw$`K2if zqD9HW@Ec8)=i}{U|MJmRhh$B0$IhhLMe&7esHoDRgtW1Ad_$ewP?0X5EY^{3m#@(a zb$tn*n3uMBc~49Hb$X_*c@gIYPuswz1Ut6HgulJ*`;L@$!Z;eEVytn~WA8=!FL@^H zpiFdO&&0MAo@)vw`})iUWP^Xf-u}k5NZ)?kKK#{E!Pf~jE=bJpEO#;Ndn*mtNt`(s zPVthCr7=|R{a-?QDaFIe)6ZyS*2`N1ZSfJp-El%N^*S-;or`>HGDzEKAq40ntrtBe zVM2_;GIr7OL#pp0jutqcDcsbA*BV1ZGn1bCD`?j9_97!uqRIICTdNJaf(T+79ihKVYj_z}x%f zK3Z?3?MvH6V3;Lmnyxs0$=ADMzA{i@>Do(=F1bZy!br$v@UfK(N6 zmI;3*=yr{hnXli?@L-Z3T}{7U*a~Al>mCROcE`ec7C`FuK|I3U7}lD=1elAb?&CG| z=10nj!d-(!R|G9Y5@+ii&kkP{`^`F8?%Z@q3xuQ|&8M5PS0&6Hi!}<%JGFa2MOP^^ zXc;$_Mt!s=;I4a&O-B#7IRFl&$f^c}3>WYu`@%w4Ut&mv{?WmDPnR7~nMY+g#|bM~ z%?_UB+tO?$AvZ1FE}uMghJz2me;l5e_e_=)<~0tKuOgosfNpQ#R>V;Wpb>qxaImv% zyFb?;i0OpHk)U;YjAxFk&VRx9rxt3f;2b*3*ZcqT=)d26{fY9a8WpFk*dI3L#wCiX zmp&(+N%i3{XhXRdIK_ne@S&mMn~8|)NA3@4O-gjvDsRku5Fgm+s@hULkn53D zU0z8X(hGzrbk#Tas?jo)ODDUD>~dnRSnn5|)TOk^FH3q(T!i>@HvgWcT1)+nK$+-g z>x5=N)020U-s)wqwFU0CQPy&^ATwf&H{S;h=w(ed!sp$FIEkQbWK=|HeQ@*!F zq~_whRS7XqT1@rcTYccBK>XIz5sg#rSYxaa2c6cHn!QR}@6(lXu-m&5%N%Y*x7a-H z#}ip(!C9xCdSm~oGPT9u@k9BkT_wt}aBo?Guu^1a&cNLdz9iKbY)6rg2OLl{JTS9< zzmm2^$5LtXM55thr;jsl2;m+qS;lMmR+;eT4;O=d(8*$O9czEVo1%GHpvvfCT75Y-AjUd{~yP;@qdC z&IcPQmWJ|*lXMBPhgY_D0Ucbusg^7@C`jC2NJVD?X4v->^#Zw|9ZeeMdh-4%uF(MsAnbSJ??vPf-*m7aCN#8>_A?JfY=f2ttVK zoo+xNe0Q|@5ctuG$j966SH4rLQFJ$slp++j?$`zV1D8Em0bEM%h(Yk{|GN!VXiX%O zuYZW5_(MzfLUZCXZ!~pVP8oKTUQl`FFIc!BcQc9Ru?d(%YY(}*ydk4@#c|(i=`Fpg z`lEL=8h<)c#Xfn4XjYNS)^9zl4C_^21+$LQ5we=;P1@@@@ zC*$r8MZ3?XF`mM4?2LOTAqqpDhnuNz$$aRCQYOxMISKcVw06u(R~M)L=y-zA_O^7L9ojzD?80#SdN9qk zXx6=%GPS-@b_xXA-O{;RiB{t1+s5l<=*a@C980IyXtZ=YS#M^>rQe9^#99p|2#upmmxh&;19^H**cCiaTI6TCmLmrAac3(W4hb9S7Q`94=tBZJ| zo*Pq)-hMXD>dxeuK@OA!Yq6dc+ujGxR2J APdZTxzG3TNUabD}XTm&N=wuN;F|U z(UH(eXMPlS9&+nUj1P!q?N6zhxtNM1*XTXRmc+8|0Vf}S)D zyq=X=w>J~q5aF4UDCJvg)1MV82BudB^(>P!Gsf?_iy&(*Q%(X_QJ)w|+Muwkd(dgAFVt0%ZRdRg66*cXa=xs-5Jc$VAqvS1~a4+@gmpWzY6SGFjwcBQB;}aeWppLg8cfG zTlreQD7i`LFT1mTXJy|08a@Lpi?<`Mk#tW5mmjvfrQ8qr@MN-Tt%0ukg66682IMJ?nw*uut>F5~ zLUKU03LO=V(atqgXxIXFAp1?TxTX4=kRqe}ccb+dPE%rVlQp~a6=^|>VjiRxiCtqb zU#B-6=2gMX5UVN9Qi$b5wlsD2FOO-K3(;{-C`YdBMc(JK-494kMRN0SPY!qP%ao`U zSs}jzHi6D2Aa=3^=3by*ktci^73Z)u-=$|A2chcPJa*^&G*9))lS+-wX)(r#ob#8B zx;pOxmbfixw8{~oOUNO%4!)x09s<7`mc6GF@Ckb{Cg3l=yYoHtnr}aM-HTx(4{JAF zkhe?%p3AmUj-q1)CC{QOLEjkjyBY)_5A?NpJxW`Cx8FuG1o_W}OsFyZ&beC`I}UWk3*2nNt79k$sHOMJUSyw5ElEWB#KT{R7OOO#ootf0g+v z)t_TqiqaXH`F&qmD4?m^_F(u1lR5kWtd8con3e)1{eE1}>@0JS3tgd-)R{wo5e4%m zyA5yoo9xr>wez5r57vMZrU`&drP%h*M@B3MqogvR1?Hyu9khLK6+T5Ftl2tbIWk)g zqUuA|6?BBMU7(yJZSwSI68%$s&V7s+6oC3(-$mtVmwDX?*C{Q<+h(!81pH$_p4qSK z!#4JIHFEvx`*`<^QDe{PMSaQED(QhgCvsp}>V}Hr5TAAO7-*!kEo!e3e`|bnw;%f% z{T;Z|?mJYc>%^wARxdl@%Uw-j%s4m2?QzBEZO_*Fh1LLvGNY85P<`6NudQW5TzzV= zd10J6OQQc2NgqF*IMi+Ch+{5K)rp0VRiaO0{VJzC`7q^!YPWAb)X6?V#fivY?-rV8 zq5tR?YgN)MRLT;~`f>*+zys|R$J3Q8cagmE(3A12HnG@l*48Z6y_`y_ceiv`FG5k` zxEsB%x@yyxQZog)t?k3z+gPBtagj@VAC?9B+pX7{=GNcr4)^_Nh{!WsaDxiy=6pIQ z2TtgC^iM+9zD#dtnw3=%WSz|UX2)2nRPmDP!e9JE*kzx&Xk8FBeHHT&!JtID|cMg5?X99m`95r4|#SNXdC}?%A7PX+O$eE3@p;p)+~}OC8A7l$%}Mm=24$ zaS03&n#9>i^grf=toCIFi|vlNlx?b|g>n#8;%7co{{D7*MHK277-|zykeunq$BXO} z)a{A5SP&WXA2{Ak*k1H}M^J{ao4CeA+D%@ftQr+e`m_s}8C!drTae36GoVMzKdEc< zsg}v5nhuwMuPw_%pg-hk=D%A`z4`n+4}@&781jXpDoirX$cx&)N4l`gf*2lHNo^Q7 z&YkshSdF&cF<-L0w${xCZK1+Ue}G6&-nKGW3{t^YCgSWM{F|g-NElb)QU6B2`#?(yxk9TeYW%DZ9L>!pKc&5EMmY!yzeG?bycFIWiwNEBi(>-92G|6DlMS|o z9aiGqGor+t-Tm>3yJ;(_3*0n=qcFVJe#!J_UzzVuvsC~I{Rzuqn6TO>uhb7D0VC@t z8-iHReUH4mo4(^oEFv`}J%&PoQb6b7<@OK&0*iEdr6rBwb9C%AjKai)L z|8RKkaBEe1g^i*bkiG#2_f5W>u&>{tSNg6;>jPqt-_A@nczcA#$Fhnnk?)+RO}%>O z+1n+MK|d4LSz(8La?fGx>0qJ3{f!T5hdpG=#~KVQ=h-0_cyfesUi0ymHWF_jAs~A` ze=b~p*bf8D35rU%de1HO-5_7J*4#r8ipn0b%5Qrr zXYBti*ZV-Mf^Vh@CH?#9pR@V_w@Fd9=wr&ji&LlePDs7Fn6du)MQZ*>F(V2jX(twl zUtt4}E=ooP{ZMbHQmn&0l#d3$qQF)iGJ1u}rSf!B=+%2q!05MT;(f;p z{WN`9tW(=&1n5&Z{uH2DCMhzW?PSWj*~qo>Ax zi))P=?LX~>?Tf<%p_CX<=kvy;FUSWyB8^`C<@1-!`Zr4|#*kI@s><)ky-)d%Tx=T+ z%nE4)nld11Z${!(uL=ljob~^vc80K=3s?VGK!TBDZ&W^_B52U*VF_q015H|9idiks z&gIQO>Lhz{v^RHQ$PJ?9OmSjGr3fy%tr2b^j29*u9JDD%E{!~2n48RP|FP=^ctdK- z&AXVc0jejw+0`qLrT~YaG2rVp#Z}nG?jPQRzcoRT1pOddbNxb!*7F&rRZ zmrTaqqRC?_&LvZAVdD1I4;J<9gVRt-Z|rTCdFA8czx96gu!UaD%Cpm|{h3_lBzMBI z@vHZ2tn6PfD<=pkEQfKaB!~zQSCtZF2Ub_8_8-L zYp`Sx<30uX7j(U0Lt!4A%NI#b6Mpyo|5AG}*zr13WutI8v}7+Z2{>ME4^RgW5+(~j z@;#ye8bKMLEehyN^Y$f*KtHQrW}z~Aj}+rIH;d$qaFYNBT)c7qRXgE8=tQ_Sq%M!%_mh`QsCjVZ&?O zs4w;irHaBQH4#Hn)-HJx^E;R|OqI^NSQF<(Wl}oHRrKYYH$I-q$o>O>Q_2%Q)6;MF zaQUIe3-I6KJH4hwm5DwoGR2Gt!7xv|7^ik>IqRLrSZSEp?o4>73$n;K18aV;3phsG zVHH*5R=Qpsw$gRaJNnw3sEglJc_3-5yK8EBei;)nqj-w~bGR7{a@rH=pn7libPDw= zqJp%Bi;R{Hwt=Qnafe^NMyCG|wDUz?P)bKxP&b*}j^vkrh3%o%?^sE5D=~6CJZ^d_ zn-yFf*BW+2txI#dh7DapEoQ;B7V+f(itb3eM|G~=9_COi85Rg)eYr97E#dr=HUHD+ z>fbAQt?o`DJ)#9|25#{6kaj20nYmiI5$=-Ls5Bt{naQW9E)3X(TlE-A3qJISQ+tC>o^+AyazeewNst8@5MLPoRN&%* z+!*tUJFP#2Fa~S}F%U2rBy-)R^A7*f;ezy0y!-h~805pn$Ysr{4JX*mU{s=_WZAcXg|9ojkF0I!Z_5vZvSkELetJ3M@kL(Lv7;zBU;V zzZ0dA!fFcoW#hWWFKc6}Xepau6K)gvmdRtigAV-{w)Wof^niAmo^m)}Q%Px|;C>|O zcG}Z2{JfKx|5Pl?wbd(k2tOX-ayE7+GA4l5yfaQE7!8jRUM5b@>hW`#QZ|wJMLV>! z^a6biOP-xBEOL6}2s$hNua^?NsJWz*NFh3ET)wvRzNXFUx`|tCkV;S9)LlcE{@!b1 z#rF2eG7>k_xQ;?9ZojLr%|rfbnvP4z(nRJP9YhpKaPxz$%lx_J*sh_Kh@4K<3FAiV zP2sRi7D2wRyn;(+e=n(|&JLl}o2K9Ek!`*DPt$ay07hBr6ztIg`k%_8Bi-~S)-rX+ zt_u)Sn)7PIfx~FTS{}X3x(LI%MgMDysV|EY>y5xgPmBf2~_Zw?i ze1-Ubef)Gn(Rn$gE#GTrNs;{5=Y9H_@)HJTOof?JoN_KXJf!Tj6Itn5SL)?IvZDb<)}(@xNYxbau0M zloH?XwEq0+Kuu>gGfhAGG?<*EheX zGV3e|eyuDcSiSG+bloZJm@cWm#MQl8WCNd-Qqv z>}Vyhk|o(tw{MrieNmHEq8Opp#orwu@#cP7$!}wj*+^< zb+i-9V^pci3Yk#63#wi_c^?!_tz&W04s#Nn4PKx#95(hT*`4% zHrv12A}fTPC*=VJ^M`&>1L|4?XV0EK5K%x=TOr&=A}{5m-xYZSj31hH^Xk$svht9`~N;;JZ7m*xiD)P^BYexQ) zolJ#!AB)_z66$}I!eeUxqdi4Ic9}}l<{y;BdX}O}all5u$2HAEv0`o ztUN0B`7p$6iMxw+?8|wrqbs)Jo?~FZ^R)vbXl-`Mvuppgq@#&JDd0^a+WgU9wj6+y zPbL1Y>~*&RjnNTKm+*vpwzr^UQKV+Js#_+#hItV%$W=w02M2p8(xN+QaWmkK*>^kp z7w;P!8~49QOD{p1`ruG^vEj>LOf4vXu9exlASO#LjJZf?9+i)7)bH2=vQL+C#NaHe z|CA$!q+=U70!)Nzfex(;smRq^mZRm?`l58#hugFXbAH|P0*W%l`xDiw$zlmpy5v{> z{S#8Y2haPp+Mg)S)&;n=sdnCG`saV$iNi$oVAhIV_@Cm=-;`dd%BvmMO4JkPzZt!R z2mERMhd4Qi9WG5$VE-()F9pztRiw+pHKl}H{p>i2bfO~3sr#m}Q5DW}?XK@{b+EGx zCg8n+x1*zI!HauxXJNFlI?C}NNb+|vp8`cq(1rS;E6|Y)8?Z)buVfmuuFD)y4bFAM zY64IZr7iOmG!3ZVHRJ9$>z+Vw$5s0F55S$1HYY#{dXD*|S-s$Kk8|dcd*4=760OYl zQ18{GH~!*FhI6Y9qn)D#3Rw4mCsrsCewzqj`fI$th+A3=;sB=WZzAZtlDXh^ZcKHW zv?JbcWWPhNES!VTRRYR#Z_pcp)917Pcmk3*!IRh3$ajy~&30HTahTVA~sxC zhq!$5Ls84_i=F$YS~+FGLF1(N@=USWShbTPj4alA1cqP{9W{2?yLhi>%6@B-d@8~h zX(=5uuK)~Weq;#xngjuP_y8z3_O@>{SNII8)jI?lqb|y<1MYd&Ch$c$5*%6;%Z*R# zUzYe{J!~7xE}gXIM}opc$5!vLXi$jmA6+)JnxVzs37|!?mN7%=~Fi-xEtp;+)8A3v?q9cXeBtTte~;s*3Ue z2{{U!^g1ETVy-zu0>@sVIzv#e{!^pMPCTMhc&0ezb`kmWdkyWdEW}6VmMV|{)!)h+ z<6mwC1RC)Iywdi?zZi7oy0E>nBL%p2S;`H{rc}Nca*AGN?N4z?*yDERuPp?eDXIu?5P&Nw9a_7`Po;ov@Y(L_ zv0;>cI+91`#V-H#^4i0LHuObi?6v+Vty1rvcdcmcNx8l7 ztu<*@30VE!`>-}9{#0Qe*v10O=zBG2*s_0ab-BlK)}{bA3gS^Q0`mt?4}XH?7$ z894Hlne44kk5&L=j9JkyO+JRE!1N{1FD(&Q(8%g<(uQn-%30yX_J2i2GAw)I0qE{+ z9|8LD;CxqNMLCkZpB=GV-YvxpU{VYh_Vr%r*iknU*6v15yF{tf03cNV3h4e_=(_fS zQlkCsJwr#)oY>X!NST{>abN2WzXEQPzy79P|5nsqKVes|%z4&~urUg2_U%y~zzhNfm6~td3U3ylARsuK`V~rfuki5l4>}%CS z(UWRcOAO~d+Co}S4bQa-CoX(F>#ruEb9DPCq^R{w<-)GO<-G6bJzO_B0Ap%`NzpgD zm#2GAc6TIyq-Q}}}?N+L{>@RUy_TQ&LNFul+z z|Ea49o!Lc;AmUCzF7|3 ze|Ff4=imhY5y+g)SWEs z>;+sOY&{`Rz{3pN~xH@Ig2R#8!Vi5=t=+f1FNB zi8kC$8@jMKEGwW!^ZaY9qlz{xNXU2k_ty)XT}R|)wVFOaGo7E@wm|qCet)h@u3(<2 zPL)o~zNI~Sl|f-=k?;o3)07 zT%~SNJ;~km@ugNZi@UtMhwu99Ov%F6gwVrIjGY$qs!co%h0@dzpgP~AMB8F63Y9fr?Q7+P)1sMN-NNZV1{6KCw4yi`Kp_ z=Bf@Xu$oj%FCP599C9W7D4Y@f`*S3hO5gW(0A+Fk&==7%xcHL$ojHyu`T(VBHt{zE$~{E-GImT-O0IE!Z8aH48R`WOUr#=V)+`X`V3vsCCQo~#W_Sb|^fC1-eTYv{G?#=}jeHMnB#CosS=a0?$H zO-Z{A#<0$E?$&p~D`#87b~~lKwypTafhLikL1x9UJ$h&5nJ8pE(;kCjeF?62b&qEJ z)xs9|dyOFlN%ow(B(IyJF5?RjoXmTeiadpCDy|gaOfN|DPfGSd60ib&0Sc}C|9d>2 zc+E=(JP@*RmrnoTNJKe5D!3--_FtmFow4re_&Av#<+BOK2GnM`S@7~4AHM}NW`BF! z@?~>6X6q3vG}vdoiOM>fJD!#@JM=@y6}lG(cUa1?j~v?U1yL6cedB_@aOwSbGc~*o zl7VN#C|v!1@a-nVzPfYv?`BgwUu!7ER0eh(jSx1t?(<+7-gw<3Cw*=bJ;>bntO9WQ zeSzFeg>tX*4C=D&=pUC-Q(`LBIh zR@*A>Yq&PEor@#+T16S;gC)L6G5GE3xho$>6bFo;df7G|{poAUd+uFVadnhf0p-7z z5~b;7iuYa=CJa^(DjmH|o)B9uK-X|mE9KgRNNTP+=3&)*CHMvy6Z>VG7#R=2a9*u0 zlLE6N)+@d!ie+VPB2b1KQ$q3VUmbgwMydvx6=A2T_`ElSByG}z*6$a^Ew_VF6@Y98 zAB@3o@H{)u9c)n4IHDamJ`c>9huMCTzANeg-##kKRH5F#7uBGv}}FJ>EKh3lbxo2%JuK*WfJ&!w4iNe2u^) zSGg(2BCC$yF~ImW90N^@H$j%1Ue2YH;2a;kAinZxt`6KLY^2u=@#j_>I{K*{eM>uP zgr2}XW0_5&yN(t0keZ9qY`&~;@QN~NtZF5;Uwyt!ugb6_QO&>O1~qLhZ|V-wltXnoM~_2 zm*S<7jibQK_r!QJd?wS*^)hj8MvKSj&zf^tP|)xmgC;ODre% z(;14K_`ZokDR$cjwEo^7ab93#uJfA>P_J^Obp^lECnWL0%>AM}k7nRIS!AUa<}P;N#Q6+EZ)CLf@Nx^If!jIvvA+YGf#W`KT}5 z6lH{#xYt*80m>t0A4`&w>{(Y4&~P9koc!W{`gR(Tj5H!Sor_cXxZd0bo_}TQM67Xc z&zjUFmg02RV0A+nL2QegUb!gls6J1p;(d%?Y_i9b=FT1|QGv!uo1QHFMu4KW8T5mH zVnZJDhC~iR2?_9pB3-#KDem1M_>rpi5VxZ;|1~N*_i?d`-A+r;?uqSMjl%g7i3OI- zxrpyjsDE98KxZ6ti zcs)N{Z)ZPldI@`M^lOa?_Jqu(~ z?|nw^lj+8aFv2ld8HAtsxrTt2Nm=@8A~*#5thiw{fRh z*@stNcl{|dDvBXCp}U;P5lZ~M?X)@oJyie(A<|LU^q$qvPj_{MC!y?*_vWeDAu+r8 z7EuV4&#@zXKSto$S}=d@5A$F+gBszQ*g(T$iN%b_fm*j^i84M!qahw#SEMgV*RT)f zGn_InvP1lU^RMD=z# z_2dL)J#}2L@S0ZAKb>~RcnlPgFAA@A$|KJZ|7g;QCQGfhW30g3Mmh{u2Kho&fEJaw#S=4e6sSG(HZdk{hC;7 zhqG?=TFPoYx~pu*_ZL0)H_2796AVa;zyS7Q zaQwb;E}Vuxt+%EpOfzf(8C(nK(P+4W+YlR31}21)c;g@|V)ZyP=EqOiRVK+_UT$Du zjSlY=v%nx()o~|~d*x$LH4kG$&b-9#$J(6)r6|ZVdvQ32KyRQ*xZ|86!(fZ)eIBSC zfBZ)E{FcRNvA;=)TH0SY`{F9PLjBeB`-qoMeT5bf)P(!H%ek`d47~&m`-=mcS#-(? zu$Q@NFemC%pdTpj#Q-2Uk|U1RY;L)dtJD|#!f)u;ovT#bNUY;{TFnsu;@2|O)ttv; zWHnBWT<_FLBi|K4zc};#>)u$HJ-xwmnwNgfKjGrvE<>@C-Y%&v_n<|%By%3}Hr9VZ z5`PDnE2uUDsW?*MZIVaj-HK^X&k0_!g%|LL*EXzXgSk0E!B^|lSQRjonY&fLnk;nT zS!B7vsw0%9gT!w(eQa0&Q_-p+RH_c8lf_LJmcZcgMuigPE`i1L#XQ3u;+&+aii8;l ztY*X)nCJ5!i`$1rc+M-da{7Fa7hp6CiA3@Plgb|k@$NB$h?z6}elPgP&r5pkaRUW< zWi8?{D0=QZUUk0Y7t^8X~Qt!zd2eZg#lY{L=a0h_4 z4bW1l5q01yt-<5_7>3B*$>QAbC9cT!Xda%8UIrc=4)Tpp{SO4~0IG$!VTu; z7H!gtqafXztqgl}?_MpUIR$yXs{gY&jDnnW`K%4IFys3B82XRt@%ThyWe1eGV6&XX zpZ9};9w5WQq&h9*m@p~kpkqwY(RGlrMIm#q3EQay;^V{jyCxW~`S6RUWoZ&`^{LR7 z0z-lzP%75|AF^f*^EXlBJ?+t#j=(zw+FR4cO;4XPHZ#@<_`7dBr=h{$eo1Dn`@%_` z2k-KL=tu9bj}eyTgv1;)!0p?>hc+c>c7~hM4n}r8`>@Lg_O8M{1jxGKs$U5z#7e3> zl~l|X@U`&!pKh(!mtKwwzV0^i*!MIqu(QC9jzXQf$R%O2zwrf1Eq$=fax@jTQqoF# zr+-rv~_@XYud+kR)0ANmsGZ=!`Rp4K9+c)d@?F}pK z^!mhp&3t5g^kj%_#%!VI5+$*Mtyg5@kTEr3J*V@ zLJM;Tzevsy;XlnW)l~nS%i^!I|InFVKVdcDFIQ}`u>1GL7soa7xgua+vnbmx{&~NK zi?!Ffacl4Q*L|8qYdswtlW>ck?w1}d`FXhqFogUiYIM%Un+Kx37b|Rsb-=DH(Qojo zKrnpn0bZcc5E?z$)by4pQ~QnDFAz%5bv2ml#m?o8|2=onHoDc-cjfn-2U z>-~Ot-G2YPUZ``P*Ynzs>v6xXYY;l$c%)sDD+->=<^^7I^rK0$NZ%I?^*(fE#D(zZ znf0|KH`OI;v1})q9P(`1;XcnN<*&vvMOiELo~G5+bRQbzwd?}LDEnL38Pcr(^2t67FYFD0k* zz!V_bE3L2r=dbHY8^LUZkL}RIf0`!zb8>|ZU%fe}Zd%R0-3qC_LEk>I<7N^nhVn75 zLTcQz60P$n4L>6VW76T~edcqmShVt28ZxKa^Ll&woHM`5aG$Dq&C)DLJ=L19G%X2F zzIUVV@!`;u(-r6+^M@t)PZg}pUN*s5UoFTTX3b-1tzVZN@`FD*n*Dq7t zhx%K3#)m3L5g3rEd^m60LVFA}(^^!AiYPsEAz8ZVcNr>ib>(sc5*LTH;?<8Izw&u% zsF^hW;Pv;UETM~Yfw&e{v*d-N?4O5Wy#?<=k$&#wL4UqvH9%k}>zFF4Ssd}oTH<8& z?nF?tKXZBl1oZ|R6Lx4X>Yjg+wx>Q1FgYio9Zx`OE~}>hDoi9)1Dq7a75NvC8*(Wf z=q#9Nm$nV#_&5PK=#)dJS(S`#Ej1=+QK^R0 zvbU$BZaHk$9MaN1{3-b3ULCn*IyP%Shp1Ns?A8DzbCBCP?t7k`b90-4iooBr8SJ2$cuGv7QHoL?aw6S-nv=@xs> zxIMJ~8d)f*_!T-D;!C?cwNxCC*C0PX^Oug+ifT@f+QnOFB*gmD^YPqt zbG8_WZq!@x$f$0Q-Gi3?EdFz>YjE+CR6@byk$8*7#0cyUe_?g>Rq^RuwIuz?vpUk8 z9mO89msV7*kf|tn!~CBuS8ip$h`;BkpKwxU+V6VZ>9U+RXP%XcS*0F2_}mS;IbvID z1ITtwH6+0Og67SV{=en|0A})dMjafUPRzzk1|3#oP)Iboa+Z3|e>eL%db?E2PQ@tR zdv_Hty2BiqoR-#0^TXF3k<~{xu+0!g<%}a4$g-|7wVvN|Fx4O;L+cr>qh!BrrrrbJ zn>-aC+exN|xDJ24Z1jk|x|FJEYtKykqI^lb!TIyLoS?h~vef^U1(gM)VXxA>GABsHu_spC5A2GZ>A@3@dqVr_*=-Aes zrPqy+Hsu+A;lwiuN8W^}N_NGTNpLUsY6VXKem+>_W1--iu?m(PjpL8r#9xl_Co`fp zlAiTyB1>i;%>MN9RSk6Of8JB?{Zf9;i-st95@xGp$?ofam(vC#21Mbu8A`Vx9hyE)IQ=O5CJj>>AF}gv-pr_ofk5l-A zL3<1K`g44R!I?&)SAS@8*2@4G$@6EpGLq39JbAOl1*T*qgg^=O=ZpZ&9nJRU$)BIa z+1f9`9bxy^0L*>GEv@kye2oRJGuK;Yp~aq3MfF*9yW2!fyjfMS68i19>h&;ox?rBS zmQ9KEl^h3CeGm1$_B`AxeYyADVYDVSsq%_?tQuSW(WATUuD?byImq3nj$D$w|1Fmt z+u=MAPU|V5wv6e7u~|_h+jqsr1hOAYRd*_-6u($&r}Ijg!5TcQ~{&FJ~tecNje9QjJJFe0bMnNHR{lGDLpMD8Luu!EJF4^M0pr7Ux?5+}=Y* zX=G-Bq1)Koj0()>fRUmVIW``-sfII+hOR$j24SYbVSejC+OrFAPHcoLO|uJQ$hE(+ z0-y|)MuS9@%DH!vzBRmQ>;{SCT$7n$4zv#*keB=xb*-9X*M&!36$`JtALHv8f6d_V zxc$(;%lGQpJIY_;=-MB7c0vlL{31bw4!Ht2MH34M8Y&i6x9T+hAwP`3$A}P}>J%wdl*l-x!9v!M&Oam+xV%!Io|y2=B7}FASKWl>r%T?qvUA@jTM@iNP4)-b zsq6PsrFUz-jkwUE=|ZPKO}8UY#is#KK|gLY86NxjT);;|Fke4D(tr^T<)A%_vG9}H!thQCVXUz3B-t zlV@i)OKJgK$)Iy$_7znK&94Qv)oeQpnoBFPEJd~uGXmW!?)rgfvUl)U7j+L4NF0Yj}0#tL$x|U*S_T#(RvwKaYQ58UaS!EaT&{hZ7P^8iT;IVynl1 z>wAQ4JMouf?V-QGm(Q!g9Nydf`NYA!*Vd~Qt5-_B&}^dFn|X%q|2aBDNkCap@PkKm zBf=;pLa}JDSqVo}1Hu7)qB8p$6aB6Y%cUduu;c17E~X;@*U)V^M$dUXA@z;0=aNBx`oYusMG)EDmyx4TKfrQ7LVR+EVy2I)H!h?qX6ls14s(H64Xm8)DwiIUFrmo|?NSYEgyt2vb7OL8-0K9RmnGQSl zz=&&ri8s~50IGM4w%KMn`?y9ov;}d2N4)APo;pr_iOe5^6gUQzPfI$&TOLqAV`1_EV{08(8hPj9hzgD%~g3dEeiMhO&rF2 z{?${d`J*$oYVo3q&tuA-;0>zMeRYDT5-Ly~`74rwyHD}Bs~FjUt7WN5KX>py_)6gk2l;TJlGrBeJj8*yn4?gI4k?Rtz><>ej9cn~|>YJ2*z$%f9Ada68b| zx$1(0Q76{E0-r`(7ZFnLK6p?CRP76yQ~r$L^w|CB9n^@L;FNY8F4-f?B0g1cEKJ<_ zwtZnUa)fIe{m$%n_!fQ@U(hIWbk~p1A#w9d033c9Y2Q!_^N5)97$>qXg9<1f$b1?% zhKrKb>n>y|lUsc#j||FTu%SLevA^wnu@{j~^S99KcR#K=5CHoQ;?JG<;cJb_cwMfXM+W?BTfK#8jn z#v;Fvau`&oMf5&q%w@#3D{S_G;a z2ZT;SJ2chV*rc;O+ULr zkflB~*l-$Zd}{Q2A8JhvHJ*Z^^NA^mq*sq6ew@#=d#jIrCQ0YlKW{h(7;%fm0`a&{ zudk>J*YO51sR=RKABy;jlMXPC%qu=39L4C`(*#SO#(<4{2m9j3L#U8tE`fGAxi16JrQt z%a<2;%gZMA3)JHw4be{@W8R$sNmxH#f({FXv%_0@tylnw(|?vGYXf9;uU9eT;34S69yz#{1&*s0y9M+Y zDQ2uEg=$Xdi~%z;p;D3EDD1m^M1hXFKH{j4&su1Nx5{I3{Pl_zSL!`iJEuB{TStlP zJ+Pl|VtwiN!n~k!&NatZ^F_#a&vF+pd^#AORWJA}q33RRO&=7NRy<7(ahMcUP_xwy z@Cc1?fc0N0K>vg>IG2xg!uSRaSj&(gx#OpQb!Y35VT1aL)b&&HHYU%2D!jKm0!zt_` zrDG6DARZNGh{&DJQhyLhD6e^qvHXY1)l3K*-L=***Gc^LCowpw^qXY#3Z0&CA#s{X z*(7nDE;Lv1!kHI0H=GFKsr|$eZsx1JmBN(WFJ=igyL45sopc)`)~R0gAR+}Zf@MlU z(-YcvE$J8dkDi33(W^9pvdsOcJ{h+@2LtQ31AMW0ib5-*y6+x(O@z+|FFDFw>3k-m|MQZm&Wy-6F1YuQkz*rK2nB z5F^1lkJ0X{I{enTBc1qx zX9a-F7zA^<{e6fG$?%`yM&V919?br+{k5h2%<+FErUFD0k9O)E`b$fRK;%2$wgpQ8 z`#<73-NXZM64y>WPBi~pD}OHf9!HD*2<|83qc*uI=lTl^1EnwI)7ZJ!{=Vkz{2|FY zn99g>f*G9hK9r-xj-PP-Lz&;gy?S<#M?uTtz5$Z#;5$-35KTs2u#>}BZhv@l3o^0` zF&wafjDeUA-G>v%kKfSP7BU~jR`21qfS5>1q-95u^G$x9YR$FdnB|N=P(6!?R5N-{ z3)bDD$oYL;LL!L2ydTMmT7S%{P4=TRc6f_q(@)^A;;8*kU?mN!heUr0k1!Qjm3J|W zmafSyX~?0BXj%6W?`VL3k7Ca9lB{bw->M=y{H2K2poobP%!($r*AFpbcXU~{!QZj3TblMwItn>Y zr`}TfxbC&jp7fe|xmC(CTIW~K1MC3L6I}Tm3OYC@R6_WzX{a+-EYff7hp2K23vJM~ zK;c0BHuHwHjwmdT6smv!t8d$)O4cdFU@q2H@ib*3-Fgp6hz9cP&?VHj`_-TRtp;9v zK)M}w*A*$r+=&s^T=x+u5V-j;w{Zg^*$p8R+-M+j_rGFmfZEb^uF*XEdH@a-ksAJZ zfCWx_u@WF%3$?#S`Sd9FzV%OmbDpc_r%XtrS(kADoD?SYZe3=9zvH!09~^t24UMw; z`G+Te8)2$1?0UF`paxQ=xq9lj%X%oR21xjU27UjsUwH@&X`?84W+_YQi#MmO8}0}# ziYx|yggc1Jhsyj7il$W&;EhpjZZfulH0!UcbPK4uZELQq0Yo8R9G}6$<#Qe&(f?;O ziK^=t%HW{$Km_+fll;6NOu`g#`}58{(Q+U%}`d}s^G1fi(z#)?yR?cex2h5QSL zw6(nc4;E!?xnOl*QwNj|2c+E9XLAv>VsC`k)s^zaB{cF9)HIzw#>1qx7KrEALV!e| zzb7pfvuFJj+sX~vzem6AG(9N4Ju1Jba@kAeW(gToo2>l&c!))q)?(QfIkhi{=kTuO zKSoAK#DeRnZY~a8_re(HJ$tG1$n+HESKme+jQBQVz2l|uFd`^rp23nFE-Kbtjw&F3Q_5qPAM!9&G5#wbxEGKg0^Ge9ssz1rPwB9^_ zmlDZSPkm5{r9k!1^Zc0iUlj!Ma%F*DlJdso=>NzK`A5(R1S-jl>P{8x;{kA)|_7GjVLl@o0`eH+e?s5_JEX7sR z|CL*=*`x?Ni1GG4gHROQl16j>FITd+Ie+ z)`7KzXKcb9x#jw)#tMbOuN%N3%KVC9B13iV?3ZUd>CG?lWByL%&We05@jJ^Nm2~fH z#$qYmh8ce3=v*w?i7t72ASpWOS9gIqf&_nlia1br6x;7i+`6yw)3(*`K+MrCzm8dX zVciy-*@fTcmLtGj1534&h@>#eoiK}2c%XZw@)P6HOirc0OHCARo_ruI4RKiXbc-m% zMnuK>u@Vie)Zj25Iymk;UJtXYq~3+7NKvA%aWEHr(@D(58Jk7JqG;6}} zGBcmB^V(4D&f~`N15B@=z=|YXSCS5`+BJ@c0Nr0I8nJ36Pi~F;ltkIlpd^t37uJ?O z+w0bH^ve3Em-H?qwLkg^>+j>mikQt6_w{j%V3^&?#dDtfG2Tlr)K=s5n$-Xg#}KV# zNZFaO3&nXHpXb@LV1cRvvSZ1>C38gbGOpd6bdg=07#nSUzwT+^^2A88`4OPY16>{| zyTkX~#>l{c_kNkhq5C^kL^6#3Rx8QRcON{Y1T)1>`q$H7&#bEu_Sgfji4`*}I;8R; zR{9r-E8RqR`EXl>CZ@~_-1CdvVeZu(20MrhG3A|P1hO@GLu0-i%YPd4c}}CE!-uM2 z!fYJebbrlc=tCo3TpbO7spo^uDK;NUkJ5c_Iri#S=-(PRd&FSfWH(1t(u31UNjYoQ z32(YcCb42fqF`%xa`d9;uVTNC9Ob!`--*JZwsTcAjZPUuHj1SOQW?HDsa{)s*(hOz zmv5}tlhzMQbZ7ztRQLMyEn!I7fp|{ADbNTJcHwjHu=d-RUz+LEke_`XP0gtYMs)7b z;ln%q>eod+O6Z=3W4zkw2YYS{piynQyhp0=C)Ry09;br(u<}3wtB?64+O{F^)nN7m z5&HS;i%L*szI+0t{z-r40VQ~FuUlJ$(DpJeXP_JbpD6S35@QX#b*g1u?C+?F1e9z6 z7S{MNM%iHK)T*tI?nyoOo<;+X*Y?{_Ug_LL*+v)k_vuUTE3)K+xFK{#=KYS>{;P>M z@}!5`i3(S$=G|_gevv&+O$|vHwl?l#f+YDlJGi8niFlMUWc>QH5S`<@LWb5H7y%99 z-%h(`Ra?;aX`rm$i&WEWc0Z->EmNfV&Lo zJ~uNvdnNw1@5X2uy6n}{JU5TJ_8>ZA>h!i?Lg)qy@xI{VSznnIH4G@XtO0J;snA9= zpuBS5Z31Ws_$J>W&vYad^X!2rIV+D(U5}Cnkti8+n0zBjh84f>cd>`HBU*e~$^3eO z>ByO&m;+~e81M`=x!JoM@66o2>ELtXZ`~+ct=UCAezJ>}T=oWUMK-iD=4kQaN~rb+ zFJbbvgkkL!IFVDH_M2V8yHRhC;UoHQDQwII$n#Vl3EIj4H0L6L{j3{D9hBDL4c-wW zf%C?E+r3oYB{PgaQUCCfCm4U?hi{Fyd8}M~HZk z(~_51mX))lwlFa(hJvN8hpTAa>6=Ek9PMS?BaKPT_XbC7o$EKzu)Ve8BwvMnzxA z)*;|MRFnvJn8jggfo2>G(a@6}E2C8!o;zpiZKh*->uN@HSK6Mxjcr$HaohGn^5L?# zJ>hubUpHhJsB|Xz$VEPdIE1*jHNJb{F-WR_ojV2?y530OJc&;414Lc$SR_?g*`i9Z z`nyp)81To>E{fb)uY=LC5agiJHLZQ)aji~(Kr`zM)L@m~k}hZPE0;su*x#tn`ja)#CkUkUyg>CIEM0z`0|W9v>3fXYMpx&j$7ow-Vf;U%&XCc?ab=~z@VPl zLu?m8VX|qfky3zHE+e1h7RGIayXa}EM{*(WGZ(UXG;UBIaH)LA%fvkwdj*EoBa5FZ zbEctwsmbTsSxhhwnS;%?dwEk7Z!uWFz>oUMsd;P`0-%G%y~i-VMbNaCF(kkt2f$@j zrMv>|>yqLCxyjH8I(>xdMeeRD9_BSCtCk3Nams0J3VG|X%;!i{mYL31{wk&-MO=P$ zdZLYNQ+)rc(4OwOQNO}xDORkr<>`s4Szm^Fvc4>cQe0AdCW{p&!#RE2sygaLx^a-~ zgjl~^ECLa`*w8f1tl-Xuj5~=vF&zew{GjWGA}sU{TzWG-N{cJNgH%8KI^ zq63ED<&P&amTL-?B)H+*UOQM$Rj_(q=dBD9WA^TZn-L=zl4z%E*&^_#ZOA<^@+`~|FOMa%w)@+U)@exXlE+ftZ#pD{t}2e(s@+%6d>+apP}hp}+@IS+j+IL><>vSlIW;Sk;< z9?Lji<_RMQ3Om&dLOzwT$nC7bC=0B+q;7WO53T+QQyH6P8T`Vj|NTdvy+EP9`d39$ zitELhzS`CiQ!6cbv^iD%Z>Sb4j1L@P{H&dRN1#uLlk4NbR*#Ek*^^2a4?CUOsmK#! zb?RWc;-2)w>Cbs+IP=n;|Jbjt%TK#s-js1-X{D&vb9n!ZYlMB|fLyKp%tB#GNVCBQ z$&Nnv!kI54X9o6n@GscXwgtO+4n5v()$?Y7BELMyA<}L9J==_RETI!->-s`VoUEj0 zpQ!~v#!LWnOaYTfD4}J~AZI8!?+uJ?V}aJw$F|e07jCG!51uiJ3DVpv<8e=sfeg|k z{YG~S&PX?$Q=^6!CCmU}_kR(&Fo z7BANlH;sxB(V6~|&zJmob*U?Uh`e{eB(Z=*B z{bkq58~jyr4PI9{r<&wwT6S{w6Q|gjwFC0)Kw2JjEZ%5neTw#0mFT+ud{`pjtSgMK zon*`Gf(iZ<54cr_&-8oCq~1MPna=MPE!(#?XOrlER99H#V%tfaJgH^g z_KU)sS9kwUCjZ>iNzy+psioVdi&8d&n5%Fx8Cp0;jBT9_C@ILZ^c3fchqQ|38*SgQ z-Qc*&mz;CfX?bpd^lN4bi8rfr?>%9_2tFTXBqParXHT=puZl9%BX52yi{piut& zV8R?=*Ac3pJbC=0kT)kQvx#2Ya#j3zOHA*8QBwWhr2k3gW_^j;gK+rXOO2OI9Jc2a zE()%M`;V9kJB3MQ@Wv&?eJ^21mSJ_01z_KsAFZ!SA6q6rn*9mfyf*ySn79O%`J)m0`ysy$sip3kbbmTy-BWKkIDMyrCS*zNQhMDS8JC zFLki({!@A#5PDw^9I4VZ!X?wlyuwL@tQZEhcj)#Q+s1u~7r(aRtLPQx^@&!0XT zEsuxXG?ED{TKGCb(s-)`?fp_UlI6&4#(NEO9~=w!SHsjvHHYc!3Fw|+ zma^!8y_gSuMOt$+c5geWnxjOH=ia$Pk)?VG$cFgs!i+>WZr`D#Y{Ss~7fy~$6AZU; zVclRC6NkfFJA2sENvZxeDx1}|n8QgJ%{W((W*r_rnW z`%Qwdn4i!i6?^Cp>CFfLdi4hMFCKR#-*z>qbA05BfKKow+1u73A&sNO#(C52*=DA1hxJHJy$!a}+To$(8P^J`2x8XImxh(7nl)2wPdo3JU zv;6k5?ptm#HC#@&xy39Aq0>bF(QYM#hhI7FMmjp2>6i-or!H;H{}D(iatOI4o$*7* z2q`H>0Zl|R_> zSl}J0A@|8Ap$D$OSUZy{f$S6fJqxpQ_&^Kd5;$_Gp7z+qhiogyzol|sK(^FAFTA(s zs4w(f7o_HEj`E70z~yk%FAjJQwc-R-u5zxbu)&_Y)w!=`|3e=Uk5v|OT1WFR_by^vDMw#@M>JCx)wylx*i5$EiSj8&&sL&Rp{FPF2)XQ|S~HTSBr)nGl`xk4AsI zs-6Cv0BjY}e?p}#H(E@*6fFDX4gj02Bj<-cWR7sUM__CXvYWKZVKU;{cwElb^A{hln)pxL-AMb)Lt&Zs)(qmGhFO9b z{kx9hAMRnk3KVbjKA44sSCI^C{ruu}35lU;#RnL-+qV)R~ZJw%pY9^p26jrBw!MVM9kaVO|K zd~i~e8RG$Uru*sLxnXcTIjt$sahp|MF3twBboyI1TO&{RpuLr8YCJy}8NK$%La*5` z9R>LJZUeVJ^pmUam+`nbT_?C^FXm(4HPj(@PlI5y5y7D=r%z7oxt`SO{glLz)qS!) zwTwoYqr3xhk^3iEJZ8JzPXlIGs?~7$eDobLrD+4luMSn>%|E7~iT~rvuP_iNUfTmw z6B2T?mW&EzhnnqfzPw4N<7?#dV~_Pas{he>U_E$FV`tAR_zAMoFjg)Y^?4U_-g%zr z%T4n6`5U0qbf$2w#)hk0SuppU(_q|77grA$LB{cUfdZ}iXdh>*ctB8?_3OCoMBM_3 zmBopL27BPNCV!!Z+gakR-h2@+d~JAgf`gK!BUW?2Ed(%h=YM19tH#5t7T8GeG+@K% zqmH34l&agZj{B67iLGfwOP<~8ZA2Eu!py+8O&h|YQZ^~2i60vxz93Zt3_QrFk8Jfogy@7;@(POrh zl`E2p4zt{t;t}+Nwc-T-5KLg&o%L<<`=`>6%0l4}Sv#oIuky`d&{VFB4T)afLptAI z_dHsoO`GR#bpeCN5Bfi*6pO3#M;QrWYWqrwmI~l5@>((Hwdd83IfsF#qlccpMIA{`XW~s9pr}g zCY92=^I33{hV~8^FAZDm`8UjzAw-jV+s_%}mzVB9R-|!_i@Q%uaBqvDXye{dCf9CfE#u%+}wyA~}bpic&NrQL$rFitS_Jy#fA z@E8;W#H%A@^Sa0Sn04PD#pNtkADD44mkE|_?z|s^S=G=wJJejRc7=o5jX(EPcy7$L zs}7xE7IbLAR!*Yp{pF;3+0(ithLJ9VajCucmAQt^2=CP{;Up}OEi=s> zT~>K;R-D+@K7b~7Q*Pc}yGBp(LBirL>n?_rKWFh4LNL}Zfmq%M`z7co)`h{A zw(-}O?c{8fQJLHG3zz4IOnUB!pZuZRW1LFpJk7i^-(2Jii->QWiatUgthcx5n{#HP zCI!rQv}38 zz9{b@z2*5H*)^NHYxdr47v|sCpDrpooj*(m8=A*il};s=8h3olQ^7dA4-Kv^2!&Lm z4BONdS7UnH5!|D|Y?TDjhkx$huiPv)$xZ!|1Q!1FdLcK__2d%*g9nIE4%F`qdb%^q zudRLMH@>^o6${qWWdG((_z5{uqxKYUE_=R9w+cHi%E8)_puAV@DH?Mn2ERQ2v25r` z{946_j{<|v9&fD|`_nLm{boTBx}Y;%ffW8wY>|P5AIe$VH}Qc-3x%eWI8Oy`YB(*3*?lB=cC}57}K zh1Vj-pv8YkC9@-(y=X%?C)eI?Q19}`dZLbwwy2)ZX-@M`|(s$mP3qM*XSQ&tLWkNFTvHl)|X4lgALV2z>lTS0Z-7Fhk+$!+Z&U+aR@ z8aU}=)llfyr{T<+;Hh^d0(rl9sI2xhvY!9r$^>GDg#H*Ab2Jx3`MwRSdta@sRe2tni*qLFKchH)j{xi+J5`d?{f2(YGc9IsSwgU{} z!`#z4T7Iu%o;waaK|aKU_;_Z$%(g$Hb5+?1SE+w< zVS@6+ZL3F46$X%)iuJ9*f8)X!=r`M$b$vqNdBnxy6UY#UYx!jQ-xymG+g&vF^}fv5 zPiRboBIuW>;JEJU)sBD=FhQ>{lj+#Ma5e`Nf8#B0^OYb(zwiqPwbPb`41ZY2SQYRc z>~FmFQ_hh>gcL=Lga^{eqdWeM$fPiv!$WhIf6_5TzrGzt!o$to4Qn3l&y>t~_P6kG z!;_$iLd@!l4-y{yS%x_Ng^>wg{4G2v7zOTLrR*y&NG$IGKIPx&7vVRLKy_sN1%Rt+=44#;V9Gc{<;oPe8L8R(dduAHH4A+=Ui9eLzmOXd z${iiSPxVt4Msa)%(rwT~a)wc8Q|>KQ37pBDpIuj6Kh#{uiM{{o1>{hkd#TvIz`S?| zGEyYh8K#--VO4H^2Kav}swbOuu zBS0sjEUWeF{QtimpzDk=d2^lYuQzCc*HK=x zqm?~}*5WUYyw_7Y?%%j}^j>m~1au$>Mh32Dz6PB`48)hy7SpS#)lFUwHXCc} zUV{x_)EVBbcxbkNVpx02KVu_4*o?M{xMXY!CReb&P>pQgee*~G2j2J?YK$qZ-DRk+ z^u*Xwa&qFDN)&s6{nrsur4s)ewd;KD#^VHyj$Hu0WInA{rvUCdt9S%vB4Jag=Z201 zn^ojKSxjmvbB;ps z%LiJ>#cwl;u(O`^AF-)U=QmWAS@W9&!q)Mk7-Civs(;DPs`EP2FWq<~3XQI|nw8EJ ztt<%xKrH^?wX5v-s8?u1m+vvQFq!fOY^9K5HQZZJBv6%Zrhk0h7UH)m6+Mj^h^NZ< zHw894j{J!c9l4-;R+V7hb*P(je1S!>T`<9LII$tR9gD-BuZ`FZC z5x4IPMqP9IAt%>f*tiaa+^n#pbIZSBKygSqziaftSs_-#QMoEc;cw+4!a`N)PD!Kd zZi__dZlv_KLiEv127;F+?_FV;Y+ord-o{8=?j?f!Z%(8xz<$@I|8kbPm|lEDCwS=; zk9JElqc911c`;mM-)hFJ%g*>B%6gRPaai=PA+c^4HCIGhumiQ9v~v8> z0D>preBODF%m*^K&4gU)8hY?z?JDys?YoXGP1Zk~4L1po@iBgRL}A3IY~ziIOmXrg zzG79jbpORoH1=lmhZfTkjW< znni7VR1=dt@k4p+zsTU%A2IskFBAX22fB<9{P;{1W`mKC_!n^5>ni^vKa6)I;}G|9 z)M}mzUQ6KC-q%3j?xHLYYU6~5#S9PTKK<}twDXs@tm{TtD$uT3vkCJ?Xd~nBr1Hma zl#n#K8 zF>FJD_WbsJ!;hV#0@g#q-+avmpX+>)_rBEPp|Z(e5T5@2-Z#YJE^i2HXTM73-$=!gG`VCLd|L%9pDD zzTyv>>Gbl7lKiG;8{@%@6sURDT>%uTye7D%|0$W~2tQRUef&4sa#TI)eaAI+wGF}u zokvtF8aAuN#?LmnAVl(n!L9e1ixcFlBR2g?UH|XjDHi$FT<)Lg=59na+v{Z;B{w~e zXUDN+7COSlT?qyqq8gOHNi+Wb>+zO|Rc32`%JBWwD$#>HzllA$r&@Wlv;R9q!eAL+ zta^{C%MzO&oDulD_i*RBtozUI{qZxa-ot2SYSSgG!S7Z%+~)i=;2(Mql2t3JGgR5^ zklQf7X{Y7>_ox5q;bRc7BEvxPhwE^Gbqy5Y{f(X0?I{6p^%brh`V$>ytrD|de9 zrDZ?iA7ah$%;bp7O%_DgFOAndl`q#ik$87>`$GE+S4ZZ9lTvYV^t_o`ovEeUm8)Sg zbX{J}tu}H5*O7*73bD{rxTX{aXPu9MjQ-(bmvpaL*d$q?z5mej6tyN%JH)SFmaLQW zSO~~z(Y519Vylyc3hN#D5ctpj9T@8;4$&4g80%%U3dJTT@b@lG?Kt9yKAx1@RPrMP z(1PVysn;Eoy+e<{DjrPix@NfN$ZZU4OgLf6{PArj8Cra~mjZobG{7-`&)hJAz82&@ zh|3X7R1r|e<@EHsN*(_D$Npj>cv4Vc(yMAkS9~@Z+B{;sRu=Qe`b+?Q*cECTKz5YX z{fY#_TdwrE{xI%=T)N45xcxJHB}LazJ!l}$61QW33L?NTk5)fzZ$lRx@}!vBy3Hy^z=S1q;Q z?%nVyt7=Smf%xq#OWU|JZA;J~GZPUg+N}SI>+9>0!UdNqeu}G8Zdm|f_i>)+Z+y<; zGbsdDF-5APdZY_WeqA3J>-d+%VGO-R{P$RQrp$w*unoW^JbDHefVO1?#EhMGVfn_C z`%#H+%Fq-5#O+y2AH-!=T&re zC0|2|gR0Ef;mfl0nBkV(`vL#dc4N@@!XgiJ1w z!;W19c!v*+oSg}lgmVjWWXYIu-$pV5Q>z;f)X0^>jTsAK?;%NpQ(~JO?tck?4-vAISl6LA>tqoE5M@lXxuW!)m<$2>6bwW&5Re&H z1=;zG%i#yiPlw97US$-uP#+mU%mmKqjIrifRA=xwr%*4p>$;xuz8%k+gcNW&g##C1 zq1H%2aJgk7-nOFl(UrUZQLz6?C1f05@|$P`KCVF-HZ=6&b?|t`?$KwIMpTXas~?#_ zJI8lf)=UiACZqmHLEqcdHUM)pf4UAE+63knVS(_E6!WY`Jdoz(H#O_AEk*ICT?XFP zz4jAVnALrK<*nY#B9~5){#RQ5k{24oA)eCpOG<~_fKjh;E50zMBFILlVDh7|^LTG+ z>-jLBG}8)S&Jg{5{I9<~GXbR5b{GgjA^juu5OV9ibGT?_nN6IFgjNU^K#hJ^^^__r zzLa&J>LJAUFKQQXUJRJGhobGCo7I5&#!T_+Mp|LZisz zhnd~}e5+983lsEO`uD8#%z`vrvV#Ix2PYn=%C&x4fo>SNL>N&fI}KoyA9ih*s{~4) z-e6&3aq1*IWndjN@DQlAapt}OAd~?C-&`uW+0Inhb>*9#-zU(eV&if~+afOJ4eZa@ zjo7wr!>OY_(7ckAUrA(yAk%h|zI<|7X+*?xuFB}m1^I>6RA{1@xjiBwSd~39tUY}e zW_oq?huLh0)xXDDV6U`Gz@3hQkB+u?M4K=G3^7pEgDnJI>3eP&ZJ$}NYcaXOxfCXB za?nnZUJi*T62mz?Z;&bq?CmT-&;%^EW({11^g5WJeuZ5ZFj}VT?1pf3v;!ea+A$7de*ry1M{r4H88*EQ2uaY{&=Mc;6%40Xu>zJ zU;Rsp#uo{|wmfIG`%+=2=2A9t*0cHBV%E2gC`aGA!m_ded|d8<>xyts2R!tyxjybQ?k*Z z5WVjX+fLSoibM~_gHp(TuyG#nWx@oo%`he=_lB-4x{tUT zG3rAFBDVU40)@$RFKvhlQ^-$ zMoj;vKIXG(nTxYdl(z!4M?SYtXPwiV^XN-4)s_xuC9othU;=(7HLT21(U)y;c9x$= ziFS}l=?esOmq=NvqesW$0%JT2&jBH9zM9yG*0nib_D%l&zr={BBdEEsehc-)vztB< z^%jW`JB|?AdNlNt?7GWt9%m&#c!EB=B8a<3={2z|>tUsDCXxK?HS{QPMTShr0T{3;yHF#? z^Lx&6gqF66kAKNx7qFHF1G^Bb7Tg@?Ej{P5BqDnDW)jPGJG@-X$$32ouuOv~c`-F9 zF~bECmyENxoY)mugyqn<5{mz^68AEq?bDQmA)?1z5uB0F2DE3u&l}uR!8x(15R7iA zUN{i=4;}W`J$H-jl3iVrU;e7<->i|shR>;}X(xxpu?p^=fkZDT#aeJ~OG8Ffc5gq+ zL+e5pcsY#t7u!P;u=zG*zvqf~%cvFoz*P~xlmrtRaw*^}0MKWR&C8fB0^ zi06qaVy(|>O{io>@#(5o6K7Oq8!r?Qbd{Oj*ADLb<*7-!G538G^g&Q~5T5Y@AjKc(l(<>7D1xZlx0F-ubB`lEZ`DHS{jq zz9IIMY=UVdY&PqHDm4`pR7Xl7$D%zcGggLp<>^+>aEB(cl)`z7$Z5)%1(6o~sD_q7 z$W#vJoEk3$T+iu2PrM)L!i&aOh6FM zB)03l|BiHPv_OvzZFA22uzjtp*7v)k1tac4t)AeBsqDVIotK+@O63Dc|5uLH<#tn* zd?_4eZ%2&HS3b_&Hno8@Rqs9K#6=kO+lnR^K`-Tt^v30EPS?zs3KKdRWdaF9r(L@z z;8R~{Csmp5yV73!FgLbKEAdW3h?dL4Hz_f%ueO;(I}_0RRrpd{hSH5G^tl}dSL&bN zfoIykUFz}G+=d=lVAbLdWU#wk`&cv~RbDYcZ3H?JWh?INlH9lWI!2*_%034NcwtLX^k0JCS{V(1oEW@`#g0q ztO&ABa4r+>gPF<^yI8dZk|!CJI@4kkjQ~P04}#X%?5fd_Q+L07J11%Ai;6&j!aP_iFc1u?ws);xT_YMEd^+C*d?D@&Sc4v zg`h{xp_Mu3vBlh+9wctA?G+ly(6byuK92yncd=IaC)jCC_$4@mH19qXwj}F2zQlL} zH>+$kfBIv@?AL;o<%I>y(<4~`{+5swo94^P{I%)Hzqv{$xDI* zSY=(V6b;1F6PGA1bwH=^JmskhOV?#qDW08W8t)cdkqc+{{GQC1Z)^}1V|w+bzr6Ug ztLC3pf(GEwcY7$GWsrJREEgk+7hds8@2N_chHDOvs&vnwuj=6|l+(yn$Hit5Y|-a2 zX%E+6vzKrQRM>BDwc&)Z8tT2HwFzD9lo7Ii@c62ar;4vPT4-xNxConeK2V61>C$;U zLApaKAPYa8V-({LQ(!uJXBoW{*X2Y;%f;c~(M=o4)0Q;wYGrw*$X!#s00JG~aAe0Q zoObrbSw=M~DOXf9p6{`U?X!QD^V)tHu{LLq1n7h7<(5CLAFO@$X1w<^&OA2>(d2Tb zL*DG%x2ksy&>(A%1q?*(^C z{BhFBZVR3(GoF2U94R-(mtw`RyWGdw8i}c7gyTG;#GxU>{A1*$?5|nfY;&)lxyI02 zPx$n%uw8fhfwW(G^@S#Sij{_u`PPp#hPKUV)e3S?fzt*nYi?krNpMP`6dGafDAWgvK^b<$(3^Q z+XK0^)B1Vx#QSEg$KMoD*t{0XyC)+*GFr(0q&Tjp{KPi03QL82E+_0o4MML}zA$;i ze9AacNzQ9?0ag(X35$l;BDQ6m9l0Pk@#x%&#kEER1MFwgIR5%9YrMM~oLRO*0&UiU1Q=M5yZa>I!h7pn zLOQ-p=v~4&!OV%{Cwlx-uQ}%f-r4<4Qjq2gL2~qtt*;W2irR#2`A1;`Mz^L*K_^;aj$EAci%kaow?_pnR~wHiB@mBYim736b?e=&^%PNIKRG%(DK3A z0?>n8p@o?|mNSzFTE5RU!T=l*l~V_(M{TPpuyz5G*l4Fu$M}nroTnk(O39e*9m2%1 zpEVa=?e$FlhuQi&LOu3Y$z5kSC8AJ#?}57_xz}T?F`zxACzvZ^t-56N;FlBBBjU6( zR)$`by!MIlYbiZ6ZydjWIe&Md8hFHtH^q&ZQIB?+&o+muCnIFvta2J!y!A!sMFPEPk_G#rjqAw?s{5ZR)*N8f&KhE6k3VsdD*X!UMnI$EYe|=8N zF>p!G^+jN1Xo1jDY2eqNPsl}wBhSI1#La+?^s1<7E1s~Tl{=n{G@_?ljY|fn zZu(y}R_avi1cv4B?WP4OM|rLvvj67Z|HF4sADnW@;M%13|0}HWg;N&@`=^gJ%x&Yc zH%8d0JaZBkwvRpUdtSB1$%13JV#t5|^TCfw$Q{9FPz<5B3$w* zP!SZBuWt-35{NDX_W#WE*J!seUS$Tkm{@lGXW`cxR?EJLHFE2q)$02wjpOda`smf@ zP-2YaSB}7zg%jd7>h?MsNeia1j~y-&z#BUYONFBl47Rhik)TpOE#VGAf%8DHIWRf_ zZl1o1z>B1X=b^kYf!_7yz%Kv;Q%PwHfxf`e5uanK>yH`>UpSX@!h~|QI{+|C9T9{T zgMk0+x(UF@92?LOrDZVANI#DRqA3IU9nw2lZ|5x$4)exN&#gQ#DAHmaO))RcRYxnG zS0CP7A31&L?!Iqc0%Ci~V9M40`Kj#nZV~4{q5boRZ##zy4c6N3*&L;6DqD`>OCv-g z;dNxdX_JTFZ^|Q*!w2~CX79{R!scY8Rzx_w4j$}fPWTZE zA^{NJK!k(NbAga{?@&PZiJ(}xrA*Fw`F=NVKxdqp)@3Z11%)A%EVFDu2ZKOc;}c5B zgcInm7{|H<`5Rbn!J*E&7tY;q&++8lv58Gz>|EB_!D&>>Mh)qiK!fZylC zgR=GDzVO7v3?$;fssL(vQNA{a>F@kCe2JHOYwMc6R?J=r@4rQ@{{xC2aaF$Dvpbip z;MN7gKvJRP%2&PBi7X4yhG*oXU!)I;P{Nf=?u(gGPZXv6Jn`Ck0Q4=?J3gm_+Z;S? zS;$kJMhOrNK%^1{o2vE}MSO16Hq*Rt3kVdIQ@|yba zuENJaRG8ulg0TcZ_w@TMAeBu%_)BA*ApAbjdJxq?9_k)t-zoh`((tT;zJa;|YXA_( zIJ%@iSEqT9hSC<3)7>+*23p3iLWqD7g*c4E4q&EjI`q3SH>tM35CQ{lx|)QbSNNPx>f$C%o8PZxsvxknai70Qk=u*d6)q^CV;$Ax(rm5K%wUmH~gMLy*N}Cr!=a(#xqA?J3p~PB8DaB%;rlWwe zL49FvL-PgIQOqS}^g@AoIkV4$HiWxcRZ7rXMdW40|`KNTC;P8S@K-@FDI#=6d_E4;Vnjn(A(J%@(Miq7?oNKkU-bsP;9c28|Q)aG<5G@YV4Kxg6ZS zGCfnb#TzLws-{w>DwmEiqhCPdI;5ces?b;0`HXuX-=H}HcCMSSt%KHZk!&jf6#14n zQ!mpIvbBG@OT)*MnPt*MprFH7T5j_{F2VXIX{8rd={xtXsu>4encye{uf3k|sajCL0y|zt!4o^GgLT z{}H(LfwYjYmnqJ3FR#gDHkPt|=!aW+?YShM)OzR1UT!KHBh@kB)>%MA>jhil!8AIC zf-jcgv}JxYTD%V00@6QU06BP!S#f)r!aj4*a!%s5-icXWH@Pph(+?c;;dnTtwT(}) ze?$2YO(SfE`q`Fm^IZ(!Z_^)0;Q=!HdXCo2aqC~(CJJb4pfLcQ?MOCP>rKlZrwIlV z>eh3Y$`{UJO&`2C^Ceo}?0xsWISru$!TP42J!yO@yuMcHHXFn(pp204mJ(faEG6%t zDcAfdQIFsXdPh~|!O%b7bkjQ7(Uk}*3>X6q8TOXuY5-AWw@34Z&$_}Qm>?k<{WOR9 zXTg|on>L;9A<)KL6Uq9H_1~|esr1bs)_=N+FO=N7%<}8G_MYJv&GiDMlg%!#BCe%^ zd6-h`&!Ewu(2$o(OMYEfYcqHIME+P@z90F)q&%FKQbbYQC}nSl3;>m5eh?Nju=FT} zM%*M3vqM&R%Io*@LlcYwC<%)?Ei8cGL<7?0jn_<$Xx(5ja1>7{^X7Bo&9^5wqw*&m zT8aX?E4FVXV;rbzDHIlamyd`!aNkDxXRQyNW96>HZ{>Lbsj73+8yhnqNYziCj0f4V zXI#$j3au&RENYIU1ew=xLRH3mt686MqmAytf#4w1pKo`T0kN(b@X@j;@>shFA8Oa( ze^}u&IFAuUCjo0Zj;63;#Kj@iAodxa6IagNI|S;D0>)J6)#?8iwq0GL?mGLY?HmyS zY6{39`CrMqAmP_J*ZW&--*@$0K$1$=C#sZE-+K4-GT>3fzB;OG6@hp$`Iq;2Ubqs^ zfj4;uS8Qal1z^U@#VP%ea7-h>TbJe>n51HYwCLCs)EKi?+wM}=8aw6P{Ly}_HC!lx zdAb^W+@~)H;dek7FS1w*_{z9NE|eoB?jQC(&)56+j#B1_KQOu?67s-s?j5+NK>G=G z7HaBN&rvsA<{_llGrI<$*C`nVe32o1jDjKTTS5TCqJZW3`S{rBaG|TQ=His5Ysyy* ztfAG@u`l<3{9xANbrj{YMk=nSN4 z3ilc53zXlBzx56}y|NzQnwC=G^X$H-QEj+u4;A5c%(B9Ybdh~AC6GXg{8Nh7yRuQ8givHY!x{kY#fJSP@XAtG-X2g12kH0=Ym_+l zzAsQJG|o5w^#YrTXVd465ORtkhY2;rDE`X>gO1A(5Rgf_k$?`5NxODeUmXKY(2RJp z>R?%$lW87{;FsM|9F+m$8;$%_us1w{vEz3H6ARjMNDetG4J+ygwwzb zU^)+(4sK(1Nah7g-yx#=si4Bkl*A|ncqy{%Tno?93l+F@3~t3;JlQu-$%?pnw%009 z%vc((k=sLE`v%jYYM`c|iQfVWS@GZ_l~QJ)!2$J6RbmXNNxcM;(Dx;TXhU0OWmncI zw2*=|dbL^T{);m)xABzG>cmC;xyQ$9L{PR>>%D4TfVJOqC#PzdWfxzSE`lcE7it$V zOy^j)zemEZ*w3C*+-k~-KdL`x2CyR7Is-efb>IvB*%eb7ykfz-Lb#`pq!NBY&#m4H zZUG;weTlTe8Y?7mR`RwEe?fx+>)+k6OW94&9{(xz{qPa6a}WO2z@k(|LpFq2{sMXd zBiY1)9#B$GM-Mn!#cv&TJNHmwvF;4NPQ7|r=e6Y^zxwUeIEcoWC?A~xP(Y#N1h4-5 z6a;ve+XUXa*T7r4RsboSC#CsV3tmb;cR!d!_9YTD{4ayP16{c*K)eM+;zCPYQk8(5 zxu2OHbB6%bvgm&Kt4nZADtaA$TtDrRBpNuU_B4c2g4+ah%qg>}XSG5<0&WuI)H(IKevoIeoK>(Kpjma2&38y)OP&6AqHu{Wi5R51g) zsBHfqgv-ALOM_bcW%hZbI8^=aQz-&e@v$RJBkT&H<6!704Ly?{|1-ulgrkjNvAuGR zouEMOT~JHvnlV}Sy^#_)sa60i%#-9Z@gggpP5-+o(1Lh#83uUfbr~`kv7v>3;Q_y( z^XbIdEDL@y)vZ9zo#;feW-n~^}_?&N?JZ6d`}7dm#>ZgF^74n6R9TFOMuc5Fqd_JU|^5;aVom@ ztF+mfTryot$Jg40ujB(NLzK{Ju(b7Z%adbg`F^^A6zh5dkzz+G=QLdIG?#+3uMn?7 zKTbtBV^GO;SSn&@wTzq^CUSzJ>lBK;fML~V2D8x6Xb|DHc&nO$L%7Ai3BVW5W0bBU z|KVi-r!-*dq6v~dH&e*Jb^GhduQT@g4t}3VRdNK3fQ2Kr*MVo(8rwzGxJ^slq~sbd zdbJeKfL_B0s*1&YHJAuY-9yC90s8=M#Z=t2VF%`Z-yTE*(Tb;J$gzv-*yW?Ge67kgDF&NFS-A z;GacB*!E^9k=aZ6-d+5cgQCL1GpG2rZvTkrU+UkulLVB*0*?W*z`Yekmf=nZ#~fpe-OCJkVGJTWkcvjBh3<<|j$= zG{Lf`z!T3RYFAdp*c*L5%QX{=#ymN-q90a$|Lx|7Cnab6DI-YfD3n4K8BG?3?0y`D z&ub2W%}@3o^-Xj~mB7H}-+)uFy&~t1b(qQ8m5=^3Z^Zh)qUur*pa395+2m%)_J#~P zV*H0oz$BOahh~ts5gP{O3gbY~QSUjXgra^>dfA@*?pRIsujhy)G#2Wz;L&=*F`JD7 zeO-Z?+^;9Jlc6b!J6j$8*Pm}$+|PCaNwEd*dQ9n{6|85tbk)t|wRAB_7PF;E!Nq=Y z#~*iWDRlce=L6h)#*-5AKfNKA7H1BXDTabDbBRH-v1aN3r%5OK;fUF@m?cU;BL{5f zQ|m?+3eVGyv!JTY!vK`4&xc5lG0L)K`np00QQQ_72BDq2CGiQnCjHhLMx?oZX?0tI!f4}SVLygYs%BzEL6)s_)5XTR3K=7t+zc{6osf^xHsf>J0* z3*HBOtUMwR1Hx+63c5AYc^>I^O0IHeb8c5r7!+tIyhDCtxM0@ruySV*c`aGlWc+Fl zqlpzSQ3lXV+U$(U@yF@S0ClGxI{N{M0!vbMBM3Eabg~;EPxDTSb#S&4mgkyYSt`IYCrk(~1$BTRv zAv$f9Y|&@AVZ36U6_iSrf$GZena4z zfj%rG4{o8?25hnV7=Yc)9rei$k!qU6ReLWO2wJ46hNOXbQfy>&T&tL{JLfMgiJm}nZ8=i^6zeX>fX zW|mILTBR${VY;*n+2&=yPz|A@E2ton&^B&|?D8C%-4F!K^KMCI{pu=($gAqW0b$g1 z@(xHu9;Ao_>V5hy9}!+km{Sw2(iKddSaYSW%^N%RGXl}h{IH!9U>w%Q4vM_jP!f<2 z#v9%*($%~NiYIX@F5^2GZ?E(4F`sRUjA<^YZ(-^GtZjV7ld<#fT7b!osf>>ijDSTG zM4=}f;bYV6LtbVAn?3sGhbUrFKazixo|gyytn;O+{)w}{Lvo$DFJ6TH=`;#6l*kQ5 zN1>l~yR-L!Qp-w6d8VvFH4s$ca9J&(xV;|6ugiD0ih!Jnp+?n@%u22UZ^R6+{m^>S zghRSpQ3FWmN>l=ycyPCf3`FUER9P*;1?mRiTKPl9D3GrX*K?Y4Qy_EF zrAZ2y08N(zI(>jp?Pq5u0-}vGr*tATiFL(7C{E1s*7HUbh(GUB3e?mt7U_1(SMU)! zL%sl7hFA0IT-sDZz2i493t6$>A!~346c+_(>zjNpk?ShGC{?xPA z@Z8s)FiXV;(gb;&ua-0rJ*ortB$OFBU*H#Oj#`uLR&u@Z0&##sH;lhhW}Z84?&kD0 zI`5++QwF8ZZyfZ|`bY!cSO;7*E{l6o6BGb8x=*|V?6|le+FXpATe)dPHV?r05Ej_- zT)FEGfR592ha^}{1W&Apk>L9eW7P zXY2`B+*~joxj+>gVMe2Wp4k0_kA*(kvhV9)iD&%n73^;Ma~*9V2qvg~4i>7g z?_N|TAx7{<<+98{F<_C;A7(AJt5<{R7d7FGzjJo&B?D5z4zy}jIEeJSC${|tINOym zyrli(B6BIPe7pep3$Jm)r#AA#aEJOlsc0O8`CY#Q6$G9k&1x43vZm0kAS8WZ1z2Qb zJ8>}8@^{P-R4nuRZWI3RoC<|3_dIgjc^}GBK6EcE#|ppNHY+9`8XeSnq_jX!Z&J9X zrL0mof-_z)VJ>{Khh(0BSE{tG3>LHh_LZ{V|17N}0TL+tQ1{-4?)7>nf--xv;;*KI zC$2qGQUR}gIM{J>XuT0{RiRjzr873 z0F0tYd<{9d6U6@PJs}(fDd~`-t(|vVy(Se$H-N* z+wT_1qbTs>+Mg&Q>fJZyqT2S{xAB2Dn3iGE573*gWbuuPigSce@Z&NGPn4W;K~e9< zv`V&&?~;pK<&Z*LZ+=6tbVf&=PW)5t!ril!RttPt?Cu*M0XZ&kdBk0ay+TwpaRU6V zdCS)q^mJ&p(GrtksJ({I&M#CmpEce`Wj=%}DJ-9&IZI>nzgjT2;4l8vbq9Cm1m}qJ zVj}G|5pd9eB_2h48+QR>TO4dEqrNGh)SVifalEPcmDs&=GzRB*uj|tKk>5J$BW(f! zdm1&r_YD-q6|S0!%t^vtu7VacW1005X`QA4dnpfg^>OLpp(0)?7^ZyI{o`KwU5eoT zwJtyPvbToF->val(HbN1Pv7KEU0`^YHL+>1-KQw}%hj=ZBR8QGH49y^uVSr;g1Qi) zu?=J>F4J_+R!A|tOJ?@=o8BD%Jqu);Gj8yw+mpyo>1<-)`9Zh))LlBtS;jll_UQw4 z1|fdedm%!_C+SXsccRVR()TWGG5aM&o>tvvbkWh@M(yj{%D#J7WA`ZjPsli^LFow@ zIf1I$yRz4)nsC-bBj1s=ps6w&SlGuo6Iq$3!8@%{%qRAaDeja7%*cLlYVFo<*LmfE zW-9Za)`=9Rth4!0&z?dTh={;CWlF3O(fi<aLGlO4yddE!4fP%PW zeX{fR?}*#Sx7szj|8AcAoy|)DIzn7E#(D6;y*?EqCH}1{?uM!!X3!0ybQ0KDD*eqR z=U`096xZCLJ)2?y8ytzMv)NGiO+q7OV2xw_PYqUf#T1)f!1WQfyAhqKU|Z9Tzf$;N zA@GqLt(y1ND%eK%%(rBN)CRadodV#a91&-8s!t+UFODz_t55Ijth^31KV^I*U+Bhb z$vg4L8}|3uZrXp)5M+Sjb$$q8x?(cdsKDsOw0OC(9G;G#=~?r;k~#= zhr7*;ry?(=u~puqy-2RZv%L&0gCkz1R(w)J4;Q07M*VVs!#+#UdJX1ON{4*Vpyz+I zkLsWQNYhsG-zOK%p~JcN(DBnLBccUUGA`xteN_8d`CVUM^A28g65J@+XF_L3wfE4q z!xpf(#3;1-T=elx0h(L%FU4w(SukDNeY*$j)rGYagD?K{R{lpy`80)eHBovD(Y#jJm>Ol7RRomG_2p8_ET{lhk1Y7p7983SyZD(s_ffO!>YtTPSvU<9uyqgB!B65 z3%=}|qddf>wEOHo{c-!rBm6#}lZRoBA?^Xc{;GQ3!`eWjGW#Ki9XZ#Vj&$4SET z|FY4i_ha`j-{xB7`Rl#HlmjNrxm*p|M|FX+-a79Xi-(Cs<2xNbg35dQyb1RCv6yO0 z59A%3@4Cg4ntxp@P`ouuS9Vn^74y$`YIi3Ls0OLWdP6Grj`z`{v*5Llcj%=qf^Al3 z<9GdF>bP}gooX0!dHTUM*}X%%{d(V8SGU%;jFliNo3V3!$`(;7BN=Ud#*&U1?jujg z>`Yd>`<@pLXCEr;UOKZe?C04qqSm@qyJN##x%cD$>EM<4r4AGZ(X?t%`GxOpnUd~) zEbM*iY;GnkJndir5nJK_`qbw08hLdr8(!W6nQf+O1rS*{0NL+(AhV+HzpJ(-vsy{n(8<-ifnU(x2+Vi>A-aQ{ zBD#S@ydD_awchg#4F5wcjZ`2$C&P@eqg6wY!!GOsW0xhV9?pHdpn7OXbCN-&+NZrc0x%BGZGe?4ext$%04$g?k8KWki>fM7U9D9sVR>G$jBxINSxj1V#`u$c#gT(-^6 zRE8PX)XRCJ2xVO!OD=B7VvB!&`AtWGIhKvmHrApRS3JX-O*cYMv%m`rc5#}7;+uYO zu91iCB2VZs#Ms=!DfHa z#%(|`G;=DKQ`fqnw?54e79mhOiEa(YjWFpuZShhYMW}AE2Vd#65J=+^zZ}K@(9e?@ zbI~{p)K}h=2l22&ZSVnyk#bLmfqd(Ekez2h(Fj9@?xjBY82F>%vUPI?Nc;KswsDea zUOFZitVMAFqq3cN(&_16hVcSrd$^+R#hTGRfZgFYVDSJqS3dYiZp+tVIfW&B9R`ikKNhfNf=`=jdlT46r5KR75;h=ipJ{yHcY*AFl#JRS!E@q?f6kuKPXpX7sij>wCv0zSVb< z(6~4LX9*zTR%t5b)Su$Fv4jLZI+Kx8ggfa}e|5*uD=B*ZS8TvnQOkL#Yjpj% zs@V2SY59}4ZRU!%8A?+&Gd#=RKtu1-Lsh-B+xPXR$3nB9h*Ld>s6`-r!hV`t3@_iq z$1IJme8)$*j$!-Ec|}UJpSow={Scg`+jRKOmn2gy*?Ssg-WdePE=DMy;(D_r1{EY! zxwB;|oAv3?g5ZT}yYDB*(YiUh*CZTuwM@NWoa^0F72P>)LVfsbJYZEdr z=5wp#Fe3H+k~b%gBAJP{2uuPSZ~Qs#q3b+mh;l*GEGwUYo(#y%BD+B)Q%^%J3I7J4 z^$vZ+$(V}S_>DrZ8?rVkk_smu_~IoAfugfy>W|L4@)ZeLRtZM4=$9j_)6Gv57hn+o z^|7Dv-MyY3fj#CGHWEm4gpF3qkjq9N?peoUk9H@%VxfDL2Ae*5vQrj4<-U{4J_Ng! zHQym3HYBj(1`nVAduQDAX4O{r=`)im4Tao6Ww0jCtz2aU!V4M6xS`VUd58>CjB<>6 zd0}BtxDR$5bC{pc$DXC=LGPr|7EQ2@I6M`EH-GT6`)RZxTI2?~7@*?aH->nlA6 zuUr1~&3IBi4c+4+qV+AgdY;Z(&5T8O4pl}D!8BkYWBLZgEF0{4HR2`Ph$1mkHg@Sw z1NnK2yl%!GPlvlSWiL+PzoUoIffc>B#~bs%xKt{Fkp^iWE3ZAKtv60sfT60%_V&KX_V32Mq+}s2J;Q^};NF3^ZycM2JRPFA2b4D!-Bnb>b z*4yQt<8eu+caTxgOI$}3Hq5`lAp}t;YA!)(f|bi_OD4zH-y0APz2xnizYR4pfH(Pv9QvV9GQY}56Gj@aO;{|C zEJ9V@d8GYiYscAFG(i1Kjr|U}*O9P!wbyY*AyZRf$qs7nFEiuM(4er^dA=jR>p1=B zO4HD|2L>mhPB<$t-Xi+*6O0&;X`5`N4(4(@3w$u#+OCoj|8mWc=Qb4mdlDDQ4k( z(h{rq$pW*KWQ>Z)9JRyVsowz8<%4v1@VoKFKVL`wwcUtmd#RI}av9;mM@!qtW1$@z z`45&aFkJe+6blb@m!&@81%~7}#+a5r{BCq{+``dXX5kphsOZj6Lx*S?H@&33MGW0m zvD3gr$i+|46H?CEJS``0hGu|a?(&~5_Z!$hqiYDD5-~jT`aVEzrN@9fK-1uH7(O$$ z{y5osf?&`i>xEt<+t4M4?(^6rPXMK!;)p$2bBI7gPte={ttpnC#;E3MBouXAvM9BT zf%W##b~n>@+DWUo&#zkPSs0SOdyQ`Ti6WqAV#C7@iv~A$&Udl8LPdUCOv6IerU4Y(s7KZ% zU0Ofpe+hOFDmAeu#`zbbqHfs{RhPREybEidYst*0eNNFFEem-U;{_S4jIF0PB<{h- zUP~S7wXlMShX;bs*bU~6-gjHSNie}JE3XCrvPquumg&Gs zifUF#anr_dlw*@s{6&Ryh^DXQjyEPJCnlUi@p=)R~>CyNVRnOlVyR+~dmw^P_U-EeId%uDMn1`Wh&ts1H1Bm{g6q{Z}_vRd$T zwO_@LD@Mw#K8HkhZ-KdAXFq0Ti*&)VnJXhuA7c5u#0?;rI;3FiAQxrm(sqOG1?S&-~Adf5npIZv@EE|3bO*NUQHRod*t2e>C7^k?!v=_!wa_B5l^h9gCd8ebQi*2@+`**jYf(I1`sgHFG5 zj21FMeQ_KpCS`OLqhdhGKB9U%ObA=qRkod@3G~L4_QJR_GI0YFu4V%I`E~@Z#%IMVc6A}DIcHUw(BI%W~yg^J0E800+nERzs+)Ouh-Oo(bjbT1?w06O?eRgBrY*x|CS zJkvB5_wuMNzrSk%Bv>n5$FH|(wnqXk;znvHu>$nsH{a_6wE#TczGdYfTO?kF1v&## zrKKlqAL$l44uv_*gfcz^!Sr=fD^bheV$bBMiZmvugVd+6*?(2M)tV$y zYs#QIxbb={alMMv!$hO@t+XE==yJ?8Z}!gnYFM%E0QG%{>EW}5u`WT1>ty31$tDHw z5ufxoDd~Z-L?WuM^22=JR`u2+y^trbPa(%Hd{B2Z_C=ZtH$Yi^1&JSA_|26Pb8 zI`DzhRZqqjq50LAQiqr~uRaCx8SXb!C~>i^itRCUDLnA}OoAgupDL@jcn0yrC0-)y zGgNdxgrPNVXfP<*9d}pdr`zT$GTTNT4!1$_V2SJX z%iC`&)*>RaZ@Ealynre zkUGF8AW%Pupbr5n#M0+7Qr_c<0Zo(kL%eQZ*~T#yo(rGw*rC~S7QT~@lx!HmZB0FH zLoR<4vz2*#Q`M&QJeze(bHsV?sD0}_9zLi|)M)qJKIP|^eiRdCcR1Z7LwjoP=8C8UhlxDrc$)y+= z9i5GRmcL`p_T`QCrza0bAXj4CPaZhiww#|$=DN^o?^0dn()G+!o*0{@l$)L6R1&3x zsA_vX8b3+?v39j$Nl3_fXyMhyVL7}<#BGcI;SGn#p6GPsC%1fXHTCOWFYWBwKhLR$ePP4YHYvfPT zi+fD{KV~?TW)8mFIreT#K9z3Q3J!=|`r_wvW4NA(nWK(3=K&_M zLypUH0ZC}S63!)sAMVA5nH-{FIgy6?a+0M_wdSg!B4EMGy-d!0YtwR~66woxs(#j` z=mJ=ZyhH`3aHaNx*`^hc3YHf6X;3V=ip_@(N$OSlxFKHxWwVMUMc-8`sB9+U;oJ|0 z#t5FAp*3K`t#bCQ>EN1-m|;7LUf~}u^2gwyCK6As`!UtRVZ2B*Y`$UCW2OE=U z(oP+CSdrXgHe`m6X3eZpM{VR^MpcRU?o6ezq49x1;|1duS!LDw7TS>dn4Ml547ulA z!)BJ+py*^JAWsI#W+sJCki<26oT3kUP zma-m-Tc$4~E<>)ylBya?jE`U2YE9sq8cTR7vIkE8F%g==@NVZ-MqrcZo-3ufn_?0S zVJOB>#{$aUi;dubk@QGj)U<4AC)L%UsH({F^oNtM2ke*l=EGchCJ>99W8|Ylb9KG+QI)Ib>B^CVBNON=QR<=J`}_M70#sHM>UW zgIWo6L?NovbO@r7)y|`J_polDMR)k#4Jywy_H|Akk<=<&RK6XAI~Q34#${}MoLzcl0HJ~uVX!SP>Ot~WBZlrITH;DI5h^+1KnBVhB|p=T z2PuQV4b}PhOAm4(x6-05HP{ua8`wL0?_g{89dKr3ZpZw9vM- z8<1e~WQ%o@ry;b^?94ZpQDP-k6vagsW5nemBwpLuh?U9qI=JxdR|uzTh)6o3=9$1nS-YN10VU$e9MsDnFK{Z-ySZSK*EGdOLZP-mK8>wWX{Ah`(DoEnxFO6EUZZ zKRtvw(87XQudg~helpOyHvKvBD1q7DH`;M$nCa@Bz##>bu?lAK?!i=hY7B93hz(29 zi=7KfP`}=8Ml3zxnGADHo5kD6IL@{`ENu}?pYgKU2Z2~evzC-4_TkKP0^06H>ho`o z-hW&O<>GNG#rb6uq$=0mK%Q;Ct~9uggvgkoKB<7DlBM%U{Q>7>3Z2u-cf4Xj4iXtn zY6FgmD@HF`!RizrR1%G$~96=ed}iHF*k=6)Swt z#4*a)Keg=FqI(wjWo&dF$@^my5YSVIukk}S2&4jQQAc7}V&7(ju4Z|)_$-~wWx9{? z{|Kq~{=$dx-45%|G6D0wggz@j+$vk!vie+Htp(Bh{mv8bP=5p<(9#D2!>}lc2XlS4hfnL&9+`Q5<$V1o#zMedN-?_lF z7iYs?>KjE!8Zsgppc?tQOb}|2;bQdKTKU|F;UM`31XYtpV~Cy9`tlVvpX*{t7TYhg zly8(B$mN@yrLV}Gqx9H(D$4On>B9KEJ|eF87p z>`-Gfl6h5u!q_{86{?Y+KN?7~tH#Lx5=18Gn3!lfb!iXXYLB*?9;}XCc7J{HY0>4% zhLXVQlqz5j_9sbwzw+Ox*pmRIrjYn_e0PGbo#1xet8kH#ryW(ueE?#t)@_waouS8{ zG~yj#B*OYy&m+?cuT1ypW_zOMyGylwXy6nSfcCBg>Q1!a)@rEtM@kVlLJPt%bxv~s zl9)_jM6_KHfQ#1w!Rp=F82#ZGQ-*Fe{ebTbH(L9!*+l8a&n z7FlnvBz$!{luAxWdX<(V`C2!4T#4P*MQSBVuE}c^ zc7ZOy-r}xiTRxx-tfHy~gaxXn=i}N1ho%-COR{;mgI=Ng1Vg+LRLY#4jh^h+#x-C2 zT`H5znfP(ANa0SC&zsJN>5S9dmS31`nv3LPlyZ;71uhdv%SJsCQY9%FedylV!#_(f zLBmv0l$dVlRxuxl@!v(RwM350o^QOU9tUvev6q$hk3MSrP&CXmf?SGuRP}N$2yHY? zEHx-zbpW&r(?Ipcnpw^@yycaQ4qv0=0524LitHLZiS=8{R27RnP}VR=)U9%`MruuH zfA%^AjR&sgXaCu_Wcyi3^vCGeOE`cy??_d5tRBOzS;|XKUpJ=_?U9$Pk)T(6y|)gAACMlqfs&dz|jGLS1ld_gd}oV z83-u7_g&B?%_a<(RfHtL+=t#N8@+Ch#cBVQDTsc=?#4?4goh}3!%2_YfzOQr0nTLv zZ6p(b^JV2uCz;Y;`dp7PvlJXvTK;JHEc5zPMhE51=<-v zaY1I>C|_9=CJZ}Nf=Im?b~Yf#t@Z%t4e0hEsh=!1(ZYt8=M`X5uR0Nd>ItAJ1Lo~H zqM5Kb-9!ZS6&220*g7zMO}04>3>GdNnIMoUY507qyee!U;nxd9w#jJIQX{d@e646D zVY=}#(OAUX=chk}9t3{9Zf!z+wIuRxK5}4*67(k;U!$i{^XY@Z%)3eIDiv+8chxKv#gUL_0G5q~P8VSp*Jow} zg+CY+U}tb3Y{LXNyjcj%!wwZ`cQs%>jGAv|6SgLA-hsqOE(~qW9S%_yhK~v8n@yeX z%B~|+f&8?QX=G%@$Oam6+@`-9+yGE1ROGkn;nWsro~+RRedZxe@Wn_`NaYE$ih z4LO!IPC=h_BK6%{k)$^Lt_`&Gb>xi1d}R(#5kcEGfVZ4DlNSCIqhOx3t_HC#_OA%n z=o;EKjj)8ZTxwBY$AO$vO^0dcfAhNk$~dsV-9Zw8h4@&Q0k&gv{>arqND01E-AisJ zaocPdGy%sMr$)Sf@)C&G&OYZU1!+hg&lX0X7n_;p)o6$pfYYmbPA92r6-mFM1n;Ii z>P4dii8F{mGg%74La0QzR9>?|U3DM#h+X^QH8&1rrf{22*^?DczS;*DMQ?s_<1;ID zz2ACfXSGEX*k1o785J3tV4l+fkCb{TY*6iSyD5>+yHH%4M>;ee-O`Rr9Z^2Be6)oO zE7kyKO?WbHWIlD3f4mRmE%7~{`DugOYKpU!78-}qZP8T~jv^qwDi7)DF6II$aIrpX zl+TD{d4**US;PS4_ zly4VbOoUtbb6Kx1bABF0 z1Wms70?c$x)<$~+)P9{@nw(W*;Gk5{2>CCM)xx~ihtIx-TV&pVEEX8Y3hLdVB%PDi z8;Lh@qg6$Ir=M?wBDt@|ChbeMiV(U{<31iU51mIu<94${Kc%Vi7@UTRH7LZ*)KgBg z=SbG{?wPiDp6S*^*}i+sa0@yHKK@rlpkBnoApi%+?`rm2s_ny^)ZuGOH61EpY8N zvB+bYgY#^FumLo5gMzM7Ie7t^$q)y{_o{dI?Q- zgtrv=eYFDV9kj*+d9P~>H1XJ&p2uh28lg>&hlJ=G05{oKKqxwXH`Xz?3JQ>phmGdL zUnG!?`95grVhkJY%etorI@T+iqXq4(OT%&7g<>4UxV6XhYe&)7|GCER--2WM6s60M z&+lj1Xo|~G@>imYv|#6QE!Spc`L;n^l6*qa$-rbsmhkgqktILk*DZoCP>n0ZP774c zCI>0}5J97j%iPmH4sYj##{X1W28uo0P;Nz7C5pT?a(hr%NMeZ32iy7KF=k|-{j7zQ z-12Do(sGE!C9%HMzO3mv@` z62wBo@lS63bZg#)z#IY}eHPwbS*6A9uycx-+{Ti;Jg-yV&!nem2~7eVcQ@fOxqZQM zzH#ncNe`aoI={hn5B!4R$5YIanOc`cA~JN;gzAKJhY>^egI@Vp-6|&q4T<$9=z(^` zWu(^OcO#_r3UF$p3C9P??!s?4Kwdk72NZW;ut#vXKG_|vRDFwlhv+*-)x6IwB_32a zN@u_=5F`+Zrx@|{7_4RJen=QB@eHrSFwuC+V{bG{Ldu*``GlP8yHLf?jfcF=K5Kgh zD43H&dym@pg}5m4=_C&m=J19KGv#jCeX-_>#`AWFzD+NL;`!wF;50or|36N%#+6v7 zxD~Ji0d}-kg|CRtHXq-Fqw&f%E^&@CL>d)!1LHW6b028h8~M5q#|j%x7>-8p$a1q3 z;^%u>Jp8N8nYg7pzej*VkwM&2&d`~wtipl7ke2qggNP>+ly){0k$n^@7cY})@5=BN z*mgvG&Pc#CPM?^WeDn3JpV&J(T07yT*Y)jID z=t?Z8-sJb`swm(l8Q=#kBZ}Wa3;thw?->?lmPL&!mI?-1k)~+~@gzO#hMxn&Lh0 zIs5Fr_F8MZM@ZOA-(@Y}^(H5dhZaqyEVSY5j-FG;U(~6>x5dC)bcKS3@@1iph{1LF zyz&RTjAqQen)gcF%1}I5lW(&7E>SJt1h*5y4Odzo6xze%Xu6{HvxL=;2x2oH(C)}n zyv?O;VT}`=^3pX~1(uc)vy|HHUz4F;k&S6_XW!(F>*Q<<>HM{JJ0<6?bQ58%r?wMCXgGsI(`^6tk~lu(|9wp}5b zz7@IaiaQ&$4*671A-B@o5b#9})f1^=0{+m)oO266ho5zDXq%^GAP#?OSvq|-bI~?l z+SnMx=JE4OxR0FKf+{t}L!|{~j`dbiCFOBV{LO^3tN~})cJr#l2*qPX-6;jJsneVX z2+$c%m|<&#@Pnz*Qlyuz%5iZ?W=?q76WwPnUA2NXApbsODk=TPy9tPUE!3P+BfOs- z6lTA;ShnwYxKz}V+0Vs1g+5_q%j%9lb+&N-SA*4hw=Gx6#zR+`9ibv+z;Cr_$Zsz6 zTyq$i>mA`Vo++eTDBYCDWi>SkJWHqplonmO<7dPrh1BC#D^JK=-H}S~Y1J!XNjOWorW+gq^*uLe%JlUa0 zFI}E+WPO2v}+Il#?!+E zc$PpbfcNCB1^6E>l54VYdmhF@Qh#hi+~z7 zzKz+l2XUXK_uajRW7@mlLglx(jA10mtqGGgmv#_9Yp%1A&o#dHBi4W8iH`<3OVQb+ z8^68j=|ha0nd`2426xqH(ZIsnI%Ep$!Avw6TEpZLwby7is;#^K)Fgi9veCv&?Paq` zb`r_xoY={p$r5Rsd(|VC!dE z{CYaB1$7Xb9{D*}wD7^bT98uf*sI|OfPs}}Qd>IHI6Q<&mk+oD0K}zae5P%=Hb9Rp zrpl+ot+H;N8^ffVudbdvxYj+GxqK?!G-g1($^j{}o9KQmtGwP$!;EPbW3gXpvw2Ir zBRzm^b5R|2GE)UU&PSnTo{7n!EW0!V-R!Y&1(U0GjsL-C1Jh|v#W2L%%*DBEVEd?E z&0otcA8tBVW}9I!2NW5FmMEe2f(zQXrb*>=rH<`y^p}eq4kJc*iW3M;j@fm))~-6K zyc<}}b=mP{o;Hr<&}IFCzP8!8Yg?Qp+Ce3Fbu5%~n(JCsqqHq5pWbetI)EJC-T5ez z)ng2ZcuMmF3%ypd0HMQGzo~NwrI&v2sjI(p0sgd8Lih$ki5Z#Rc|HJQ%N=8~Vf}H% z5t5m%;R+XJ?9A4+P+;oINKXT~tAZup76cno=Lt?BpM&B=FWG~YMp}Z$j?h>4HEw9W znqktEIi-Yhy@z-3xcQh*SaDj2qVWh;Yx%1>vcG@T_i+0Q(QQw zO6w|_A31T*t;Pey`hlJn+NN48wnnHM@)x}FTL|S^skfB-to`BBTO@I}h!s#y`3Y8* zdp{{5yw_b<AZI2DcCJ5h_{#4{VXnSfYBmRlQL^M96U(HH~{wr8j(w=% zQBW^(+RtY_lgE59y*&6>q$r`iTYBc$E;jnID9-S5=x9;K0n2RpRy&+Pw~N~T?#j6G z2n_5#s^u+c+^I7VFg^V@x>W|*QMjbSDxam@!Q#Q3Dh=?xPkmlFc!r%YV#Nd-Q2gbP z6ay+o(cV>mTS-W@YV9U+oa~UQ#gp&nI1OXcn>{uP`EFk@h)loOv`D!Ys8s3dfH4r` zzicLYoo=MP@pcc;4y&WzEj|6$5WpYbB{%mP$nZnmchov|=utoGOO5_oKDE^(2TI`; z;Dwo@Y%?H>k9Zf|JbDW@9gD9mYqLhq>mBRx{OQq$WGLXN-X%b&7BN2h;@eBt?18+R z2BcNtEu~C#{sQ}1RF9h;{-PRexjN7wj1k|F*&VMLix+e8RS^uw_zby!&;?l6^!rqM z8UVPY`#2`SZpm&StnEHIxzv~kNwNMNNna8W8GVVp2P(eL`@1tWCX0KDECx{Evg@$r zTQ~yd-`tpN9pvgxVzOME>A)=y8D`b>(aVTjwd%;2#scqzL8{-_ikyzeWGb|Tg?GvO z>SGSPtr*EdA2qAM&gn}z<^Vfgt4Q`bv+9;JkOK3at`OQH6YJUz7NO?cd&M}r*g2== z5-w^EQ~`x2o^vpnm;C%*rPb(eAa56}cCu!Qh+Z z!$N2UnQ3*O2>qNw>l+q!!$4WVEJm`Ni$E!{=*ZsRhWw`H=R-a37O~#5UR7=9qBgz; z%+_!Fhf;<;()BRAu!!A z^)9Q7@c;o&d=jOy`^}CPCrj7Wz9y2tbt?Xf8HsRAI)%SYlJI@J9BNX$_`Xx7tZh*J z4D6dN^S&mhp1n<3a4Bo91DJ`5!_IcyP2l$UXwQ_YlXY#vbcjI00~X`w9~>5w1jJ}& zrABt{*TwbOkrnfVIkt4qm{aJ@#68**REu<9)q^#WgKN(ea$~QdVs6(;j}2s&GrJnL zlG$3B-U$8+LCEjT!e*++_V&?5RL2m7Nh^#mpB*&WSUw(tame%w{HBab9RQWyIw_C) zDi~Rsj>|CkAHVQa^(n%jF`|dbl5fDV<0e}wIJRrp&vf0q`8XM{x*+Eaw=+k!!Msf} zgD;#rl$JOg4Ti0C{9Wc)DHMfe@4HvR;E{s?``bie^xRwZeB&>4Nrh|A!h{GWbgHEd zg^Wbusq+{@`b7{yiMAdU2Zrx15l9&yG;8P==xo-W1;Lpz%uDfdhR}?G!BcO1Ng2{W zJ~7=}38er9=NWSPXMWri_2>2uly{Y)zJ1CF&{iih`B4%x`-HqMxZ=*85RPIxX>8 z8~#-+#-sZoj_&=I@t{XtPYKd zkG-Z3vFFm2o1F4juxwqv4%&wXMxcXLn49iXC_+D?K5$uGx8q2SjN8gcokA@~iEY%&kF8v7lP~KIA2M(w5k?r1}&1Xa8jVYfYfDoaO*|D7>m8Ov$j#om8~=L;j0=%wYHT_ z1=fUq5zv+%WgkRecG7|FNx^*W{&@WJ>I$sXi8Ebv+p8L?&*^6xc(-WR65Mg zx*r3#=w!fBWX@tlfLXv0k`_8EUi>CssDHJBDJClFXHtK%&UvAokL@%$C-gSrS78w{~BmCL-RTIRTdIgX^0x z9Z3Pyup;*j5Z){+ORPj{tdO~0KKqKoIjZ{y`Rm48c3Oj5FN=~dc#hjLmJFvfg&&c1V(1b+_C0%&I8iKx}WUt*cpq*=l1X zY#u3+QpUR_uV^iFaLWS3HEsw!8E!6(O;}_UGqB zdkxh(bAM5>(^+*OiB%t{!<{2FEXmpC^5`7})ZekN_6S1$1dky7`CzQ0mg_>)mv`ri^9c}*FX%|oDE#AH1>OyjGv zM?i&jS?@D6Utk)7JV7q3`f)jW&t4kb8SO@PVO@xrl-8to5Jbe=@)D?hmi_sudW>VX z*(6qqWoQe27$~$$P5y%rk}~6OKnzyHs$_C=!=dSr)cQtziFhtLA+ezC*`sb(<-?F3Bx?S(Buewv+NA63wv#|od?Aubk`=EbQ;nJOdk%+B6TwFX2wYEEJi+o zX2eh~rS-$o0=*gk3{}@PS~fowH?&z5HVW>kFu!pTwR^%HOjPf-&j_ARcP8N1I+m!4 z261te*vdH%=2z}<>Xmqc#xtulBV}uT^-U%2OuA-S<|QkkKApBX>)8IC<=57Ix&68L zGL7u%u`)Rqrq0dbSf(>JT$1g-x{pZ6Pnde>esru7y~#-w)6xxlD0i}gsv{1X1X9Ww zZ?io+KxORn!s2)?lwq=>3Sf|rRZ;F$w+)zkO=sni_#|+Idj+0ihcH=MBFc$3jw&bLj(TVI zgpyS$?3}U^-1}YNNS1L{HaZD5rv7}RnfLwxvuI7TjRpqb0Fj6%u#@gZym*fEJngYZ zzdqztn*D5dnqf<#AL%hV@Nhb$8yYa`y7 zj?Vla?Iz(`spW3`cweJQgvqGOx^VbF}l zi~!?K{b+f|2 zx`nEogI;j~dbqiKC)xRtt_yBLTttO00y3u5T z;@U~TSJp=Ml|2x>f*aN@9Kc;Ln|w>S&Fw|-N!Fk5zAygDkzR|+Ru`hbTWOQVSs|>ry>--hRVFl zK|d3|+IZw%eD4jifZ(dtU7~bURJ%5-|>bPn5k(AUHh zcq(-rz>*v&vSM{W9IS%Z^c%g)ok>V+d1d7GmITG>Q&9`9^}1C_u0yv zA9IqOSk5VuLLGLW?Q6J2RBY?|O*C(drH8&GE54^7F&Y{QrUQP5zs`ha)QcNUd?+`I zidE$8{-$lGKgQApeWrBa@Fj81HCL3w`m$6cSuRdM74A+D3R9mT@#{RRo)Xl4+t9#2;)|%OlB}DA#=wiTo&p^c+>79 zf&8#y0-6cBvWdn=|AMstdkpquwbo-lrcQC_k+3RL(z3G4#q)NIJ8j{g8`Y)r~? zQ?gALtgaw=OqhQDN}=OHhg7Av>vB}Tzppi|52H!t0s<>^ zHcC0OBfz$AL4~>Emf=e_oy}lI z;ysybz`NCYsHVj2g4~Bl-pPX|v3z&eB{)hL3w#@~#K%as*OkOOF z9Tz3X+IYw;IZ4|5wgMr7dnZ!7BDs@GDSocIq|ak^7Kew%!9ldi`1Nv-5vOI2&{G`71seivwLKZ{zj523B^vdb5k#0cP28nZ0;UZ{MuMY+5 zF%0B@$8ikJSktsYE7@JKJFmrm^@KK4eP%o&Gnm-@!ea_Z-@t6lwQZaV!yo|Bh8!-8u$L)$!9O8`kna1_9cMp38nU(-tyy> zTOUrexe1=#3BH+|fvVi`LC217#Pue>+4_Pn5)B?OYSKnwNs&qe*{V6OXFxNuI>@Fr z-?nB;f=Jn=Z}`pwl{K%q^EJC)J+>XpFU9B$MY&tD2?uqMXyV!@lj6!d29}2*RmaU4 zNc~)nTt)Cku#_k59CG1X3Z342wm)HqeDFI-ZNYAvp4OP0P-Ou~>kkkz-x)}6-%c_z zW*)!_$t$z#bmzEbTc%Ku8a!!Q((&K)J$jaMQJ7S@^@DgTolB3 z7SOD9`GBi{psdUoyW}>f=Otl1XBfaY1oZMGm&&X7-%rLL$km_Vr!_R68OfVk>nf+A z*hsoo?R=tdjc%Ls^o8cL5QC-#ms6>J#2~LdhkGa9bc>#fnGpZZItpG$eiAPjAHQc2 z4;DGFo|k3BQw0Pe4QyRR6YCy}L+iJAP+{tvDJnYdw4o><3*K8Phj)H%$5jow9G zhGcwc`bf)P_#^$%87B7hT)U{|nJ|B?O>%W(Qh+I*c&) z5fwV6^2^u1N~O?}E%F49sw3E{i^q;{<~c(0pgbRq$(U8|>VZoy&Bd}peSVgMxc5a-Y!?f zm)HpHZ9j8BGSn?=Zu`NLXb_0nyY~d8wNv<|gYm#yKz7myv}VGA2TzGR0HR3{ECdKh zFa7KpCNnThsuVbjbGj}c=Y-<~R&*D`NaV9RZy6q3V!?{map+~k z&tG!p@4~@jatZ_T8-Mt;Nf-w21!ua2%|qC~5QF@2b`d(B)k?exf+^+*TUGeTC96GZ z!&euqgk15jW`BNUF+st&(x+2hW(2-))&^)#|FOE|-#*k!G5|jE-#mGHyf}*3K5ib_ zi&(kve_m#hYr@B4KmRZZG~qMn8}605SRHVuq&WTh$a~}8*0uUX{TyLs|IGtK9@&^> zG&p^f$P0YgD7H^ZgcpV2G<35LTtfT|N4nr__TPTYR9(>+IZpC=VMrPF7QdfFQx#Vk z3@JY%J@w-`Ly)k6O2mY2J1jzD=JZv`7gtUM{^2qhC3c{B^GfL?XIJpA9u?QUM2ed( z$*~m_64lrK=4~=go@M$iok}O%i>_-lOAAq6OhlSd45ME+Y_@;1zGJ2!IQ=19g|Dst zo)7<)FaGJ5L|_nmP9?!NWrX;Q+TZNio8omGj6YZQHWm0{420G`SRX#Jede^JB&|>T zA6|PQeT0wvH*Xj?CMNPZo!SUq$-j9@THDN*Q9t)=(k-|(!`pU56;{tL<3KGBV)#2i$R_edl1C8-^@(g&0JxwLqIebJ(MsY3;G7V9{N)MAFoH^ z(*F-Hvpt?}(gi{OSmtjY(D4HLGQnOG*jo?hU4N-g`oas&%VJPk{JKF zvIzOV%}4%A0ca^+G37e3{-Zr!{-Yy%a?2kLj^uv5b(QVsu9J?1(&~Hyet)?OBnf*| z3=b9yy3-?nIDl54kp4h$YuuaA`dRc>ug^Wiy|FCNRcs0*MSE3pWv>Mbyf=q4*Un59!C zUN76)TL|)A`8+OY{C!#*kJJll-{J+QsDOEy*Hus+{Rn+C$S08`A%s&{6 zfBI$W@z0D`+g=f+%R>I*QmnA7I@1E?E_2G)EFcyR0J>uPYT#4LTOt=(PCyK0u~gq%tmIZ7><@wC`mr0d9?u$^^B2Jq&HY1=(8LLg z!P}7+Pu)KS#v}H_k;kmu@6&)>e6oA)@o=(o^`Ay#``oL)9rwT9A+)F7HS8#Shc30A zM_RNP;mBUo1#*mfHS4iMZc!8}l5|nBMExf&`Lb6T=14# zfr^p15Gs2z=^S~vQCoa@4r@1oZ1IVA2WBm*>i}Ik;jx?3)GNQ0Pv2N0G%0N~Dj(3i z%jzubF^|T5j_?Hg(*Mr&_pWj6V!ku9!iN%KfBM`W@B($rxBVzmO}+4gqs~%PwlWeY zAMza05oodYqT@IH#(;C&R|8P{9gy(b<8^>#hJi^PY3haMsZVLR<5eQu#0@H}hRaL( za}8vC{m&L{UO9@0@#uXo&n#GSw}x9x*=uxE=1le@8m$L+hWY&@tX*5Xv3+aN8hI?v zF(^Ws|IY(+cf+BuU(F2leX7k0{a#^UEbdpA+~^9zi;b!N))2Z%#Cb4_huh!-^|Kp> zp`HQiI6d2T>gIsd=)u3;Y97IAxI_-88ulmVvbgH0^ zz{0GIfyAc}cKsy{A|ZT#lNEphsjrx3C}K<#Lz9~llK16VW>Wv{E!e0%AA*K4q||uf~TIz#XvN|B;5>E0)C$o&|8!r9io13 zuLSH2O(~E}bb(_`7l>l!a*KAJ(Xtn`nG6mu4wfi#O1NJxiV=0nEtJiuG6&02n2UTb z$Tq=sr6KZZf1XjWGu+S^P_8Eujw&z+UqP=Y8U7k-t}0MP&cOUyMNXBhfK<(*z{?i> zNiZ4}j2P!HDFY{U=~mrJ9mBWCd?3yYS=Sz&c}OO1J%Cy6gJDe>*b1|rtRRaFvgWbN zhRr8t)8A$TM==Lt#fur3>sH*td*d*8;N5z`{tEn1lYzZTRj2{?UDw4z)tE8njztja zBmobm3@x+{yk;I8{g!sK9Gf5y%)M2OAfQ$4Co+{wn=Z zu##$@3ljXF6D{)Ye>`MA9;QO*%sdKq0#DkoE{;h9kROEkDButDDFWx=vQ>O{3YajP zy5;UtrtYpByv^vbZDaq5*2qU?Ieb=g`Rm8pNfdxIKGBObSX23=0z_#RZYn!Hqo0M^K!2r12lzjY{ zmpJhc<9Ft~I@oT~ZRa1U|0>$XD?3Vod)Q7XunC+{7Uazqg1E!e-xKlrjHqE%GF-$5 z`Q~3syX0M!IO)e#8y0L%1Rk}-enhNCjAN_ft7IG(Kp&%0g6t(vB-IGBijP4Pghi+>@E!oW#lA{M&Qcl(||3reQ{9oz%p` zg%&ZTGimAcdLM_;t8QQ!hk-%l^L;cpn&i%}AN^}}WO^&XE3EPeVX`U~Hdn8|y&Dtw z4yo+2-gf^$AtgCqHAmnmPhwSCbx5Xfl=(Jb@9bD#&1Zrj=0mw#;UsSGF~CnwKY##r zRfqNMA_UadF^!d8#eiVu$4sID`r7jgU>Rt<0 zy>!uR6}2aDQ;%TJBcr@@)fiAH=`~Z0q&C(Mn=t0DxKM-v%tZvCP0E*5N&n#U71OUD zo@BY@c(A8i56Dh5M^TAKL|-y_?PfXhX}%(W%H?9WwjWmfv6pVqPSZ?9E>WHaa!6bR zOjt6xe0Pbx2L!YeDqxh66Rx!46!~28^T9UFAmyyq&?yHxMDw3j{B+6eO8?rF_z(1k zIph^l|G65%bpUjyE4B%rk{^JV`nkO%IIzGPJktA4*xGmaSnkWde%0o*&+^l1wu$!+x!wQO)4>S+w2e%Mm_ z!=9aLkvsQ!R>^bY1aY_1#~m72BLw?dzI+67mhuJFcg*E0?=-D+U?AyIVM;Wh+i`CC{Yb`mWZm(5yEl!Y*wAE3FQuGBE|&Jx*u;@Pt4h}3YlTHcM5 zGP&=w@J5g$1i5u*>sXCQx>Ol79cQgE&0{2~lFI|?abA@L!@>awNoZpS|aO%{L@~u*8JnE=PfdK(@=dLw+`h&dk{&L;QnU47yDNkN<*#?aP@y) zGSglvc$NC6h2KAX!{j(S)1gQ1c}Qlr`cr;yt*Y?do5%PQ2<3sVr_V5W3?}VYhKqag zm4bBEg>B{#(!CaiN3%)$*2T z{?5WMg_NGP?jXvk7t~hs^C!h!i?Ic>=|11*24sqP`sI1|)!Z$jrF;>Fs&FSL6f^N1 z5sYHalA2Li*aUW6r+UUf+To&1wX+TP9cJbnRK|jP7798cpe}4Al2Ot-;6UV3tdgy* z9>Y4wd1_i33GRuc2a)q*SFgT)=6*)gWJG(|1B+34hQ5=7@Me86TjAuK`ek90lklP z0>K7U|B-nS6G>Q1PdpH`C-xUxfx3j1^Hv#N6E=HvRBzLX?^{of6BjNTWeIY5h;&D6xR;qAiY}%;(H4s zO35^p?0A+vREHk52Cb@pup~YM*I#HKdYCm0$#Ns$bL<({nRTP>jphEzT<_F@;F7qE zNKVeZxXowEPv`BZNKVP9cFwXv{39Xj$1yLqU<}?Mb8}O`u4@E^QWyqysEWg?c!WY; zhNS6;1JFC1Mq;e=v1+)&6?f=0Oc(}@uRL;hmPZwQ zS%8-5Rcu_{x`}31eUC{VgD5kHp`Tv`Z!2N%KFVX*t!YU861hlra6-emwpo30YApjl z{vwFTjm?xv!QaOU?-r@npR0K0PT(m6(Pe+je5=Uf_rXUJ@7QEJDlgVOIDMA>g_oxe z)J^{!D%@AKdZ_SM8%q+^lqdAW&s-pDDSIULeC>t6eil!OPsGx1Z)Z_V*s~lvG-RQr zURw5Ro=&GBPR;4sGiyY7mbd9apw~Byt)*PVQXxv1zY+EVTMG|e7U$I%%v~D zkN2NHrB{@2n5$S~pinVI&N40+G}5dMY;R4 zWkrHrSQbG$Ze|z8;WY{uhT~ez*85EEk58!;2}Q!!hrCiXs)YT7b z;__f}ZMUv}z}sVUoQ8GP)J0<(p)?<;Mab@}UhuoDnd8nnErO4lj_dOE;q~_6eB<`3 z>6{&=MV6=fA@^ffr{?iMS`CY4%2GaF+v34-U$HHsE^Wahcem{_NqNF^x3?oXvlHO{ zj4z`gUQ4>!PqSvXSdDwos{B@@4$_l9>1f%SJ4-tJYT8YCMuF?tp-fvRRdpyp`<8O=Yq%g$?JnX1#UcaLA@z5 z$nDRf)CkUm|~+)F{=V$rF%=v za!{~m{#z}qJjh&1R`6aR(E&( z{SQ{l<1U#zPtd}^V28B%lc{np-rO%u+SNYm?brARe97xV-)9mle%YSLLvrOAt(UDYJn|o`80m5F z?HgKLcWtXRYg-WWn2S;5wAQO3OD@`}7DM~`GmN7$RG-B=&!jTqUlleIllN{Cfn-`9 z{MPl=D_xzoFxl?PLq~J-7JY8LvAs4=^LP@0&aLjQQsJ>;_z1kS%v(@1nHf^obP>~J zspTbaBwNPDi8|S$)paK2|w|3$Wi5#Ww3Pm|Ha2+$Tz z%i?rgPF>w97z>)Dn6Mmw+~zP}L2<(hzI!>e&t}qWB<4b!!;0duM;W>W|rp|9qm|A43Gu0o56|-sGl^`gQh^4QXXBy}ii3 zJUQBO>kZ`yH7QZWO=g_-uuc2xwd_qOO4~AoE1T}K4KI(?rO0rVoEfsIV=w^#c8GC~ zLW=$whT+Tmx9MfO!^=Sq`q)8$9v-<(2NJAa%D87;Hin&NGu3uMOWvz6LFTb>ttgJG za^q`8{4*9Q!}$;XFq+4}Kzzvy*1B()%IZ4v2ArnbRomm->0?osOzsMAFV%L!b=CRq zUTp_l+$VRiizCRB>#c_n32tkBYDnS3{^&Jvf=h{-7!$mz!~Q)7y%X^Z^oq&18~RPw zC6++`p~2{0=WwrXtYUq5prc}$>8$-ARd8HI9Z}7NXKTi<`qvGcR)_P^?GfT!3QQZz zrO!`Xy!dlvFCJVG`dk-r%~#6vFBTP6cj-6@y?Uxr`0;H=VO&nxEK$yc1jl6cbHch( zz`DvZ<4$4{O-B8Hw0WH5sJH##3w;Ni!>I|pMDhqcJxDpiZj zgFQwAwU+KX{f6hwi^(yTrtF<**Nw*S7fo&@ic8apw5)y4VcAy$2#+j}@0M1gh#h-r zw>jyfk3oZ{9APYYpNp8y*AEt7kwDYUb0!tv7=7WP9jlFQv|m>>_n^XT?_j@HLp?dH5Z@Vh2vQ!`;CBZquQVqa(EU} zm4xP-%*EExFJ|;>9Bx=?)lI1|9V2%(JtD?)?>=edz6nnuUD9uMFUh#Pj{Kaw`2U(1 z`N#Pp{Np7J@tj7gl3b?JxyzO$#7Ni|-N(0!g>ic;XT9G~NNBWrO`Z#DWYK^>r))g0 zN}hXzv131x7Ky&c!&_nK{?;0Cz#*m~L30;|`DtZ?{DPG|@`7J{z5|kQtWemz_uZV^ zRBF{e!rW=|Y}h4L8y~q14}hDyS;+kI{B0<(2Ib@ZK|dr)$k zj$aNe{{QNY83TM#rx;wLkYrHNA1{KC!|j1&V($ zhV~!7^)e8V`%d#op8Np+cc5>-f!S58Zu4e3GB8Q5;kMZ|Wx`bH4&S3E>H5>ECd)?f zme-=F06oBL~I?72vLnutj&$? z#fyPjwj+*Xf#Ibi8bmeNy~`HZ1aLB%ps=f&A}2mh%oR;zAg+RQD<5|{dBNgA*k7M} ziGLCsBu1#}-`g6HBC+3k_0~thwC>VTTHZ6OfeOm8*~ruEnkOrT7t2>?{J&4l4ud}> zB*p?e?;>Gu*G2+-(50{dz@{a84;5SGW{Z`f1^?mamhu{648-nGM0P?hoaYYUK!Ju9 zy$ISIz1!M-q&JC`uRd%w5;#Pz5)%#LjTO8H`@ zXTanC@TpFc=-(^h^-Dm1=mj7n1`y~3+Qp&~cd+!5RkNe$&p4_R2XHnVKX<~5p<LAn;fEzU=8irO_tRTTJCC?dP@BFJ|UbG|9yuBcTg2V)ByK=NwXLnb`+a?V-4YD(5? z6pT>x^@2zHAeA`eSMIbrk>4hc(;uH~OVCk8yU0V|{Ja_47IwXAw_@D%vgKf8JX}?o zyMQc|_`0|VlW*rG;Lp$6`9#jvP9BYWD`eB70W!f+PhSBMk>y9+uBXa8z+qFz zX*}$h-7A3?8?{V3@A4KdYx=jT&EuCvueM$HlXxd#-CoYVTC&w9cQVuLKR$;E$Lfjf z;2iRw#3k%}Pk8{1grr(hk@NGQLpA}BpyjE67y$|}YP~KJ2QZibCm-0DC1a_zQ~_-) z2sTP^LvPJndBkYDE`NM|A7cl>v{$V#eGGbd^;7&T&Hv_zH# zcYL;HNv?Zj-z+hvXT%Qbaw7v_?N}IFsn$oVT$fdq$!HYsWQg8{?tU~3U0ffMSOT~OtQ#+P?E2YMBo6$m0m1*`FcIQ)wWjRx`pyeP$lc90zC@NF!PD2@=3vGE&TUzM z?0Tqk3p;z#GC|A*jpBN*TD6N`JlRMc*PCymC_Mf`F&D=&+B+xs{qwcF+|0T1enrrQ zJ-89#*e15#yhT2SpOQlM8;lANl~{S;2J&3kZbya)SPu4@7x!&e;peT6itOGHESVy> zmgS*e2S;ey-n`R3Hwf}{y7vWlRPcn50{C6ot12k3)2#}>*dx;XNEy^Cio}z|%(^pt zR~XoK@QWUo^J&Vo9MBKg$Th!twD9*lK;gU1mP=+wsyw=@IJ3)bXR%vsL^W<~6Y!Jrx_N_5BF%0b|yb^nW!(`tMSLzgx;Taz|GL#fADEp?yAd^2$tW5S6?r4<{48Vtb`2Ws1 zs4X$>SxTnPcRYo@obATF4tp!vp*t8!NLnpU4$;csEl2$5ZKXTU1`E%;H9rr*RI4*L zLfhE{B{1PI_i|w>UILF(e@gxA%71z}d?Zq{PIIw&welh!>ES+c>`Ln1eFvbZ6Xy6B z^af_Z-iC}*YHKxNH`cNO+x-A83{>{@i$wxT{KlVO5|a94Yl=gIkYeS!eBB{7(6+}Y zbG%Q^sh!ty7z%S=_SZ?ub{*%`sEsX{*R=UaEj#e|FrQJYxiJfRGEjiv&rk`wJ%zZf zoAElFkQjGJ+AO!YiIQ_fCcO?a_I}p3@JO8B-JV1iwAgQM!&PhkmT&I;nX6g%j+K3Y z;OlWaXP@nf?n2r&FanF}&e9q%(V*aE6nAy3tw@v#mZQKRCJKaUg zg+&z?u3s#lnwpld&L^093ViwTaL|-vp~~XtqqtE6zFN1Fc+HK9YW5kaE~p z1E*b6c+_)WuE6WKNWObaBFs`FUzee=lHtDanykRB-=b)!gRozNxQ>Z;AG|*@BVoPG zwr|-jH*@!Ny_UxdescN|t%5}l(cn#d#iCobu+i6?yrI{#3{6|5!|!Oa^&SNNWdiU| z(*_9+MDD1P+C%xw034W;w`LrAe>YA$Sa%AzD8mMdoTvF!^~jaee6eES6lj%)twpFAw?6?3QAN%l0rK1eJU}yunUE79@%Vl zK$m6qX09)kEn4<}f*ieSYbKootzjv!@Ol*>P!E2klMI2?&TcOY*W!tjdKi&g?ZKty zobUU7tf0*ZA^v_}aHuM4LYw0HmR%wC$~p`?8A+|mGC81`ixaB`woZs+rPTJ-fcR2+ zxzfRKGgaO#Exu`1*o&y@?)j%jp8tnyWJO(nRS|}ka?c{}vyDPy!q9O4tJFDXA5J#; z_}F;IuTM(*qpJe6OsW92N#0`c6)~HAS4%2GvBw0}92$HIDcXmU-6=#x&iS9Ra$Su4f50R~KLC8wNIt z3HY8&Lt95SXTU125);1&vo4|qEY!Dps&>KxGy4vEjqWyR>RA>#ca_$y_D+|Fje#9S zYrp8XkZaMyXkfJ%7-R$5lx#5e-pYM7Mh=+{FMmauySpm8!k!{g=Rdn35RIop9%YmU z5p(1~a-9#=|1pu}8<8toi_R)fJmyXD`klmEAB|68?x0eSu}uKkUs*t0n<3E%BZb?bM69x Date: Thu, 25 Jul 2024 01:25:57 +0000 Subject: [PATCH 040/304] Update OpenSCENARIOSupport.md --- docs/developer_guide/OpenSCENARIOSupport.md | 1032 ++++++++++++++----- 1 file changed, 750 insertions(+), 282 deletions(-) diff --git a/docs/developer_guide/OpenSCENARIOSupport.md b/docs/developer_guide/OpenSCENARIOSupport.md index e71a23da9d5..b8b71f4628f 100644 --- a/docs/developer_guide/OpenSCENARIOSupport.md +++ b/docs/developer_guide/OpenSCENARIOSupport.md @@ -7,184 +7,188 @@ If you want to know about OpenSCENARIO, refer to the link below. - [ASAM OpenSCENARIO: User Guide](https://releases.asam.net/OpenSCENARIO/1.0.0/ASAM_OpenSCENARIO_BS-1-2_User-Guide_V1-0-0.html) - [OpenSCENARIO 1.0.0 XSD documentation](https://releases.asam.net/OpenSCENARIO/1.0.0/Model-Documentation/index.html) -## Specific Features ---- +## Dialects and Extensions -### ROS 2 Launch-like substitution syntax +### Substitution Syntax -Our interpreter supports some substitution syntax of [the ROS 2 Launch system](https://design.ros2.org/articles/roslaunch_xml.html#dynamic-configuration) (a.k.a. string-interpolation). -The substitution syntax works with any attribute string in OpenSCENARIO XML. +The interpreter supports some substitution syntax of [the ROS 2 Launch system](https://design.ros2.org/articles/roslaunch_xml.html#dynamic-configuration) (a.k.a. string-interpolation). The substitution syntax works with any attribute string in OpenSCENARIO XML. -This substitution is done only once when reading the attribute. -Note that the substitution result is finalized before the simulation starts, so it is not affected by the `ParameterModifyAction`, etc. that takes effect during the simulation. +Substitution syntaxes can be nested and the substitution is performed from the innermost to the outermost in order. -The supported functions and their behavior are shown below. +> [!IMPORTANT] +> This substitution is performed only once during the reading of the attribute, so changes in parameters that occur during the simulation, such as those from `ParameterModifyAction`, do not affect the substitution. -#### `$(find-pkg-prefix )` +#### Available Syntax -Equivalent to the following description given in ROS 2 Design (unless we made a mistake in our implementation). +##### `$(find-pkg-prefix )` -> Substituted by the install prefix path of the given package. Forward and backwards slashes will be resolved to the local filesystem convention. Substitution will fail if the package cannot be found. +Substituted with the install prefix path of the given package. Forward and backwards slashes will be resolved to the local filesystem convention. Substitution will fail if the specified name is not ROS 2 package. -The package specified must be a ROS 2 package. +##### `$(var )` -#### `$(var )` +Substituted with an external representation of the value of the specified OpenSCENARIO parameter. The parameters you specify must be declared by `ParameterDeclarations` before `$ (var ...)` is written. -Replaces with an external representation of the value of the specified -OpenSCENARIO parameter. -The parameters you specify must be declared by ParameterDeclarations before -`$ (var ...)` is written. +##### `$(dirname)` -#### `$(dirname)` +Substituted with the path to the directory where the running scenario script is located. -Substitute the path to the directory where the running scenario script is located. +#### Example -#### Evaluation of nested substitution syntax +```yml +ParameterDeclarations: + ParameterDeclaration: + - name: map_name + parameterType: string + value: kashiwanoha +RoadNetwork: + LogicFile: + filepath: $(find-pkg-share $(var map_name)_map)/map/lanelet2_map.osm +``` -These substitution syntaxes can be nested in any rank. -The replacement is done from the inside to the outside of the nest. -An example is shown below. +### Scoping -``` XML - - - - - - - -``` +The OpenSCENARIO XML standard [does not define](https://releases.asam.net/OpenSCENARIO/1.0.0/ASAM_OpenSCENARIO_BS-1-2_User-Guide_V1-0-0.html#:~:text=If%20a%20reference,lookup%20is%20undefined.) what to do if the name cannot be resolved. In the interpreter, the names of the Element and Parameter are lexically scoped. -## Implementation Dependent Behaviors ---- +- If you refer to an identifier that does not exist, the simulation will stop with an error. +- If multiple identifiers with the same name are defined, the identifier reference is chosen that is closest to the lexical position where the reference occurred. +- Defining a `StoryboardElement` with the same name at the same level is treated as a syntax error (In normal lexical scoping, this should be handled by shadowing, but in scenario languages it is likely a copy-and-paste mistake). -OpenSCENARIO has the function that the detailed behavior is left to the decision of the implementation side, which is defined as "subject of a contract between simulation environment provider and scenario author". +### Command -### Scoping +OpenSCENARIO XML standard states that `CustomCommandAction` can be used to either issue a command to the simulation environment or start an external script. -The OpenSCENARIO standard does not define what to do if the name cannot be resolved, as quoted below. +For OpenSCENARIO interpreters implemented in scripting languages such as Python, this action is often implemented as a call to an external script file written in the same language as the host language. However, `scenario_simulator_v2` is implemented in C++ and we cannot simply implement such a feature. Therefore, `scenario_simulator_v2` treats the string given in `CustomCommandAction.type` as a command and executes it on a subprocess, as `sh` does. -> If a reference cannot be resolved uniquely, for example if too few name prefixes have been specified to disambiguate fully, the result of the lookup is undefined. +> [!NOTE] +> To make scenarios portable, the usage of `CustomCommandAction` should be avoided. -In our interpreter, the names of the Element and Parameter are lexically scoped. +#### Built-in Commands -- If you refer to an identifier that does not exist, the simulation will stop with an error. -- If multiple identifiers with the same name are defined, the identifier reference is chosen that is closest to the lexical position where the reference occurred. -- Defining a StoryboardElement with the same name at the same level is treated as a syntax error (In normal lexical scoping, this should be handled by shadowing, but in scenario languages it is likely a copy-and-paste mistake). +##### `FaultInjectionAction(, ...)` -### CustomCommandAction +Same as `FaultInjectionAction@v1`. -This Action is specified in the standard as follows. -> Used to either issue a command to the simulation environment or start an external script. Allows the user to activate custom actions in their simulation tool. +##### `FaultInjectionAction@v1(, ...)` -For OpenSCENARIO interpreters implemented in scripting languages such as Python, this Action is often implemented as a call to an external script file written in the same language as the host language. -However, our interpreter is implemented in C++ and we cannot simply implement such a feature. -Therefore, our interpreter treats the string given in CustomCommandAction.type as a command and executes it on a subprocess, as `sh` does. +Forward any number of event names to Autoware as ERROR level event. Events are forwarded by publishing to the `tier4_simulation_msgs::msg::SimulationEvents` type topic `/simulation/events`. In order to perform fault injection using this `CustomCommandAction`, Autoware must have a node that receives the above message types. Note that `scenario_simulator_v2` has no knowledge of the contents of the event name. In other words, what happens to Autoware by this `CustomCommandAction` depends on Autoware implementation. -For example, the `echo` command can be written as follows: -``` XML - - Hello, world! - +##### `FaultInjectionAction@v2(, )` + +Forwards a single event to Autoware with the specified error level. Same as `FaultInjectionAction@v1` except that instead of specifying an error level, only one event can be specified at a time. Available error levels are `OK`, `WARN`, `ERROR` and `STALE`. + +##### `PseudoTrafficSignalDetectorConfidenceSetAction@v1(, )` + +Set a confidence value for traffic light topic. This action sets the confidence value to all traffic light bulbs of specified traffic light. If you specify the traffic light by a regulatory element ID, this action sets the confidence value to all traffic lights the regulatory element refers to. + +##### `RequestToCooperateCommandAction@v1(, )` + +Send an `ACTIVATE` / `DEACTIVATE` command to the module publishing a valid request to cooperate. If the send fails, throw an exception to fail the scenario. + +##### `V2ITrafficSignalStateAction(, , )` + +`TrafficSignalStateAction` for V2I traffic signal. You can optionally specify the publish rate of the traffic signal topic, but otherwise the functionality is the same as `TrafficSignalStateAction`. + +##### `WalkStraightAction(, ...)` + +Make **pedestrian** entities walk straight without a target. + +##### `exitFailure` + +This command immediately terminates the simulation as a failure without transitioning the state of the `StoryboardElement`. See [Termination](#termination) for more details. + +##### `exitSuccess` + +This command immediately terminates the simulation as a success without transitioning the state of the `StoryboardElement`. See [Termination](#termination) for more details. + +##### `:` (do nothing) + +Actually `:` is not a built-in command but executed as a shell command, it is worth mentioning here as it achieves 'doing nothing'. `:` is known as the null command in shell scripts, and can be used as a command that does nothing in the simulator as well. + +```yml +UserDefinedAction: + CustomCommandAction: + type: ':' ``` -The string given to attribute `type` of CustomCommandAction and the string given to its content are concatenated with whitespace and passed to the subprocess. -Therefore, the following two cases have the same effect. +#### Example + +In YAML format, `echo` command can be written as follows: + +```yml +UserDefinedAction: + CustomCommandAction: + type: 'echo Hello, world!' +``` + +In XML format, the string given to attribute `type` of `CustomCommandAction` and the string given to its content are concatenated with whitespace and passed to the subprocess so following two examples have the same effect. ``` XML - - Hello, world" - + + Hello, world" + ``` ``` XML - - - + + + ``` The effect of calling a command with `CustomCommandAction` is outside the control of the interpreter. Therefore, if you call a command that has a destructive effect on the system, there is no guarantee that the scenario execution can continue normally. -**For portable scenarios, the use of CustomCommandAction should be avoided as much as possible or limited to the scope of POSIX.** +### Condition -#### NullAction +`UserDefinedValueCondition` enables simulators to import external values and compare them with a specific value. The boolean value of the comparison result can be used as a condition to control the scenario. -In particular, the following usages that achieve "do nothing action" are worth special mention. -Here, the colon (`:`) specified in the `CustomCommandAction.type` is the `sh` command is known by the name of the null-command. +#### Autoware-related Built-in Conditions -``` XML - - - -``` +`scenario_simulator_v2` uses `UserDefinedValueCondition` to control the progress of the scenario by Autoware's state. -#### Built-in commands +##### `.currentState` -| Syntax | Description | -|:------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------|:--------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------| -|
UserDefinedAction:
CustomCommandAction:
type: FaultInjectionAction(, ...)
| Same as FaultInjectionAction@v1. | -|
UserDefinedAction:
CustomCommandAction:
type: FaultInjectionAction@v1(, ...)
| Forward any number of event names to Autoware as `ERROR` level event. Events are forwarded by publishing to the `tier4_simulation_msgs::msg::SimulationEvents` type topic `/simulation/events`. In order to perform fault injection using this CustomCommandAction, Autoware must have a node that receives the above message types. Note that the simulator has no knowledge of the contents of the event name. In other words, what happens to Autoware by this CustomCommandAction depends on Autoware implementation. | -|
UserDefinedAction:
CustomCommandAction:
type: FaultInjectionAction@v2(, )
| Forwards a single event to Autoware with the specified error level. Same as `FaultInjectionAction@v1` except that instead of specifying an error level, only one event can be specified at a time. Available error levels are `OK`, `WARN`, `ERROR` and `STALE`. | -|
UserDefinedAction:
CustomCommandAction:
type: PseudoTrafficSignalDetectorConfidenceSetAction@v1(, )
| Set a confidence value for traffic light topic. This action sets the confidence value to all traffic light bulbs of specified traffic light. If you specify the traffic light by a regulatory element ID, this action sets the confidence value to all traffic lights the regulatory element refers to. | -|
UserDefinedAction:
CustomCommandAction:
type: RequestToCooperateCommandAction@v1(, )
| Send an `ACTIVATE` / `DEACTIVATE` command to the module publishing a valid request to cooperate. If the send fails, throw an exception to fail the scenario. | -|
UserDefinedAction:
CustomCommandAction:
type: V2ITrafficSignalStateAction(, , \
)
| TrafficSignalStateAction for V2I traffic signal. You can optionally specify the publish rate of the traffic signal topic, but otherwise the functionality is the same as `TrafficSignalStateAction`. | -|
UserDefinedAction:
CustomCommandAction:
type: WalkStraightAction(, ...)
| Make **pedestrian** entities walk straight without a target. | -|
UserDefinedAction:
CustomCommandAction:
type: exitFailure
| Immediately terminates the simulation as a failure. | -|
UserDefinedAction:
CustomCommandAction:
type: exitSuccess
| Immediately terminates the simulation as successful. | +Returns Autoware's [state](https://github.com/tier4/autoware_auto_msgs/blob/tier4/main/autoware_auto_system_msgs/msg/AutowareState.idl). `` must be the name of Vehicle with ObjectController's property `isEgo` set to true. -The termination ignores the StoryboardElement's lifecycle transition (that is, it means that `StoryboardElementStateCondition` cannot be used to prevent or detect the execution of this command). +##### `.currentMinimumRiskManeuverState.behavior` -The terminated scenario determines the final success / failure / error. +Returns Autoware's [MRM behavior](https://github.com/autowarefoundation/autoware_adapi_msgs/blob/main/autoware_adapi_v1_msgs/system/msg/MrmState.msg). `` must be the name of Vehicle with ObjectController's property `isEgo` set to true. -**Currently, simulation results are notified by simply writing to standard output as text. This notification method is temporary and will change in the near future.** +##### `.currentMinimumRiskManeuverState.state` -The following built-in commands are debug commands for interpreter developers, not scenario creators. -It is unlikely that you will need these commands for normal scenario creation. +Returns Autoware's [MRM state](https://github.com/autowarefoundation/autoware_adapi_msgs/blob/main/autoware_adapi_v1_msgs/system/msg/MrmState.msg). `` must be the name of Vehicle with ObjectController's property `isEgo` set to true. -| Name | Effect | -|:--------|:--------------------------------------------------------------------------------------------------| -| error | Generate internal error: Used to ensure that the simulator does not crash with an internal error. | -| sigsegv | Access a null pointer: Used to make sure the simulator does not crash with an internal error. | +##### `.currentEmergencyState` -### UserDefinedValueCondition +Returns Autoware's [emergency state](https://github.com/tier4/autoware_auto_msgs/blob/tier4/main/autoware_auto_system_msgs/msg/EmergencyState.idl). `` must be the name of Vehicle with ObjectController's property `isEgo` set to true. -This condition enables us to import external values and compare them with a specific value. -The boolean value of the comparison result can be used as a condition to control the scenario. -In scenario_simulator_v2, we use `UserDefinedValueCondition` to control the progress of the scenario by Autoware's state. +##### `.currentTurnIndicatorsState` -```XML - - - -``` -#### Built-in conditions +Returns Autoware's [turn indicators state](https://github.com/tier4/autoware_auto_msgs/blob/tier4/main/autoware_auto_vehicle_msgs/msg/TurnIndicatorsCommand.idl). `` must be the name of Vehicle with ObjectController's property `isEgo` set to true. + +#### Other Built-in Conditions + +##### `RelativeHeadingCondition()` -Like "currentState", the conditions start with "current" return Autoware-related conditions. -And like "ego.currentState", they can specify the entity reference by prepending the name of the entity +Calculates the relative angle between the orientation of `` and the orientation of the lane on which `` is positioned. -The following built-in conditions return a string that represents the state. -See Reference for specific strings. +##### `RelativeHeadingCondition(, , )` -| Name | Syntax | Description | -|----------------------------|----------------------------------------------------------------------------------------------------------|--------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------| -| currentState | `.currentState` | Returns Autoware's [state](https://github.com/tier4/autoware_auto_msgs/blob/tier4/main/autoware_auto_system_msgs/msg/AutowareState.idl). `` must be the name of Vehicle with ObjectController's property `isEgo` set to true. | -| currentEmergencyState | `.currentEmergencyState` | Returns Autoware's [emergency state](https://github.com/tier4/autoware_auto_msgs/blob/tier4/main/autoware_auto_system_msgs/msg/EmergencyState.idl). `` must be the name of Vehicle with ObjectController's property `isEgo` set to true. | -| currentTurnIndicatorsState | `.currentTurnIndicatorsState` | Returns Autoware's [turn indicators state](https://github.com/tier4/autoware_auto_msgs/blob/tier4/main/autoware_auto_vehicle_msgs/msg/TurnIndicatorsCommand.idl). `` must be the name of Vehicle with ObjectController's property `isEgo` set to true. | -| RelativeHeadingCondition | `RelativeHeadingCondition()`
`RelativeHeadingCondition(, , )` | Returns the relative angle to the lane heading. | +Calculates the relative angle between the orientation of `` and the direction at the position specified by `` on ``. -#### External ROS 2 topic condition +#### ROS2 Topic Condition -You can pass values from another ROS 2 node to a scenario through ROS 2 topics. -The `name` field should be filled with the name of the ROS 2 topic like below. -```XML - - - +`scenario_simulator_v2` can read values from another ROS 2 node to a scenario through ROS 2 topics. `name` field should be filled with the name of the ROS 2 topic like below. + +```yml +ByValueCondition: + UserDefinedValueCondition: + name: /count_up + rule: equalTo + value: '500' ``` The type of topic must be `tier4_simulation_msgs::msg::UserDefinedValue` type. -You can handle the following through this function. +`scenario_simulator_v2` can handle the following through this function. - Boolean - DateTime @@ -196,200 +200,664 @@ You can handle the following through this function. See [Message Definitions](https://github.com/tier4/tier4_autoware_msgs/tree/tier4/universe/tier4_simulation_msgs) for more information. -## Non-Standard Extensions ---- - -### Success/failure judgment - -Our interpreters have been developed with the intention of incorporating them into the CI / CD pipelines in autonomous driving systems. -Therefore, executing a scenario can result in success, failure, or error. -Note that "error" means a flaw in the scenario, such as a syntax error, or an internal error, not an "error in an automated driving system" such as "a vehicle accident occurred in a simulation". -In such cases, you will be notified of a "failure". - -## Supporting Status ---- - -Our OpenSCENARIO Interpreter does not currently support the full range of -OpenSCENARIO standards. - -### Actions - -| Name | Support Status | Limitations | OpenSCENARIO changes | -|:----------------------------------------------------------------------------------------|:--------------:|:-----------------------------------|----------------------| -| GlobalAction.**EnvironmentAction** | Unsupported | | | -| GlobalAction.EntityAction.**AddEntityAction** | ✔ | | | -| GlobalAction.EntityAction.**DeleteEntityAction** | ✔ | | | -| GlobalAction.ParameterAction.**ParameterSetAction** | ✔ | See [here](#parametersetaction) | deprecated from v1.2 | -| GlobalAction.ParameterAction.**ParameterModifyAction** | ✔ | No | deprecated from v1.2 | -| GlobalAction.InfrastructureAction.TrafficSignalAction.**TrafficSignalControllerAction** | ✔ | | | -| GlobalAction.InfrastructureAction.TrafficSignalAction.**TrafficSignalStateAction** | ✔ | | | -| GlobalAction.TrafficAction.**TrafficSourceAction** | Unsupported | | | -| GlobalAction.TrafficAction.**TrafficSinkAction** | Unsupported | | | -| GlobalAction.TrafficAction.**TrafficSwarmAction** | Unsupported | | | -| GlobalAction.TrafficAction.**TrafficStopAction** | Unsupported | | | -| GlobalAction.VariableAction.**VariableSetAction** | Unsupported | | created in v1.2 | -| GlobalAction.VariableAction.**VariableModifyAction** | Unsupported | | created in v1.2 | -| UserDefinedAction.**CustomCommandAction** | ✔ | See [here](#customcommandaction) | | -| PrivateAction.AppearanceAction.**AnimationAction** | Unsupported | | created in v1.2 | -| PrivateAction.AppearanceAction.**LightStateAction** | Unsupported | | created in v1.2 | -| PrivateAction.LongitudinalAction.**SpeedAction** | ✔ | See [here](#speedaction) | | -| PrivateAction.LongitudinalAction.**SpeedProfileAction** | Unsupported | | created in v1.2 | -| PrivateAction.LongitudinalAction.**LongitudinalDistanceAction** | Unsupported | | | -| PrivateAction.LateralAction.**LaneChangeAction** | ✔ | See [here](#lanechangeaction) | | -| PrivateAction.LateralAction.**LaneOffsetAction** | Unsupported | | | -| PrivateAction.LateralAction.**LateralDistanceAction** | Unsupported | | | -| PrivateAction.**VisibilityAction** | Unsupported | | | -| PrivateAction.**SynchronizeAction** | Unsupported | | | -| PrivateAction.**ActivateControllerAction** | Unsupported | | deprecated from v1.2 | -| PrivateAction.ControllerAction.**AssignControllerAction** | ✔ | | | -| PrivateAction.ControllerAction.**ActivateControllerAction** | Unsupported | | | -| PrivateAction.ControllerAction.**OverrideControllerValueAction** | Unsupported | | | -| PrivateAction.**TeleportAction** | ✔ | See [here](#teleportaction) | | -| PrivateAction.RoutingAction.**AssignRouteAction** | ✔ | | | -| PrivateAction.RoutingAction.**FollowTrajectoryAction** | ✔ | See [here](#followtrajectoryaction)| | -| PrivateAction.RoutingAction.**AcquirePositionAction** | ✔ | See [here](#acquirepositionaction) | | +#### Example + +```yml +ByValueCondition: + UserDefinedValueCondition: + name: ego.currentState + rule: equalTo + value: ARRIVED_GOAL +``` + +### Termination + +`scenario_simulator_v2` is being developed to be integrated into the CI/CD pipeline of autonomous driving systems, and it concludes simulations with a status of either `success`, `failure`, or `error`. `failure` and `error` are each caused by different factors. Specifically, `failure` is used when issues arise from the autonomous driving system itself, such as a vehicle accident occurring during the simulation. On the other hand, `error` is specifically attributed to problems on the simulator's side, such as syntax errors in the scenario file or internal errors within the simulator itself. + +Within the scenario, you can end the scenario simulation with a status of either `success` or `failure` by using `exitSuccess` and `exitFailure` from `CustomCommandAction`. + +> [!IMPORTANT] +> `exitSuccess` and `exitFailure` terminate the simulation immediately without any state transitions in the lifecycle of a `StoryboardElement`. This means there is no way to detect simulations terminated by `exitSuccess` or `exitFailure` from within the scenario using conditions like `StoryboardElementStateCondition`. + +Currently, the only way to know the result of the simulation is by viewing the status string printed to standard output. However, this method may change in the future. +## Conformance + +| Name | Supported Version | Detail | +|:---------------------------------------------|:-----------------:|:------------------------------------------:| +| AbsoluteSpeed | unimplemented | | +| AbsoluteTargetLane | 1.3 | | +| AbsoluteTargetLaneOffset | unimplemented | | +| AbsoluteTargetSpeed | 1.3 | | +| AccelerationCondition | 1.3 | | +| AcquirePositionAction | 1.3 (partial) | [detail](#AcquirePositionAction) | +| Act | 1.3 | | +| Action | 1.3 | | +| ActivateControllerAction | unimplemented | | +| Actors | 1.3 (partial) | | +| AddEntityAction | 1.3 | | +| AngleCondition | unimplemented | | +| AngleType | unimplemented | | +| AnimationAction | unimplemented | | +| AnimationFile | unimplemented | | +| AnimationState | unimplemented | | +| AnimationType | unimplemented | | +| AppearanceAction | unimplemented | | +| AssignControllerAction | 1.2 (partial) | [detail](#AssignControllerAction) | +| AssignRouteAction | 1.3 | | +| AutomaticGear | unimplemented | | +| AutomaticGearType | unimplemented | | +| Axle | 1.3 | | +| Axles | 1.3 | [detail](#Axles) | +| BoundingBox | 1.3 | | +| Brake | unimplemented | | +| BrakeInput | unimplemented | | +| ByEntityCondition | 1.3 | | +| ByObjectType | unimplemented | | +| ByType | 1.3 | | +| ByValueCondition | 1.3 (partial) | [detail](#ByValueCondition) | +| Catalog | 1.3 (partial) | [detail](#Catalog) | +| CatalogDefinition | 1.3 | | +| CatalogLocations | 1.3 | | +| CatalogReference | 1.3 | | +| Center | 1.3 | | +| CentralSwarmObject | unimplemented | | +| Clothoid | unimplemented | | +| ClothoidSpline | unimplemented | | +| ClothoidSplineSegment | unimplemented | | +| CloudState | unimplemented | | +| CollisionCondition | 1.3 (partial) | [detail](#CollisionCondition) | +| Color | unimplemented | | +| ColorCmyk | unimplemented | | +| ColorRgb | unimplemented | | +| ColorType | unimplemented | | +| ComponentAnimation | unimplemented | | +| Condition | 1.3 | | +| ConditionEdge | 1.3 (modified) | [detail](#ConditionEdge) | +| ConditionGroup | 1.3 | | +| ConnectTrailerAction | unimplemented | | +| ControlPoint | unimplemented | | +| Controller | 1.1 | [detail](#Controller) | +| ControllerAction | 1.0 | [detail](#ControllerAction) | +| ControllerCatalogLocation | 1.3 | | +| ControllerDistribution | unimplemented | | +| ControllerDistributionEntry | unimplemented | | +| ControllerType | unimplemented | | +| CoordinateSystem | 1.2 (partial) | [detail](#CoordinateSystem) | +| CustomCommandAction | 1.3 | | +| CustomContent | unimplemented | | +| DeleteEntityAction | 1.3 | | +| Deterministic | 1.3 | | +| DeterministicMultiParameterDistribution | 1.3 | | +| DeterministicMultiParameterDistributionType | 1.3 | | +| DeterministicParameterDistribution | 1.3 | | +| DeterministicSingleParameterDistribution | 1.3 | | +| DeterministicSingleParameterDistributionType | 1.3 | | +| Dimensions | 1.3 | | +| DirectionOfTravelDistribution | unimplemented | | +| DirectionalDimension | unimplemented | | +| Directory | 1.3 | | +| DisconnectTrailerAction | unimplemented | | +| DistanceCondition | 1.3 (partial) | [detail](#DistanceCondition) | +| DistributionDefinition | 1.3 | | +| DistributionRange | 1.3 (partial) | [detail](#DistributionRange) | +| DistributionSet | 1.3 | | +| DistributionSetElement | 1.3 | | +| DomeImage | 1.3 | | +| DynamicConstraints | 1.3 | | +| DynamicsDimension | 1.3 | | +| DynamicsShape | 1.3 (partial) | [detail](#DynamicsShape) | +| EndOfRoadCondition | unimplemented | | +| Entities | 1.3 (partial) | [detail](#Entities) | +| EntityAction | 1.3 | | +| EntityCondition | 1.1 (partial) | [detail](#EntityCondition) | +| EntityDistribution | unimplemented | | +| EntityDistributionEntry | unimplemented | | +| EntityObject | 1.3 (partial) | [detail](#EntityObject) | +| EntityRef | 1.3 | | +| EntitySelection | 1.3 | | +| Environment | 1.3 | | +| EnvironmentAction | 1.3 | | +| EnvironmentCatalogLocation | 1.3 | | +| Event | 1.3 | | +| ExternalObjectReference | unimplemented | | +| File | 1.3 | | +| FileHeader | 1.3 | | +| FinalSpeed | unimplemented | | +| Fog | 1.3 | | +| FollowTrajectoryAction | 1.3 | [detail](#FollowTrajectoryAction) | +| FollowingMode | 1.3 | | +| FractionalCloudCover | 1.3 | | +| Gear | unimplemented | | +| GeoPosition | unimplemented | | +| GlobalAction | 1.1 (partial) | [detail](#GlobalAction) | +| Histogram | 1.3 | | +| HistogramBin | 1.3 | | +| InRoutePosition | unimplemented | | +| InfrastructureAction | 1.3 | | +| Init | 1.3 | | +| InitActions | 1.3 | | +| Knot | unimplemented | | +| Lane | unimplemented | | +| LaneChangeAction | 1.3 (partial) | [detail](#LaneChangeAction) | +| LaneChangeTarget | 1.3 | | +| LaneOffsetAction | unimplemented | | +| LaneOffsetActionDynamics | unimplemented | | +| LaneOffsetTarget | unimplemented | | +| LanePosition | 1.3 | | +| LateralAction | 1.3 (partial) | [detail](#LateralAction) | +| LateralDisplacement | unimplemented | | +| LateralDistanceAction | unimplemented | | +| License | 1.3 | | +| LightMode | unimplemented | | +| LightState | unimplemented | | +| LightStateAction | unimplemented | | +| LightType | unimplemented | | +| LogNormalDistribution | unimplemented | | +| LongitudinalAction | 1.3 | [detail](#LongitudinalAction) | +| LongitudinalDisplacement | unimplemented | | +| LongitudinalDistanceAction | unimplemented | | +| Maneuver | 1.3 | | +| ManeuverCatalogLocation | 1.3 | | +| ManeuverGroup | 1.3 | | +| ManualGear | unimplemented | | +| MiscObject | 1.3 | | +| MiscObjectCatalogLocation | 1.3 | | +| MiscObjectCategory | 1.3 (partial) | [detail](#MiscObjectCategory) | +| ModifyRule | 1.1 | [detail](#ModifyRule) | +| MonitorDeclaration | unimplemented | | +| MonitorDeclarations | unimplemented | | +| None | 1.3 | | +| NormalDistribution | 1.3 | | +| Nurbs | unimplemented | | +| ObjectController | 1.3 | [detail](#ObjectController) | +| ObjectType | 1.3 | | +| OffroadCondition | unimplemented | | +| OpenScenario | 1.3 | | +| OpenScenarioCategory | 1.3 (modified) | [detail](#OpenScenarioCategory) | +| Orientation | 1.3 | | +| OverrideBrakeAction | unimplemented | | +| OverrideClutchAction | unimplemented | | +| OverrideControllerValueAction | unimplemented | | +| OverrideGearAction | unimplemented | | +| OverrideParkingBrakeAction | unimplemented | | +| OverrideSteeringWheelAction | unimplemented | | +| OverrideThrottleAction | unimplemented | | +| ParameterAction | 1.1 | [detail](#ParameterAction) | +| ParameterAddValueRule | 1.1 | [detail](#ParameterAddValueRule) | +| ParameterAssignment | 1.3 | | +| ParameterCondition | 1.3 | | +| ParameterDeclaration | 1.3 | | +| ParameterModifyAction | 1.1 | [detail](#ParameterModifyAction) | +| ParameterMultiplyByValueRule | 1.1 | [detail](#ParameterMultiplyByValueRule) | +| ParameterSetAction | 1.1 | [detail](#ParameterSetAction) | +| ParameterType | 1.3 | [detail](#ParameterType) | +| ParameterValueDistribution | 1.3 | | +| ParameterValueDistributionDefinition | 1.3 | | +| ParameterValueSet | 1.3 | | +| Pedestrian | 1.3 (partial) | [detail](#Pedestrian) | +| PedestrianAnimation | unimplemented | | +| PedestrianCatalogLocation | 1.3 | | +| PedestrianCategory | 1.3 (partial) | [detail](#PedestrianCategory) | +| PedestrianGesture | unimplemented | | +| PedestrianGestureType | unimplemented | | +| PedestrianMotionType | unimplemented | | +| Performance | 1.3 | | +| Phase | 1.1 | [detail](#Phase) | +| PoissonDistribution | 1.3 | | +| Polygon | unimplemented | | +| Polyline | 1.3 | | +| Position | 1.3 (partial) | [detail](#Position) | +| PositionInLaneCoordinates | unimplemented | | +| PositionInRoadCoordinates | unimplemented | | +| PositionOfCurrentEntity | unimplemented | | +| Precipitation | 1.3 | [detail](#Precipitation) | +| PrecipitationType | 1.3 | | +| Priority | 1.1 | [detail](#Priority) | +| Private | 1.3 | | +| PrivateAction | 1.3 | [detail](#PrivateAction) | +| ProbabilityDistributionSet | 1.3 | | +| ProbabilityDistributionSetElement | 1.3 | | +| Properties | 1.3 (partial) | [detail](#Properties) | +| Property | 1.3 | | +| RandomRouteAction | unimplemented | | +| Range | 1.3 | | +| ReachPositionCondition | 1.1 | [detail](#ReachPositionCondition) | +| ReferenceContext | 1.3 (partial) | [detail](#ReferenceContext) | +| RelativeAngleCondition | unimplemented | | +| RelativeClearanceCondition | unimplemented | | +| RelativeDistanceCondition | 1.3 (partial) | [detail](#RelativeDistanceCondition) | +| RelativeDistanceType | 1.3 | [detail](#RelativeDistanceType) | +| RelativeLanePosition | unimplemented | | +| RelativeLaneRange | unimplemented | | +| RelativeObjectPosition | 1.3 | | +| RelativeRoadPosition | unimplemented | | +| RelativeSpeedCondition | unimplemented | | +| RelativeSpeedToMaster | unimplemented | | +| RelativeTargetLane | 1.3 | | +| RelativeTargetLaneOffset | unimplemented | | +| RelativeTargetSpeed | 1.3 | | +| RelativeWorldPosition | 1.3 | | +| RoadCondition | 1.3 | | +| RoadCursor | unimplemented | | +| RoadNetwork | 1.3 (partial) | [detail](#RoadNetwork) | +| RoadPosition | unimplemented | | +| RoadRange | unimplemented | | +| Role | unimplemented | | +| Route | 1.3 | | +| RouteCatalogLocation | 1.3 | | +| RoutePosition | unimplemented | | +| RouteRef | unimplemented | | +| RouteStrategy | 1.3 (partial) | [detail](#RouteStrategy) | +| RoutingAction | 1.2 | [detail](#RoutingAction) | +| RoutingAlgorithm | 1.3 | | +| Rule | 1.3 | | +| ScenarioDefinition | 1.1 | [detail](#ScenarioDefinition) | +| ScenarioObject | 1.3 | | +| ScenarioObjectTemplate | unimplemented | | +| SelectedEntities | 1.3 | | +| SensorReference | unimplemented | | +| SensorReferenceSet | unimplemented | | +| SetMonitorAction | unimplemented | | +| Shape | 1.2 | [detail](#Shape) | +| SimulationTimeCondition | 1.3 | | +| SpeedAction | 1.3 (partial) | [detail](#SpeedAction) | +| SpeedActionTarget | 1.3 | | +| SpeedCondition | 1.3 (partial) | [detail](#SpeedCondition) | +| SpeedProfileAction | 1.3 | | +| SpeedProfileEntry | 1.3 | | +| SpeedTargetValueType | 1.3 | | +| StandStillCondition | 1.3 | | +| SteadyState | unimplemented | | +| Stochastic | 1.3 | | +| StochasticDistribution | 1.3 | | +| StochasticDistributionType | 1.2 | [detail](#StochasticDistributionType) | +| Story | 1.3 | | +| Storyboard | 1.3 | | +| StoryboardElementState | 1.3 | | +| StoryboardElementStateCondition | 1.3 (modified) | [detail](#StoryboardElementStateCondition) | +| StoryboardElementType | 1.3 | | +| Sun | 1.3 | [detail](#Sun) | +| SynchronizeAction | unimplemented | | +| TargetDistanceSteadyState | unimplemented | | +| TargetTimeSteadyState | unimplemented | | +| TeleportAction | 1.3 | [detail](#TeleportAction) | +| TimeHeadwayCondition | 1.0 | [detail](#TimeHeadwayCondition) | +| TimeOfDay | 1.3 | | +| TimeOfDayCondition | unimplemented | | +| TimeReference | 1.3 | | +| TimeToCollisionCondition | unimplemented | | +| TimeToCollisionConditionTarget | unimplemented | | +| Timing | 1.3 | | +| TrafficAction | unimplemented | | +| TrafficArea | unimplemented | | +| TrafficAreaAction | unimplemented | | +| TrafficDefinition | unimplemented | | +| TrafficDistribution | unimplemented | | +| TrafficDistributionEntry | unimplemented | | +| TrafficSignalAction | 1.3 | | +| TrafficSignalCondition | 1.3 | | +| TrafficSignalController | 1.3 | | +| TrafficSignalControllerAction | 1.3 | | +| TrafficSignalControllerCondition | 1.3 | | +| TrafficSignalGroupState | unimplemented | | +| TrafficSignalState | 1.3 | | +| TrafficSignalStateAction | 1.3 | | +| TrafficSinkAction | unimplemented | | +| TrafficSourceAction | unimplemented | | +| TrafficStopAction | unimplemented | | +| TrafficSwarmAction | unimplemented | | +| Trailer | unimplemented | | +| TrailerAction | unimplemented | | +| TrailerCoupler | unimplemented | | +| TrailerHitch | unimplemented | | +| Trajectory | 1.3 | | +| TrajectoryCatalogLocation | 1.3 | | +| TrajectoryFollowingMode | 1.3 | | +| TrajectoryPosition | unimplemented | | +| TrajectoryRef | 1.3 | | +| TransitionDynamics | 1.1 | [detail](#TransitionDynamics) | +| TraveledDistanceCondition | unimplemented | | +| Trigger | 1.3 | | +| TriggeringEntities | 1.3 | | +| TriggeringEntitiesRule | 1.3 (modified) | [detail](#TriggeringEntitiesRule) | +| UniformDistribution | 1.3 | | +| UsedArea | unimplemented | | +| UserDefinedAction | 1.3 | | +| UserDefinedAnimation | unimplemented | | +| UserDefinedComponent | unimplemented | | +| UserDefinedDistribution | unimplemented | | +| UserDefinedLight | unimplemented | | +| UserDefinedValueCondition | 1.3 | | +| ValueConstraint | 1.3 | | +| ValueConstraintGroup | 1.3 | | +| ValueSetDistribution | 1.3 | | +| VariableAction | unimplemented | | +| VariableAddValueRule | unimplemented | | +| VariableCondition | unimplemented | | +| VariableDeclaration | unimplemented | | +| VariableDeclarations | unimplemented | | +| VariableModifyAction | unimplemented | | +| VariableModifyRule | unimplemented | | +| VariableMultiplyByValueRule | unimplemented | | +| VariableSetAction | unimplemented | | +| Vehicle | 1.1 (partial) | [detail](#Vehicle) | +| VehicleCatalogLocation | 1.3 | | +| VehicleCategory | 1.3 | | +| VehicleCategoryDistribution | unimplemented | | +| VehicleCategoryDistributionEntry | unimplemented | | +| VehicleComponent | unimplemented | | +| VehicleComponentType | unimplemented | | +| VehicleLight | unimplemented | | +| VehicleLightType | unimplemented | | +| VehicleRoleDistribution | unimplemented | | +| VehicleRoleDistributionEntry | unimplemented | | +| Vertex | 1.3 | | +| VisibilityAction | unimplemented | | +| Waypoint | 1.3 | | +| Weather | 1.3 | | +| Wetness | 1.3 | | +| Wind | 1.3 | | +| WorldPosition | 1.3 | | + +### Details + +#### AcquirePositionAction + +- Property `Position` of types `RoadPosition`, `RelativeRoadPosition`, `RelativeLanePosition`, `RoutePosition`, `GeoPosition`, and `TrajectoryPosition` are **not** supported. + +#### AssignControllerAction + +- Properties `activateAnimation`, `activateLateral`, `activateLighting`, and `activateLongitudinal` are ignored. + - The simulator behaves as if these properties are `false`. +- Property `ObjectController` created in version 1.3 is **not** supported. +- Properties `Controller` and `CatalogReference` deprecated in version 1.3 are supported. + +#### Axles + +- Property `RearAxle` is made mandatory in version 1.3, but still can be omitted like specified in version 1.2. + +#### ByValueCondition + +- Properties `TimeOfDayCondition` and `VariableCondition` are **not** supported. + +#### Catalog + +- Property `Trajectory` is ignored. + +#### CollisionCondition + +- Property `ByType` is **not** supported. + +#### ConditionEdge + +- Enumeration literal `sticky` is added as TIER IV extension. + +#### Controller + +- Property `controllerType` created in version 1.2 is ignored. + +#### ControllerAction + +- Property `OverrideControllerValueAction` is ignored. +- Property `ActivateControllerAction` created in version 1.1 is ignored. + +#### CoordinateSystem + +- Enumeration literals `road` and `trajectory` are **not** supported. +- Enumeration literal `world` created in version 1.3 is **not** supported. + +#### DistanceCondition + +- Property `alongRoute` deprecated in version 1.1 is **not** supported. +- Property `Position` of types `RoadPosition`, `RelativeRoadPosition`, `RelativeLanePosition`, `RoutePosition`, `GeoPosition`, and `TrajectoryPosition` are **not** supported. +- Not all combinations of properties for distance calculation are supported. Supported combinations are listed below: + | coordinateSystem | relativeDistanceType | routingAlgorithm | freespace | + |:----------------:|:--------------------:|:----------------:|:---------:| + | entity | euclidianDistance | undefined | false | + | entity | euclidianDistance | undefined | true | + | entity | lateral | undefined | false | + | entity | lateral | undefined | true | + | entity | longitudinal | undefined | false | + | entity | longitudinal | undefined | true | + | lane | lateral | undefined | false | + | lane | lateral | undefined | true | + | lane | longitudinal | undefined | false | + | lane | longitudinal | undefined | true | + | lane | lateral | shortest | false | + | lane | lateral | shortest | true | + | lane | longitudinal | shortest | false | + | lane | longitudinal | shortest | true | + +#### DistributionRange + +- Property `stepWidth` is ignored. + +#### DynamicsShape + +- Enumeration literal `sinusoidal` is **not** supported. + +#### Entities + +- Property `EntitySelection` is **not** supported. + +#### EntityCondition + +- Properties `EndOfRoadCondition`, `OffroadCondition`, `TimeToCollisionCondition`, `RelativeDistanceCondition`, and `TraveledDistanceCondition` are **not** supported. +- Property `ReachPositionCondition` deprecated in version 1.2 is still supported. +- Properties `AngleCondition` and `RelativeAngleCondition` created in version 1.3 are **not** supported. + +#### EntityObject + +- Property `ExternalObjectReference` is **not** supported. + +#### FollowTrajectoryAction + +- Properties `Trajectory` and `CatalogReference` deprecated in version 1.1 are ignored. +- Property `TrajectoryRef` of type `Clothoid` and `Nurbs` are **not** supported. + +#### GlobalAction + +- Properties `TrafficAction` and `VariableAction` are not supported. +- Property `ParameterAction` deprecated in version 1.2 is still supported. +- Property `SetMonitorAction` created in version 1.3 is **not** supported. + +#### LaneChangeAction + +- Specifying `step` for `LaneChangeActionDynamics.dynamicsDimension` is **not** supported. + - Simulator may lead to an undefined behavior if `step` is specified. + +#### LateralAction + +- Properties `LaneOffsetAction` and `LateralDistanceAction` are **not** supported. + +#### LongitudinalAction + +- Property `LongitudinalDistanceAction` is **not** supported. + +#### MiscObjectCategory + +- Enumeration literals `barrier`, `building`, `crosswalk`, `gantry`, `none`, `parkingSpace`, `patch`, `pole`, `roadMark`, `soundBarrier`, `streetLamp`, `trafficIsland`, `tree`, and `vegetation` are **not** supported. +- Enumeration literal `wind` deprecated in version 1.1 is **not** supported. + +#### ModifyRule + +- Class `ModifyRule` deprecated in version 1.3 is still supported. + +#### ObjectController + +- Property `name` is ignored. + +#### OpenScenarioCategory + +- The simulator reads `Storyboard` in XML as property `ScenarioDefinition` +- The simulator reads `Catalog` in XML as property `CatalogDefinition` +- The simulator reads `ParameterValueDistribution` in XML as property `ParameterValueDistributionDefinition` + +#### ParameterAction + +- Class `ParameterAction` deprecated in version 1.2 is still supported. + +#### ParameterAddValueRule + +- Class `ParameterAddValueRule` deprecated in version 1.2 is still supported. + +#### ParameterModifyAction + +- Class `ParameterModifyAction` deprecated in version 1.2 is still supported. + +#### ParameterMultiplyByValueRule + +- Class `ParameterMultiplyByValueRule` deprecated in version 1.2 is still supported. + +#### ParameterSetAction + +- Class `ParameterSetAction` deprecated in version 1.2 is still supported. +- Class `ParameterSetAction` cannot handle parameters of type `DataTime`. + +#### ParameterType + +- Enumeration literal `integer` deprecated in version 1.2 is **not** supported. + +#### Pedestrian + +- Property `role` is ignored. + - The simulator does not take into account `role`. +- Property `model` deprecated version 1.1 is ignored but mandatory. + - Maybe this is simulator bug and need to be fixed. + +#### PedestrianCategory + +- Enumeration literals `wheelchar` and `animal` are **not** supported. + +#### Phase + +- Property `TrafficSignalGroupState` created in version 1.2 is ignored. + +#### Position + +- Properties `RoadPosition`, `RelativeRoadPosition`, `RelativeLanePosition`, `RoutePosition`, `GeoPosition`, and `TrajectoryPosition` are **not** supported. + +#### Precipitation + +- Property `intensity` deprecated in version 1.1 is still supported. + +#### Priority + +- Enumeration literal `override` created in version 1.2 is **not** supported. +- Enumeration literal `overwrite` deprecated in version 1.2 is supported. + +#### PrivateAction + +- Property `VisibilityAction`, `SynchronizeAction` and `ActivateControllerAction` are **not** supported. + +#### Properties + +- Property `CustomContent` is ignored. + - The simulator does not take into account `CustomContent`. + +#### ReachPositionCondition + +- Class `ReachPositionCondition` deprecated in version 1.2 is still supported. +- Property `Position` of types `RoadPosition`, `RelativeRoadPosition`, `RelativeLanePosition`, `RoutePosition`, `GeoPosition`, and `TrajectoryPosition` are **not** supported. + +#### ReferenceContext + +- Enumeration literal `absolute` is **not** supported. -### Conditions +#### RelativeDistanceCondition -| Name | Support Status | Limitations | OpenSCENARIO changes | -|:----------------------------------------------------------------|:--------------:|:---------------------------------------------|----------------------| -| ByEntityCondition.EntityCondition.**EndOfRoadCondition** | Unsupported | | | -| ByEntityCondition.EntityCondition.**CollisionCondition** | ✔ | See [here](#collisioncondition) | | -| ByEntityCondition.EntityCondition.**OffroadCondition** | Unsupported | | | -| ByEntityCondition.EntityCondition.**TimeHeadwayCondition** | ✔ | See [here](#timeheadwaycondition) | | -| ByEntityCondition.EntityCondition.**TimeToCollisionCondition** | Unsupported | | | -| ByEntityCondition.EntityCondition.**AccelerationCondition** | ✔ | No | | -| ByEntityCondition.EntityCondition.**StandStillCondition** | ✔ | No | | -| ByEntityCondition.EntityCondition.**SpeedCondition** | ✔ | No | | -| ByEntityCondition.EntityCondition.**RelativeSpeedCondition** | Unsupported | | | -| ByEntityCondition.EntityCondition.**TraveledDistanceCondition** | Unsupported | | | -| ByEntityCondition.EntityCondition.**ReachPositionCondition** | ✔ | See [here](#reachpositioncondition) | deprecated from v1.2 | -| ByEntityCondition.EntityCondition.**DistanceCondition** | ✔ | See [here](#distancecondition) | | -| ByEntityCondition.EntityCondition.**RelativeDistanceCondition** | ✔ | | | -| ByValueCondition.**ParameterCondition** | ✔ | | | -| ByValueCondition.**TimeOfDayCondition** | Unsupported | | | -| ByValueCondition.**SimulationTimeCondition** | ✔ | No | | -| ByValueCondition.**StoryboardElementStateCondition** | ✔ | See [here](#storyboardelementstatecondition) | | -| ByValueCondition.**UserDefinedValueCondition** | ✔ | | | -| ByValueCondition.**TrafficSignalCondition** | ✔ | | | -| ByValueCondition.**TrafficSignalControllerCondition** | ✔ | | | -| ByValueCondition.**VariableCondition** | Unsupported | | created in v1.2 | +- Property `Position` of types `RoadPosition`, `RelativeRoadPosition`, `RelativeLanePosition`, `RoutePosition`, `GeoPosition`, and `TrajectoryPosition` are **not** supported. +- Not all combinations of properties for distance calculation are supported. Supported combinations are listed below: + | coordinateSystem | relativeDistanceType | routingAlgorithm | freespace | + |:----------------:|:--------------------:|:----------------:|:---------:| + | entity | euclidianDistance | undefined | false | + | entity | euclidianDistance | undefined | true | + | entity | lateral | undefined | false | + | entity | lateral | undefined | true | + | entity | longitudinal | undefined | false | + | entity | longitudinal | undefined | true | + | lane | lateral | undefined | false | + | lane | lateral | undefined | true | + | lane | longitudinal | undefined | false | + | lane | longitudinal | undefined | true | + | lane | lateral | shortest | false | + | lane | lateral | shortest | true | + | lane | longitudinal | shortest | false | + | lane | longitudinal | shortest | true | -## Limitations +#### RelativeDistanceType -### ParameterSetAction +- Enumeration literal `cartesianDistance` deprecated in version 1.1 is **not** supported. -- Currently, ParameterSetAction cannot handle `dateTime` type parameters. +#### RoadNetwork -### CustomCommandAction -#### WalkStraightAction -- This action is a temporary feature until `FollowTrajectoryAction` is implemented. -- This action cannot be used in combination with `AcquirePositionAction` because `WalkStraightAction` just makes a pedestrian NPC go straight without a destination. +- Property `UsedArea` is ignored. +#### RouteStrategy -### SpeedAction +- Enumeration literals `fastest`, `leastIntersections` and `random` are **not** supported. -- The implementation of type [TransitionDynamics](#transitiondynamics) for element `SpeedActionDynamics` is incomplete and - **SpeedActionDynamics.dynamicsDimension is ignored**. +#### RoutingAction -### LaneChangeAction +- Property `RandomRouteAction` created in version 1.3 is **not** supported. -- The implementation of type [TransitionDynamics](#transitiondynamics) for element `LaneChangeActionDynamics` and type [LaneChangeTarget](#lanechangetarget) for element `LaneChangeTarget` are incomplete. +#### ScenarioDefinition -### TeleportAction - -- Currently, **only LanePosition** can be specified for element of - TeleportAction. - -### FollowTrajectoryAction -- Currently, the action handles only "[followingMode](https://www.asam.net/static_downloads/ASAM_OpenSCENARIO_V1.2.0_Model_Documentation/modelDocumentation/content/FollowingMode.html)" attribute set to `position` mode. - -| followingMode | Status | -|:--------------|:-----------:| -| position | ✔ | -| follow | Unsupported | - -- Currently, the action only supports [Trajectory](https://www.asam.net/static_downloads/ASAM_OpenSCENARIO_V1.2.0_Model_Documentation/modelDocumentation/content/Trajectory.html) with a [Polyline](https://www.asam.net/static_downloads/ASAM_OpenSCENARIO_V1.2.0_Model_Documentation/modelDocumentation/content/Shape.html) shape. - -| Element | Status | -|:---------|:----------:| -| Polyline | ✔ | -| Clothoid | Unsupported| -| Nurbs | Unsupported| - -### AcquirePositionAction - -- Currently, **only LanePosition** can be specified for element of - AcquirePositionAction. - -### CollisionCondition +- Property `VariableDeclarations` created in version 1.2 is ignored. +- Property `MonitorDeclarations` created in version 1.3 is ignored. -- Currently, **only EntityRef** can be specified for element of - CollisionCondition. +#### Shape -### TimeHeadwayCondition +- Properties `Clothoid` and `Nurbs` are **not** supported. +- Property `ClothoidSpline` created in version 1.3 is **not** supported. -- Currently, the values of attribute "freespace" and "alongRoute" are ignored and always behave as if freespace="false" and alongRoute="true" were specified. +#### SpeedAction -### ReachPositionCondition +- Specifying `time` or `distance` for `SpeedActionDynamics.dynamicsDimension` is **not** supported. + - Simulator may lead to an undefined behavior if `time` or `distance` is specified. +- Specifying `cubic` for `SpeedActionDynamics.dynamicsShape` is **not** supported. + - Simulator may lead to an undefined behavior if `cubic` is specified. -- Currently, **only LanePosition and WorldPosition** can be specified for the element of ReachPositionCondition. +#### SpeedCondition -### DistanceCondition +- Property `direction` is ignored. + - The simulator behaves as if `direction` is not given. -- Currently, the values of attribute "alongRoute" is ignored and always behave as if alongRoute="false" was specified. -- Currently, **only LanePosition and WorldPosition** can be specified for the element of Position of DistanceCondition. +#### StochasticDistributionType -### StoryboardElementStateCondition +- Property `LogNormalDistribution` created in version 1.3 is **not** supported. -- Currently, a feature called "name prefix" (in [OpenSCENARIO User Guide 3.1.2. Naming](https://releases.asam.net/OpenSCENARIO/1.0.0/ASAM_OpenSCENARIO_BS-1-2_User-Guide_V1-0-0.html#_general_concepts)) is unsupported. +#### StoryboardElementStateCondition -Instead, our interpreter implements lexical scoping. -See also section [Scoping](#scoping). +- [name prefix](https://releases.asam.net/OpenSCENARIO/1.0.0/ASAM_OpenSCENARIO_BS-1-2_User-Guide_V1-0-0.html#:~:text=A%20name%20prefix%20,new%20name%20reference.) in OpenSCENARIO User Guide 3.1.2. is **not** supported. + - The interpreter uses lexical scope instead. See [Scoping](#Scoping) for more details. -### TransitionDynamics +#### Sun -- The implementation of type [DynamicsShape](#dynamicsshape) for attribute dynamicsShape is incomplete. +- Property `intensity` deprecated in version 1.2 is still supported. -| Name | Type | Status | -|:------------------|:--------------------------------|:----------:| -| dynamicsShape | [DynamicsShape](#dynamicsshape) | Incomplete | -| value | Double | ✔ | -| dynamicsDimension | DynamicsDimension | ✔ | +#### TeleportAction -### DynamicsShape +- Property `Position` of types `RoadPosition`, `RelativeRoadPosition`, `RelativeLanePosition`, `RoutePosition`, `GeoPosition`, and `TrajectoryPosition` are **not** supported. -- Currently, only `linear` and `step` are implemented for values of this enumeration. - If you specify `cubic` and `sinusoidal`, you will get an ImplementationFault. +#### TimeHeadwayCondition -| Value | Status | -|:-----------|:-----------:| -| linear | ✔ | -| cubic | Unsupported | -| sinusoidal | Unsupported | -| step | ✔ | +- Properties `coordinateSystem` and `relativeDistanceType` created in version 1.1 is ignored. +- Property `alongRoute` deprecated in version 1.1 is ignored. +- Property `freespace` is ignored. + - The simulator behaves as if `freespace` is `false`. -### LaneChangeTarget +#### TransitionDynamics -- Currently, only AbsoluteTargetLane is implemented for element of this type. - If you specify RelativeTargetLane, you will get a SyntaxError. +- Property `followingMode` created in version 1.2 is ignored. -| Element | Status | -|:-------------------|:-----------:| -| AbsoluteTargetLane | ✔ | -| RelativeTargetLane | Unsupported | +#### TriggeringEntitiesRule -### Position +- Enumeration literal `none` is added as TIER IV extension. -- Currently, only WorldPosition and LanePosition are implemented for an element of this type. +#### Vehicle -| Element | Status | -|:-----------------------|:-----------:| -| WorldPosition | ✔ | -| RelativeWorldPosition | Unsupported | -| RelativeObjectPosition | ✔ | -| RoadPosition | Unsupported | -| RelativeRoadPosition | Unsupported | -| LanePosition | ✔ | -| RelativeLanePosition | Unsupported | -| RoutePosition | Unsupported | +- Property `role` created in version 1.1 is ignored. + - The simulator does not take into account `role`. +- Property `mass` is ignored. + - The simulator behaves as if `mass` is not given. From 93b86bc1b6d130f988643859789ce3d8e1d3f9f4 Mon Sep 17 00:00:00 2001 From: Shota Minami Date: Thu, 25 Jul 2024 01:34:05 +0000 Subject: [PATCH 041/304] Fix typo --- docs/developer_guide/OpenSCENARIOSupport.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/developer_guide/OpenSCENARIOSupport.md b/docs/developer_guide/OpenSCENARIOSupport.md index b8b71f4628f..6cac4e739c0 100644 --- a/docs/developer_guide/OpenSCENARIOSupport.md +++ b/docs/developer_guide/OpenSCENARIOSupport.md @@ -175,7 +175,7 @@ Calculates the relative angle between the orientation of `` and the Calculates the relative angle between the orientation of `` and the direction at the position specified by `` on ``. -#### ROS2 Topic Condition +#### ROS 2 Topic Condition `scenario_simulator_v2` can read values from another ROS 2 node to a scenario through ROS 2 topics. `name` field should be filled with the name of the ROS 2 topic like below. From bc92069b7e16c823f4a3acb1126e7b7408c330ea Mon Sep 17 00:00:00 2001 From: Shota Minami Date: Thu, 25 Jul 2024 01:36:30 +0000 Subject: [PATCH 042/304] Fix typo --- docs/developer_guide/OpenSCENARIOSupport.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/developer_guide/OpenSCENARIOSupport.md b/docs/developer_guide/OpenSCENARIOSupport.md index 6cac4e739c0..ebe4b2c849b 100644 --- a/docs/developer_guide/OpenSCENARIOSupport.md +++ b/docs/developer_guide/OpenSCENARIOSupport.md @@ -727,7 +727,7 @@ Currently, the only way to know the result of the simulation is by viewing the s #### PedestrianCategory -- Enumeration literals `wheelchar` and `animal` are **not** supported. +- Enumeration literals `wheelchair` and `animal` are **not** supported. #### Phase From 441ed76896cee76779c007a0e3df375a9b072bb1 Mon Sep 17 00:00:00 2001 From: Shota Minami Date: Thu, 25 Jul 2024 01:39:11 +0000 Subject: [PATCH 043/304] Add `Cmyk` to custom_spell.json --- .github/workflows/custom_spell.json | 1 + 1 file changed, 1 insertion(+) diff --git a/.github/workflows/custom_spell.json b/.github/workflows/custom_spell.json index 32db063ea4e..cecc85a3aab 100644 --- a/.github/workflows/custom_spell.json +++ b/.github/workflows/custom_spell.json @@ -6,6 +6,7 @@ "Canonicalized", "canonicalizing", "classname", + "Cmyk", "Dawid", "DBOOST", "DBUILD", From 74da50b8ba8563e22da04c1e45d057b944db31f4 Mon Sep 17 00:00:00 2001 From: Shota Minami Date: Thu, 25 Jul 2024 01:41:50 +0000 Subject: [PATCH 044/304] Change section title --- docs/developer_guide/OpenSCENARIOSupport.md | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/docs/developer_guide/OpenSCENARIOSupport.md b/docs/developer_guide/OpenSCENARIOSupport.md index ebe4b2c849b..26012086727 100644 --- a/docs/developer_guide/OpenSCENARIOSupport.md +++ b/docs/developer_guide/OpenSCENARIOSupport.md @@ -220,7 +220,8 @@ Within the scenario, you can end the scenario simulation with a status of either > `exitSuccess` and `exitFailure` terminate the simulation immediately without any state transitions in the lifecycle of a `StoryboardElement`. This means there is no way to detect simulations terminated by `exitSuccess` or `exitFailure` from within the scenario using conditions like `StoryboardElementStateCondition`. Currently, the only way to know the result of the simulation is by viewing the status string printed to standard output. However, this method may change in the future. -## Conformance + +## Standards Supported by `scenario_simulator_v2` | Name | Supported Version | Detail | |:---------------------------------------------|:-----------------:|:------------------------------------------:| From 82f6b2517c4e46b921c2cf750d71613488362e8d Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Thu, 25 Jul 2024 17:26:14 +0900 Subject: [PATCH 045/304] Update ByEntityCondition.EntityCondition.RelativeClearanceCondition.yaml to check RelativeClearanceCondition in more detail --- ...yCondition.RelativeClearanceCondition.yaml | 174 ++++++++++-------- 1 file changed, 101 insertions(+), 73 deletions(-) diff --git a/test_runner/scenario_test_runner/scenario/ByEntityCondition.EntityCondition.RelativeClearanceCondition.yaml b/test_runner/scenario_test_runner/scenario/ByEntityCondition.EntityCondition.RelativeClearanceCondition.yaml index 9311a799ac5..5dd00cce153 100644 --- a/test_runner/scenario_test_runner/scenario/ByEntityCondition.EntityCondition.RelativeClearanceCondition.yaml +++ b/test_runner/scenario_test_runner/scenario/ByEntityCondition.EntityCondition.RelativeClearanceCondition.yaml @@ -20,13 +20,13 @@ OpenSCENARIO: CatalogReference: &SAMPLE_VEHICLE catalogName: sample_vehicle entryName: sample_vehicle - - name: car_1 + - name: car_same_front CatalogReference: *SAMPLE_VEHICLE - - name: car_2 + - name: car_right_front CatalogReference: *SAMPLE_VEHICLE - - name: car_3 + - name: car_right_back CatalogReference: *SAMPLE_VEHICLE - - name: car_4 + - name: car_same_back CatalogReference: *SAMPLE_VEHICLE Storyboard: Init: @@ -39,7 +39,7 @@ OpenSCENARIO: LanePosition: &EGO_LANE_POSITION roadId: "" laneId: 34513 - s: 10 + s: 15 offset: 0 Orientation: type: relative @@ -55,7 +55,7 @@ OpenSCENARIO: SpeedActionTarget: AbsoluteTargetSpeed: value: 0 - - entityRef: car_1 + - entityRef: car_same_front PrivateAction: - TeleportAction: Position: @@ -63,7 +63,7 @@ OpenSCENARIO: << : *EGO_LANE_POSITION s: 20 - LongitudinalAction: *SPEED_ACTION_ZERO - - entityRef: car_2 + - entityRef: car_right_front PrivateAction: - TeleportAction: Position: @@ -72,22 +72,22 @@ OpenSCENARIO: laneId: 34462 s: 20 - LongitudinalAction: *SPEED_ACTION_ZERO - - entityRef: car_3 + - entityRef: car_right_back PrivateAction: - TeleportAction: Position: LanePosition: << : *EGO_LANE_POSITION laneId: 34462 - s: 5 + s: 10 - LongitudinalAction: *SPEED_ACTION_ZERO - - entityRef: car_4 + - entityRef: car_same_back PrivateAction: - TeleportAction: Position: LanePosition: << : *EGO_LANE_POSITION - s: 5 + s: 10 - LongitudinalAction: *SPEED_ACTION_ZERO Story: - name: story @@ -103,17 +103,17 @@ OpenSCENARIO: Maneuver: - name: maneuver Event: - - name: success + - name: failure priority: parallel Action: - name: "" UserDefinedAction: CustomCommandAction: - type: exitSuccess + type: exitFailure StartTrigger: ConditionGroup: - Condition: - - name: "" + - name: "check all car is in range(not clear) means the condition is false" delay: 0 conditionEdge: none ByEntityCondition: @@ -123,13 +123,12 @@ OpenSCENARIO: - entityRef: ego EntityCondition: RelativeClearanceCondition: - EntityRef: - - entityRef: car_1 - distanceBackward: 0 - distanceForward: 9 + distanceBackward: 7 + distanceForward: 7 freeSpace: false oppositeLanes: false - - name: "" + - Condition: + - name: "check not all car is in range(not clear) means the condition is false" delay: 0 conditionEdge: none ByEntityCondition: @@ -139,87 +138,116 @@ OpenSCENARIO: - entityRef: ego EntityCondition: RelativeClearanceCondition: - EntityRef: - - entityRef: car_1 - distanceBackward: 0 - distanceForward: 9 + distanceBackward: 7 + distanceForward: 0 freeSpace: false oppositeLanes: false - - name: "" + - Condition: + - name: "timeout" + delay: 0 + conditionEdge: none + ByValueCondition: + SimulationTimeCondition: + value: 1 + rule: greaterThan + - name: success + priority: parallel + Action: + - name: "" + UserDefinedAction: + CustomCommandAction: + type: exitSuccess + StartTrigger: + ConditionGroup: + - Condition: + - name: "check clear with all cars in narrower longitudinal range" delay: 0 conditionEdge: none ByEntityCondition: TriggeringEntities: triggeringEntitiesRule: all EntityRef: - - entityRef: car_3 - - entityRef: car_4 + - entityRef: ego EntityCondition: - RelativeDistanceCondition: - coordinateSystem: lane - entityRef: ego - freespace: false # True: distance is measured between closest bounding box points. False: reference point distance is used. - relativeDistanceType: longitudinal - rule: equalTo - value: 10 - - name: "" + RelativeClearanceCondition: + distanceBackward: 3 + distanceForward: 3 + freeSpace: false + oppositeLanes: false + - name: "check back is clear with front cars" delay: 0 conditionEdge: none ByEntityCondition: TriggeringEntities: triggeringEntitiesRule: all EntityRef: - - entityRef: car_1 - - entityRef: car_3 + - entityRef: ego EntityCondition: - RelativeDistanceCondition: - coordinateSystem: lane - entityRef: ego - freespace: false # True: distance is measured between closest bounding box points. False: reference point distance is used. - relativeDistanceType: lateral - rule: equalTo - value: -1.5 - - name: "" + RelativeClearanceCondition: + EntityRef: + - entityRef: car_same_front + - entityRef: car_right_front + distanceBackward: 7 + distanceForward: 0 + freeSpace: false + oppositeLanes: false + - name: "check front is clear with back cars" delay: 0 conditionEdge: none ByEntityCondition: TriggeringEntities: triggeringEntitiesRule: all EntityRef: - - entityRef: car_2 - - entityRef: car_4 + - entityRef: ego EntityCondition: - RelativeDistanceCondition: - coordinateSystem: lane - entityRef: ego - freespace: false # True: distance is measured between closest bounding box points. False: reference point distance is used. - relativeDistanceType: lateral - rule: equalTo - value: 0.5 - - name: "" + RelativeClearanceCondition: + EntityRef: + - entityRef: car_right_back + - entityRef: car_same_back + distanceBackward: 0 + distanceForward: 7 + freeSpace: false + oppositeLanes: false + - name: "check right is clear with cars in the same lane" delay: 0 conditionEdge: none - ByValueCondition: - SimulationTimeCondition: - value: 10 - rule: greaterThan - - name: failure - priority: parallel - Action: - - name: "" - UserDefinedAction: - CustomCommandAction: - type: exitFailure - StartTrigger: - ConditionGroup: - - Condition: - - name: "" + ByEntityCondition: + TriggeringEntities: + triggeringEntitiesRule: all + EntityRef: + - entityRef: ego + EntityCondition: + RelativeClearanceCondition: + EntityRef: + - entityRef: car_same_front + - entityRef: car_same_back + distanceBackward: 7 + distanceForward: 7 + freeSpace: false + oppositeLanes: false + RelativeLaneRange: + - from: -1 + to: -1 + - name: "check same lane is clear with cars in the right lane" delay: 0 conditionEdge: none - ByValueCondition: - SimulationTimeCondition: - value: 20 - rule: greaterThan + ByEntityCondition: + TriggeringEntities: + triggeringEntitiesRule: all + EntityRef: + - entityRef: ego + EntityCondition: + RelativeClearanceCondition: + EntityRef: + - entityRef: car_right_front + - entityRef: car_right_back + distanceBackward: 7 + distanceForward: 7 + freeSpace: false + oppositeLanes: false + RelativeLaneRange: + - from: 0 + to: 0 StartTrigger: ConditionGroup: - Condition: From 8b3f33227019847b0114c8ada53e8b3ff76da87b Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Thu, 25 Jul 2024 17:34:30 +0900 Subject: [PATCH 046/304] fix condition logic of RelativeClearanceCondition --- .../syntax/relative_clearance_condition.cpp | 20 ++++++++++++++----- 1 file changed, 15 insertions(+), 5 deletions(-) diff --git a/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp b/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp index 6a7c556aa11..cdfcabea439 100644 --- a/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp @@ -34,8 +34,15 @@ RelativeClearanceCondition::RelativeClearanceCondition( entity_refs([&]() { auto entities = readElements("EntityRef", node, scope); if (entities.empty()) { - for (const auto & [name, entity] : *global().entities) { - entities.emplace_back(name); + for (const auto & entity : *global().entities) { + if ( + std::find_if( + triggering_entities.entity_refs.begin(), triggering_entities.entity_refs.end(), + [&](const auto & triggering_entity) { + return triggering_entity.name() == entity.first; + }) == triggering_entities.entity_refs.end()) { + entities.emplace_back(name); + } } } return entities; @@ -61,8 +68,9 @@ auto RelativeClearanceCondition::description() const -> String auto RelativeClearanceCondition::evaluate() -> Object { return asBoolean(triggering_entities.apply([&](const auto & triggering_entity) { - for (const auto & entity : entity_refs) { + return std::all_of(entity_refs.begin(), entity_refs.end(), [&](const auto & entity) { auto is_in_lateral_range = [&]() { + // The lanes to be checked to left and right of the triggering entity (positive to the y-axis). If omitted: all lanes are checked. if (relative_lane_range.empty()) { return true; } else { @@ -85,8 +93,10 @@ auto RelativeClearanceCondition::evaluate() -> Object } }; - return is_in_lateral_range() && is_in_longitudinal_range(); - } + auto lat_ok = is_in_lateral_range(); + auto lon_ok = is_in_longitudinal_range(); + return not(lat_ok && lon_ok); + }); })); } From 39594fd362c91b32514863d4ee02b2d4dcaaf69a Mon Sep 17 00:00:00 2001 From: Release Bot Date: Fri, 26 Jul 2024 06:05:55 +0000 Subject: [PATCH 047/304] Bump version of scenario_simulator_v2 from version 3.3.0 to version 3.4.0 --- common/math/arithmetic/CHANGELOG.rst | 3 +++ common/math/arithmetic/package.xml | 2 +- common/math/geometry/CHANGELOG.rst | 3 +++ common/math/geometry/package.xml | 2 +- common/scenario_simulator_exception/CHANGELOG.rst | 3 +++ common/scenario_simulator_exception/package.xml | 2 +- common/simple_junit/CHANGELOG.rst | 3 +++ common/simple_junit/package.xml | 2 +- common/status_monitor/CHANGELOG.rst | 3 +++ common/status_monitor/package.xml | 2 +- external/concealer/CHANGELOG.rst | 3 +++ external/concealer/package.xml | 2 +- external/embree_vendor/CHANGELOG.rst | 3 +++ external/embree_vendor/package.xml | 2 +- map/kashiwanoha_map/CHANGELOG.rst | 3 +++ map/kashiwanoha_map/package.xml | 2 +- map/simple_cross_map/CHANGELOG.rst | 3 +++ map/simple_cross_map/package.xml | 2 +- mock/cpp_mock_scenarios/CHANGELOG.rst | 3 +++ mock/cpp_mock_scenarios/package.xml | 2 +- .../openscenario_experimental_catalog/CHANGELOG.rst | 3 +++ .../openscenario_experimental_catalog/package.xml | 2 +- openscenario/openscenario_interpreter/CHANGELOG.rst | 8 ++++++++ openscenario/openscenario_interpreter/package.xml | 2 +- .../openscenario_interpreter_example/CHANGELOG.rst | 3 +++ openscenario/openscenario_interpreter_example/package.xml | 2 +- openscenario/openscenario_interpreter_msgs/CHANGELOG.rst | 3 +++ openscenario/openscenario_interpreter_msgs/package.xml | 2 +- openscenario/openscenario_preprocessor/CHANGELOG.rst | 3 +++ openscenario/openscenario_preprocessor/package.xml | 2 +- openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst | 3 +++ openscenario/openscenario_preprocessor_msgs/package.xml | 2 +- openscenario/openscenario_utility/CHANGELOG.rst | 3 +++ openscenario/openscenario_utility/package.xml | 2 +- openscenario/openscenario_validator/CHANGELOG.rst | 3 +++ openscenario/openscenario_validator/package.xml | 2 +- rviz_plugins/openscenario_visualization/CHANGELOG.rst | 3 +++ rviz_plugins/openscenario_visualization/package.xml | 2 +- .../real_time_factor_control_rviz_plugin/CHANGELOG.rst | 3 +++ .../real_time_factor_control_rviz_plugin/package.xml | 2 +- scenario_simulator_v2/CHANGELOG.rst | 3 +++ scenario_simulator_v2/package.xml | 2 +- simulation/behavior_tree_plugin/CHANGELOG.rst | 3 +++ simulation/behavior_tree_plugin/package.xml | 2 +- simulation/do_nothing_plugin/CHANGELOG.rst | 3 +++ simulation/do_nothing_plugin/package.xml | 2 +- simulation/simple_sensor_simulator/CHANGELOG.rst | 3 +++ simulation/simple_sensor_simulator/package.xml | 2 +- simulation/simulation_interface/CHANGELOG.rst | 3 +++ simulation/simulation_interface/package.xml | 2 +- simulation/traffic_simulator/CHANGELOG.rst | 7 +++++++ simulation/traffic_simulator/package.xml | 2 +- simulation/traffic_simulator_msgs/CHANGELOG.rst | 3 +++ simulation/traffic_simulator_msgs/package.xml | 2 +- test_runner/random_test_runner/CHANGELOG.rst | 3 +++ test_runner/random_test_runner/package.xml | 2 +- test_runner/scenario_test_runner/CHANGELOG.rst | 7 +++++++ test_runner/scenario_test_runner/package.xml | 2 +- 58 files changed, 129 insertions(+), 29 deletions(-) diff --git a/common/math/arithmetic/CHANGELOG.rst b/common/math/arithmetic/CHANGELOG.rst index 991cd182db2..f02dfd36e72 100644 --- a/common/math/arithmetic/CHANGELOG.rst +++ b/common/math/arithmetic/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package arithmetic * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.0 (2024-07-26) +------------------ + 3.3.0 (2024-07-23) ------------------ * Merge branch 'master' into feature/interpreter/entity_selection diff --git a/common/math/arithmetic/package.xml b/common/math/arithmetic/package.xml index 920c1f5df8a..0898ae893af 100644 --- a/common/math/arithmetic/package.xml +++ b/common/math/arithmetic/package.xml @@ -2,7 +2,7 @@ arithmetic - 3.3.0 + 3.4.0 arithmetic library for scenario_simulator_v2 Tatsuya Yamasaki Apache License 2.0 diff --git a/common/math/geometry/CHANGELOG.rst b/common/math/geometry/CHANGELOG.rst index b6182992b5d..c6a59c5c4bf 100644 --- a/common/math/geometry/CHANGELOG.rst +++ b/common/math/geometry/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package geometry * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.0 (2024-07-26) +------------------ + 3.3.0 (2024-07-23) ------------------ * Merge branch 'master' into feature/interpreter/entity_selection diff --git a/common/math/geometry/package.xml b/common/math/geometry/package.xml index a6521ca64fa..05964560f14 100644 --- a/common/math/geometry/package.xml +++ b/common/math/geometry/package.xml @@ -2,7 +2,7 @@ geometry - 3.3.0 + 3.4.0 geometry math library for scenario_simulator_v2 application Masaya Kataoka Apache License 2.0 diff --git a/common/scenario_simulator_exception/CHANGELOG.rst b/common/scenario_simulator_exception/CHANGELOG.rst index e1ddf9f9b3b..c5e3be0275d 100644 --- a/common/scenario_simulator_exception/CHANGELOG.rst +++ b/common/scenario_simulator_exception/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package scenario_simulator_exception * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.0 (2024-07-26) +------------------ + 3.3.0 (2024-07-23) ------------------ * Merge branch 'master' into feature/interpreter/entity_selection diff --git a/common/scenario_simulator_exception/package.xml b/common/scenario_simulator_exception/package.xml index 5239189d015..e67f5d199fa 100644 --- a/common/scenario_simulator_exception/package.xml +++ b/common/scenario_simulator_exception/package.xml @@ -2,7 +2,7 @@ scenario_simulator_exception - 3.3.0 + 3.4.0 Exception types for scenario simulator Tatsuya Yamasaki Apache License 2.0 diff --git a/common/simple_junit/CHANGELOG.rst b/common/simple_junit/CHANGELOG.rst index 0258b39f883..b9ee3aef00e 100644 --- a/common/simple_junit/CHANGELOG.rst +++ b/common/simple_junit/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package junit_exporter * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.0 (2024-07-26) +------------------ + 3.3.0 (2024-07-23) ------------------ * Merge branch 'master' into feature/interpreter/entity_selection diff --git a/common/simple_junit/package.xml b/common/simple_junit/package.xml index fcf3f77b8af..70da1e4a78b 100644 --- a/common/simple_junit/package.xml +++ b/common/simple_junit/package.xml @@ -2,7 +2,7 @@ simple_junit - 3.3.0 + 3.4.0 Lightweight JUnit library for ROS 2 Masaya Kataoka Tatsuya Yamasaki diff --git a/common/status_monitor/CHANGELOG.rst b/common/status_monitor/CHANGELOG.rst index b6124b6bb2a..e02e471460d 100644 --- a/common/status_monitor/CHANGELOG.rst +++ b/common/status_monitor/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package status_monitor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.0 (2024-07-26) +------------------ + 3.3.0 (2024-07-23) ------------------ * Merge branch 'master' into feature/interpreter/entity_selection diff --git a/common/status_monitor/package.xml b/common/status_monitor/package.xml index 87e6dbcc8de..56e8f7bfcd6 100644 --- a/common/status_monitor/package.xml +++ b/common/status_monitor/package.xml @@ -2,7 +2,7 @@ status_monitor - 3.3.0 + 3.4.0 none Tatsuya Yamasaki Apache License 2.0 diff --git a/external/concealer/CHANGELOG.rst b/external/concealer/CHANGELOG.rst index 9b7ec240312..732dcf2f3d3 100644 --- a/external/concealer/CHANGELOG.rst +++ b/external/concealer/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package concealer * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.0 (2024-07-26) +------------------ + 3.3.0 (2024-07-23) ------------------ * Merge branch 'master' into feature/interpreter/entity_selection diff --git a/external/concealer/package.xml b/external/concealer/package.xml index 0470dd272bb..9fd05b96c92 100644 --- a/external/concealer/package.xml +++ b/external/concealer/package.xml @@ -2,7 +2,7 @@ concealer - 3.3.0 + 3.4.0 Provides a class 'Autoware' to conceal miscellaneous things to simplify Autoware management of the simulator. Tatsuya Yamasaki Apache License 2.0 diff --git a/external/embree_vendor/CHANGELOG.rst b/external/embree_vendor/CHANGELOG.rst index 4501671a247..f6cfac2ba57 100644 --- a/external/embree_vendor/CHANGELOG.rst +++ b/external/embree_vendor/CHANGELOG.rst @@ -24,6 +24,9 @@ Changelog for package embree_vendor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.0 (2024-07-26) +------------------ + 3.3.0 (2024-07-23) ------------------ * Merge branch 'master' into feature/interpreter/entity_selection diff --git a/external/embree_vendor/package.xml b/external/embree_vendor/package.xml index 1b54a660046..f597e89ed18 100644 --- a/external/embree_vendor/package.xml +++ b/external/embree_vendor/package.xml @@ -2,7 +2,7 @@ embree_vendor - 3.3.0 + 3.4.0 vendor packages for intel raytracing kernel library masaya Apache 2.0 diff --git a/map/kashiwanoha_map/CHANGELOG.rst b/map/kashiwanoha_map/CHANGELOG.rst index 46d89ea6249..016de2404ea 100644 --- a/map/kashiwanoha_map/CHANGELOG.rst +++ b/map/kashiwanoha_map/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package kashiwanoha_map * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.0 (2024-07-26) +------------------ + 3.3.0 (2024-07-23) ------------------ * Merge branch 'master' into feature/interpreter/entity_selection diff --git a/map/kashiwanoha_map/package.xml b/map/kashiwanoha_map/package.xml index ce4b1ededfc..b51c782f6c7 100644 --- a/map/kashiwanoha_map/package.xml +++ b/map/kashiwanoha_map/package.xml @@ -2,7 +2,7 @@ kashiwanoha_map - 3.3.0 + 3.4.0 map package for kashiwanoha Masaya Kataoka Apache License 2.0 diff --git a/map/simple_cross_map/CHANGELOG.rst b/map/simple_cross_map/CHANGELOG.rst index 22282cbb198..aeb9fab9012 100644 --- a/map/simple_cross_map/CHANGELOG.rst +++ b/map/simple_cross_map/CHANGELOG.rst @@ -9,6 +9,9 @@ Changelog for package simple_cross_map * Merge branch 'master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.0 (2024-07-26) +------------------ + 3.3.0 (2024-07-23) ------------------ * Merge branch 'master' into feature/interpreter/entity_selection diff --git a/map/simple_cross_map/package.xml b/map/simple_cross_map/package.xml index acbf5dd783f..884f93aaa43 100644 --- a/map/simple_cross_map/package.xml +++ b/map/simple_cross_map/package.xml @@ -2,7 +2,7 @@ simple_cross_map - 3.3.0 + 3.4.0 map package for simple cross Masaya Kataoka Apache License 2.0 diff --git a/mock/cpp_mock_scenarios/CHANGELOG.rst b/mock/cpp_mock_scenarios/CHANGELOG.rst index bc906333fd7..2f3d85c8d6a 100644 --- a/mock/cpp_mock_scenarios/CHANGELOG.rst +++ b/mock/cpp_mock_scenarios/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package cpp_mock_scenarios * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.0 (2024-07-26) +------------------ + 3.3.0 (2024-07-23) ------------------ * Merge branch 'master' into feature/interpreter/entity_selection diff --git a/mock/cpp_mock_scenarios/package.xml b/mock/cpp_mock_scenarios/package.xml index 255412c1756..2b6179b986b 100644 --- a/mock/cpp_mock_scenarios/package.xml +++ b/mock/cpp_mock_scenarios/package.xml @@ -2,7 +2,7 @@ cpp_mock_scenarios - 3.3.0 + 3.4.0 C++ mock scenarios masaya Apache License 2.0 diff --git a/openscenario/openscenario_experimental_catalog/CHANGELOG.rst b/openscenario/openscenario_experimental_catalog/CHANGELOG.rst index 39a4d45eb67..3b045468fa0 100644 --- a/openscenario/openscenario_experimental_catalog/CHANGELOG.rst +++ b/openscenario/openscenario_experimental_catalog/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package openscenario_experimental_catalog * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.0 (2024-07-26) +------------------ + 3.3.0 (2024-07-23) ------------------ * Merge branch 'master' into feature/interpreter/entity_selection diff --git a/openscenario/openscenario_experimental_catalog/package.xml b/openscenario/openscenario_experimental_catalog/package.xml index 5fa44633a10..74baf0143e7 100644 --- a/openscenario/openscenario_experimental_catalog/package.xml +++ b/openscenario/openscenario_experimental_catalog/package.xml @@ -2,7 +2,7 @@ openscenario_experimental_catalog - 3.3.0 + 3.4.0 TIER IV experimental catalogs for OpenSCENARIO Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter/CHANGELOG.rst b/openscenario/openscenario_interpreter/CHANGELOG.rst index c21bae1b89e..466ed93a195 100644 --- a/openscenario/openscenario_interpreter/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter/CHANGELOG.rst @@ -32,6 +32,14 @@ Changelog for package openscenario_interpreter * add publish_empty_context parameter * Contributors: Masaya Kataoka +3.4.0 (2024-07-26) +------------------ +* Merge pull request `#1325 `_ from tier4/feature/interpreter/lidar-configuration + Feature/interpreter/lidar configuration +* Add a test scenario for `ObjectController`'s pseudo LiDAR property +* Update ControllerAction to support some new properties related to LiDAR +* Contributors: Masaya Kataoka, yamacir-kit + 3.3.0 (2024-07-23) ------------------ * Merge pull request `#1059 `_ from tier4/feature/interpreter/entity_selection diff --git a/openscenario/openscenario_interpreter/package.xml b/openscenario/openscenario_interpreter/package.xml index ffdbdffdd2f..24e6778cf32 100644 --- a/openscenario/openscenario_interpreter/package.xml +++ b/openscenario/openscenario_interpreter/package.xml @@ -2,7 +2,7 @@ openscenario_interpreter - 3.3.0 + 3.4.0 OpenSCENARIO 1.2.0 interpreter package for Autoware Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter_example/CHANGELOG.rst b/openscenario/openscenario_interpreter_example/CHANGELOG.rst index 901a263cbcc..a2f4f8b845a 100644 --- a/openscenario/openscenario_interpreter_example/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter_example/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package openscenario_interpreter_example * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.0 (2024-07-26) +------------------ + 3.3.0 (2024-07-23) ------------------ * Merge branch 'master' into feature/interpreter/entity_selection diff --git a/openscenario/openscenario_interpreter_example/package.xml b/openscenario/openscenario_interpreter_example/package.xml index 21895c9830b..2b6f6b35019 100644 --- a/openscenario/openscenario_interpreter_example/package.xml +++ b/openscenario/openscenario_interpreter_example/package.xml @@ -3,7 +3,7 @@ openscenario_interpreter_example - 3.3.0 + 3.4.0 Examples for some TIER IV OpenSCENARIO Interpreter's features Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst b/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst index 0fe321e7b1f..ccf9beef780 100644 --- a/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package openscenario_interpreter_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.0 (2024-07-26) +------------------ + 3.3.0 (2024-07-23) ------------------ * Merge branch 'master' into feature/interpreter/entity_selection diff --git a/openscenario/openscenario_interpreter_msgs/package.xml b/openscenario/openscenario_interpreter_msgs/package.xml index f61976af7e3..3db1ab61b94 100644 --- a/openscenario/openscenario_interpreter_msgs/package.xml +++ b/openscenario/openscenario_interpreter_msgs/package.xml @@ -2,7 +2,7 @@ openscenario_interpreter_msgs - 3.3.0 + 3.4.0 ROS message types for package openscenario_interpreter Yamasaki Tatsuya Apache License 2.0 diff --git a/openscenario/openscenario_preprocessor/CHANGELOG.rst b/openscenario/openscenario_preprocessor/CHANGELOG.rst index 9c9fa531704..158a7af0db8 100644 --- a/openscenario/openscenario_preprocessor/CHANGELOG.rst +++ b/openscenario/openscenario_preprocessor/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package openscenario_preprocessor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.0 (2024-07-26) +------------------ + 3.3.0 (2024-07-23) ------------------ * Merge branch 'master' into feature/interpreter/entity_selection diff --git a/openscenario/openscenario_preprocessor/package.xml b/openscenario/openscenario_preprocessor/package.xml index 9cf35811f3b..4a0a90ea450 100644 --- a/openscenario/openscenario_preprocessor/package.xml +++ b/openscenario/openscenario_preprocessor/package.xml @@ -3,7 +3,7 @@ openscenario_preprocessor - 3.3.0 + 3.4.0 Example package for TIER IV OpenSCENARIO Interpreter Kotaro Yoshimoto Apache License 2.0 diff --git a/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst b/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst index 7bbbed269b1..726dfc7eb28 100644 --- a/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst +++ b/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package openscenario_preprocessor_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.0 (2024-07-26) +------------------ + 3.3.0 (2024-07-23) ------------------ * Merge branch 'master' into feature/interpreter/entity_selection diff --git a/openscenario/openscenario_preprocessor_msgs/package.xml b/openscenario/openscenario_preprocessor_msgs/package.xml index 708ee18849f..1a33424fc06 100644 --- a/openscenario/openscenario_preprocessor_msgs/package.xml +++ b/openscenario/openscenario_preprocessor_msgs/package.xml @@ -2,7 +2,7 @@ openscenario_preprocessor_msgs - 3.3.0 + 3.4.0 ROS message types for package openscenario_preprocessor Kotaro Yoshimoto Apache License 2.0 diff --git a/openscenario/openscenario_utility/CHANGELOG.rst b/openscenario/openscenario_utility/CHANGELOG.rst index c0a9eaebdc8..8f89eba97a6 100644 --- a/openscenario/openscenario_utility/CHANGELOG.rst +++ b/openscenario/openscenario_utility/CHANGELOG.rst @@ -24,6 +24,9 @@ Changelog for package openscenario_utility * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.0 (2024-07-26) +------------------ + 3.3.0 (2024-07-23) ------------------ * Merge branch 'master' into feature/interpreter/entity_selection diff --git a/openscenario/openscenario_utility/package.xml b/openscenario/openscenario_utility/package.xml index 8e6d26cf040..f37d57df7f2 100644 --- a/openscenario/openscenario_utility/package.xml +++ b/openscenario/openscenario_utility/package.xml @@ -2,7 +2,7 @@ openscenario_utility - 3.3.0 + 3.4.0 Utility tools for ASAM OpenSCENARIO 1.2.0 Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_validator/CHANGELOG.rst b/openscenario/openscenario_validator/CHANGELOG.rst index 1a1e1c68113..1d6b032c061 100644 --- a/openscenario/openscenario_validator/CHANGELOG.rst +++ b/openscenario/openscenario_validator/CHANGELOG.rst @@ -10,6 +10,9 @@ Changelog for package openscenario_validator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.0 (2024-07-26) +------------------ + 3.3.0 (2024-07-23) ------------------ * Merge branch 'master' into feature/interpreter/entity_selection diff --git a/openscenario/openscenario_validator/package.xml b/openscenario/openscenario_validator/package.xml index e4494bd1ce3..96a78c145e9 100644 --- a/openscenario/openscenario_validator/package.xml +++ b/openscenario/openscenario_validator/package.xml @@ -2,7 +2,7 @@ openscenario_validator - 3.3.0 + 3.4.0 Validator for OpenSCENARIO 1.3 Kotaro Yoshimoto Apache License 2.0 diff --git a/rviz_plugins/openscenario_visualization/CHANGELOG.rst b/rviz_plugins/openscenario_visualization/CHANGELOG.rst index 98236e8269a..1dd9df87bd5 100644 --- a/rviz_plugins/openscenario_visualization/CHANGELOG.rst +++ b/rviz_plugins/openscenario_visualization/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package openscenario_visualization * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.0 (2024-07-26) +------------------ + 3.3.0 (2024-07-23) ------------------ * Merge branch 'master' into feature/interpreter/entity_selection diff --git a/rviz_plugins/openscenario_visualization/package.xml b/rviz_plugins/openscenario_visualization/package.xml index 2ec12cb34a6..8c97d64aaf2 100644 --- a/rviz_plugins/openscenario_visualization/package.xml +++ b/rviz_plugins/openscenario_visualization/package.xml @@ -2,7 +2,7 @@ openscenario_visualization - 3.3.0 + 3.4.0 Visualization tools for simulation results Masaya Kataoka Kyoichi Sugahara diff --git a/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst b/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst index 7e6e0955728..297ef0b0971 100644 --- a/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst +++ b/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package real_time_factor_control_rviz_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.0 (2024-07-26) +------------------ + 3.3.0 (2024-07-23) ------------------ * Merge branch 'master' into feature/interpreter/entity_selection diff --git a/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml b/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml index dcec7f66a56..d89a824aa9b 100644 --- a/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml +++ b/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml @@ -2,7 +2,7 @@ real_time_factor_control_rviz_plugin - 3.3.0 + 3.4.0 Slider controlling real time factor value. Paweł Lech Apache License 2.0 diff --git a/scenario_simulator_v2/CHANGELOG.rst b/scenario_simulator_v2/CHANGELOG.rst index e2c97861495..b6ba188ebe7 100644 --- a/scenario_simulator_v2/CHANGELOG.rst +++ b/scenario_simulator_v2/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package scenario_simulator_v2 * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.0 (2024-07-26) +------------------ + 3.3.0 (2024-07-23) ------------------ * Merge branch 'master' into feature/interpreter/entity_selection diff --git a/scenario_simulator_v2/package.xml b/scenario_simulator_v2/package.xml index 69374013ad2..73ecf3a5149 100644 --- a/scenario_simulator_v2/package.xml +++ b/scenario_simulator_v2/package.xml @@ -2,7 +2,7 @@ scenario_simulator_v2 - 3.3.0 + 3.4.0 scenario testing framework for Autoware Masaya Kataoka Apache License 2.0 diff --git a/simulation/behavior_tree_plugin/CHANGELOG.rst b/simulation/behavior_tree_plugin/CHANGELOG.rst index dc80b692e40..b1581fb72d7 100644 --- a/simulation/behavior_tree_plugin/CHANGELOG.rst +++ b/simulation/behavior_tree_plugin/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package behavior_tree_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.0 (2024-07-26) +------------------ + 3.3.0 (2024-07-23) ------------------ * Merge branch 'master' into feature/interpreter/entity_selection diff --git a/simulation/behavior_tree_plugin/package.xml b/simulation/behavior_tree_plugin/package.xml index abfc5b34317..06c8165220b 100644 --- a/simulation/behavior_tree_plugin/package.xml +++ b/simulation/behavior_tree_plugin/package.xml @@ -2,7 +2,7 @@ behavior_tree_plugin - 3.3.0 + 3.4.0 Behavior tree plugin for traffic_simulator masaya Apache 2.0 diff --git a/simulation/do_nothing_plugin/CHANGELOG.rst b/simulation/do_nothing_plugin/CHANGELOG.rst index f5bb4e87dde..7b0d77c9509 100644 --- a/simulation/do_nothing_plugin/CHANGELOG.rst +++ b/simulation/do_nothing_plugin/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package do_nothing_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.0 (2024-07-26) +------------------ + 3.3.0 (2024-07-23) ------------------ * Merge branch 'master' into feature/interpreter/entity_selection diff --git a/simulation/do_nothing_plugin/package.xml b/simulation/do_nothing_plugin/package.xml index 1f09ab698fc..97d5240f53d 100644 --- a/simulation/do_nothing_plugin/package.xml +++ b/simulation/do_nothing_plugin/package.xml @@ -2,7 +2,7 @@ do_nothing_plugin - 3.3.0 + 3.4.0 Behavior plugin for do nothing Masaya Kataoka Apache 2.0 diff --git a/simulation/simple_sensor_simulator/CHANGELOG.rst b/simulation/simple_sensor_simulator/CHANGELOG.rst index fa1bc752f42..04758f08c86 100644 --- a/simulation/simple_sensor_simulator/CHANGELOG.rst +++ b/simulation/simple_sensor_simulator/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package simple_sensor_simulator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.0 (2024-07-26) +------------------ + 3.3.0 (2024-07-23) ------------------ * Merge branch 'master' into feature/interpreter/entity_selection diff --git a/simulation/simple_sensor_simulator/package.xml b/simulation/simple_sensor_simulator/package.xml index 1e0f85b5aba..dbb6b9b090a 100644 --- a/simulation/simple_sensor_simulator/package.xml +++ b/simulation/simple_sensor_simulator/package.xml @@ -1,7 +1,7 @@ simple_sensor_simulator - 3.3.0 + 3.4.0 simple_sensor_simulator package masaya kataoka diff --git a/simulation/simulation_interface/CHANGELOG.rst b/simulation/simulation_interface/CHANGELOG.rst index 8839262aa35..ed933162281 100644 --- a/simulation/simulation_interface/CHANGELOG.rst +++ b/simulation/simulation_interface/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package simulation_interface * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.0 (2024-07-26) +------------------ + 3.3.0 (2024-07-23) ------------------ * Merge branch 'master' into feature/interpreter/entity_selection diff --git a/simulation/simulation_interface/package.xml b/simulation/simulation_interface/package.xml index 6952140fbc5..75b6c33cd3b 100644 --- a/simulation/simulation_interface/package.xml +++ b/simulation/simulation_interface/package.xml @@ -2,7 +2,7 @@ simulation_interface - 3.3.0 + 3.4.0 packages to define interface between simulator and scenario interpreter Masaya Kataoka Apache License 2.0 diff --git a/simulation/traffic_simulator/CHANGELOG.rst b/simulation/traffic_simulator/CHANGELOG.rst index bfc883af579..fabffcfe75c 100644 --- a/simulation/traffic_simulator/CHANGELOG.rst +++ b/simulation/traffic_simulator/CHANGELOG.rst @@ -21,6 +21,13 @@ Changelog for package traffic_simulator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.0 (2024-07-26) +------------------ +* Merge pull request `#1325 `_ from tier4/feature/interpreter/lidar-configuration + Feature/interpreter/lidar configuration +* Update `MiscObjectEntity` to display with a magenta bounding box +* Contributors: Masaya Kataoka, yamacir-kit + 3.3.0 (2024-07-23) ------------------ * Merge branch 'master' into feature/interpreter/entity_selection diff --git a/simulation/traffic_simulator/package.xml b/simulation/traffic_simulator/package.xml index c07521057ff..087d6eeaf26 100644 --- a/simulation/traffic_simulator/package.xml +++ b/simulation/traffic_simulator/package.xml @@ -1,7 +1,7 @@ traffic_simulator - 3.3.0 + 3.4.0 control traffic flow masaya kataoka diff --git a/simulation/traffic_simulator_msgs/CHANGELOG.rst b/simulation/traffic_simulator_msgs/CHANGELOG.rst index 3c3effd653d..bfe7977a389 100644 --- a/simulation/traffic_simulator_msgs/CHANGELOG.rst +++ b/simulation/traffic_simulator_msgs/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package openscenario_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.0 (2024-07-26) +------------------ + 3.3.0 (2024-07-23) ------------------ * Merge branch 'master' into feature/interpreter/entity_selection diff --git a/simulation/traffic_simulator_msgs/package.xml b/simulation/traffic_simulator_msgs/package.xml index 6c1f3fee0ea..3391bbe7a1b 100644 --- a/simulation/traffic_simulator_msgs/package.xml +++ b/simulation/traffic_simulator_msgs/package.xml @@ -2,7 +2,7 @@ traffic_simulator_msgs - 3.3.0 + 3.4.0 ROS messages for openscenario Masaya Kataoka Apache License 2.0 diff --git a/test_runner/random_test_runner/CHANGELOG.rst b/test_runner/random_test_runner/CHANGELOG.rst index 26f3f6934c3..8479b47387b 100644 --- a/test_runner/random_test_runner/CHANGELOG.rst +++ b/test_runner/random_test_runner/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package random_test_runner * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.0 (2024-07-26) +------------------ + 3.3.0 (2024-07-23) ------------------ * Merge branch 'master' into feature/interpreter/entity_selection diff --git a/test_runner/random_test_runner/package.xml b/test_runner/random_test_runner/package.xml index e7b7b0f52a8..d272ee3bc68 100644 --- a/test_runner/random_test_runner/package.xml +++ b/test_runner/random_test_runner/package.xml @@ -2,7 +2,7 @@ random_test_runner - 3.3.0 + 3.4.0 Random behavior test runner piotr-zyskowski-rai Apache License 2.0 diff --git a/test_runner/scenario_test_runner/CHANGELOG.rst b/test_runner/scenario_test_runner/CHANGELOG.rst index 4ef9428c510..1f8fc2ce7c3 100644 --- a/test_runner/scenario_test_runner/CHANGELOG.rst +++ b/test_runner/scenario_test_runner/CHANGELOG.rst @@ -35,6 +35,13 @@ Changelog for package scenario_test_runner * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.0 (2024-07-26) +------------------ +* Merge pull request `#1325 `_ from tier4/feature/interpreter/lidar-configuration + Feature/interpreter/lidar configuration +* Add a test scenario for `ObjectController`'s pseudo LiDAR property +* Contributors: Masaya Kataoka, yamacir-kit + 3.3.0 (2024-07-23) ------------------ * Merge pull request `#1059 `_ from tier4/feature/interpreter/entity_selection diff --git a/test_runner/scenario_test_runner/package.xml b/test_runner/scenario_test_runner/package.xml index 0e6b321b352..12be8f20a1e 100644 --- a/test_runner/scenario_test_runner/package.xml +++ b/test_runner/scenario_test_runner/package.xml @@ -2,7 +2,7 @@ scenario_test_runner - 3.3.0 + 3.4.0 scenario test runner package Tatsuya Yamasaki Apache License 2.0 From 546337330c96302f55beefeb1932f7fc7f14ea06 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Fri, 26 Jul 2024 15:38:39 +0900 Subject: [PATCH 048/304] Implement switching by relative heading of triggering_entity in RelativeClearanceCondition --- .../syntax/relative_clearance_condition.hpp | 4 +- .../syntax/relative_clearance_condition.cpp | 60 ++++++++++++------- 2 files changed, 40 insertions(+), 24 deletions(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_clearance_condition.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_clearance_condition.hpp index e0db2617c1f..5140e728818 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_clearance_condition.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_clearance_condition.hpp @@ -40,7 +40,9 @@ inline namespace syntax */ -struct RelativeClearanceCondition : private Scope, private SimulatorCore::ConditionEvaluation +struct RelativeClearanceCondition : private Scope, + private SimulatorCore::ConditionEvaluation, + private SimulatorCore::NonStandardOperation { /* Longitudinal distance behind reference point of the entity to be checked along lane centerline of the current lane of the triggering entity. Orientation of entity towards lane determines backward direction. Velocity of entity is irrelevant. Unit: [m]. Range: [0..inf[. Default if omitted: 0 diff --git a/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp b/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp index cdfcabea439..54440096543 100644 --- a/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp @@ -68,30 +68,44 @@ auto RelativeClearanceCondition::description() const -> String auto RelativeClearanceCondition::evaluate() -> Object { return asBoolean(triggering_entities.apply([&](const auto & triggering_entity) { - return std::all_of(entity_refs.begin(), entity_refs.end(), [&](const auto & entity) { - auto is_in_lateral_range = [&]() { - // The lanes to be checked to left and right of the triggering entity (positive to the y-axis). If omitted: all lanes are checked. - if (relative_lane_range.empty()) { - return true; - } else { - auto relative_lateral_lane = - evaluateLateralRelativeLanes(triggering_entity, entity, RoutingAlgorithm::shortest); - return std::any_of( - relative_lane_range.begin(), relative_lane_range.end(), [&](const auto & range) { - return range.from <= relative_lateral_lane && range.to >= relative_lateral_lane; - }); - } - }; + return std::all_of( + entity_refs.begin(), entity_refs.end(), + [&, is_back = + (std::abs(evaluateRelativeHeading(triggering_entity)) > M_2_PI)](const auto & entity) { + auto is_in_lateral_range = [&]() { + // The lanes to be checked to left and right of the triggering entity (positive to the y-axis). If omitted: all lanes are checked. + if (relative_lane_range.empty()) { + return true; + } else { + if (auto relative_lateral_lane = evaluateLateralRelativeLanes( + triggering_entity, entity, RoutingAlgorithm::shortest); + relative_lateral_lane.has_value()) { + if (is_back) { + relative_lateral_lane.value() = -relative_lateral_lane.value(); + } + return std::any_of( + relative_lane_range.begin(), relative_lane_range.end(), [&](const auto & range) { + return range.from <= relative_lateral_lane.value() && + range.to >= relative_lateral_lane.value(); + }); + } else { + throw common::Error("Relative lateral lane is not available"); + } + } + }; - auto is_in_longitudinal_range = [&]() { - auto relative_lane_position = - getRelativeLanePosition(triggering_entity, entity, free_space); - if (relative_lane_position.s < 0) { - return std::abs(relative_lane_position.s) <= distance_backward; - } else { - return relative_lane_position.s <= distance_forward; - } - }; + auto is_in_longitudinal_range = [&]() { + auto relative_longitudinal = + getRelativeLanePosition(triggering_entity, entity, free_space).s; + if (is_back) { + relative_longitudinal = -relative_longitudinal; + } + if (relative_longitudinal < 0) { + return std::abs(relative_longitudinal) <= distance_backward; + } else { + return relative_longitudinal <= distance_forward; + } + }; auto lat_ok = is_in_lateral_range(); auto lon_ok = is_in_longitudinal_range(); From c206ff14b6dc4c9c3adfe0bf35d50b8bae1b9cba Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Fri, 26 Jul 2024 15:39:41 +0900 Subject: [PATCH 049/304] Update ByEntityCondition.EntityCondition.RelativeClearanceCondition.yaml to be a better test --- ...EntityCondition.RelativeClearanceCondition.yaml | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/test_runner/scenario_test_runner/scenario/ByEntityCondition.EntityCondition.RelativeClearanceCondition.yaml b/test_runner/scenario_test_runner/scenario/ByEntityCondition.EntityCondition.RelativeClearanceCondition.yaml index 5dd00cce153..da97625a8af 100644 --- a/test_runner/scenario_test_runner/scenario/ByEntityCondition.EntityCondition.RelativeClearanceCondition.yaml +++ b/test_runner/scenario_test_runner/scenario/ByEntityCondition.EntityCondition.RelativeClearanceCondition.yaml @@ -61,7 +61,7 @@ OpenSCENARIO: Position: LanePosition: &CAR_1_LANE_POSITION << : *EGO_LANE_POSITION - s: 20 + s: 25 - LongitudinalAction: *SPEED_ACTION_ZERO - entityRef: car_right_front PrivateAction: @@ -70,7 +70,7 @@ OpenSCENARIO: LanePosition: &CAR_2_LANE_POSITION << : *EGO_LANE_POSITION laneId: 34462 - s: 20 + s: 25 - LongitudinalAction: *SPEED_ACTION_ZERO - entityRef: car_right_back PrivateAction: @@ -124,7 +124,7 @@ OpenSCENARIO: EntityCondition: RelativeClearanceCondition: distanceBackward: 7 - distanceForward: 7 + distanceForward: 12 freeSpace: false oppositeLanes: false - Condition: @@ -171,7 +171,7 @@ OpenSCENARIO: EntityCondition: RelativeClearanceCondition: distanceBackward: 3 - distanceForward: 3 + distanceForward: 8 freeSpace: false oppositeLanes: false - name: "check back is clear with front cars" @@ -205,7 +205,7 @@ OpenSCENARIO: - entityRef: car_right_back - entityRef: car_same_back distanceBackward: 0 - distanceForward: 7 + distanceForward: 12 freeSpace: false oppositeLanes: false - name: "check right is clear with cars in the same lane" @@ -222,7 +222,7 @@ OpenSCENARIO: - entityRef: car_same_front - entityRef: car_same_back distanceBackward: 7 - distanceForward: 7 + distanceForward: 12 freeSpace: false oppositeLanes: false RelativeLaneRange: @@ -242,7 +242,7 @@ OpenSCENARIO: - entityRef: car_right_front - entityRef: car_right_back distanceBackward: 7 - distanceForward: 7 + distanceForward: 12 freeSpace: false oppositeLanes: false RelativeLaneRange: From f785a8b173248aca6d00e59b595e1b719079d713 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Fri, 26 Jul 2024 15:39:53 +0900 Subject: [PATCH 050/304] Add ByEntityCondition.EntityCondition.RelativeClearanceCondition-back.yaml --- ...ition.RelativeClearanceCondition-back.yaml | 262 ++++++++++++++++++ 1 file changed, 262 insertions(+) create mode 100644 test_runner/scenario_test_runner/scenario/ByEntityCondition.EntityCondition.RelativeClearanceCondition-back.yaml diff --git a/test_runner/scenario_test_runner/scenario/ByEntityCondition.EntityCondition.RelativeClearanceCondition-back.yaml b/test_runner/scenario_test_runner/scenario/ByEntityCondition.EntityCondition.RelativeClearanceCondition-back.yaml new file mode 100644 index 00000000000..2d6975cf0e4 --- /dev/null +++ b/test_runner/scenario_test_runner/scenario/ByEntityCondition.EntityCondition.RelativeClearanceCondition-back.yaml @@ -0,0 +1,262 @@ +OpenSCENARIO: + FileHeader: + revMajor: 0 + revMinor: 0 + date: "1970-01-01T09:00:00+09:00" + author: Kotaro Yoshimoto + description: "" + ParameterDeclarations: + ParameterDeclaration: [] + CatalogLocations: + VehicleCatalog: + Directory: + path: $(ros2 pkg prefix --share openscenario_experimental_catalog)/vehicle + RoadNetwork: + LogicFile: + filepath: $(find-pkg-share kashiwanoha_map)/map + Entities: + ScenarioObject: + - name: ego + CatalogReference: &SAMPLE_VEHICLE + catalogName: sample_vehicle + entryName: sample_vehicle + - name: car_same_front + CatalogReference: *SAMPLE_VEHICLE + - name: car_right_front + CatalogReference: *SAMPLE_VEHICLE + - name: car_right_back + CatalogReference: *SAMPLE_VEHICLE + - name: car_same_back + CatalogReference: *SAMPLE_VEHICLE + Storyboard: + Init: + Actions: + Private: + - entityRef: ego + PrivateAction: + - TeleportAction: + Position: + LanePosition: &EGO_LANE_POSITION + roadId: "" + laneId: 34513 + s: 15 + offset: 0 + Orientation: + type: relative + h: 3.141592653589793 + p: 0 + r: 0 + - LongitudinalAction: &SPEED_ACTION_ZERO + SpeedAction: + SpeedActionDynamics: + dynamicsDimension: time + value: 0 + dynamicsShape: step + SpeedActionTarget: + AbsoluteTargetSpeed: + value: 0 + - entityRef: car_same_front + PrivateAction: + - TeleportAction: + Position: + LanePosition: &CAR_1_LANE_POSITION + << : *EGO_LANE_POSITION + s: 25 + - LongitudinalAction: *SPEED_ACTION_ZERO + - entityRef: car_right_front + PrivateAction: + - TeleportAction: + Position: + LanePosition: &CAR_2_LANE_POSITION + << : *EGO_LANE_POSITION + laneId: 34462 + s: 25 + - LongitudinalAction: *SPEED_ACTION_ZERO + - entityRef: car_right_back + PrivateAction: + - TeleportAction: + Position: + LanePosition: + << : *EGO_LANE_POSITION + laneId: 34462 + s: 10 + - LongitudinalAction: *SPEED_ACTION_ZERO + - entityRef: car_same_back + PrivateAction: + - TeleportAction: + Position: + LanePosition: + << : *EGO_LANE_POSITION + s: 10 + - LongitudinalAction: *SPEED_ACTION_ZERO + Story: + - name: story + Act: + - name: act + ManeuverGroup: + - maximumExecutionCount: 1 + name: maneuver_group + Actors: + selectTriggeringEntities: false + EntityRef: + - entityRef: ego + Maneuver: + - name: maneuver + Event: + - name: failure + priority: parallel + Action: + - name: "" + UserDefinedAction: + CustomCommandAction: + type: exitFailure + StartTrigger: + ConditionGroup: + - Condition: + - name: "check all car is in range(not clear) means the condition is false" + delay: 0 + conditionEdge: none + ByEntityCondition: + TriggeringEntities: + triggeringEntitiesRule: all + EntityRef: + - entityRef: ego + EntityCondition: + RelativeClearanceCondition: + distanceBackward: 12 + distanceForward: 7 + freeSpace: false + oppositeLanes: false + - Condition: + - name: "check not all car is in range(not clear) means the condition is false" + delay: 0 + conditionEdge: none + ByEntityCondition: + TriggeringEntities: + triggeringEntitiesRule: all + EntityRef: + - entityRef: ego + EntityCondition: + RelativeClearanceCondition: + distanceBackward: 0 + distanceForward: 7 + freeSpace: false + oppositeLanes: false + - Condition: + - name: "timeout" + delay: 0 + conditionEdge: none + ByValueCondition: + SimulationTimeCondition: + value: 1 + rule: greaterThan + - name: success + priority: parallel + Action: + - name: "" + UserDefinedAction: + CustomCommandAction: + type: exitSuccess + StartTrigger: + ConditionGroup: + - Condition: + - name: "check clear with all cars in narrower longitudinal range" + delay: 0 + conditionEdge: none + ByEntityCondition: + TriggeringEntities: + triggeringEntitiesRule: all + EntityRef: + - entityRef: ego + EntityCondition: + RelativeClearanceCondition: + distanceBackward: 8 + distanceForward: 3 + freeSpace: false + oppositeLanes: false + - name: "check back is clear with front cars" + delay: 0 + conditionEdge: none + ByEntityCondition: + TriggeringEntities: + triggeringEntitiesRule: all + EntityRef: + - entityRef: ego + EntityCondition: + RelativeClearanceCondition: + EntityRef: + - entityRef: car_same_front + - entityRef: car_right_front + distanceBackward: 0 + distanceForward: 7 + freeSpace: false + oppositeLanes: false + - name: "check front is clear with back cars" + delay: 0 + conditionEdge: none + ByEntityCondition: + TriggeringEntities: + triggeringEntitiesRule: all + EntityRef: + - entityRef: ego + EntityCondition: + RelativeClearanceCondition: + EntityRef: + - entityRef: car_right_back + - entityRef: car_same_back + distanceBackward: 12 + distanceForward: 0 + freeSpace: false + oppositeLanes: false + - name: "check right is clear with cars in the same lane" + delay: 0 + conditionEdge: none + ByEntityCondition: + TriggeringEntities: + triggeringEntitiesRule: all + EntityRef: + - entityRef: ego + EntityCondition: + RelativeClearanceCondition: + EntityRef: + - entityRef: car_same_front + - entityRef: car_same_back + distanceBackward: 12 + distanceForward: 7 + freeSpace: false + oppositeLanes: false + RelativeLaneRange: + - from: 1 + to: 1 + - name: "check same lane is clear with cars in the right lane" + delay: 0 + conditionEdge: none + ByEntityCondition: + TriggeringEntities: + triggeringEntitiesRule: all + EntityRef: + - entityRef: ego + EntityCondition: + RelativeClearanceCondition: + EntityRef: + - entityRef: car_right_front + - entityRef: car_right_back + distanceBackward: 12 + distanceForward: 7 + freeSpace: false + oppositeLanes: false + RelativeLaneRange: + - from: 0 + to: 0 + StartTrigger: + ConditionGroup: + - Condition: + - name: "" + delay: 0 + conditionEdge: none + ByValueCondition: + SimulationTimeCondition: + value: 0 + rule: greaterThan + StopTrigger: + ConditionGroup: [] From 63b7de91c68e57d6fb22a21c866d859f4fb65af3 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Fri, 26 Jul 2024 15:42:44 +0900 Subject: [PATCH 051/304] Fix copy bugs in RelativeClearanceCondition --- .../src/syntax/relative_clearance_condition.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp b/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp index 54440096543..aaf0cdcaccb 100644 --- a/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp @@ -41,7 +41,7 @@ RelativeClearanceCondition::RelativeClearanceCondition( [&](const auto & triggering_entity) { return triggering_entity.name() == entity.first; }) == triggering_entities.entity_refs.end()) { - entities.emplace_back(name); + entities.emplace_back(entity.first); } } } From 2ab48c3246ab886afa3453781ca9df3b5731e5c5 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Mon, 29 Jul 2024 14:28:06 +0900 Subject: [PATCH 052/304] apply linter --- .../src/syntax/relative_clearance_condition.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp b/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp index aaf0cdcaccb..5d210b1f039 100644 --- a/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp @@ -107,10 +107,10 @@ auto RelativeClearanceCondition::evaluate() -> Object } }; - auto lat_ok = is_in_lateral_range(); - auto lon_ok = is_in_longitudinal_range(); - return not(lat_ok && lon_ok); - }); + auto lat_ok = is_in_lateral_range(); + auto lon_ok = is_in_longitudinal_range(); + return not(lat_ok && lon_ok); + }); })); } From c66b6276d89a7b9557f59b274dca189604d1919d Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Mon, 29 Jul 2024 14:37:49 +0900 Subject: [PATCH 053/304] Add Integer::infinity function --- .../include/openscenario_interpreter/syntax/integer.hpp | 2 ++ openscenario/openscenario_interpreter/src/syntax/integer.cpp | 5 +++++ 2 files changed, 7 insertions(+) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/integer.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/integer.hpp index b074cf26ae6..7c8a00e37fc 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/integer.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/integer.hpp @@ -35,6 +35,8 @@ struct Integer explicit Integer(const std::string &); + static auto infinity() noexcept -> Integer; + auto operator+=(const double &) -> Integer &; auto operator*=(const double &) -> Integer &; diff --git a/openscenario/openscenario_interpreter/src/syntax/integer.cpp b/openscenario/openscenario_interpreter/src/syntax/integer.cpp index 2c7f55c03ea..f9632ec2624 100644 --- a/openscenario/openscenario_interpreter/src/syntax/integer.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/integer.cpp @@ -34,6 +34,11 @@ Integer::Integer(const std::string & s) } } +auto Integer::infinity() noexcept -> Integer +{ + return static_cast(std::numeric_limits::infinity()); +} + auto Integer::operator+=(const double & rhs) -> Integer & { data += rhs; From 2830cfd094287c1b6213013afed02c6ee69e3a3a Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Mon, 29 Jul 2024 14:38:44 +0900 Subject: [PATCH 054/304] Fix RelativeLaneRange to use default values in the specification --- .../openscenario_interpreter/syntax/relative_lane_range.hpp | 6 ++++++ .../src/syntax/relative_lane_range.cpp | 3 ++- 2 files changed, 8 insertions(+), 1 deletion(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_lane_range.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_lane_range.hpp index 7108b45bf2b..620e83ec807 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_lane_range.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_lane_range.hpp @@ -33,8 +33,14 @@ inline namespace syntax */ struct RelativeLaneRange { + /* + The lower limit of the range. Range: [-inf, inf[. Default if omitted: -inf + */ const Integer from; + /* + The upper limit of the range. Range: ]-inf, inf]. Default if omitted: +inf + */ const Integer to; explicit RelativeLaneRange(const pugi::xml_node &, Scope &); diff --git a/openscenario/openscenario_interpreter/src/syntax/relative_lane_range.cpp b/openscenario/openscenario_interpreter/src/syntax/relative_lane_range.cpp index c94ce16d95c..2911617b6bd 100644 --- a/openscenario/openscenario_interpreter/src/syntax/relative_lane_range.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/relative_lane_range.cpp @@ -20,7 +20,8 @@ namespace openscenario_interpreter inline namespace syntax { RelativeLaneRange::RelativeLaneRange(const pugi::xml_node & node, Scope & scope) -: from(readAttribute("from", node, scope)), to(readAttribute("to", node, scope)) +: from(readAttribute("from", node, scope, -Integer::infinity())), + to(readAttribute("to", node, scope, Integer::infinity())) { } } // namespace syntax From 019bf2c2771eb058e4ed1f142d42f000e49b913c Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Mon, 29 Jul 2024 14:45:52 +0900 Subject: [PATCH 055/304] refactor: clean up includes in relative_lane_range.hpp --- .../openscenario_interpreter/syntax/relative_lane_range.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_lane_range.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_lane_range.hpp index 620e83ec807..f6f94e9332e 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_lane_range.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_lane_range.hpp @@ -16,8 +16,8 @@ #define OPENSCENARIO_INTERPRETER__SYNTAX__RELATIVE_LANE_RANGE_HPP_ #include +#include #include -#include namespace openscenario_interpreter { From de4c942b8f2ce234b4a6bc95e457e7ed3df89558 Mon Sep 17 00:00:00 2001 From: Dawid Moszynski Date: Mon, 29 Jul 2024 17:38:45 +0200 Subject: [PATCH 056/304] ref(behavior_tree): use CanonicalizedEntityStatus as shared_ptr inside BT and use ::set --- .../behavior_tree_plugin/action_node.hpp | 9 +- .../pedestrian/behavior_tree.hpp | 5 +- .../vehicle/behavior_tree.hpp | 3 +- .../behavior_tree_plugin/src/action_node.cpp | 86 ++++++++++--------- .../src/pedestrian/follow_lane_action.cpp | 13 +-- .../follow_polyline_trajectory_action.cpp | 24 +++--- .../src/pedestrian/pedestrian_action_node.cpp | 15 ++-- .../src/pedestrian/walk_straight_action.cpp | 5 +- .../follow_front_entity_action.cpp | 25 ++---- .../follow_lane_action.cpp | 16 ++-- .../move_backward_action.cpp | 17 ++-- .../stop_at_crossing_entity_action.cpp | 18 ++-- .../stop_at_stop_line_action.cpp | 22 ++--- .../stop_at_traffic_light_action.cpp | 18 ++-- .../follow_lane_sequence/yield_action.cpp | 18 ++-- .../follow_polyline_trajectory_action.cpp | 28 +++--- .../src/vehicle/lane_change_action.cpp | 49 ++++++----- .../src/vehicle/vehicle_action_node.cpp | 2 +- .../include/do_nothing_plugin/plugin.hpp | 15 ++-- simulation/do_nothing_plugin/src/plugin.cpp | 19 ++-- .../behavior/behavior_plugin_base.hpp | 3 +- .../data_type/entity_status.hpp | 2 + .../traffic_simulator/entity/ego_entity.hpp | 6 +- .../traffic_simulator/entity/entity_base.hpp | 20 ++--- .../src/data_type/entity_status.cpp | 16 ++-- .../src/entity/ego_entity.cpp | 13 +-- .../src/entity/entity_base.cpp | 38 ++++---- .../src/entity/misc_object_entity.cpp | 4 +- .../src/entity/pedestrian_entity.cpp | 16 ++-- .../src/entity/vehicle_entity.cpp | 19 ++-- 30 files changed, 250 insertions(+), 294 deletions(-) diff --git a/simulation/behavior_tree_plugin/include/behavior_tree_plugin/action_node.hpp b/simulation/behavior_tree_plugin/include/behavior_tree_plugin/action_node.hpp index eda786c8202..d167045dfb0 100644 --- a/simulation/behavior_tree_plugin/include/behavior_tree_plugin/action_node.hpp +++ b/simulation/behavior_tree_plugin/include/behavior_tree_plugin/action_node.hpp @@ -66,8 +66,6 @@ class ActionNode : public BT::ActionNodeBase -> std::vector; auto stopEntity() const -> void; auto getHorizon() const -> double; - auto getActionStatus() const noexcept -> traffic_simulator_msgs::msg::ActionStatus; - auto getEntityName() const noexcept -> std::string; /// throws if the derived class return RUNNING. auto executeTick() -> BT::NodeStatus override; @@ -85,11 +83,10 @@ class ActionNode : public BT::ActionNodeBase BT::InputPort("route_lanelets"), BT::InputPort>("target_speed"), BT::InputPort>("hdmap_utils"), - BT::InputPort>("entity_status"), + BT::InputPort>("canonicalized_entity_status"), BT::InputPort>("traffic_light_manager"), BT::InputPort("request"), BT::OutputPort>("obstacle"), - BT::OutputPort>("non_canonicalized_updated_status"), BT::OutputPort("waypoints"), BT::OutputPort("request"), // clang-format on @@ -103,6 +100,8 @@ class ActionNode : public BT::ActionNodeBase double width_extension_right = 0.0, double width_extension_left = 0.0, double length_extension_front = 0.0, double length_extension_rear = 0.0) const -> std::optional; + + auto setCanonicalizedEntityStatus(const traffic_simulator::EntityStatus & entity_status) -> void; auto calculateUpdatedEntityStatus( double target_speed, const traffic_simulator_msgs::msg::DynamicConstraints &) const -> traffic_simulator::EntityStatus; @@ -114,7 +113,7 @@ class ActionNode : public BT::ActionNodeBase traffic_simulator::behavior::Request request; std::shared_ptr hdmap_utils; std::shared_ptr traffic_light_manager; - std::shared_ptr entity_status; + std::shared_ptr canonicalized_entity_status; double current_time; double step_time; double default_matching_distance_for_lanelet_pose_calculation; diff --git a/simulation/behavior_tree_plugin/include/behavior_tree_plugin/pedestrian/behavior_tree.hpp b/simulation/behavior_tree_plugin/include/behavior_tree_plugin/pedestrian/behavior_tree.hpp index bd651428aba..54c03685898 100644 --- a/simulation/behavior_tree_plugin/include/behavior_tree_plugin/pedestrian/behavior_tree.hpp +++ b/simulation/behavior_tree_plugin/include/behavior_tree_plugin/pedestrian/behavior_tree.hpp @@ -51,24 +51,23 @@ class PedestrianBehaviorTree : public BehaviorPluginBase // clang-format off DEFINE_GETTER_SETTER(BehaviorParameter, traffic_simulator_msgs::msg::BehaviorParameter) + DEFINE_GETTER_SETTER(CanonicalizedEntityStatus, std::shared_ptr) DEFINE_GETTER_SETTER(CurrentTime, double) DEFINE_GETTER_SETTER(DebugMarker, std::vector) DEFINE_GETTER_SETTER(DefaultMatchingDistanceForLaneletPoseCalculation, double) DEFINE_GETTER_SETTER(GoalPoses, std::vector) - DEFINE_GETTER_SETTER(EntityStatus, std::shared_ptr) - DEFINE_GETTER_SETTER(PolylineTrajectory, std::shared_ptr) DEFINE_GETTER_SETTER(HdMapUtils, std::shared_ptr) DEFINE_GETTER_SETTER(LaneChangeParameters, traffic_simulator::lane_change::Parameter) DEFINE_GETTER_SETTER(Obstacle, std::optional) DEFINE_GETTER_SETTER(OtherEntityStatus, EntityStatusDict) DEFINE_GETTER_SETTER(PedestrianParameters, traffic_simulator_msgs::msg::PedestrianParameters) + DEFINE_GETTER_SETTER(PolylineTrajectory, std::shared_ptr) DEFINE_GETTER_SETTER(ReferenceTrajectory, std::shared_ptr) DEFINE_GETTER_SETTER(Request, traffic_simulator::behavior::Request) DEFINE_GETTER_SETTER(RouteLanelets, lanelet::Ids) DEFINE_GETTER_SETTER(StepTime, double) DEFINE_GETTER_SETTER(TargetSpeed, std::optional) DEFINE_GETTER_SETTER(TrafficLightManager, std::shared_ptr) - DEFINE_GETTER_SETTER(UpdatedStatus, std::shared_ptr) DEFINE_GETTER_SETTER(VehicleParameters, traffic_simulator_msgs::msg::VehicleParameters) DEFINE_GETTER_SETTER(Waypoints, traffic_simulator_msgs::msg::WaypointsArray) // clang-format on diff --git a/simulation/behavior_tree_plugin/include/behavior_tree_plugin/vehicle/behavior_tree.hpp b/simulation/behavior_tree_plugin/include/behavior_tree_plugin/vehicle/behavior_tree.hpp index 885da5cd5a5..fd3997d13a8 100644 --- a/simulation/behavior_tree_plugin/include/behavior_tree_plugin/vehicle/behavior_tree.hpp +++ b/simulation/behavior_tree_plugin/include/behavior_tree_plugin/vehicle/behavior_tree.hpp @@ -55,10 +55,10 @@ class VehicleBehaviorTree : public BehaviorPluginBase } // clang-format off + DEFINE_GETTER_SETTER(CanonicalizedEntityStatus, std::shared_ptr) DEFINE_GETTER_SETTER(CurrentTime, double) DEFINE_GETTER_SETTER(DebugMarker, std::vector) DEFINE_GETTER_SETTER(DefaultMatchingDistanceForLaneletPoseCalculation, double) - DEFINE_GETTER_SETTER(EntityStatus, std::shared_ptr) DEFINE_GETTER_SETTER(GoalPoses, std::vector) DEFINE_GETTER_SETTER(HdMapUtils, std::shared_ptr) DEFINE_GETTER_SETTER(LaneChangeParameters, traffic_simulator::lane_change::Parameter) @@ -72,7 +72,6 @@ class VehicleBehaviorTree : public BehaviorPluginBase DEFINE_GETTER_SETTER(StepTime, double) DEFINE_GETTER_SETTER(TargetSpeed, std::optional) DEFINE_GETTER_SETTER(TrafficLightManager, std::shared_ptr) - DEFINE_GETTER_SETTER(UpdatedStatus, std::shared_ptr) DEFINE_GETTER_SETTER(VehicleParameters, traffic_simulator_msgs::msg::VehicleParameters) DEFINE_GETTER_SETTER(Waypoints, traffic_simulator_msgs::msg::WaypointsArray) // clang-format on diff --git a/simulation/behavior_tree_plugin/src/action_node.cpp b/simulation/behavior_tree_plugin/src/action_node.cpp index b686714ffc2..29fcb393d7d 100644 --- a/simulation/behavior_tree_plugin/src/action_node.cpp +++ b/simulation/behavior_tree_plugin/src/action_node.cpp @@ -59,8 +59,8 @@ auto ActionNode::getBlackBoardValues() -> void THROW_SIMULATION_ERROR("failed to get input traffic_light_manager in ActionNode"); } if (!getInput>( - "entity_status", entity_status)) { - THROW_SIMULATION_ERROR("failed to get input entity_status in ActionNode"); + "canonicalized_entity_status", canonicalized_entity_status)) { + THROW_SIMULATION_ERROR("failed to get input canonicalized_entity_status in ActionNode"); } if (!getInput>("target_speed", target_speed)) { @@ -84,14 +84,21 @@ auto ActionNode::getBlackBoardValues() -> void auto ActionNode::getHorizon() const -> double { - return std::clamp(entity_status->getTwist().linear.x * 5.0, 20.0, 50.0); + return std::clamp(canonicalized_entity_status->getTwist().linear.x * 5.0, 20.0, 50.0); } auto ActionNode::stopEntity() const -> void { - entity_status->setTwist(geometry_msgs::msg::Twist()); - entity_status->setAccel(geometry_msgs::msg::Accel()); - entity_status->setLinearJerk(0); + canonicalized_entity_status->setTwist(geometry_msgs::msg::Twist()); + canonicalized_entity_status->setAccel(geometry_msgs::msg::Accel()); + canonicalized_entity_status->setLinearJerk(0); +} + +auto ActionNode::setCanonicalizedEntityStatus(const traffic_simulator::EntityStatus & entity_status) + -> void +{ + canonicalized_entity_status->set( + entity_status, default_matching_distance_for_lanelet_pose_calculation, hdmap_utils); } auto ActionNode::getOtherEntityStatus(lanelet::Id lanelet_id) const @@ -116,8 +123,8 @@ auto ActionNode::getYieldStopDistance(const lanelet::Ids & following_lanelets) c const auto right_of_way_ids = hdmap_utils->getRightOfWayLaneletIds(lanelet); for (const auto right_of_way_id : right_of_way_ids) { const auto other_status = getOtherEntityStatus(right_of_way_id); - if (!other_status.empty() && entity_status->laneMatchingSucceed()) { - const auto lanelet_pose = entity_status->getLaneletPose(); + if (!other_status.empty() && canonicalized_entity_status->laneMatchingSucceed()) { + const auto lanelet_pose = canonicalized_entity_status->getLaneletPose(); const auto distance_forward = hdmap_utils->getLongitudinalDistance( lanelet_pose, traffic_simulator::helper::constructLaneletPose(lanelet, 0)); const auto distance_backward = hdmap_utils->getLongitudinalDistance( @@ -167,11 +174,12 @@ auto ActionNode::getRightOfWayEntities(const lanelet::Ids & following_lanelets) auto ActionNode::getRightOfWayEntities() const -> std::vector { - if (!entity_status->laneMatchingSucceed()) { + if (!canonicalized_entity_status->laneMatchingSucceed()) { return {}; } std::vector ret; - const auto lanelet_ids = hdmap_utils->getRightOfWayLaneletIds(entity_status->getLaneletId()); + const auto lanelet_ids = + hdmap_utils->getRightOfWayLaneletIds(canonicalized_entity_status->getLaneletId()); if (lanelet_ids.empty()) { return ret; } @@ -240,7 +248,7 @@ auto ActionNode::getFrontEntityName(const math::geometry::CatmullRomSplineInterf for (const auto & each : other_entity_status) { const auto distance = getDistanceToTargetEntityPolygon(spline, each.first); const auto quat = math::geometry::getRotation( - entity_status->getMapPose().orientation, + canonicalized_entity_status->getMapPose().orientation, other_entity_status.at(each.first).getMapPose().orientation); /** * @note hard-coded parameter, if the Yaw value of RPY is in ~1.5708 -> 1.5708, entity is a candidate of front entity. @@ -402,26 +410,30 @@ auto ActionNode::calculateUpdatedEntityStatus( { const auto speed_planner = traffic_simulator::longitudinal_speed_planning::LongitudinalSpeedPlanner( - step_time, getEntityName()); + step_time, canonicalized_entity_status->getName()); const auto dynamics = speed_planner.getDynamicStates( - target_speed, constraints, entity_status->getTwist(), entity_status->getAccel()); + target_speed, constraints, canonicalized_entity_status->getTwist(), + canonicalized_entity_status->getAccel()); const double linear_jerk_new = std::get<2>(dynamics); const geometry_msgs::msg::Accel accel_new = std::get<1>(dynamics); const geometry_msgs::msg::Twist twist_new = std::get<0>(dynamics); - if (!entity_status->laneMatchingSucceed()) { - THROW_SIMULATION_ERROR("Entity ", entity_status->getName(), " is not matched to the lanelet."); + if (!canonicalized_entity_status->laneMatchingSucceed()) { + THROW_SIMULATION_ERROR( + "Entity ", canonicalized_entity_status->getName(), " is not matched to the lanelet."); } else { - auto lanelet_pose = entity_status->getLaneletPose(); + auto lanelet_pose = canonicalized_entity_status->getLaneletPose(); lanelet_pose.s = - lanelet_pose.s + (twist_new.linear.x + entity_status->getTwist().linear.x) / 2.0 * step_time; + lanelet_pose.s + + (twist_new.linear.x + canonicalized_entity_status->getTwist().linear.x) / 2.0 * step_time; const auto canonicalized = hdmap_utils->canonicalizeLaneletPose(lanelet_pose, route_lanelets); if ( const auto canonicalized_lanelet_pose = std::get>(canonicalized)) { // If canonicalize succeed, set canonicalized pose and set other values. - auto entity_status_updated = static_cast(*entity_status); + auto entity_status_updated = + static_cast(*canonicalized_entity_status); { entity_status_updated.time = current_time + step_time; entity_status_updated.lanelet_pose = canonicalized_lanelet_pose.value(); @@ -444,7 +456,8 @@ auto ActionNode::calculateUpdatedEntityStatus( end_of_road_lanelet_pose.offset = lanelet_pose.offset; end_of_road_lanelet_pose.rpy = lanelet_pose.rpy; } - auto entity_status_updated = static_cast(*entity_status); + auto entity_status_updated = + static_cast(*canonicalized_entity_status); { entity_status_updated.time = current_time + step_time; entity_status_updated.lanelet_pose = end_of_road_lanelet_pose; @@ -464,7 +477,8 @@ auto ActionNode::calculateUpdatedEntityStatus( end_of_road_lanelet_pose.offset = lanelet_pose.offset; end_of_road_lanelet_pose.rpy = lanelet_pose.rpy; } - auto entity_status_updated = static_cast(*entity_status); + auto entity_status_updated = + static_cast(*canonicalized_entity_status); { entity_status_updated.time = current_time + step_time; entity_status_updated.lanelet_pose = end_of_road_lanelet_pose; @@ -490,9 +504,10 @@ auto ActionNode::calculateUpdatedEntityStatusInWorldFrame( using math::geometry::operator*; const auto speed_planner = traffic_simulator::longitudinal_speed_planning::LongitudinalSpeedPlanner( - step_time, getEntityName()); + step_time, canonicalized_entity_status->getName()); const auto dynamics = speed_planner.getDynamicStates( - target_speed, constraints, entity_status->getTwist(), entity_status->getAccel()); + target_speed, constraints, canonicalized_entity_status->getTwist(), + canonicalized_entity_status->getAccel()); double linear_jerk_new = std::get<2>(dynamics); geometry_msgs::msg::Accel accel_new = std::get<1>(dynamics); geometry_msgs::msg::Twist twist_new = std::get<0>(dynamics); @@ -501,17 +516,18 @@ auto ActionNode::calculateUpdatedEntityStatusInWorldFrame( angular_trans_vec.z = twist_new.angular.z * step_time; geometry_msgs::msg::Quaternion angular_trans_quat = math::geometry::convertEulerAngleToQuaternion(angular_trans_vec); - pose_new.orientation = entity_status->getMapPose().orientation * angular_trans_quat; + pose_new.orientation = canonicalized_entity_status->getMapPose().orientation * angular_trans_quat; Eigen::Vector3d trans_vec; trans_vec(0) = twist_new.linear.x * step_time; trans_vec(1) = twist_new.linear.y * step_time; trans_vec(2) = 0; Eigen::Matrix3d rotation_mat = math::geometry::getRotationMatrix(pose_new.orientation); trans_vec = rotation_mat * trans_vec; - pose_new.position.x = trans_vec(0) + entity_status->getMapPose().position.x; - pose_new.position.y = trans_vec(1) + entity_status->getMapPose().position.y; - pose_new.position.z = trans_vec(2) + entity_status->getMapPose().position.z; - auto entity_status_updated = static_cast(*entity_status); + pose_new.position.x = trans_vec(0) + canonicalized_entity_status->getMapPose().position.x; + pose_new.position.y = trans_vec(1) + canonicalized_entity_status->getMapPose().position.y; + pose_new.position.z = trans_vec(2) + canonicalized_entity_status->getMapPose().position.z; + auto entity_status_updated = + static_cast(*canonicalized_entity_status); entity_status_updated.time = current_time + step_time; entity_status_updated.lanelet_pose = traffic_simulator::LaneletPose(); entity_status_updated.lanelet_pose_valid = false; @@ -526,19 +542,9 @@ auto ActionNode::calculateStopDistance( const traffic_simulator_msgs::msg::DynamicConstraints & constraints) const -> double { return traffic_simulator::longitudinal_speed_planning::LongitudinalSpeedPlanner( - step_time, getEntityName()) + step_time, canonicalized_entity_status->getName()) .getRunningDistance( - 0, constraints, entity_status->getTwist(), entity_status->getAccel(), - entity_status->getLinearJerk()); -} - -auto ActionNode::getActionStatus() const noexcept -> traffic_simulator_msgs::msg::ActionStatus -{ - return static_cast(*entity_status).action_status; -} - -auto ActionNode::getEntityName() const noexcept -> std::string -{ - return static_cast(*entity_status).name; + 0, constraints, canonicalized_entity_status->getTwist(), + canonicalized_entity_status->getAccel(), canonicalized_entity_status->getLinearJerk()); } } // namespace entity_behavior diff --git a/simulation/behavior_tree_plugin/src/pedestrian/follow_lane_action.cpp b/simulation/behavior_tree_plugin/src/pedestrian/follow_lane_action.cpp index d1d8790ac60..c24d13d66b1 100644 --- a/simulation/behavior_tree_plugin/src/pedestrian/follow_lane_action.cpp +++ b/simulation/behavior_tree_plugin/src/pedestrian/follow_lane_action.cpp @@ -38,21 +38,16 @@ BT::NodeStatus FollowLaneAction::tick() request != traffic_simulator::behavior::Request::FOLLOW_LANE) { return BT::NodeStatus::FAILURE; } - if (!entity_status->laneMatchingSucceed()) { + if (!canonicalized_entity_status->laneMatchingSucceed()) { stopEntity(); - setOutput( - "non_canonicalized_updated_status", - std::make_shared( - static_cast(*entity_status))); return BT::NodeStatus::RUNNING; } - auto following_lanelets = hdmap_utils->getFollowingLanelets(entity_status->getLaneletId()); + auto following_lanelets = + hdmap_utils->getFollowingLanelets(canonicalized_entity_status->getLaneletId()); if (!target_speed) { target_speed = hdmap_utils->getSpeedLimit(following_lanelets); } - setOutput( - "non_canonicalized_updated_status", std::make_shared( - calculateUpdatedEntityStatus(target_speed.value()))); + setCanonicalizedEntityStatus(calculateUpdatedEntityStatus(target_speed.value())); return BT::NodeStatus::RUNNING; } } // namespace pedestrian diff --git a/simulation/behavior_tree_plugin/src/pedestrian/follow_trajectory_sequence/follow_polyline_trajectory_action.cpp b/simulation/behavior_tree_plugin/src/pedestrian/follow_trajectory_sequence/follow_polyline_trajectory_action.cpp index ec6920082ae..8e722f5afb0 100644 --- a/simulation/behavior_tree_plugin/src/pedestrian/follow_trajectory_sequence/follow_polyline_trajectory_action.cpp +++ b/simulation/behavior_tree_plugin/src/pedestrian/follow_trajectory_sequence/follow_polyline_trajectory_action.cpp @@ -22,7 +22,7 @@ auto FollowPolylineTrajectoryAction::calculateWaypoints() -> const traffic_simulator_msgs::msg::WaypointsArray { auto waypoints = traffic_simulator_msgs::msg::WaypointsArray(); - waypoints.waypoints.push_back(entity_status->getMapPose().position); + waypoints.waypoints.push_back(canonicalized_entity_status->getMapPose().position); for (const auto & vertex : polyline_trajectory->shape.vertices) { waypoints.waypoints.push_back(vertex.position.position); } @@ -60,30 +60,26 @@ auto FollowPolylineTrajectoryAction::tick() -> BT::NodeStatus if (target_speed.has_value()) { return target_speed.value(); } else { - return entity_status->getTwist().linear.x; + return canonicalized_entity_status->getTwist().linear.x; } }; - auto getMatchingDistance = [&]() -> double { - return entity_status->getBoundingBox().dimensions.y * 0.5 + 1.0; - }; - if (getBlackBoardValues(); request != traffic_simulator::behavior::Request::FOLLOW_POLYLINE_TRAJECTORY or not getInput("polyline_trajectory", polyline_trajectory) or not getInput("target_speed", target_speed) or not polyline_trajectory) { return BT::NodeStatus::FAILURE; - } else if (std::isnan(entity_status->getTime())) { + } else if (std::isnan(canonicalized_entity_status->getTime())) { THROW_SIMULATION_ERROR( - "Time in entity_status is NaN - FollowTrajectoryAction does not support such case."); + "Time in canonicalized_entity_status is NaN - FollowTrajectoryAction does not support such " + "case."); } else if ( - const auto updated_status = traffic_simulator::follow_trajectory::makeUpdatedStatus( - static_cast(*entity_status), *polyline_trajectory, - behavior_parameter, hdmap_utils, step_time, getMatchingDistance(), getTargetSpeed())) { - setOutput( - "non_canonicalized_updated_status", - std::make_shared(updated_status.value())); + const auto entity_status_updated = traffic_simulator::follow_trajectory::makeUpdatedStatus( + static_cast(*canonicalized_entity_status), + *polyline_trajectory, behavior_parameter, hdmap_utils, step_time, + default_matching_distance_for_lanelet_pose_calculation, getTargetSpeed())) { + setCanonicalizedEntityStatus(entity_status_updated.value()); setOutput("waypoints", calculateWaypoints()); setOutput("obstacle", calculateObstacle(calculateWaypoints())); return BT::NodeStatus::RUNNING; diff --git a/simulation/behavior_tree_plugin/src/pedestrian/pedestrian_action_node.cpp b/simulation/behavior_tree_plugin/src/pedestrian/pedestrian_action_node.cpp index 57b05a73540..cbf2f304c22 100644 --- a/simulation/behavior_tree_plugin/src/pedestrian/pedestrian_action_node.cpp +++ b/simulation/behavior_tree_plugin/src/pedestrian/pedestrian_action_node.cpp @@ -51,20 +51,21 @@ auto PedestrianActionNode::calculateUpdatedEntityStatus(double target_speed) con auto PedestrianActionNode::calculateUpdatedEntityStatusInWorldFrame(double target_speed) const -> traffic_simulator::EntityStatus { - auto updated_status = ActionNode::calculateUpdatedEntityStatusInWorldFrame( + auto entity_status_updated = ActionNode::calculateUpdatedEntityStatusInWorldFrame( target_speed, behavior_parameter.dynamic_constraints); if ( const auto canonicalized_lanelet_pose = traffic_simulator::pose::pedestrian::transformToCanonicalizedLaneletPose( - updated_status.pose, entity_status->getBoundingBox(), entity_status->getLaneletIds(), true, + entity_status_updated.pose, canonicalized_entity_status->getBoundingBox(), + canonicalized_entity_status->getLaneletIds(), true, default_matching_distance_for_lanelet_pose_calculation, hdmap_utils)) { - updated_status.lanelet_pose_valid = true; - updated_status.lanelet_pose = + entity_status_updated.lanelet_pose_valid = true; + entity_status_updated.lanelet_pose = static_cast(canonicalized_lanelet_pose.value()); } else { - updated_status.lanelet_pose_valid = false; - updated_status.lanelet_pose = traffic_simulator::LaneletPose(); + entity_status_updated.lanelet_pose_valid = false; + entity_status_updated.lanelet_pose = traffic_simulator::LaneletPose(); } - return updated_status; + return entity_status_updated; } } // namespace entity_behavior diff --git a/simulation/behavior_tree_plugin/src/pedestrian/walk_straight_action.cpp b/simulation/behavior_tree_plugin/src/pedestrian/walk_straight_action.cpp index c9d6ca6b4a1..e4b8f5f3a95 100644 --- a/simulation/behavior_tree_plugin/src/pedestrian/walk_straight_action.cpp +++ b/simulation/behavior_tree_plugin/src/pedestrian/walk_straight_action.cpp @@ -47,10 +47,7 @@ BT::NodeStatus WalkStraightAction::tick() if (!target_speed) { target_speed = 1.111; } - setOutput( - "non_canonicalized_updated_status", - std::make_shared( - calculateUpdatedEntityStatusInWorldFrame(target_speed.value()))); + setCanonicalizedEntityStatus(calculateUpdatedEntityStatusInWorldFrame(target_speed.value())); return BT::NodeStatus::RUNNING; } } // namespace pedestrian diff --git a/simulation/behavior_tree_plugin/src/vehicle/follow_lane_sequence/follow_front_entity_action.cpp b/simulation/behavior_tree_plugin/src/vehicle/follow_lane_sequence/follow_front_entity_action.cpp index ed88dab181e..8c30fce024a 100644 --- a/simulation/behavior_tree_plugin/src/vehicle/follow_lane_sequence/follow_front_entity_action.cpp +++ b/simulation/behavior_tree_plugin/src/vehicle/follow_lane_sequence/follow_front_entity_action.cpp @@ -52,13 +52,13 @@ FollowFrontEntityAction::calculateObstacle(const traffic_simulator_msgs::msg::Wa const traffic_simulator_msgs::msg::WaypointsArray FollowFrontEntityAction::calculateWaypoints() { - if (!entity_status->laneMatchingSucceed()) { + if (!canonicalized_entity_status->laneMatchingSucceed()) { THROW_SIMULATION_ERROR("failed to assign lane"); } - if (entity_status->getTwist().linear.x >= 0) { + if (canonicalized_entity_status->getTwist().linear.x >= 0) { traffic_simulator_msgs::msg::WaypointsArray waypoints; double horizon = getHorizon(); - const auto lanelet_pose = entity_status->getLaneletPose(); + const auto lanelet_pose = canonicalized_entity_status->getLaneletPose(); waypoints.waypoints = reference_trajectory->getTrajectory( lanelet_pose.s, lanelet_pose.s + horizon, 1.0, lanelet_pose.offset); trajectory = std::make_unique( @@ -117,9 +117,7 @@ BT::NodeStatus FollowFrontEntityAction::tick() } const double front_entity_linear_velocity = front_entity_status.getTwist().linear.x; if (target_speed.value() <= front_entity_linear_velocity) { - setOutput( - "non_canonicalized_updated_status", std::make_shared( - calculateUpdatedEntityStatus(target_speed.value()))); + setCanonicalizedEntityStatus(calculateUpdatedEntityStatus(target_speed.value())); const auto obstacle = calculateObstacle(waypoints); setOutput("waypoints", waypoints); setOutput("obstacle", obstacle); @@ -129,28 +127,19 @@ BT::NodeStatus FollowFrontEntityAction::tick() distance_to_front_entity_.value() >= (calculateStopDistance(behavior_parameter.dynamic_constraints) + vehicle_parameters.bounding_box.dimensions.x + 5)) { - setOutput( - "non_canonicalized_updated_status", - std::make_shared( - calculateUpdatedEntityStatus(front_entity_linear_velocity + 2))); + setCanonicalizedEntityStatus(calculateUpdatedEntityStatus(front_entity_linear_velocity + 2)); setOutput("waypoints", waypoints); setOutput("obstacle", calculateObstacle(waypoints)); return BT::NodeStatus::RUNNING; } else if ( distance_to_front_entity_.value() <= calculateStopDistance(behavior_parameter.dynamic_constraints)) { - setOutput( - "non_canonicalized_updated_status", - std::make_shared( - calculateUpdatedEntityStatus(front_entity_linear_velocity - 2))); + setCanonicalizedEntityStatus(calculateUpdatedEntityStatus(front_entity_linear_velocity - 2)); setOutput("waypoints", waypoints); setOutput("obstacle", calculateObstacle(waypoints)); return BT::NodeStatus::RUNNING; } else { - setOutput( - "non_canonicalized_updated_status", - std::make_shared( - calculateUpdatedEntityStatus(front_entity_linear_velocity))); + setCanonicalizedEntityStatus(calculateUpdatedEntityStatus(front_entity_linear_velocity)); setOutput("waypoints", waypoints); setOutput("obstacle", calculateObstacle(waypoints)); return BT::NodeStatus::RUNNING; diff --git a/simulation/behavior_tree_plugin/src/vehicle/follow_lane_sequence/follow_lane_action.cpp b/simulation/behavior_tree_plugin/src/vehicle/follow_lane_sequence/follow_lane_action.cpp index 014973cc74b..1b70dd26599 100644 --- a/simulation/behavior_tree_plugin/src/vehicle/follow_lane_sequence/follow_lane_action.cpp +++ b/simulation/behavior_tree_plugin/src/vehicle/follow_lane_sequence/follow_lane_action.cpp @@ -39,12 +39,12 @@ const std::optional FollowLaneAction::cal const traffic_simulator_msgs::msg::WaypointsArray FollowLaneAction::calculateWaypoints() { - if (!entity_status->laneMatchingSucceed()) { + if (!canonicalized_entity_status->laneMatchingSucceed()) { THROW_SIMULATION_ERROR("failed to assign lane"); } - if (entity_status->getTwist().linear.x >= 0) { + if (canonicalized_entity_status->getTwist().linear.x >= 0) { traffic_simulator_msgs::msg::WaypointsArray waypoints; - const auto lanelet_pose = entity_status->getLaneletPose(); + const auto lanelet_pose = canonicalized_entity_status->getLaneletPose(); waypoints.waypoints = reference_trajectory->getTrajectory( lanelet_pose.s, lanelet_pose.s + getHorizon(), 1.0, lanelet_pose.offset); trajectory = std::make_unique( @@ -74,12 +74,8 @@ BT::NodeStatus FollowLaneAction::tick() request != traffic_simulator::behavior::Request::FOLLOW_LANE) { return BT::NodeStatus::FAILURE; } - if (!entity_status->laneMatchingSucceed()) { + if (!canonicalized_entity_status->laneMatchingSucceed()) { stopEntity(); - setOutput( - "non_canonicalized_updated_status", - std::make_shared( - static_cast(*entity_status))); return BT::NodeStatus::RUNNING; } const auto waypoints = calculateWaypoints(); @@ -132,9 +128,7 @@ BT::NodeStatus FollowLaneAction::tick() if (!target_speed) { target_speed = hdmap_utils->getSpeedLimit(route_lanelets); } - setOutput( - "non_canonicalized_updated_status", std::make_shared( - calculateUpdatedEntityStatus(target_speed.value()))); + setCanonicalizedEntityStatus(calculateUpdatedEntityStatus(target_speed.value())); setOutput("waypoints", waypoints); setOutput("obstacle", calculateObstacle(waypoints)); return BT::NodeStatus::RUNNING; diff --git a/simulation/behavior_tree_plugin/src/vehicle/follow_lane_sequence/move_backward_action.cpp b/simulation/behavior_tree_plugin/src/vehicle/follow_lane_sequence/move_backward_action.cpp index 41ab85ca134..d1412b22029 100644 --- a/simulation/behavior_tree_plugin/src/vehicle/follow_lane_sequence/move_backward_action.cpp +++ b/simulation/behavior_tree_plugin/src/vehicle/follow_lane_sequence/move_backward_action.cpp @@ -35,13 +35,13 @@ const std::optional MoveBackwardAction::c const traffic_simulator_msgs::msg::WaypointsArray MoveBackwardAction::calculateWaypoints() { - if (!entity_status->laneMatchingSucceed()) { + if (!canonicalized_entity_status->laneMatchingSucceed()) { THROW_SIMULATION_ERROR("failed to assign lane"); } - if (entity_status->getTwist().linear.x >= 0) { + if (canonicalized_entity_status->getTwist().linear.x >= 0) { return traffic_simulator_msgs::msg::WaypointsArray(); } - const auto lanelet_pose = entity_status->getLaneletPose(); + const auto lanelet_pose = canonicalized_entity_status->getLaneletPose(); const auto ids = hdmap_utils->getPreviousLanelets(lanelet_pose.lanelet_id); // DIFFERENT SPLINE - recalculation needed math::geometry::CatmullRomSpline spline(hdmap_utils->getCenterPoints(ids)); @@ -70,7 +70,7 @@ BT::NodeStatus MoveBackwardAction::tick() request != traffic_simulator::behavior::Request::FOLLOW_LANE) { return BT::NodeStatus::FAILURE; } - if (!entity_status->laneMatchingSucceed()) { + if (!canonicalized_entity_status->laneMatchingSucceed()) { return BT::NodeStatus::FAILURE; } const auto waypoints = calculateWaypoints(); @@ -78,12 +78,11 @@ BT::NodeStatus MoveBackwardAction::tick() return BT::NodeStatus::FAILURE; } if (!target_speed) { - target_speed = - hdmap_utils->getSpeedLimit(hdmap_utils->getPreviousLanelets(entity_status->getLaneletId())); + target_speed = hdmap_utils->getSpeedLimit( + hdmap_utils->getPreviousLanelets(canonicalized_entity_status->getLaneletId())); } - setOutput( - "non_canonicalized_updated_status", std::make_shared( - calculateUpdatedEntityStatus(target_speed.value()))); + + setCanonicalizedEntityStatus(calculateUpdatedEntityStatus(target_speed.value())); setOutput("waypoints", waypoints); setOutput("obstacle", calculateObstacle(waypoints)); return BT::NodeStatus::RUNNING; diff --git a/simulation/behavior_tree_plugin/src/vehicle/follow_lane_sequence/stop_at_crossing_entity_action.cpp b/simulation/behavior_tree_plugin/src/vehicle/follow_lane_sequence/stop_at_crossing_entity_action.cpp index e5810a1f86d..c85e6cdf622 100644 --- a/simulation/behavior_tree_plugin/src/vehicle/follow_lane_sequence/stop_at_crossing_entity_action.cpp +++ b/simulation/behavior_tree_plugin/src/vehicle/follow_lane_sequence/stop_at_crossing_entity_action.cpp @@ -54,12 +54,12 @@ StopAtCrossingEntityAction::calculateObstacle(const traffic_simulator_msgs::msg: const traffic_simulator_msgs::msg::WaypointsArray StopAtCrossingEntityAction::calculateWaypoints() { - if (!entity_status->laneMatchingSucceed()) { + if (!canonicalized_entity_status->laneMatchingSucceed()) { THROW_SIMULATION_ERROR("failed to assign lane"); } - if (entity_status->getTwist().linear.x >= 0) { + if (canonicalized_entity_status->getTwist().linear.x >= 0) { traffic_simulator_msgs::msg::WaypointsArray waypoints; - const auto lanelet_pose = entity_status->getLaneletPose(); + const auto lanelet_pose = canonicalized_entity_status->getLaneletPose(); waypoints.waypoints = reference_trajectory->getTrajectory( lanelet_pose.s, lanelet_pose.s + getHorizon(), 1.0, lanelet_pose.offset); trajectory = std::make_unique( @@ -92,7 +92,7 @@ BT::NodeStatus StopAtCrossingEntityAction::tick() in_stop_sequence_ = false; return BT::NodeStatus::FAILURE; } - if (!entity_status->laneMatchingSucceed()) { + if (!canonicalized_entity_status->laneMatchingSucceed()) { in_stop_sequence_ = false; return BT::NodeStatus::FAILURE; } @@ -132,14 +132,12 @@ BT::NodeStatus StopAtCrossingEntityAction::tick() } std::optional target_linear_speed; if (distance_to_stop_target_) { - target_linear_speed = calculateTargetSpeed(entity_status->getTwist().linear.x); + target_linear_speed = calculateTargetSpeed(canonicalized_entity_status->getTwist().linear.x); } else { target_linear_speed = std::nullopt; } if (!distance_to_stop_target_) { - setOutput( - "non_canonicalized_updated_status", - std::make_shared(calculateUpdatedEntityStatus(0))); + setCanonicalizedEntityStatus(calculateUpdatedEntityStatus(0)); setOutput("waypoints", waypoints); setOutput("obstacle", calculateObstacle(waypoints)); in_stop_sequence_ = false; @@ -152,9 +150,7 @@ BT::NodeStatus StopAtCrossingEntityAction::tick() } else { target_speed = target_linear_speed.value(); } - setOutput( - "non_canonicalized_updated_status", std::make_shared( - calculateUpdatedEntityStatus(target_speed.value()))); + setCanonicalizedEntityStatus(calculateUpdatedEntityStatus(target_speed.value())); setOutput("waypoints", waypoints); setOutput("obstacle", calculateObstacle(waypoints)); in_stop_sequence_ = true; diff --git a/simulation/behavior_tree_plugin/src/vehicle/follow_lane_sequence/stop_at_stop_line_action.cpp b/simulation/behavior_tree_plugin/src/vehicle/follow_lane_sequence/stop_at_stop_line_action.cpp index c5d131be2f7..23011a89e47 100644 --- a/simulation/behavior_tree_plugin/src/vehicle/follow_lane_sequence/stop_at_stop_line_action.cpp +++ b/simulation/behavior_tree_plugin/src/vehicle/follow_lane_sequence/stop_at_stop_line_action.cpp @@ -53,13 +53,13 @@ const std::optional StopAtStopLineAction: const traffic_simulator_msgs::msg::WaypointsArray StopAtStopLineAction::calculateWaypoints() { - if (!entity_status->laneMatchingSucceed()) { + if (!canonicalized_entity_status->laneMatchingSucceed()) { THROW_SIMULATION_ERROR("failed to assign lane"); } - if (entity_status->getTwist().linear.x >= 0) { + if (canonicalized_entity_status->getTwist().linear.x >= 0) { traffic_simulator_msgs::msg::WaypointsArray waypoints; double horizon = getHorizon(); - const auto lanelet_pose = entity_status->getLaneletPose(); + const auto lanelet_pose = canonicalized_entity_status->getLaneletPose(); waypoints.waypoints = reference_trajectory->getTrajectory( lanelet_pose.s, lanelet_pose.s + horizon, 1.0, lanelet_pose.offset); trajectory = std::make_unique( @@ -128,7 +128,7 @@ BT::NodeStatus StopAtStopLineAction::tick() } } - if (std::fabs(entity_status->getTwist().linear.x) < 0.001) { + if (std::fabs(canonicalized_entity_status->getTwist().linear.x) < 0.001) { if (distance_to_stopline_) { if (distance_to_stopline_.value() <= vehicle_parameters.bounding_box.dimensions.x + 5) { stopped_ = true; @@ -141,21 +141,17 @@ BT::NodeStatus StopAtStopLineAction::tick() } if (!distance_to_stopline_) { stopped_ = false; - setOutput( - "non_canonicalized_updated_status", std::make_shared( - calculateUpdatedEntityStatus(target_speed.value()))); + setCanonicalizedEntityStatus(calculateUpdatedEntityStatus(target_speed.value())); setOutput("waypoints", waypoints); setOutput("obstacle", calculateObstacle(waypoints)); return BT::NodeStatus::SUCCESS; } - setOutput( - "non_canonicalized_updated_status", std::make_shared( - calculateUpdatedEntityStatus(target_speed.value()))); + setCanonicalizedEntityStatus(calculateUpdatedEntityStatus(target_speed.value())); setOutput("waypoints", waypoints); setOutput("obstacle", calculateObstacle(waypoints)); return BT::NodeStatus::RUNNING; } - auto target_linear_speed = calculateTargetSpeed(entity_status->getTwist().linear.x); + auto target_linear_speed = calculateTargetSpeed(canonicalized_entity_status->getTwist().linear.x); if (!target_linear_speed) { stopped_ = false; return BT::NodeStatus::FAILURE; @@ -167,9 +163,7 @@ BT::NodeStatus StopAtStopLineAction::tick() } else { target_speed = target_linear_speed.value(); } - setOutput( - "non_canonicalized_updated_status", std::make_shared( - calculateUpdatedEntityStatus(target_speed.value()))); + setCanonicalizedEntityStatus(calculateUpdatedEntityStatus(target_speed.value())); stopped_ = false; setOutput("waypoints", waypoints); setOutput("obstacle", calculateObstacle(waypoints)); diff --git a/simulation/behavior_tree_plugin/src/vehicle/follow_lane_sequence/stop_at_traffic_light_action.cpp b/simulation/behavior_tree_plugin/src/vehicle/follow_lane_sequence/stop_at_traffic_light_action.cpp index 2e26a8f722a..e8033ff1ad7 100644 --- a/simulation/behavior_tree_plugin/src/vehicle/follow_lane_sequence/stop_at_traffic_light_action.cpp +++ b/simulation/behavior_tree_plugin/src/vehicle/follow_lane_sequence/stop_at_traffic_light_action.cpp @@ -52,12 +52,12 @@ StopAtTrafficLightAction::calculateObstacle(const traffic_simulator_msgs::msg::W const traffic_simulator_msgs::msg::WaypointsArray StopAtTrafficLightAction::calculateWaypoints() { - if (!entity_status->laneMatchingSucceed()) { + if (!canonicalized_entity_status->laneMatchingSucceed()) { THROW_SIMULATION_ERROR("failed to assign lane"); } - if (entity_status->getTwist().linear.x >= 0) { + if (canonicalized_entity_status->getTwist().linear.x >= 0) { traffic_simulator_msgs::msg::WaypointsArray waypoints; - const auto lanelet_pose = entity_status->getLaneletPose(); + const auto lanelet_pose = canonicalized_entity_status->getLaneletPose(); waypoints.waypoints = reference_trajectory->getTrajectory( lanelet_pose.s, lanelet_pose.s + getHorizon(), 1.0, lanelet_pose.offset); trajectory = std::make_unique( @@ -92,7 +92,7 @@ BT::NodeStatus StopAtTrafficLightAction::tick() request != traffic_simulator::behavior::Request::FOLLOW_LANE) { return BT::NodeStatus::FAILURE; } - if (!entity_status->laneMatchingSucceed()) { + if (!canonicalized_entity_status->laneMatchingSucceed()) { return BT::NodeStatus::FAILURE; } if (!behavior_parameter.see_around) { @@ -114,14 +114,12 @@ BT::NodeStatus StopAtTrafficLightAction::tick() if (distance_to_stop_target_.value() > getHorizon()) { return BT::NodeStatus::FAILURE; } - target_linear_speed = calculateTargetSpeed(entity_status->getTwist().linear.x); + target_linear_speed = calculateTargetSpeed(canonicalized_entity_status->getTwist().linear.x); } else { return BT::NodeStatus::FAILURE; } if (!distance_to_stop_target_) { - setOutput( - "non_canonicalized_updated_status", - std::make_shared(calculateUpdatedEntityStatus(0))); + setCanonicalizedEntityStatus(calculateUpdatedEntityStatus(0)); setOutput("waypoints", waypoints); setOutput("obstacle", calculateObstacle(waypoints)); return BT::NodeStatus::SUCCESS; @@ -133,9 +131,7 @@ BT::NodeStatus StopAtTrafficLightAction::tick() } else { target_speed = target_linear_speed.value(); } - setOutput( - "non_canonicalized_updated_status", std::make_shared( - calculateUpdatedEntityStatus(target_speed.value()))); + setCanonicalizedEntityStatus(calculateUpdatedEntityStatus(target_speed.value())); const auto obstacle = calculateObstacle(waypoints); setOutput("waypoints", waypoints); setOutput("obstacle", obstacle); diff --git a/simulation/behavior_tree_plugin/src/vehicle/follow_lane_sequence/yield_action.cpp b/simulation/behavior_tree_plugin/src/vehicle/follow_lane_sequence/yield_action.cpp index 456622d8daa..002db268065 100644 --- a/simulation/behavior_tree_plugin/src/vehicle/follow_lane_sequence/yield_action.cpp +++ b/simulation/behavior_tree_plugin/src/vehicle/follow_lane_sequence/yield_action.cpp @@ -52,13 +52,13 @@ const std::optional YieldAction::calculat const traffic_simulator_msgs::msg::WaypointsArray YieldAction::calculateWaypoints() { - if (!entity_status->laneMatchingSucceed()) { + if (!canonicalized_entity_status->laneMatchingSucceed()) { THROW_SIMULATION_ERROR("failed to assign lane"); } - if (entity_status->getTwist().linear.x >= 0) { + if (canonicalized_entity_status->getTwist().linear.x >= 0) { traffic_simulator_msgs::msg::WaypointsArray waypoints; double horizon = getHorizon(); - const auto lanelet_pose = entity_status->getLaneletPose(); + const auto lanelet_pose = canonicalized_entity_status->getLaneletPose(); waypoints.waypoints = reference_trajectory->getTrajectory( lanelet_pose.s, lanelet_pose.s + horizon, 1.0, lanelet_pose.offset); trajectory = std::make_unique( @@ -82,7 +82,7 @@ std::optional YieldAction::calculateTargetSpeed() if (rest_distance < calculateStopDistance(behavior_parameter.dynamic_constraints)) { return 0; } - return entity_status->getTwist().linear.x; + return canonicalized_entity_status->getTwist().linear.x; } BT::NodeStatus YieldAction::tick() @@ -96,7 +96,7 @@ BT::NodeStatus YieldAction::tick() if (!behavior_parameter.see_around) { return BT::NodeStatus::FAILURE; } - if (!entity_status->laneMatchingSucceed()) { + if (!canonicalized_entity_status->laneMatchingSucceed()) { return BT::NodeStatus::FAILURE; } const auto right_of_way_entities = getRightOfWayEntities(route_lanelets); @@ -104,9 +104,7 @@ BT::NodeStatus YieldAction::tick() if (!target_speed) { target_speed = hdmap_utils->getSpeedLimit(route_lanelets); } - setOutput( - "non_canonicalized_updated_status", std::make_shared( - calculateUpdatedEntityStatus(target_speed.value()))); + setCanonicalizedEntityStatus(calculateUpdatedEntityStatus(target_speed.value())); const auto waypoints = calculateWaypoints(); if (waypoints.waypoints.empty()) { return BT::NodeStatus::FAILURE; @@ -121,9 +119,7 @@ BT::NodeStatus YieldAction::tick() if (!target_speed) { target_speed = hdmap_utils->getSpeedLimit(route_lanelets); } - setOutput( - "non_canonicalized_updated_status", std::make_shared( - calculateUpdatedEntityStatus(target_speed.value()))); + setCanonicalizedEntityStatus(calculateUpdatedEntityStatus(target_speed.value())); const auto waypoints = calculateWaypoints(); if (waypoints.waypoints.empty()) { return BT::NodeStatus::FAILURE; diff --git a/simulation/behavior_tree_plugin/src/vehicle/follow_trajectory_sequence/follow_polyline_trajectory_action.cpp b/simulation/behavior_tree_plugin/src/vehicle/follow_trajectory_sequence/follow_polyline_trajectory_action.cpp index 98be60d6e81..c2c097a0da2 100644 --- a/simulation/behavior_tree_plugin/src/vehicle/follow_trajectory_sequence/follow_polyline_trajectory_action.cpp +++ b/simulation/behavior_tree_plugin/src/vehicle/follow_trajectory_sequence/follow_polyline_trajectory_action.cpp @@ -22,7 +22,7 @@ auto FollowPolylineTrajectoryAction::calculateWaypoints() -> const traffic_simulator_msgs::msg::WaypointsArray { auto waypoints = traffic_simulator_msgs::msg::WaypointsArray(); - waypoints.waypoints.push_back(entity_status->getMapPose().position); + waypoints.waypoints.push_back(canonicalized_entity_status->getMapPose().position); for (const auto & vertex : polyline_trajectory->shape.vertices) { waypoints.waypoints.push_back(vertex.position.position); } @@ -60,34 +60,26 @@ auto FollowPolylineTrajectoryAction::tick() -> BT::NodeStatus if (target_speed.has_value()) { return target_speed.value(); } else { - return entity_status->getTwist().linear.x; + return canonicalized_entity_status->getTwist().linear.x; } }; - auto getMatchingDistance = [&]() -> double { - return std::max( - vehicle_parameters.axles.front_axle.track_width, - vehicle_parameters.axles.rear_axle.track_width) * - 0.5 + - 1.0; - }; - if (getBlackBoardValues(); request != traffic_simulator::behavior::Request::FOLLOW_POLYLINE_TRAJECTORY or not getInput("polyline_trajectory", polyline_trajectory) or not getInput("target_speed", target_speed) or not polyline_trajectory) { return BT::NodeStatus::FAILURE; - } else if (std::isnan(entity_status->getTime())) { + } else if (std::isnan(canonicalized_entity_status->getTime())) { THROW_SIMULATION_ERROR( - "Time in entity_status is NaN - FollowTrajectoryAction does not support such case."); + "Time in canonicalized_entity_status is NaN - FollowTrajectoryAction does not support such " + "case."); } else if ( - const auto updated_status = traffic_simulator::follow_trajectory::makeUpdatedStatus( - static_cast(*entity_status), *polyline_trajectory, - behavior_parameter, hdmap_utils, step_time, getMatchingDistance(), getTargetSpeed())) { - setOutput( - "non_canonicalized_updated_status", - std::make_shared(updated_status.value())); + const auto entity_status_updated = traffic_simulator::follow_trajectory::makeUpdatedStatus( + static_cast(*canonicalized_entity_status), + *polyline_trajectory, behavior_parameter, hdmap_utils, step_time, + default_matching_distance_for_lanelet_pose_calculation, getTargetSpeed())) { + setCanonicalizedEntityStatus(entity_status_updated.value()); setOutput("waypoints", calculateWaypoints()); setOutput("obstacle", calculateObstacle(calculateWaypoints())); return BT::NodeStatus::RUNNING; diff --git a/simulation/behavior_tree_plugin/src/vehicle/lane_change_action.cpp b/simulation/behavior_tree_plugin/src/vehicle/lane_change_action.cpp index d387bc604d4..593915b94b0 100644 --- a/simulation/behavior_tree_plugin/src/vehicle/lane_change_action.cpp +++ b/simulation/behavior_tree_plugin/src/vehicle/lane_change_action.cpp @@ -46,7 +46,7 @@ const traffic_simulator_msgs::msg::WaypointsArray LaneChangeAction::calculateWay if (!lane_change_parameters_) { THROW_SIMULATION_ERROR("lane change parameter is null"); } - if (entity_status->getTwist().linear.x >= 0) { + if (canonicalized_entity_status->getTwist().linear.x >= 0) { traffic_simulator_msgs::msg::WaypointsArray waypoints; double horizon = getHorizon(); auto following_lanelets = @@ -102,10 +102,10 @@ BT::NodeStatus LaneChangeAction::tick() } if (!curve_) { if (request == traffic_simulator::behavior::Request::LANE_CHANGE) { - if (!entity_status->laneMatchingSucceed()) { + if (!canonicalized_entity_status->laneMatchingSucceed()) { return BT::NodeStatus::FAILURE; } - const auto lanelet_pose = entity_status->getLaneletPose(); + const auto lanelet_pose = canonicalized_entity_status->getLaneletPose(); if (!hdmap_utils->canChangeLane( lanelet_pose.lanelet_id, lane_change_parameters_->target.lanelet_id)) { return BT::NodeStatus::FAILURE; @@ -156,14 +156,14 @@ BT::NodeStatus LaneChangeAction::tick() .position.y); switch (lane_change_parameters_->constraint.type) { case traffic_simulator::lane_change::Constraint::Type::NONE: - lane_change_velocity_ = entity_status->getTwist().linear.x; + lane_change_velocity_ = canonicalized_entity_status->getTwist().linear.x; break; case traffic_simulator::lane_change::Constraint::Type::LATERAL_VELOCITY: lane_change_velocity_ = curve_->getLength() / (offset / lane_change_parameters_->constraint.value); break; case traffic_simulator::lane_change::Constraint::Type::LONGITUDINAL_DISTANCE: - lane_change_velocity_ = entity_status->getTwist().linear.x; + lane_change_velocity_ = canonicalized_entity_status->getTwist().linear.x; break; case traffic_simulator::lane_change::Constraint::Type::TIME: lane_change_velocity_ = curve_->getLength() / lane_change_parameters_->constraint.value; @@ -181,17 +181,18 @@ BT::NodeStatus LaneChangeAction::tick() * @brief Force changing speed in order to fulfill constraint. */ case traffic_simulator::lane_change::Constraint::Policy::FORCE: - entity_status->setTwist(geometry_msgs::msg::Twist()); - entity_status->setAccel(geometry_msgs::msg::Accel()); - entity_status->setLinearVelocity(lane_change_velocity_); - current_s_ = current_s_ + entity_status->getTwist().linear.x * step_time; + canonicalized_entity_status->setTwist(geometry_msgs::msg::Twist()); + canonicalized_entity_status->setAccel(geometry_msgs::msg::Accel()); + canonicalized_entity_status->setLinearVelocity(lane_change_velocity_); + current_s_ = current_s_ + canonicalized_entity_status->getTwist().linear.x * step_time; break; /** * @brief Changing linear speed and try to fulfill constraint. */ case traffic_simulator::lane_change::Constraint::Policy::BEST_EFFORT: - target_accel = (lane_change_velocity_ - entity_status->getTwist().linear.x) / step_time; - if (entity_status->getTwist().linear.x > target_speed) { + target_accel = + (lane_change_velocity_ - canonicalized_entity_status->getTwist().linear.x) / step_time; + if (canonicalized_entity_status->getTwist().linear.x > target_speed) { target_accel = std::clamp( target_accel, behavior_parameter.dynamic_constraints.max_deceleration * -1.0, 0.0); } else { @@ -205,27 +206,26 @@ BT::NodeStatus LaneChangeAction::tick() * @note Hard coded parameter, -10.0 is a minimum linear velocity of the entity. */ twist_new.linear.x = std::clamp( - entity_status->getTwist().linear.x + accel_new.linear.x * step_time, -10.0, + canonicalized_entity_status->getTwist().linear.x + accel_new.linear.x * step_time, -10.0, vehicle_parameters.performance.max_speed); twist_new.linear.y = 0.0; twist_new.linear.z = 0.0; twist_new.angular.x = 0.0; twist_new.angular.y = 0.0; twist_new.angular.z = 0.0; - entity_status->setTwist(twist_new); - entity_status->setAccel(accel_new); - current_s_ = current_s_ + entity_status->getTwist().linear.x * step_time; + canonicalized_entity_status->setTwist(twist_new); + canonicalized_entity_status->setAccel(accel_new); + current_s_ = current_s_ + canonicalized_entity_status->getTwist().linear.x * step_time; break; } if (current_s_ < curve_->getLength()) { geometry_msgs::msg::Pose pose = curve_->getPose(current_s_, true); - auto entity_status_updated = static_cast(*entity_status); + auto entity_status_updated = + static_cast(*canonicalized_entity_status); entity_status_updated.pose = pose; entity_status_updated.lanelet_pose_valid = false; - entity_status_updated.action_status = getActionStatus(); - setOutput( - "non_canonicalized_updated_status", - std::make_shared(entity_status_updated)); + entity_status_updated.action_status = canonicalized_entity_status->getActionStatus(); + setCanonicalizedEntityStatus(entity_status_updated); const auto waypoints = calculateWaypoints(); if (waypoints.waypoints.empty()) { return BT::NodeStatus::FAILURE; @@ -246,7 +246,8 @@ BT::NodeStatus LaneChangeAction::tick() curve_ = std::nullopt; current_s_ = 0; lane_change_velocity_ = 0; - auto entity_status_updated = static_cast(*entity_status); + auto entity_status_updated = + static_cast(*canonicalized_entity_status); traffic_simulator::LaneletPose lanelet_pose; lanelet_pose.lanelet_id = lane_change_parameters_->target.lanelet_id; lanelet_pose.s = s; @@ -254,10 +255,8 @@ BT::NodeStatus LaneChangeAction::tick() entity_status_updated.lanelet_pose = lanelet_pose; entity_status_updated.lanelet_pose_valid = true; entity_status_updated.pose = hdmap_utils->toMapPose(lanelet_pose).pose; - entity_status_updated.action_status = getActionStatus(); - setOutput( - "non_canonicalized_updated_status", - std::make_shared(entity_status_updated)); + entity_status_updated.action_status = canonicalized_entity_status->getActionStatus(); + setCanonicalizedEntityStatus(entity_status_updated); return BT::NodeStatus::SUCCESS; } } diff --git a/simulation/behavior_tree_plugin/src/vehicle/vehicle_action_node.cpp b/simulation/behavior_tree_plugin/src/vehicle/vehicle_action_node.cpp index 6dc4ef3a711..549ba448d97 100644 --- a/simulation/behavior_tree_plugin/src/vehicle/vehicle_action_node.cpp +++ b/simulation/behavior_tree_plugin/src/vehicle/vehicle_action_node.cpp @@ -56,7 +56,7 @@ auto VehicleActionNode::calculateUpdatedEntityStatusInWorldFrame(double target_s if (target_speed > vehicle_parameters.performance.max_speed) { target_speed = vehicle_parameters.performance.max_speed; } else { - target_speed = entity_status->getTwist().linear.x; + target_speed = canonicalized_entity_status->getTwist().linear.x; } return ActionNode::calculateUpdatedEntityStatusInWorldFrame( target_speed, behavior_parameter.dynamic_constraints); diff --git a/simulation/do_nothing_plugin/include/do_nothing_plugin/plugin.hpp b/simulation/do_nothing_plugin/include/do_nothing_plugin/plugin.hpp index 3de43ba43b9..482e3411ff7 100644 --- a/simulation/do_nothing_plugin/include/do_nothing_plugin/plugin.hpp +++ b/simulation/do_nothing_plugin/include/do_nothing_plugin/plugin.hpp @@ -70,14 +70,13 @@ public: \ private: \ TYPE FIELD_NAME; // clang-format off - DEFINE_GETTER_SETTER(BehaviorParameter, traffic_simulator_msgs::msg::BehaviorParameter, behavior_parameter_) - DEFINE_GETTER_SETTER(CurrentTime, double, current_time_) - DEFINE_GETTER_SETTER(EntityStatus, std::shared_ptr, entity_status_) - DEFINE_GETTER_SETTER(HdMapUtils, std::shared_ptr, hdmap_utils_) - DEFINE_GETTER_SETTER(PolylineTrajectory, std::shared_ptr, polyline_trajectory) - DEFINE_GETTER_SETTER(Request, traffic_simulator::behavior::Request, request) - DEFINE_GETTER_SETTER(StepTime, double, step_time_) - DEFINE_GETTER_SETTER(UpdatedStatus, std::shared_ptr, updated_status_) + DEFINE_GETTER_SETTER(BehaviorParameter, traffic_simulator_msgs::msg::BehaviorParameter, behavior_parameter_) + DEFINE_GETTER_SETTER(CanonicalizedEntityStatus, std::shared_ptr, canonicalized_entity_status_) + DEFINE_GETTER_SETTER(CurrentTime, double, current_time_) + DEFINE_GETTER_SETTER(HdMapUtils, std::shared_ptr, hdmap_utils_) + DEFINE_GETTER_SETTER(PolylineTrajectory, std::shared_ptr, polyline_trajectory) + DEFINE_GETTER_SETTER(Request, traffic_simulator::behavior::Request, request) + DEFINE_GETTER_SETTER(StepTime, double, step_time_) // clang-format on #undef DEFINE_GETTER_SETTER }; diff --git a/simulation/do_nothing_plugin/src/plugin.cpp b/simulation/do_nothing_plugin/src/plugin.cpp index 9f5597e3f7d..4e0e9a2be2e 100644 --- a/simulation/do_nothing_plugin/src/plugin.cpp +++ b/simulation/do_nothing_plugin/src/plugin.cpp @@ -149,25 +149,28 @@ void DoNothingBehavior::update(double current_time, double step_time) if ( const auto interpolated_status = do_nothing_behavior::follow_trajectory::interpolateEntityStatusFromPolylineTrajectory( - getPolylineTrajectory(), getEntityStatus(), getCurrentTime(), getStepTime())) { - return std::make_shared(interpolated_status.value()); + getPolylineTrajectory(), getCanonicalizedEntityStatus(), getCurrentTime(), + getStepTime())) { + return interpolated_status.value(); } else { - return std::make_shared( - static_cast(*entity_status_)); + return static_cast(*canonicalized_entity_status_); } }; - entity_status_->setTime(current_time); + canonicalized_entity_status_->setTime(current_time); if (getRequest() == traffic_simulator::behavior::Request::FOLLOW_POLYLINE_TRAJECTORY) { - setUpdatedStatus(interpolate_entity_status_on_polyline_trajectory()); + canonicalized_entity_status_->set( + interpolate_entity_status_on_polyline_trajectory(), + getDefaultMatchingDistanceForLaneletPoseCalculation(), getHdMapUtils()); if ( getCurrentTime() + getStepTime() >= do_nothing_behavior::follow_trajectory::getLastVertexTimestamp(getPolylineTrajectory())) { setRequest(traffic_simulator::behavior::Request::NONE); } } else { - setUpdatedStatus(std::make_shared( - static_cast(*entity_status_))); + canonicalized_entity_status_->set( + static_cast(*canonicalized_entity_status_), + getDefaultMatchingDistanceForLaneletPoseCalculation(), getHdMapUtils()); } } diff --git a/simulation/traffic_simulator/include/traffic_simulator/behavior/behavior_plugin_base.hpp b/simulation/traffic_simulator/include/traffic_simulator/behavior/behavior_plugin_base.hpp index 8094598791c..168dda9f05f 100644 --- a/simulation/traffic_simulator/include/traffic_simulator/behavior/behavior_plugin_base.hpp +++ b/simulation/traffic_simulator/include/traffic_simulator/behavior/behavior_plugin_base.hpp @@ -55,10 +55,10 @@ class BehaviorPluginBase // clang-format off DEFINE_GETTER_SETTER(BehaviorParameter, "behavior_parameter", traffic_simulator_msgs::msg::BehaviorParameter) + DEFINE_GETTER_SETTER(CanonicalizedEntityStatus, "canonicalized_entity_status", std::shared_ptr) DEFINE_GETTER_SETTER(CurrentTime, "current_time", double) DEFINE_GETTER_SETTER(DebugMarker, "debug_marker", std::vector) DEFINE_GETTER_SETTER(DefaultMatchingDistanceForLaneletPoseCalculation, "matching_distance_for_lanelet_pose_calculation", double) - DEFINE_GETTER_SETTER(EntityStatus, "entity_status", std::shared_ptr) DEFINE_GETTER_SETTER(GoalPoses, "goal_poses", std::vector) DEFINE_GETTER_SETTER(HdMapUtils, "hdmap_utils", std::shared_ptr) DEFINE_GETTER_SETTER(LaneChangeParameters, "lane_change_parameters", traffic_simulator::lane_change::Parameter) @@ -72,7 +72,6 @@ class BehaviorPluginBase DEFINE_GETTER_SETTER(StepTime, "step_time", double) DEFINE_GETTER_SETTER(TargetSpeed, "target_speed", std::optional) DEFINE_GETTER_SETTER(TrafficLightManager, "traffic_light_manager", std::shared_ptr) - DEFINE_GETTER_SETTER(UpdatedStatus, "non_canonicalized_updated_status", std::shared_ptr) DEFINE_GETTER_SETTER(VehicleParameters, "vehicle_parameters", traffic_simulator_msgs::msg::VehicleParameters) DEFINE_GETTER_SETTER(Waypoints, "waypoints", traffic_simulator_msgs::msg::WaypointsArray) // clang-format on diff --git a/simulation/traffic_simulator/include/traffic_simulator/data_type/entity_status.hpp b/simulation/traffic_simulator/include/traffic_simulator/data_type/entity_status.hpp index c02cb4b0079..68a781808a3 100644 --- a/simulation/traffic_simulator/include/traffic_simulator/data_type/entity_status.hpp +++ b/simulation/traffic_simulator/include/traffic_simulator/data_type/entity_status.hpp @@ -44,7 +44,9 @@ class CanonicalizedEntityStatus auto set( const EntityStatus & status, const double matching_distance, const std::shared_ptr & hdmap_utils_ptr) -> void; + auto setAction(const std::string & action) -> void; + auto getActionStatus() const noexcept -> const traffic_simulator_msgs::msg::ActionStatus &; auto getTime() const noexcept -> double; auto setTime(double) -> void; diff --git a/simulation/traffic_simulator/include/traffic_simulator/entity/ego_entity.hpp b/simulation/traffic_simulator/include/traffic_simulator/entity/ego_entity.hpp index 2d0fd76c432..4d780ed2343 100644 --- a/simulation/traffic_simulator/include/traffic_simulator/entity/ego_entity.hpp +++ b/simulation/traffic_simulator/include/traffic_simulator/entity/ego_entity.hpp @@ -69,7 +69,7 @@ class EgoEntity : public VehicleEntity auto getCurrentAction() const -> std::string override; - auto getCurrentPose() const -> geometry_msgs::msg::Pose; + auto getCurrentPose() const -> const geometry_msgs::msg::Pose &; auto getDefaultDynamicConstraints() const -> const traffic_simulator_msgs::msg::DynamicConstraints & override; @@ -135,9 +135,9 @@ class EgoEntity : public VehicleEntity template auto setStatus(Ts &&... xs) { - if (status_.getTime() > 0 && not isControlledBySimulator()) { + if (status_->getTime() > 0 && not isControlledBySimulator()) { THROW_SEMANTIC_ERROR( - "You cannot set entity status to the ego vehicle named ", std::quoted(status_.getName()), + "You cannot set entity status to the ego vehicle named ", std::quoted(status_->getName()), " after starting scenario."); } else { EntityBase::setStatus(std::forward(xs)...); diff --git a/simulation/traffic_simulator/include/traffic_simulator/entity/entity_base.hpp b/simulation/traffic_simulator/include/traffic_simulator/entity/entity_base.hpp index f48f20377db..3509550a77d 100644 --- a/simulation/traffic_simulator/include/traffic_simulator/entity/entity_base.hpp +++ b/simulation/traffic_simulator/include/traffic_simulator/entity/entity_base.hpp @@ -71,16 +71,16 @@ class EntityBase */ \ /* */ auto get##NAME() const noexcept->TYPE { return RETURN_VARIABLE; } - DEFINE_GETTER(BoundingBox, const traffic_simulator_msgs::msg::BoundingBox &, status_.getBoundingBox()) - DEFINE_GETTER(CanonicalizedStatus, const CanonicalizedEntityStatus &, status_) + DEFINE_GETTER(BoundingBox, const traffic_simulator_msgs::msg::BoundingBox &, status_->getBoundingBox()) + DEFINE_GETTER(CanonicalizedStatus, const CanonicalizedEntityStatus &, *status_) DEFINE_GETTER(CanonicalizedStatusBeforeUpdate, const CanonicalizedEntityStatus &, status_before_update_) - DEFINE_GETTER(CurrentAccel, const geometry_msgs::msg::Accel &, status_.getAccel()) - DEFINE_GETTER(CurrentTwist, const geometry_msgs::msg::Twist &, status_.getTwist()) + DEFINE_GETTER(CurrentAccel, const geometry_msgs::msg::Accel &, status_->getAccel()) + DEFINE_GETTER(CurrentTwist, const geometry_msgs::msg::Twist &, status_->getTwist()) DEFINE_GETTER(DynamicConstraints, traffic_simulator_msgs::msg::DynamicConstraints, getBehaviorParameter().dynamic_constraints) - DEFINE_GETTER(EntitySubtype, const traffic_simulator_msgs::msg::EntitySubtype &, status_.getSubtype()) - DEFINE_GETTER(EntityType, const traffic_simulator_msgs::msg::EntityType &, status_.getType()) - DEFINE_GETTER(LinearJerk, double, status_.getLinearJerk()) - DEFINE_GETTER(MapPose, const geometry_msgs::msg::Pose &, status_.getMapPose()) + DEFINE_GETTER(EntitySubtype, const traffic_simulator_msgs::msg::EntitySubtype &, status_->getSubtype()) + DEFINE_GETTER(EntityType, const traffic_simulator_msgs::msg::EntityType &, status_->getType()) + DEFINE_GETTER(LinearJerk, double, status_->getLinearJerk()) + DEFINE_GETTER(MapPose, const geometry_msgs::msg::Pose &, status_->getMapPose()) DEFINE_GETTER(StandStillDuration, double, stand_still_duration_) DEFINE_GETTER(TraveledDistance, double, traveled_distance_) // clang-format on @@ -94,7 +94,7 @@ class EntityBase /* */ auto FUNCTION_NAME() const->bool { return BOOL_VARIABLE; } DEFINE_CHECK_FUNCTION(isNpcLogicStarted, npc_logic_started_) - DEFINE_CHECK_FUNCTION(laneMatchingSucceed, status_.laneMatchingSucceed()) + DEFINE_CHECK_FUNCTION(laneMatchingSucceed, status_->laneMatchingSucceed()) // clang-format on #undef DEFINE_CHECK_FUNCTION @@ -247,7 +247,7 @@ class EntityBase bool verbose; protected: - CanonicalizedEntityStatus status_; + std::shared_ptr status_; CanonicalizedEntityStatus status_before_update_; diff --git a/simulation/traffic_simulator/src/data_type/entity_status.cpp b/simulation/traffic_simulator/src/data_type/entity_status.cpp index bca16c13460..7bb9052dcea 100644 --- a/simulation/traffic_simulator/src/data_type/entity_status.cpp +++ b/simulation/traffic_simulator/src/data_type/entity_status.cpp @@ -90,6 +90,17 @@ auto CanonicalizedEntityStatus::set( set(status, getLaneletIds(), matching_distance, hdmap_utils_ptr); } +auto CanonicalizedEntityStatus::setAction(const std::string & action) -> void +{ + entity_status_.action_status.current_action = action; +} + +auto CanonicalizedEntityStatus::getActionStatus() const noexcept + -> const traffic_simulator_msgs::msg::ActionStatus & +{ + return entity_status_.action_status; +} + auto CanonicalizedEntityStatus::laneMatchingSucceed() const noexcept -> bool { return canonicalized_lanelet_pose_.has_value(); @@ -171,11 +182,6 @@ auto CanonicalizedEntityStatus::setLinearJerk(double linear_jerk) -> void entity_status_.action_status.linear_jerk = linear_jerk; } -auto CanonicalizedEntityStatus::setAction(const std::string & action) -> void -{ - entity_status_.action_status.current_action = action; -} - auto CanonicalizedEntityStatus::getLinearJerk() const noexcept -> double { return entity_status_.action_status.linear_jerk; diff --git a/simulation/traffic_simulator/src/entity/ego_entity.cpp b/simulation/traffic_simulator/src/entity/ego_entity.cpp index 5119a5e9c71..65d6c56772a 100644 --- a/simulation/traffic_simulator/src/entity/ego_entity.cpp +++ b/simulation/traffic_simulator/src/entity/ego_entity.cpp @@ -124,7 +124,10 @@ auto EgoEntity::getRouteLanelets(double /*unused horizon*/) -> lanelet::Ids return ids; } -auto EgoEntity::getCurrentPose() const -> geometry_msgs::msg::Pose { return status_.getMapPose(); } +auto EgoEntity::getCurrentPose() const -> const geometry_msgs::msg::Pose & +{ + return status_->getMapPose(); +} auto EgoEntity::getWaypoints() -> const traffic_simulator_msgs::msg::WaypointsArray { @@ -139,12 +142,12 @@ void EgoEntity::onUpdate(double current_time, double step_time) if ( const auto non_canonicalized_updated_status = traffic_simulator::follow_trajectory::makeUpdatedStatus( - static_cast(status_), *polyline_trajectory_, + static_cast(*status_), *polyline_trajectory_, behavior_parameter_, hdmap_utils_ptr_, step_time, getDefaultMatchingDistanceForLaneletPoseCalculation(), - target_speed_ ? target_speed_.value() : status_.getTwist().linear.x)) { + target_speed_ ? target_speed_.value() : status_->getTwist().linear.x)) { // prefer current lanelet on ss2 side - setStatus(non_canonicalized_updated_status.value(), status_.getLaneletIds()); + setStatus(non_canonicalized_updated_status.value(), status_->getLaneletIds()); } else { is_controlled_by_simulator_ = false; } @@ -279,7 +282,7 @@ auto EgoEntity::setVelocityLimit(double value) -> void // auto EgoEntity::setMapPose(const geometry_msgs::msg::Pose & map_pose) -> void { - auto entity_status = static_cast(status_); + auto entity_status = static_cast(*status_); entity_status.pose = map_pose; entity_status.lanelet_pose_valid = false; // prefer current lanelet on Autoware side diff --git a/simulation/traffic_simulator/src/entity/entity_base.cpp b/simulation/traffic_simulator/src/entity/entity_base.cpp index b350ef4b703..82dfc29921d 100644 --- a/simulation/traffic_simulator/src/entity/entity_base.cpp +++ b/simulation/traffic_simulator/src/entity/entity_base.cpp @@ -34,8 +34,8 @@ EntityBase::EntityBase( const std::shared_ptr & hdmap_utils_ptr) : name(name), verbose(true), - status_(entity_status), - status_before_update_(status_), + status_(std::make_shared(entity_status)), + status_before_update_(*status_), hdmap_utils_ptr_(hdmap_utils_ptr), npc_logic_started_(false) { @@ -67,7 +67,7 @@ auto EntityBase::get2DPolygon() const -> std::vector auto EntityBase::getCanonicalizedLaneletPose() const -> std::optional { - return status_.getCanonicalizedLaneletPose(); + return status_->getCanonicalizedLaneletPose(); } auto EntityBase::getCanonicalizedLaneletPose(double matching_distance) const @@ -80,7 +80,7 @@ auto EntityBase::getCanonicalizedLaneletPose(double matching_distance) const // prefer the current lanelet return pose::toCanonicalizedLaneletPose( - status_.getMapPose(), status_.getBoundingBox(), status_.getLaneletIds(), include_crosswalk, + status_->getMapPose(), status_->getBoundingBox(), status_->getLaneletIds(), include_crosswalk, matching_distance, hdmap_utils_ptr_); } @@ -105,7 +105,7 @@ void EntityBase::onUpdate(double /*current_time*/, double step_time) { job_list_.update(step_time, job::Event::PRE_UPDATE); step_time_ = step_time; - status_before_update_.set(status_); + status_before_update_.set(*status_); speed_planner_ = std::make_unique( step_time, name); @@ -141,7 +141,7 @@ void EntityBase::requestLaneChange( "Source entity does not assigned to lanelet. Please check source entity name : ", name, " exists on lane."); } - reference_lanelet_id = status_.getLaneletId(); + reference_lanelet_id = status_->getLaneletId(); } else { if (other_status_.find(target.entity_name) == other_status_.end()) { THROW_SEMANTIC_ERROR( @@ -531,28 +531,28 @@ void EntityBase::setOtherStatus( auto EntityBase::setStatus(const EntityStatus & status, const lanelet::Ids & lanelet_ids) -> void { - status_.set( + status_->set( status, lanelet_ids, getDefaultMatchingDistanceForLaneletPoseCalculation(), hdmap_utils_ptr_); } auto EntityBase::setStatus(const EntityStatus & status) -> void { - status_.set(status, getDefaultMatchingDistanceForLaneletPoseCalculation(), hdmap_utils_ptr_); + status_->set(status, getDefaultMatchingDistanceForLaneletPoseCalculation(), hdmap_utils_ptr_); } auto EntityBase::setCanonicalizedStatus(const CanonicalizedEntityStatus & status) -> void { - status_.set(status); + status_->set(status); } auto EntityBase::setLinearVelocity(const double linear_velocity) -> void { - status_.setLinearVelocity(linear_velocity); + status_->setLinearVelocity(linear_velocity); } auto EntityBase::setLinearAcceleration(const double linear_acceleration) -> void { - status_.setLinearAcceleration(linear_acceleration); + status_->setLinearAcceleration(linear_acceleration); } void EntityBase::setTrafficLightManager( @@ -563,20 +563,20 @@ void EntityBase::setTrafficLightManager( auto EntityBase::setTwist(const geometry_msgs::msg::Twist & twist) -> void { - status_.setTwist(twist); + status_->setTwist(twist); } auto EntityBase::setAcceleration(const geometry_msgs::msg::Accel & accel) -> void { - status_.setAccel(accel); + status_->setAccel(accel); } auto EntityBase::setLinearJerk(const double linear_jerk) -> void { - status_.setLinearJerk(linear_jerk); + status_->setLinearJerk(linear_jerk); } -auto EntityBase::setAction(const std::string & action) -> void { status_.setAction(action); } +auto EntityBase::setAction(const std::string & action) -> void { status_->setAction(action); } auto EntityBase::setMapPose(const geometry_msgs::msg::Pose &) -> void { @@ -634,14 +634,14 @@ void EntityBase::startNpcLogic(const double current_time) void EntityBase::stopAtCurrentPosition() { - status_.setTwist(geometry_msgs::msg::Twist()); - status_.setAccel(geometry_msgs::msg::Accel()); - status_.setLinearJerk(0.0); + status_->setTwist(geometry_msgs::msg::Twist()); + status_->setAccel(geometry_msgs::msg::Accel()); + status_->setLinearJerk(0.0); } void EntityBase::updateEntityStatusTimestamp(const double current_time) { - status_.setTime(current_time); + status_->setTime(current_time); } auto EntityBase::updateStandStillDuration(const double step_time) -> double diff --git a/simulation/traffic_simulator/src/entity/misc_object_entity.cpp b/simulation/traffic_simulator/src/entity/misc_object_entity.cpp index c8e650ea6e2..327eb5e4c7d 100644 --- a/simulation/traffic_simulator/src/entity/misc_object_entity.cpp +++ b/simulation/traffic_simulator/src/entity/misc_object_entity.cpp @@ -35,7 +35,7 @@ void MiscObjectEntity::onUpdate(double, double step_time) if (npc_logic_started_) { updateStandStillDuration(step_time); } - status_before_update_.set(status_); + status_before_update_.set(*status_); } auto MiscObjectEntity::getCurrentAction() const -> std::string @@ -43,7 +43,7 @@ auto MiscObjectEntity::getCurrentAction() const -> std::string if (not npc_logic_started_) { return "waiting"; } else { - return static_cast(status_).action_status.current_action; + return static_cast(*status_).action_status.current_action; } } diff --git a/simulation/traffic_simulator/src/entity/pedestrian_entity.cpp b/simulation/traffic_simulator/src/entity/pedestrian_entity.cpp index fc2d4f51d2f..091dee54eda 100644 --- a/simulation/traffic_simulator/src/entity/pedestrian_entity.cpp +++ b/simulation/traffic_simulator/src/entity/pedestrian_entity.cpp @@ -71,7 +71,7 @@ void PedestrianEntity::requestAssignRoute(const std::vectorgetBoundingBox(), true, getDefaultMatchingDistanceForLaneletPoseCalculation(), hdmap_utils_ptr_)) { route.emplace_back(canonicalized_lanelet_pose.value()); } else { @@ -109,7 +109,7 @@ auto PedestrianEntity::getDefaultDynamicConstraints() const auto PedestrianEntity::getRouteLanelets(double horizon) -> lanelet::Ids { - if (const auto canonicalized_lanelet_pose = status_.getCanonicalizedLaneletPose()) { + if (const auto canonicalized_lanelet_pose = status_->getCanonicalizedLaneletPose()) { return route_planner_.getRouteLanelets(canonicalized_lanelet_pose.value(), horizon); } else { return {}; @@ -139,7 +139,7 @@ void PedestrianEntity::requestWalkStraight() void PedestrianEntity::requestAcquirePosition(const CanonicalizedLaneletPose & lanelet_pose) { behavior_plugin_ptr_->setRequest(behavior::Request::FOLLOW_LANE); - if (status_.laneMatchingSucceed()) { + if (status_->laneMatchingSucceed()) { route_planner_.setWaypoints({lanelet_pose}); } behavior_plugin_ptr_->setGoalPoses({static_cast(lanelet_pose)}); @@ -150,7 +150,7 @@ void PedestrianEntity::requestAcquirePosition(const geometry_msgs::msg::Pose & m behavior_plugin_ptr_->setRequest(behavior::Request::FOLLOW_LANE); if ( const auto canonicalized_lanelet_pose = pose::toCanonicalizedLaneletPose( - map_pose, status_.getBoundingBox(), true, + map_pose, status_->getBoundingBox(), true, getDefaultMatchingDistanceForLaneletPoseCalculation(), hdmap_utils_ptr_)) { requestAcquirePosition(canonicalized_lanelet_pose.value()); } else { @@ -254,14 +254,12 @@ void PedestrianEntity::onUpdate(double current_time, double step_time) EntityBase::onUpdate(current_time, step_time); if (npc_logic_started_) { behavior_plugin_ptr_->setOtherEntityStatus(other_status_); - behavior_plugin_ptr_->setEntityStatus( - std::make_shared(status_)); + behavior_plugin_ptr_->setCanonicalizedEntityStatus(status_); behavior_plugin_ptr_->setTargetSpeed(target_speed_); behavior_plugin_ptr_->setRouteLanelets(getRouteLanelets()); + /// @note CanonicalizedEntityStatus is updated here, it is not skipped even if isAtEndOfLanelets return true behavior_plugin_ptr_->update(current_time, step_time); - setStatus(*behavior_plugin_ptr_->getUpdatedStatus()); - /// @note setStatus() is not skipped even if isAtEndOfLanelets return true - if (const auto canonicalized_lanelet_pose = status_.getCanonicalizedLaneletPose()) { + if (const auto canonicalized_lanelet_pose = status_->getCanonicalizedLaneletPose()) { if (pose::isAtEndOfLanelets(canonicalized_lanelet_pose.value(), hdmap_utils_ptr_)) { stopAtCurrentPosition(); updateStandStillDuration(step_time); diff --git a/simulation/traffic_simulator/src/entity/vehicle_entity.cpp b/simulation/traffic_simulator/src/entity/vehicle_entity.cpp index b6adb24c8ac..eb6a4176036 100644 --- a/simulation/traffic_simulator/src/entity/vehicle_entity.cpp +++ b/simulation/traffic_simulator/src/entity/vehicle_entity.cpp @@ -105,7 +105,7 @@ auto VehicleEntity::getObstacle() -> std::optional lanelet::Ids { - if (const auto canonicalized_lanelet_pose = status_.getCanonicalizedLaneletPose()) { + if (const auto canonicalized_lanelet_pose = status_->getCanonicalizedLaneletPose()) { return route_planner_.getRouteLanelets(canonicalized_lanelet_pose.value(), horizon); } else { return {}; @@ -120,7 +120,7 @@ auto VehicleEntity::getWaypoints() -> const traffic_simulator_msgs::msg::Waypoin try { return behavior_plugin_ptr_->getWaypoints(); } catch (const std::runtime_error & e) { - if (not status_.laneMatchingSucceed()) { + if (not status_->laneMatchingSucceed()) { THROW_SIMULATION_ERROR( "Failed to calculate waypoints in NPC logics, please check Entity : ", name, " is in a lane coordinate."); @@ -135,7 +135,7 @@ void VehicleEntity::onUpdate(double current_time, double step_time) EntityBase::onUpdate(current_time, step_time); if (npc_logic_started_) { behavior_plugin_ptr_->setOtherEntityStatus(other_status_); - behavior_plugin_ptr_->setEntityStatus(std::make_unique(status_)); + behavior_plugin_ptr_->setCanonicalizedEntityStatus(status_); behavior_plugin_ptr_->setTargetSpeed(target_speed_); auto route_lanelets = getRouteLanelets(); behavior_plugin_ptr_->setRouteLanelets(route_lanelets); @@ -152,10 +152,9 @@ void VehicleEntity::onUpdate(double current_time, double step_time) } } behavior_plugin_ptr_->setReferenceTrajectory(spline_); + /// @note CanonicalizedEntityStatus is updated here, it is not skipped even if isAtEndOfLanelets return true behavior_plugin_ptr_->update(current_time, step_time); - setStatus(*behavior_plugin_ptr_->getUpdatedStatus()); - /// @note setStatus() is not skipped even if isAtEndOfLanelets return true - if (const auto canonicalized_lanelet_pose = status_.getCanonicalizedLaneletPose()) { + if (const auto canonicalized_lanelet_pose = status_->getCanonicalizedLaneletPose()) { if (pose::isAtEndOfLanelets(canonicalized_lanelet_pose.value(), hdmap_utils_ptr_)) { stopAtCurrentPosition(); updateStandStillDuration(step_time); @@ -174,7 +173,7 @@ void VehicleEntity::onUpdate(double current_time, double step_time) void VehicleEntity::requestAcquirePosition(const CanonicalizedLaneletPose & lanelet_pose) { behavior_plugin_ptr_->setRequest(behavior::Request::FOLLOW_LANE); - if (status_.laneMatchingSucceed()) { + if (status_->laneMatchingSucceed()) { route_planner_.setWaypoints({lanelet_pose}); } behavior_plugin_ptr_->setGoalPoses({static_cast(lanelet_pose)}); @@ -185,7 +184,7 @@ void VehicleEntity::requestAcquirePosition(const geometry_msgs::msg::Pose & map_ behavior_plugin_ptr_->setRequest(behavior::Request::FOLLOW_LANE); if ( const auto canonicalized_lanelet_pose = pose::toCanonicalizedLaneletPose( - map_pose, status_.getBoundingBox(), false, + map_pose, status_->getBoundingBox(), false, getDefaultMatchingDistanceForLaneletPoseCalculation(), hdmap_utils_ptr_)) { requestAcquirePosition(canonicalized_lanelet_pose.value()); } else { @@ -213,7 +212,7 @@ void VehicleEntity::requestAssignRoute(const std::vectorgetBoundingBox(), false, getDefaultMatchingDistanceForLaneletPoseCalculation(), hdmap_utils_ptr_)) { route.emplace_back(canonicalized_lanelet_pose.value()); } else { @@ -232,7 +231,7 @@ auto VehicleEntity::requestFollowTrajectory( for (const auto & vertex : parameter->shape.vertices) { if ( const auto canonicalized_lanelet_pose = pose::toCanonicalizedLaneletPose( - vertex.position, status_.getBoundingBox(), false, + vertex.position, status_->getBoundingBox(), false, getDefaultMatchingDistanceForLaneletPoseCalculation(), hdmap_utils_ptr_)) { waypoints.emplace_back(canonicalized_lanelet_pose.value()); } else { From c1cab6eb1ece2df58982f50a78fef5a5ecaa7234 Mon Sep 17 00:00:00 2001 From: Release Bot Date: Tue, 30 Jul 2024 00:50:29 +0000 Subject: [PATCH 057/304] Bump version of scenario_simulator_v2 from version 3.4.0 to version 3.4.1 --- common/math/arithmetic/CHANGELOG.rst | 5 +++++ common/math/arithmetic/package.xml | 2 +- common/math/geometry/CHANGELOG.rst | 5 +++++ common/math/geometry/package.xml | 2 +- common/scenario_simulator_exception/CHANGELOG.rst | 5 +++++ common/scenario_simulator_exception/package.xml | 2 +- common/simple_junit/CHANGELOG.rst | 5 +++++ common/simple_junit/package.xml | 2 +- common/status_monitor/CHANGELOG.rst | 5 +++++ common/status_monitor/package.xml | 2 +- external/concealer/CHANGELOG.rst | 5 +++++ external/concealer/package.xml | 2 +- external/embree_vendor/CHANGELOG.rst | 5 +++++ external/embree_vendor/package.xml | 2 +- map/kashiwanoha_map/CHANGELOG.rst | 5 +++++ map/kashiwanoha_map/package.xml | 2 +- map/simple_cross_map/CHANGELOG.rst | 5 +++++ map/simple_cross_map/package.xml | 2 +- mock/cpp_mock_scenarios/CHANGELOG.rst | 5 +++++ mock/cpp_mock_scenarios/package.xml | 2 +- openscenario/openscenario_experimental_catalog/CHANGELOG.rst | 5 +++++ openscenario/openscenario_experimental_catalog/package.xml | 2 +- openscenario/openscenario_interpreter/CHANGELOG.rst | 5 +++++ openscenario/openscenario_interpreter/package.xml | 2 +- openscenario/openscenario_interpreter_example/CHANGELOG.rst | 5 +++++ openscenario/openscenario_interpreter_example/package.xml | 2 +- openscenario/openscenario_interpreter_msgs/CHANGELOG.rst | 5 +++++ openscenario/openscenario_interpreter_msgs/package.xml | 2 +- openscenario/openscenario_preprocessor/CHANGELOG.rst | 5 +++++ openscenario/openscenario_preprocessor/package.xml | 2 +- openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst | 5 +++++ openscenario/openscenario_preprocessor_msgs/package.xml | 2 +- openscenario/openscenario_utility/CHANGELOG.rst | 5 +++++ openscenario/openscenario_utility/package.xml | 2 +- openscenario/openscenario_validator/CHANGELOG.rst | 5 +++++ openscenario/openscenario_validator/package.xml | 2 +- rviz_plugins/openscenario_visualization/CHANGELOG.rst | 5 +++++ rviz_plugins/openscenario_visualization/package.xml | 2 +- .../real_time_factor_control_rviz_plugin/CHANGELOG.rst | 5 +++++ .../real_time_factor_control_rviz_plugin/package.xml | 2 +- scenario_simulator_v2/CHANGELOG.rst | 5 +++++ scenario_simulator_v2/package.xml | 2 +- simulation/behavior_tree_plugin/CHANGELOG.rst | 5 +++++ simulation/behavior_tree_plugin/package.xml | 2 +- simulation/do_nothing_plugin/CHANGELOG.rst | 5 +++++ simulation/do_nothing_plugin/package.xml | 2 +- simulation/simple_sensor_simulator/CHANGELOG.rst | 5 +++++ simulation/simple_sensor_simulator/package.xml | 2 +- simulation/simulation_interface/CHANGELOG.rst | 5 +++++ simulation/simulation_interface/package.xml | 2 +- simulation/traffic_simulator/CHANGELOG.rst | 5 +++++ simulation/traffic_simulator/package.xml | 2 +- simulation/traffic_simulator_msgs/CHANGELOG.rst | 5 +++++ simulation/traffic_simulator_msgs/package.xml | 2 +- test_runner/random_test_runner/CHANGELOG.rst | 5 +++++ test_runner/random_test_runner/package.xml | 2 +- test_runner/scenario_test_runner/CHANGELOG.rst | 5 +++++ test_runner/scenario_test_runner/package.xml | 2 +- 58 files changed, 174 insertions(+), 29 deletions(-) diff --git a/common/math/arithmetic/CHANGELOG.rst b/common/math/arithmetic/CHANGELOG.rst index f02dfd36e72..7b6c04cbcb2 100644 --- a/common/math/arithmetic/CHANGELOG.rst +++ b/common/math/arithmetic/CHANGELOG.rst @@ -21,6 +21,11 @@ Changelog for package arithmetic * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.1 (2024-07-30) +------------------ +* Merge branch 'master' into doc/open_scenario_support +* Contributors: Tatsuya Yamasaki + 3.4.0 (2024-07-26) ------------------ diff --git a/common/math/arithmetic/package.xml b/common/math/arithmetic/package.xml index 0898ae893af..4776b1d86b7 100644 --- a/common/math/arithmetic/package.xml +++ b/common/math/arithmetic/package.xml @@ -2,7 +2,7 @@ arithmetic - 3.4.0 + 3.4.1 arithmetic library for scenario_simulator_v2 Tatsuya Yamasaki Apache License 2.0 diff --git a/common/math/geometry/CHANGELOG.rst b/common/math/geometry/CHANGELOG.rst index c6a59c5c4bf..0ee3efa0b45 100644 --- a/common/math/geometry/CHANGELOG.rst +++ b/common/math/geometry/CHANGELOG.rst @@ -21,6 +21,11 @@ Changelog for package geometry * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.1 (2024-07-30) +------------------ +* Merge branch 'master' into doc/open_scenario_support +* Contributors: Tatsuya Yamasaki + 3.4.0 (2024-07-26) ------------------ diff --git a/common/math/geometry/package.xml b/common/math/geometry/package.xml index 05964560f14..255a568654e 100644 --- a/common/math/geometry/package.xml +++ b/common/math/geometry/package.xml @@ -2,7 +2,7 @@ geometry - 3.4.0 + 3.4.1 geometry math library for scenario_simulator_v2 application Masaya Kataoka Apache License 2.0 diff --git a/common/scenario_simulator_exception/CHANGELOG.rst b/common/scenario_simulator_exception/CHANGELOG.rst index c5e3be0275d..570387706e8 100644 --- a/common/scenario_simulator_exception/CHANGELOG.rst +++ b/common/scenario_simulator_exception/CHANGELOG.rst @@ -21,6 +21,11 @@ Changelog for package scenario_simulator_exception * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.1 (2024-07-30) +------------------ +* Merge branch 'master' into doc/open_scenario_support +* Contributors: Tatsuya Yamasaki + 3.4.0 (2024-07-26) ------------------ diff --git a/common/scenario_simulator_exception/package.xml b/common/scenario_simulator_exception/package.xml index e67f5d199fa..3dff5760fb1 100644 --- a/common/scenario_simulator_exception/package.xml +++ b/common/scenario_simulator_exception/package.xml @@ -2,7 +2,7 @@ scenario_simulator_exception - 3.4.0 + 3.4.1 Exception types for scenario simulator Tatsuya Yamasaki Apache License 2.0 diff --git a/common/simple_junit/CHANGELOG.rst b/common/simple_junit/CHANGELOG.rst index b9ee3aef00e..0b2782b93da 100644 --- a/common/simple_junit/CHANGELOG.rst +++ b/common/simple_junit/CHANGELOG.rst @@ -21,6 +21,11 @@ Changelog for package junit_exporter * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.1 (2024-07-30) +------------------ +* Merge branch 'master' into doc/open_scenario_support +* Contributors: Tatsuya Yamasaki + 3.4.0 (2024-07-26) ------------------ diff --git a/common/simple_junit/package.xml b/common/simple_junit/package.xml index 70da1e4a78b..d4b9277a8b0 100644 --- a/common/simple_junit/package.xml +++ b/common/simple_junit/package.xml @@ -2,7 +2,7 @@ simple_junit - 3.4.0 + 3.4.1 Lightweight JUnit library for ROS 2 Masaya Kataoka Tatsuya Yamasaki diff --git a/common/status_monitor/CHANGELOG.rst b/common/status_monitor/CHANGELOG.rst index e02e471460d..fe49cc3ea4d 100644 --- a/common/status_monitor/CHANGELOG.rst +++ b/common/status_monitor/CHANGELOG.rst @@ -21,6 +21,11 @@ Changelog for package status_monitor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.1 (2024-07-30) +------------------ +* Merge branch 'master' into doc/open_scenario_support +* Contributors: Tatsuya Yamasaki + 3.4.0 (2024-07-26) ------------------ diff --git a/common/status_monitor/package.xml b/common/status_monitor/package.xml index 56e8f7bfcd6..ade3b68ce5a 100644 --- a/common/status_monitor/package.xml +++ b/common/status_monitor/package.xml @@ -2,7 +2,7 @@ status_monitor - 3.4.0 + 3.4.1 none Tatsuya Yamasaki Apache License 2.0 diff --git a/external/concealer/CHANGELOG.rst b/external/concealer/CHANGELOG.rst index 732dcf2f3d3..09953844e4f 100644 --- a/external/concealer/CHANGELOG.rst +++ b/external/concealer/CHANGELOG.rst @@ -21,6 +21,11 @@ Changelog for package concealer * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.1 (2024-07-30) +------------------ +* Merge branch 'master' into doc/open_scenario_support +* Contributors: Tatsuya Yamasaki + 3.4.0 (2024-07-26) ------------------ diff --git a/external/concealer/package.xml b/external/concealer/package.xml index 9fd05b96c92..140b51e594f 100644 --- a/external/concealer/package.xml +++ b/external/concealer/package.xml @@ -2,7 +2,7 @@ concealer - 3.4.0 + 3.4.1 Provides a class 'Autoware' to conceal miscellaneous things to simplify Autoware management of the simulator. Tatsuya Yamasaki Apache License 2.0 diff --git a/external/embree_vendor/CHANGELOG.rst b/external/embree_vendor/CHANGELOG.rst index f6cfac2ba57..b8da66880fe 100644 --- a/external/embree_vendor/CHANGELOG.rst +++ b/external/embree_vendor/CHANGELOG.rst @@ -24,6 +24,11 @@ Changelog for package embree_vendor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.1 (2024-07-30) +------------------ +* Merge branch 'master' into doc/open_scenario_support +* Contributors: Tatsuya Yamasaki + 3.4.0 (2024-07-26) ------------------ diff --git a/external/embree_vendor/package.xml b/external/embree_vendor/package.xml index f597e89ed18..17206d671a3 100644 --- a/external/embree_vendor/package.xml +++ b/external/embree_vendor/package.xml @@ -2,7 +2,7 @@ embree_vendor - 3.4.0 + 3.4.1 vendor packages for intel raytracing kernel library masaya Apache 2.0 diff --git a/map/kashiwanoha_map/CHANGELOG.rst b/map/kashiwanoha_map/CHANGELOG.rst index 016de2404ea..09a29d4f889 100644 --- a/map/kashiwanoha_map/CHANGELOG.rst +++ b/map/kashiwanoha_map/CHANGELOG.rst @@ -21,6 +21,11 @@ Changelog for package kashiwanoha_map * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.1 (2024-07-30) +------------------ +* Merge branch 'master' into doc/open_scenario_support +* Contributors: Tatsuya Yamasaki + 3.4.0 (2024-07-26) ------------------ diff --git a/map/kashiwanoha_map/package.xml b/map/kashiwanoha_map/package.xml index b51c782f6c7..cfceebfce25 100644 --- a/map/kashiwanoha_map/package.xml +++ b/map/kashiwanoha_map/package.xml @@ -2,7 +2,7 @@ kashiwanoha_map - 3.4.0 + 3.4.1 map package for kashiwanoha Masaya Kataoka Apache License 2.0 diff --git a/map/simple_cross_map/CHANGELOG.rst b/map/simple_cross_map/CHANGELOG.rst index aeb9fab9012..d3a2ba16657 100644 --- a/map/simple_cross_map/CHANGELOG.rst +++ b/map/simple_cross_map/CHANGELOG.rst @@ -9,6 +9,11 @@ Changelog for package simple_cross_map * Merge branch 'master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.1 (2024-07-30) +------------------ +* Merge branch 'master' into doc/open_scenario_support +* Contributors: Tatsuya Yamasaki + 3.4.0 (2024-07-26) ------------------ diff --git a/map/simple_cross_map/package.xml b/map/simple_cross_map/package.xml index 884f93aaa43..1d3ba40ee26 100644 --- a/map/simple_cross_map/package.xml +++ b/map/simple_cross_map/package.xml @@ -2,7 +2,7 @@ simple_cross_map - 3.4.0 + 3.4.1 map package for simple cross Masaya Kataoka Apache License 2.0 diff --git a/mock/cpp_mock_scenarios/CHANGELOG.rst b/mock/cpp_mock_scenarios/CHANGELOG.rst index 2f3d85c8d6a..88ee30ed5c0 100644 --- a/mock/cpp_mock_scenarios/CHANGELOG.rst +++ b/mock/cpp_mock_scenarios/CHANGELOG.rst @@ -21,6 +21,11 @@ Changelog for package cpp_mock_scenarios * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.1 (2024-07-30) +------------------ +* Merge branch 'master' into doc/open_scenario_support +* Contributors: Tatsuya Yamasaki + 3.4.0 (2024-07-26) ------------------ diff --git a/mock/cpp_mock_scenarios/package.xml b/mock/cpp_mock_scenarios/package.xml index 2b6179b986b..f971dad5d0e 100644 --- a/mock/cpp_mock_scenarios/package.xml +++ b/mock/cpp_mock_scenarios/package.xml @@ -2,7 +2,7 @@ cpp_mock_scenarios - 3.4.0 + 3.4.1 C++ mock scenarios masaya Apache License 2.0 diff --git a/openscenario/openscenario_experimental_catalog/CHANGELOG.rst b/openscenario/openscenario_experimental_catalog/CHANGELOG.rst index 3b045468fa0..5584f01a717 100644 --- a/openscenario/openscenario_experimental_catalog/CHANGELOG.rst +++ b/openscenario/openscenario_experimental_catalog/CHANGELOG.rst @@ -21,6 +21,11 @@ Changelog for package openscenario_experimental_catalog * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.1 (2024-07-30) +------------------ +* Merge branch 'master' into doc/open_scenario_support +* Contributors: Tatsuya Yamasaki + 3.4.0 (2024-07-26) ------------------ diff --git a/openscenario/openscenario_experimental_catalog/package.xml b/openscenario/openscenario_experimental_catalog/package.xml index 74baf0143e7..4a8fda2841c 100644 --- a/openscenario/openscenario_experimental_catalog/package.xml +++ b/openscenario/openscenario_experimental_catalog/package.xml @@ -2,7 +2,7 @@ openscenario_experimental_catalog - 3.4.0 + 3.4.1 TIER IV experimental catalogs for OpenSCENARIO Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter/CHANGELOG.rst b/openscenario/openscenario_interpreter/CHANGELOG.rst index 466ed93a195..633d6a844ec 100644 --- a/openscenario/openscenario_interpreter/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter/CHANGELOG.rst @@ -32,6 +32,11 @@ Changelog for package openscenario_interpreter * add publish_empty_context parameter * Contributors: Masaya Kataoka +3.4.1 (2024-07-30) +------------------ +* Merge branch 'master' into doc/open_scenario_support +* Contributors: Tatsuya Yamasaki + 3.4.0 (2024-07-26) ------------------ * Merge pull request `#1325 `_ from tier4/feature/interpreter/lidar-configuration diff --git a/openscenario/openscenario_interpreter/package.xml b/openscenario/openscenario_interpreter/package.xml index 24e6778cf32..4959c10deef 100644 --- a/openscenario/openscenario_interpreter/package.xml +++ b/openscenario/openscenario_interpreter/package.xml @@ -2,7 +2,7 @@ openscenario_interpreter - 3.4.0 + 3.4.1 OpenSCENARIO 1.2.0 interpreter package for Autoware Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter_example/CHANGELOG.rst b/openscenario/openscenario_interpreter_example/CHANGELOG.rst index a2f4f8b845a..430a037ac03 100644 --- a/openscenario/openscenario_interpreter_example/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter_example/CHANGELOG.rst @@ -21,6 +21,11 @@ Changelog for package openscenario_interpreter_example * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.1 (2024-07-30) +------------------ +* Merge branch 'master' into doc/open_scenario_support +* Contributors: Tatsuya Yamasaki + 3.4.0 (2024-07-26) ------------------ diff --git a/openscenario/openscenario_interpreter_example/package.xml b/openscenario/openscenario_interpreter_example/package.xml index 2b6f6b35019..4c9b91216db 100644 --- a/openscenario/openscenario_interpreter_example/package.xml +++ b/openscenario/openscenario_interpreter_example/package.xml @@ -3,7 +3,7 @@ openscenario_interpreter_example - 3.4.0 + 3.4.1 Examples for some TIER IV OpenSCENARIO Interpreter's features Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst b/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst index ccf9beef780..96cd09eb6ea 100644 --- a/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst @@ -21,6 +21,11 @@ Changelog for package openscenario_interpreter_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.1 (2024-07-30) +------------------ +* Merge branch 'master' into doc/open_scenario_support +* Contributors: Tatsuya Yamasaki + 3.4.0 (2024-07-26) ------------------ diff --git a/openscenario/openscenario_interpreter_msgs/package.xml b/openscenario/openscenario_interpreter_msgs/package.xml index 3db1ab61b94..b18a3f7a9ba 100644 --- a/openscenario/openscenario_interpreter_msgs/package.xml +++ b/openscenario/openscenario_interpreter_msgs/package.xml @@ -2,7 +2,7 @@ openscenario_interpreter_msgs - 3.4.0 + 3.4.1 ROS message types for package openscenario_interpreter Yamasaki Tatsuya Apache License 2.0 diff --git a/openscenario/openscenario_preprocessor/CHANGELOG.rst b/openscenario/openscenario_preprocessor/CHANGELOG.rst index 158a7af0db8..e1de288583e 100644 --- a/openscenario/openscenario_preprocessor/CHANGELOG.rst +++ b/openscenario/openscenario_preprocessor/CHANGELOG.rst @@ -21,6 +21,11 @@ Changelog for package openscenario_preprocessor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.1 (2024-07-30) +------------------ +* Merge branch 'master' into doc/open_scenario_support +* Contributors: Tatsuya Yamasaki + 3.4.0 (2024-07-26) ------------------ diff --git a/openscenario/openscenario_preprocessor/package.xml b/openscenario/openscenario_preprocessor/package.xml index 4a0a90ea450..ff3cce230d6 100644 --- a/openscenario/openscenario_preprocessor/package.xml +++ b/openscenario/openscenario_preprocessor/package.xml @@ -3,7 +3,7 @@ openscenario_preprocessor - 3.4.0 + 3.4.1 Example package for TIER IV OpenSCENARIO Interpreter Kotaro Yoshimoto Apache License 2.0 diff --git a/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst b/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst index 726dfc7eb28..45a0949520f 100644 --- a/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst +++ b/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst @@ -21,6 +21,11 @@ Changelog for package openscenario_preprocessor_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.1 (2024-07-30) +------------------ +* Merge branch 'master' into doc/open_scenario_support +* Contributors: Tatsuya Yamasaki + 3.4.0 (2024-07-26) ------------------ diff --git a/openscenario/openscenario_preprocessor_msgs/package.xml b/openscenario/openscenario_preprocessor_msgs/package.xml index 1a33424fc06..b9b00b6a039 100644 --- a/openscenario/openscenario_preprocessor_msgs/package.xml +++ b/openscenario/openscenario_preprocessor_msgs/package.xml @@ -2,7 +2,7 @@ openscenario_preprocessor_msgs - 3.4.0 + 3.4.1 ROS message types for package openscenario_preprocessor Kotaro Yoshimoto Apache License 2.0 diff --git a/openscenario/openscenario_utility/CHANGELOG.rst b/openscenario/openscenario_utility/CHANGELOG.rst index 8f89eba97a6..6c2760604c4 100644 --- a/openscenario/openscenario_utility/CHANGELOG.rst +++ b/openscenario/openscenario_utility/CHANGELOG.rst @@ -24,6 +24,11 @@ Changelog for package openscenario_utility * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.1 (2024-07-30) +------------------ +* Merge branch 'master' into doc/open_scenario_support +* Contributors: Tatsuya Yamasaki + 3.4.0 (2024-07-26) ------------------ diff --git a/openscenario/openscenario_utility/package.xml b/openscenario/openscenario_utility/package.xml index f37d57df7f2..ab2e12c6b85 100644 --- a/openscenario/openscenario_utility/package.xml +++ b/openscenario/openscenario_utility/package.xml @@ -2,7 +2,7 @@ openscenario_utility - 3.4.0 + 3.4.1 Utility tools for ASAM OpenSCENARIO 1.2.0 Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_validator/CHANGELOG.rst b/openscenario/openscenario_validator/CHANGELOG.rst index 1d6b032c061..8eeea4a1c84 100644 --- a/openscenario/openscenario_validator/CHANGELOG.rst +++ b/openscenario/openscenario_validator/CHANGELOG.rst @@ -10,6 +10,11 @@ Changelog for package openscenario_validator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.1 (2024-07-30) +------------------ +* Merge branch 'master' into doc/open_scenario_support +* Contributors: Tatsuya Yamasaki + 3.4.0 (2024-07-26) ------------------ diff --git a/openscenario/openscenario_validator/package.xml b/openscenario/openscenario_validator/package.xml index 96a78c145e9..30348686cdc 100644 --- a/openscenario/openscenario_validator/package.xml +++ b/openscenario/openscenario_validator/package.xml @@ -2,7 +2,7 @@ openscenario_validator - 3.4.0 + 3.4.1 Validator for OpenSCENARIO 1.3 Kotaro Yoshimoto Apache License 2.0 diff --git a/rviz_plugins/openscenario_visualization/CHANGELOG.rst b/rviz_plugins/openscenario_visualization/CHANGELOG.rst index 1dd9df87bd5..474305a1de6 100644 --- a/rviz_plugins/openscenario_visualization/CHANGELOG.rst +++ b/rviz_plugins/openscenario_visualization/CHANGELOG.rst @@ -21,6 +21,11 @@ Changelog for package openscenario_visualization * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.1 (2024-07-30) +------------------ +* Merge branch 'master' into doc/open_scenario_support +* Contributors: Tatsuya Yamasaki + 3.4.0 (2024-07-26) ------------------ diff --git a/rviz_plugins/openscenario_visualization/package.xml b/rviz_plugins/openscenario_visualization/package.xml index 8c97d64aaf2..f140c14f106 100644 --- a/rviz_plugins/openscenario_visualization/package.xml +++ b/rviz_plugins/openscenario_visualization/package.xml @@ -2,7 +2,7 @@ openscenario_visualization - 3.4.0 + 3.4.1 Visualization tools for simulation results Masaya Kataoka Kyoichi Sugahara diff --git a/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst b/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst index 297ef0b0971..448b4c17643 100644 --- a/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst +++ b/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst @@ -21,6 +21,11 @@ Changelog for package real_time_factor_control_rviz_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.1 (2024-07-30) +------------------ +* Merge branch 'master' into doc/open_scenario_support +* Contributors: Tatsuya Yamasaki + 3.4.0 (2024-07-26) ------------------ diff --git a/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml b/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml index d89a824aa9b..ed803ceac17 100644 --- a/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml +++ b/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml @@ -2,7 +2,7 @@ real_time_factor_control_rviz_plugin - 3.4.0 + 3.4.1 Slider controlling real time factor value. Paweł Lech Apache License 2.0 diff --git a/scenario_simulator_v2/CHANGELOG.rst b/scenario_simulator_v2/CHANGELOG.rst index b6ba188ebe7..6410f0674ed 100644 --- a/scenario_simulator_v2/CHANGELOG.rst +++ b/scenario_simulator_v2/CHANGELOG.rst @@ -21,6 +21,11 @@ Changelog for package scenario_simulator_v2 * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.1 (2024-07-30) +------------------ +* Merge branch 'master' into doc/open_scenario_support +* Contributors: Tatsuya Yamasaki + 3.4.0 (2024-07-26) ------------------ diff --git a/scenario_simulator_v2/package.xml b/scenario_simulator_v2/package.xml index 73ecf3a5149..cee69b01c8b 100644 --- a/scenario_simulator_v2/package.xml +++ b/scenario_simulator_v2/package.xml @@ -2,7 +2,7 @@ scenario_simulator_v2 - 3.4.0 + 3.4.1 scenario testing framework for Autoware Masaya Kataoka Apache License 2.0 diff --git a/simulation/behavior_tree_plugin/CHANGELOG.rst b/simulation/behavior_tree_plugin/CHANGELOG.rst index b1581fb72d7..a09ba91219f 100644 --- a/simulation/behavior_tree_plugin/CHANGELOG.rst +++ b/simulation/behavior_tree_plugin/CHANGELOG.rst @@ -21,6 +21,11 @@ Changelog for package behavior_tree_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.1 (2024-07-30) +------------------ +* Merge branch 'master' into doc/open_scenario_support +* Contributors: Tatsuya Yamasaki + 3.4.0 (2024-07-26) ------------------ diff --git a/simulation/behavior_tree_plugin/package.xml b/simulation/behavior_tree_plugin/package.xml index 06c8165220b..aca3bfd10bc 100644 --- a/simulation/behavior_tree_plugin/package.xml +++ b/simulation/behavior_tree_plugin/package.xml @@ -2,7 +2,7 @@ behavior_tree_plugin - 3.4.0 + 3.4.1 Behavior tree plugin for traffic_simulator masaya Apache 2.0 diff --git a/simulation/do_nothing_plugin/CHANGELOG.rst b/simulation/do_nothing_plugin/CHANGELOG.rst index 7b0d77c9509..025faac304e 100644 --- a/simulation/do_nothing_plugin/CHANGELOG.rst +++ b/simulation/do_nothing_plugin/CHANGELOG.rst @@ -21,6 +21,11 @@ Changelog for package do_nothing_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.1 (2024-07-30) +------------------ +* Merge branch 'master' into doc/open_scenario_support +* Contributors: Tatsuya Yamasaki + 3.4.0 (2024-07-26) ------------------ diff --git a/simulation/do_nothing_plugin/package.xml b/simulation/do_nothing_plugin/package.xml index 97d5240f53d..0307a928e56 100644 --- a/simulation/do_nothing_plugin/package.xml +++ b/simulation/do_nothing_plugin/package.xml @@ -2,7 +2,7 @@ do_nothing_plugin - 3.4.0 + 3.4.1 Behavior plugin for do nothing Masaya Kataoka Apache 2.0 diff --git a/simulation/simple_sensor_simulator/CHANGELOG.rst b/simulation/simple_sensor_simulator/CHANGELOG.rst index 04758f08c86..f2a45f9d25b 100644 --- a/simulation/simple_sensor_simulator/CHANGELOG.rst +++ b/simulation/simple_sensor_simulator/CHANGELOG.rst @@ -21,6 +21,11 @@ Changelog for package simple_sensor_simulator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.1 (2024-07-30) +------------------ +* Merge branch 'master' into doc/open_scenario_support +* Contributors: Tatsuya Yamasaki + 3.4.0 (2024-07-26) ------------------ diff --git a/simulation/simple_sensor_simulator/package.xml b/simulation/simple_sensor_simulator/package.xml index dbb6b9b090a..9a96c82d724 100644 --- a/simulation/simple_sensor_simulator/package.xml +++ b/simulation/simple_sensor_simulator/package.xml @@ -1,7 +1,7 @@ simple_sensor_simulator - 3.4.0 + 3.4.1 simple_sensor_simulator package masaya kataoka diff --git a/simulation/simulation_interface/CHANGELOG.rst b/simulation/simulation_interface/CHANGELOG.rst index ed933162281..187a8a14b90 100644 --- a/simulation/simulation_interface/CHANGELOG.rst +++ b/simulation/simulation_interface/CHANGELOG.rst @@ -21,6 +21,11 @@ Changelog for package simulation_interface * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.1 (2024-07-30) +------------------ +* Merge branch 'master' into doc/open_scenario_support +* Contributors: Tatsuya Yamasaki + 3.4.0 (2024-07-26) ------------------ diff --git a/simulation/simulation_interface/package.xml b/simulation/simulation_interface/package.xml index 75b6c33cd3b..d6d2668063d 100644 --- a/simulation/simulation_interface/package.xml +++ b/simulation/simulation_interface/package.xml @@ -2,7 +2,7 @@ simulation_interface - 3.4.0 + 3.4.1 packages to define interface between simulator and scenario interpreter Masaya Kataoka Apache License 2.0 diff --git a/simulation/traffic_simulator/CHANGELOG.rst b/simulation/traffic_simulator/CHANGELOG.rst index fabffcfe75c..b2979f9d273 100644 --- a/simulation/traffic_simulator/CHANGELOG.rst +++ b/simulation/traffic_simulator/CHANGELOG.rst @@ -21,6 +21,11 @@ Changelog for package traffic_simulator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.1 (2024-07-30) +------------------ +* Merge branch 'master' into doc/open_scenario_support +* Contributors: Tatsuya Yamasaki + 3.4.0 (2024-07-26) ------------------ * Merge pull request `#1325 `_ from tier4/feature/interpreter/lidar-configuration diff --git a/simulation/traffic_simulator/package.xml b/simulation/traffic_simulator/package.xml index 087d6eeaf26..585537d7a8a 100644 --- a/simulation/traffic_simulator/package.xml +++ b/simulation/traffic_simulator/package.xml @@ -1,7 +1,7 @@ traffic_simulator - 3.4.0 + 3.4.1 control traffic flow masaya kataoka diff --git a/simulation/traffic_simulator_msgs/CHANGELOG.rst b/simulation/traffic_simulator_msgs/CHANGELOG.rst index bfe7977a389..0a0876b5856 100644 --- a/simulation/traffic_simulator_msgs/CHANGELOG.rst +++ b/simulation/traffic_simulator_msgs/CHANGELOG.rst @@ -21,6 +21,11 @@ Changelog for package openscenario_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.1 (2024-07-30) +------------------ +* Merge branch 'master' into doc/open_scenario_support +* Contributors: Tatsuya Yamasaki + 3.4.0 (2024-07-26) ------------------ diff --git a/simulation/traffic_simulator_msgs/package.xml b/simulation/traffic_simulator_msgs/package.xml index 3391bbe7a1b..29d83e0fd73 100644 --- a/simulation/traffic_simulator_msgs/package.xml +++ b/simulation/traffic_simulator_msgs/package.xml @@ -2,7 +2,7 @@ traffic_simulator_msgs - 3.4.0 + 3.4.1 ROS messages for openscenario Masaya Kataoka Apache License 2.0 diff --git a/test_runner/random_test_runner/CHANGELOG.rst b/test_runner/random_test_runner/CHANGELOG.rst index 8479b47387b..d5aa32cb2f2 100644 --- a/test_runner/random_test_runner/CHANGELOG.rst +++ b/test_runner/random_test_runner/CHANGELOG.rst @@ -21,6 +21,11 @@ Changelog for package random_test_runner * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.1 (2024-07-30) +------------------ +* Merge branch 'master' into doc/open_scenario_support +* Contributors: Tatsuya Yamasaki + 3.4.0 (2024-07-26) ------------------ diff --git a/test_runner/random_test_runner/package.xml b/test_runner/random_test_runner/package.xml index d272ee3bc68..06bc95d02c7 100644 --- a/test_runner/random_test_runner/package.xml +++ b/test_runner/random_test_runner/package.xml @@ -2,7 +2,7 @@ random_test_runner - 3.4.0 + 3.4.1 Random behavior test runner piotr-zyskowski-rai Apache License 2.0 diff --git a/test_runner/scenario_test_runner/CHANGELOG.rst b/test_runner/scenario_test_runner/CHANGELOG.rst index 1f8fc2ce7c3..71adb8b8e11 100644 --- a/test_runner/scenario_test_runner/CHANGELOG.rst +++ b/test_runner/scenario_test_runner/CHANGELOG.rst @@ -35,6 +35,11 @@ Changelog for package scenario_test_runner * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.1 (2024-07-30) +------------------ +* Merge branch 'master' into doc/open_scenario_support +* Contributors: Tatsuya Yamasaki + 3.4.0 (2024-07-26) ------------------ * Merge pull request `#1325 `_ from tier4/feature/interpreter/lidar-configuration diff --git a/test_runner/scenario_test_runner/package.xml b/test_runner/scenario_test_runner/package.xml index 12be8f20a1e..80a6d8ba53c 100644 --- a/test_runner/scenario_test_runner/package.xml +++ b/test_runner/scenario_test_runner/package.xml @@ -2,7 +2,7 @@ scenario_test_runner - 3.4.0 + 3.4.1 scenario test runner package Tatsuya Yamasaki Apache License 2.0 From 57a3f922c56e8fda7bbdd5c189593ab6fa4c0e59 Mon Sep 17 00:00:00 2001 From: Dawid Moszynski Date: Tue, 30 Jul 2024 14:17:22 +0200 Subject: [PATCH 058/304] doc(time): add realtime_factor doc --- docs/image/realtime_factor/panel.png | Bin 0 -> 79398 bytes docs/image/realtime_factor/slider.png | Bin 0 -> 6280 bytes docs/image/realtime_factor/video.mp4 | Bin 0 -> 5052114 bytes docs/user_guide/scenario_test_runner/.pages | 1 + .../scenario_test_runner/RealtimeFactor.md | 50 ++++++++++++++++++ 5 files changed, 51 insertions(+) create mode 100644 docs/image/realtime_factor/panel.png create mode 100644 docs/image/realtime_factor/slider.png create mode 100644 docs/image/realtime_factor/video.mp4 create mode 100644 docs/user_guide/scenario_test_runner/RealtimeFactor.md diff --git a/docs/image/realtime_factor/panel.png b/docs/image/realtime_factor/panel.png new file mode 100644 index 0000000000000000000000000000000000000000..46d25a6333bb2923698cc8b4390c7408c200cb17 GIT binary patch literal 79398 zcmbTdWmp_Rv@MFeC3tXmx8M>2!QI{6-3jgxg1fr}cNsM3;O_43GQ7#T@7(X6ckTP$ z{OOsV>gwv+U3>4f)~-lJc}Y~HFGvs&5U5f=#FZf+AU_}=pav1(z-K0&PL99_7#A@q zRRr+I7r`_F{2Sl(yQZs(gSo4Rk+T_ug}sBF8Iy~NvzeK_i=~6>C3KGvxDoBYM&F#x zj9jf8>`7Iv?93oMTpbumIao<;tsF_&S=l)mN!i%=xY+qvx#rgSspQaz@I&46nCf z?c^u)ctBqM;+O?_2u6Hn!QR2rIQnF(&WN!vUVZyjSJ2&iH+2r9cUPExtQ5>X;I~w*M#ED*B3X!M)&TN2pCRj7!)Hei*xm$C@7={lsnr+t%H-D8udaMVXlQ6y^r{H(@bI$K zDk;I}AsAu^zdUTY3BWBvLSSn2qN({_sJ**_8XBM_3faCFg&=%!y=%RJL^2ul%@w zr#ce4opN3@iY=!L@X6oTe;TN%8Jn2YwX~Fi&uCVwCnhEmZ*+VHKahA$nk;pU1VsSI z3n!Wil81-p&RcKg)I$Tp^;luDYLJA0AiA)SVlWDuf{aWQss}v$>ySE4#HaCLi2AtVIaKGX!88v}jZxK6R?2ixb*Rg_d(9CodzTNf9Bdp*O0gWLQ2 zRO@g5dJB;C^%c<9*B=<#fV&X5&Hb{=(RG;na@HLk9qoFL4DRMbR9=2kvzlJL5_O7Q z6~Z+g_7ObMSy@?sG#TT$OTnFl{Kb@#lEPxtOn7>l)65wW{FsvtEU~hp`8SH4o-qL6 z*MPW8yL!M)ZaUgi!?Nv>YkD^&*m4mc2!+!j^BMl+-L8*svn?-VUdAMa(@&NzwEzAU zC|*2OG2fnNZv-{?&MCmX{4>&rT~tBQz}=lsQ$Xzrji^C{Z*L9E1pHl*JRrL2i5jq+KmOp7e@ye@7B}WnxVP`XJT2Ez+&l>4cyVuQ z)ey^_s8RI-u{o{>biV@P+-#P;K>CM>WX{q`SUF%@q7m^8Y;^f>bgCChpwes9j4v7l zWLu!Rb~QBIrgeC1bo&u_csvS7i6C6>P1_sn-^j&=Aa^X+KSDV@T0RlTG;Qy9qtabi z$8Tgr%pd&_;`2WUKirU?{eS*rl&997hxx9lhHZiY(&1b-7eWq0?e7x0*_hjM= zvqkft*E2WHNAJ6UYAz~58O0gN;a?5TV~aG`MR4}SH!Vgc@=4bq1& zPP~x6GT>E|!l-pqy9(hY8q|aF;ik>W-~F66A5eL8&u3c^=6r$|Km)5dDj3Kfy5O>H zPB)6h7U=zJm&RCe1n_%8_0q|8rD;#xr(2^7G7x$runwV z<*W3>4w(ULsk7a&I*`C*XY)@t<)Fy&1b;a92h z12k{5TYvuEG*k(lADF9@lrJGTkHV_IthIXMA)T+LFNduNG3dhm=R1rqzR{`u@*z#mt*|C-?=g1`rHAqs%OKSyXm`Sj0cKF7cW zfDh!kKl~~bz;EjRa6vkw#(t~+`%B??_>>A_g$@ASN*Y)+k zbn|PA1^n+G$LF_DuwV3*_^)05U&ipixmZ9Au<32fTzgM224q{=os9Z-`vLEYpq}&E zYDRsZK$(=`Y)tS|?2IH!0)%t!zcFkX{3YVy;SuP3qtzk{aSx{cb2lJI?8C3yHNa!n z<>=-%;p>8KJiuMf_HQmoP`q65lQWex>XPt#&qj!@l^k5ocZ?P$USfVuG=IJxlh&up zl$2UW&*rZlVk#VW!&Yo-HHE1if83AtqCnt=iXsx)kBw&u_&4LOW_xl@*7qTu9<{KrwX!Hb>?tbtV0)>J2@YBJeX&)shQl5%O`zHM z9#pny$9Wq+Xm+$5A>5VZ(auxgjA-C1tzLXT#Y@=zy!86d&=H*I_c=Yr1`v|al+=_3 zbg&4P&q$c&EGFkGu(Bw#b^dn{)R%G>_8JuE^EvX`ii5U9@b0BY$Ru2*Eb`e zMRtc$T8@`2(CY3t_g1kP(%5=a{dT=?PWpb-$9_Cc(lOtEE6?X2O0md!|2;|O zbZ0sl+5l&_HaH3!fyH$9v8h^o=aL1P3WurFM2>2K z){tv!YB?IIZxXVLIbQ`uCb5Bv+6#DtY4-$?{uf#TSjge-XB6dY5MpcCt+09hE!rFz zoU{;}c}|7Klncibr48;gF3PL{@2s(0FBV#?F0`m;kQMA)#tcm*jAp|{C7e9MB5?l} zkU(N7V6%Rgslu}>`As+qveek^`2E>)!{!LV8mq%R&TOZ%ny|+awbBnV>69LXn8FAL z^MzKw0Z%9rurKQT zFY(!n6hH+HNe8FDO2PY{5jsBH_17ktNJD+m!0DELWTUZqn)E#2W|aT=lr4KK80GRf znl%lP5mf@khblL_yJ!c89H#m=&57S5>cp$J6v@@InFamlsted1>u(R12Nhk#vINcTM?vFlw*iimV<_M2- z?9ikM>s$(=ha;tn>x*0Cc(NF`!l#Eje!l*zMZ55GCLLu`K^05n`#dMUJ%K*<-f0q*pEIg5A;6lr}Ah`K_4pIX$r ztd6R`9iGHxwx{RfUhJhqy3w8`tRe+cpuXJaS>AqJk8UnrUA_q6oAf06xeQ$w*L*V5 zv#EL>CxP&@*Y^1+&f^hublT|siijrgz6 zro%ok=@2%S3y!s2$0$yYs6R3Kkq5M?Strag-!V8?R_}VQogQ=U4=Z_(a=Uq~uxMdm z@-Rr>$#zK-rcp2BpW2c-Vx6%M zBkg)qL>l?5r$zt5=^ydLf>)1^0Vr+%Kx7Vzg4va@_Z=;hcB9BYd@6UU-{$|$CzHxt zY`5BMHEf*`CSTgWxk-|JL3f5wmuhCXK8<3(6(igG1{1XkD6RD!J@*&BQTNlr zlR>z?5)7S21G{Z7Odd;R!NkWODV9l%h=?F1BZCZ7t5mOZ-j`Od(H*H!t4!nfV76JT znE)g^xcCG4{DrV$Q^)|&zKXNIcl=T@tIgalOpFD`6-eYv=0~0g39CN&m=jcTXOS|e zjw}_#Hy90aPik@KUyc^!VBJ^shiq1BWxv39H$E@elN=sCS3bX66T3qSjciJh-K5WH z-cowe>wrc8!iZozUQw}R+uTSD;o;#iZq5M)`$zZQVAP+=thaNsKelY}^_VsH(H6K; z!;esX=3jb+Me_zVilI1;+96=0y}8pnY-a@;azF762;CRV0*As!Lo#1oe!g6v_}N$} zx`f?|{Gr%+3ak5q$jgEgCGz!_(aA16v(YbCZZ8h^yl)z}*$4T)G@%%6$tzPKdpQRS z)jGllgj7EC!9Czt)Vk?<5C^&C^DK`~VgM}H=fIH0u8b1sao@IA$v1&)O(AAR55yCh z*~@Up7eU8K6|Jval>~OBIYU>u7nw?q_HSf8oc?Rif2%*NyJtskFN-k9TV~+>e_Xiv zE7LpYQKlg53nY*--5mItrcdcrMO9LtbN87xD zEtQM0HYOj^V$9d1xxty5!S%LFEZyO5NcM7aA}Tz`2fEA)p;@lGIy=+pc@@D?bom^D zJ7w`0hz0t(u5$b}+z$V?TF+dagCnZIbP0tjtWJ>bvM0DiN}>6=eZ>+sTwlZo3`Yt{u}GpN7We1I2GPJ|BF zpkqC@%k?oN!Z}ArM<}oB>+ASj)~azezr2AYoOgU*?<{O@kfp$qYV(npEAeEF+k^>t}B7$5}m^z?geL;m}U31Kxu?) z(v@aA8BI;iX5h0hvx4r`&HjE0$;Cg~)s$3J`Lsyh*+Kfb?{YxO z%BT`++GU9VSbkt)5`zIqetUf$s_E=0Xk_&bzxkCxzuXk!MA2?VY9XA_bQ@GRSCQ>Y zbn;sLdFH5kShL~6;Y~YKY2V<3 z{;m}VwGVr$#=+Dw)k_!sJ*Mdr_IJZCJnuJ~<`OSVnmojbj1k(GhS^iAIk8EAMD!cJ1qomaF@>1*F zyBNjb%ix)mQ&->nCNH;|L%w=yhZlc3OL4N`+ zS`Gw8F`d4YVeHV|55NWd^_x;i_62T+72vgcQ~ZiZgZW(jXupnkhooVGSs!`%@O7y_ z)~3$m@vgM6zr*-@=X@yP^YCvTo3;=BB6IKhNVr`Om$wOiQH(K%7zAR`zSq^KdJRMF z^?tt23RM7*J2#hSV5+cdwP&^|`>+>K+1l(I+tSY23$rv{>@;1iz(247AZB{tt2-`C zBuk**M;#Y({UYsNY)gGTePS3d8ojMu1sCV_WUGZX(`_Ix_c}XKODF9A0sSi)lqdbM zVLJa>t*_lXwWz+s_oOit-Y%etuJk6<_eis|PzD7$e%VkieVJ?X*)8uGIsT2SsFU>M z@tBp*DGG@sY`ZxL+eAN@^B2TVChp$y3;Vm5?IS4nXe*#cRSleD1eP3*7iWqOQBmNm%cr6$2OP=jj zqJy9p{%9_}is*V$bFIGVjpY_`I1`EN+31s_Xh7tSUGaGUuiNv`ChC!1{;lm4>tZc3 zYWaYVfUn1Pw%frSa2LQFfxjE>xUv*+EGYfUN;1ej*3BW_H2oZ3$m+7sKr+5$Zz8?# zXQVkmv$uznAK4nSI1w6lXg=ooC|Y zeH8ud+~-Rw86=ci^9XC514?PcT+}vND93vo-zENh%&iVQ?lV6)lMk7BG$0gXxT{8RN#{RzDJeV5@V{fT=AM;cNgO4VAdLHR*Mw6A3R@SThzeVHZcafkCPYwem|B|5PNDQ|0b z*Fl^#0?TbC69iB$*doX+emTrU8DIj@l8$UHB(eEe1K)@QDB_Z)F$OJcD_JUL!0H#Z5Fi zxr^`lrjB#Re+r20LD$sOz`(!0IlkWal3|&o~q2rL#7zgB4KSCtclH4%HYQq?C zGmTjGgz9F^hUv%WFa!i*yt&kaap}YPYPo)wciap(L(uJTM|E(xBs?4&9!7R> zSZrLyh$;}sX8J%*3oePbv6M_~h9ky76Di|`7u-#!x2wceSajjZW&ocr4uBR)|S=e)g%P{!t-b6Iq zw^G$y1S>2(>W-Z~q>}~mG?SPZPlVrdDHtD~iq2&^hmFIHpRT>upA7V;QD{=V=zfi+ zVcvfd)@ZYG8R)Pj;+xPOTUw~8cP_*r*8$%!fc`jo+T%h$r!D!J^i#IWG@<<0TUWOE zkHBhpgZ_+T4j1!IY2oqO)?d=K)usXQk!% z8g^MxLOi@5V7}Jh-#?x={2vvvK>2hSG;eJN2!gd;Z@)JHT1tqEV|@Aq7>XsZn#zOJ zYj^d!!e9Ew!iI|!sGw<8s|&rJamZ)$g#rxoz!sXTP-Cc04%qI4eK=e0Z?;=q>h$9H z_3IZ3KD#(Q#7>W7$2gEA&M<$~(Y#An%bzmD6KTYkl(*3k;3!%M`=7M{Q2#oNjz%t& zh%NAWyhx%|g5u}r2dlQUTJ@Cc9Ud0ow6V3d)$wLe3WrJiF2cF=KXLTMr{brg`tKwb z{ZV#VW6t_-uWr$(-^OSl zmBoGC8+2!1KkNAObvjUH8)6jhY1el%8qti#g!c%=JPRqg$UFL{tgcJSQ+RR}2KnZ% ztz2j@u(iyP023(eFrX?dX5F-e1PoO*Dggljc)Bv(H!F6RTHLP8y!1*f|HjPgeO;%FOJO)TEIjthuH-;T#}|rnMdBk%euTI zFz=cL^FjF4|LrRTm(9ZXHE)ykJk-`eB<3Quq<{h-JfSkEm(=0JyH z)(uU^#8rreO?;J+5FOyYmCTK`Mt6Q_F!FlpKyh)v@mR?c?pbfA&6noFSu29QXmCwL zc_2ErcC6{M0Uai~6`L*LVq^lTugG8$iDbqIt~rxfLBX*q6@I0HcTg+{@uy z*z_oS(Mz#e9)awhV76fPwo}js^ELIp-{>8|TW%>HR-|JxBcF@*Vmo5Qa;Vx<@5Q$} z{PfsH22ti%pR|qeKQQ_Xvg7N3uSAGiX-EeJ8ga4Z*DD6JjVX~sDaH3NPTQq~Fw_&p zAvw`Q9FgoWy4MrG5eE zL;Sad|Jq7dc0XO+?n4dJnOuy?W=$dGWt7EbT(Dvn;(a!@Yqy&hD0sPQg>W*=i-PWP z*y7Ir*oRydJgNC^m0!=6Gix>8hr;$7JbUyYygx4s*Kk!2e~1=;a(Ob_CEqA_PKobu zw^%9nVWO@rRJ^T=v9{k^%DP-mhM|>*X(j?#AO{$&E^x`7mYLlDv3NGLXrD629W4?Z z*>^NO^!$<`($$y%l6$RNTZ*I`alpe} zl_qU-sw{!_5)`pgd)-rPqa{#B*Mf_de>ohk67=eq5oMsW27FM9$HZoPKU^~EcwO}j#=V>}UGMsanbxG+8l zP|3nFmpiV*q0U~S#3SI$rct@GC715JPnW1&9IZ1rtn#qM?}>aX0Z+s7Fw@E{{{b^& z^Cs(m$(~{@N3eafkJFsh^hsBJf9rtAl38ANsX1BLt_e}`vB61)a37v~ND@9uM{UJb zR;~{2`-lGIO&$N!`U;5wbYKu~9+^@8JzFucy9<7w zM4(gvxv-qHdHHq$f-ivK)C$1L+rm?1JJzb#jPD-;OGNso>0N{oZd655P5hOebQhc` z)j=2WeuSMh+lsZ=a)j|Wt0g~FR}r~w+ofiC;8d=k9BkXGj07JD2q>T}mkT((NkMaB z8)ta3hDHjyx_;%tAW|vBYs$64ZWBS5g#J22TOypm;N=)Faz0y0xvbG_bKO?HxG<^I zK>WD#%1~$i8J~$vO!ZPvDM3XhbW7*{o62!-%ZU-UyChjh`o$a`O7ddB`IH=&Ll2Mi z@$3yrC4!b&vbdWw~lqXKD=;4S(8LP3-n1n|Ej|*Yw z!D7zhF47ZctP=`)WU_(Za@rtX3@oexFtfeX<-r|1(;rLDU|)^!`eC%N*in{RcInTGvWycX@SFqlamD(LjXuWzec2pU=fx~w8rQXNMuf+hnT)DRF6jb=;aY*(9O6A}_^ zCEs#|19Gme9KqB&85x-tNgBqahwz)|lnq1rdWU1XJsv|(z*^4F&4A&JMH;211l-AH zJHihNL~B!G`g5YQY2#YVOy(5=X|+OUfQ{{@Yr=qeQ(~(3yzx@|HH7uZPgQ3n5vP2w zMGIEJo&@{`2j_ZqgA8vq(mXG+5|(s;$1h2`>1&w^JdqCHi1$O+If8egu1rdn^fO#d z+SLn+Z{^ZSEEvPxyNk3pV$g&jH*s~l0D{!T?*6BHsU(8s%oPcSjt7z*^$`oN-Femu zg219oEH_o| zZV=kz?|yI|dwGnud9-;I*4;iQ;t_9RK>=t_&(BId{(jsJ8{>D!vmf_W0p5qeT#J{x zV{ob87cT3NT8D+o?g6`}obR7RJJ)Kd)W$4)Jv+}_>^yw{3cf97C`~pkg-wgL=4iyy z(@N)bDpNxw!^ShAvJ^kn7>qNxG9OFT4)&$_n8o>SWm|A!@YG|yN$v_#PbE7QJ0Nfu zz|~yE-r51TcQH%QY3WXzG$A%wh!5Jw-yvOvVz%)xv+L)Pg2fePo zy6Vhj+f?zj`G&KPefaJdBNpifIz~b@R7`p*1{mYVePbbzfgW7=)3%|Yy!cx-hM7h_ zy=csKv`2S|XYI~FZioE#WOmt#1B?;J%a!>mXrOC4`9w&}K#n6=aVEBHZpGEVLXI1+ei&5AAx^WJb@H z-i;{5UM=~u27XybNun3jxC(1`{P>F%Y_XZ4)4TKWTA28Mqc<L;oprI`^Put-(CW;Vue}% z{52{;wN{udF}fq*$jv@9Au&4Tes%u4;1>YrVXA`@g`2(cMeg@NC`vk3&h{r!aE+7b z_2c7WAWHCjK|w*Q@3V6aGZsF6WM!pI+(G?jivtN*=j@0-6VeCEhu@=d>deM)RJm?z zth41M!K&x+T>0Z0 zb^H2uUOl+W`LN3=VI4mJQG)>@U>^-eW}+*J-C*gOHY%v2gI`osbgo+GF-PzHpZL2= z4fqgxdU=@v`}W~%)PH(v_g}&PR%7-5sc$+c?>y`=9Z8hcnC18qdv`Pq9T4y_oWSt! znh`L`@=+)mKU44>8LX=26f^FB8aiF9ZE!tS1{3?4?o}mLN3MKeQegVHh(dfXCDtW+ zWAD5=`RS@5Cn=#e0b@satNg9JUb`CX3YZPLWlc>f!Qv!2Ie8GcC>BD!T6=IbnL(?~ znW|E~+W2CvtxB)sf$i|+*qr~BimB5N@%5#4jcL!tz`oANQfqCjYjPnZJUc~tAa0Nm zRd|?*sdlz|;#u(Y=~>ZrC^Di7{wc47X7H7nM*CnBTWl@7w0=LA@a;F4K`5(;nlP6+ zg>>}r7`El!-P#HSi|VDbPRBFFx(e2m&XP`71*Yljc%6jA0M&LlT_ku#?p~5ZNg)ROA4?tz!UcQ8ZYwV{ zcdukw{^)Fo;1}#X^7H}y|Bt$Pv4OkzzXDL@wZje;VylKw@9U1N_-y>IDs2<2-NL>c z-xkl$F>modsb_z_i2Lf9RIuG!`_+?TAK{$dX2VuKmfgRVF9R%HZmZ;TQKV+eWLoHT zbwB#g*-Q6c&prM#FSOmk#2I5Ks2{@q$+iQMUXlsX^9+geWuEJ4cH1B9X^+3-!pkFAp znSc}PveHxsO04jT+-F06j!?q}be1=73%J++)H!=}R6PDC88>V2JUYgT#?CL<7!LNk zR8P9q^@LjE*(m$I_y1a8R(KV%bdpTtZ=~AqB4XpmA^&qc=G*l#*$&J5tQ(5)JdC+` z!=ls7xH}wA!^g+h?+@1XC1SrM7upnU+`^-Fp`pFwXTAj`ZpWjbc!%!j$I(8XNi;c{ zI_qR~;Y$5(DQ&1~#{8(t9zW8LeI9F0eFnbdH@uBZ8a(WNbwrctM-shLQkQ*C0L8|A zZgC-Efjv@UVJZrk^*^h=XI4q!>7#IFBI$l%w^I|2^IiXJaZX*@$K$dRKWh!Q0EMOyu#Co+QU8tQp zXW<9=88ls)<$yh&e8Z#+9iJ^batY4Z}2x-I%UhP4lB=sh)II;p_p>6 zEpBEEmTauPeZ$NHO&rKsI9ahrYP&l!u5UNb8eF|0-?E}TC*JExo3y*91e`?|gl93G z6tYMhO^v|d-VBYrp!djo$Fd1-cM@5EL9MUJ8vGRfRZ4Dt`pouHoZ zaCk5+HmV5u1NDuVnD{?R9jNH&5Wg!;onqa+oH@i$YpHRn$>=09G2I{X)9K#)FQ%1hc zFPt{IzY`_Ol$ogFSIlq}-V!;IH+LV~YB3W)mc zql5PdU0htWp}i&e0)@dwzNTb|oL?OMV*CfL?`IF*W*I6&v7!3z^0q$0EZEi<)~qH!bO$te50X`tiC5_Xa)PRl7Vb9X zoJ{T^V{FT>!6oc-=g-WWcCX=UCe3xJcUg^EUg^;U`}R+^WlcuRmzAG3@pdsD|(>K){LVL$w?`aIWW2;wG?XFC`#o zFbqwR>(2_OZAMsybyaydqtVZ{NPD0ThjB84m6X zEniMjcOqIe)EC(eIRh(JAYdP-q|V+7;VZi{0gb?R6*FU2%!OJb&xDM(9CkmFFaLw0 zOVVxpP~?eIIEyMlVM$+sM0svx`>OA||G=)&lPRy}Ac%X={bQA-o-RoCCQ+ANt1A(; zW5xASHzs`y$Hg#)=N0FCplO}`3+~@NO%*LTMnQ?$YUDJoca<6NK_Y?*86PMV(9 z#w+n0(aQUJ3-GE9iR>ns2An~Sf(tbkf08I)KCdcb{l983sM|X;n(bO#UuH|%mRyO4 zabQD!$GnrvuH#FlBXCpaTe-C=vuEsiCR$=zyGpdt=@4`oRi)wxRrK%O$4}kDpIV%; zuNIe8x}EXA`a}q4L(%FqpJi9e8tFP;d!_*jKc7qbjtp(4PA&Qqaff zxuphmc6_%$D3bPq{uD0%ZKNK5hFN7iJL~Svnk{@OKwh#-^m4XC%55~YQntERtnH0F zySZI(6; z%VsJ*9_P{mSakBnWx+SbVso_Cbv?JacQ=BZj=t6KKT6hl($6=l)%ssjQ5-ZO)xJ+~ z!qNP3=o2Z)av0y!Vo~N>Cm8EyJa_sNPOxZv$;K0ec3Giz-EwZS+f3l$zPU0uq<7t_ zQ6V-h32H6G*pYf1XnrFJsi@Fo#F@IwYIFU4)H-0R^V>UH%=E0QD)n9?d|%;;&Bd7h?&9Hh&6) z%;|8R)d!l3*c#PGHs{+nC1dIPVh=|Ep#VGyu$#ofd9;w)3^~2k&7GjsfxgwNHUH@C z=;6i1_cM2xyC75NJU?E53gL$?gLrft*D+rwkIIUCo{C3o%gaJx**AeydEMT^_1lma zbCN#n{}s;GMa7?0Y2Ku5pFA3hknjH!XD=BU0_}S{X(|tgx*hFq&zpfPV$h5WeWGBv zR7sMr?wRUPNx&f}|L#N7;4ek_M_DOrj^T_KBXS}i>EZzi%U1lg1olYSiqxSEt=Ni9 z^7CUh8S_1IA&YDqsfF=^oW+eYd`7BckV}9I$2oFw|N1QI`I-Zx<_F`TcFNy`=KH-v zl=r8vRPZtRD-*kff=GFW%&LjX%gM$68#({c0>wX+=iA}UXtdsSCTomhEnc%c$)E-s zAckZGfx}P~f$YK)T>mIv`c3V3#}(#pRl>9SfXt`@$5rDA^C*M=K+Vv^cuGSkEWYeJVY?sbMG3-CF zg=P}L(W+E&?4xR95Z!w)`(&5SQYe(x|7Viqb0u~!&mTGmt}}%)hX=Fha^_1AXR=Ly zDSPWa&A^K6*LIu&)h2VS(eJkg*C)N>oBpQb5$Il}V;>Q0Ps+vf{8c#uL0gQOmmbs4 zvu=v~8>@d3GlFv{NTYFT?r%P+`@SI7emEt2W@C2mXR@Azk2HEfUgaN-f7iu(gX7RY z|C_YRN4Wk@t5plTuj}@I(Ai7JT`sRjU&wrUZKE?jN`(^@@9)8$uD$GGCpzbZp0>?o!PWJiPy)$-fPpCuyz5pDGGdX>{08U+8%Z4L zLgBS8mtz$X4pwx)5-`>4=S3g8xNNA>DsDx|2w)~X_AZ}zXz z?=6;`A86e_RYyl4#KG{t?Ll1l@ZUzNh)$aSzFjN2G}S#lSNQ0A4-1-Ehk77b2BdKY zeh7VElQ#yDD2Wf!xyp zNZDX@Pr|?z2F-wTt>gHSRgFsurbI#--!A(dK6EW!wh`J>oDU0EzT+8mAfWnXr@Or& zNt)Onf`SkO>ikDVGBlWjD!V@YE~F{8ZrPF2$yuMQFms}VT zEe#)ez39WxiNgq)(Lr{rmIsdV?{3;%Es!VZMknYpns4t|a6C){_cl1=yt+&0QYLNw zp_V#C8(Jij4@{?8?5B1s?H4u{{-gIAs4sKbH4Q}>5`uwXh*3m| zk--UxT|`eyUl0ftg`^D2i2mmJ2RTS65DDRjQq&ziQTdD%y3~)J`q$Up!~_vB=KTIn zuXBdAjg2$gw%5t=i%DCPlUb#?>YcEzWSs13c+u%vwhv49k@Cz*|t5cO|eI-b(z-NIamoF1D@!7HLZd?J@{iz^DtBx=6k zvf|ydLDR*IeG4K*Xdw>@fZfM4v*r3+{w%Qq_cfpP&xJA^0kc7W9&L>M)^MaNGC}h_ z|I@{5p{9ptJbK~!DBhGL@E5*b1X0tcR8WJ~!z;N^)QF+~<^syoaa0>zwJ@;eKEP!4 zz2~jnoQNU7GoD)N7H`dkydzptx)QJClD7}Mlksc43q6w?5%=ha)A8J&2G>#+Or zfc0Fx-F7xlBSLm}&i5^wjhp9Sj}6VgRI^;5mo4n>B!ivkk!mOUzkj%$83PEpOFIJW zJ#O*fPAha3f@qoV1(uLs_Xq31-p^cD%~Xm)!-u zyPx}Z)<;Pby3rphT*mE)|6T^|{v`qdV(y9SM8wtxK96gn3cdazovVshD3W>`wtrnJ z4kjezv$aOr&#&DXAVIq9ZnMJy3#a73A-C4%YNT&C)l^NFqyn~?tQV(BRd&zZ!3KI0 zZ6s=)_1>SW32QAh>+h+{>}l1aq7p-6Uy!H^KNSk)-nC+$Y2JOBZ5GL9tD92|=B7;1 zCxeaVE|(l?&&6vsAxWPDv>7(5#g@2Q&LR;_(X+>A&xhT-hQVwg-5d;f%xaYo_g*3o zVb~#0MX<0q6ipTl+NQ7nEdBo21D>1W&w!pF+d2A~n_A(o3w0SBChqzo6jI>#2be!+ zYt5^rla%76T6!89IfDm0GYbeqo+uztPO8|G7)wJ?Wq5ER)gvoNsVU=4XD-V5`l3zN}?P`*`St7$Ev$d26&c zN1DzQC+sPXl8>NNZdgXIY1gDs%y>1LP1g6rn#B7B@LyNtC2*nGz z!h=Sw3$=)$xm4Lev~mx=_WqGC8lDOr)#KShV~N(dHO{rvTTzstgxSQR^@8gg{e{pG zz+`rYKdP3gZ7H;yzE*VM(L964L$dhd4g1q?@n4_{cJ(_Ki9sNnFp4J1a4mvDwDEL6 z$B3;EO0LBfl6oxhhA!GsMl9I$2VeL%?9Ycrvf*7=mQ00zpzk#~*Daf`FB5t}%R{Xg_om0zEpv@hq# z1`@g$O}GLU(fowa942$PYCaYG>--HV38|4d;P?iE1j zpGxZ`(YAvE1d`OI^v9JrGdjHk;gQr#u@`;O2iXr^ZHqUWcw0>85DuS^ry@^>#+l|0 zuiAUtpwfOVa3wwNB-vj)W3qPA-AV`<9@f)4JsD8ySh}OLKNv4Idd9hW@DH?Cp3j>r zpslL`*$q^^b&=HUd3r(`rvx-?d^m&+prz>_4OSllkga@+R7i?q>1NTgQd|ASXWVT7 zgHG--<*u2Ovl7z#19{pNJkdUikw58h|E*KRHof&;=WX$09jh+FpbMi1423qYb;Xu0 zYt59YQw#O=w$tN1PEbVMk8d<)xQmGVec2<26`G4dU5C3q=jI#X7&RK8h@qt2mhE?~1SP-saJJ_i_Tx=IRXw<=bK4K=4incfB4!au@$FesT zB=;D^oZEsC2h{xm%wb0}U-$9N@vMMEs9dkULlS9vbq`IAG7#Lb@;Oj?J$v=O-#r*y zJZ9FPee(^uadlkr3w~Vq+L!Wh2cgX!RiIV(lRyAtES_92Aowvwi<=?)`l1gMfrPKL z$5I#Mk|&!siA>P-Hv^Y_oYQ+GjO3zI!s!ijBe}DppWN?bj!1Q7Hw_qX|qu@Uob|KoQtawa|Ih3e6Qf}GFgC$OnWdS+rTmLepz>kGW!7k(SjOWcqD4~4^jj6lE3WQ-m? zbnqu6>|~Ef;7@uD_hY;!-@%d}dyiK;+!IR{4Ihy*xUKXOO)m`or5g)>Y|s1QOdgn+ zNurTB(b0y@-{dNJt0; z1qC`ODHxYQt|9pVogF5dg`rb3@ffyI*5`& zUEfur3T615id@>i@c$!u3;jVm-UIZVF%wNR1`GEnBKfAJ5iTw+F0ZcUs+K91DEAKy zsWtz~dy$xG9ML&)zZa2fDE0SNypr{I{BG@M`Lg5G^<166e03J>;}x@!^$vQ*c0Rpf zZC&Vyh$}C*_Ex9W*5XW!tU63inoTD_8*7qx=&o`>ZzyZ|eHR^>WVELmk*$x?iHddv z3*Sq8Ukw5&{~a;vHRE74t;;;c-04g0dPH>ZzB{hTErzh{Tz)0@Awgxx`uCK%|1epd zyETk$Me0sk7u^*s%XiC>C6M`Mtusb=Bk!hOY{_c2#Ra>5;ia4!@asepH1q6pAc9Up zgr==yvDRqKpx4L9K9DWF)B-^=w)*^%m^L(~!_dD5)ji2u{DybxjU)c> zZ>k&LO7@)Q4gnY?VCp@Q|EZ$nWXCt50qGB8aLu7pjqZhPh}B!Z5Tl5feZ74@b1ori zWoLj`M8UJRLxej>a2h3n;;ST=(<>_$GT-B2iKZKmdQO7_S+;>ZmF>^`N3lpy9sOgr zDS7EPEyJ@-$qH4hl^DInMo7GtS|2*^+|r%jh7rFO2Ko66IB^lV_i%=e7iIcw)8)EM z{xq*>8Xl-dP?0Z17eYwUwe2J4s93vNRh(U+T#WOD$tyVFIX1E09nl=C+V^cpg-tH{ zXCE#l18##1aBmW?+dJGnl_y`-Q_u>rgf1P{VCOHLx}_{59Pc_Aq*Oq$X@sjt}*I>-9)O`G@OHgC(ZEe?qNnkkr z1z093G2cBmLr^h^8nr4vbFm}TqP_oTf-XP_79t_-z)Ez zT}^zyfKwRs71;MA3-Gpgm^bn%5YtuO7-%Q^UOsY#^%p_E5`KEfZG88mRNH{w!no{S z0Qvj-r|>${m6ViF?zgqHu)3V8ht1No@1r4FU=#5t8Tg3MT@^t`Xy&#i5zkhXmPzr# zEtT(955ae)Es!wJj@*?-tU9H(2pHnW&8N`5>&TL?u`>`nP`$QkDO$fPr>d7+noXxY zbQ1maO-sBLxp8;xA45ho>yKo0rc;5O6OS}raP7E?`M$Rq6$X7E#qc%G!w73F_T=Vj z+t%DHp{K`I;^scBujC2jHt5Zb8r2Tv#bd$1jDnJLL@H8}J9=<2l5xl(J(hiRlcFlI zzqw?~e!OyEzuJ_7A)Kf!U!8kbKLIMrBhKz+?M9tn`0MTntC+d*4UhTi;I;`5ctG4M z2Uc_-rx~HgBUq2yJAZw;OdAQ{HF2a|@c+(uN^huD*VrN5R&+pimpaT%8kj5C5+J$L ziV@fBC*b(op7umNA?~Hz+R%LMsB2hfkoBcw&Kj)?S^@eYX`^ zGaIlJ4M-|Z`n+8!1ps4=mz8(7noKBnT7u(N$vsTOD`+-XPr7_@!0yI0rZKwb5$~Ht~yIq{tciCw7!|6$K=igy|N_**cM;=yNO?h^HJq+tQSyPs{cE6kwPs{ z%b*xqbsl~#z79D-`XVoVOA_s*7DdfsP#g|aO;o@8Hwd! zZ_veOVvHjKd*hFqgnKk~;|Dt*VbgTP$5uzfidrOJ2KTCg21z} zYG7BcEB2TTS4{fxbg2j-8RvHy&&+Di(7y2pFX*{koq8TpM*p81pGPIi8e`V0sPD0-g1+!8lQf$Ensp)U939K-HsNkK z0scJ@p?*@a)1_mX6yI&5X9%&C=}IsueNy`U;X>v}4W+O=%PT5s8XE^YS7hXlcUmxQ zA(6GU*+T^71C=J`U`(eJ#BD|;My4p=D}e&u8M~)ZS^gor{quhN8rZrUnZ?NF`Nnj3 zQ$(9~;v`z)^Mj50eC0Z=EX*T6L3?g=Yh5yA=!k^((}cJUo>x5~B)solA5d1Tot96g2prvlm|2S~^gE3dAC3tEk>M<)C` zDIKR%b~zeOB95DI(f`cwvHl$23ZmvG`F#0LQd$rluNl(e+SGVMMexJ(KHuh<*Jmvi zO53pSIwDz9P}(%BHcE1%2OrtZ6i%2FG#sxwnNZGXS&YAyxEcgLp;8Lpl`-b~#t@7% z*6KjBO6Oo@<&U$}MLeb0pSZH`y@s2A%ARoP7$82sb&-v8gHkNt+&!@9zN>bdDY4KZ z)|P*vM}*CLVopwby}7G};e1b{4TW4aky!@8tcR-YP+~{=s3yyKOI?u64SV=d>5ZF( zb~(eAZJZB3B32aA=|=%Oo)EBKG#}{waUL zb#Qg9vfB*qwS1$ZK!~l{!*b<}LK@-GZb_B?p-Cc%|CFyi7Z+prg?&k#gVJ<&{W%p- zqU^R*7Tn~OPM*XMkBCauY=>AHQPmOf-$|!FIO*gpkuY;J>;=_x2SREzo|+B~F2Yih zXN2?pv&b&Nmn-(h34WK%le#*CMeJ#3Pn zu$Rnlb6A{*9Us6SYAV{S)k3yFCcxl1zyh?Up zmeH-uMC6#Su*Q4tk6##uuR{VO;R89GIJ(W&fCar4A%_&Kc_I-%Qq!;4@q{{_A-Aaw@)F$B&9N#8$Q|zD9dZ#INmg20t)| z*=ixPd;8X~_D=2Pl2!qMh!>ms+9-fJV^bG%BzQlCP`Ji@0H2YDc-4}B?!Jr{Rf)#a z-WyA)3MK+RSPctKr)~*v#_Cg^?n$UtZyG=Gex%c#UgRMm+v$qk|B%R5a@$MYpEs}J zf$5K*JX7zAYN8ex7YhsI{5=jkpED8aj&C%ZL&p&0>b;ptF?qWF7)oq-aK@{$KhLc1 zdj~a^1jc<$`DN-t z)c1xQZP7O8CU=gW{W4u&#I~x&wv|$;&$7&?iZM{k1#6hSbqX)9vF^2X1^ij17o48& zvB?-fR2qStUjnYi-QNjIA1dU|SDYX{?z45xk)#FpY^j-=+axJ$Ujz3f`rN7JC;VR6 zq}JWMJdq3MnmgNHGyQrOP(bG>VMYRxDQWTxAdUVfmHc%wN@bk!=;Vb@yO z^iFXPFKe1t)0@`Lm=Dho(k~5EQ6+OHT5omYhXH2(|B$pB z!04|f#$dG>bQy49shY-PHBtNzY5!AXy~^seQLpBrTm+TvljrRbx=7o>hS7Z~;3sFo z`_U}VtouG06@SXGn*VPz%$4LKT~J_p_A_*Aa+oGv*Fj2?{a5Cv^PRY))@iCnxIRI> zo~tscl(pmOYr{oGLa{S)_QSPG#t!Q9-iwB;Cr1~!e{|l)qP>*&j*HBm!PSmHmU2%9 z>sC~gQTZ3iSm%H!-JWAwdCd2PF(->P|Cur;{)bmsoLiLY$FO`ZH*?s zj+G~(r*@>fzFv4FByxswK^@a~!x{3N*aqy9lOpzJOSsH;eS!OqF5~s3j>|-dd1#c! z=p{n!tuPEdhk5u`D$>ibCa9|o_CO!vHT1PT&cr>=eAykk{nfC_Plidaqs!tW40wwv z$&-DL=gpt!B?F&hK!I2RYt&CKFZBAIHag32K2lOrfu8NsKYw-)48TMbg6O8fI*ETH zA}T~(80WeG05AW%WrqPE|vqL6SiU!yHhPFY!5k-xzRTqpr6DuES)%x8GPwFh%^b2m>< zt#oEmQs(v!ozQdhIEtegt9!ICv;J)W5k%k^ZXCl~dRZQ4l}j7c#DU+Je|*>2i-5M+ z&t3YZ?yClW*CyK04&pFbBjx^(T_XK3CmGokI-XdwjWMyszUZ7?V&|9j@U1_#iapx0hg!;q0Xd{sul3@v_?=cr6nB4hv)!eMK zq1eTI2_6RsS_Vk})!KWTU#hUYXkBgT?BLqdmhNoPph%#^S~I`~@y()v%&!Xu5$Zkr z!0_=La5AH*4iR0v%YOJ##ezC9KuV)z`c$f%tr|ATIQEPGQcq5DNN5^uZ}?L^m2_sU z>iJW?i}PND8EIy9>%)l;QQ_#RUP1=cI-&ba|NYy+`#m*h42FsueLumS_f%MNzmrf= zumre{ruk}T{N_VL^0-r_E0U+GII$FQ8%|UkNmN}9lYJ{UenHUCA;4H_#*?SSz$ZjW zn0cWTwp<_9Uc-}N=_(NHnwXI%U~n&vIBN}Joj8B~3rwJ1(NyWz<#cqF8&YL_O$v5u~xN;~Nr1rhw z^N3$T%49vqgi_NZ=OoV>OA){Q*Ku90W@giV;A`fUP}(hmc@ZmfRsl~yzutbwdfd$ z&Q!io@Jzb60Z~$sg&>@w!1U%Jg~I2JIxODv*4xMJM99z1l;7&019qJIF=YQui=O21 z7kiyz+4vv5*e`s1Sp=U*#Gr2C)gYR6dt<8`RP#DghvU!8^Cd0PiLBh&#^W9`8;$R; z0UBu<9+=potd%EJDN*RKvnSlea<@Vqxl{8GMLk6bWqiNclk2k{m*l2X!Vp2tKY&eOfJp<+5szb=6R5VFUgzD9*YW z^rZJCkXmT$Tj4xS_vh!x7TaR%^2EF%fbtbmmdWylq zc}0$@D#0nvI_CA%8M2Ke?W8-h0&pn21O0oC$~abGh7yU8W@i7237D0edY0t;8z>yX z3YT{PJ(Hd%P_BWKtv7>MhaNf!7eR!$Fr6cV^(Puc(2~RTbg>G|E4lRU0bz4uf&?eP z)k%}{Jv~wal0Sn8;wP^Q-Z6K{<+D*o35VO(6~d_t8+m504O>e9Fv5Sm^Rn~Y6hNd^3U1LeUZ4^=vMZli0y zT0C==yJ;=xVywKKYDaS*SdBoXNdB62e~{i6o7m8TZJO8rX>HPO)J!bwCqTS0MpBz# zDCGB^Y=cy8@fsA&=g&rBQ$2ZV-(oDkNEA?#@%su^ynbtXglt3B-`N}6RYz0C#Z2~O zNkf+OFQbj>71oiZMeur5BS?bXw*6mN0JTpm+0;lO$9EQNEjdB{a7?VMl7k(gxUX6Z zz0%Hp=BCKQ7M5hCD_^r(yZZrmcup1$zl>+=pLTyn*2C8tKWwEVF6FD-+k{(@epk?B zyWuiI503Qc*_cnLd`M6~XJz8FMT}>?*6majk5N9PP;jVKZ+d|2+Q;iz&6JaWWUJL6 zpfpB$M}6@@=uY5G__CJWjm~c-7hQvP#lBC$zeI{zdwSgPhsl5wfhC_btaxGuC1HLlz@s2j%&#G; zXfs*Zx_Y=BX*7Z$=_~2J;}qRgm@Tga?%UX>|D^k=cGkc4dVJ$DQyNjO*S&z+qqP|urKmE-K3M(rD$w9;n<4Xne`-pN*8BslCg6@>!7GEMD2$Q%Jd zPcvKKP(zQ4Ty*31w5rEp=eJ)!O?Tlbq`G7a5r#Hxu6s+ z-D&5k(x*2tCdSjoJ(X2mHeGqF;^QO6P6jo`bUGnd53FhSX2WSo4oaaETfw`i#n`dM zxgmAgT2O02Hc&+l?0qJ@U+mwaZ=q2+gP-q7VVh$EE9A2y^IC|AI^*X0zozH{lQQ_G zu8%_gIdooQs%Tei9jnO2uO0~CknCtx{19oo$Ec@wE5VBZd9r4P@G1R;Do;;8S|1K8 z%v5bQ`?^Mxvv@d$SBv}Eo5a2a-6l`C_v3y-Z{>XT>k34+&bH&3z~Mzh!gEd+d-VOK*Bg{v=T^B`#^Q;t*!80VVR${7m1cLqefI`!sb zGCnD2fxvXDr)Qt&h<<8Q$JTyM0Cvm-l)J!}q=B}{TKb8A(FOk|t#3Gc!gR$5Nt$yE z)@h-Fjys^=?z9I~{J(TjUm_2xFWeyS^8At?1B9q6)3+bA7C}`PXh%Vy&sn2Q)N3skf)lkfvTKlceUk;M*5pIac41FG6kR8!P695^!O5Wh%L5MX;D z&M`kyV{18v+~K~`Tl#FZEhV)+IZ_^I%T8>S?*35W69|iwG3Gy4U2Xm3H1DJq=S~|V zX3EYALHCO!CDh+tgC~joh;615)h(tkfpB($do(+)nlZ8RN)z>+KzaVEM%=Td`o5~L zG7CjpdP}dvFSo;;Pug^MIf239n0MO};LVp$crUgEtfOtAxg-8tEp6oNLc6AW&f3W{ zf$4}H7#?mVmvF6}Wn?TO3zw1yS6MAMsZI7%lKV@NeK@@<1GW*OCv3-ECRTvNQlIla zFzeGc$#2*O)RJrnboD;}bOwR3cV45)t6(wxd5xs3ze@K;Qt}3ikxm?(kZv`hu#&9R zchf4d86ECb4cs%IPy^igW^yC>Ft~hkqoY%UH#P!If270P*L|IyAmF~c{Cs8>o*|QMI z4ns}L^)}TX>nWpXd%6^+x7B>%L*L&Kb>h?_!VU}@X~9chKf*c|ZH~g4`E%cV$o_a| zhicV>ls1y{ zxghR%wQ%xqtmP>WUI}=v6+qK-`f`ARAJjn-=g!P9gZQ{iJ=Y&brYhp z6#k5eipw#<)lSIX4E9stq}Lkj2QV`-r~j55tXQ&L(eNo-LZoQ{-5*F^6F$xGv?CH* zDdSz=@Hk$x0WwvF88{<;P`RA(kM&Y}A5G^{F`M=1v&1B3ig|UqKaKl&vlaj06ESSB z859K-e3Q!<+n-I51})Xmy%MOJ)*6wqevJuxH*t90#24gvV$HUJAmvn!ab^sgNRwxM zmoZ@WDzGjJkh1;m;UR>QM|LK{}*^PSX!28HO0@4b6S?*A$*Ad>uolZ+Lecz3~@=Pd>X5WW=A0!5a^DLx<@Y@(N4 z2PCsdqTs{+ScwlVYof;hU9dLfu@8nTBicmZe4sa6Lj6{I&U_AXf1GPw3bC*q`&4Lt zz&g&G!SxK_1%tW_|1mZAXz)=f616M;6TCx7kn%s@2TQO$k_vdlgRLbWW2A z&>d1ezP#YAC5n}EzlwgqL2dUs9*s!r75dB}k#NaSQXo#gs9ddsD zbg(+qdf-1Air0Th;#HZ(htG`R2mlJ#mJa|5x;q7V49_DW3qizit#&TN=Kg+ALjz}H zV`K4x1-QOYubls`UF7JP{f}zH!T|50-V(csgLWDGdJrpn>l>{z+JKUBg>$O3!(z0|0 zSoX?9kw82T1H3hjYG-e~f%W4f$_+<_{_|r*qZfa<> zvC39TTl21g#;-Z1#CtQYk{Zo07kjUbYrZ^N{uoTmu3ODb?B^iS0)K)=Mb&WRkWe2=4xf9zRb_nsx@+_&W z;^XFJ^&RB~)+ssliNId5{~1%O#E<=PFV5XIE#AP$c9{&`g!%b-%$xOp|M2)+%Ein- z>)yb@G$5j8j$9XV|JI*WlR{~-tLQYn-$-0;9=w6<4Yk~tb%Fb{Is-+B91Sn z8VV~&lNR87mgp4eUP_}*|CSNb_>ux#O5ao1mPw!9mL7W4J2~gUw8d_)bn6)be%NGj)Lx= zW}^unj1V*(w6(3-<$=37CbpboD1?b2FjM6Y0Rr$NRoZ&^mo{KR66e2lg=3R~2G0NG zDA(j|XVu6Wjm)>Cm%IzYb$P~p;hZkyyyFpBcP*^3b0Q3aNuFycory=a*35y@6x*+< zTUGD@Mt5ro`=IH@#ecZ zU4pU=1XIK==9uFd(YM<*I;LTLUa)L*QQ35dS{$3@jntsY;9c7I3QktFz7zCb6ar0L zwJkI5e8gX$(W4-*eS5nLjQDCZO%EM_1nz7qPG<|zvS<5zPcVfk07N81L0yOw&XwIe zwuY7PHKKlec8HYbfjubiR3N*^qihixM`cq5x;~U@*(tgs7{xeWD@;>2IySktZ$YFH zdH8NKZ(Gw#4ej`srByXzQ99FUX)Jam8Ssyo`VJo>7zrBg++ zQP^R%9Bbd_xj1jBjvHxZfd$xbB450oy`>X{iYM0pbb{HGk1bCsa2lGLg^c~uqrkU9Wiy2j#aG_Et2_Tf^^R>4#y zu(-(QL1k$w$=DC#5?Ij@r=rh{BQ`NHsHv%G;OYA6s&{Rz;4qU*GL~c_6`(Fkj`O|) zL8IN7Y;<*?OM;05U^4OJ z%!lq2{_i4^IuU=6?q|8$ZjrX>ib}uz+hIWX2tBAUK%{uQ{1$y z&_augiwR-3YrHHr+Mix0J3r1D|Ha}BXSu-=7wP4e)}vy^?6Ij58`mP`y=ulxp=?1t z3ndV#0sKPjW+=kajnt9pBY5G);(SL`C{Z?R&~)O}3F!*_Wqw2Y6O2Ih`p#TvMfOxTA*XAG1@;3JZC(bExY+^4?ODLghO3p&}!{ z;fX&GvoY{*ICLb-(q(r^D(KA(M5-tyq5g8#HY(Nj{p{6WtzV*cUNR6Ud3PH=;uJe; zFJij&Pc=52%Z^r@*4-yee;Jjiaf zu$7CvR_U(@-X=^#vc9q7$2Di>%4=}cgp8VmYNg!gBQIl<(P}2BModhn@@~HLjhe)b zB*LOy_fSI)-vu9dCMr%3AH8Sqn4Tg4H@Z6XrJXhS0xh7rP3K&H{^|vdtwUnb6WTTm zSF8_vn?*016x_KVkDPexTlt(O^c=`6#)EGiy85>--YISdA0j-H|CvIc=mfI>=4=|P zo)Ya}Q#Xqs!LHeAy`T0yDfwYda}mUrrsgNdTBarq%M_V+TLz-zC%E13U{0zvSfldE z_~%!4qh~T*zC)w3I?FUaJSo%^t5RK0)Z~BmzB*HGEHYoTe>poQWN^wA?A+#Zbr2Qj z-e9~iE5Y&kBZ`L4T><`B_1g#aju1U2U`E}6jotk{wvN*V%TZZouvLPk%_XdV^&lfj zK|$aA5dM{y4pJ*yc*_%J!Lh8{#L0><0`;#s5ObLO)cUno+6bnU6RS2`jw-6 znifYjae@mZZ4JEMMIvRfJt@%A*8NB!NTA6cwGLIMu5p>+ix*srd-z^#T}U~9>+#{e zr^VLiT^-(~^Is#8pA4|tUSdIWdM8cb7epaJVA6rxJvnBF``a=_CNphA9FYq?8O*9S zCTm$p_&DajZaZ5i>uy8F_4jg7j0jM#hJuuP`TA3t!3{k8_FFvaMIX_z_Pua3VwwK2 zu9z>GWZ*~SrXOMgK;p1m3=i5FR5`8#?-^747##1^D4)_DI}h=UV&xB&-DUn2TTb}Q z?X1oP`Sg`UQGU|o{Mo+#P}Reut&v2$@(Rr+r`@9McI<|FD>IU+hHAE@8G1#)8l0O zHaUs(hiT{`o3?){w3-rm0gL4t$fSZqzE3v?b5(j>QUz7{StbYjU5`ugBFBM!R+=Er z8!nx^t!87H2wGzXp*j1+$(0Buvd=PUusdHM9*ExG@c$pT(k=RRP3&E-bF+ z+V>YgJr3Lb@f7fm9)UR`!L!vl1+PzKcDI+`n=DYLB&LK5>iPzna4;q^O(z!(+Ajmt zO5lEuw2yb{QQs^i-{c>0ep8Fc?wcpY2P&yK^<@oG1$#RNU1j|`QitKlJt?wG=BY1i zX|(wd;KJT*+l;FGe6$odnEm2}9yyCG(FRzUtG2dvdL;eG?xT)fIWHK*tyeJwa*dkV z?l>q`wCfp8b_)OszQ;GoQ^%D#baQj0)*zWqPqZktse%V>GhBZ6cRex1_*~1LP;l`m zTHMR)cOa(Je=r0CxoPX*>{i0c%Bq0POUT&B=yJt03%pINn4KLZ zu&L?jLVJ@fMkpjPKi;vi&E`7eMTpPN&VnVu8o%lN*9KHyB=>>VA31*)S-mD>o9o3s z=;=o6Mw!kLyZQ2&=X-@_gWJnl(}nZ>IU?mA#mkONG3J~8=w$+QXGg;1e?78!@FRoJ z($WGCH^;6zdwFA<44I;X_aV+A-g@^t00W7xL^=o9Eu!&U@x2u*F6j3+@{9k=*(GXw z{qD7a=1Rl);SPnrWZwKYC#3jEEjpLxbfY6p!1Lbj@zNkRE^cIGq-TAd7ytn9x}J~6 z$qQ;YG5daaHGVVj>Az?s; zV<{jZA;FvwW>&!6@dD*DL^E}*%jJ`=uFMJMBg(v7l*6s_J_-QRo~F? z90~x|we|wv2C*?Ba7h9dg&;nmpSWlj)VC^DX6K>lRLTrC#dZDb0@av5$`4%p!o^dGMu_*H<58J;tWwJdbQ`O(JrW#kIG5F$;VYl#)2I( z(bAK}@kxAf z^3306!O{u8CMaBKZhW_YQTBrb>fTjhJi%P&PI>sb&ZEI-bNgF=#;1>9i`l*pXuVu( zjC8X?tC9hDhEQS~N>R}az2!&XSoLbHObXFv+%;-}i zUfZ`O?WY{J7$8;gLx~2jS0j89T=Kg7h6%P1yc~l_Dn^2)pM@_EgeQ6Cskk=xwKx%N z(P#wgFDH-+>MTzTb_tjjmxQ5xK5R$;+h8yn|G~q8%wDia;c?v8(Tw~5rnUX=SV3HH zob^Ah-{=xxzq(aJ`J>zVLx3ABsR!A7wDQg;y9W$@B3zKce$E$|F2gZ{o1? z$bBvFjCD&6IRO2qNX7~-H#Zr8r{DwM2Q|!3!GP>hs8pE~uZA%S^A-v><6>6KQ<2<151^Ifm)PYT#LEyRa#Av+1c4I8Qvd1qY>7=Y3c?K zN%OT+n&LXMhW0Y|!qWElv23C|%?1lsR#U3UH~t`dt=^Q|EZpL+p$;Dwz=$?icY}uo zWGwbirfgJp`MozGqWK1Jwdz!7JO#|ldN;l3+_B_+hlm7B>a-w$-PaeRzy0tSVn5J5 zqgDf+6+IVJ=L?Hvtu0h15?5og>9`tHB9O`RR0lgAKyQCB5{4s`PTU`yb-z8NA9zi* zn0FqyPda8ENce=dkBacTRMaI9^o0;>@esXkqxU@1JC6;&#V-o1{B`clH}5 zOkD1i0EYLLd}8k-Y(HW7SY5b9=RpxHJ|H(1ZR#OTfS4{UGG6rFP-~s%3Scc%94qO{ zIXGy(R559a56yHxd9a!P$z->mX5STIfH@1>q=o3RawC`%H&)MnTDkI-->+~lR6lF& zvt?6leL7K3M)=ts+T^7OaP^TVEswLIf22*YZt{3eh`pb!D-|J@;%mvjBTp8TSXG6o z`S@p{e?#>v+5Za*08kYjO^86YR*!AR(Hys0FPXMMeA&q)>F-`h(1EAjip(pZC1}7I z^LpdJuS-+E`u80?OER!V-mTgG8TAGrXn?neNvC%71nY-%!Nb{2ay@yf0(h*j$eto?*4eM1y#{25tvBiwj z1fTOd8XVx&kzS#-#FD3HIlAx3wh%>zCc96%1ExHt3${eOQR-$^|Lm+wnfxl7Lij5( zhrY4aUXJ>jgajifsD=mFDxE$L0jYH#UG=vqgbo=k!x=O#2cedEVR(rdfy zIo}L=^U#`jLtJ9nXB3bqV{TKZ?QT+jY8N2xGLu-}c31dR0%yufOUCSt3Xta(!d8e> znwz?@d}=5c;0^V4c&AZ_G??fg_*c;pEdu1|6NemiyK*%W{v8Ve-#X~UsI`n zHYW!zHhOJ^-`Ydam9K|x@5C9g_?egqt%BC02LtVCXIh1p*C>8nEsN#QHA7De_O81D#ZQD=)|@Z?1WiG6e?ceA zsEmgJrsEF03HC!>a|D%z_<#BA{SN2r!cm4JRKdyZLTnqzh$(;2j$ZuT!QLETcY14x z$z9*G!r|>%QNnJZMVb@VB3a(^-D)1=O(~HoKX=b^W0b;id)R#U_g82>erDkvos=&J zLqtLjs5&NXv^R?VI?}7_YZRe{;3X!&Rcamtr0SCeYeb6{NG0fYWQ33x5ZvY~``g^= zEG2g1yyxjDP!^7|6_2sAc`>0duv;Wo^ZL{CUj(GazuTq~LI49E}sv>dY#->iqXa6{B65MzV?b8cWND z8v%C`{=ZJhrwI})$8#$8W7qu9I!M_ko7;+NzfR&4gDYow3wMpYHgA;Broz@V(t#U6 zlb$9K4Fe6dm;Nyd&!z&Kjc`T!D`Y~^I-ab#Dtl5Vk>g)1Pk2bdvfJ&hXeJ9y!lUh5 zA7o=U`M;)b;>|8+1bk%P#T)uq3xrnsz^{&_+{>4vU4-N+<|3IAG2^83i5@u%#d97k zmfK@2`s-CPrRhk@nYYW;X)Cf0HMZKG$I2yAeN0#@Ui^u0Y`&OLE_!nnyNvtyDMR=f z0nT?vr>iW!m`#bZMUpfs7LC8V{noW5y=K2uU1z^M>x`Ql^-jiE7poM&GCoh4EG?h^Q>T*as&i~Z@jzS{+P?3>~KjnEnC1WWp z{)@0(f-&+R!nPnQ+0%aQ1g zHjq|Gb1V?QD-_u;^*gQwpw4JXe$Vw z{qVg2StDw4a2=%c<(!X6yV+N&AooWgA~ZBKf7u?e-8~Knc+dFz7yiEzDh2_MTXb%S zkNRg4k5S)cXxO9 z;BLX)LvVL@ceen+-QC^YW%bLq_qnIL?>@Kt7Xt=s@GjQ#RMo6GYu0oD;0;oh`xck( zLWT(j!K&g&V%ZGa!wR48haDwldpRtf(>1F!dEMiGV}{sNM~=Hm372Dy~sVWb$41xRy8uB7oa!Anf{sY zT=_D64tz=;IYL*g0v;Y*d=WaE?k%U&s^IHz5ce|YBv&$aP!)?~XLuG^SeV0pI^62% zD(TswESJ|M*>P?3krCSH_N!n~-IMh7#oTAeUatu?2ICw-@lD;0qbZE9esA!7r0;)# zT&UI?;pO_aqwwuG$IZZp|3_7*x3{Nm30o0%2;bW^HDAVtgfPwVB znY+J4u1L2}7Z@;DWGKFhwHXFKWw;Y4 z>+SJ8K;#Q$%gF(Yr$Jx4%ZgWCF9u(I6upU~#-~xnO+r5f;!3TXS-#(cR>GK0B*4U> zNDU}G(jx%0+;#=E0l2=8B+)|vp5k(HU&hA9K>B&fRYk(*be_L5mV<&IFsjU)*`6Cf z124&`&BRa7Kq=u7BUIZNox)-zVQESI?$N)}WEV%L`?h$|5kqWuy(f)8!1Hd=4Qw-# zm6c6lGP|nifs%s8Y)(IA@yF!x{!CNYm&@pwWxHto;8Y^1Ke;Rm+=f^pG|C-nlanIS z|1D~TV-NEHy^M*8iFud@?Wx0`0L+WHxUhu_8fhJ(K!x%1_cvQYlL;?X9G{l*{g z4-gQHr=K%szlkG%LcsmAzP?^$09cH_(-=R0GI7w7k$u9&E6;3C23U!r$Nc~xmH@u@ zA0Z*RQ>Or1^j5K$fbw!0;FI&XTLcRE;(r324nHwye&ggM?J=qy_=oykfPcYzdyfj6 zC`2*uLV&LxKZLG87!|86qI}`}TCKOF{pbHQG#Vv=SN=Sm<4$o*8)?)Ho-Erow1fEP z72k!fyy3A>K#!?*F7Y=mkv3pATH5oO=&P!>%5XdHU4^eP-VsJpFNp?cIVu#FG$(%2 zI{o)IP=EMtx(FUAt|$@L&kX%R?62*-3+)tsr7d9=M%I-U!d|WRVZ6n|=BhwekbRG{ zQS_I(t$2|d`F!O{esBfY@YeW{VV&ULSAIDC0xD*s4)W_MN1LN%-r_ocxV!ppp<+G- z^2wyd4UM{Qqfpda1FQGV#e93`&u9qk%nyg%0p&OR8MjfTV2_utf+qcOJ z3jyu53(ZK7#KiF^CoZ?U()^!rC+9-byTi?fo55 znx@zI6s?X}BytE(W9;KLCraHbGAClhcCD5TZy2j+cg>ZllaklG-TQ6pe7|j2DBhOc z>qYSrGbJ}9?CkJxdIr(3=K^C*3mUu@;B20kb5s(u8z-vK8ykASxgl4a_z*aSpZUA% z@YwGIg(XR}y%CWhP6BadAUdO_Gi68DM<4{r-srbmKD5u_Qr zR;E0#?Fpm~<5!kwtJ^XiF5YyvC_0$RS7Sb2@AL^-30RBTlsIMdW@BieDKy_*e@;oD z^7FJ-EL$C#vbX=}oMCR~n~M%b@TOJ_p~C6yy@W^~AF#bK?T3nOw@T`V3LHH5F)5p?&U7FC zgl5lu9*Sa)vp(KGbKfv7FA?P_P)((jw0=eGE(P+cGk1=6vXx|nhW6D^(#Np}8&9l> ze<=BKa`}rPzmVQc(PoZC(&)5_U5l0{3?s5 z?cVk1$AdaI&U=ku{lr6H&>D;wR;%6fV(`LrD^LWHoiz1oIR+C)w5Av*GZ1R?yvPSR z-{DUAJvHbtSlwaNPPP}RAz{o>ABe6;hYncSj4obJt~5XUd_q*P9k-F?F~Py-mFOK2 zx)#`?J21bei%1y>Au5ax4g7L)(e_kvSs@j5Z4g1g9!z@*CmKT8kz zh3l4#&7N{}z~GRLvjMKa9Nt)k7PWjOohBtnYMCL?7(tyG5Azq$q&*&*Qi7I{eF58{ z6^-XpJj3N2(tR4aXQEL~*L(hi8` zyZ9VPoE?Lj*5-5#Px4kcr6^~7ct7}YB$io~cFOGC!E5JLb(M(Z zFzHofw)_nJ$0F!7JB$9mEe&EY$^SEAb(p&^B<+>h8vSexugT{-2kGL$j5JRgemU9{ z-A$5uMRFEIXDqGdCDFW`CC1T{-5DdlxYSX73QH#n@51IguVBw8H4E`x=DC)2W4=Zlm$kM2aj25`Twp9vVf$a-jugOk3BE9`|b&}rXy_@_emz@s~v_pG$WV>NmaM7Pe<=PFO$AJu<( zy(KtMxQ9hg_q-%kW^l-g3jPF%Hxia{C;ARkZ+Kp1Kv|X6>y{ANp}646epOInp)c;{LU|!a#8bEH%oJ;)g|* zaQC2uDy)Qs$*Z~}XVg&XX3eBA#)da`Z9AyHrq9DORO;!sKPlz2{0!~*^)n4@H#NY>{herIz88pGUL;!5+HU31hqGL)JT85p1zeZV1VwmZeX zQS2|?PJ=7yhb~Mo@uqwd-??K3&&N@Alm0fbhUBmc?<8|F`YS!4f8F|rN57kHt{xAO8NCZwsm>Nss z6${7N(ds~9(|E#wr`8B-62TsnL54>NbB`Ni*07g3;%my{t5!7a>z@rCZd2XwQA9nS z^4WhX3}J&tEFw$GQ~t(EVy*0Z2Q(+_ZSYmzd_i+HW$^yg12OwGIjS)0X%N+K+=ze? zGbeZ9QIpcqxH4Orkolg@+HmC$50e7g){0+BQs-OaJ1@6}Jjfe7GP2R-A2y!iOqf_Y zOpAkKUWawzaf@R?r~0n~i=lwfWQe&8v~zBB*~rzq^v4mGt1{O*nJl>RhPcS>^Bd*Y z1%FO=Pt1Dem|&|EJ$u%mWj9I6PpY{d;#9;EUoN`oNk*>SwzsculH6#eFo#S2%I)E% z@Vk>i7YS7L6Ai^>^yNvnt3SIwHN?atDqE<^@Y4EhQi73MgDaIPA;F_v$}SEcjf04r zlr4@>75K!UksB)u3?9I(hdbCL^^Wi)6wk?wK0d_U97`+_gl+NY$RgLkSTyE5JQ%v< zT?t&xJJ`uP(Q6jklvMSw62}bzbs)v(=V8vz8n=w13Kk0Nv1Baog#^dsNv2>!!^KU_ zpuJ5JZ}M?JzT)9hJ%}2L{SXt@eJ1CpK89tv<$$U;kM~imYg(Exl|KW4@JfB&YP)m} z_{^K`_pE}E8Ymu*IdeA2Z`Kz_NG`GLb~{Y=)nEMZGS+8J+o(`>UXr#&$D(8J1*NpK zs`qK_oHJQE_q)5gKCoZnLqqv6RoLK25C7(ATGTW!Iu~4Trx>7!6sK+k+Uq>ANp?@*l};@??!dx`IUf zp}09-r@2XHu$g1Je84Ak(_}*Xw%IlFa2y%~P?{YeS6`(wPic*i`cr?a=d1Wz{`tCw z0SvJbk;Hh*{O!M9l~N3HrVZj&#q6gzSjL#AH+XBsyqRZrdO?_Dc4urd`$FR3L4K%< zS(@e*t3bQr*NyqSE$@|iFkYX}xPY0cEHSgCSwfz+CinnoPV>^2C57tHI~6i)ZXTo0 zPUK~dBqpp)$x1#wY;CIs{h&SC7hjoyQ^b!+x+$6b^tPM?G=+JHx9&5molZ9RP02At zBT2_fV1r{2CmGAh{6{|-c=u&-|^$JYh%)3^uF8)9%l@%AQ!n z*v%ijnd3$2x$;M;aXK;2??|dy#rL*O_jjpIUdc1=>0vwYhG2%>7RYo+7h7o@ulJaY z-xF}G*jrx`Q^-PP$JW`&V%*6Tq>sju#>~{*Hyw;|yVFb1cTCtL8J*Dqe263rmB31Z zfuyA6tqmkTLW}LGWZE;P)B@>jP(CM@O49ZTN_Q4otf?L((A|jKnTT?2_0kjSoP@LB zNOg&4Br%6KIL`C>n9|-{3nAxrZ#a10c);%T1s;8kNI4mn%H8AzyIJqUznbw)3!bFu z=3@f8a$zdd7K&u&p}Q}M^g!R+LyY*o#;b;Um`gj#=m)J9(caT2E*dHhPAD)uLaBUr zj{*o_1A>A&tVclYKYH1oZ|701RvxrPzrDkVLIhkkK0Up!SPte+|DTl$)vtg2Q{`nc z3l3T%-W%v&*1k+`0^Kvx2{jWszKb*|6S`8*u~C3acjd;M=3PTeYlAg z(n{aLfmQPSg)-?2o!+2YM_{We5hW$%^k2lo-0#A|!t_>4b<`5|SsK7`T3!5$$O(Gu zH({VpRjDTHO+=@8nP6kqGk(x1n61Y6hqHK?2invM3JS;uePQ~*vO+*xVGnGC&%JY> zb!w)p&+>Knz+1T@;?dX76NF=_R!^XvoZxX*9FT`L!^r$z9AsKu9jur?&E6JfS<#MM zHK71(a|DRS|BRUEg=wK~X`qK}d8iRXp=adx-Z24}w&2K0NseIHl znP1;X!V3v!%~L|sI3N|UoW-ShH_wLXyerbY7+6F^f{mG2LEa~t zG$IPbUr(oSho$%qI~#Tvh}k*2L=EufV*@Doa2hyWo4=$-&Xzy(x?koJ0@<({xpQ-! zf;oSwF;{8GTE+4gX?sQae)p2H&~AmW8d0HC%HwUCE>kr8kkg1JPgD@vhoXfYi@jUK zjk_S`6YsJDrCABJ)z4%vzwyPkA3FR8RQ6WF7REE(zMhi1f5YEUtY?s!BHH>9E60{d zT4#?X5l1Oop1^#e04l@~08a7)V#rRWAR48T9w1FBn(Z^{KWR`zw-)Y~fcchC@r_$G zQ?K{8;sWcTSh-Z;f%M+ZC9ha}vyTRg1|VP4D96%)K!|?2KyO4g9HE@~Mm&$@bQ<29 z#oK?@eqa2g?Cb$r=$Af={Vy#*?;0D{>Z0~Z2#vrfcA&h3YteimClA^4_PJ{4nIelF zDSzfQED>;1J%C0nYfOGViC_?%{=r1Hn!5Vt{=UhK*P?ZyZT4Xzd^JZ)oDtcy3vP2j zyz1|X3dQfqvg~vQ-+fBd=veSLyFyT86BJDzws(H;I7j_yV{oKOwtd)7U+HLx#hZsH zo^1f1g~i?6*S6DI>Ij##t}i;x{XlG4Dz!6_PmUhgY`@pK7k5$C*GLxQ;1c+bOArHr zOXs4oT&Y&QRqF^i4|lJx6U0+qHH+uAjl* zd}ki6$WX&gYMNx}?M%pl+Y%kKGW;|s+m8WIu7=4;u=Br~y%k3}CE{i-#8;F+4a3E-HF#f&%~lk750HY)^{3vZ?@R zAO~RUY2sYzthq*mrTAK#>pH*EKY!2bfjkzJ%xF?1p9=-$5ANR;^#(%}m6S9f%lj$> zoS6(Os$mA0K)*KE>m0dXL0<^d&t?Q#BANwG7Y&LGsDe0=KW=Vc$s2Q~%K%`Vh?X`2 z0O&t{{P-0SLCVhV+4e-E*-+(rZT!BrIe|t~t;2)8^W`cOiG+9S>3n&?YisSg>nGUH z{)d7vJjf-Ros6{Ej`J9)sol>FCp`WBAj8f^{=K^vm7PYa{)gC>MlYt8_q_B zHN9ljJ%yghPuRTbwtYWOH;j-(Lj2vdsCU&z8G^`uXN7hWUoZpOeCwp9 ziXWiAHDfR*yJR2YsBB$d*8g!F6l{W&Hp)Aa(qy>DM~H|B!;ut{9Sh0tQphu847v%Z zG*NM(L{wx@>7Dl89U_JpHz|)bg3K~H+a$29W;EGOYGLQhs`;)@^$q%YKAJavDDW{; z(dI~4iD371@i?lgj4K5%e%%qbQg(C3CwUWo%@OlG$LfyqGBCu1Okjqk)c}jiQ#FOQfPg&!dJ6@aWY>{5;-Q1P_G;E zCa6@3qO$ibR9D=yCO!?b_k}k5VYjxMIuT-R_PJ`WI~E6lJ%if-TXAg}l1dRiWhLUH zmqWl!pJj61FMTG0$6sqWeJFXOUA>a6eFgmW6nk+v;o{aOF!A}I%5hD2h5LKrP6dG& z;yPvwJ5{LHWUQHMr#^*Jk=W&sAN5dGmrJ47k46my|A8s~Qv~(6LvCDG7GT4pIl_cJ za^*5|A-Dp|M7NeNu{ahwWI{P> ztd->JHbht@#xGSJoDnATx&&7WokGN6nN_muLKX&S$>S_$tG`FVvh#<{-wDCWhZ9f4 zJv(Tf)*I_e<&wCJv6%`~*xWzLxzFglL5XSbb5HNnu>V8DOeTJ~LpPl@m$HJnQg6k= zm2siV#Dn&`Kyp1df6K_o2*Y8G0C@lQsrQA1d^7b`X=}!o6>=bX5&cik& zWxf!2u$I_jLqDY*Xr0pQWG@gInz8=_`C~uV=YOtW5ou ztL;7(p|Dq5!4{r8RhhcMqd%Tn)CgC3{+4+`m|Yto zjoF;~T*qqmB;HGI9waTzWK@t^ZYlJ+W3gR&dOtB+L>MWtd2+>7A~5fAwR&;*P+B74 zr0j`ae+^mbNO0jP3VWPdJ?Y3QOp8RGurqgNgMK`gU)6-3#2T7V(g&KzSY?Uec&Z5j zllFT=8g-wAVpsDeUSkD0BVtOY6}(C;5CLa*vm;XuC5|3{!R3b>|3)PK@&>DuSezUUS;FW}R&Dwxl%fBN<(7Y$ zc+vt|PEq9eb?ANM{^tKl^;UDZYa04du~DLTe^8=hRMykoKI_U7fz@6lS^@!6EG(R8 zaVC6R!2iNoi7#YImPb@=G$Jk z{tEv;>k+;_-xL$;HoFBtam(7-+iDBgmv8S|sbZZdV&n zwC};NIuIdG`d@lyz$pIGsn9dNp*>TaT);!;+k-jcs;-%1FIP+^9V zC7<;_MOnhiE|~)%bC4$e6ZL&tr!y*qQ@s96lE%)U-B$^i#sgWZXS|;mw}o~f_LHWU zuc5{#`}n$Q!+%74U7DBljZUR{?fS(fy`-+FoMyCn#)|U{@9ru57GtlcHRcTlt?=ks z4Rl(`S`G1r_Gd@go6V@avG}~b7*pwXbM>cvs4cGT71#uq!#2$)8mS57K5Xwz4V^5+ z7puz%o=oPhc%-95NrNBWU(**LHs6QH~Ukkj_kN8Z~TsExyQ zhi~mYx^APq?8=cJz7J$g4<8s|`SbUE9nL$P0tMU{gW{BWN-f?Nc~QWo`VsiFGom*g z%=D7&ydlwPN!3r{yWfncn%(Zf@m8b`!F<5AOAwYg021675=WB& zMiz1dA!PGok2a^Xo|qDvBfVKeJe&%r{G+GaG`g9v!2DWrc^Sj`jffGcvhf;MeN>P3 zxhJwbvi0_~LHO7JfnvUI;dOP1_fmy|g^6J)Q%}lD=F9_7aOYjiXg~?vwzj;3$S(UN zo6mbaPb5xx_L45}(}RJcMHR%NOhIx+OkxtdE=|uE*ohLOBj2jLad7sAZM{L@_U@A*yr8A3XBT| z#6yUU1}yDgpd)mY<@5){mI9I>7-)6w=$JkkHDnI0B4(}t0Efue0|eVWlGGGts8bJ- z*{ZY~Y((`-+c^XoZ)qd(P_|fVs-o+sdX&VqBctij3mr~1z9^C_6J)AH??CCsV0gyn z;AnP0aXUo9)91IQIH=^+up*dkZJ{5%z7Q)+aeq(SEfoQZK11;DK$>IwzC9`t(4Zz^ZYlYcliZmU zJsmndE88`yCRxIK)7LLNKIOVzHPsBQGbgcCxzck{R+@}mIdb>hhTh(JlRcHk!o-9p zl2{U0E!Eo7JB&@~SS-2etq8#iohQg?vln*UCG1FIT=#Rl4fJQbC+xUAY8hP6Oz~?% zt;vt+${(~Qzfr5`b8ZR4d)5)RIfa#fYk)>KAA6E;wud)pyG(tVQn?neooa4_Kbt$2 zi@nv{7N1rnxvsiLd&@y^QQv5B;DBBLd4b5aHGI;7JzIFE5`B#@JrnDF^^GkI>Kn#9 zz@==`02OPeK=vO!F`I5#aYjAkm{&82n7_G7+AM-EDT)?19xdx9{WmJJST-q%3c9p; zc4&0x~hU-OqdMV|}2)Ig=R!@vLGqikpBZbH0#Ecbj& z0>`LR(1S_^{1Vm~uH`-jMVboKD>=X@;r?=-?ts%}jt}TiJk)W35qE=cE<3fOL;KzS zfv=ll`jzs_cYDrdD=2!8w=Wtp;i4u-e490^7pFILvAhy(%g)(Tf5+0yX9D|VlGh^+ z$E=Ko1C`E>gHX0OUl!e@d(WHd8v8@ju^CCChi#*cUNP+UA_Dwv;Dc;Zx_x2}BaLQ! zS04&S`Jp0k21;6@;cm*hc5W3X?~}VXjISRwS$da>!HlR9|HvonWC+H(zP#M4dfcw6 zX;8NZi~H7~s!;M}d+>731JGpfA81lTef^U^A*9(hJn5LVcAeAz-vpc69@c*mY-#0y z?a0;%*1#JM`U2-NR{MHS@F41t!BARn4l7_4<|^{%EzwoHVv^{fD# zo%(QjzT?1P6g&_bT%69=qgQ z4JnE(DIT8AKNycE9UGdB7WDT;rkmnI%D@+(OzJ)1(5eDQdK8!)@Xzk5s3PdQ*K=_m zNo&7w@KO~8*;d59>+-(EfGi}Whdp3$!ZoxM-t}a!qztnb3vbT=>GZ%pJ&t}?DPCT4 z2C{p1-tp7px_q)j$UnLXQ%kv>=_X1Pj)@_KGR9Z~V~;ppuOqdbgWfKX0JOc|V}QOm zllQP)MK7t*Y?}U&f&7G7rulZGA+NmTnv6_GAxw#UAv%&{gO4CciE7 zHn4mhH|@B2vXIpT3>+?az5q`^J;LLU_!3H#gHdCvxnVtcQ@?oOI zV=!Z8zc=sfT-?j(X{K%|CA5hO;)>fVbv8so_)4!}G`v<=y;vY^NQ+SBJ-Ek?|yjvN}V3YMf|=A=c}FH??K zCIsB=md+2ZdX5tAO?v5){!4#x3xCvORc%sYbui$kYf5*vyrI^O2CCyb`*C`XUv}~q zYw`m3{(Z7ZPpB0J4)eQ@Xe561&qD<`aaJ|vI{Z)!8oi5+t{M1&@g_RI!}&^r?Y?lv zmX%MfCbbX7pW8VS3q>MjT+%fM+Fm1T)-MTW-uxHrj+hE%GxrwKg4867(=wDIC%oLN ztU3MRc`J>T;)xR)Dx_ND8^0H|K^O0I_w;;XyCv4;`HxN2{DAI9Mh>sqB%0@Mi|zJc z!gQXZsdR}*R$x0qGM3BT6s;`O3pJsuIQxt>UPy6ywm+q;%p+R^bUX7;7HT8(Nh&U^ zYWJi%vpy;FbFIX$taQZDsMheDCyqy|_Cxp}--F6`|Gtj{d8R4j!59+As-PP0jOFvm zcuD;(`xi0#9I_hiuFgyP>meURWck#5lM4IDgYoU&j^0KT-R31;mvyW#^_f7*Vm1X! zHbVcGx@2&PzNHeY@l_wUW#%;U=v>9jacy{+dpywbd~x4W?!=8EhHifwq_g&aAB6?{ z&fQ6+lKucatb>JYZfk36a#R>f)e1|kYJZ}#vsVkLyrN8Mg=xQyClq<9`O zS%kj8_z~Po@}p}Hk=9R|4^CI-Y|e-#yHS5`LX0RAdtZVu%KJyR4X5SfN;IHLn>Pb= zCs7W}HvVtjz@RI$Ci0yy znMSaiUa?E>BX}DnJ_R>EN~-|s?WOBmPlgqj?EXglBtl>xeyJ!B= z=JA!#`0#SPwfR%!q{RYnE~(?%+?N3$hh7Pd@&=R2q&-;n6#&!2m$Rz6cIRu{U~`qa zFSMKtKVa`f0WSvaI#;JcIg}mS9sYhIv;|f;&@Q zriP?R0va_jhb@ELKqVWUuz9S?!iE~^mEGyQU3RvzW&63G_O5U6VC?LNtR<599C;YB zi-$f91PtROskFlSpY=ya4yu`vc(_oXd%S^2Db+wE)mGRwx*5Y|f@ zRmAVf<)$5#&?O$q{{eql$|xp8lSm$oeKxU_>pLn7SmGcU4|+-*8BjfQfQoxg(`h%J z&eD?QfJ5AzdXY#*mAJbUQ`g2I+NLl5o0J|~WL?oUG8FAm;gm!%%{%oke%W;bSa(Yn zPgKbgQvPZ|zZH)m5U2qO<&PglkIAQ8hLNfg6wSMB)f5LS`iUMb3YhMT6nm@G-}vJT z_+S}5sn;5hhS8C;$BSQ+`z%Jnteg6q{n{SFAg7s;nL2f~z0zXy})tltJa0!u3u} zxFFf%Q$!$FZ~*fSI}QB0!QfDPA<4M9{A9C zLx5^wQ^_ATF(bXp>{!9F;*(WgGwIU_zPB6~ z8>Pk%oW;%FuW*-Vr)DUozIj!ok>!8We-SLY^hJvBG+-j707erH04?_JRRFZ$f9wv$ zqta-^^#mi5rTwgKaKzy?zC^N|ELRU6J1;A|ZUW<e^0kXa3g2YE~XWnDJB`Bh@|GoZcTgiT_`JxA8^K>F&9SV%|{I{;omD{FLc&C z*+~2uIJIoV`g`#xXv)rvpI!_RIPBEZsHnXXTfb8sZZPQFo@{?g8;RCzXM11xltdGD zq=?IGXy@fw8`7Vqk-IOvN9>*NESuor9hzbAX;N>K zTOq!=s>ZpmGFs9NHWUffRkP-2WK6U_DSi8}`44=`D*M~~$%UXgggU+$TvINW&o~`P zB9S54GwLdcibTUevG0O5*j|=NJ-1gUcY45_6F|UY$hph@a zU8sft=*a%`?pgyT>}aFpq$EsW4A8zVyi4yZ1qHN;$v*D>a4!ks*jR&D@@p1gZQ}gK zKH2JQ111uQ|2k3=1dsC}iyS6~nEOrfAAN)}P{hpd3}ORwtU$&X{`b~d#Q)kl>x(r0 zqARcAHdpC*Shp4RZU%PFf>f;2H7DpjWxTaVoj3|=Bds4o^%!P=K)-#*;|yoP|3!xg=|y*n z6(`c3{_PQ^LZ`zkxEUw1tryq#vRfv>itTUx%zX5cr_;?CLADzneLmuJKZ6}19ECsc?!Fq~;`LDJ*P5MlDr$P_BJR zvmS-CycI3qRBHxS&yzfsJ+GiY2tJ6+YD3V*ee&Ja%En;Lz|2#TSp2D9RIuZ$)pgf> zL6v*2QiznLhOojI8*o*n49Ax&{P59pCORY)w6lq`4j|5Eey(e8=Q4u+%QqhIqOj*%d8*Ky?OV!RkU6K6w zQHT+Y9Zo_uV?DWlDrCoQtf9bQ2X9rU%^t5Vg&$T(@{-T5Y-|Dju>aBmB$CfMeqIl7 zHAr{zuMPGRG_Z>0WR`IxT%w7{S;Z04&@3YxHfGv64|yP#(t>zn1T{}tuYc`QivS$I z0RWm7NJ5NTpc~05hH0b&K&^MN35UfHFnLP3xu++d zzVRaD)#)>S^a)9WnpdZR;q~cun1%a#!g$76`p5MY4KdH6+*e)w)tYup3D$iSU1rS6 z+WpWur90=|p&6LQt=q@-NL8JMZ&6SCZb4pJer+mlBPXy5*`rE#I^H$nvtlb_;&m_- zKJCf)4(^D4&(?(E^cTxtb#LDML%iA`APW29gs8;DVj?y|$QGt1(X_L@Uao|8H}0k) ztC`CCRxCnr7aZemvergYmw+WMJUJ@zIP{30 z5aN#fJdm=oy@f8gE7D$Z{XsK06soW*_!-(2a8Rb8v)GAcEIvN}U9S^5)*bi_pd;V5 zP(DeC?`)jV20XIsSFrZXwX>Zj=!~UR9cK2wP>b+2-*bk#%@Y4v#BFaz@tSS9Jl)*s zBtXm)Vytx~7rtIJD45pY+YqhHB>1Mg-rLm2-=vwE#aK(`9dbwAdH44=%l>br7W+^_ zrO>UL6;^{OO^+Y)B7+S)hEeixs3yvRb#SsuaB?o9ax2ZwjQ@z0!%ym3-pcnHHiaug zSlrVVLpVV^tTSr)(X}w#RMFRXH05%m3j$cB4M;DkhJ)sex}4V;^t(TfWjy=;7G6DE z&4=Iaj~wUW_k`47r5RwYO{_UIHqc-;RC{{wT zg>IL0iRST!MhNrmnEs+z90e;UNN<_LIBE19jlakd>F;TM?r+al6FD>NS0^%pnBk+G zd`5`TX`(_)D{tD}{#~Po2kXRaAe4mDQWnDuZ7|hg=3xjEvy|Y$5w)#yWmfO>g3gsj zaV%)}3lvSy-72r@w0&=5@xzL1{6u6Et_`WHsnROH~7fy)AF#Mh8eSL}6fy!k>gE=!Ki*LAummeiX5V8e{Bt0T!zp8z@&w)~G z-&4(-#UC1RG_s4fu0Hgpc`ygL;!|eJ;!SY$Q#F6{+3JF z+9&utWmTIo%O_M-We&1JAvsSMYP4tRAHqh?N{zIH7>@kHmgxN}DD@uE=P4@r*U>+2 z(yM-d-xs>`Vve((9lO{_w7R*NCcJy}(dJK@_QMv@}#n zaU3OblHBUTUhK2aWuTg@uU{e1{2HYs94HxL441r&?(9y}7%9roBulo`oVfLek9UTh zEnzWTwY1EE@N+j#&g9|fgy}7LO;~b1UJbRwwSboO{&6~xBSj4Q6xGxd%w|i_td<*$ zw*H0yo6INPrW;&bT!0nnMGE;62nsU_HC8whG6bVrj@5MsJ3%l+CaSbVOF8JF*iBzo zwZ~_$3dxzb;HH<1m^u?E3T#~@xmC(Q{uvM+Z_x$O4(s6ti>J26AcoimTI4SxMwy@D zXqnRoaolQa#IZ}s#x^5=fVLlU#xK1}JUL45K0>4Pe?UceXr<7E4$mriG-t7C{*&b+ zPy}!CizA9}&0Lv0kEP4zuRW=*)nJva4Lam}zH%$VPgC^Y!Hcnj8k=VXd_IrsuDq|S z#B;^VRj!kKB`M%>Kh9>;AHvnU){>c_BQtt;JY5eRZ1FQ8&3)|S((Hn)2&vRvT~NDr z8G_XtptCeiDL--#Ri!ESs)TD6rv#{0e=PZu!wYPz)LcMj4BE(nF3Vs`t@VNk(P8-Y zO~XeC8N>8}^72q=>h7+I*uBWi6z-Bv? zBG~r0BT+ebILn)%>!vKy^@&cG-YYd>&q9U1B7zxNj`?q(rZCTsshicGX?O|A5h)(K zN60!94(0~Cr0cz8x%M=|F7Z>S69ShpATD$m5r1$&4a!D?aa+Ada?%sXPTx&bCI30z zw7$3GQYZ`(z_@=2|JNR^*MgxlH3Z3+p@WWviJcQr9y-)m-lDnouwqH2-M9=C zrKI2h2UjveLU12ui@EO>bJPV=$uZkEGl3ctJW9PC14b`qAAwBZatWP=U0;|`9Vo)>zR}%z*VHCA}UwhvMF>8)03Mm7F!7o10~$L9U3r_qW+xBl<6FR0mY3z1;2rUg|$p5X&8 z82avKDvO~}qTuG6wk=77nbYZXpY2Q(R5d^{$ZE@QNI+FsmKzw3ULFD&k&$o8^oaQT zMsuu%kYqAuY?sEsREHi6kxbJv?ZZJU6&lGcVevS7vMk=P<#?&-6GlMeY3CH#VLDJ# z^RIV!0%Q783B!QmB)qWDWDG^Ad9vxaAI<`EuzQ;uEA53_5_D5Ax;2yp4kgSVT^5qm z9Bdb#Vab&^v9u=$%eAbpGpMz#jwNYmDD0aiC2+IiSXR82gYR^!T6Lr)yF{=gQK!uO zl;Ft_S6oGjDUrIFU3WMgEBS1=Se2dP=gK*zdRR+z1Y{&!q>-*`x2!oc&e#U z8mtOzsz)q_h~uhxWebAx5g2hyu9`W2Bs>=Vb+LvT#g^I7nWh*?){1C*GGy`82}Pn? z+Ewglc)phCrb3tg5}^9c4@8B@X8RQ%A77o;Vk&P?vd{!=Eq+c1?ZNAgk}D?Bu6E_~ z5~Oh&wsaTY2kJ8by=uivZd}G_8^r%L!0pJ&>5hu7D=~*AZ+c|swl<$eh0FWp ziY(6=8Kc1cK;R5g$8$g%Baw)jZ;DBOKAUJ$*;BlF?yR|<4_*jHBLl&X6PewbrA-QQD)b0K=GhNQhoYuV=SIJ} zdMcIwU);TQP+VWTE=UN$3GN!)U4n<;?hpv>?(XjH?(Xi;xHS^o-QC@8=l7lO+;e8` zOifMQs;Qbks4i%>^xkjpcdchV5^H#s1t97`AbvdfVP;0{et(+lc6SVxlAb=(=6Hg) zhQ1#{A2P8vdZYX?aT_;Y0_Ygna28c*JX~Y*`7=`axafeTS%%)r^+ta1{s(!P%C2`josqGKTDbMWdv!mMOdgntj(Jhd{^VZ!9 z19xft8=N8@ZDP$Ob&6sZZDPMe0^{rVlp=ebHR7*<4Mh#%Ba#K6#ZVwh4?h$Joq9lc zIGkiMeIaPtj>qE?1441+E7jRRK9_;P!B7|&7$BsF(EHVw7MQ{990k(M8>kh5ru<8% z0)e8ybyhspXfh|>LuKH8D50UEpQx2#`5IA>H%q|&3<^`qey&{VB;_&_$)h>YYw%D7 z3hTQU5s)|!>+prizL`N+2*3ny{>m1LqZ+n=Ggvh8MrjU7q>Ia!d3KV4&3OE~&6~&1 z9fuoM<%N*!@I(q3*;3N9Ca(99_%ud0I!oGwGLOv18)c ziU=7xoIBjR29q!PPE|}wSAqxE2(}E%jUOQbj@VHYe(g)8Gw^#8B!Lg_)28Hao4q7!)vog7Ie)VYS~kdh~V!x z$)M392!GN-qz)FRlxRoK{G8 z2NW?y>_dYiiQSM^yR1Ux*GBeQ<7G3>4xTa*1l_}gC$&e4#T*M|B+%drCMz;w776kO z*uw0@KxPVOtDWs77KTJQkn;~HFNL!W7vx?`&cpMneDgXloz5P)-s#R_vB(ILT-bo9 zx~r>r6ciMB`T0y790wq`*~h0RTac@gf!g58O1k+%mF?5DAqKrh%8IayeZ)a3o`N5G zqxaUrw~tI;ORZ28V20TjtnH>a^H@i_MR{2e6Mi5HpZoIm)?<~5hg(EnWGpf?^cy85 zrRWMsp%NDtXXE5FVcVslalLtJ5uUJ=Ef!bs@Y4M3c(lg7!&U`aIpD9a0AW^Olwp3P z;?W--fI^$S2gOz8Lfh^3E~&Puh(Jv^fHS7z@>Sv(U)ca42iGahK+h{*jxAxe?ONUyMm1j8pECS zFaFDVi@@H&fs~dugIE}x(3|4?Us4|4qA3&5Maa<+V4zll7RZ+eWcPTFr?G*|hj?x} zRmuxN4mZ2w=^U7L|K#gj1U)c6X7jklMe{vFt0l!6Vw2hbngtmJ*E^l5AJ135xM+ex zaZ8mzn_wnVrxz2A;^&bR*Ql(e$kT1yEG!2+q}ydy>Oa>`S21ij(2!Rd3OsgqBu~B~ zKz@ew_dQvtMkOSa)zHAJt*tF6Fc^F4vfUB!dfbBg`@?RvI-DmQ{s{7_s+axMIU~cQsa&BMy1&iD+H(rIV{E(C~QqXR=RGE+(Tl-rSAuWiAxWG4!$05tP%bX;(lVY4{h&*4Y124iBc=L{x_xkz7) zxEzYuTb>~l-Dl~~dH4*cJZ8u;x;@xaQV)6nB7`a#(ykdpG$${L6pOgVG`#AlG^^&` z<4+bwU)i(N#EOr}F74|2h02Ep>&bvoQpI`e8R{ErkL{(JUBk)fcZ=+5!gU_LrQh5# zxGYEzNQ#G&geVL%4u%LdP02Gxtd{js0ZER9X0{9&70gvkq8DKeX^$+bAj|Z^y4FhG zX9<>;*Fz7Q=Etfcf*BDS*GH4amtwVhSBQbt3dX54ovlLw9TRurNyA;L_LDzc+DMUu z=R{gk>lDzf$C>Rn4|jKlua8%xq&&Pm&7GaR{*ZeXzfwgfUj+mz{q()bjA>)Co_DBl z8Uu_8Zt$dStzAq+HI#E?so+`Gsy67R+LdxqNyv^NN4Sjis!}jyNXn# z7l)EA`Hj05EUD--*Y?gEtZs;vvQWjS6_$I?+i7`r$@TK>oXOUVlKV=7%zHdEL3c(! zk~?P!p831Z5275rVEkWhb1GHUyl}P95UBAaS@nlkn_5=PTRnN=dOW$NCOXleAfIz( z{_hYV>V@kD!cLzqD|RssFI^RYZ^QBNc&c>vcA1~MJjk}_hGyCf(Qv=5u0^bQ@fLvL z(fGlGm?&4VdoyN*HqniX9P#ojDv|oubDi61@>UB&AUcR@L5%8s3FXzc4GamihpuI@ z0Uio;SrkpOX|47xuRTC#H$}*XtH;?%3T_cQy`nSvjPPIVS+xiK`XsTf<%Bnfa&2l@ z(efe$YX<9}J~GvYC=a%GPw>7_fa(64t~kV!o=IYV(l3)|1;K1|r6G}0Xk)nH9D%Qv zUQ?d_1<;&ERO?vjNjfm zkc$7TjFT&`{|FW57^bw78Qe>*sap1r)$E)46cDImKOS79J$_&^WD8+B>k`P`Lt}ro z83!vbX?}B3tr`P#y*zl>`DIs6JmWN(FUg0VvuSTdUAD(bt!{)-Ve^1Uv>DpEFjJ>7 zo*q*p0bxp1aEZWPeI6|jFr0M$~tjz7LgLBPrFB=VnEhNkf{=-5c(nj-PgJ z#4PW_j&QTr%2G`hn0*zK{o>7NOZh_=>PM8mBQVrr-mAARaE&UXFZ2tkIsZ>{72vS_ zqG$qBwb)fG>aTeKtfq!`9$xA+;<(-_hDn11{tV7C$tRJQ&x@sB4dW5Dspm@4Vxvd- zR#(xxOQhvjt>-B9VNF1*6m8B`ON8%LV4!XZaM%ovFn&KeI?ACeA%&@Yej zY4XJhvC|+PlS7h(qng5iowIy+=QMztH?*J~wjg_d_yV!DvkJYc=pQ&qQFYnU&F9HT1)FrKV8*^TSG0U>-DePRT(02NU?+KBqr8sET7w^h{_z4TU> zTwIqeLE3B0Q7-Sw2HN!pyA0!{Kj)Kw(pTgtjk5 zFRJCqoX%H05Q14)I+rIfXaX^f$W-PfxxeJ7zx=>LwNd1qqy88ZL2*R%*- z_>(0x$-`J~*Ij&|ite5fc*i=d&vG-9v}AL2AaKNL#k#9<|p&}m>ACB6hXOxLSRiG<_CL7o9#=l+9FoEpVWaC zO8R;TwfGMC#}7AHi1Slf-sqpk3&%FC!=eG0qZyreVy7}*!O0&~984_2`J{0P6+Tbq9(rY0 z`7S;|Uxp?Ge90e;T#H}bux0S~TXMhW2Rju61;dK%#ie6Vu^X?@gbsc85D*UhMq;Ww zhazWlWB=UFDX9qUZ5=xB@?ft_?>of8F;1Nk{y#ySSB7&FdkM`LqcdtIx67Xx=$_rO z&(E}>Hp6a!!JDyj=8TQk;5u(PaXWUw$D84P{E+RAU0HKL#K(P{kjMZ!7<$x%3?=`d z4c`~ols9{K^og#n#X@WS3x)?%_3_ti8W25|@LC4yLzN83Y-(znQ}RS|P7m{-P>(+> zR2df{JE2zZeH{4NV#zeDk}2!Z5EZL&AR`*nne<0Kc~uA@xxLEGz{1`U!FEvU7Hcgc z;fA?lg(e5J=UTiL!b?0?3;mafgQbRRQplh7O6>8(WS7Pe^+BHD#*(rGS}l?8`9Wyo zQ}YZtcKPBPDpIA~zCqIHkj<4pyy}Dd2Q&t9wcL9(v_JG=BW0023JHIG*ZuTvDYavsOAC`S}4OtYy@FRZuN&c-d3r5gMSJ@jT z+ocTbH{L0k)%ox7=XhUM=$c|NA$(Y=EOCHLVCzC1)_vItUU+iu4-vQLKNAix8e@xJ zvp0EiF_ksXZ(gn=Ukw9bt1rMn@6*@qYH^j53OaNpVTajZyzX z?KpTf|2VC`_VuqOWAL%b!=B_zW+x`uiih~hpzmUrZxPr?6NYAbd+o8gD3=4}TSgt9 z&P7nR7-Ip_5_8C~sCIeAQOg~QeL3$<*iik;6li$hiGn})Ht<=JVU#0%vgs<)HVN$d zkIg00ykm+?wD{Jn+AqwR&8>()NxHxK5+;y_IXTAv#|h;ae_GAR+?d?l zs9rF>1)fRq1bghj^E2R0-rFyZocjSC#7bo6=G;kbh&gr>F?i{)Q{Us@Xi-VuJ ztm%x#`CJhNP~2qx+e>QPtTd`lQ3iFcxf|C#n*GJzHY3PdZ)ng(#^N=o`s=&6h5{_k zZ^STF!u~cG&r8f&Z6q)|kA>{tG8!G-7s>B#{ONBW?b9u;d_m?9_2*e7brZ6>vcK(i zoK;%wQx(0*^oFU;{G+p8-diXd3;1*07 zlX*?8P42ezAXAKHp-b;Ce?yExKFBF4DaAoV_cu2rq@)lW9L*XNAm0PO%O()nE}H-2 z^``V9fkI@?ZGFSuAH)O#WntIo4Zz-?uf2?ghX0d+l9b8qtWc^zhQnc%kuORF;ym@f z^z`=n+3k(yQjYFmT^(Mic@ofVfV@_IPnL(sa2haTJzfJDINk4QaUz3Y(W#N}@LnJ3 zKaS_h@wgm9JYVi>-5;z#l(3_z{NNHW=+?2}K;_TaZ5%O7+D+Y(9nlQX*5l#eANi9& zM5+(BkZeCZ^;*3z#*rYRkSn;RBhr9?PYki96a2^bjkIEN8!D%|t7KaKISocTStLWj4@<1#y%M z|N67HxASY=PpYT4w{wH8k7)i>4aiwuPhXo=?oF`ij@mE1k_smgws8U;SJm2&r0wSJ z9k<$80{aO^Tb0dqweKc1nu}r0sZdw%!Z*5_qbkX|27_9A7Z^sKf`%*Npi(_D;>}dt zhM=DP3D1M@nCJ)!OJf!i6%;sEC}M0B?7kJoihYR>SVNgvhW3kb7fN^dDkLnNO9{G$ zN-orw{L!HE`u6SH-=r%Lj|p@`UNhJtNj0AR)3w%qvDANy3UXg<^N1L)C!Z#HWqd$9 z+qv<60dE|QbyM^na)X&1JF-(XCDRsX@NljWoI9P%|f>l{<4;=RXI958hJsJG0kv>UM7fv|sztTVWI>v#@ zrD%HM>cz*Hb*<-xC*Z2zDJ+0Nc*zA#Z)@o9U4UsNWW58=nrbfJBR zG{|5cjERY9sfuRF1zD*Gevdi`c`A=kd-6mewjuvCyeqx-=kq5KWm+KuNz?}N`Icmh z{zd$S>=cx_|22-2)5lgroJgZuWVa`ga9{Vc(1|!lZ!hA4I$Tt5g7%OY>;cbTYg~w0NN+rca8e}s_#MrEo76QO!FXD2*m`K2X!^MuoMA?4|SFEz&q*kgFkDn~6 z)s?ZYkQq1b>1wbTeK>WknZOjvujLN$uG{K%$>h~;D5?X{s1&KRpjS_Rcy;u?{Ba?M z{!n&2nJ)yb&P;k}7t7!u&z8o+ak`~}z9=9U5a>&V>PuerhpBQO&OEFZO!t69?drV_ zHSAtL7UNzqOna^1~bMv^REZ0$xdS$52*Z>k4Z*O zLrYyCtVH{Wvs$Y6qCKQdEy5R+QL|H=7(t6W+1%+?$I}TZ2w3UfHx#6@HKadlA3Lan z&xz^CXV{9|w{0JVRykdi*)?{3ay0SeqKy)UOxR6dm8d5*82*lfo5Z}o0{SMhqghqq zPgcO~VSlgsWHn7!#b3r`py-B012OL`HZ^=bO;M@2qGAACW|Cc(` zo`f&o{)?pvB{VkEgoA`!f8(00%Nj$Xe0W8Ppeuy1*;@B0W}5V3V}>IBz}arv92#nDUVca zJ(c#pYm0osWU__c%KV(i(rQo%a^zvhcY6DxQKhfZmC|Qd2Qa6YBeLA8OcjsW9#aKW zEE8QxP@3w&dGITkzGD9G8kKx~XAF{QziZ7wgYu5^FI_Lxc9DD-#?oAP@P zFYGl4ZWzk5q0ABw2aT@8fTXh;$qsSwCJ2|gBF|_rKO-qa)uE+;BiWnrgveh_%Tg=b zL%#}FN#Bd$yN)rF-==JOsYSz75Q@W!VSmzW-44krsW+u=Oq(ePLlwPmv4Wh0RBYtq zn&}G9d`-@`gP(HMB38g7ldAO91>H%zO}xRl=W@poA~K$=P)=qo7duRdl*hp&m>!O0 zUI#05F2>SknLfq*aaScLt{{#cx_6(YB*taJnidCm$A=F!UCkYYw-{l{WY&={B{1CZ z{CZI+6`6~Gaie~*u~!AlXBV~wD3j2hzYqT>xoJ=EOTvF8H+8(P34{7000kNO>O1*t zl_vMX#)Y>K#0OqYef@v<;dFFly)${PhjxI1WMY^eWt~_Hq3RvAP%}tV6AFMCi(KKc z{^bgaOTZ{E;XkB=TkX1iDfN3;m{xrK{pvvcd@4jmG%@~xToNjmCitNX1Q~eJrQLz? zX|b_82sDdWx!9p47-csUacA^DS^pp=p7kKaq>|8@0(UxRSb5v9MqGkOymoM2BG@|k zeKvbNX+#nVd6zwL$r#9JV@O6@L9ZuF3?q*1yfzv>nsql-kQ0qr){l$*_79*E3XcQG zcr&iD#ibcTD5WeUh$|aj<;EK)b7U0kJI!X9_x=z54eD&&%lSpM;b&87)G9Kn%U*eQ zgbW;2oEh8HA$dcYb>_&_E?ZdXYcbHp4#z9~2mEk5MX&0}$;tiK6>BlU;&_DxBLF7k?Lwpb!Z>$RGJ9d;Fn3UEbUPois;Qzhw7* zYAFQ^Ls9w$;TgegNvvvHmkf2~Npe_6=F>Biq_D6-&^MCWVAe@zZ~hmXz!*gRqniiB z3V)v3E1xorjfrJRe?$MDhzOkIH1~EXBpGL@0c}k~Ld@y$pXzvuy`rxL&ROFn{A%Ln zvgit7=t;+{an}40(~Hl&b;i>9b4E>hK3A*oX>1wYokfZ%EUkF1cOw?h9T+6c3v5{M zM5cfE9xkc=3t{G3Ak`qsKI?QnN=|WeCXn`MJG!)#?5pd|j@eyFl2bBWwGtl!RwVWt zINBHCI&!^zfc z`xV&~4@Ip*$(D zfm%BP!%?G=M*p;zXoBqa7p+p_Jdy;1!%8df_!;`;q8O_k@56N@25 z&fcqm!OC=Q&Im*fb~JqKAR7m>z#19ANGrcXfKzBrjCx>aKK^LnS;gW!e019SuY(C6 zJy25-6uO+u9gM^Ut;J4)Y{0Piy?8(c6CM1JNE%wMT5Wf^DUg?!$A|_0`20K#G6}O# zP}V&-4_%w6HdQj^3R4eGt)%(#S@5vYfXWls_!cWVr7k0u7m~4A6YHbBSVzxPmLOXP zc2UAdC`-hC$)lM64S*+FKMWzo1C$f11W$aX>zeqc`&%D!WucYX#DUZkC-R$GZTDO? zjz5jJL<-GnyFH?CGStnGYGzg(zOmeOsR6U!M`nS6K}8*v`~B=Y?~~U$n_CpF(AyJC zLFss{tsPm7FD^OQ|HW+Hn1DxleP8HYiN)@Zfsuon%&I3k`?;_wCNl)U%hgY21~|HRKOXQWAG<>~|K`L%6JjC1X6Mk(;icrSda@Q}lhd(&QX?zk|d6MGaUxrOQv1pl6Kv7j?fWv0!-=8v!XR@fCrSh+wRUIrY3gh!TQb}LDuh~ z%Y9`kwc*T;bpfGUt^SMX177K^)6q|}i1**B!)XY-dS=s|Qf@_YH==d#E{l|?GYC~V zWM6@e2JhG;gEusXGmHswd{4HHP9T08<~$i?!P#MGw7KQJM%<@VNpt>Uuf4cOmzM3* z?I_u!Wrxh#^u^*d3eXrN4|d|~*YDq3Z>)hf%4arvTv_wI^Z~c?_ zs?LO??1z(iJI?Q38Zp;2GwE|V9y;HyTe)`P7J@gQ-_!_hi1b_WhK}!rspPz{Ud{oj z_WxMHeymqgd6Lmc+?~pH4$%DqIB<|qFASbOyScF*PE5sRv)IW)-!C-Z3~atP$Z0Hc z@WS8lAIy|b;;`Zu*R*MUYH0r0PFu%k^YI8Q#6OvNC_y}f8Z$~Lh8a;Mh~cls+3ERg zvF@Gyhv~*de$g)hf~{*(DxW&u#f%Wj8r|qJgMrd4ZM0E4nbA>!g)d5Tu<0tX2J%Ow z@rm`XKkK+`C`K|*a;Oi{1@!d|f}YQrls^}?;7WEA`WZH&^ndu@@T|6lMSWq5aSA-- z9b&S)VcS@+@hMQO$l^&_Kcl5=F#b-)mP6^2N7RP=w^*x>*I?hljD)GS%8ll-4?@{+ z>f5M*#t#K~R6lIHLe@l=N>3gQe_|=4RM{&w<^6n;^9xrek>9;~y*v`#XYni! z5{V7RQhqyfU6=tQr3ecQM2^$GyM6dD*pn9fWf*4aBcTk#TrRjLu3gvU{$-iVutINp zGqgH;V*^Ubi!1cDZ-d!0IVotvd+5()M28Y>d~g7)bPA_2e`T@KXo@xgI{iSoe4*bL zIbY`I_*0X5fBXYTMdt26ksH}RhuU~r{}kYbxh~&} z{iX$;>IMyH2}07S?AhQeU*Sj9O-(P8RCjTh!m!gz^gl1t(7Y zOjRf|M-<^fTG{u+QQlb0n`tH3>3Ey%@2U}M)~4I?NX{rNsiemL=nmm^~(J9Ds8`-T~Q`x^qo^8hh7Lc{HFA5h!1x#ZuqNHZOr5z0kFAGopksyBN4?r?7~X!;M716ZZ}^ne7V6VAM2aRlG+^HeD&L1 zuV^-gc>KfS6IG=hss zNC>E}w~uPJ9ZAN-Bt(oMEf||@zZ?6f%>{7C{42&8)ZT(lF{kA`7OVTe0?$1DK0JC) zNdANL_Wz_`wob3`b8&HTIQ^?D7l68Qa~nXzeU5>Lho{+z?(ZHiB0$2J&O6UAqklzM z{@0!gavS}C$$gB7gFS}O-{qf>DaS9?zP2daf7t~RnWBmBOY zIlu={Yp)Gy{d-^NlY<#^N+b;7?FWy5i}9PWAK-eE^>?!M_Mw7)OvDDvzgo7BLR zWgvTs_Ow_n#{b$p|{leQ3<9&>u4g4PswzOsnt1p-BH(x8-eLmXVLeqs&L;) z1{B9R%8mAle*WGS!q*tSV^uC%&N9@K|9y^o>_A8zqg*nn#r0+LOgA|6cAn)0l4^B{ z)ki&B>fq1sm#x|Vl#E)NXIl&6$m^d>naoa-@+or+2VRe=rfk%r+gmB?zNW1So&6dZ z!wCEs_<=h~lMa%Q-`iQnWP2-ES?7sHHdQn|rFba@A@7!Lofqm0Y1R(%m1~s!i$AyS zCbJ<*o^bl|`Q>HbiElkggVOr=n-jiRe(xA^LzUH#yRtSq#1{WSX6p?{#`3^AE<0;V zL(GTgGgBj9*k=4h-;mQM{2!UGxKBsdEEa>F_}u`+*WMF zjitEY?+pKMY&^fKv7cPZ48F{)bbUW%XKHCFht_6>P!+2-^!0j$y@?~fn% z=iH28d67Gh&KLBZf<42 zJ0S! z&Z(-|@53xX+m8Oryl|p_OfnnoM)!{G8h*4d$DXfZ4vZ5uyGElFh@8)^XQ=N(uXRsd z{+2NP$&+{4L?B(Lu1K2s#eewadjj5vxi&0L{CuHj zJf~2JJ8gA79rXE)l-;`sTSHVtEaWja5-iR*q}H|sePbD`k%nIfj1jRn*o4^ zWKb1v_LD2x6;nUyU|rE~E%>ycBF;a0UTCDJ20~}VF71oD`UfJuu$EYjN6bguH@4ny z{W0u`&^FCO>tuw&KSk?U=*tZy%_iNg5SOeD!pv`eZ<(nEPRgXs@O5_is8oHO{kR5y z_G}90wBVUL^*p+hT*gSKx#5LfNj5snrm~MZSWVMysMJdEnE2{~RwfaAwK8%W5{0y# z%frO$t^Wf$@XWf#aveNs_E3JRwu*w$6C;O{D={L*f)qXY+K?Jwx@vy=LHjB)d zO#jrPIs0i55Q^f;mgfw=9hh8{--thQicH3orP2GrXC>|r$b9XL^sx zZB5Y8oI~Iye*~4j;Hfmwg;?GqWJs<$U~*Qe51cN6VCl(PR?g2l2`6DxF zEcfAjh@lk8D=48)9OapxHti6Gur}lcOwr?lGVYx8ajM>Ia>jiVWaiG&5$$AJd3+V7 z==L%HM8SxWCjhWj0v`BFZo7J6ztHz_dHg6<+?XCipH0j@)C3^V@U}BL+*3-lt#5BD zGx%BRSYrT_&hBH*oT|3u0Zem|7d5t$-!Fn6^}+OpDI<7$75qt&$_qIM_Qy z^Vxw^i{5zQ6zHU8FQn^lEo8jc_@mOhy*VpdAlLpF}w%BHl9O;2_aSDebdXFTu;P7p`#9d_-bcc z(qd^Kxcj&%+j440$mAPe8m}NHeC`hME+l6yI{=@}FM1Q02XsU^4t zzbF@r_sLoK{t2r+rJhY^OYe2%=nrPu@ECoiX-sW!#OVAC??b#hD+C{YuACR^b3AUU zG(`5)nW~>(XNn3%B9MCqE%7dr2pfhEmj=R-TyKwiIC1zE@I0ZZ(*Z<}MxKJ&E-2stXy^yP|Um`!0OkeXBm~BVpsS&t) z3eG=a`IH%=zsxu4T#Yh5e}!)~FGgn7xW+6t5KnfWf9?X(ois)-yPBn zhgnW-%9Sf0IemPwb{an)u}|Kgs<+dnzSkJjUdlqLMD==POpe?uRUV)UH`U|x*u=WR zG`i6va6dget8I2JSnSs9-)I{iIN`(-mHFO#@v;qFfh+L`-<>Q}*L~5u&p+*shV%=+ zPf~Il!l>@|&g9Q(5uwXa!E$opn}Bje#;#PG0A8qV82Cz28?$9BN+k8{gE6Qj`(ftf zZqsvN%54PXWRgFjd)3?it5vw{3PJVOsW0&i!G&7F~mv_<^J;{QI{BQ@n|cnlBD}6T3-U7TT#qE-Ocx z^x9yt34R>@J+F0{6)A3zK7I(2r? z6@h$J?~v$3e6BM%L)V%BBoJ0B6?vcZV#zgJICufx@f9`fsFuW>aUzKn8Ob-rZaC#!!+dZDR8EJxjUf&ztvexQmg!(3lq zichJ=4&lW)td^X|N*yB}%|_7)r^qy##CWwfPnW@_nj_Z6FHzKsPI=;%xzU72R3(po z3O38;wbnt%+d^Tu%GQ#o++%u*htF7Qt^vsHrfSCzMp2^G?`vLZvYXdnYUSg?Y_{4e z$YsrxBpZk+BCBklrEK4Md$T1fa6vjQ*Ish1MEt@_$ZAk;9uMKQ<{b08r}|o8!$^ts z6O25X!}K|9>R2*);lTCP^Sd=xWKNfD7d=~FGQ-lrqdDRH=A9!2pTUHKL z`)T!Fc|FlFXcdk-u4kv^X=VWBsk?DW~4x%NtI`M$x}rC0$= zhTdp*Xyxj>!7nNh-Ulknm95G`dvuh<(51B>|3b2DuR^a>D&g!M!?EjB5-?AQ#8JZ8 zvp-XzWfvgy^CCavbh$ruQ(>Uy#f%EIt3n_BWf*;3buzYk7n(+?Ey3M%S_@y*0Up_U;;oBnnp*OC=s(u5%x83z^22QVLyeXS(4c z)tK8AoLpWD?!vsZ;i{de7POr&;GLY>@hSrC;{DTjvGe{~vYXwT|9rw7v(4M8rQZr0 zP;bf15Wu_ZB03z2sbwwO6(o3My(4lWOec;*#A38UAH zHziM7jIR8qn;G0d7S7_I(6RctYi^}nneHXa_}Yq%T4!Zu4Hp%w*RJItHP*($$>Y@y zH4l%5u#k|!i#ouovu&nQ@MhMBolTjEU)9i-{V0IBNg+efx#Wtq{(PxjXuceuyV zBWFsS+7yQRJ0%^G4T|-$WMwUmYl+30(riZzH~4p`#o7Z(hl6fRIe;t1G_5oCJl@ ziuV^szhfmDp{MUFR1_Q2)D3n%%&ksxH2QOE%xdSeM(wKU{n^Si{1#;rFI+UZ{_;y) zd-7g^G$r&KnUc?MnJWXCfkSwT8yzarUs{%_<2|*Mcb{y{tbg7E(`{@*s0}eIo-NFPStfCoT=f4_v4Bag@qi(v*R5 z{5E7=rWAE1ME}*+`ur;Q^O&_cib3ImgQonteVHo0vizE1Mw6~hXF_kut_D<>+^P~} z1d7=zb;?BtkY#H}6cbgNC^F@))yfL*=gM=3JE5k)z@85Lq z+=lK^ipC4@s%Pbpr5#_{M-47=!ABdFweh8&y-us5l{pa!=XT2(6H5YIoGP>de4@&>_C7l5j>KX-cbfwk=*eV5eQ&7oLtySbZ;1{M(IcAcibJ(2k zhQ2I^LL(v$_4R#@r+PU*1Ib5CXG^C1&#OZyK;a4`GzwQM&la3~S!T=@GyzDQb-I0! z)G8Gz`KG9-sI6XaTzq_dob($UMEqUf0)I%hQG^tk%1+b(T-r*8Gd=h}XwL`0uWXft z@H9q?6{AoW&)`PIFX6uRqe}N`^B}zeP+zatOxUy9#QNzF7GB9pSIocJ^H*g#rRF33 z1f4+uz=dcqZ|&*a*|p9O=_gNQR!;gW^tS+{ZQGbj%%9NTDk1^^NI#)<4M|@EL9a9< zTMPk6KYwAvc!U0_cU0^V4)m%b(yI;HsD>Hk9kfY6V(kC6O{H2jKYx2tB zrOZzcc#xK7_+vu+pCeCl;c`Qr;${4S7s=r5FkJlSG}!;QpT_?;AO8O*M@_LaAH-$1 z7_L@xSj! z%N_T;;c{5zIk2=2|uZXLDn;%cMvtR26{Juz;F=r z$!eo3a*8q;4iSy%ipwThvC}e0v4@qqLH`u9#?)GpE~D}lerU7|DGi-Tp&P3 zsULk?(2ddg4068eS9h}DvOJ{)J1=hIPB<#!2Lv%tt{*Q`;DKK8J6imTBQj_+yI|qq zH@1Zz)Jj!Cd&iC@vqgyU7*RRCu813Sd_s9`J(GlU`BF86PaPi6v@;>=_4l?Ut*BWp z4qvM|N(EAhzg%8j_fpi*My_X!tPkII-nzU$xx%kyRf{2e6T&81iA9&Thy1bE5=}oi zmb<@Ta(J=%tXhW`_oua{fP+mEV*4Z!aicfUgii;VLcs}3&zYsvQ?M)nx_4tG+~fV* z>^WDGwGl#|U?(%gv)c}#LO6Z)1^L?%)bZe_uA>iTHc5>Bg=$J=bws15qs0tWEl^3- z_=viVY1`WjjzHMf+ER|E=1H#`jjf_rXtt+JreQBKwm|LNlj7$r^dZ(bT7!dp1c7mT z{EWt8g13$SM?3~3Q(%-OMj-<1>|tcWK%&ed__l$kq2zNfxmdQ>l+xjf`qK&uZ2x96Z1 z=R6VUNzYWbNa7iP2uhAbv5wjv)rR`TZ3r@ReYrBrpI+1{kgHTdlgO&m!yY&%T&_2s z6uuqx6(_{GR>+g#HN#~6QHkS{xz-yl$x#DpQH_@L^&X=hRb7mU*-*{Bf}g3;$jqF@ zpXpbI8=dfNM|A1%fqUS{6hdq4Mc-{*egxt!sV5Vz><0~0)}s2s#Cg#xd| z3ibsEv+7NroqC#?E167`pd`K}=K^|yl=;Bgy2rqA=GTL zcu?-fPCCU=SAZ!w5qj|XNWl(;ad1XrNk!@ z?%n&;b>%2%sIFPpeu0oXE*&%VYL-8#d(!jCa5#d(q$AKwlOaghcO{MPLD{0B>So_^ z`^WAKt5?AoEuCU{BGf~T(3IQ%d@DTcY5QWn7Tbolb4Xbl#~Tam*(OvY{lf}^>z%Ld zG|}Gx(PZDZxb9Iioo7RAsHtXNduyD$9M4~wdVS%6m)raS1qNN8XV>#Gqc0na6pyk| zTZNvEBT+3+f_$at-EpDQq!#;fpG<#Tcjr=mLscPqL)l#zpzsyvUFTNku2cxoAU+cl zSsph{NgPf}k$*LeN_$?^;0_(Q@v^Y~#<1w|Gh<!CZauT-WCIRGd^^2g0=^KR41O z8TE(ma4PHn`s5cH*p(cr*H9OI9yY9)_55CMZVq#S1>g_Pw{JJaLeL{4^;uLj$9EHwkN0l6&N*IZk8Kc56p)+5VxgF%cd(OL|VE~ zRvQ^ImN|2`W|l6;C!m`d9V9-7guh%ry?S)AuY~XIn?&mZ6FqLUluq$)&eYChC4FQ0 zJ|{M`V&|34@U?g5%6rr?f3ifJ6{&Bq5IB$q&cd-ZEfohNGZjH4QsgONe3ov*^eJKQ zt~pjyWGk#!Oq<5CxzZL=+8Wvu>Q8Lu@NWFzw-Ker6G(%x>b8uAWDZhBRl;>?u9v#r zToRbFl3cD5`|z_$3l3oGO>%3vov@tgDf%YvQ%3(kqmQmvlIQjBE+r@_Dd{6sB2;qn zKGOidx?}YpcL#&5Y;B$C*&6d>%FOD60GSBm3=gL`C*pq|KoF^z77obO?|`zp|6 zchO9GL+HuX%^i%H>rs|o*1d5Y|06K2NIuY&I~H&LL-y*o;kQ{s--q%&7r%$E2Xf(E z%$Oj+q&Xgw~NM8R;3IStVJL{MO*xkV#e14SEE?l~c z*q{}aX|LxlGCIfB$*XC|DgO;V#>=x&XS8(XXLLt7TavIN5kVRFE#KLj3vu-I87`Bq z@*ydIoupU7nxvhkyA&8Ql85cZgwF$<}e&v3N*(9?6&-f8Jk; zO)xVMJfkDaa>$aKmapWdL8e|dNq8kqwARcKlBcj$&-r*oyndWQiEtZymG)O^s08y- z!Z7H-v$AutH5eyPXFeE~CKlfb3YY|2irV)C+=oCf&ry5=Z?IC) z&!x0N)B41NaC^azcXhMO8hdpa(^8DE9HnQo{7I9nme6}fLwmO8o2w4y*4&m?6`!YY z1sdV6^h?>m&TpQi;!t^sHvHBb`kB&s92Fvb3m=~CGjle21+-+V-Ab*pG7Wp_gjIca zSq%qm2Hjy|>mGnUe6z{jH0?!fvQD7e6o_FQfX9 zt~32-I+nW}-y9$wZ0wpLrwu#%=1*VUt0M2v9ENz}7o=RZ>84V|2lMFK5(MfyKX zwEwmoh{~%9tY6mRN+aAPkPm1!IP@JY<|rgDb8GlcRurG7YqHYn8NE1KCNUsJb+`A@ zGRe~UYl_=0eMZFm!3O++5VEJ^=xUuU_AaFpcn3e&@FFGdjMUyA{XWS507+(z%8&HF z^a}6_oQq*yyiU0n`rjEmE^yV=l(?4f%&))LGEomBf3K>(q%-KwLLEgyjoA5if_6#z zD9!1Qc34|#5@dTlu-ws;^zev<*+16YYUEi zVuP~)AL2Ytl8LTeygtE6AH@-%;F)+MWFH9QldJY2hdb%y+)hDliGHJTq7}(*C2QF= zfR~a8KK#*LN9}BeWy()buw5Ti!`IVhnJ#Q_ubfA_z1=(1rNdEnmw!Wpbv3U zSJG*Vn5e+Ficj4=x}WQ;2d35YNtVA{*IE$tkLYEQ6*Qj!_C9;~uFi_6b@X^FEBY#ziR1z7Vcs zMBh3oTJdP1Pg5CQ8m{4Zl+cuV`*+It_b5%1Xn}{7Zf^D#Y$m~(3~wFA^JL{MoU{!Q zC2f-OVycLwHvDG1MZpwBzv0~GSQEj^#HyD@W1P~CtNefCec0;>p$|S0eNIGfN;lY& z2e(K?ygO0LpJ!|#$# z5+O%#!oiD*Vuq#=a}}ck)LcCJjr`Cw=eh%^&3iF!Udh_r^L%_|Q~5o}V60 z)m2z7eoJtU)FAbGBQXb(y-Qtuf0+=m|AnL6>Ct0p=gy9D`5naatT3_S3hJsDTH-+kw)Nylo6a>!9_NpVv6}P>4pd+)Wmld9#~!%| zXU7F)N@rJAJzZ9~q;muFhbUL_e^!MRuqv|#XYVuYnm?BX#QQeOpq@HEer*V7M$q!a zi9#}uyh{QQTA>%*-F`Rh>ZtzP;6mQ3qta>B znKyqu?{~E!Y0*Y_8k7}7veC`4E*kj}Og~ylU3J*hnd_PlS?KNw@pT=+eDM?Hk$5-) zC@BrM2!z~S*+zAIL~N|-qC{;8h2ye1+EC2J3t^@2kO$q80tXT_IcDnAP>S@RB`-N| zqkYf^{Y!EWzB5CGt=Wjr5AU;o4$?6(Idftx{BYhQq<|~Dq~8EixS%4>I9+My^%YA( z%6D-NT$f+}qLE8(>d&lsTaGt?e(EO48HOmNx7AEMdxNAMO6JpBi*ob)4-2N!V4O&7 zlv#p&8!+qfzD~uk99M7Z?Cnv&@ltx6`_%mcBcs>8-xtcMN-dq&CKf- z{6?-}Ci3)8D-a}bw^LJNx05~}TWzdaexLY3!B$<;Dk*?*Jhiazl4N^=G`bhu@H;!x znlvHG@>f+S5_BL&WmZJ*Whr3WmLR^RKhDipWwR)K9bL$ojy}I&agYi<*(*a5A+Zy-0 zSN}8=MwssPkUSPVm|9fMb z=7#HT8~#oraq31bdvItY0)jn^-;l{{w(PcNf=NcpRn&=nrtd=CDZX?Ga*S2+WaT*v zr`B0t*_qLQZk9+yi~T_bjF-;QPkiWWk(isKRMBc!ulHsGpVb#8tGa7kq?~(osnMSO z%t{Q4cCs(cUX8g*h_#)K$ET1xdTln-68BBD@4%zCX@;2?xX*J(AJcbT?_cx9o>f01 zB_W8ga;gsPCefd+dv$+ZFhKKKBGO?bmjl<{bww)|hxE)lX{ZUy&dfBP-tdhVlDBZ_ zTp^@hc#9kKEC0`I#E#k5Cplo7<@0V&S>thNQ`IYK%NqAr$gMX`6PfHkVDR+<++}6^ zS$WUAnX{*)W$sBy^GtequWVl4*YKa?itZixpdrmik8f9Q?7vTBPLFm;%3 zI0>FKzJY9Z{N@dDBO@cs+9`>NJtxR16bjYrejcKfo@3Lj0;n5;f++{Bd?0@Rva&t~ z|2ytXG9wD~_CB3U{Be_V=;)2q8u)hL4TV|*g3|ROPXEAJ1<;~rZf>qJW2DVvUFJG7 z^F9F8+JUV?p8$v#`5%ba_dg+CWyW-y$L>RLYim4gItmz-eJ?EafEz%Z|9`9okp0k* zUxQBFq=JF2S?eW00@zu?wCK?duC{5V@^z|^#c%;hHEQZ$2(k9~2xt)U^dD5!<_UoS z(g*awH*5`ZUqTQG33LFEo@;r>lr!p3`08fF#}GI$+UolH$;b_gW?^9=A|xy~a0jOQ z(MNgB`M*NHbPfSfKHT2$#S3~sn9-~mCSF^7XwZ`)DFk#HyMu=}4{dM+`nWv6;QI}k z1!#%;H5d}3^FL+~G$U#JwkmHP#0qO$TiXaIQs(X7H7~<--b-NP-9VDq9RdRTi_1bL zIF(bV>!Sa%$kfg@x;G}xzhax-^|ugKZ@s4+ppE9905BP7rPROsTJCLMg3vIa*;$3T z>eZB_M|&80n)f0VEZR+tR?iU86!QvWN5E|T>R=~Da@9Mx=aIs_=?KAo*gHi(EbOeE z^M=%kj!X?T80Zx)9k3i4+(l3aE?eGmKDt~sDJHgHFi$v6?~)rA%JH- ze9$1py3*?;dEh&wF;xwGX z%AM?`p;xXg3zBfbb&Hn{KrM^7LYj+Jq3XsBQ`PZAkBBIB?@Zzu;>vx0dqC!T&|GMH9u_ekeI6FPfq8HS zHD!VE$X{dul;D@rwh%Xlh+SC%!dj3#gT$1hX7B@HlHQo1b4u!c;|=O_QOng|MYhf| zlu3WAhxfk4o)nobi8~{=s+WeN@Eft`!OOEFQdP=8$0&{9s4nS`x&Wo z7ZXE1jrRpi=l((8FJ9?({gCPW;W^H=!=_;iS8A%_0e09|6r7>ISsl{sceEi^_$&P> zDlPVHK#Xo4UR}L24EFYP0Bv-$Tp!39Us1L+xZ(AsdO6QDTWF`7f`WrM2=W7-yR9h# z2e_v&@$o(}q%yx*Qbp6&m6pTvNLr3s#lc#7S#Nfd7S<>GFbic1c=w)y(rI)^6pm&n zf(zD00>`}Xdwk$0v+>epvvY#*d&~qrBfnfF$l7<*FKMLdp^M7(XKe>Ih06;+J8c*| zRM0PRE{j$u5)-K=Z!RR~xT*$Y^GiOLPe!$V=!-BFiLD87W;Nblq*_Y^-V+;+V&N}; z(%tL89!KQZG*Kpmw}tM7g+ESQmayQj{WjQwlTDV4Q{uPpJO&^-ecJ!Srvc@FYcyITY9|y>4IlLJ$Ks zbiVSFWha&5S&_n0Wk27w zyf2?CC!u7un`gJed+>di15E(8>Tx{pk7UKvxS5K0Yrxl8uaxtY?7>g*!Ogn>ne4XG6D=>(Xs|y=TMK zvCN8ag@LIw%U4TTMOtRkDMmpq0+nW`Fyo-(n>Eg4e1fUMi1}~YzDf3)V%XX)b2p;o zmh$aXTqd@4dpa-e$apFWdXs*bFNcS<=qws-l#Uz0W7CJY&eiDAq?Z{nnPz&`zX%YT zOn7VB=Gz!9X}=L^jXJsTZ}H_#^Bv`=jUNtxH$(-ZlJIuKHg+>jJ zcSyLr{&Iq$q1|FHco#Uo9oh7(kjY6_AiEpBk0ac8Zqrtpw*HMvK3qM#_dq+c`n3H!o4u;7M4|1qMiKxj||<{NkEa{8RIGW zWa4-~gS;nW@o5^n+@J8qC!|Cb3hMHsvhZHqI(+I>iW)542jlv~O*U0Mu29H0a_Ew_ z!)@L99)<(bZlCIubRp2n1L@NCCy1I~Kv~NgXuk-N(`}7cYu3@gjI&;&9rlG6Yp`XS1@rCO|oFnG; z>lv!ykf(0_B~(P0^z+!a8?a-W0i)GNNSC#hwwCG)b&qflZz(>Gha6iQ%5jjyw|L1) z`rc83j|OBCHJW;}rPGMiGAxrh78tx}`F#c!ak$HW6Mt{5XWG<+9V|MaX(bYfSg)NdbWH!oX z^w)kTk^0%QzLO!(w(h@9Y_TCFdly0RQ|mO__z`A2`Gw|H7?7oBK5&>K9ZW>qg8=KM zQ@#Ifnf`h)!@uhj8sJ_LcA%xvd`FYVUcVj2MZu#;u>GGF)1)Cyb8ts16u$_ekZ6RA zFYu`Vb`PQ&;MBD{JkRn8ndiIEeBSus@|~J=9}wh6wa}NJX$6weyfJLGYy9J&k+<`r z%>n$-0mNH1zG_)s&-F<|6M-$Qs(ni?xeJ8W<_{hR>M_wD{Q9h8z;dY{jT2H-kbKUET+~>W{=F1$S0VkqW5NHL~D%Yb&UT>Jo z#od`QygWHFWh^x1*K;9A)2b{eY5oiQ?jmQyet+DN2<5wFsi|O@Lk(Lx&|st-D zQRQC;bpZIcH(%6BH#hIMqcOqqK@LVu;v{gv-jTp&x1+@pMDEhJ7#G4rLJi44Q;pL! zrA2d>q>0koFXv$gko6#`1#H;6V#G#@INhVeNt_GA3f)p~jc4lpR>!Vg_9U*<^OZub z$B%wh;<@TgNc1zx32UBUxc-@{(}p+mmpKX@A!)0VrOnd3{e>{DCW4lC-oCy}!d~se z28nXf^?cx*;ke?C*E&7~@!2NDCdv%O!frzj4+sKV-%pO$Io5QJ&c|kYoS-JgC_0N9 z+rjnN)fm|8wDhHjs~ik^tQeG>OXVB5=z6mM4a z&4s(g8?hjTRo-%cy-vT<9D*!khqQ*eWY@2&dHuwul{T&_51t2 zK0Y?GgD1$Ov_gOP7Vc6uHNk*wb5MZ@>bPK=s9~5E8nLXtMIl3(BmKzO{5CjmQ%Lp}aBYW}lIHGtf!VIBS|oNYuxF;^=492= zanht?%=qHDYUMvpwuUn-ppRVfk9Gh^V0W3Ik^uNyN^(q)A*7~n)=M?NSo9jl4JMZ3 ztImCS9Ty!Suns}2Q9#&sIL>d13FW9kWT0Ste1Yx7&K`S*f zf3<*nnK+TvOH(lcYOugfB_8z~NUs~UWmYi8iAiA)7#~?2dEZxBG_ND4Vq;EiSzZK=;-Svt zLyDU_NzH#T>5}a_-}U=9O@SFBUe8@j@Ba8=n$Q*DFY}yR+kO|J1Ky-+0JW~)TX1FD z)T}#3{@A08?de~__xU3R8WdpLX*Q66!0}I6*r^5#SZeI)RL@37m7l7vZv6cmdt}W@ z)WeC1T_}i{;I^zu@X!p1jA*~;yi_6wMYN82;mon_>L@;JOhA~xM8r2xQ(0C_z9#FTs-t=>q1x_D0rS4DZ-V-WCK|}M_hOl4Owg{xY&4jS-4rF*gCs7S@XDCx>;L0yW6>VoS=2e zB8k}l5-GY_TX@*JIKR-fcd|zD@^ImPA;kXzX#eSjAitn6_X`05NfALwVUgbsT}&t_ zR6A-)^19wXj#hpA)o&jA&*n2S)UVY>nB|#pNSK(SM5c_3^mv`G40P=s_n_J>TBf>= zJncMA9ADQcop225E0>ntOy4=x??f1V{FS7~RIYBbgLoWZN~@qQ%7twv_P>Jojlq9h zuw0DY+-JLxCl3~B+nquCuwRA|D?~}Da?o^)WlMR9Ig%(KyUMOTSUMLPoR(LAD*mM? zFmhOKI1&Lk9&6M8eNPf?w+E4tQuDDTRkhH zW3ApVH&ob9N0?fI&Bw+%@&o>vPEExHu!PP}UPOmAU^kbdeLsTAi=IfUI0Rx4RfB7{ zQf2WG-dHyPGo8T>;{M7|7`u$)y4k!OV7afpZTW! z9nutL7kYx;eE{`t`O;#0G&#~_-iy5u`nEe0a@Np}5ZhtPo6=DD2F$9`P<~PpYI9i} zSc~OTce1Gjm(Z)Lz^$dr9POHPWOwRPo=32BX1zR{dCZDY)) zJ@TdU@~9L)u6*|+X3DKlY7^ZhvJt@yu{3KWg*=hNIBd7p+g|DnK4Atn8qlhGXP3Ll zxu73jr44KV3~p7!>oq3QrG$;`NXG(HaxppSI@XppxPYniLF&7FJXppJCdr3$R|&Y* zJ;M^>)ziRyY`_y1H;D`l|4#uC`cV@}_psVZXK{`d{@D`hLTXu_A>MkB4^0tFe9Gq3 zDhGcyDK{GoZ;Ip2m5W#{1q-?>8RL6#zs5s4(ec}es+qXwpv{AK@r$tywwiSo7UJx< z8o!KOeU^l!DZ-zA8HGzan}m;X9K;-11kF}F8?Hhj2V!EQ--V}GUGH<6<1 zDckyyEQ)55G#k!8T;ktdk{t9cB_~wb_C@v8`YuCGU)6K3(@r6fp$VGZth;#CB_UVf zZ-d(S+Ca#B#hQDHoFHA2D?TCXPZuG*Ph#n)rm$xl6TZv>$t~tD zLJJ)!Ys|O#=-vx%>X%9oT?OPk(j#2a`59r6dw?3*V_~W(x9(!mRh99A`)EVb6l}8q zcjAO5sx^~kteAK07TG%2LEk4_Fo&Y7V}k~0v<4-A=U@Q*$FB>cx0-KBY0F-!&Zf0N zYVL1K>I1;$UMTe7mN*;&o?F|MIz49jwES43_Al+B%M$|D6v=AHJ*l!=UV~CRqJ3JhR=*e1w?MZS!#y2GIN% z0W$%A7R+boy=^?`i%B%|mfUf-xM$jVygUqpQP zhIe>uJWX^MPUON=1L)tZwug;(-hJzP2@tFRF#vKYmTJi zw^^YD9^DC4xL`BP32W1%ec~8VS&GmU+^e^X4F>n&iS_klY?IN{?vjq)6Il9}2@U#n zY?j-*B-&;5eYYcf`{+Z6a6@;3%~P*;W0^XOj$K{O3|#g0c?R>yF%&wDt59=FaF((@ zjHsUYgMWARQwx_6bTE^)LI8B&;#-=O<$keWqo~@>p2`FoWAW^wLOzsQ>K2I4UF^O- z%>_kI;C((yekV`*jvq4^WD-B*=!ShxWZPuhIC$rT1C5_31Q<1XFKQEZ^;C5N0S+$u zp~!H$zY%d|{1aD0V>e4!zG@a)Hn~AbA`edE`JS9qZEd}pbE-$)rY%_GIzfTSM_%K8 z@uoRNxmGLa2i<4jI#~i{_-hw3lnctEk5f_c6rJ+#c=vG54$U6vv2cpKmQm{VSsJ*X zqGKCgWeDV<9pe&{z8-@-jx5xq$40hp}nQ*!>bl{=+%#Avq8$~AMibVTyS0)XV@WLPtKUWqHW6gco5}82VZ?_ z)r;Q{)S8BOm1}XF)qd8x)7NP}+X}TS(lB2QnN$j1G4+316;PKc5oiIh`v%+Oi?elh z)mb}A%m$)d;hjvEx=I;ENC9N5XV!gM*HzV@c0@2Mo!;K7N>0}ghYAatb}k**0DnBd zv95o9XcO?{r^k)N$P&-p=nv?m5C*+rOxMn;=l2JRa_Pr>mEg*#jSRGc>`#jeGbjj! zh7{nip7SZIhHWG_h0+VCid!FrfKC@BW*pSBC`TtyM`<(RPF>vBbn1n+^kj4AcQqd{ z82;+?K55j3i%`eGjA3i1fI4pXx$wsMNQRXm_pS5|T~m{}#AjT+!fu;dRE*kCYYriQ zf+NPkvS>Wq61wE6Y7nQ|V8&JkPm#$`kJYE`sbZi9ErG8peLpYrr=10RGoJ?2aOa9G zavFB=`^LiYg?#D7*H~%pe{#oO9h?j2?4Nx&6Zkp%>`MEMPIu@qomq2mpBy7pU7J;3 z)pkJlY;d?!@kDm|^i(JZ)rMZ+MQaQOD@XY$o94K^Kn$G0&*23jhhF*2f_HMMlgUnQl z5e41n-)7=t(Lk{tCR#1&4<$|0!c5fG^El92z5R4g-eOFWadiuegxbUPM@G?yTNW4p z=ZdYJ3D&xeE!%B+q6xL7fstLRc3Wmcate;hcTM;Xv;MdRNLuOIBw#ty%(pq-uSRDXw7bq()ura9(+^kgzL=Anv|5t8#{|nw;kP}v#^4%XbX2du6dkx!noaE zWYKSFB|L7WdE}nzPuMI{k>$8%$mOzt_;d^I6JOXOg$J0&`1jzH8ZNlT^tCaHHFjIkWt@-Zo!m@Nl)%Ny|D7+*fC+@07< zDc_@h{aoeAzKVF;sK$(E{oAV{ zU$7!Hi(JZH5sn>u!@VK;m!f*Z0v}o5TetfWMYPGrZqOQOi;i0L>^M91eKA@G4MkHm&%`RtEXk^=6T`wEdzLuCy*yfED zq`90&ul^;anK#L9qA@IA$i7SdJ~f02MZ*jo9RpH`P9pBh4^tU~Z2Ca_B{{#+E}`tt z&z?>X%H?@tAzaF4df;Si&CutgWKUFTiah3nef?_9v>oIaT1QP-$sxbZWMcRAHQ4+n zN)sWhB&D$qK(#-)ZL!7&IhRh1@r2cT0j@l_FPBh4o{0csWt2jGp$5)}leHHzh)BiI zr9y$lS5B|Ly`xkm>`Pv+`Otk$?7-?8sgXB#tn#h=nE|J--?6YWNyza210vCm2L|5< zQPE)!U;mcdc5U%lXFg0_?%$q-Lgs@pyTusFY;v~#C=O#u)*XMFQ} zqMY8U2DW%Y$p!}5?hMOPAA9rVA&ja6yN8zZ{fUP*#30>{YPbOBkW!>s_N{Y|AZt+G zRHJ)x$S=Y`P4Gk|7YQp*$JMh>hOOBr^I>O(-*HqA{^8v=ZMW!K4VGUWKYsc%xiiUn zE4~VE$MUd9m=Xe#0sKWt6qh#Ze!;#Z`Fs(A6YNgDEIY)iJY(hWN*w_NnZxwa$I zCe&o?-YVJZ#{x$F5b<0dk$-Jee&sk?iJjY<&m$?%CR#$XOM`64_;*ucmG z`2NJKJN9b^ShrE$gU{qs=LQvzlZq!>)6Cwx)IYg$mXJLoWC9!2m=)hPvkCmCBbz%x zRJgoU8UD}$^E(>dSTAOzpKl*e-;`x4Jy8s!uD4?Bh-&`xkh0pZcf!{v^R2~9G|-Hy z*G9+h*^020*+^G}I~n7)0f*6SLa2_WxHa8g#_Y7Sx zd0N4!xVI9HaqI5x%clKI3puDn!FA?|Jnz1x9Z6X1`f)?)u6z*h@@E=dZXzmpw;Nwd zFk3l>O$ZEC_;o6aUgx3^Dod78@sxy7ZXU`Vs z*`0;JzrC)0g9HDTCBo>{ZjpBLGOYR)4&ZM~?8yvy_qXkdXZ{bng~Twv|BDrA$6wYj z58wQ!w(&Xu z#HlEHcz85B-5f3V4<@sL0G%E5oMZ~RUe{Tky3>nNg=_?lHx_D{MmE!2XI$Q;w$DQX z93ksPWQse75bZ(58C}nDhLPU)2+;O&uxNY#c`v9<%D9ubVCnAy%E)9#MPcje@!S+D z$50j(7bj+A`8B?yQqV>7#0J=q-f-IhPY9(&t)FvP!*~bQ#{LBM8Ya<V=J zlHH#{q3gd<%{LDX6nCY3_&WGTm~0@e9&Z4Dz6B;PX1K#nRIpv2h6e{<%E+`UbeHeG zLXP=^4$k^2tm$)Vj%QsqK;bD;#dT*-4i zWcMDaR9{wQ?F!AAfEV?W3`T7xPatj0mjRgQj`{B#e`wU%OdM849f_sw><3bgEq=8; zQ68b0#PG_q)S|^=K!iy+s*=LPNQz^*Dpvhs|B+*0l8`B{Y2*znW34c#f$#p-(yedH z#jHYFljXtOucp@4_3oiC;u|zEF)>gEiWkp78H>}=Rw!K!ii_2B!mdW zO+lv^#B_AArKPZJj>Dfc&p|9=IzMqGfm`-%%`t&fkfxrdi7jNHuQvQ9JRLCktQ z)y_(0w#0mIonh6`Ic+jNmh3-U(qH?VfE>)M<=zqA>BhZ|rmwztK(GjlO4c3fkqLXs z)mu?%N~66^LI!DeN2KFY<6|NdU}9zw{vx9u2w&DcK%t$;YtmW@rF)aB}l%oAwRA&eEVrtO}}ca33X1$c+qn# zIxP_*p5h)pHX6FSVj}vE96HV|B9e-RMQC2T$T?%Cr{^I_k5t%q^%5zQY~q5Ja)dsa z1Lpy_b9Bk*)vcAGkOHRvNNeJmdXN)?>X7d%OO6r0^-@JG>;TG~p06QZ2^P}ZUQv6! z;NKq8`g0?6W4kA#(&E4uqaMME=;Ix?D9yvF7gH7Wz*X{IDZa6dAk=aGiq<`iF+<#! zKXIt2sE{DT*)|%s2n3t+Z$P1L|M7LCSvR+q3Z1Qw;r~D|S@^zwJ|L6~U=eo4Bujgc z?+c7?d#lXjKW||HbUWxO3L1r|!5DpDd$RZs2x*>m(;gTa8eYt-_Q@ij;khTeEsQXK ze0pyg|&JsyTSKeQHyw3LCxMVi9NH$Wh;+3DiqB04UvufHG5*49=^mkn7X`x_zJ zmV{+xAD!ozkRVLK$f)V&CYa7^%2^-R*eJ%DtQJ`RjTqXH_+L1`zF&?17qAun7ldX0 zeJ5petJEs56XPzBb)20@lCQGFdSaNl1sZgft>0DWC{~bVx`EBA_6MfQTR< zAPCPMtmA#o`QCc&qt8D-UpQ{|UVFXQwbpfg*0t8289^WrwY7(@i=Df(BM5{5g8vKr z<%M}!@Ho2g^MF7gRBJaYE0C&os-q>$11M9AjC68RIV-o?vOKMLH;w%X^)%haTOVFQ zergVC3uiYgY92v8YBxS^L2haROLIXOOc1!B$O#nSQqz=E;NYi*>dF8mEv+no3o_0w zz7AH_9@M*44ClyP?P zuyb~D7p1mcLzHQ zpfO)ga8o7Z;{BH+As^j_oV~E6hz{mM|BO(<5^`m^&O|=Vk>M#z*aKWoKjS zVGh8YU96l;ZJb?ztDjD~05@E+@&)P^=M~`od}!)u=LGyp?QUV^WM$#$AAdz z-luL>?zX_~ZWg9r%@qgS#mz$8!p)l6(H!VlxLLq2z-^q|)UI%2#JM?vGOjN0ickNA z`G^aO04Ll%tX#zTsqI{VQ38Ad7({>ta|JvAKAfOn5QtpQDk=mdxjEKIU>Al-3Iajk zKW*!~hI9JUopU#L!afEhbP=2r+!o0s)e*2bKn8Kib!io(P^Gl-TE=ph^xTtfXb<=E zNzW`~;nHoruCyz+W}|-<>(zzsm)crdn|YcG44mnjQVBMoH+ubc*)y4~8L7;mt9Pq3 z^B{Z#2WWHbPWfqD**c-5@q`%9}Hk>L1qIunttF9|tfW zax|JM$wWGwxkEl82_;T8Y_xtBIGLr>AQCm0bF?wUU=j98m>=IhOFSyTH8*;hbY!$* zN@3KB zP~wRoK@<(&0NRiA0?iBt24|i<9z}4>j-wk7i!Uj04b~w(>($W5)ObDH@RcLFe`Qcq z9EQt57VVbp4y(P=$(n{v7IxOq8)F94J>eVWien2To^#m;T(L-w{U8CCmS+QvS~U)I zKCr^|O{KW(v&QMTcJb4Xx2-0;=hxpQC7L-=Hbw+k!1_?A?avKg{9ZWQqfTAh7#g7w-)Y)DnUsTz zx}A~|2Z2UcU*2CewD1cVnl@dch;}`D_KMb1g@L`ghMA_M2VEB@RXH;tqb6S16nmRC ztR-o9dyPJ^s>yAG1H_YN$ez^!I3^nlAW(4GNzTRdy%(f!CFQ24vzMfDh`QG$8GaNi zQ}54Ge|5KbhSg4V_%Lv!?xIV>+-yB+9&gOd)mtWq?~a@v@4q|LC%=e}HA(VZ5`V5hY0G@-PP~v^Qr# zo!9<;a^oysY(+#$TT}hLrHQwC@qPvw*pY5dbXwA)a-h!fqEzAsR6#=!?0YH{j~brI zl1Gz;Vr`6KJI3VbciqryCd}U&Xay5-&1Ef)d%sV=cs-P3xQ^UKvqRg{ehT##?QUU{ zV;)joyKi?c9&s$n#SHR8iQM>Cnp`axM6oW#5DOe4P8**LcIO8uP>)!QQ^KTh#UBMZ zk??R}`CdSO(dlK&jT*WFLtO5+;doG&9Y4+8`Cd%@0j-o+*+ti?voGkbpy!5)?uerf zx^eh!OWvn55$2Bc9_f5UaBImNT&)(^lU$GTa#uLc53FB#AtZOBx78sb!b48C0RcHaOY02 zZrYipTdTWHmG7#Sxzsa4nuWTquJDX1&122(^n0h+iRj&_znkf)AB*%Mt#7eR?}!My zeqKk}$LQh2=p9X$bA(xQ_uM=zB_mnVaG3{6P(&kiD<_Xam4vDtS?h{TgrIZz9xk_$ zw0+jgn^c;1?X#kh_FlVXTSX7%jahN@AS-lAJigsNnGH9JMAmK7*GSk~2-G7@Yg4tZv_x4O-8 zb6Q0gee){Rndz;QNO}{!w^H(1b^P%c`$z)D{HMKA1HESC3G3p{Nk`lZwYpfy+KsIH z!s`t4wYjV2fet8W(^>EF6}1n#!?*H!76NuJ7-lUlYGahjVGW03pjNzk8@&BKqi{L^ zntacHAoxM($$XXSf)lmN8D)&hv*oUD2X2&~?Yt!fxf@_*?u<2r?S?_ydLchWoRW4w zA{xgmOfYj14TCjv!g#4!t9Tz3?!KN%ru%07TT<|26KAwOg=CM+yxnyVjo10w3l-Q# z*a}+@o7u=cT90z`$i>8`(yW*$X?Pm2?AFunJdL+rin!abgn`nnZNW5_aaW2;gd2Ht zTFKz*Q%RfrbIZ`f3bOeP?Ao!R`e-rJElpU%1hbl^=NK>Av4SxVyJ2u@0Aso1@j$4L z-vlKw7R1nOC{{Z1@!SNyx5I3u>|K4?&L~>p$?YkA(MC<72^e9Rs@KGHtBof;!-dNqwH1dHOEmp2d(>TM}1nP&G|4d?HS z1k!3sdg)0iu!oyoJnC1{F_N(NXVz=C!JKaH>Mf0xf)1D&j?<~}qM|<9T`0V~n8(Gu zVkzZHa#bRwnzYT1l3k``q0wTK@TLP|GVI+8$yX1Fv^Rq+cPHq2nAnv1?W_zRSU%ZE z_3xN9KL{v(VD>`6X4A(`lVQk4-5POwr0qIZ_ak_lJpcwu^Fmn;W=XI2w^4R z4O_+yg8KHMqPq2M?jvSb*j0iMGi~WPgW+BF^X<@wH~U!jBj1L&jNm?&@Q4!Tvgt^F zYhHd&T?9!BTK?9GiBNl8MVpo?dlo~M9~Vc4{ta>OzBB8N-vyD%+E?pjgnY%I~@10HU2Z6>UDcOK$T$>D*x zy9Pyun5^6z)t~F84v>-4h{){IuQ?CkpJ6m{yqw9=E7Qf+x7f{lg6;Eey!70R^fN)c z`h1zq>%#Ofv3Gu6Yx9ru#}Q#~mAKu?1$)}V{G_O-)98yS^xSxsunH~Jp(^{s+e$~_ zuibmOX_Fin^Oh4PR!A0<%kZuRS!d&Sya>wPJ-3%x&=AYltox239Y6kzJJuFTJ|6`1m$Lv*S~>8|xF#q=Cc+p2vVKhW1a!Cy~2rk_l(WaKxMMus8|Y zzVbq^(a?jQ<6K0YzW6o?)Q7QP8>2Y*hPmpFp7nh{lIdIf5~h1EnlUOE&2o~Xvud-( z&806n9CPrFTsvbJ%JiBj2QmAWje<*TDH5eZv&$n>1KEX6M}d4#x*SVr{7WWf_tkK{ zV>`T3$*1m3^8TogErqlrutKs)?qrfxKS*xYrPPE*ls;^6bH5Fd1K$`bD-X>zO+rJQ zzC>61g4;>LY-20PK&NJzI&s7WWwRZ5#tLn9| z69wjHcd`1NW%*q>9<0xm-*i}P?4R4vrGue$=DpVgLIVwm@^U?& z8^b7wqp4jUR=*C}EET-&!)sef0g(u-HyqTk3vUrA?{E@e z%V%7)zF*B_gd`F>o$jHl)dCtnnXqQbe8Gv^9!T&;8=>i1O0f!_>+@HTJ!A4*&5CRZ z^l+_RQ&HM!-4t-c$|`v)wYlm;TEBkrtu=J^QC5W!{@1SgyEZkj{+#IJJP*9n~T80Z~U^YG8(AT z(@M{vJs|bH)v7-CO7YRTC!VvrH}tbFX1>;naKXVt_jJy{1nX5DflBpeaWEN+(T&E( z>ly?!A4ufCJ!j8&yRU!9^s=FIPf;&oW%^b?7v;DixuhnmMNE4=2Fv&@KHS4BV{|_} zx+iBHb&C3q%3ISmA#<4bhL=P+*$(mBRp_7reNQL|J|Jrt8ubW5orkvWmQ|i$(g))C zDG6RZK$GJib-&?pP4N{{DLsr?I=4~(>Y{(MEA~c>ELEfp$gAKQRh*@~b*`^5jD`NG zBDV*zNqllkU-|yy`M`Li)((yN$P;`ehnLsRBxkm!N1fH2vCU)L|F|^O{m30>It~#g z<(t)vW;-5A=)1H$*>)0a@uUJsC_UR~(ZrHcs}U>E$O(z{7F!lt^;b)>hMIY=byzxE zKGyf}AskU&KwCPd&mSEwi4S~psg|9`ntO5W^;9_zHOR6te4C^rM)x=g zbuD8`IhN>Jg}$XI%CK2B%l1R3!MC`?dr|kH_p>yfq?sH)B^tvmG7W@S>phL-VZ`8R zZ4R>9Gn(_Tu9u#dT--Ot{Pj)>iY9c_{kmSWMLJMD+cdyqayVHo7*}RAU$4sSJb9x( zo?Rd=NuNjJQ{c#eR!wlr?#?n?mpGH(307#WJda6TxDN@< z#TQaMvu~htoXwSK1_@dS&L}Bi3#!%3PoPHS-q~RqP|nV|hA~G&nt1+&z=u*@Y&1=* z(anZ+rt^DGDelrA46J0ZMNs?T`RRo8PEWl=h2Ru>RGd>^37fgVs?;)S=km>C_ma z1FMeKl|_DeznDi9l_c09-il7=Y<;d^8F7!_^5`Xd)jWjP+;MTGb~4IFn{{q0@lm1R z>Vh6EPvJ;(J6ClC!gSa>Ou{;;W*dxMHmp8R6LzdX|2M@ZoU=FVZeKZcjnaM4w{>Mj z;(Qm0eDCB!koV#99F7;)rg0%Q1Vm#WXMFqpF%sn>gLC*Ff+|011ZRMs2TNbXA`ckc zXfl57rJ`%XZVc)B&~aAs@O+5)M5IbZ4i%QO4X%y*_;^!^ZE*b**k5yzYuoL9k+0cc zlIVLJ>W?3D?4hB$xkdZ>|2+*r6w=Y*lq)XD%j8$3CgIlDfl4gl*jlj!Z(8 zpO5dY7{03QpKSE3A?10tuxD4xg)CQ(k|I8{(p)QL6TIYHD(BKkiWzrBHl||Es-CoN zM{N{myL~U$W11FmZj5ISo^&HAdlRPyNkm`Qi8GZz!obCT(JEm<-c(ve85fSwiL2(Z zzpwhyRMm-tR7i{Z`n@&K*tJ5)$QVe1R`BxPLojaze+!WUq&#vRmb5w{_K<(5xJTo?g40rv3`nY=bt4VlNMz-wajA z$J~SNUgl3g9h4YOVxC+VU-wE&mijo4dqpKMRq%GiqGu$33zjvtR%#tJ!Mgh!@F68valg?_ zZ`tG{4c;4X!b|6@se+vYH3`Y`Fz2{1M~nDhc50Nr;x=JH=OPp(=n!&uOnu%(Qc!J9 z21N4+=OI5y6V_3kU#pg{Mmr`-N$bvms6&4T&0N`=Yr#TpEwxci@9KpgyJuYDR(Smy zk?V*kufHb5oL;2W;_&>65{v7S&Jxb%vhbYS;ktN1^(8|Ir9=BjZ&PW)mD*@YBD~gC zOA9OoAs1fAb^mE)feymiFvpd^^Towj+>&Dx^_O^!5ukjr)e;AqDApsA<*+G19s(v} zHFK>HTpTQhdhiktPDdzjqL^JUuS4Lfj-si9DIXPf#{S|9ZTh=$Hy=OMV{1)79&Llm zWUnSaEz*^?8NFL{O1IzLwDIz_pTf!4-kiPMebH1XM(j?t+rusk%W786$f>QS!HxLb zjUig6&TxrE`#K-1@<3AeX(#-c{Ne|-577AX?UUkEi3^5aSHEy?V1V7NW2`o}nUP>D z`Vhs-CdiwKLG_*-){rJWId$P(R_)WXXXUDJJ|263lpSVTmv*&|GGd9<5N_($py&>B zz4J!?a7}W^9h)Sc&fv93w*mNUuvhlD#d~g_iA3|3x|(`npLkhXzCHV_CtJ>M44YJA zTQ_n2)ScCd_w*?GSX3T9;1rX3S(&}0GjlK&fHl*=V6-VSGuBWmPGU1~ps>3vQGbEG z=V)jyeX3S6!I!o5&VkV7m(N8XQpS;1CbVU;nUU?4m9Ku#=Od`f^z}1)8hAiH6BkGAoq4B5emtt!#h z$0>>h`AyzTbs56{H`eNZ-K^*s! zp&NHM8)&RZHOKA}EpMdDw50FPK|Ce`1f{uFLv^c=+D*d4lba=7m-?kS%9 zEQMN3vwsx3)3c$*akyRlS)z5-^Ua4@BJ)b3+5N4rEkcUCz#^<;7g}Le%L8o37em|B z@mNa^5Rwc?Y;wF0+r%A|u4(RK)y3!?`B{+P(+BUE{Y@?vT%6fvf0$z^)!qZ5nzp(%F8-_m zF-uWRz?&l4_#kDO=2|3kE ziRm?pA4{$K@oxSgM@z(H{YUqMzO~t)rNRKW-4y+>$7Knr|yAaLyqn&H{=mw zoKqH31fq9Igp0vVp`cN#87+6QtG)RkkosHX9qA9u@CyXCOvM~WQXs}Q5CMBEhAnUv z0s?QsUqPv-ud=7Fw5P9lr?015-0%Yb@8|#Z!2j6;PFl?~j!>FiO*Usx4G8IgL!XSI za6&O`@_gECZNQl)*~I(4l5}2itFfWX`or0c+ze5c6nfsimrc-U$hAWRG{iPZTM9-P z&+HXJ+1Eva7p$;S(8p7piG*QfT(?GVZY~={+96#HUEemx>k_cfyq_!FQAVpk1`48iXzV7R+t?ddnFEyRpL3RYi%Ca;_Z}8y9#%1KlxyS-$ePtatPp~S!QDn$^5v%BKn`JKTW z%NEIvw$xm1+<*@D*7oDK+K5da7 z@GG~9d&PD2L*ISEBh!n~8VGb-$U{UuycY`To$wA~ zoI*=`)94=q;+*6K3$paqK_sx7y-^ZG#e!(EN9OuFXl{y^*1G8?(ul>h&!Zc?xjkP;#)@b(tq6J!y3_%(3S=Uz{DJ5h}eDwcgPPHVcF#I@6xenOLt7|pbz*Pyb!=IUtb z;X?yX#>IQXFb^0S4$Z}lBskGw;ru9t5cx_$Lk~iVMD>b9tuHh32r*lOptu#7Z-ItH06k(IEon;-gpU_|DY!=dfmC(~|Ep^irgNOLJSBehRsIj1see^NAYm~4 zP1>`jz{Cr31zJ+6BzcNLw8|>Mtj)vvRb0T8&_8^E4t<6~Ag#ry>gP~?6%=V#3j7ua zu+$N-^vxG2NIIVXR}qaLgYbY{2Q&=5PPQt5fH2CNftv@hsm?MfSiaIx?~6dSac`7q z@9gzCOeLX9qfcnL&r#cNk{^dOtBoP3d~mdhCqh|qR$eB(bE{2&J(W~Mk&h+%gD=DG zrs`Qe&(s-P5c_?XY4y-ts&e#f6ncE2zV}w*T^!r}b*+RRx@zTG*pEz~G^ds@s*+NY z*uOw2xe7fO!JUqd)JYTE2NS&^gpsk70)9@B@24kOMXQH5fO2!@5CJa|b0FGiLV?Sk zhVnh`24*wrBV^++n_E4q5~djtK@G*aGEi!Mkfo&2kIve|%84YIGn($hX0;Oiu{QpD;%gJg3?FV@Sbh$ze zxX~PJEgivp5?2vg-d~YwB!C81B1?VXi(#e6;7(X-KdP4|i&j z^U^Ki?$JlVjzSn-hqmCG(Zx~!Po@Gb>J9<8_5gPf&iw_G(RXzsIRdmy=yf)<1_Xqs zKx~3hPe2T+(lfWrJp`AsKs=H~1_693ULm(jqVcQWR28`dFJ5rT8 zU_9V`HzYezjU7y7jslPMB5-xW?yH8+`(cLAGs(5B@u2aVL^3J)wL$1@(fD?ON$wx@ zAH>VP(sI zzmXXXFoEzAmHi`=L|^f5Edh6sg7g3O>fiSd{1)&q!fg;3nBw4WE*dxXyWHFXpjG^8 z8trKk87Ku<=LGNu|H!+Sp~57*U^HNqnjSi`&XA?F%0J!NN`Kw7A z2!x*bnYjL2iPxdm&oN(>3chovUbPs6NOuBaR29X`P$f9?NH}Z)u|6=(D?~ibrKghb z-jkhRO_kiyV9R;1fU7hlU|7na)BYS{n*sBaYNBqRSHeRnqm23)eas-?ypF6De88xG z&>Q4jv*Yj^V}pVIsDtLpgl&D&j>zD0;1mReXHnaqI*t5@`9v42$BIn-=xp~Yl{k*f zD3uWfI=ld4LmTc#!upfhnEY_2GY=n^iN45Mygg4WD_bwd;T14zU>}ijZ^$OCtsY?# z;SD+P?#i9)`LS5VoeUNxspcAY<hBLPF!GWHVU<0$~E;0nb8J=vO`|4vHV~$bahyniCMG zl$eUNgb#H;9qv3VZ?Nka@vYVE>2*d!&u42nM%=k66$$}v?W-=wHPJ?*HB<+JR@VZ^w0H_-Pl|6+{e3VAECP@5mRECgXP#p-d2vtA8fZ$q)i(_eAm>=$(RRu97 zQYV(%eEKZ!lWJv7nPI+g`iUHSRRvC}3>WrBxxpomty3yInE`}O#q#G&1seSM2XO>B z349LA0&zl|6g7nhJ4k@c?ugb@F1^3X_`oMxdbpP zWP$GeR@2ui|J?&52f#!i(^eV$30%XMcewsk^D?C2=Ab_TfPn6(tp617Z)J%CKSr+b zqxNRFEDPDATRmMCBD+4r^={9^Z&}gkBy0jmgtMQBs+hlxNCgnHpx4zDE8)6xDm)-* zNf486L!}uL&ZW8-g3BT(l-CCG9)h*&8q3S_uFitY1>E=_%2tsnw4)&2XC6Juykf># z1iFkL8g-Ypl$AP;HQ{Cf5PlHQ6OIpp>>vJtYk>3N*#ZQ#1E0S=p}E>csv0NY=VP;h zrreMp8B#e=bmlW${>dTs{gjYkPGqSLT6uj&wREKZQa|QfsV!lJEo1`?2<^drCcID7 z%dT~Diioy(cW_x|x>Li!sEq&^h$kaiW%?6@i_yl=Hc&s{fd9>ax zQJR4H;=BotOwF(q9un+Hs(9K8#8|stnT0rZ_d*8|Zjp^dH920~tH+C?qXRzgD^tTy zD;EZQ7Oqsr?7xjj0}vCT*G+7PPIcpxaKKX*77F9C%#a3l)-C-Fhm4CsHmXMGk!jtP zhGpZF+?j|S0x3{wc~DRaewz(RI85SVTKEUTR56m^Q$uP~=%b~6sK35B#JRh(w5PY= z0}=}Ig63Lv8EKrrmpD}ttv^~9%Der?eW(|^?q7VF;T=~S#n-##r;s2svZIiWf)Ko8 zMynduO26hUc_TqF)s4?=0H(lrF+Ss^+|DV0ejXqLQ9-FQI6UiW?-1# z5yM;puY3@Z5q9#`i-l&QL1&um${!?*p~(AY zzN=3@(_JR5ol)9Rai9leMW+tbW#)DksP>1Q3Eb-N9?%4!JTefc@I1n6-QkloR0RKE zJqT_H%8laK)D>G3d)dJ+0YY_Ui4*yrK0;(k+AGwTJ+9ZW`B+mU*Q2-3mVAD;Q2dz97eGt%MrAz=VA7JA*MIA6-}^p64K1$c81@PG`0 zO#R~so~9FP-;g~Btdq675UUWnxfvQVuXmjHtb~*T#M>9f_>gw}zHp*~TmJE{fY!Zy7sQK2JT^ms#&gRUc~9jPwC{2>1` z@-$BZCWC~Zk67$|R4ryH^um!ic61pLa@|7Ar5CL8aH7R+BHU~fj@%JA@%H5gq`Ipw z4uU@uG4%l>fsjpD|Fs(NNhv_5I|TqP>Nkcg9QV^9`?-5QH~YVO?56^!)&av8_0!=B z0!hlA-OhHYvZ_*6XqDTf5W|nWJqNl}o)#@fI~rK-BV9-cUtgH>WPe?_(=7nQ z2Pek;tU&xvL?C;J?)jn*hTrr7*m=@pXG&n@QUD>e3`rawVK(8Ry?$Qw#I}%KA*C)X zWQhiWk0P3i(RCu2;g&@vu#NMjYmqyV>M7X2xaHT=e{ql&W)bz}J|VdMfIK9z2js{6 zygWca5JZHy!JkMXmTSJCUE2XPkUwPne5`^bDUciMe>8{S{!9e7dP zhB;6>+KTv+8tkcu|2B#E3atAC%*6bK+JId8r9&a0ln?+2glpz+3|BbrAB5`{xBUzM z{JTr1>Hy3qng1YGf$e&?EBZf}LwxH{3Rj>*;mC@gmxuoanFPIlefh8S0naI%DKUwD zs0WUOQf|xKlnm(3swIh6Ww2~{@sB6$9c3U)Q+HjT*u-&b~atv zm|z!PWITM{eqM)0PBocPIis8F3`8r##-+rV$kOjLzg13A1Hgd|%d*qB1y9X?yYwU8 zLv=a4t&z$y37>ah9Cb%EBNBpnY|XUEn@e|S8165UD{Fh{+p8lIDrw`_UU@B+-g<|oozrG|A<-aj@;nw}5*!|Y*|8S|l z`}K5_1&G`7e-yU>PD7O;lMiVDHW2ZTXneI zlg=P8@fx;=gw~ue79F#Js(>pEJ&zEdid9l7|By$(`x=$I!D!wv z_?vV7c>s`}mMXV>D?s}>kEnC_gFyVB75uqM5Cl?+VD>{h5)6pn&|og07l2T0{%4^I zj5Rt&yRblCNVW;y%K|++I(rY6z$^F3mAiUCFa5=t9>66M@X7`JaX= zSOwHgBUbn*V8}f{?;G{%bD5{D%fmC4P3%^?#@hKTk{o zh{@3FEsTF74I4i7%pmkhh8|~GxAWQ}?8q^+T@hl!s#G1^2+}Hrn+OPb<%s;8I8dUD$AFqSq2{EwR=!*M?DnXzrrR3=h z>;ob_4(ku>^YFw-BBqsfsVBclczkXkg}p;ERp%k^fGWdg&)UmydZ}-4Fb;qQRATU- z#w-XaIR8FDs8JMI_X3pxQADy}iFEo3TYG(lsu}jhy0Oc8<*uI|uzvP8%8}2+{~>6J zH!;r>8sI|A)`f5p3$oMst|@itw84qJmaH_w_YKXdznKUkgbz9pM}rQ(OeX#~#HW)i zAcKQHAGY8uXx~GdA9(2eUF>2+1NH%l;NZ^(?kC`AFub=AEfIy+B$McQ==IJ-Ez+P` zRp4h>%zdN?k)fHu+$U`NLyrPq9|o5~IP>R2_n$L?W`g{|xkH#gEf=4e$vPqJIBqmW z1QWOMV39y|Bp1gzg`;Uu+!Sj>k{BK;uE99R(UA(3`~NFx+H7JBH=| zQ#-g$(+ZlzSMNa(l-$YqRptKCsf$0&m&6Dry z`eVI6bbRM?XwUsvXhWGf-7$-+{;Fz5YFeZa`oETxFMaaKj|g!Ag9E|2&weblWuWNn zi8m3DIxkfVvvj&iX@=gP3;nAWpye~W;d;~dxq~Jo(<3jSNo8o6Ypm2Y;h|<&1%G#g zI5p4$K+vAC|B$%IK+#g}?U;R6#pf9H1lbd8AK=U2%Y~H2^WsJrw6jErKOgNQAeJ*ZiVDpDp-|f#i97U!I#9XfL2O z%Y#3mH5|plRiNTy*6*wOgka0ps=}O7tcX_?!KZrtDk!#n#S%Yd|5ye;jchOoSjPR) zU|gV;a39(DvA~x$ymI7M-}aH{LnDJmlT2vd-4>$q?`!;2J9aO4#pui{chHVeX;tys z0(Xsm&6Gp<>vAiXj_=D~g^!mf(1ITm0-yzlGwM8!LOhw@&m>>Xx*NPLiZ3rs-zk%g z8J3K@7bKcD+BYO~oyvN$@@+ zRewlh{uLx3tZ0bP>nnd+@UWe%;La#-L}D{k`l`&31=Sr~GJF@xaCer$b)hWLq<~68 z`jU!vPE0TL-a9grHSKI~XcMzpyDVJ^ap`yb?la+{L1~Pw@}&`*tT|qZpVpk z7c%v6aL&{l_uL;gH7{m_2X>gM|pA`x-P>I-US=g zkE|Bl;C|z1>&qcCuNX5}k?*)M@A4prGMG$KF^P~})Qz}AClXo!UAbnTygkGMIo55^ z!744_Ziv|3{7}io7HMLP;kTzFrr@6QZkEzep5Qpy#}+G-id3R{KAJZD&VvP_K>l#W zb7D>HB=7n5XrE{nV?5<4Dxsn1qldb`Q^}rxh(o;WdaJkGrgchBxvD1Qv=2v@8QuM%IwdbTl$a>F;|hBr0PXX1Gq%Ne%a^7(Z&g4_OELs%=j&>a6eXep$lneRYH*v2<4Qi zO3_)WDG$NGZ(j^~Ca!xG!*7Y}T=Pf@LZtMP+lR6%b%O-hbZQ@@hXc$b@jhIFDRL8? zHG_4C$`UNUjd_)S2Qd)at<8ck%$cu6Ir5evgH0Tfia@Z%LzA2Lu+5{r&kd+Wp1a+r zXmh8PUQ+x+O)q-_vd8(83FPNp%$?^trqqHSGt%C;=XvW~p`>AVSIRR~RB_s6@O z9>TotL$L?SR!I(cAtoV%?{C+sP%}-Qm#3dQml89pLwM7|;VfslEoNGf>ILeP2inNbyiZHq#(sLsLdXrw4g^6M`_F4Lw zh3?>x3WBI+!4o!yS2Xoa4oI)Wm&;}S2?qVW{oa&UI`f@X5jK9LIa2JO{y`n0MD61c zbJ3D@_9ESjOH5vA8t)!Ox691*n8w?pFsiS3q(=28l2)n_5DmFR#ywgPBXqjRT_3f! znUb>Du-$i;@r1SPJ(RA`=fHzQNy}7``vcDIIl^_rS4)JKPVH^ML9hbl9R7@Autw0VE(Q}nL`!?=vd z0uY{OW)6)|TkGDDEZk1mJTHOSIWLI$L}bijK~8<(zT3eKbN*rJn7(8A&5@^%*Btiq zUXRDWf6Cz5f-C17mRmDoyf!AdXo@ef=xUiKW_`bi2E$yrJ)KTan_VTENPe74O$)OU9idxU5XUzB0u_-R?yUdj9PXFV84$U+XT zerbz550_R{XKq+>eyn!5yvre{KxrUrO3n2Q0~2EG(iF)O7 z%pkQ)fhynZGmV9O*#!i3=WCNOq$utE51p-XA0A3du|c5=t@Sy`VNMmm?}0!;g@ zVt+)3U$t`WNn-RZY+{F7%i?(PR}pFNJi098U!!f7XFBB`R4B4a$xkR;42d^0N#HZL zl`rz;%*V4yPPH0^LLMdYCk}@`qefxfvqQ4Y+zG7D{OB{D7faUtuKH{}^g46V{YLVl zqGL|gIxSRGdOgs9jo##2|Yn*ynDRmRs`Z9&e-=i*)CGYWp8VEvIa_^K@CnT)C4eP~AkjmwdzXaQc|kcIIoSD&Y*UgfmD4Wk{9 zdPPBV_fD5C57skE0*yK5L2nx&Yqe!BiHl4yNS9;fN}k`u+!lN!>#6}`#1q=iG`pe4 zP2vz?i1t{n&8q4Bcxp*HcT6N@=r{r%48PISO#B@U2_K#S*>e|cfF(0-(WgjKrA0oxq}V5gk?%9bKc&bX z`hQ&jksq;QkS%I-B8=7nVvKJ_6}M|(vgRUMz4?84B;d)=Df8FXJU zZSudqOqEX-&i|eR6N0*^N`V0>^Gi`GN_cf)|36DJ%md62z)tuQ!f4QXI2QgHG7t#G zlaUXDEsYc9nkM{r)6ONm|Gf2UBmTz&)KX;N0TrkdoV$>v=B6?%QY_)l8}&!--co^ny> z4he$POgsEB?sj_{D7i@~j40#K_KeY%hzEn6M4O0(3RvB|guF&8IWE=w!&QjFY85{@S*^FYW_ zcyI79$;nKg>OyJ42-jW;@_f|#3bq{aqW~_pu2r;fOT-ndH9gFmerGdj&JB~}g*QyC zS|Uq%F%uR)l9SB85Muo>M=bxs)}?B>m3vd2h-NzK9og&XMbnVl@QEyHCvJHpH3zNz zUVF!4D481Uu2mb*Kv!@cs;WKhgZH1k#!io>R0+59eiwH<|3@=FPTUCTSX7sDQ|xyL zjGwKgKRr)=vwgRga}|*MBWY&myNa{OKDEq`{Q_QPf?eNWa(O~ zDBIIvWb*?xal2Nt@_uz2baMuK05k@G#sQ)5iHT77B-RG;LPZlM9OmhyEh>cmcv3|)evC2c_&u;12HvX8y*MVP{AnuK2$ZzL%M zv}OpJh4!cI^dLOmp$iDsH9(4=UA1xs1N}l_FbLEo)I4>|ZIVmEzo)U9y%wQDAfFOd zF0WVxnc;b+(`XFm)Z%QeQNZMWsCkDUXXYgn0`t;`{Iy7oRTK#|$Wq7|IGWPnBSNq( z<&F9bs)*GzKSsPB0zA3s;hWoziZ3BvBFyteo;uAARB1RWLN`0d7PefD8-t7_tIkg0 zypG)M{IKxx&nHgkY-9yCpxwqXLG|$6ArELC?mFD*vQF$ls!%cEkO_EC$Lu)_s})|! zD;-?aqOzn_)kRRk_mrkfWL~1JEIm#(5?G*BSB+FPsGYOkYYWrw1wQMWunv6Ix62T{ z@N^*8CK{9dER`?wG8|{(fB(Hrk0=3d5;%`^5b!0?MgRybZ#16fYu^cGBAqKWm)cK-wYOOxOlv@!F6vNX0L`%LZR zCc{|Y3PD>AAI=g_+q|rld`)A?9-dfFd}Y=!*42rl zyRp+OigOTN1o$5kfJV81^T^<`3-192A_CY4rJ-9Uu!p{hO1NQ4^!nMoH*j}gOmAQL z)9AJtagtt2*B-ogU!Y{AqapX*sefaC_HVD9Q~$PnagiTykTq(V$VhDX_NRUssEgaR znN?^49Q;{0z;pzd?BD!57li(QPA(8cMD5Sv_w!Q?_yz#Xf@YER{7ICt%E*pdhd~)h z@z?F>+vn%|s42wXGn4X`f0Alo7W}t=5Y#3sK^Bt7=TA7?BP_IVg=gF6f#x|w^JwDW z4jFXOr2oac!r>6cH~-^^Zp@WvMPXjrE>A$Edv;ThQr zK_2~;!er`fIWo<1^fdG;p#K5<#x*wv?ETZKM%RSopKDc74*By#G! zV`KC3Zr0V+_40YVeN&j3nf>(-A$()e5t_%#{%O7g-l|lJvK3CjC*R(dSA$(FP2X)s zpTwk1D}oR&&H6N9m7&uFPjkM;&$xq~_9Au#O0g{ZvN=Pz0_y36VQ-`){ue^im;S+0 z<>Tpvt!)744bBr;|2)q0`IJi{ZrdGq&AY-;FfI6W&In`3A6D}sA{xbnaP#&-YqU~| ztbqSx2ALIiKt1PmSS#+bH6x*Yc*mAYn^hGlW`y+1RjMKzX{L)3@8~i%b+7ct8rDIz=(RqCp{7855jC1iY!pu`QfjkDRU{wtJb8 zD!7fT!EVGgNMAq=gFo9_K9EOf_qpfYRD2Qhq7Dhxa|)mX+A2PG039!bKkyBCrIEgq zGL5|JbmID6uDKP5QG2?VyL>#_0jNCyRsG^JsQRrwl|zha8{TIW~mz6Iqk9K26c8{E3z7?r?G zs#5Vq1iCGMp?UnNq%OedU4dq)F8?`qI+XzklL$9X4t{=U*K5FyzYfE{dmum!v;xoq zZB_Wh`9%vrRK@yf)(UOE3M)g31MK&}wZQO8WP+J{%;bT_{JZ9TtxZ2z7O)1MDj9tV zPB7E=?{fKC_Fp~rTwi8QN7di6ApD$yIR4(Cbo`A$ z2_L(!LHTbD(_hx}MFSkyf0qWpa{_;8mNVnuXuz-aRUAbC4@iJl-0zhD_}UVXfWWU2 z`Ku*B3IGCb6!?2%GSK1oNWkZ1LEvwS$ zcPtBnpjkfhe9?%X@SnQ!lZO?6YxbE@i`_tdF#>Mfyu+3*)0qC_lU z^#Jb)!mIy_86dp7_6`jA{eJru%clQ_um86hLE=sf2jkj6R`f2Mn1NsP5^PoDf9fR!b$QnB&mIVn9q^H6WzZ(ParuB*eEcWlMZGtn>{NMlf_x|g*_9#xvUmlGq z!da2OYYoVI-^blnq&K3tq7)K$G?1Tgakr7yUaqaYqG+1r-S`XWztQ-2AH;gW#N37R z62||ljVRSBD8R+Y0-pY-fRVUoXu#0mleP4pYWqv*K=N)3oX-63nErohMjJ;XR^86vg!XECPd!fA*+82AAlhpQ~z^_0Eb_;MqmS+{!@d&V+Wy6{vSj9wGtAH zm+@19|F7_V>MsENFsFeE_)iH4=?l&)X%)`O{9SjRJ%c9UtbX>;x~3-FVF^lL zVmBk1PNsH_eU-)33gzxuWBTm^gFY|%r?WIXS%)hGltVjoef2Yjh)$`&u+PXF81#d+ zglB>l{cx*gT(=GM-&&;6V)u2H{My>0>8l+neI3 z@z-AMaTrp;M9scT#6~6W((-1VP>kpN)1m>nYbDe|aElsywd?xC2)rTi6&BMw;TA$D zW(4S}JhLBj=|t}+mspfNzS@pv=Xs*T$|neRwZEL{fIF7qauaftAXTlCT@|A83O0!J zD~X|FDXcC8XxCiWi=CFQ3K=;-Ttx&C`&1Kbtv2={T5~!yU-%Op5~r5Eh9b4aX&;| zXJ{JlY|e{MMl_#==Fs2Cx4!%}J~rY7-LB6d?8@wd5IH7QsO3dFdw?!AG>%7=Jne1a zY0kJe)ypU-KKPuG*JcDP?y4Eks6eF25t_@h^z5J^>FzMYx|b^-TvC_HGqpq7hNQm$ zarzA9PKl{r)dnd{x9G2E5@+u$kNI@?lO@IGVLjg!&-AIRzs=Lm$X+dls|ebiuvnjM z*`Ety-0fd2)jr33fFIzLZZ2%!Hr3I#b*FXTS66sF^mak;{lirXpN`3fGFeETYn;TI#{M*i_r%qCd}1i*EG-dqsjs_= zKsHjgWj+l(4++Ri0-%b#>foTVc6&54?UbO|Rrej)UUJI39g%W8GX6crv`*TnM{anw z^;Dh$F>}_5L<~eHF+=CRrlET;SKsT3z=i5q?KoUj)Hpa1mdCU{HHF(4``v0O7pM~A z{I5659tvq1>hcb;_A+I1e3Gl8CU*}y+O$0DuVSYTFO-K3a?G`6U_wVFc8dL|&^w4& zOVbG6YT~$CPlHNueD9HXBeao-abB#VMt}cCof;?7v~Y0Hc#TTQE66OBduOEO1l=;Z zwjs4`t6oOZgGd1t>CNeFCO&pP->uT*o^2-L0+tycBK@(nLq@FzZFNN^c=<4C1f*jkHV z6-jR{#q*wrd^><-)wi%(!*CRYJIO_X9&}vuFKqu>adO|cRkt9?vDHB5Y|NvnMF$jE zsbpd1fJ$3Jc`$Hcz946esQk|6E%Ti+bh-+pZj7(OW(u3*ul2)^Jh0SM4OO7MG4Mm= zQPt{Nf|y0|z8YT)|NaBZ;!|T72&4vyp=)|Fn14?*ID(#b?rK|!L1{W|n%I9c$~^>h z=@XgZ89e?Zj$ixQr~GbIX7cXc=!oroXx_Z^Q!kr@{QxCFLd0^?!<9(9A@wu2t~9g- zUhptpmiO-5)Xwu^ykYdyd=aa<*DSxs^Wbnm{oYbQk6oM>YVpg03-=$zCX&0@T8hT_ z!|ghI1ZuAxjQB!knHMY%E-=UiM)XBQ_AKY0rF`UXFr2Ixq%E82a2=#Sn$BdDL83$I zP?0Ji4q6u9L>k5Kf{GF>9jrGg7iEIV%@{(pbgGCr8G5pjW-{|T=IaBC1h{@Ym~05f zsq1j_t<)AwG&UZxUEDMf5eEb2kCPidf9^zIhsmbXqhv;H5 z_{p&o4Ru0D^-$u?izKU-K;O7#h))5+II;8Nj_4o&t9=9VlXuONoTyBJ+|3m`vy^Us zWH9>#mY{}hYgVb)hjO;rlT(u)Ed2{77dJm(092UN4ifCLH=ya|TQ8mRL{hxqc9kB* z*+=t*O*LCT&b-9{g5xI0*_-E)Jfl%q$B94+RvBlpZ;(CaT?%8zw)FUsqa7~1EB*5X z>0#PKlgd<#9X4E_M_&`K8%a;ti{_UmkSMm0h-*rv)_yp`-XF3h9{0Hm7=CepYcy0Z z>xS4DTKG+dtOJFkbTb;R#qNu8Iiv{=T#jB#7C$sVbW57`MLn0cy*#OfYVL>lcndXO zXvMiAvDUe3a+lsLNoA@6V~y{$(-mlN#H91xWt!@cpF9u^Z5X9#9_-R3fKh!)`qr=C zL7qhNlPd9sVRRaVUB>K=T~mSI1vnO7vVD(?mWJL@6lbU@+I>W_g7ZtBLl^fHIM2bm zN??nBA@3(xp<0Q8lgsVKg49B{^B%1DF(cdl9-q`&@TNS zldS%d5Bl;{ z0t-&yzh|i)UYjoILoIf?V~ceh>{ZqU^|%{XB=d8am9Kw z{^a5+LRDD`RPB(8gaX~lY{RB7O0$p4(kL$6W3NJFT&fP@q4pO(jM9zM>qo+;U@ZQ6 zHE3-AreUfaNP4_S=R_7GB6?ZII3bGOV2t>Lu?JMY~<+H`%#Ax!tWGpw^stQyy5 z!+6$PC{5(WT=185OU3-FC5$af)DpMwLt}gUXGblnclmTMF+BS_oqH@gPUBjUiqtNd zs5a-e?^`V}Kmd(J3S-CBiRM%{3gm7|BUY0n4+QJlS#0_05GJ$OxB~>2W$GHm^sI4V ziT1!BP(leG)FVK`aq3Eg>#_*K()G2+cw~%58WXlxd+(tYk+(m<(W?}ODUr-5)^{m> zHz{%Gi+s7IEP|J!V`?}e^G%-Hm8?{--qIu1Z0+oAl5hs?;rG4e<+F<1l!77hGIVoK z>(R1C!)*QW*X`i?H-mxCZoUeu(y7m5+Y{ltl3y5V@yYCa3k~=JUAwWgj?jYkRFP{Q z#~<-i(4dl6A5)IKuOE2%l@}%{=;!34%~x?h^{{lp+oCT8Z6@Ur96K+$LQ}Y7 z$(i6r>4kU5-|)laYRy9zzaH)O;waI#CmG8bU<~FlrCW|?&@JGy(N|M6!&Xh;P03q0 z90|z>zs>SCn@P^I*aI^?Kji9b3@K%6g520qeKaZQ@s64?vnrN*?TDj0Q_onJi0EZ0 z9wk%&ghNs(Ev{C1Y(3YO_O#Yzh2+!lc1DfU(}vU!_yY$UgwDkmr^BiDRi9GUThY&9 z+(D7>F)JeGt;Sokt%=PWr{C<8;R#?*Zl1@z z9$FodUcHKt)hfdXVb_C8{}J0GUPDp%IS$Tj{&O-&8H&wfb6_2&xJKCA&m0v}T2mXy zgiRB=8$8=ysGfX1(g$;J$**0b5{R#vn$^U*=jl0E^nu!zmfvO#v-*Ydd{~@)PiV5K z40E0mB@G$k7vIot;9C^v1}m_ZH{PGjZ`D#d&nH~=xDr^jdXKO#bvKf<2tGGJ;cj(i zr1VQU*t5*t3f9c$135WoL7#3EaZ6TY?V@6;23IXWt+tdfRvhtwqOeB-59?Rr>uVHg(CV_1CxVMl3OnFpylg51R z8E?A+Wz=X_uhY1f*~a>+6Ch!9_!Z%O?Pd!P%Va$!b{;)av)tv5%+&e=~v)&VmKX(Z@s_M>M(meChQ@~xH^NwzH_ z1({cnq$lhl;)(jQt!R0(P#@Q0HNEa-Lpz_ z=4?lg!w%z+X&;~IrD$PXR6zJ}e$^ZEy8Oros68@Ce#eSa`FD;~Hs@>!WKhlVLFL|u z7^k_aOpLCloR7LuunojtKLB<5!nos2oTYY9b;3OKs#> z3oMO2ZSvrv=;`&6v)*Bm>ev>9OvLk*oO^!ZJyF<>{VdX1*MluF{Mr}sc|F4IkbtVO zX|hS2fi5YD$}9<4@@uQQM+f2rH=f|$L|fPlECy=P+qs%8CAHkuk!4w_GuFCg6iAPK8e%6yl7WtF=EiVz zVYU%|Q})nN$jja`DM7FAdE+`!JC+8rZ>CwFT?NWP(XW|RwzPXZ#z!39=cE+zXs%3l z>?MVC1f~XG-g~Wh$_GX3nbW)%*$e8y8j~H=zFQ;|(v(G4x8=iw8~*5O??=!rKz!0S z@I@I>)1?u6+`rF9tN0?H5I)@I4X|hlK_%=eqR6Ui2`ZM3%~>a@3On=+G4N~`<3TxC z&s_>bXq8HaAOz)<*-4f;s(?=F6`u$<{gLR4cR8qH_xs+g`zc;QY1~=ydMium!>I*W z4^^Imdp~+Yl=l(Bm}c5_pBS3`u}>eRrY84=l$N?(H2q8o--L;=&cns$1vr_SCJQ{h4i6RH-fNa zpD71rGSKFc2F2fWc|2QSh_65qk(k^|dE+9@WvI7&a@7vZzPee+MP6pbPsXJsFZi}M z@M!d zkBagf?~>L|L`h~-^OEcna|m8adp8R5IGWF-<gTsN{Pb4 zMP{uroOFEu3r|rh$T+cU+7YZ-tAZkA24P3>kEp`c9(2ruk$qA<$C}vkEb%dpP$d>A z)>R6s?U#Eg*au%z(~iX;?-~89wC~yrrHbENr3ffQ^HbnA-K-W@dar3Aa$H7dD0X-o zRdQQmUi!spR4a7QqZD56>U=#z**l;bJuaTp- zsLDZW8^mfvQogPqJk7FVe@S2nn`M9)$Ob(^MI^p*TV=Dae2(2xVhnw=X_g|JE2d;_{xlA)Iaj$qS!bTi7;&KN zFS?|Bjxv-=oE(3x?^W&hH4+Hg?Q4?e*QyS5 z@@R+DK_9S+OzP?2<<VtnOD z8idPf2Bd_dEHY)27KTMo@LuuM-U}f}h|$j(q3f}##%9}$S65*7rqg=TNGg%XG1Kd2+!}_*Azt$nM3sqxLkBsJ9lRSB@e>jE?H`L#D(-TM7~7DfK`p(TF8wJGRj-K7UC zB8>I!ou(bY>Zhp5<6sWX>mpm+k|I9JeZ`L&Z*2zm)VV2<))%0g&hm2+Hh8&42Myk` zaYmFy?5+qqO=)DjKV6p$GlD_kuk)^kv45TI=73jXu`w^y#_;{f+`_%$VOmcuUf`t; z?0uS-xPDa0$%(9Xr{xDq!pU55f&MRM?(>IC@q@gJN-X zwc(cV?netb$jGu$Y)i)Sz_t{Z{)}5w?AB!PQP=g z%}e5T1`i#kPp+8vP%O6j?3jflRGQkUKhblcaxChKg)hrX#=@aMz3)C$Xlhrdie9{4 zJ|c0G6t_|F5{3C7&4W6)Z0H&Tu+J2$hv1H`Pq)!8z6Ny%`0m=`63U=}aPobypEIe@b}j;7l+wQP zsqcQWN8`cMhx62xlMEvFeCXJ!AVT=`3>-~WTht$ln+7yg8U#wG*Pbuo5x3*I0gA$V zE7Ei{&86`%Gng;3^fSz+Ma@!jjZ*qixmCZ-2?WtArk`7U^Se{H(Hk{Wc4w|Nk_orYdv}{Q$v|nU3_xPH1w_w93C!_p2?KUFT-8NYkd9DxI-JCi}Ue4 ze-$E4BMfY#2brGI?sty)`~(m$&SdO7ft}40MOXSPVg=AQ54uqtU7?Crww~6*W70Tk z2#bG31f!eJAdrcEEZoCr+WYc6Ro}N1_a&hafh`oWn^thq52`nGL5Nvt_`?t09d+Mq zE5ma7!?F)H&&abG8xFR;PoU5xqq&q_(d9G3XzZy2P&3op%M;7Kt~o}r--f0Idwpb8 z7Z>uaYF1R#D5p=HZI+_z16D+fKDd@+J12)Ln==5UY+ffJLTiu~Td?FSfs{$cqjoTu-5!+F!a*rlOJ(c{k;i%;G#(kc4lVEQKB zVyJr6z)M%zJ79AEgx$SEK^vC>eU;vUx7*v)OCmW;WF-ZF_vKX%d-M49L<76?4fPfZ zFpmv(w!X4F6vska`r4^S>ZrRf^0-sW6n)v6TBS#-Ge1?OYMfSrr^jG`J;NfRcr7Sa zesbP_h-KM03yDd~AtwyBh&Q7_rT5NXZMHkDIZo^lQj~sxq{cp1UXxHVgpSYd?!xZ< zPT`zd?vJS#c#B{1Plfs2Vlfw7yk`(FUNy^_JEmKoz#?_2LQKq-N?M?}Gr@4m8((VO z;aUa{T?|~l2+d^YrzZ8nu@i8A?X7Sdc1YCK*|A;zndAI&4NA}G2kmXX+F=3p=Q@tz zDiR6E!TeZyp*@jUK~zjVDW>g`s17FE%wPcyK*eL1X3Ucsl3sXvK(GI}Q!mP=ui1Q# zGPQ{)%RCuQuX`u5i=(Y3?3`=DkF<2Pu(PEXFoSA}XOlfvN9OHJUpRhk&Z`UT)+X~g zDd8fmc`j_#*%?_{734G)Nk$(zG&pKXcZ?RA=`!>}k3!05oo;DmtCdX0{s9y%rGad* zVXVbnA{8jWmQ=^X&}XJCFxat;mlWgK3{8E-h_Kn;rtv+dp3C6Trm7R|Rlsc_n2{w3<)twS z^b~?=e)>IP%DcxG!!X|OG!N^JqrL~t!uXddWqRjc`xMZVa=!~0*~4=}TDCDQX1N=#mnou{GOT1cNa*%{n9rMF8lsE_ ziWIl1Rm(7vmw>lP1B3yEt}3XP8L1mi7w3~)M9e!M1{jws zAqB(pe0%MuWq|qOz#2X6U2ESr^jlF+_Ds6&idA!QK+!i1*tmr!2;GT%R;6)_sKzLw z9hW9h;+rO>taA3`<+i~=zt_yHUo@o)foHMC$yD4P%!zm->jtf!be?f0cgoE_P$ALU zriHk6E>Y#1mko)tapBFiijJKnKO<(mcl6w_jAUW*HrCsX>ww^#WY^mt?w;eY8}8&H z-OLLAW_?A|5yDtUZ;W)D`%-v$ovb3W3ezi}jO+F1@rmU+_UY?FY5xqgq=p>qD!z^E zM7-jHvVQ#@S@H00^fUpNU=Z6#f3r2w#sSTPTsIeIO4G~rlqHw%i{_QOJqv&?sgJR2 zYbo7ZbhTd=`Mp5hc0ub=3zp^+Q|z!Dm%>0;lFu*`-zf#&nHy7|K?TxwNTSkGmM?Ic zulA}o>6sBsd_i)7L6uFCdYfQ{J_gR#`-}NDNO0hDhDqVP#$WS|vz`Gc9r@t*5(tTw zZld7E-jU(CTqe&gR@hY4JDdqUUFPDj`UaM0o~DW1b`*VgvjfZ{h8wjIhtgQ48W@)3S#F94Z8%jff17i4ew>E0!2^c6rl?M(5me-G7bwH@2stcctsDOKj0axauh0UA;3#}^H&m4 ze=e^#zvLwaf_Yc}JQRW)O*~Kp7Cz*j$H8y7wNuaiIzohNy#N57KLFr?eGSm6--`&g z!ozw4ILa9M|1f}lLSPb+U=rg$Nq_(-;^fQ8A*jKR`1@>A1wsJ&UOk4Fy~GB9LdIOk z&jG+$@Ll+m%baaw9X@IpX*2t00L*wLaN|$G{`3dVO#lE5D4f+*`uoQ&AmA&r_zgSf z4uxnU!D$`>1{)no2$V!QG-hn*rmPL%ZV=Zb5UT*I^MOVRDMg6{N8C(t+P_C7d!57B&k zCH&&aLbAf6Pf=CVX$VC(+lv@+KDWNGY^`K*Zg)~crYWM0x(koZFVLK*!UndlxjVOw z2vhyGQ_54$OYEw20Q3RG^i{d%+`*hmJ_S{~mOXJ+Qs0)FSAZg(m%y8LA@)m501Y`)pngzm{^CaCsxMSFYc206jfe z`WxCaEF=?ARY}(MBPv9Im z0xmj?v7C%>sI?ks=S*jS%RH`xu9LSjg8PJx`LviY4Ye&8;Z;Gx-ofy1X>W(W1klg7 z6kGeAL;PTeRMX-Bp8goAoM#~On#$IB*$0aN-iG6~h_w8`|G1yt* zN8`N>aeUW!vm5Af)%+NGUvMU`Q-p34Ae$>&L*B_>KpPsRN-M9PCuYTi@>LtaB?x(iN^)bO{$!9ttaAN}N`5DeYb>-blF zCOodxvOtiy5z1z0ih-0gyaCxtrjO{H9C4_W#%;@eP->=<1(<9yJ+hA<@gk<&!>o{} z-+IvJ+)1t#EHw@X+z)7SeEnjL`PncIa4yK%?iYIiC`bzVl=!O3d%RuVleTG(9SQN> zxNU`4&z*_eEd&DMW)!{L<%RjDi0?a6Nv=L`FdQ1aIFD#{cR!EVJ|vy@t-j75Gkn4;99L98N0 z{85> z-nbWX!mY_YpBt7ei%_ty*spfTiI6!nuEs?Zi5XCGF59?Bwd5c+-EePOQE540il@ic z5 zauXUKR8l-z=+@{KeKku}e@EjF+?%Jv7mfX!J^wsl=lAh=G0X6Thrxkyc zjha%r9+GEz5qs}4?cWL;O$6!Tlg6SsGe%moPrT{=5sNl-ER(*Oj6R11rH9TGpC+wm zv*&9;>ZT$dmLn4&WR|$#f)s3&O@ND|>bk>u&UGI82B?z7sDOHo9hS^CAHNI2e z9x^leZ*KQv(MQC#+8yR-fkW z4|}BII(Bq`RFGyv(2&bIOWToEwTW%WPB@#Q#_eVnNm;NOb~&!hgT)u>*!UQ@FS+CT z3cuNSrZsu?&!6araX@wKp?&HPsyVzD&b9tv;W5CMBdA9`O1UnimG<$IT0pMcK$sP# zW!LMfZgPK>XL7y*$H1>_q+~=_ud^U9qeV}cEW_6+&Wl*k_`qT39hy8ApW@I}HR}3w zvjxH&lRRAaG`8IVx3Ew7x;j~?n0vssx{&p69I1k*Lrf&3H^!H*7HYEF7=`7`7=*Gl zoHPTQ)-~%xs7rs?+rkD-apvh#`;F4iAyls1^)x;=JB_EPW_&1nJ+s`6ZT|5sEMIg#k~xwVP#9}FmtgOHFsh+bfq zB*?6!YM35l#oA9F4zf@vLyo4wd>RXh?p5}Ws-8w|^Rb)k9~W(*`0|}lNzHzloJV7=t1&` z)(a)!viEG>`Fzti&C2!8M-JVIQZG4k{GrRuRXX-mzNIO4IYl@$fo8QjTd9|%5+Uvg zmjk-zUiTql+Sd|{hlt_Z%H+}No&=e;Hd8uDFHn(-xx+Ozu6nsZbB?fMoHEpd8GhXeP1Guh5n~~9LBNS);bVYD{dI}uUp{K;xXlaxWaJ=ABoz{5S_yo8`)})BW*>LFA8lI2QOe0 zqzWTsS6w@5$UZbTG@qW)Qw0CZ_?bcwoOoOtrac|H`YeH5vFMNT@KL&ITvw9y>@=4*aBftB-C7QBwp_f4mjcHddZxb}QI=oj zeS*+67!|TwHyct(4^+PCxm_11z{Kjb;@b4`|7?>XV&bmg~8~r*rD#k0jh{?V$(CG=~D|9XC#R+GRgD zDmOVG5Jf{w2XYmqRkBFKCLj8iU?gh5#P(Qq;d8ZdKRf7mEyx~kePwpvEhKDMiH5w z{dScq z%l2cRX_6g=EO4q9*@*W<5S4XmkC(-rdpb-Y{Yn@p7!}>wc%dy7*U9OXAe<0Z?*9NvQIph z(&E6DF4UGwlbAQS<_$5kK+eY}TB{9ri7eXG=)2*166g*ei_zj~7aQzFBo`)N(wTr! z+S`Qc#?#U7ZB#OdhHNAr1!JOxI+gY=+B!gm`fE*D)hf*szwzryx>xvv@k{F=6BzXi zTokMm_G;EnD6R2N7+ud3y5Huyf?@T_xdWNF(nyDWf{*r{%#I5^uX-d})sPk6zuVb) zN9zA{RE2iK5k5s9*>yVGVQ^)HUpC5sR@;GmfhB@W$4h>5=L{*GhCNX6jEWXxF_6>d zDKRD!hKSz3(-5+~_;^_I`Ak^)VCK#Hj6@mU(Ah=we)*jF({p%<9x6_Ug;Pa3QVj~i60~yXBAepsC_3|`)1~O9`RK8Qh2V6XTG^BbWS~<(#L+!PN z9SDpZ56y>NLdsqwnAIa~;Od4`<^NbtAe2p)qW55ZQL0jRPsPBOpHY@hv>Nc)&zg=r zD`(yO9GYQo=MCt2bS36&o50S%M;muS41qt2>A>X>%+E1AyP& zv2}A9TkPzaC88;sH3LeGX;LA5@9RTVY$K8VSid0oMV8((g#@Cgo6LwP|9L_13e>W} zqEtiVjUoOcaQHp`44@Bp?6;RR2+Rn9@adjwbm-1TVgE3P008gLN&#{R*Z?j7PjqR% zXzBp~G$EOYP$L2qxw_ZdvqEBi!Tx2q!2>{$j7e>{zXDroVF|DU0AGj8^g+9k2CHIT zasPS30Ag?e3J?wEOaGJazs9tH+P`!ktV9eyZ(zI|4*(XV=u2_-+k2 zZ6zV#Oe_H2?loKl01(msb2MIDGF9VY&E{0qMccJ>ox42LPD^<`V+u z6Z4bLFTq0krC<&r097WD*WbDZMGFC#g_^lB!KB4PR)U< z2Z88}Gq~vZU&r)NZWMJX?MX~hiPKe*Z?Wl8ni^q4V?;PXVSqh zXo)cz;cBDLj~`h2D4{}fFBMdwaR`rcH+r`D0Du}GSWFv$V-Gk2;7s69 zLA(Rj0&prw46?f*@%Kp``Z%Qad1Gj(dI1Wcis;8U0FMf+%DdvBUYF2?9Tbtwf+*zX z#3cPc&lSvG_5+wJcpZN^`pFdpz^P&u7Xkp_QIWu9DZi{tpc4qJTjeXR#7BWIdmm&0 zAc_(DzT{pIJ>eyXqa73_RdR z|15zh832GV(F;I7EbRqA$Je7ylMwsL=F5I<{qwL8qF~f?FzP?d6{ugpxdJM&I9N{j zBxtaQe+RZ009=Dat*i&6HOv|Y0E=G-Kn}oo0I0%A9cM`5J+!q9-`Zl&zXJ*ve|35OeqUoq0C?GN zCDyA*f5YmL+7cdb%C>ymnN6~xIz=UcmAHCAj+tethW>smskdC!@E7n6qQC*Sz0x7L z;s{{?ns#(SF!M^ymc^?YJ(w_oa_srA4OIc6? zLYqBduX4=(#0B1MDB>$<>~A)7>LB%UiAQkN+@BiRU;c}zg_;;FTNXs#(Qn44AHsi} z3KFpuA5UBs{tJb-Lo2=z1R9VCMH;#aWgDrv2eZ<6y?;A-CrOm)(fWR1Ce+9Pd4cHY~kuWH!rc+$=lDU z0D!*hSO7#S3`0Ie5RxVM?>{?2&}v|Ouq`^K|A#I9-OkAK0UAOOEPoyi+%xJK7!Z6v z&hbClqTdDlvr_$|!(VU81K+W6{0}4aZ%p4$oO}z2Fj7spfWIUmKDcfUkOGGM&9;C* z-KuYMT(~~5<1`a)hahRuybl6E%mWj>5&&Gi0NCwG05mf~0zi%lCGp|F7O*h4&fQSp zBm@9pOMXjA_1tcksJ}o>Sr|+VZ1j%D|6%m%W8(BP%4Y|a@BEhl09m1s zfL{R^Hk5lI$uWm25)kY04^xAOCO(1NAuIwV0nj&e*ASxwauvOQo(cr`XdOCFIO`Pp zUp+{&XPUe6KhQCDmVH_kT;P&@6zQXI(9AW)aQT}tD1FpWey?rv*y-B{v{q_G+0J)q z<92m&G~XgbNshPgAM6OQX!E)X!xOP;mcO1T5OocDx<5`pYu^;7)XrC2H{oP9Q(oZ3 ze`=d1b`o>#hW6!V#$k@w!m>arf13Mnc9}M<+GlXPkmi=edUtn~4~aqU^pUH$@7##* z>?oaLORnvvxNYvKr3elmUHPG`{A_LZ$@yOEumMMkDTd4-8t+~K2YI9|u{93nqha{4BYdG|17_x;Wjd2yW z{Mb1WZ$?hW|HWRCfnU)b%Cm1?DS7=V$*nq-4W2XBNB&D$J<}3)mxNu~^P&cAvya_Z zmoVy2W({nF`|4JbnNNV5acxPyAwA@oANxDg0*dYaU7+^sZ$zm92S?Tt6*L(o=Ei)h zWzB`$tn(QcobQ4L0Qzh$vzW94c^7n)0&I+Z!yUeF(ghnW*H^xI(2HwjAfnP9s9O+}f(=Xo@<7ep)}lu=;G9V{iXPo1pQ7b6Ufo$8-&!MjZ;Wz?KJvcr7V= znRKRwm>cUM&iSfaQ1nXos&I2J3BIA+N31#CtmWpi6CZ7KpXs*)&FVVG-um&e!djaJ zS?A!yQ&dHNE27iP0iKaWjeBYN2~rsf*vSEP4EMGseZr6tdENV9SBBCmn=d)f=MIux z$L8~l{rzt%PDghw?nf~V7EquAu!-hvH48Vk8)}L-1a#>G1<|7wtud0J)g?S}(46Mz zrV>(trltBcVaJ?0=h_;TMjy2>9erT&tX^zEO;%)unbhX(N$C0H!Y`~o5=`7v5g%GsX)63iz=*z$Y zkz^PMF`Y66oCk!$OPp!Ev8c#N2zHpaT5ANc=WUl(>7Wts2Vak|=a`&r7l&O8S98`SU`15AOk_VBgx-}(SDU2Z-_phS`yGaABH;3JsI_*`#|y`|;RGv=9{5hZU9wDh37 zAr=@~v|eY}fRbvMY9W3pwEQ5wXHluhuJusQnC|~kcsTVgB!@U5cD_aCHB;7*x{>Od za(Sd#{?Tv|9WTS_JqqFR+2-|>RNuLQ`&rEDcd_JXt96}gwlfMPPLwZu-+krFM{FCf zcnAfj12Nb}eaUL?LqyvXX;JHrq;{-_c4*#%KB4AueB@*#FZ(3#@4R&o1lt{wtT?4N zu(ZP`2p3nt8uI+vYSoJ(NwSX%ngKo@PlcVa5*s4R!!y77ZP=g%odih>X0F3Cb)Wmf zUV2-Do?Wz%01PJvEno@@U$j2FdSergF`aM(t`a20V*18gmwM$*C)o*)ZDG?h?jkHR^HJcsZR19vGuxgN z*X~%os{7m(V?IxDw*l#XX%FZ(vaKJQNA0$cF{si@D8n(93oyLcl*w!_~V|$Cil)kPrYMXU6pXYdh?b zoJKExUNGa!d?B7Q&e0U1=Dg2&ykB=!3Po==KVH1!z|K&7;+%%!c|$ttgnKR2851iV zXA8Y8P|h!^V}C(v5D*3|HrPRY`iJNG2b|@8Y70YLCC9T;DEwc*A%K^Qa(;^?ia?7$ z&xJQ1%%m2~agnzpbb#!1!`&IoMiUCgQ(-I z6nXb91pLMxw|pUx4?0VJT{a0_EMcN$?xxyJFPIpxjRv->vi?YQ+CN9vq-He+k+PE?Z#3JE(R8D^&0@q z$We7zZt;ifBUos-9k`*sz7J1Cm&V@>6#qO|)N?S^K;f)s%768~>7M^kuLwkf$itv@ z7?QI;^z(nakVU|gVEfH9A|L?he~-kCF}=(v74Y}&{4!@KDOwPpk-DA8_xY&|@xBdu zYuTD`zsqALe*HD<4&R-NH37SDB1@kX0b6yq$AA6*0a`$%zc&+o1;H2dgLCjNwj-_( z*FRHwHrmblmxZto-+JW_^e!(|LkaB-Fm{n&B+g;{6F@43UJXu@(^XNh;XECSvap~}MEffEOZOdo z*Va>G&LA=`Km$T|OUFBTU0++0)BmQBMT&Zl5VAP$6P|^wWK+e>8D|X``0H5fL-BX1 zr>kqN>@p%F+IPfi8GdAd0096o6XT4z#Oy{p4!1j!K*+Y-R3&w;1R~9LmYRSzOyiBH z5T^$OQ$e0Dg8c9<(g(m1Uo}Tji)2{5cklE0!Eq{{(ZSTMlxNn*XD3Uhis(0&#-%H+ z6p3Kt2x_Bhuq#!jcE9A^Z~$1b9n>x2aD)>!p)HUtT<^ZEBn}oBJBWhnT8QMxs*%5`WC(H!auQ~+`h zx@6k3eF`Z`eKGl8Jhxex=CUcOMa6@*w47s$FfYl?yX3!Y-lksX6^{u~LTQLB>}T=| zN>}d53Wm(0wMhBB6Oc%ZODIsKDOM}U3?^iJf=Rgoc(gh}@JEa^lxuAZ&qOxl7r_15 z8Gcte;pCXZ*y^@S9&d0?NCjs{bJ+4DQ$viHvrG9BVEkdq>OvlP8g1cDL~P4+!v#a{ zS@5>M@|Vz4l(H~wXf{8CguCSh>Vi;yGkwJ2auy`-K?H>d;}abX=LS*%;MC2n`XZm0 zySuC`gl-IUT|~DDXCl5V{yFiu_RV(Su9{(of|6KI4Qd=bshlbvy0kiLjCzXQiZ|Md z^>D=`Kif-Dzbs+4@WWx9sZB|e01oAt_7iBPdfzpb{Q~Nv-gfrNpg_$@@?y7jTdlXT zsLpyu({%nvX*^&$9uXpcz@+~iO4uYQoJ`uwd~J*@)6t)%)mb95K!8i!@_3fJH3_?( zM8Us!E3P6)qKvC(`_?7W0wxzT${$)E&y^FahtY5>$5pS&(0wn72CILcBgQu{z#s`S zsIWL-$4e2cN201J1E{?ATi^fy1p1Hj+)oLg=%cdG;pD{V8YZmfheS&lYX2Yr+H>3P>%`@j5ovp$7CY=51lsXe&;dNpZa*a086V?J3|J0wVvN15g zX|Y?q$trW%XIC)od`6)sv{t&0aMz+IwCKs9cUXjh!PN{90009300RNSC>Up7#yBQr zp$@mAbk5I#z9LA=Br^`MypmowkHX(XY}8u=y;#E<@aMhb4bcFC2h^R4GL314&Y}@} z;JAYr858TA+U;@NdKt;YHc9V#_Hxi}v`cyF8(I2iC__RsPl0zFwzxRi>dq;iCm)n4 zS_2)2sCAw&6_IrX`U3iSIyrea^tJmDF?%z$RHb$G8VB(TdgNEK`Qmz=RZ5z+*j0sl zC=%U0;>eN{n+Mt`3`qtECm>G4xHu9 zms%@!9RA)Sm9T{2h7{y8l1NT?YyDapZTRf1M99u_w%YetT<v%E~`^;Wu?v9dr6w+L9>5_So9pymb3=aLy^wu?rX9iSe(3E9hiITsLOE+U_z3 zA`|gbsBz*L4X3psm%^**g0yd>_K$AJ(%{FCL1l;-^HKf;OEOeW+E3|+A zW+exMUuPghjeHKdaT5QXA1laO73Ryb9T?=amJsfV55eaV;R#Nfh8N5 zbhROTE{k#BSLXzRgKjl!%|`Tm7j=AxhzBZyDhM#BgIN0pWua>+Qa0p(1=h(IjU`5` z$_gOlcW9_cIC^$zWex~{0YU44v_^L|ryb%iU5{Y*_y809z-nG&Bm&v8Oe{QMgb0^hZ zTh)AIvueyo8Vu7+n;GNZf&6y7pJ|*GPmbeW0|~NtVLXh5^jri%X?~w6;7`b zmsP5>XoENvIU7u0c7=zrCWk1Ny})~@h2y@$zgA%3)Fj<`(&O(Z!q3=L)) zhU4nIYUh(W}Rgdo>ul|Oj(cL2Iolr~CYjSxa7>ZxacG&BSR(88DaQT>} zMP(Q`I1!P=K678jkjb+J9FDKXt?(GSZXY1$V$xW3Nv5%-hKH%DMh5E++c~O*Y`M$N zYuRGQIaHT}NgK2;XX5X2Lr<=0J|0=l*Twr^&wGdK+3xY@A|H|$nX$#2`bM!UiRaGs&PwJ_FCQ!?#QDb)IEVM!`yp>@LVgvPU>Z3gY(KKX1mYTJS-hl{}gA8*pmZE;0i;GR|Q_ z{+eyb`-%$i|2&cHjs3eU(o;&`VO$(8ib!d7$9`qeph>8?%go+;SeMWM zaw=2Ngs^1Cw?#?kqO6po{A-ql6*M%aHW5+f{#dX}tuN;;M}@4|BmXtt0RtW_OL3QF zt4CFOiX}LXOFl9S^v?sn#uXDaw+7;WoLC?iD!@<Zs^#YB z4aKhvmi0B>ffC%!*HpXK0GIJ6i&@#`_Yug~cI!INFox?xNt*|}Y*@wP6HUnl#JgFo z6iGTM!R_@snq60`FLGi-$_i@-m=EMV5P1S5j^ZuT>*bndTsTjHI?0aNq-iO+QGfNz znof5^1<@E(uvMegmY=%tJZ6Ph=HeApsb*Uc24>H(Wgq7=Au0TzgxRn4R(DI_%a68XQVJeGACIWXdu71 z$ND^o$Wqlv`x4g|p^|BuywBep)%d<-zIapZtpNlb6PT&L@@$2yR zdH{|`j@Ah53{oi0CO$Jz@r-fcac!&q9D?Vl=nNXJjhj%u! z&pjv0=D0@S91lMYt2n7fQ|Xxx(b3|J5V7W#X^4`8N0rLwJ_;Cn=bs|SzH;b|#6e8h zBOL@gC#DHvyUby4{MKcV!a^GF)PHOAG$GyvCsO|2E&u=n00Qmh2hy z?}BgiPIEv3r_Ef} zcCO$v3a1j~a~FrFX%guXqaEcapxqa`%{DML`~fFj2N&Nuo`x^ zJq9YFklgf|N{2WWDbHmt^{bH0o*R4lrzEtEpnlz5Xvjq5)@5?{8k9aBwA$9zj%s$}TT{Xy=~KbaocuSbx5x zVdM3sr&UWK6nR__T~26~J4D^B?D(wqhmH~>b=hm*r{`f1?(q5v`Jbpx&qTsIAFBi( zA^Sknq?-s-E{i)jX2qd6_)S^3tDCdv8OS`cc2Wux|mft3>1S$Bl8t) zronvd!nm0RYZiTb5k5ZBL6E(zxMDe2W_exduw&%Kpo4%9K$vLbl<0gi&C_gA#^=DC ziRSF%w+?Q0A?_HV`Q_@97yzHzx4m4A+6go^i#{4PN67XJ^tEN&;JT)Qf7Ej3*C5X@ z#u?&n>^q?blO47eLuS+a*%<5P!qMgi@nL?93@WozeN(P zEr`mChP)045$}Cj#Nq6Eg+#Q>@7BbhAikUwZOM}RrOrnK+Mosb2Z)iYnTcV}A>pY{ z&WkQrs2l|9PR|F|%@e7pPacP52)#?Ei+SCHZ3-&?aUX7YnIjvw*kdvA z0JCos)0HNXm(eTa(9wHHujh}{pXx!|fJjI0P;fyuNbiI`&Ba$1b?yq$1pbG; zkI}~mz>x-OSjdzPY<=ortf`5{{YXPcWOd?#w|+g;j6*t~dL>ZYkkDe#;xSwq;Q{`_ zRbZ99jD_dcG@a+}szmx@Vs(d{+rn{p!$JaVDwHLA97w%^0m4w08p0Pg5{VG2E+AgW zZHCM?YLf#;PEC1P`$(nk3cL^=vZ{5ft1=m5aSNidi{lp*V4F9S;uv{-Kx9YbRMs3Z z494Q{m#6L>1LhYBS}E}PpVId#3FG#sFa?TK`bS&Tgd1{;&>!j?`Rx$rzIrGumaO?( z>!sYo#FaFhnyYybV@N9Kv7P_>AuxND?i5E@zBh5dqcbt1DYHD?00;q0_*`qQW#-GU zW&=vo0o59+b#c?(LVbqBwSt4`Bm9^|6oYkE6`Q2Ag*sX8M3TrfQvQNz6<*#FbBp>n znj43$W81|kqBAll98%*JF{irE?br^|av>(0hT?j!{WGtgHB)dO{FU1m4|eN?L!DVS zAB#u%8JNGlx=w`lADAlv4*O_j6Y)F@`-kQ1V{k`DaCc~0cjt-Fz=0DJ-6X)62?b#D z!RB)XLjf38K>l^`Bh=^5-F^0%ruqAKS$samb%_;U0%TaUt;JWK)rn*5LkJ~Fpa4$0 z-O3*+@d9qC5w6yI7Q44Sj|miE$<#5sF&QCf?kE;3uw3Q}g`GAPPG2PVulp zX363}fIUSDDl6UV!?SgN|6YBo2v#rN>Amd2i?bmE&+@xFmzioWNrt5S?r+CD!5?t| zt}S8!00RI3HypeHbn#Q8yK{2~(NeV3Y@!oZjC73CQanDqkK>E=wD58Ta2Z>9F%}iV z+-oeaz($OiP+S*bN8hENsY)+M=jv(@nStE|Vz|n79I*V8rbZ8r4d03C`MDo$+h3T# z^DK`b>#i+9W%!WvgXp%vehuQ`#6Z=se8@hnKsYcptSU&Ya0YStlKMfi%j)t0rgz72 z^eg_KT&O<-L1t2_f4ypn%cN9E{ORg#k$<0$3qd;T-jkpxeG+Mg(&VBNpRa;~8HC`V z+n*cj-X3QeK|fOAi3uzP0{KYe3|@E@ECb;IBcDgsSh7?G=8GW5Dqwmv5xlXFa?BcWwNkk248v6VPs0>ecop}VTYyjin)p!^N_ zu_wz3NRVq=5T7pADsN%{D~+zFvkt5jN)j#>E-m4CdddYX2!zQ{Vw@~HI+z>A^qT1i z>Hh*_@^0CZ3_*25K8`)PoipSc4iuHE)hQ$4;e@F|wekW2)8^nb)9^5`Ijdj-bSb)G zY8DOy?RBgJ;Eu+-{(YbjcLG<7b88T=%&L=%2|bm<-;n$RWpJX=XQlfVG73g(?B}A3 zN)rco2mBR^#|Hkx_6W zTnjvs{$-VBIT5n{?35eKoWXd61NIb#qOX7xmStF4Z^`Y69A+!}&r6pN>=f(|i~ajM zAmJ#iTSaP?WhKfp1bzHHS1lyB*)GMxb5}BZC})Xkd?Gc(!r@aRZ#9_=_Z2^_pFM+u z#J()D%&zXMfsYm6&=tyaK=KKgBhheTR_?np&18@{f6K9jD@wa^7L#aoudF#T$qV$k?-8{H6gDZs~04P%|^{a$;qr7b;dd&CqvLX2XzQU1^)3w zvw}we9!`+4@DALV{reG`S5&X^q515Mm4B@uwm4Np@!ORHp2gX@I8Mp%r@N;NmLswd z#HT3k;CFJ+Y&J+G{vKr&4W{H5JMXLZu#1C0Rk*eOlJT*p=8(D(tyh1uWo0NO{tZG^V0BPrHJk6+tVAKr_Qg1*BOW<%HFCt?9m1sYD}nF@Pa6CB=(IR4$U+R z8dYsTccI>$)M&<&S|%Xfah{JgV+)Ugg{cba2p4Lis4`Rh_E>j;E#Cf~-+_Wq>LtH8 zrv3Y}Fl|mU5H0bnX>L|Bq|pW%rSQFowoh8BBWkgLhqyo-s5%DJlFqFjHVBUj8vsJ! zo=QbNrnqGMiU459U&B^c7w2}uwuU>4;paAR4Zmhnk?7|Zqjkj;)b*W@pOJ!(8I2&>^C0eJ0~SrBB@F-&i3y%~(Uj9y~rwLZxjRtWXpftMTr*SAd^uX^3k?bT&{ zly3qQx9+0r&QxorQAWklgb-GtFq1Bh(((jX*9Dn3@&i)^sbl$3Ln~pEQTu9B{O}JM zN=cti(#jOoLyGW2FRZ%d>@n?CL%&`Da&vd9;zR0+k#0!Yf|v&`_G~kix2>$_E^{z8 z6)E3kF9*RiOCqH&b<#a0w z6awO4xG8Ta>X$F{8VDpyfHM`<&*ET`vow<**j^b=Oea|C`_7ojDt5}+aKEO4uka&y zRNpSe0-f48GB@qy4oo^@r}^C7XHm|{n@O=W*$vpm%BOWq3c7b*>y(;O9pone*C-`t zgW8P!$+Bs#C(2)zjQwk#!J-J#@v&X-cmMzc000R~4l8G;*2XJLm5za@7(GyD644jN zoPMj0XJqX6U2eRs9(YgOy`rE(21Qwk{8fL)9V$j>u);Uv^3x63G<)qKAE(IG4nJqS zh?&StG;U!t^+E{qDImaC7A0Qx$_#JV+Xg-!II)_+e)uy9=t$HDZiXE4m@US8MSsw@ z>@WgcZ^Z!8&|L3(PXRKBlikm`3`E>Tm4AP=ug_BvtX}Ox04a?gq5-ym< z(Vk1v_m@>Fa#o187_C{!a-|IOj>_)r1V_yoa7MM1NCzNi3NDWR?h_RxUEfb2|a2Qnu1*q*$r4JmV?5T-u68 zxcH-QWG;AHYKS5=8_7?3jb<#%nmt^W*5~!*fSn|KNTlyMJn0%$qAHaJGkRIf9_R+K z7V~R7;4qZ9D4kZ8%RK$wE=H?PVy>mhL-VsYKnJD09v--;wlvdm$gBINSijiO&Dlvv zT#)6fQR1M$A?UzN1jCN&GK#FZrU7cnDetJ0Jo!ABJh+E=Ya-`pi6TVcY?3t#PqWD18V2F%)(9%T&K|#o{ z&;Jww9h3(@NhGJZxjGaiv(3^pgQqaOzh_nX!}+Z0U>U|Z(m(m1#n}vul`o5s_|*Vs zy#>qQmE&K@v3KRY%RCOYaWP6>qE>s^E-wi9;ePObHaUv;TC1znwzElo0HXM6QO}xHxivT~oh>We zl<*pT-||@$mJY^{Xp~$CV7w>XRt^qfP+rC6$bbo}%ed$fJHOW@0WGXD2-hAnrgaf}^@us*Fnjer7u#X@rSe$SIonO*d_w6*Y$XVE6_nH&?i=Z|T zdZz zL1A8-cx4CiEG^b2Q?xF!H)%N@jM#J3Ql@hi3bP#LcbyrDEy}_@vZW?(+~X{P6K9F< zc@aCyM(vKK*4?h!)h{Aa)MdkjfGV9R@hLBj0$^by3uZto|a@CTO5c{Lcwrui(~A86;_(eZD!NUvJ(#j1sWo0HmIOSB~EhY!0|rq zm000a1+r=n}apYwo2~MZF9LRQ>rinh4 zRty~h&&=jpC?C5626l1!7e;_YN7(X0Ma-I<@TwVO21kl<{_fM^^eJy^(0yPhMr}@> z!qGwO;}q|UW}k=cA7H5I;oL6BI0r+cGT@`H%YMQEuJ zmLb5Nk`!XFmG@l|LqTw39c5Jlceh+&QRTwUxToW*4!Ogs=Hpn8ybDpj_V!|TBpa{$$TsiP)2=XA>nL~9Zn^btP=X@+?>Xuig#GjPzJx42n z{-{Mj5Mv+Bix=4b-yyykP7J-l;p!-2PC>{YMz}**S0gwnEY;OqB*8B& z=u(+^eVWE|#x$%#ryQEChJwnZ=d`kGse00pc8v|6BB)U+;!ljNyGtScmp ziPbI&2TxZ9R#?AkjyxYp3GAK`L_5L<-nzKs5F_MwYV;60VFcB3%R}U2PB#&=dbqN} z0-KNjU8y%~cVRp%R@L2uyz@5g@Y9w`*y!0LFHE!4;LzL=+*-7FH6im?{-X)Z(%?Rw zZ1fA3YP2tl55gqfG!``BILBBfcsOHvmsOqL#*&`+mXWl?<(=UGvT2S z5#mq2WXMem2wy(&avu08Wc$F8s6JQ!SmCWem@VljDoEN%_%}Rh!SzzBvs#f^cF>j) zXpsUKa<6K2w9Cr*=E9spLvMHQTApUz8b?eVtA05UK1wEk(YEv5q$$)3I&C`D` zYZxJ!r;}CXOwdpSN&`I$M8wVhplVGSfVw_*Xlt!Nd|VLOYpcr%@w8Jg|mOryqB4&~avtiF$jLd>M))7a9?eI82>y68P5!F3p;<5#} ze=S-AP052#eaDh#O12{uRuJ0xMxgM={X!B|{+L+lX?1Jl2pwRA>v^zW-w2W}Zn{Z&(pym2CGS$M5J}JEAGOZ zH!KK`)Ud(BYu|uq?^FhTHP~ySqftrX-Bms|NfZlcr4$#*z&cWAUL-2AX4AJwaJ>~| zO;v^pA`GJ)r@(?Y-)DMDoMcF4X9138z4$>#yoL5W^fmzu)_4FvL?ssu)>5v^BvW8L zwo$Z$AiwRH!JBgf=ICQOnG#%LAf1hbrQnH|-;*YOFDc7YYXp2(36>#MtUuQ7IUHyKsFOY!Si`b$_P^l&{ZM4dGNavrrs>R#^Rk5?JkDRkBg zwhfL0+J7Z0aQzbyqarHbg#{*(P~4_8ua4R<;`21=`qZ|1>d?~YBp;wqv~7EuAPgDC zz~M*Q3j3(|OD42Rsn~E7$L0O0m$Ufqi4Y}yX=6=$+@K&Y3h;53O6|N=_YC4c$tU$U zYlS@%s~4-@FJa7{<~&~ehWIQHIi?mOsFe2jTivR{S6YMXkPWJTn|^SKx{WjT2$=4| zq=*QdYkCg;=PZESPew`y(g!a~lJLlBu&}XH<_JzMzVsZ9F@<9b6$ucn;?|{!U2)m; zpKL*l3{+K|I>`b=n4-<*=54W0wXaVc9*v_3C<@GFY@W*SHsRT8ZTzJ8$pw>PuOYp* zQu_MtF~>ro&i2xOi=^ZxO-oetjkyf2VlHY{R){6^USgbgxD?SuHp+z+W9Z>IYv=+l z0Mcv#0IZCOo5TxFSd(k7LSTkHWH66QydPA${H3y*N3acYhE_bO;N?P2R?jA%Pa8T- zmFBClqDK81!Xi6{);u46h9F06QI=qkK@s z2;oD)M4x#WKmO41Ujl=_edt*_zBd=a;24vgsle44;dF{6x%?qeA4d_8ch5CSON9BQ zPQB`c*hwS}oc;Y2VSB#Juwu%_5h-FWev(~B0TQv?{l?D|Gz z&5#6m5O{w`zZB-KG@`nYIg?w}!>8RVf`7|cw0WmV@{~b1_%+3!#D&eX3?z6NN{SW# zJG*}}4X*#XVC)RmFdJX2qTps!1R}4yEyOXV`HEK&;l8N$7o*$Jj~4; zh1qw$%8ZXKso~EF%cA`pP_C{jfcmK5y4RYyKzbjRK|#osC1l#KFw@5EdVW?M>rqPY zVUUns@Vj#?fDDHF%? zcuk{JSuy@ry0GJ%LPaBDuQVO~LdrHLo}2AB(1jNDmT^*!UoSRjzyzg#2b|0a61t{A zB*RJIIW+S1B~I6OskzRZd42u>x1Btg6nUKBp91YbUDT;NXN$QAb;5%2R$DwtnW|L5 zwd~{ROQP~Dsihn@)(BMkG-TS$Qqp5CH&(#>rwt8xbO>YKZ#;C!RH9RxY?LKS7w89} z|BX3I_WN3Su|0`7bss^ep1-=@pw%yZ{|N@xJ^;C`krz05Vr?>*bs-&sy~V44cd2@6 zw6I0A+EOzBC_J6?#B-a|z)6#BOgPDh^Bip*!5g&ZAfEB)raPnt0-%9jhXP&82^!VAQbtWjB&g+!ZndX^kyS#K6_@BjcvJd3YYe057_ z!{FU~?3rd*f98-xdsAkkuwMgF=7jEjx*9*UKgaH)=C2ULFK#S#HvKadB%`<>d*mF_ z;&U(oK^gy5fG+TVmBNk9VfT&X78+BPNbS|4KZ*4*q&pz<$ zU;kstz=LiSx6cvHDIW|lMc!>I4=f9wI$a%6VA4dZ*-qyDtr`fZw`1@nECR4U znQHB~Px=>#5Uhwxpk4?At=%aK84CGo?tlORD+Yi8eyOOD|Mrmz=egf(cavpD&Dysp zPNhxgx+B2yB~OU6S{*n&5=C+XXZ5*BZZX$>Am$t%6``QUi49@=mtDHy<_L8FI;of= z_tv`9jB~uev0X8%K7C>S(S>M^8igd^ZJ2up$}a4UK;4FTdZaMzHXoBwX@kIzA(wTg z)t7(XB@Y$@KmO{b;DvD+6BVr~k%P#_%G?|x9ueqTccu2UybAqH*WgJwZPM7y3Y)i@ zK~SWvwWA?@TBGWteS?)2jd&zn;cJ`a+uB>^%UdBzO{PqQ4gG{hHqEsC)|gkiTR&Q*b+(0l-kwbez(M z;CkdZ?x~7hM&>@**PnbwJ??$+0wVK~K{QLtE*wH}dGZcBq!)@&-8)F0aA|s@?qosL zPM0CplGF`!J|wD#J&`f)-0FYyS(Sj~Dxp_F+1&X0x}mUoCr%YnSJrz_?k_vOPTtJ? zKDbMGOfGH^Cz7bfMclGG9|nc%U~zp%`rB>I>f0)=3Ek5uh>+}Fb<~E}pXJlRA?K(N zczezt9{5Xmo(1;NK?$3RT2s)ggz#O}9DZ@J;4rtJ37d>58Z$@g+JnfqrR7m%G?`4R z4fhvB1-3x+W41T8dFRoV&zj~s&w;9Ix{b{$lLpv03eJK^1{!_^k$KCUJ4(dj5`bzs zBWncOJ3`g6;yAJZ?fRUur+Ezr*RRO;HjV&uWe2vAXa9bK-Spn`uw9k-EA zypPy~UxRbH?rdOjpr@HF0z&%jOaLy#azm{BEEGp_; zT3+2CjNyf$$U}vJM$BK<50ZF5dLMAfN#??Bo3DaYA!(pPDofxP9*(e-4|2(HiN54K zz~RJxj1qKT78voYfw`IUs;WExO#Jov1V|+Ppbj27kMaowHr_DTh^W1Z(=fsymC2D* zZaDF%TPKL3H~*P1M`1`i`-x*S>|_Q{`|q@*!2eXKIx}5q;s}X-^bQS#M!^#l<+R^L zp2aK77b&S^ko7r0uHS8-_dl1LYT=16&6wZgdPRx7>@8lYf=^giAJ$Wy@RP^0Jxlmy`Gtjs3==Koda*A{GZGW*6 zd@>AXM}ge_p_~Nf)XE(!ls(&K@pSx=aZND7FCvwmpC6VC#vvuuOApXxXqUr?;ZiO2 zuGV`Ux8Jfb(VgaWYKKzCdEknUxsPb%ly#O;L^8{23MdWnxs&ap(*X&)I#ixXSg5=G zt@;D5gd|}tRhlb=_Iq!|L6C&tqFC}F5hB<`4!^XTq6ml+WDlMg_b7{eS=f1kI{^=1CGgkKZWLUn0(6B?$ABrKP8u-z)*zlXheLw)*9- zJF-1<`;Cy4HgC^0)N^DD6EWaNyeS-B&5fH>Ix8U#^sa}Y%iNJ(N2DncJ<||Nq$bi3 z6e(;w_JdwNKa1)CHr+jC_z@h2Vd5Vkwkn(#w3A`RrWC*B3h&A}WUM)+F#gI+NM6L| zl$)k?WD#hvI1H|mc8TuSEXyr;TXHKT z#M@Dc3Fy>pKF%sW5a7D+F1FH>YbKUbw*x8P@;?T3-47jZ`TvL$$@GZ3B$Cq(Tp6AM z`7|i=^Kxi5xDrtm_=QeE8rBOerK>5TLjkPz0O!Z`PphJcg2RQ zvJ3x$^eW1g33Wf`fmqF&~tboqT#l?A92Ts%kd&#~mN9Ud`;) zq^$NxjWZm`#mDQasMZq{V~>VdPtk?zw!!FU%SDs8n4p}FVFxA0kFNaTz40YUs7lkL z`yR7~!lSyFUmeBb1>k@H0j8z<000jH6JBd_MSBT{TM1NHV-p&!nea0-DT0tYdN;%! z(R*i@Rzj=Zk52Y`DC43mcn#>EexmTAP7Yxg$g zqaeXlPnR^5=NVEc_PQ^?K_xl7=Q_BSpVWx>Hs&wqt-Uv(8xW~G>zKA zWAq3ezyJY^;s5|Cb2LNfroEhCR85H2!N*N{V|hcvp&i&~v(=qiVAG*Gzh~=JxMW%7 zj?s%SY_v?)X`auYvKy2(O1@EJ?d}ty5EX)7eKFw74W4dZmGYv2*`K@sI^f zn>qr(8U+!aiv$dt>Ghb9HhOuw1~_osyHykMtK3{P4vtd+mYs0_Cb#>fRLqwuaP}dg ze0}4(bJHF({)gu#+8xk|+lJx(c9!)KY%ZJtOF-cPoo!Vo-1t@aHB2w3xe>;{-39J5MG!FjiVwp3;*F;Dggi~6#s*} zs~*Ageed%7#{yP?TOtQF1 zs?eQ=CJ~ss7tK!~clK=ai#=@utw;R69*EN9oKOnO_LGurYw$)8ou-;G_gHPye3zfb zwjW{puC`Z!i{g2fmFL{Mnc*&BaGvCC0NcO;FlYb(J<39(?F|^QvL5Ub)PgKz(D&8^nixxLiTERkFZ(7D|k^EDDdPRAjMu{TW^^0s-Yi55b4VJA# zR}vG=x7jseW}){s9kWCzx$vdB%3()(hB7aV&q-mOo8Q$f21IE{sVP*L!2={^Nc zL~1cyTSDZD_5kde0x*z}m|AyBQ2v8p`QS>wD zrzNAodQa)lOV$?)9ZUAWbq2iMDj(Q+d#Rj#=Bbklgaj${%TNW-pO4-dY29TQGE#Me z`9FO#h!(@p^oKO9!mY3gn{m=MNga zf2=NDk6;NFLCzr!&nS&{2@hn$Da$2d5G7z_&$rhn#HoWPM?>_fC^1nw$u;ZG?xmxV zh}^y(re-lU_hBI#K60YRcS@O1ApqMPxV-Pf)Xz)Aq-~CxYfulLt1=~NjD)dY5`J0r z;T9CHJCWA?8~8|Bw(k(eLCCH$L1!Ueq|QzJe5=BR~ibySLE|8FqUdOVx|v zQKg2r+7teu01@MW01KkZPclTdy=B?YR*%Eh`PN0#eQ#;xl1a>Lop*PX6-UXHB;5g` z^9#Av)-vy@y0r>0`fe>VIFOp_uAVxkKb;iPH6SfH;bD zzDx=R5u>t_q(C-_dJZZe2)1^eYpJa`f5D6KidTQpiYj$j{i|U*# zM(ntyLjzy05O`Sin&3b#@wO-Dawc|_z1ySg$2iQ84Xnb)IQaiy?G)O?TaXkxD8y=G zASbq@(AMT}`c|3T6$^4#4|Jc(7#gctHxC>>+hOy}uM*Uj^p8R&g_roL=TnQ(s~dOP zF5DoT;ZRQBHz=ygnWf6>Sj#vHOXNrZ0B>Xf05&)|RC1<9{NgzLFqVa;2dpUx#S&Ow zzZpY=tfzIP^f`k3?SN#T@$JbO*{%1cUBO=%0x}N2ut>#r(wZuGh?!HS=Ju6bB)pz=z}zEFL}Jz%z28IP_AQ7ZfhIvQ?W6>g$7hs)ei#2N->{P$ z6`I;%CfzxU%=JRD*m6-1H#ch^3aBjt004UA)BpujD9UptK7^ZbS|jml%=!Uzg_;^PngQeu4ty=I@K6A6XSJ4z3!NOVF#_q9MI!bI!=jBD8|S-@JA8 z7gsgGTJXI)Mn&E#61ncn(myR0^?fslErm22+~^<0nbdp~-(;>S1`mZgOJ9ci?NtWG z{5BHiI;&2%lQue|xYgYvQEnxF$6h+j&1yQr*(9bE`UP!$g0mP8SuR z?r~rf&$^EQ@>5U>)G49pdW*OAi4C2j9I)-F$Oa7||0ovKI$=ANI{*f*Dd4@}00096 zOf-yJk($~~nP}z9v(+tFdp=S5Dxsu^(WCNo2%F+knVeko8;Wp1U4*M!@;vcjo$*8U zAP&^Km{BS>?5-`2QHgPAt#XWoni(nW8<3fqiHm(6pFKQvOt~xiP>)@A>CYZSQLFse zImFGs&Xdc3ce8%BnXxy-o%`~96~l10uwSY039vt|lOG6dX-(lpuIck4K03$RPeYZn z8)1mqVW&d2L4(|)K?~){QJbgVYg9%lbeC=Y&>YaBzK3z^o-VO;4dUso^fYcRVLYXA zSmmeegw@#;w?74dESmIKwx*7XtrX4UssR;>8CB0)5isRA zF`%1<^y1t9nuD0#8OFfCsO6@o+63=~Ha+WecX`)XVs)}+Wa%>L9d`wp@s7IW?H$o7 z5oCG4zo}uimO~f(V>mBCe61r?WGt&c|FM$qpv<#*;u$Nlj0|`~En{D`%iXfco zm9)YqDTFYU5OSp&4=Sp|&d%oLt<}kSlmuY?d6wLg;UoIG+d5q($YwRs?>o}UJ3Udd zq~0cduJj1~L2_OSLVty>0&yS!0a;j-{%8AQouB{!0|19;a8`pQtvQviH|cD|Ck4J2 zfy3dk*SFU>jhHP0hiszrJJ<}~)r9R$y(%Da>bt3HI4FR8suY_0U)(>^VMRJ`b;Z`% zb*ihNZ{868q24lERT8*EGn}_E>*LP1X&cDVBaZxtm5jH;Ii7Po3V^bMtN_+n<&xCn zDOmp3p4?rRPrv`;41To+KVP3FBb@z0e(|P4X2%&2;0pROXE_$YnC?vb;N^jRu3M(%5Z_Taf8JO*X}i3i!SvG*5$v==;*{wHq9re3bR% zgVZWi6(0aH!IUHi1zq2%<}u&)6kSvfcSO*%w=ACRtS)ZT0be z#K9|ps(s!ExG{J)`WR^yUyDuS)TiF9ZSRX{I~T~NHeoEt&fB;Qooe<()pQmGb_2k7mWvf|TT;bT>B~Rr}P*MdZaD0 z1(GKW;%^RjiwRZCZB|m~NFME%P(MW5T=qE14aU1^v35AIv4-7R!}<~F@uSl~Vj`LB zqf0poIkliy`H(M+#QE+nK~*KcCCGkIlZ&8w8F`#k&feA`wf`=mf;mtXr?$AGdP+Pv zseQ_<(_IFtiUnTj*3|huPn%oF5vO7~?s)}dG_EN(d%JJ#?p7_Wak6@zJ4u0B`y+*7 zi+4BZ^T$LJ*NEM+FajNT6p8|^ug0IZdpsD$f@yzW2)p(Oql2WjF`&CrRM=xxIZhrv z?`3Io+I9wGMXitL24rpv?B=@{SCg5H)r_9ygL*SjIj%wWgE887pccisW~_y0i$tI^ z>hudW%u{7FikE0U3Pw)D#HdCf(1U3rt@_!*wZtwa^bw6yBz^CdOmTE6G7mV5Y)v8K zM{-!$n-Udu$r31LHN|FLcJp+;YmHvW%;AA$fELK+Ji4h|JYmFpn_98FmQ!w&x1|Z1 zovk>2w2jHfuq-P49kR@ujcqjeWb7j3tsQ?hOnB|b%niY>(k5w}9C(;cID}%}Tj1|P zBWY(pA`XkXqhd?yaYj3#b05#Y?qNcRGTzAn@~|ONR9&$In3{)AnL@X(7S9z`;&Mrg7%J{c%N%Wu|C3s>0Z zeSLG}h2$#MNtaWE2lV*T`+}ANj?OZvT-erJW-!%j5VdkfCoRFH^vYGDbXCB?L*9$> zA=^uKVj)GGy?T4wfV81|3`)}_OpLnlehuselM^TVb9e^`w&@$l2==s6ab-z~+yYLN zm!{eu?t5%Chq1lP7i1~hA3vpTeiOCaiF(<07$1h1#gK=(=O}S_5j@DFxo>r^mbv9) zcz&N2)wgMli~FZ|a6Stgu$!(s zn}>_KJME(6k1Fod#*3_9$-2K6B^l2SylPVevyEH4mc?iT0JKdW?I{7%VHRn%j=1(T z)I!B_V#gW^G?i3^BC;FwGIMrPSoMe@Rl4t?f@y0^x1Qlt3i>T2A1L?nHuJPL^IiJW zt|KlrX$3u4j!nk?5Oa|M*HR&lpC{QLV_%$3=2`F&cSpk4iQuMUVPz${xJEK}CFQ|d z?2@h7JMU`>*SC_fN-g!yBgg1SSoBW)>C4UTRNZCa9bBMRbMQYdTw6q!qCodunn7XA zkusuClzhHIKwG&cM+BP_IBBYJa9j5Y8%9GBb(sq0=#sDcOYBx2eFd_)XUZc*=RFFT z=X4%%zE3km?#Bd}ugk6>(K(Ltu-ODC(9iZ&w@pI3IF24391p)ja!t#`jqN03k7ZP# zT**d9<5Us1F_SlYXx$7;@BuAh*hMTco-HpiYYbiJf<%*atr9heozKiiw3}~)g36X8 z##yW-;RG!!P+3!WF}4!6gxX_ z8D{Fc7uX4A?}t94p1_}1CyRp@j&#uDQ6Z`s3eWWoRD`=zf_Hb_B1AyR>ZI*hFb!U_ zMshr4`#y|7g$0Y7u^{zn)?Oi^FG>vLlLPeF@4x`CUUxWgSEyAimc;am+D`m^TDZJK z!G~9VVLo$uX^52lInu01nc`PuOSlYftXJ| znqSw-vr(xkxCj(;@$?wjXIHAHmtDJ$==NxkJC`vhTCzMLQkMC)C@G6Ur{zFFCbMx& zv%jnim9N7(WOc+nn8{F%3?VIoz_&04edg*TgceRWVH`q5U1 zoQtC7h|wVP)FkipO{FBkf+qU43TKtXNFZ-G71u&N(3iu1|MayTf>0_B;WbIgG4DB* z0>k!9X50$|Dbhgq$~LTP9%NR84txxJ0`bw1Wk;bwNfrR8(B+O_q>?6uNjASzO=k-U zC*Mxho5b^n+?G(}y>onr?$p?o@HxEnR|B=R{YpCTQxA9H$zR%YYl{vFqC7p*Q!AA* z)ETv~2R(D@ff5g6JClvJe28h{7#b(=TKvS_KNxy+b$+Np-~+6I@309L@1eb+aG0by zX=Kyug&_xsru5#E?`tXORgpQ10W;wyu;(GB>IuncYX4vb_5r=6J}V3R|LM-j`+G!1qk`}%c~h||AXC;YhLx_P*7;-!#?-kPGlbwawfgMa{rQX;F-gcT`cj%T%+ibi z4dj(u0`Ac4kmo*frZ24AfS(*}diBKK;!R+lu^YoO9u@S`<&M~uN!Tsq#QQS+b z$fj&*#j7PJlE5=>+dCoIC-}`LT|uVQj2rEd>V~I1hDYoa16RSFcl^^x^P`yU=?wf+MU&;ZX|ZUGgIz zb=Xr|?)`jgr6}f&x{(Nt%i9+bfq2n^K@3>lug=-}0N_q7WI;T>s=AJ#XL9$fVZALI zO(g;y)tG%56I>UNV1 zon}S&#SyTYN6f6i-MK@2&CUViF>2OtUx`i z?U~t`<`AE}*{zhQnL9sgn@l#S5=SA##j$An!iPr4;epeAjyw%b=unjHBh!0vOts<$ zTYTXuA^b7U#hj`xo>EN9xr8d#cjSs|K{awB{^3Fex6LJxubYJ}+^WixegIA=b&`D0 zCF1?K@AWembYky^R+|k{J9;_8j8WuaDHLz>TFYmB^!a*J)fUg$S_*=+Cy5((D#qIe zD@8ynk)u|6*GG6e{YWi1>dk?2BjOZ&(}k!vkC;kqm;`%s69x*AQwX@Xi#yTdv`%EvfXOjirT zX*KLdY5wLXMCBcPp~5?qjrFg5xty>TDm}?7X+QFXbH>dAA3muyb`w_%raEH8$BcqX z*Zx4PK!)kt=CUm0?D}fz_>t4p=E8^RZi_5)y2e3)k5XsZdJYQ627*n~6%^V#hp=v- z*ulFF?OfFKa%Ei)ulFDIlG4Ct3Gla*@W`UJm9+(L6s+I%UriyxJdf+tAscMBSjd`e zbsb8;i5ZIbwu|jf+R?F+vM3Gp9}e(-NMhY;)&GJ6veYRjnzB8Z%`aiO!jRBeY5EDH z*0GgrAgE51+uN&Ey&(eN%Qtw z6b6ny?L$Vg&)n=JcZfBHbzahqCRk$@a5TspjH8}ZzUmG<<(kYB1||9AuO-ooS#l&- z-$V*tddwt@0yi~!tK?(%tMR3ns>PH%@u9xA+-PEL__1YFPB7(_7=N0vaW zvh?T45)m^g;#Xn8&zG>6XBhG1c>SOe%Il(^46L}hp1(G;B|zYoVHfB}J@f|L7;Sx4 z#7O3*tz{ZA-UjvD-tQHCV}Eb{gM;tBy3iHS{2dt)lh%yGol{5q^K%i4ZmO4V+myGv_vH=!XM zqx+tikN7DW!q=6U6}6K4tu?g>tcB*DT|ncfzof6gNvpW%GolDtD(>Y%nJV#|=yI zb5%Y4aW)HU-ro1Qv6cI7|Izk2tfW_wal2ac!20}fxpg981t%g6=lzFb@L^i;TR||5 z%A)&I9*Y$uL{uh8PL8w+O&p>@3dL3FTH-D^cB5Gxj2TA`V%W;UTJ^y7Y5>3z(9{nW z@|4%MsVvO!xc*5>li*7JUU7_dseuZSPVz>)o%s9#)gwJ*ANs2*{Qy=PabU8p~@ccusutn4&HS`p6pKU5zAk$@yfAx!g&TJs zbU9d3BY{^W>n~#TQee#h0dAU$=Mn!hR9)1frHboWB;g`f2a%*cQcX@kGq9+Emc^iq-jx6iH10#h%Us@GuaT?HPgzfn33JpyJWZWed|H6;k0*~#z-cn zOHHWy)B`7_l0r|vu?NRc?eZ%)sDA+W1o^4DLlR@&Pvifjc z=R)giZ(>r6P&UQ+JG zXGhS)nY&m4Znj-htI3Ac{bHHz1ZIKV^|pX~qNsKt^_WX5ndFIsu8L;ECiWsi!A|i| zk5?0ta@8A0g$Wpn#r}SdxSiq?{U%Z*_c++|c@z`Y$@Nl>>Nd1P4XKW6+`D^Zb>R=p zDku~wl1*P^XA^Vyy(L53L1|cCNbr2;A(&10nl<8utDkf=IkyoBCY(O@wx)ab1&6sC zu@IRiIVns>Jpg~bVwTLn?@dSc;O;ACi9HdMT^my2b>05#{6J(m{CbYrS4SYp-gkHW z3T+9<`-KwZrs}C~QQL5pgO9iD)mK$3iv7uu1)Y)79IHKkC4Ke@)4IuaEeZLn@ubT zF3otWGzIyovJCIsCT<4;uKK+%_?kDcr1oBoTq)ni+RzcG8;zMce+_5N6A&^+QE`NE zXNZtOJuJ(}bAzTWFWwlZglk6*$>aI?yVg4T7>pr@`?14sIyv&n)TBw&HTMJ#n96 zGgP&r*x+A1TN&9GOW5*yEJyI>N)zqoOTThX<7TqpguGQA3OQCYuI|39xvR2-5_wFvT~ddI zpKIp9GioQlS>{7QQiA+4%47A;wmNU1r?w;CkiU!{-H7`6o%66kL=mWurqSK@^wd2( z6LV>Y>~^lYBxU!tRt95VFYG{}BF*>(rA?TsUbS+_;N?SB7X;sL`~7Frbh= zKFiJb;ycgL>PS@r)ap@-!x8yn1gssS2NXK=x&V-;j*%gz2y6bxb?2xgR8 z!#O`bX_C0?z)~R?SG$+Qetz`83_BLAp(Mgk7H`>-Ug)r2gcLtPp+p_m^Qw6%=LP=J z-M2_!-SG(ryOdoN91Ab-P`0$zj2U^M0;bjw`l~mLhTe=RRs-ejua}Xo47xN5t_ODp zpiNe#9ylLe))j2ANNPqKH*ob$8MtS7aN21WU?J2|A=*Zzc`ay$-l{+_92A_9=s(^x zxkoSqBgx2dP$V-e>~9j|`Px8(mRO10*~HN~jm#oF_0i2kTj1ikZ3)Q{n&)X5siHqM z+VFLq1vO4?LoWFD_Hza72R3NK0iOBfN7p>%T&BmbZr4`eqyp$qAY;AJ3M`G+VciQu zePbu=rq^Mp!?D6aHEK8FXq7hub(ynnJJIUUaq}yN0dry7ANujsd@vY=L#us$R|Cf&fwfjm@D-i0{z6Ir2u9;`H!>SfoMv_N zhX#F6k84{WqQ#@DbeZix-N8qo^;0y0lM0YP2m5cwkenIEPa|DWPR4q((G-}q(>%Z9 zRYJJjjl|dgA}2|o69Y1+9zg!utmPLWT^a5?93u z>#-K6dkzx9jQ8q=jPEo$-Fmr|GJnZ~&u9u+A~|_MqVnv1*b}TODh#LQ7q1%&J3a1z zU^wpiYF47S7|{A0&knR)yJUMsf-c4@Fzmt{Z`j0?qTDO72s>FsnVsD6C{|}uU>HHd zDnZZrRZFHtuC0VhMu&zG>;=-kfZcGD^2GIHZ(k22B&ZXw*kZZqMq%X_>DG#SY(a>@ zV@n*h>l4*}LfC5fQ&c>=T*q8PW-@nehZz<0p<#37Gt?25#}~O}C_p!pY9CgjCm|xn zy%FTf`dHUpEl;OL+$v;7KT(C`>6CzG;3{xg&}jPT4mtMd@mig%g9+t?JrjBfdg!~< zLW(!)X|lM|_`!M|gqm=#tii11vW7yDx`3x#i``W&ox zncy&Ii70oVyL$AveHWsj)*F1%#EkY!-vU)(oo)Ucr=0tAq%-!BmNw~@Z{(gx`Go24 z;Ku1AiMib5$7A7gaGgCb+YD4Q*{VA}D-IM76du4oqg~Ik+nQB=UcRnW(@oU2cgu9} zka|7FvPxXwBL2LMMc4E3^?)))7}{OV-T^}sI_5UqhSy)NvicI%pS^rmmptt)Y+66` zRARgRLqT)#Hld(Syy#b}vNzI$o#AfT^q+86pj!sB1TaO6hQ(P`@6zI5(|v-{R8*Cl z1gmn7(s-}KW9K%5=OZJ>c^dZ#b7hmuj~9_TCtB(hFq$NrGmkmx6&ipA!*ha0`ule- z8G1;NsuFPNb3Wcys$_CxzIF1r<2gZ}`*V-gwCCf&@^c>i+XMM-~xNS0|vndV$ z)-nK~+_h70Gnz&4x^HerE*fpXw@q(y?PJug5@?>P+CV0eBX{743H?n=gZ>`6UN0{D zGR?T}yK{o27vel35JT?_1pP4&9o9lXqLGg;IQ?q+sBe z5rNERasV|j?S6K!lronbgH+Uf;zgDb+R$180 z5)vVd$>JKt|HM}&=S4M;Azx-WYpd8Pfby2!#xi@c)sAI7&OLxm3C6r%Z`L7$rh%Nc z(J+mUalMCNR(Mo)zyqtIk;Z|ibX__|T9E9y91nPe@;diLMV)(-k<`nbrv>JD8C?sM ztC#bYe$02QU7 zo3P1dxPBOJ#ivBW%1NSuBZ~WAba8^ePi@WYb$(71ZnEjHe8Hc8WB3_4)Zk2me5uUL zZh6x^q64vylZE-3GQ*8Bce2t~!wBEm(Yei3+nQ=wGbK-~jBX0Y4`enlB-##?WRdjV zK~r=aB|#TJuy(m?l+=9xm^*iafxBf+50i{NXU?!=b>` zM13B9KOIRA0I z-dXg006fEBevRsNzvr74Z$a&>j+cd3kxd#+9j|yjqkCqZ3?%Wet!ZgymM8p@nW<}E zMd`x&ulblgxSv`+{?PJuQ7u5=#x zE5e96OH{W5)o9(L6OitQsCR`#vgul2Uw8_P(Wl7VTQCXR*C?FTtP5npT0L+3JaUBP z@DU~)--P5$nCco|>73r?E(>M6+86bmFmi!R=?FW)rnsLdhf&3A<^TAN;I&HD>eWsR zW}QQ_bdu*Vr!WEwGTUBu2==y63=CKfRpZ?1aUE*Vz4xE3qDO5ORl4l#9lpB2pbt1U zya((mUJh`jxRX9(32<1~zXWf^2VjrW#2!YnaYr8#>yD&EneSR1Z{T8y^_8;UISFM^ z&{r3IpX71hj}n(LH-H@NJb)&{rg2i_QQ&?JWSm~z?A3Yv5w%e@fRuwbmEdx7A~gti z+5rD3<v=<8l)d74-I-&F zZ{$Nw{aL~jVzRexX;M%;gH){f>E1WAiUcJRO{UoDM%?!va;qNkVMN0ViaW7EPc}YH z^-J1MRJXI3v{jkdmC1*$}(P5e>5wL%nJT;Jtdu=Ll^F`Kc z5e}0vM~VtbvPsdqJ=)YBUI{iSa7@@5xTAy?D~hz3uTG-s(c$_O&<9s_8v>dKQxv!f z9_xhKP|7f%Stp?Ezbr~LkWmx1@8H`#0wvA_G*4Yk%k3p>JX+Rorg`W%BbP!I*9C@G zz8`_rrGBIs|9k;$FK)K+IOga9?u@O2D}v0pxVn$k>sYgkE37P&?)dQgd~ffy4)z7m z>IuHm*#xyOMN_TdGiymOK7PRdyhy6pU|MrvUwrJtYaDemv6z)(Ye$rD<*m5xP&(}A zeN3Cn>$QN&%Uv$(D&vNA)WqK9%~x{NIxqajiW2=p43~{PT00~pJ5a4*_O6$v^Br8b z+RP!2tw2L-7dBbO( zPRTK}1I8ghlWRiiyFa#AcyYNYG**B2Me4jtkQk8<*8YSm0k+L>do%GPz3c{N5~LKj znOFYNkO!+;S7UP+^~Ib|8lEBYS2Xo;y>Mn@iB_8+Y`ENwOesMd;}tibWuEJL7;R*X zV@3p4DXW|zmYXg(i1W^LW1N;&13wOq1;)rT}C?8q6YfQ|Q3iuUA zk+)P-NLRZ?JohVK3B!u>BWKNA)@_`3j_uo#U8c@79nQXvTy=~|)(RU1zZ-Lh{JfQC zMDOWknGdYuq42&g;&p98x_FF?p?+4yLawQ>sy7L3($_?LGuaK53wJ~HX6U8Y+k#g^ z$xpx;;4|?S&mfEg2DZQ@s)mSg^nn@?F84L)Y_hWQ?KtNJQ7(5!P2nLNC&9h=)Iyc3 z5F^sC{%q*L#NhggIou2*RmCUd5hAON?2%8!OrJDeU}k-|hc(-Ji_4idATje*$^GP| zntSum4-0l+GZI+Xf)w;Qm*~--lIjF#PhFX2a9vBlf|cs0TfSMjd27)9US0=%?b2gi zR{E=CNi17R(`_t{COh~K9O(@czR7ww)kvM$GH*W`YS@>}uERYe@U@Xf%xiANn-T6iZAer@>y4OKy&Dbf;pB9V8T-C5DMHQxM{J z*y$ByXm3(+GFm<(6zX@SrKg!=l-YnWi*9)#(r>VMorrr_U43WibuNXr#-U)2*deC} zyGWsl^UceM!KMiibzv6bP3pD>cpdGo&s=3s6}XvE*Wq6*dwJ& zcVmK68eDF}-&o*|!E+dQy7MS(kL6j_O@j{(nnJXMJ?=xn(qUGr?3-EQ+t;kaWNSw) zAM;#8rPQN?6=&Vp?scqNcPdDj%b`19Ri8j&U{K3T$RA`K593iUdws7?o+#x0?BxZ+ zMvHR2<`Np^2e%X(s;)OhmHIZuZ`jD@i~2F+5ufkikix7~y4`r&3hO$7I0V`|5gVv(C3ifW^pZ%&8}rLN zTwd#V(T?VFNuzuKtunk6JJcg$DW4Rg(3#Av53q|o1Jg=<4KtFBC zdFQ^we$;LH2DXrLWTJXG2@06abW7*7ts@Z~>qQETD!hRF=8M`2W=e3Mpy2)B9+A9@ z&d_Y_O!#)Dpn>F80mutj#xM`vhoZ-oT;w@bOR;arm!g{#KM$?c^HBk#*uPxFv$uYX z+(5U#CekJqnxv(0@)~J9o(-(K)>0&v`e_a*!HxLk^CrIo7g{2_&cx1+GIeNi`ArR2 z5og{FRFFo;na?O0$ym=p4ABS1+-`T&XQol_OKkHfjSw#-sC&6)X!|l8tq4;JM}0#h zx+b3)E!zf`Uow)D+m4KK62qUw9pb>ODZO79j6fW%Eehz!8(cs&?$@=gOn8jZnnMek z!yu{01{uDsi{K+Ei7q}XxW?70PMjORO_UEEE3oibX(Nm>E7;yIJmf7*t`~edZy!LF ziWg5w))0fh(=JV-;_^QEGz&5V1{(CrNuiy1bZPeP8k}-7fEC3DfWbD~3&qS1te;K~ z6~Am{1Te3aVwhLfKqgAc+13D{2O9t!`Y~{Q1Ay590QMb#@HGHx;R7-H0E7kr4lDqD z1Au}|_M_5d^(faaJ5 zAd3{~3jx=_0Lm&DG!B5`WdUvgV95vIqX0NNKHv}ldPV^f0KlIDpf><$u35kZa*H!? zeFs3<0YgCnpae#MuO47&1rVqJI7dDZ902rE0c4O{mH`+l0GfLi@Pyow3ZT^kDEnY2 zLdY$JfFR_S_W%OqOWID5PfSB@F#yQ<0Q^k=2J$_74n80SVyi4bRS3`w0Z7~cQYiox z3_#`a0jc$$PEgB!KB4ycMD*tq>A#%l`+NdopwAl>gkt)F<_)sr6c@<~32z!OplMde zfgn)x(qEqT$@!_-nu)KQ790}|Z_yj$gHh5WoeM|Y6l{5IZ4>MV&17;Jh7&JIBHx~E z@>I}N97?!XF*K4?3>ow#8^FIweBYaB;hKN7G*ltGRs2S`dkfu=ia14AS^h$)^A3uf zJ$KExD|75YZXYh7ZHi+&OjrN>b+A%Y zfQ)dNqR~RN3rxkVs$J`q(!5+YIP99$F+J5pl?2;mXA_pBtAkry;9U|?(Au7NshQx} z5-LBV%!wPSD%0tp zP>t_3#$Bt>68NCq6R53y+X36@SfRpoS4mQfC<7yAgrm{U6A?aE*x)=OiNfJDGCkfc z%gep=X+xZoMlUI}&60)R3f=%Q!+v?+dLWVT4ltM*=X}%N^l4IH39k_*Ww`NWZ#lSa zb&bEZ30Ixk1M$9gklDuKq`h6M$E#};Bmhon$L!NpM2h=1Yz?AjO)FULOEPR9cpb7% zg2%<%37SUAGIF*eS?1+iF=TIs2!S-sX7U)c4H|>>1`sRsFcuf#pU_{=@wJdX40E7~ z!LlDd5DLb*F4UP&kazXAqK5EDB8gONL`vsltUv=i{8$#x`d*koMo}fIWTJ^H*ZD*2 zn{s9)s9d+!Mb?s(XopDx7e&-@Q!$4JBD70) z7|58<&6SFfgj1Cd_@`q&=J{xC5%&x`#4mo{ecG9szlzok0DyA-7(~=pSDz~i8c1AI z@w@lLYx*g^f&qrY-Mhv$yCs1SjB%(6>jhb!qJ?husEnbKv0_*0+TB|`B%TUzPt*@@ zw^tP@7HO<*SW(_~T-*)OU{0kA;ESZ2 zn2@PBkkt60Kd9$E5HSD%d;SEpKn&MkN`dM&&jJ@mC(uoQn(qeqD$;GI7gslo>!C4JgLLj%GYzCw8s zJNwn%Kde@dPb9E`V0M3v2_h%B^Gk{_0HDwP0N@%OeiDvT56tgSFdy-M-}$G$!gWD# zjUc$2UvPiCtiQ*GZGoVj@yFn=-i3ndXO6A6 zycTTTz}72S?cudrYbt@VrTiR=330eD^m2h5F+Y6X z{m69U=IrJTAM%Ph=CuB}IevNj^7JaC*vPHhHcl=oN4bMWIRg7QP+tK5-rqkY!Tovw z04(_v$V{6beHCU@i?4PdLZR^0t`d!P@NF!Uimwj+q0qnEJ^Ped&p`>)cT#@;gr`C< z0Qi1Yrj`ZTQpDXZazJu~9Q^z7!x^h33$Oe_cIoNg5B^iPVR#@07()z@`pSU6v-+Qc z{C@rC9P@<0`GtJ(7pf2-d8|~Hs0&;Z{mKsvG?K}8>g)G<@B!Xt-z?JKPa!8(*Ig%0 z5$wu<)BOGD?-<`@Jtzy}w+Y0M+}{lOyRu*_c58oFxX>YK1o<#=0(IB-<5g`#e_G$W?7tUk#|hj6f7)&TB}IA~jp+xIpgtg2{b+^2Le`7> z)Le3+Wcq&T*!&XVPoE|JgSn_lzaDB1zEN2J&FMc}{U^J~5SjRtah!C2MEoP%R|VjP z@ckehKr#oxgEY^alHZL7n; z-yQ$l>-m&C8{Yv4H~$L`e`e6%mHTI2k}v@P;K3imP36xAE-NdMOb1~9lO|sWrJ~KHse7(#0*HAEa>;~H+lFa%xI*)xdt6$ z_zPv>0wI?}1F%p{w|S7##DBZsA8uHF0)?uAm^%J1v9|6A( z@*lQwW5RwE4;rc#0%!>VH2Ho&5RIWK31ngSxF1C&f%IxV^)w`Mh5iuMKX~@{egVOt=L{qqgTgSAheppTIf&HE$_pOpd7_)`ZU%J4W0fE~upCq?*lQS-Af)Ua9K zH-w$pK{fS%dfVSb8BP&mgc*N=LawCPf2tD9f9Qh2X8=sT&;OvR>ZbfK;{65)BBWZ? zB*n?={=@9Q>Ms0^8-EdfMp6hKge+<%f5iLoGXDY&wiyBkA&Z*d_rrl`%Bw5812135 zgo6JgBHwQz^d1EEQ&hVYzF!h>8GjHB^86aohyb<_yp8Y21JTqvO*KCESzH}p{!g*^ zem?N{4weV-JezA7g_l09>XVH$lVZZ zg)H0`gKr^7)178>0p{C5?p;6({oxu0?vg<)G3QUv?Na-GX~10J@UO1_QP9+1CD_zN z<>zR_Cl?{wVCwfrynm39e<22cIQ3Z@Ae{x%-0y~i4JOOQ9q!5a(TGBZ5u^|wAqi}{ z@$`F@0Wv%GpWwQF4&0~5(hxXT6r1mrf^Tj9{v%(!bEW%va1c_uO8yb<&sE_2 zo%#04FXIJQlkdR$H+lv;klKTc7aY=)_*6gtr*cdF6SbiJv*Z4Crv5r;_+15V2B5;Z zi(AS5C?#Q^LyUktMgXHYC%F@a{wMNZ4jD9m6cQTvq5^^6u=0O9WC;AZv<%$%IV$jJ zgaT0kpPxj_Uq#2~8(MyysQ=pb=Z6JZ2UR{jg9kzhzPKjHcPToriP`b7m)|L;^F zn9e!L_ou1AuaS=WhL!KH^<5cP9u8IAIDRNz-yM*l=wLPRI}8(RJg9Q?Lz{-OfW z-^0p(!GbS+f#}?ys{%1g|CcJ@43R!aUm!*DXR5%jBZ91NSouFv0aA#Qki^aYNwoa6 zan7dusVb2D6KVM=nBUOyU*O=Mt3dYmu<~E9;7ea1yXz;a0OVO=F5G{i0%Lr)+A82_ zQ<0R?n}7HhDH^R`q@dX3pGg7c+rBfs zE#&);{08?EiTNp*-w^X(VBxo3fA;QEu6z$K{{;)a3=O(bev%G+dQ9leAJZf9U+X|% z1{HjmLSN#y)>+&<;^Q?+2~ zCz2DQ1ykRU^Iu@%|3?cx1rwqL)8E6*f5Cz;eS&GapQr_%{4q0n|AiKe@gs%Tb37qK z6^`w$|3O|t$v^^a#hx-1*Hf7CxLbclZtDLOX!C(3}{^P_ms(CLs{6(P$@r~idCOf6Sjay?gw)%^;F zm$wQL53&z6^2_L*Uu~3KTb=rt*}`s+=;YQCzOPtJ+JvhK-iE%e-KL4lxFcW99y)#% z)FQS)Kie9wib@zYtk>y>p(}(#yvEWf2FCSg!tn-CH6{x3(9=Vv;@bKfU~YF%eqkgr zG=<95vNsLkJDvDBtUW>Abms`S`NVVHt*Y+lYzZ!P|L4cRp(NsfmU?M89l zYy)^tEfJ|5AJI`gd&(=D88TPEWU5nG!p+SWY~d{_*i~A_kdrF4wMUM#dV@p{Ma6Mq zt-p=*I5%I9Ywdw`UyI|6w?4K3t93PDNOV7;P{ZzNzZPj5lIGLb$B0n;My{_((p*s2 zZRN+5Xr(NOdYICqquT6-hPs0A(KQW>&0J}hUOwOfe7hL(Y(sAQSgx7P#W8Ykf%~Oh z4azm|*k5hmzo~=T4y&d=s)cYuV#nNKDt${QYLCV+*T3-WiRx-#C>{^G=aJt2hY#Wp zPD`clB2hJ#P2x!slxALPy&q}Gg0rweU=ACPsC{HI>-q3$PIa;MjVF6rVI!qwe1#e+ zv|>D^6}NHwj9gI{inX-jhLx$DVR{K}Rj!VPqT2SJ#7Wnc|r{x#q?4%QkfvIDE!QWZlQlss|r;>yaKD!hu{>Ed^HDc^^L`qT?vuuRwW|CnIOf z_iRU)a}tZ_b!%k-&Kl>WVV#{#anadS=soF{i*0OES~kH*WvS`4h<2A9bq9zm3cN3I8(L^JZ}b88pUXjAU8FQ{so zwdgVw9rJY>R{ZYPO$U6JJS#i0Q~tAK`4J{-Jq;s zZ6ND!JmC96CazC3g8YH*7k=6RC6kVsEdV%>uczGtlLk1AyEM?Agdaa3n0fm2!JV() zY5kt2|MzR4AyY{qugNANeA5v9dBaEVW_LFa0QG&gi!ofM^tbnq|5R>&2mHmW-~W#W z>AwKp5CguyX@bq>+_>2CAY-G&7PqaCON%PMEwd?qSASItG+Ovyys=Bv4>83DV#>yM zx00VsxkNQ4z}&Ss0SC!t7>AlxhUVQm&6Fcm^3#>a0srpkKZ^~l8pIYWP$J^@H)+rS zN+t4pH)EQ!*&jxQg`k2VsQ=NhK_&cUd5kZCLG{=VLL+a9I-yq-k>{Fz_yw^~X#)KK zVuLfphVN|7PQVh-HdyuFt4t&_E9+m57NE7y-rYS?bW zRBx->w%(W~suMcbQ!mQRKnrUS>7s}0OuAZ~5D%(Oa3OeIwiSd&MdBdrtagSi>0Z%J zcz;^->AQuhL|qr*$E|qC@yuYa;nY5qqU9MT+tY)I(KmRpmiLlid#o3v?kEJ27SoFw zY0C-L10Pitixz4{~xpnlfWXG(`*#Cm#l8Bgi0 zXGT?~qD(f7bLBqY?77gYO3A2q|CaW|1I_J?WNbsTRt3`vOm6*rw4!^$kDAe+B6iw6 zra#l;uCPJ0e#byJ^tdFc5*NEguv{Q#y4@NlCpc8EpqffZmj)ca7FB8ACzP{s7MlbD z@hk@?$9m=P+`%-tsvDdqZLqG4-NElUZ?mn{X^QU)9IQhDt{& zdM|^0i_kP%%^~FqNQ}AA3*Z1Lz-K!PxUXcJ{w6XJ2=V`W6+=p5s zPP5CVm1b)FKGE2TYiQ9MQRMYZo(b5kegQY(_YI%)>{N3JBeMaV%u`Fc3@@Mt^5Y2K zI=M7dg*fiY4;TpRiAva<#;s!R$veMahGwtHb-31m7{ko1{wlR(qPWqhAKC+-JlHO} z-tT2cF2}epBQ!==Ini}W>LesQl~#~B>{8=IPp}D_LKQg|0^|WgN=IljEhL!~R`8aBhfp zVyxT+6KKgn2bwswuthgFRKsw9Y|-W+6G7FY`RY!$O;#$gi2QsDUKT+pDQr*si?#d3 zk11F|P$l)TK_vB-N_@`wgiPUF7;5|)H2D~dAs*tm8p)s#dCr{?R0Vq;?SL3OoV9{s z#?E~?X}LrcS^^74)Z5wmpgJm*^V_2B)m@@vX6yj~%2bch$LG$?)osYj$k?8lc)bf{ zPMGb}hCV_>TchGLZ5T7gvN>m@LM1!RnSBSf_0^c-G_zTF_6pmqFDpwY6)-qnZDh>Z z-)6pfXeewPvWPFXNn^;Cl8lDbt?$a(X^rUH<_}vYjOWeH@14I0pGoQV_UUnacC`KY zs!k9RUspo+(U~S;lWA}AIHo4rz3!`QXj6Sxy=Ms@dwSo-Dw0*GCU#E5WfAiAC{u(6 z5g8h322juiAy?i>WUHTeRw?F>mifx+91eXz-s%J^GtuHe|G;(hDV4>Zx^B;tRh#m5 zD)tZYE(eG9Va0`coRW1+X(4`rtEuG(iH>J>ZuVujOh7DeFV@ldUEHoKyIWFwZH#Xb z<1RJZC3CRt!*!8W=|0k)eqeE`hibcnceneP@dR}987*pkZ6=MU?kMc~TB?f&YogcE zyX}eSQs}|1SMc5fj8KWk^(WT&*S28qCHU#UdL~8szIjPCv$RBp9;W(;F~C~i1g=lf z%u=61;I4KWuha)EXNhY>o>^$=7P%HFf~_^|H^dqo;JJJJW!eoYe0TJwy0J4fyNxTt zpIY0_Q$6w6AMZpe_CZcAgydHQ@;#8s$eG&LhEx&hsA& zJnj-ZKeDnim(h_s6){noD4Q~h<*!|<1-Yy67g;JYDw|ItXHpP9fjz5v6F5Q-O|C45 z6RstdcaV1?AJJE+5wl%jYE1-s z7oX0WpIP%ldD?1{1>~(3=qMRqjpyyk@TPk0#m*BS#6B9iGjd0$Z?RnB zT>>XEJ6E=Q_~mP3`MLH`|Btw{fUY9h_Wn6>cXxLnLV&mscOmZXN|d;}2cpD1A@1(( zo)8z}ZUiFVftmN1cjvyj$=ti%w-#%0lJ3<0?_Jfu-hFCUwKBR0n?6}UayJCoLEbrh z!HYchwwV#mP!8>^#X@L)H+t0k611qNk;RVfzXSG{&?(AiVlWQ6M5Jjo&&R z)->ZpuE11(hTq&~4h`*5NT|qS$1Y0rZgLr1JH+|yts-0amR7Ibcu+ZZR=nnOlHIf+ zZD|zFmf`~}VZOr!r26}yGu^Dq?BpxYJm1{4;G#|pbe+5~?Nt|W{P0_eGA5FxLbZU? zIgQxqgPA+c-STgKW>}Z%lO4OHtiEkRbSoBTl3WtYDT~M7t}Rc2i17Z)NZy5pg)OyR zE^kZ~N;-!8WwlferN6o!VnB}tQEs|Z+#+{&q^4X{kA6l(39vP~xez^jFF-?bfl8L- zgtfvbFZ5y#*V2Ksf+Bu?vNTfzRn(AC0{kK#bED(JrU?=$D^-&m0S=|JrLyg(&#FbdGq@uI} zy?#gN`}~=O%Hfu?J50hI4LO|4R(#ajHTSA9k`eaW{sd|y#;>Dx_JK!om<1|CWgivI zIl2kLvfhQ-SifE#-6!)zGl^09sQdhl&`Z~t!Y}wyX5*;`0ulzuEQ>8)sh&_SCSpbt zY(Q!Ihdyg!_75|xg%u&ZsNd#RHLtTD$G$N1^d3zm+>>@YAFXTh-LG~=a2wh^gv;#{ z$jppICm@MBR!IyUF-H(7zjDRbX(=k|;ul*bIL`ch_)co#(nxpGm3tFf?CrcEB>Q}% zWF0zB)mcHEG92S3i)RW&dVRi$U`}E3@Cc@5a8aHdR-p^w#TOoX&SEVJ0HY?D49S)u z!^ZOtovau)qZjVES^P*OVS6jvM4t-0+vRBd^J}IJ+R!M~OnpBbgEu~l9bdse$yeaG znJOLD-?04@n@+j#8XRj~$3k>>>Gg$fOh?1w;meAyGId{YF;k+C9i@Guc4Zt_6IL@b zU!d{GdVIW+jw}~XQ|&4`cW7*F#00*zUUwn^E3saD5sNKiC!v}?1-+P3-4)mM${eIm(?W?AKj#365ZhUGeI58OW|#&?O>>6 z$|bhIL6fw84RN+ZbypbG)Mv^E<*JLXu~&qg6&A>bB-WmK>B+3jkYRFm=)CgpZXRT? zQN%s5kuZnh*{ZrqVu&zIdRSW$0!=im6khdpD;#uV+uXy7~CIo>Ph*5{$` zuzse&Uy|EHzdYZ()7~8ohMQ$6xVC}7!m^B>A=0?!>cj%(E0Nrz;*mp4i|f*UHC);s z#AXUq9-bL ze%f&v_eKk*KNy&M2h_2&-Ocr;`^FdJ{Aq8h*XUBMD z19-}GHmM!C3U2ikcW#Bl@giDBt^m#c%L-k()P3e4Rg zX9Ifb7)3t5@_AK)ZCcTN-f$5pFguwV%B@)p<;WRF+Ya$8iW+C8s1%f_-0@q>8_c5QXpU8{2&&B6g({XAp)7fBR zHoU~*8&Z_eI^($$RUnhGy%8YYVG*&7ptY0^7<{jUNNz@fipscGZX{T^4yXMYQEzav zA8`TUedtgn4FoU$Hcj-QUU|v%>MDC_vT>~soV5O=>@)1()UG_E`Pt1|HhvC#Ly;H+ zQgzvo3q&%AJk+NNS0A-9s(2!LmY|wMb4w~LE%34f1a2=?otTW%OO!r?OQK6xT?s+3 zm6~w%MjCF9)V=VzLDY|@?whH6Lp`3kl~5IS_fo(^w>OfaeG{vV5L24t8>F7tN6;5S zz|M>4)G&lYW1jD=Fr-`x5W%68Q_luvxI1&&RRmsUJTWn`1m;t}r2eq<=7vx{dQr-p zo_m@DMbctYH+?7tYH4`n1z&7jcem#asp6qRO;C&Gq}-OriLDb6QZ6}C+R?MS(2ro^ zY5~Ib%Iwu_sBH8{M`IZpvW99cq)5xFJ8HySmD+;20?waZn%aa~M7FBHB5qA$PgAJ# z>}oXS*(*1IsCBx~`^MkQ2PXo)LBXolBgSquwBJ3Q$exy*_SZIHhNF@k6D8}%;V5U; zLCx|vo>MTmotk2J3n;s)LSJM=NKLHKwIh;N5Kk!0mWe;G!kt8-HMpd(nMD~qAeO}gbhy|g9 zO${u0@<>eH5fQYb=DhXT-R9@Bb|MfOkOQL|zHD z{-Pn%7DK)Ii_oixX`KqvoV#G{8YzCo<n+=V#Q{Va{Mw6I!X*191zQ;jpJId(*5-pXM7*gi=aY3Y znt7(3y?}}k+VTtd6<{*Q-54~#zl$tQeN(rRjPuz0{HWHeu!}drjz(=Q$j+Bi7?4EB z=_$Q<;Cad;cVmoI+fTVU!4YaIrFj}K%m%)n2+^>&j8cZWZ^TDnRGyjkAL@;KvJmv@ zXT;_mMra*Vd$Xo!FP@ORP4MaUH{k)(dLjCEIQ~pkA+y2fFd@JC)fjco34@)joegv6^c3$f1 z@B4~tZ@5Y*q&|@`Z6xMLsPpKvjjDYki%SeC!lrgbb9bY+1*)66$yrp}CxRUz72P9~ zcN)u)h`jS@b1+V60P4+_cDBRR3;R8i6q6zf z;!?yKub-qb54rLba@!-Q#+-1HD(1eC<_hl+KeqZANByU-RAJ;3N#7iRxz^PCQz``c zsQJcKPVdW7ts^p&Gp$s#vU+*2$)bqa%};xjIj_2Xsuzx<959`cra3Ou zJu%T!hqp@mE97QWrzVLfx6{S&GSiZ>z5Ot8r8^a~yW5D`>9ii*1%saHVnC>@EI}I3 zV;*iaWus=!SrkV?xo`Z}{XFH+L6dXs(Yh-X9YMmUUEIXV_z9L*UN#2uVRk31J98>I zD6gDydy(Acq(yV=F%GPkMf_zFvYt^Uo2H&NkMEf{qb;>8lRSl@D#`j*Fx++w?YC`)CTB?pdIw{xvt>kg zxeWO*N2NWq0@LiH{h>N{Mxin*%*!I#^}d!@ahK_PPT5H1b0VIC!TO39H|(jpdh8ij zz@bGpAgPYjPtQydZYBw(shtS?I0yba^Y@V$&r%EML-Z z>Yc>*61T(Et?5GiLMYWkOqv0OV0LKoYK{>R|?jf~*?S^Jn+X!KM35HbyBu3S-Qs#M==(%VZh@8#CpM#2GK!8b~S|WIe*) zl_=ByOku8eH89DPa``Szmm)Wdx76nb-x&ZzZim&&ApX#!fxVP_nJt%KdT z4EcF;gp0OA1``2&<_9^|gJ%e20Y)@Fkx(>eN?Kv;=!f%q1e5jo?@!l zC&Hz0m$iMUkgC&MXfO-vf_T%KKE=9RDI+tq+D1eINsN+f8xb_u{LZc?6=7zCJk7!bLn;5{1kVxoCJ2o<)|Q zRO4cMSvCM;UaxH)*D4I{WbEm^!>0SJu)Q$Pd9*>&I3G0HEUiW!q^N@(r#1oedjpe7 z3rx+O`D*s(iI-qEun@NE+xfcZmH4rE{qQaWXA0Tj8om|g`IJWy>}5bX_YUF9^ZCmR z-RQGO3!NA5vw^sH5bGS?`*pd6UzBk^EVOk-u2GMMY`G!7F7I2vZP`_s@97qJl`?Z2 z1+~)?u(6`SoT3D6Jxr5Ol5Kbj2dTSg-Hca_({hnmNOKG_YeTwTV*_3=GoXyJo#r_)mHrU;M>iZpVk_@&U#z02pHs&*treXZO^I091%4rC`er zLUKn-?c_$8sf9Yr^`3dXh--(g!SjZmP&L%O6%FB( z3KVg+8MW!nmFCzVBl22b`XC;`Jk53*6}a^wKp|*o6L0QzuevHKIfl7EL73yPt~t-J zCpW@oTeWUZC%{c^|1JWVZ#rd~Slq#Qta>aSisH>}owx(!)BULX(y58;yNLT3#DWYL z)CMcks+7^}GYCLUW%1Q?E}2I4>aM+eKaoxkR%o&FJ3BA!rO*5y1Ybyq4Xi)~KF`w` z(%~j;*zNRr3MW~-d&Z2vF;-C9-DHi3euV?j~-N*=Y!k;}LPHBnS$Cnq$35^tVLszFKg~B5^XA5IkWWgY|lQ&fsFNPp`oa&*hXeKR8eQ(IZ4RUTR!fSeoCTzM*QwM z+O!Tm#>#qdz{_2sb4o08rH{2AsVG^xL2q6T9w4?pH67+7c7$;e`x?F)!FxTqNI#2s z;mlB4iZ%TL_`a2~KTK8UlLBnrODG*T?@*)Dz$ofXgF10RlnhZ@{hcj|m!}vW2B(4v zwu9&Ck^MnpS|;>fylsNF-aPSqUNbEu-8U@Dz;RCn5Oe)dCI~7hXoIb}? z4GkHkVSL;MaAc26a?S3xwQSON)M`2VYHYouvT<=wwjGWFdwAE4DXXNXRhPQP_kGY1 znys`Vd9P@zuyQQq$`RbG>zuxn7+SNx8rW0p4bkc!7T~hp|A3Y)Oufj!w0|k^Mgs`v z56mQItZh-*jC2Bp0mP)m~&COQ_6>P#!^`t6J^&_ zq*tVTd5X%_b$l3}pP@97lH?%g7=W=YNNypqwdtg9o}fd*Wk0z7UdT(B;vNPNgnx%C zFbj|n=9PX=312wvh+v{`pxm(XPUU-zBKZNLpHm`d8?QVf-4fVw!ty81S*!Y`x0@}K z-UgLMQTPrtX1!D$mnglg;GcM8SsR8z3=vgqDc4->O|09{Xi_3Lg7xKddFmot{U;h4m4Ta<^!NLuf^a>srRh% z4W@}JotOvU|EZNdLu+(6>z=99Q5zs+a{qeSQH zjHCH}=LnMyFr@!ardt1E7WUVnpKBpO^Vzr$uPOi)!!heO>C>9t$%jEN`ie3GmSz90 zd2nC_CroRR)nGe;3$v`FXH1yzsm}rQdg@gIl5IOXpa@9L=%P{2wZDIw}GIuc3=S`hV;yD(ha6 zbh<(rQyGEV;wSW{3xLr}!{0Q(q4W@g5_H)IG%-zRA|WRV*0kWe7moYMfQb({3WMnK zm!%qiJo$Ir`PmTQpl%1yE!tC)<;C0as{Ng6qri)C&K=* zZ~n<=9Ofc+wEFeuo`g#H6T0iTO0qlJGb^5eirp2;*B@JDvdG~Zu0BMc{X?_fle;CAJYQmE& zW|iXQw#$vH$kkXbQ#4~aW;$^FgnJ|52|&~<3!#aqyy67_VAZ6uR@ok*i4b&w1G0gs z^bG%4bo5VR_s44j=anO?@`qBvdG-YXz#B#`rqbXZ_beT(wC5n}V52WN#_?n&h0p@h zsUSeINGhZIgkD>SvA24@Pgtw9G*BSBO zf5P?*>SK+Jd}|6fuwHy^Q_$FDqzVn%4e==%`63)BeBeMEgZ4_=kfo20>DQm-dubqP zkAeEnetl)x4*|K;@jY<9fUZ*g9D>Np4_gu4Qmfa5dli}iZiLhW%=U*WjuVSgh*7W~ zlmrJxwBmZizUiY@7=3W?K*eS8pzvk#B{4jLQhyu)pyI9r&_3AU0QBiGC2HK!kP<>_ zk{>@q<_)JgeR2~f6TW|gO0bw4o5%z?Y)N9m{xyj;?hTkY^6k$*`(s;w@tME|By*K7 z_4z-Rss1qa7kM2x04pmJd8mc^v?nI3-4|_rSs>6~jm=VihK(cb5vR~G#7;`r;&!fhZYKLS%Z zivBS%`rordP>YajQyTtQ+8EtqsG|`3C3*nur{taTJRZ7jlb4!~4XKk0lbmouW?66P zz=Yo|{t)!EI;4s}0N_pocEcrD@A+VjP@qc|5C#(XNVv*+f={JN3hUTlc>4H*vbsRW@(80dhgo%a3{bUKt7~{ zeE1VZ|H-zQzqYXie&axDU;P9m#9Hn4M9rOzcIXfi_X`?B=nsaT@an(l$yZUp0t-+K zMy<+qHhvWg03gox?7yve4oQw=k=c-;Ir-y;_0WF^${>-hd`Vn?zee^qi~@%Ik$tp( zn1$=W{4K3`hzLl~l?jC5OBMXvd@OP{HILV09XEdx6=);RuS=XgH<6(3P*hExomm7eo{icrKvs^HP)i498(;i1(&c~F2563_y2`IW3 zIx?%W=gtjMH_a=aN65_*Ip5;C(u>2?`Fm&w7@w8*kitHHv)l&b_6JJwLb>^Ffdi(Z($S@zwn4z%nYcdozX}y zBo!^12z_pQ*Cf4hLp%8aKim`GcAh7yT@U+t=4*3i?VjUe{4Ji{*gb<61CfT5+&(Yh zx>bE}RUvo;iI6n2L)Gqkz)1RwZ{J_Bp#N|IIJJZ+9RKDECC5EDD8qV4*MiPLI|g|a z0rKeYaaZ#z7#dpEeTcb0|LT_RX^vkJqR6-{)(`V&yU=9~cAR{*dZo?skq;IG4zT@k zud)Y8dMtTCF`#Sx=9&$-|JmCRkZ0@%sNlR0HZ9Q#GHeb^mHazEeXx~Z9RmdM7T^G~ z_eg|-f{P`8R;67pCnH|{(=HB$pXALW6b$?r$0H!i4*}n=p#+;#?MXgs`bv+Usp$|2 zMUm-*Ia7fQvzqtdR6|0Dl_>JRV)Fzv@zCTxkNB8yz0eAR#{M|gWhU6WB7^ZLVrY<7I%z)nx!c$|6-xxU$pe!`S2e>4)@_t zcK%lhKt522Zun9aANdXDuT1y9N&Zq7qfaKfya4wZOfL9Sv@>#oC0dj~$4c1ysV(}2 z19F_c^exY6yQ-KP007l+grH_!Ltl+NuTs<5Y|ZDU;S)he7&{GTJFe(`cz-4U&~?3k z=Y*+j2{g)upSY3+8;)F_W!{vsU`U=*eXaw+iT3O_fIP(v(TYlCwc(pv-YRAgRl{-g zi=cUM0FZt>kn{pmHU7l9ha|z6_%*ThZupiYMdRrTFI$=%Eb}kfgz$Vct|r4tz4QTq zsrWMQQ$1DJScCE)`(7!$*pa16(u&vWQ`#^wer3CEh!6`&zWO-v-XcYeI-Y1$_4#T) z2TxovXfB>IvET{g=!0DW2lD~>;tlfUk&yg7U;fGMY&a?pqH&Jbfm6tELO)Cc-8hPQ zW`4dm?=QyT9}WSDK`P9EshSA?_*n6WlOFEWzdG~h{zVobbB_lmkn8ux={*0Hl|NiR zx*#h3xFcx(iIe}*KP>sypN7zX`|l5p{>7itl7j5jfb2a4V!zt?jmu(T+nkk%#11kS zhM)9M!wiT>4aa6&tA^|dzjy-Bfn*cNRqe=I2Keuy>*jMs<`RLrG)M5u5wg&W)4oq#`&}-D3hMHoKL0+4d&bc{qV4$0zs$!NT9X8{KvTaK+C_K zrq~KfpaFcTMiP&kIQl2pWg54)xo|0%Mk%`_8YZl9pO&Vl-w;7M#X2vg%5~~ ziykM6g!%^h-VZ%HS9zpD!Q8{+Xf?r|PKTV14F9yX@ZB74T97~DZTyz8Cjcx~;@%O4 zUa5TI9%ri_EwWqUrAVTRX51@HRGBpRHOFB>?c3q@pONOxno!U$iQoICC5vY+*QW_F zCOz=rK7e`x>Vqy|s^y<>^)U2S`n_1Y|McL6N2E!U;?IEJ(76;le>rj)Tq{r?H_je>r2&19xebF00TiJYC-lMLakpCegiK5 z*a`#zT3vNMw_ASk0*Y@|`S%Ia4!F0DZ=^B^^QMtz|pUySPtgP^e6YxM!`< z8o>x{6-{4)?zt&9^NWeK#z|#<^!_dylkj#MRWvA%c&GzFQIK{Jajgdb7I7KwpAiO2 zG-~h_RE1Yt@*v??yM;WsjBpk;7I%-QX1|$&;?VOr_*b8e z8lLrAp|%O5vO6&6IByE>HQU}D64Dd_0D3ssr~bo2CrWL%kyg{UEribpQal$OR8hSo47|UT1HWkdzO_8V7nNKXjD%OFDt+U-hV9JQ0yspIG?m z@ty8Qpqaotq4!mIT=Hj=G|R-qlt)cneFAkPpaYod^e1XP48IjY8#9Of-|TzlBA=1u zE(S8BqQzi`Z7U=cl>*Su-U$`e(gmDr+rJ@a+7fuGRx^q(vGvsx8cY*}Uz3tb%C|Hx z#4@95ZHz8Y(%QzZE^LYoh;MFvaIZoQf!qMW*Xfb)`%lByN#g$ozMUX< zL9BOrJPdz_FC1vu)Ptk@^VSApuhXAc_%D(4J9{BUf3)#nesO@@YXaGO2)}-{`Wt)s z@SlCTqCB(8IfrCrT_4?M#E&5V#90S_+{+un4nlf}N^PEks;E+=8g5#X`n7kU8Je~L zKyE^7A_mI;!_L0mUehf~j5GNOC>elqpm!F|p4bcT1-k!)@h@Y4=}VR;$N|v&pws?; z1i)~@fer^|gzmb^5Ul$4G1l)KOf6dhU<`GpeF}Pt?T82cX%7zW&sRl)a^81T|0x1L z*!0hkDYk-gUO2u~uh4&=zU+RkOn}8U>aXGp-*xc3dpzreIQC>EWCu4I_YTRLYuGAR z+h2*Z^rsz4uDk;P5cI(AWIl^t3%iwnF_s-K{FYzCK%eGcU9yZb+ahfatx+Y>Jv?CRX>&#>Z67YAOc+_5Rr4@!iKE zxDw^BMJvEKg%ei)6alz5O`zRGzyWyRS4Zy^b;2VbED(|vB+mmR?~z#hpIF6bTF8Q+ zaPA!bVHZt@x2^xd0>A+gKk_gT>VnMwZ^-(4S{w9u)csp&ZP1@k_t&VAivWOSF+L)W zzc+^i!WiH^D4Y)=(=Q1>(fWR@G0fa^AjCzK?$V{=<17H8RsW!M_e@ zgGbRG<@E#rNGW|T6;an7q3_~HKZEK~f)W0GWLh!CVY6JSHKTA#wFFF5zT{K=A%yWP z7(WGX{Slg&(?FU)tPBzQ|Hn!|D_?4K(Z9<|6Mq{O6y@rg6c`uJr_N8GkxZn?ZywxL z6L8ye0>D^$k=0E|T?^V_O*-~6T0InXa_&R`jLgQCMqYkZX(qz040^V=zh#{J3RQ5W zi>(iiBDM`EhVj7E#6KbAA%w%k>5Fw^kyIkKD-c-=v<7dSKw>5q2ihOoXHU0$P(uGE z`2YbfSbe??5T7wp@+~WN(%Qx z9$k7O?^O>u{4CW~iYw3nh{5J-<@?I9*ziZxfmv>RtF4a+$2sV)er)lU#PD|j2iRKn z6jmQoQAh}_@o}=@huPT8%lasN`kR6%bzvomhid^wfTV!9mTdU{iEBSbeJ@{X=HS1} zHM7NP1mVdjO=2|i5vt}n-?x+l=MvD~TK=QZ(=wPDbW4~}hY$?x${h8SvsoV4oc=sm z<#nH}NyMZn=t~j(dsXB5DUSNMKKoG`DZhvtiw96@?F^>;7Sw-s_52zz|8>-q7vu}5 zJgM+c40#COFuL16N-BOkYfB1+&ZuWWNWhq)oNovt5ja(P9cJN$4~Yc>ctURc`Qd#F zi1~3N1x=C{J`yRioZLrkvEGKXK)+8~ocGlL18&go~nw;Nq8r9~>hM-CzKC z?#N;Tw-EwkQX`22dm*PHiJeI}MfSX`z@q`+9oPya5AIiRuo#dO&{IH>#NQ&9CSaZy zoSz2|Zc}KIw{NTuhzIT)2|(<|Wqh~<@GX!8Z@#2Y{{Jarfu-WcA9yT}$DuxbundSs zkcwfx)XM#Tms=LYz#9qv%RM~hXlv_iHw3|f9RV#C5~Gk4Pf7%J>a|23cYC-mBLn5} zmn4dYSx0RWa>g(EkO^?dA&c;Hr=sNDvRj9O7P1Di6-(Fx;oDC!ZWU#);b0pdyH;QtN2emrP` z%r!ldC%?LufrPa6!Tuq@fXso?u%kYwu%tq<0M zkPp%VTKm;x{&)BVWN4h?t>Xnhz=KB;ZzYDKLJve%rmNxQq7aHM8~9mZ_e=jj3*mns zmFENL@Zd{o&iRi(Y@&t$658{@QTQnhQUfFb^hDW>@E;)9_r$eoDYJxv{_Le_p5j_w zo3Sa{F-46mLA7lU3B1UgPD&T~*(JtdX5AxlMI23pvT|&vtmwo~2xf9({5dU_X+SPu zzA^wvnsSc(2sda+KtA{YQ-}Vbp$fv&?JAXL(^Iixd$I$-&4XA#f zYZ!hcIsTyd;l6-6{if*=Q0trCXrb6zI5Fz>Fc?h&ZcR2Ll0#q;oah2;8eYgomngs9O z5CFW0DeK`Xfbt*_E__KNRR2gP`um5s^0&_f1J$bn9QjhGf96(?TJ`HUsHpYm4U`15RpsD$izI7on!32#ix#<$IEDEQEqAS-e>Xhvh&rPC#?4vMr z$%Q8JUco7HukfH`94NtCm`Gwf1nKiqmw_JoGgcme^LYm6OPty!1vq8vmT2AZFB4EQ zIY!dUv=&nq?fsrT1<)NHbd2w-$UY@@#sf?J$5Fm}J?VL(XADnAcoTI_VAqhpp?4R*bTcpkt#D?3%(eVXwJzxFMyYl^ZL;ihLfQ_XHik!y(D%!?(} zCu>BduLY?BEgQ1!MJki;v_oAomd!>rl6WDoQy29gX$?t@EYF^HUg zE5GB=+Im}X<*k)wyvYSW5gdV3(z?9G)LC2C-T~Wg-#~LoJy-#6iPs-j#N1;%h)}NN zKH%cmVFdHS=)yM3_*K6*zn6R$1dlo46&8W92Qzb6N?%ue2n^iSNziA*#&d5ZY6QvU zH7rCH&rT@ZotsH88d zOFn>SEQuprH|;ASgyMc-CPzu#g59<90X&gpRmJ-(93!(hE*h8`o0nj)fdPEiqV7%y zNZaj0p^4DD+*HeUc1HSonNPZ^RcDf=Ctl7E2s7~$2Rxr}Sh>0*;H?S*lOZbLrx)$< zDN^1G#1f$5j@&VldYed1XmugLcI@QJ8mHJw+KL+s+T;L8`p*@s)s;-J4=(u=b}ICe_ffAtvzdw*JRu_N7s1nypWL^WERlx((9=xDaITkGu|A`z57BjrLt@1ugEDytDe82>fDzg=4_(qEx zbXJSB{>}w=`ZZD?R&45Io66vpIkn&%#&Bh{Z0@%=7+JwGuB{aWl*PniAy+x4Sth{B zqcb2~?6}ERI4@$@Zc!Aj0_CnvZ{hbnL&^0$1|KcgV*(BL6W@d$`zsz#5i%%8MH3dJ z4Y)3RzXUq@?<>o<9`TEr#ZkG!E177kpJwamZfG5fs=4dsWG@ zE%k1+jZSC|1;n|!@rcQI^$i?$7G1=L6-RKyQ6dP zY<*7*zxxySFk)=@$=k)7IQcvG!bKC1fQGXg_N3eAy!T$Q=ZB=?2?8GN2#p-JZ?ugY zqc)6s)}>B|ky)v%I0AM(Q21Bk?XdNpFR@t-)k;<_&qrKz#BX@_rbcA0lk|14riG7D zHg_vaqJ3rI0X9KvuT*OHiy$fxI0=~{bA6REYEs@waw9+ykOQW`6`jt`t&Bj~;SH{F zB-mqSsrT+7lTu}f1LB+gnPQXYjd{`om@Vg;wYTXw97snT3>|NT(9-x~T?xa`KAS{$~U8H{6O<2 zy2+Z+$}yBAv7i!hbd%FF@(3ti%yA0mlLC!gz0YYX)9eWv#%orH{@y90Y5gt=x6Y~+ z^z6@Rl~FFw2FKlw%I0t^sFyi=_q@Ye&qCpF(GQk@*Uar|d4(`$R({&G3Y{-N8`)zr z(A8oMzILldzg99AQ$_<*y10f#qjkqk!#uh?t&o^ZONLQ}Q5pP!Ju4 zE#R!Jq-Jk8(ORFMy>Xd%_n|bw9Uscwb6RkseP*G?WYbJ>lZ0@B=Ds|4$Qbv2;rXUZ zx+3Gw5njG~%A{8lCbaH0ucZgmJ3+%I2NlTrnmqKHF<+#l^E)P3boKD>47AH;7r~&P zemyj&M1w`%UJ#g$!FVO1{BdfHqvxHfeh_e)vxZLP+@IV#%^YA}<5?3c?@ixrXFk5PM&+UV z*k}hvIb+tUCJYT(c5p{wi)%^dgz-9G#i(Kg>5N(<%jR zu!vh{CafVN$t0j~mwLDMpaEfYhiYiE_m-$~xY~+ks8}giv@td}I6GxocUYsq)q*S% zl!12s7yauJDOio-cQTTw6Ke(5rG{nRW z#yXvu4ObYJ_q;-;T8Ym!p^7-&hjvG#^)_gr%{!5np(|OT@-oghBC=x*b%pYx4i=ED zwG3YM!2&-qow*Jau6Qtpi?>vl&l)zo!%2I7@KU?Z2Bk(kBsq`e#CiF=Z#`IKjBPDk znpTbQ%ZYE@hBa(1eU#{1^m!PbOird-f|N}3RL_dFz6xYpcSM|Zj29AmVB)tE7 zaC*GEcaVmrHE4tpss5%bI+!5!5}rENLb0 zlWM%OK8=2OyIi0_bhd!py^3=xvZBkL;x5T!X8npuX<<01ENjxihUesN_%bS&5O?y~ z=WfiebSdxP3z8Px0R#}Z1n8cc$$J_8a%Ipw{4}S;i&Z) zPQCBB8PD1pB#;6X|_$-FsCsv%M3_=4*E%%N>l5qI99(pDTYUz$Qj0VxTe9(5#agJ_}k z{rbU7csX5sye0uv@eOin8J0C>j)Nw1&?04X+={-^iqNNuS!t5eG_i)ZXdMNf9h-Pa zB3yc`ryo8@S#xJ0eZ-DC-Yhi+FM;#Snp&WvH0$dgf$kuh!o4Y8j%U4Z)pYq@#O)WK zQMxv&9=+~QA!>xa%0Y6(vgFyJVpT>F9--&rB+4r*2=t}Mf_NhUIM zC9X8=fOI93xBJ?||DC>b&y7>j{34Ye4^bH>r7$#hKP2sfY^U~n{jOR4(OJeW>bU&f z3M0L#${4OK1wt@pbmx$cgCJ{jonDf(1y{ILDE54{g3T*>YDaw=F7O^@baIpJJn$s$ zZ*A<9AMaYBC#Gwr%}bt5^gaI~L4!YHkfzCm)14$^zz_^KM-=63>(${xp;N|_Kb$43 zM^PfLYccShGJzS^y*S$2ac}_s3rYt=c}0N=jh*;)2js*IS7#Ar2>0L(4cNHv8Moke zIypYpk~TBP$d@49)OkOhqWJt!xx{^xofV&V9BM)=s|{@op&l~bnSEcneMmvm3$N$m z1d4r7WaaKBFFR!4`WctSht!rNGLT%SrugCt#2{Ml>B}l`g*g z{QcxNm%%n`A8n=}oUi>A%vxwQ;CmHaFkDEgH0X(xrs()x zn&0S@8yntIOToW!>QUTSZ;EbnOSw9BS20z%Mx^U5Uz|DLx7+N$Tjf19T`!>NA!`HD2wU27eYEQ;sEKJO+~ab+c%_&f*mDg&2_w4o-Le*QQ@nT2Pn_) zY*@nG4fguX}{_NUs&3wx4Q zI+9RqSjA+OZ*~e%om%RgBO}WfZY-;`H0!1LVRQRO3J3x1OFCyGb2n(B5}q4U@KpGS z5oU%rdc~1n`D@Sd=+l{bj*ZYe^^SQGEp!T~_#p6u!$GI!yxNfYd`QjoM3RqC-Gra+ zr#X0hBXdK{B;fHrimsxI7QQB3>~ADwJfYM}T?6)hpp>N#?#q2U0GKTY%Yyk*F`h^y zHL@8Zn=fxQyO4joB9_05tSXLb|#CXPCqkMm;)rgjsWJE zowj8@LhZQb7uXHVwnvi}aW9PWEc3g58v#2rxe8~-U;%CX)B|g&iS?Yt1hp*O$etkh z(sAA5qwn1|L+6mN(IAXrkwobwE15M;R~@#f815e7S^Lx1p+$lPa&Y0aggLn8G)l}L zrW?!0r)x<{Dw#!7;?(p#oK}YP(!kFpXAcfNu(65g>c-=s z-c6IRO-^VqZ|_q<3`fx1^z?%_7hbo%TnnG1f6a0|#A>9wbwu9eYg8S7jk3vD$YHhZ z3^)d=rM^`#o%7<{ggnOLbPs^PRu6Kjf`0ZLPQK>DtvV&ph=SIAkMaG~dU3n{cPxRH zCgrx?0~8r;pJwD9G25|rR?ZRS{mG34C0fabyR5c@r02IojDoSWzYx_r_jp5uu;_l%1Y;1iT22g+ zGZ?GzrCg$4IP85pQ{ zi}Q}#`tJsUea(PlPzq^Zow{UZnlC?jb!Df_WNU5<;KP&u>culQ)iWcg z{r4QRWxnHNc2J!nKBhs|nl{DX37Z9pDGLiVx}KoMO$9HcOB?%};uN#c^-xSf+h&RL z=x8S-vUZqhWSo9?59JYt_o{!lAE8?w`q2S7Z%PA2a6NyIZFahcHLjKZws9a=*dnSs z;*HOa;)}T~Byu>XSHoa_{7VWhI9o`@Z_p`GWbey?Wl0b>8JRr3=z`Nz*|Jr$f!E4U zoPE(_toe$RnGw}PPS^FE!<$p3$YAPd8x$RhvA%t8J|&odO$!`~3V3TmH6U?Cb)+I; z-V;BKV^Em4b_XT++OZbuYS1WM=`*>$Sr6~W!hH(;gxSU0`8<9&Gyi_v#@Hs};`Dyv z=kA58H85iCrdeNk< zv3;VLjNF&7MDFl{zP2)D+nHA@cXxPLJJ#5sfPl9>w z&^h!xWBuFb0TjXnUw7b6wm*_hJCDH{>zgUICf%Pyj0kX5e1X2O>if`6uw->>p_F+j z-tz4Ei9=L9(e~Yf@OPXa_cF5qye}0j2R^l7gHt)(HISQjgDt%tBpjN@)D@;ScPS%# zxC|NQoOac36;h?cO$h*wwP8*U(9wy?Y+}Kt?O>~BT+b10K4WloueOb?Qq?Gud_5ix zZF)Kw<2~!)BuCt?$nezevd)N~#Zl{^)~Q`tuqXYxvu&DKZ#bfr;Ow&*f)-`BXz0oJ z0E%S4(tS$>{waZ`TaPo)D7NnK4#DhMWob5G645`HmcrZt|7e&Tqbbsz8Jw$V=SjMoR|T zZ()+N^!5Jb4s5(|vgB)8x6YbFd@`8$EUvUT$!VSXFs9K7%6kTjHOC&caV_fDT?nl2 z1w63WN7bKlQsv%#n+tPM51VR;$1@+J22551$WR=+@S$VYPiF zx{dLEKEs-X%$csMgeH6@y@?b~)T_a+!g2o4K5ATk4sXgU8M0DnM$zhqe}TrJW<5;S=D677-{ycNnDu5y443*5Vq!yY;z{Q~PY>jZ&-R*GZ;~j9Gac z&LxeYeLGL*`G+0uQLQT?vpt!uQBC4r?YT-8M*b`9(-r3U7Vt%l8#YFDpyQR5f>3l# z7RaET8uZrfzVScWd?Bxap=8ichsaz4gyE4+ML)!KTawGxFcZY;lVKrnKvg@8qy^u0 z`vv}Jkw_!?EyWi{gkGgINjVq-moJ|S#38od;^aKd{Is?zBE=2<&kY`rf}Nj_w39YG zO-II^2yFLWjB=>mR|dWU(huI97SZ|Eab$!%QD{QRyjDsZeW9^uQ4KjT5@uFZ1~(hk zh_0|^TEb26%hF%}LHs!k7O3s3CHyxn<<&>|52h4?!ORC}z_=ir1@m+>yRd)F|J~N% z;LFNMw;lMN87^*sVG`tY@6RkP1lUmnlSEZ9MqXnFbUKqJld$(1;4jXv&!~$8#5c5` z)p_7Q#E(zgG*0}F-4h3`7B5aL-%CGPG>jQNdEJjYUZ4zW6>}2JKk8Znk=LB-W+Lm3 zdywne-_P3YytL^7JgJEyqe-{Y zpb9$c&ujp;s@VQfUGK<|dfM!>(hfg}EnEFKPR4uJhiT*-6Hrd8S~U2EVwxXKORXE_2hbJ z+K9=Qm4NG}Ry`a`YJ$0%%PK;c8`DE5s4YoI1+OtU>Cggh&?~zc@)Kzg9R9vq!lCKB zD5RvW*mumL;e&+#N%^WHiY1=AuFsVm?~nFY#Sh-VDJpXT^ch+49w3$h%D{&yZ% zy3oB*!ZHHt#2!QwOHhM3cPG>>oBZ=%b^@~O5)htNN)rgB%9{rZyxq2BxAqdvs6^z5B6gP$c~Sm`+JNSq&tcuM>sncJa$1(JP)(t#*||Gxi! zlIUQXbAmE~G*VmSYg7Aq=sFSvO^>jL^OTMjje9UpNuPa$INnOK?5J*fQF>-a?QlG^ z;|Ob(29$Rx{@Rlk*FI|ntuF-ke#?O`1%@y^U*@e5E74v6P4&tlY$e+fSNRI@6^#W@x; zK1Vm=LVuF)`o@=L3KDS!M_k9*pvzp2%eDz**H6W(mvBCpfEh>c;a}64nx9_!m1JXI zxg&Iw5uKtkRv)o{!_BEln|j2R&_GHg3B+5g$CoG`W0MDS?w&Npqtp;B9G3vRmoC5@!$RxNiSJP=yBa(dk78;$t*9OM7ZG6WNBvvm_f#g-_3#okz?OGIx|rH0 zfExKHFy#kvH;M%BP%U`*lbF)&f^)Knh+G5*0tkb{J43lp>$C|dQ2fHgF$h2f*jORg z43UQuAgV%y^?ItgrIYE3K$!}LuqkYerVt^?U~~<`Q)wVARXg_$Yh!XSS2&Ab5F;Fx zIXY9sl^>=&n)d69=AX2g%dA^0k0xYd|1Kpw1S<$*UdD=5)MW3Q%H-U_=yTXMTZKIy z=wzk^PL@DC@e!w4iB}+4xu*vQF#YV#Zy8wuI86S|T^<4uOQOIs3(YV$Y!}^J=WuXAPbGqa zus|EGJA%>~9G}INcdEUtc}T>JF*v~D1?c5%hX{_Ex+vQJclqn$mCnDOsx*r<>A9>%- zTf2&OL_k=u#AZ-E!gb;{D77yV4zeV-(_%h&oakY#}q`x>J^hi;tNx;ul!_ zJ+<`4Sr=NkqajU$Q)gY>zy_(Ax+n1t7+iIlDgoX1a5U|hkHk;r@+5*CrscS1bFjtV z_uj{;m#MusYJ2l>b!F>kfSlP-Yq`!y6n?ezPQTj)VI!wrb4u3QoUEwQ6l?(i6PO#b zYuaeugNZe(R$BTEt}bbz7*t0DiXGhS+YM_x4mYr(LZ$0rW|I=A@vK{xI^;X9!AhsK zR{SUtcU*PSON#rph!c0LFdtvPMftLt@Ij*ySR&@gj`HvS_wy~|4 z#n&e*<0c|E@UsQ~#~4nz0F32f&cmHVXwk+0;QyqPFI6d{}YG~o{m>aqlsU~J{TbmP8H(L*0rN|;^9?$ zy(5s$L6tIcgm^d7V9ta$r>M!ZC9);Bu!fe@Wx&TX<0NDnoUt&X{Hw|mJ}qegI`j7tpJ zqmE*XZPL@`{o9O1eRj@5Y6pN=DDXaV=IrC+}>NIGINYy9u~ByiqsWkNlp= z;JlQQ{`v`JQkdxH4qlD9&AdCn25yBjs*VLEvVK#q;?U){xE_tqWXJUKJ;!e;exDm{PXM1i^Atz5{SHBRs3JW zP+^|EiQ94~n`lSvzK=OBRAlu^ih`#Z3^Fdd>7)>DAZSAHv##*}J$ zVsAe-|JK>XHu$;8Y=6Zj7d*PLwH?O>?`xiX5fpXX;7l$S)Ey_SZ1`GBr3ubr1(^Jf ze3V?AP#_F{a_;<6W>9r?n23j1bFUFiAG(T)_E|El7#B ze69*dIIN@qF;?s_jtJr52B&l(Sm;IdEBne18=C7DqW`SC*Apix)POrQJHLzVrnhD_ zp3vc8n#2Lgt=Y|DYD7>%r8Y${fZ2yZ_F%o0}j6=FvS8>>QcQ`T`5t6Ae>|q0z$y zX$0bNFTP_xx`DT~4Qu%+eT+57z4R*?Zii?)!($Xb{|@c@#CNcl3U}NqXSH%oi?frd zkc_d5XG(hC^8gscQ%s-z0`|H|Mfh*LTBC>#Mm(##HH4l6OLXF4o>IysKGTV6uPhao zstISY^Ss0i(yBD1$<(seHoses)aEMN(x3*C?=}{DeSZ%pLjMwhTl5v zj-jk0%6W!v&gB0cs!8h6_-NX|Wg0llOCS~%76%xPlu5F{AN+V^gw=kSu z0zOOiTSFnXVdmm4|1S4?e#yKftc}S>^o5=+jB|Whvrbu`_W0!zouD4>w@q314psEA zXu%8C6QmJHssQ68Mj!THe8V)vvOUrn&(0$fAliLDqz&an3z$Wa@Y9GgejT^XWrZQoS_s~gVvzBwU25yWc%(61 z6&VLg8N-qO<%a{i+TeDzOf>qit)RO}daT_gNGFM{4-P>cH(J%V?Nd}mOZ$ef6J-am z$_P2vu<4{C8O|DYlhM7Me4uE@714W|u6Zh|&ZkS2&f)>(9GG+s8}Xn^Ko4UYZumOl z8Nx=5H&g|o1TX@O#`?PyJ%Q|o9&-Eh3qw?!+Qfr@p5?+IZqrAAac`9LPWUtQd-=e+ zrrT2RJ^5!kRT9K!?BC~ zAva|jglfHnYNXsHyQQGH_0!G^#w5TK<6%x4m~g~S?^Dk<`zOGh3s`~q*~-zI ztlJ^)GI04WD^7BdAu?qN45Nsz}{$rn}bw00RI3 z3jVuo#jYG!mB4{Bv?rGW`cMDu3Yt991FiEI?b&A>r#Y&YX{_w9N)^Hk{V7$w{MCC( zAn+S5WAa3RIAX(!J^lm%rC#&3pL&BL=UU<11CA46$Um-bJRaEG$Pi6pMWH7 zd_CBvJxYTzQXfbPV*dBh#o)T9F|0AlXMmb2sX{#FIle!HsgU*PbU`;T(sJ;LWH)iU zUs(f*w7iuE$8F?pCDmm_oay$~VAoXX!`AP-$AVM7q@47unQiR)pB`y_&a75{*k6{@ zBVe5>%=}|};D!A?xes)JbV6+9xHmj7KL;*jKUQ(g{FzYL*QHEl3U{61C1w(AXx(IV zvt*y2wWAk_fdI}vd73^tWDm#_ctX{?OTm`ur{sF_Yfhq@X`Oar2S*XigkHhkHc>?N z18SuHgMpkhEd}2B3_fB#E*#bZ`|y749x{tc6Hy_|zo*vSn4PPm1cB*a#~v9~>JVNH z#p{)IW$HYQiOv|Ahz956vIvbPx@+b~tuv@XC7A)(oNuR-r^pNtT-vza32Lx+Y`aP z8d_4sMrcBh3GTeo5X+2db9WdEods-yze*4OyDYk@-lFaLjq(+X*VJ})2Q$GLwmruf z14?BKz;ze(Q|9u@x_GC0HU+*OZngW$Cpqd=IOKWxr8fr0>r7e8KmDb@@I+T$nB37-LO4n z60`zj(E4^IuOmoKap6Ql2Vh)`yIHLsnfocStNo|Xl_pR@r<=5x3z+H9Dm6c201}5< zW`r00uTvgun*h$7QsK|2-myIG*1oUy zEk+BJh(DZ)DyT-clasr{Q;%xjvemY4zXETKcgR3KH5H?N>|nOX{7B#wY?;h zTq0+;4*-Y#SM&_^vm(k*chjjG`U#-%FM%?{QyC33c?=SL3i_}u_E!ObQmz|-LPGd8 zC&$N%}~p|39=M`Y1qfiSb9?}hL3j!q*ntc<@RND^n)4SNN z8+V0QS|!aS0_qsRN0qj~jOphfY5hivA6G;J_qSg7f!hv@0(+n(o`8ZN{@_&)q0gcr zi$vzCAXnntLJ182un_8jC979~91&vC1Hn8100iv{@K;%`x#y3PYp3n*gwo#BD+s|IFa*%X>s{p^uxt> zFRm`d-Q&@{y$b#wjUU)WTSxF0BKD>1SAez~zVe^RDAse}YnUl?$1K3FiORBmJj(+Y z|C$C29;hS<;D>C$7S-wfnhUO-O=~lCdPwCMPoI!+nN6T6G`*g8n7)G)_5S{)S4W^y zxv-uNsc~u#*bI)=SZ!?Ux2#2iNx`WCQAf?^a&rp{+Aq*1n${6q0#Ux5XnP}$q)j0h zL<4aMUW%EXB9VEf^Nh#K{V;+nlB))N^F8V}Fwjnw<>}+geTJN0P&P&c2!(B@OwmI5 z9_Z7_ZXrh%10(z((zD>+y@0*S%&0xxoUfSj-po-iCSuiYc3^v3d4(|VlgKpYKcz)d ztUXe{c`5yuOfU!e+-+t(>uvz?Z!dQJr}aVVm&*l*J@#QTJfWzz*(1diV}VQ|kR2_* zm?(#1UEkGU`rFM(^sSgWd5@{#%JYRw_)d3VN`v`+<;gDHVHf%8Gvwvgc!v`#5eE_t zouTu|MEhJbb$&6F9}#_buDpQoj1XE6oh~A|q#?g%c#RY;>FDxzTvnVExf6*YaG))zf}D=Pg;*>*xt4r#GF9yEFb08BOvw8%IMZ zox6eLumE2k1hW7D0{{V?V42P8AqJNY+P6%fg9kz3cdd*xz4U|rpJbVkaeQ*wnP(|A zd)-Vfy-yC(=Gk`Z1noh1Pt4rc;T9ZF%-qqC_GdQ<=|OV4Ue?#sQ;J2T^OtXikfy4s)%plHP=@Y?w@%v~Y8G&?OI=y+_5DG8d12RR0_jj=N1t_Rq)* zSih_u=V`hetXuY_gSQn{aUmk8si|A?k)iI+Z5=OYRNz0C>bG4rtSQcaRC)9fqk!1} zryq%N@_!%RG;n%0J(uuM2*{*c=50Fhl#tKmKZ z4<-8}FSj=jfUhf42*t}+h&evU2u46tI!?g^s-4W7J5oO13y)k$iNHwZQ%-xavM6)^ zsy%Q-k2nL`o0RxKY)!$8Hu}{1`fzdw?Eh07CsYHaWht(*K0yO2hFg~5u(!FVCsNTX z-}+7b%1nEs`n0@@43??%W}vW;T^hrM5;%P%~3NLPkjBNOH{0%rxswVl-K zHzP#zKGPGNoQdvM03DXpFaQ8XV%%RbSZIonF45=T^XC*y!0L(R@?SkyMoc8y%zq`0 zW0e@PcTs1g1s>@g!p4EulUbp^XYg!pShY8;5^gn0$$3ZsXla`Q(QX77C53 zUkJ9UL5xm^@~iva4XaA2NC!GqMR*@xll_&b|ML^ur(pnxxRM~6^0DPEJVShq3Ow@s%kJs z9e?@c$G?^y=sog!r?)(0_OetO`}VaT9lX4;j6gcbn839~-K}$*b8F|IY`4nq{T>>q z+wJ$XKN;@$RJWqn?V`PM<5-v8BkX%J#5m$o28Jf@nX?R|ZnOPjtJZCNjpf!H!B|p%*@r#HdO#%TC5RbqYWSI0#?XenK<` z6NDiOW$EPlN+23;lwb(;|1X{XUdYD^55Gi$z**V6$R}8RmWXiHiW@u?l+Bi-mN|0BTSG5Wt#z00096UGsbM@dZHgmzpX#x>bz7$&98_~s=0{rWwJhY0%7z_J*lqG<@5E8&d3dUW zk-$-(o9XFA-u5KEb1IdWKGwe%)&Ysb54%$Ia{uB2BlO7{g8IQ)W>pSpRVnN~JNuFw z+Qy0^DXhor3l_=?xaMAWT|0i)R(8Nb$0#y#kgJo+FPfWp$J@_{YS2>}|JP2-t>YTt(z?6o| zX$ID2DEd+Uao{r3=!Kuk;7QZgFXxIgbQKq-`SY$9ss%4prDL`ZbGdz6qjUfOG<4R8 z00095O?lC^FT6!BDO`F%0EL|tiQ9V09vhrvd=#tt?3455rp;Yc8iX$%QKK zH1V#R+IgWI|Kaoc>98|#p`ea8;Y4rW5z)R`C9yu(Ovse;=nC#}(~pV1cZK^dN%Kx+ z!?4yQ>i8al|7_@I9v`Zx&pif(08%(87|1!t&;Buz@e!Zt3An1Ws&J>4+99HOh0nzn zSL6Qs&D>A*c8JK4ph(0>IGI|lw}x+zSX8Ghm7j@?P6l<>U8U)7HoIeCl9qZmqEpF| z56TCEvbA`(1Db~Q*MC9E!EhqOhxVu{^J$C?=CD^u^idq+MfNx)-Zx^}L|0}5 z^2Xh+8x0pBv3F=+2M3H=3XZpxJ@_Anb99$hs3@R}q0i716h)^FL)#sr^U`|xEa(n# zR1U#JM3KufrFQ%@fok6_h?aBhW3!~RJ1!5Eo4y>k1<8(1Osria0BOCV_hf>7^Mt?w z&Jio(000D#ze)fA0{{R60mM9yu^CH*0-5|d)?i%S2^l#B9@OMbCm$jyOt+>DAX6ed z7xqN?aQbv6!+mF|(4n1UO6)>tVAAPiy{mKJURSlYOv~nb^}8nQLzZR^I4LK#ZtlG1 z`=WCzy~dDT{tog0>} z7G3ucTSwR3fm{uB(~kiMLK66g3BP3MV(*X*;^^PJIT(JjDkeD4_|J0i+)?61f*$Su zHH&rT!b)qn0KT=xAKbgnN$BrFCuK;1_e0y05^;6oxI2Z00RI3@kaIa z+9oL!e~~N+P$gcS`G1X#KHxC5?Ffwk$Y8;Sqe0uV&OPT?$5t=V1%I!Ar6@2w04!mz z+i?%=svX#Wll`f36PMF`&ozA+%kTfYOW0sTson`wnuDLylbg0$PWTCLlPEbyxpXFL zpZd}UETKC(qdDrR7iO8UdcP5FvL}gChyU?L|I+gro>gZ=$ww>C1}k%7@^fVjWGa2{rxOLorTb zAD4V_F^qV;ghvAj-4tH4;ye-F-jh|*2t0H>2bruAOX5jVvt<=epX(=qE zP~euYuzjYH)yW90B$6QT$U{zLfiQ7flPpGH3`^QCFC}ailAo`lsEFvZj8+7|fsvr4 zO<=F_)&Bqj(t?se000V}8l+8R>rS-c3E%Q}AL+SNe#xX_C!XTP@U*xMZlx<2E>@GS z|LYLAC7P!$vN1frM6QNJvSCtmnI?dn5UMI>WGWzht!Krb3GCpaK zAHA4kJ`(U*#N#67NvoNo;7OLR6!PU_eaz&iEp274)&RbQjoQQF(OV`g#%;CcthxXO zwEQ0}0;oEdeZC`S87 zN;b}O4N+6-}&NuGCKOXXlvt!ZY5ywyS*)GYgY`DK&@$ z$R@-~QpZOCrgQ1xEwRgk0a3#=4$HmEwA4Z4TIoaIMv(Q(o~;>DuEfzP{2v{<)c=1; z;Qyom00RI6(R|Qs000932W!=_O{HsHSeW46L`t9kaF4mB(sZVKmHcwz%t2H|9;5f6;U*z4onbeoyDvJgN~O;#LyoHogD{@50n@hCU0L0Jdt2!8vU; z@4JS){;EEt^(k&6;1Zi<$acaQPu^J+iaosPl@!08{^``vCnU?542WFOD~ZJ^UAMfU-YWAe=Z!m`CIHKWCg7IXeIxMpXz-2C^Hcb;w^W>p*dxCg208tK zqNc&xIP%Og=y3q(TX~Yj3gJ50a<@I`%Um#;80df4xdov}6 z1Ze1WSe?8g0=HO-q3B7JuV?clC}^Nz#FgX+XHnIls+{jmaVs*%6WKvU7yajq z5!2NT#doy+0=eP-ZzULYq;tMD%Bq&Q+XqhH821Obr^wZtdT}#8%joj;6x2e#nO@jY zB(`L|uf=>v6`8+Ixz;7}V3H3dqPeqEkqJh+cpqCzYep7a5!_>6;g3*X5R=!G&$Lx; zZ`!Y5AbrO|Gl}t*4S|boF_uK^Cnbrg@H%sn?)nbKUk&XlvF~_$$q@QZTk06MNSk85 zW^Lq`uBqk=okD@AnR=(DBz2CmV&082_P2Mu#zUQ?TGy|eCQxhJ z$3MNWO`&vdO*pS2C*jnaLR9Vich^7$o>Hc%Db^m96(@I|Pq^wT4$FMC^8{$u3I50Q zLW!+)b|jZLa+mP(3I24g*VQ4byG4z!`%x)5bxC1H0}J}oC9fbc z82BCe-nTYI(p#p-=U;rAdl6riOnxFgVbW?@^^PaSOyWHM8^%DJCaw%rqFEnVBw}va zqY(HoV7~XZr-C)wQy}8!IW#h__YjJm>K+BUzs(ewOfs9~GZPq&5m--m?Y_%!oUe+k z)Qg<|`h#*6?j2Cqjt=igq;iKjkZk%`zDS^iEob;*W1m=h5Ds5KQEr>ojS?x`4eb@1 z^oq?v>y^Xd+)MX3h12&hDv#Lkv+4` z?4Ws<_q0_ZyZz+5j}|6r4SR>wb$O0gT@TY`nrDCm>C}TeeDJPckmJK6(A!~H4Zpaqz*v4?3Ov*p|SBj zgenyfhs65ydMgwUAZCI_$kn8njqUqR9t?d2mE9l}ruU3{9qg#fB*mk00OHUPc+H zPma&qR{&gI?^BV|hc_XyUH^g) z*@Bcl3Gx(;;%3l>%|KSKwE*A!Ck?aa(=+L;eUdI+WkNp<`Jh>KNnqA!Va+Hry`3yv zPmx+)h3Z<@g(RJd*|NoXkihVIp$D1yw7jS;?f~F`%q9d5bTlu0B+zvIiRu_RK*bLe zl7RN=xl@lxqlA(BVkP)tgq_hDN**jiIV*vPGUCw8%rn*h?v@trL>oI$)k<>V#L1QAxd>#RqH(v09#vazKr<}#70m-8OCwMNKR-)7l1@s~In!KjfKG$PHu zWVnR}VK3=X!&h*AusKbC(!x8Q3ZHnu-~f?ahwu}6&C)4e5Ks!LE!2YV>fdNyj+(-^ z( zU#eD_S17*?n|=_BCzk;tH`oS3uVgwvEzcX-^j{M#7yVSUgEhk}?5hgX%nk_(*#k0R znPZ&-ojTaodVk}TO8r^Rrm$f~+I$sv(l#4QD9rO@UkwI4a{oOXqh(&d;^Z>A<#q@u zp7Eu^B$UP|W7VGypekQgh#?W9&oZt18u;=p9P*to{b>}*POjJm$tfBlcRn5s6-s&I zE-l`=^~Ed(zdkzu&6nq!Flvp%e5g6S_q|9*u2QCWbwiB}v>>tyw13 z@yh=yj>ca5c~@}SX%3R@s+AFlLBVZw?O0;?O1VgrRP$sG7bKdQgH$(^fB*n1o&^8^ z0{{cKB(Iak731~6@q5n8?rla0AV;G%5&jLSisA?~W8Buy*T{y-BI+)f-;H;W4ikI= z+HTDoa0sw)s(SBgsJ>gqX)&4!YfxdA`BAu{E5!lROZJb|?CQ9VS}`P^wlA{SQw)iZ z?R5DNr77MJFy3y;mAY&$3pL@z+_%6o!p3k7_ozTle&8RZ*(<-mCN7)^XlQN5O0N*VG>LA6%h_m4HitLlw*h;2bDZ|VY7|Y(&rC> z|Gdi#!L}Lno3TN|@_NmF@KfA;&*Y;g<6%(nI|_D5ny5+O%_N3s-oVI)N!om@9i__bNm$ST z00RJ0{Z!A7sTy9$J1lP)4wjwdzhddd;bTqRnL)cWnF0vBwPc;xVAZUs1HtXeFu~)* zreXgt`Fuwrr-Vu{O587qStD$s3S*R12M^W_hA$qGq();=R)&Ikrg!8{|Cs+6aQ}Fn{&?3S zIU<#Cod$BiyKB_Qj3v z)TxDFS>Pzs$dU^+3Q&u==Ud%0B}o}@*4W;bXaJ~j7D26TO)E(adj7A2gD3{cB~njO zmuvF128o;X{CKFctX+o!)m zuJp(3gUyTl6waoat63ka_#pRBjA7+Tnd!i)HYJz+flK;IT|*IXo9Y4I;gLwZj>QW2 z?rZk-{-q7V(nx(iNV?vm8>7#`_Lmel1jGlMQ3t-*VT59kYy5FMz)6ykV*2(i%4c+E z6R2uKo{qcu1RM*IHpxKZt8I^Hkc~qtrDTZwcF-_B`mzH4&~3Mf^j9C=Tekc)+IQrP zjHU|f4Qxn*T=vD9*7PAB3M~uK83>j#NGgX@)OiH*tue|zYavqln$(dkoYOaQ{pP08 z<=tSnpK=nLv}Z(?t7$8hY?w%LyAo#KicdNxhplEKqI_ahBWc6w7c{Cd{7~6!IZT|9 z#R*yd>57@jx^Ib#o&SbP{n)|z;l!)CGvv-=45n6<^pku|15G%^vsyHf`O{*r@l5TRg65HGYqcw#O| z=w-J|F3pwTv_=X}BPZFg=FfQ~dfoVQA5#Hl3KzLskSQGZGu1#=Vsz)8t~Z`7DpBgK zSz48Z#6I@I^YhD^__7;eAD_(J{q+)QI#lqcDl^?`8g5#9lLVvmSGJn3y#**NJ0CTKVsk|=U2@z%W_b0{h9VN&VY9$- zGs`xRA$I|D;iIG#3Xwy5O5%a9V%4-II+WdaF*Q@To`uHs>Xd4@r|->dF3(xlVc?S< zfhb5g5&IsuZr6**tp?ky+RqCSZUw5aW(!o;HFGGHsSPX=E-l zsJxu*Uk@B3gJ)_-VT)#i)+FBgLV$aZLcf0gV3ivtZ69&6 zuqYvbt&Z~ryPH?58Qam}oD*~cB}E#~NZl>f-ph$;C2(Q*!M~we(CeU^wUWfTB`o_s zXAsR{0~jTElhjHmFuT&6E+pPcmT-y4PTKwQpZWQ856BM9A6GHV9-^WXc=+-diT3q) zF303F`=;V|SJ8Se^>AIB42S{eDdgYM^zV=Z{ZtUXkUb7o3DLdW8bZp+W9OH$y6df| z0=Q_F#gu1_=x6zEoOJY^wx?vdMzj-rWeI2(weuN0T8)-THIY|7_tA6$!dhU~(W-lZ2nIu?>Rwoh+W zh7N-ug=~7e3i~jVF56dyR;l!l%YNlJB*y3UfoEmWjBFFFpk&mTf@JBNk6E|fkr3|Z$Fox<#FY#G!00dI<%Z_Mwk`abhaPxlx$}jVSxV=CULq?SKD;1 zBeOFWAO(1X>&vr=wV(lP0(V00nfR1q!m!$?#I+))liXrXRc`S3`xfE*P*}mAWE@!Y zmM0Sjp4R%Q(| zo-h;8w;g71ofbvME;S{CW#$uXSn)f~XjAg?tdF-M83nyqX4{LP* z%aok0C3gqkv6Tz>N(PmsZ`P3#?an)NY(p$VAR2#$O?Z-*v2#kw*gr@rNi5#ouIN_~13a6)!JasG>gu}*^YGlRSY%^{^u{9VU6n99E< z#*C{C;R?q#=xADyG6cgcMbnXyyzI=DhcBxF$Tw#UOLEQ>4iW@YBUnxknqPQyreLby z%iaREdK8ojvWQ@556Gn0X1?S0MKY%ts)&k477nEg2zer%Fp`SX)I@gXNAQtbt$Zy- z*TSF*P5#l0PIuE*fwL%Njhg4sY}fGr^NBctm!9$c;e8e{{pdtC!nuLkP70Ujo%A%h zVSeLYctTL(UZmph&J0tPNmCDD(SY>Ki?-d9$TdA{>@m!9@-MV@<>%tpv-CfX%4S~F zl5dzB@OKWW%KdydII%Rc_SqQsst09>dr3V8{Tm%~$Sup`F+0@G*7Y$ncfwQRB(wm& z$}iPYT@aHe+mhSooFhXld%twYNi!`wUQIKQpF?i1Y(P|>_#vl8vh`HKEy>t-{>`jXe+PP+{DqH^dQc~Qk=v}COdxt2$1)< zw)O>z$$4BQ^y%C`3+4*l$>Xpv&-?pnM`vFpy-$rMc0-QTtCi|w}cBo^kpjXNNq5n*>lx)dtH>&oCYhIXf5E%p~ev&UHMU$ zOm}578xRg^|Gvo_+g2g}8b;NpHOiA>I`jwpc|w^9uVc%InXhm=z-q`jXv zBO+5v?i5GF+ZH&G-mo#C>XI&WDD=ZVKH`DH3;O5-j|Z_p00096h4^3)l_~5lO3G1e zsxVyCD$6JP^>Njc7p|tm5X!S2TWRSX6bDNRidQsv=p`Mpq&x6_gH{ z^?K(a1VwIg!#`d4t!L6FCdzmCOsa^3!qu>5_ipqIo!r{I26;1l>C6U9b8rWZ1kYNl z@>pG@o66T%&gNEh(5zoqu-clG$3No<`K1LK zo;`2GH7U3z*uPkpAE^nj8;xBQ_y2I+8ul9vil}iF4W1RbWKkJYT>CkwY>v8yYMG#6 zA3Qd{yK;lxD+*nzhqEN3?gxJ18!n? zwz2lu*Qy={kYwQ+i}pB8&VP+&iSYYXS;5r4x0n<%0h#ssBDNDE> z(JTEj^wj%kPVemEk0`&=e||srE_&Smp#9RSl0wq16_Uw{l#RS;#?wLXsKAnHc!$7N z980!@YeRe2pU~#}V=e}jS%WpvGrT3`SVK`FP=PEo_rpUAwBM-S)-vB{wW#v`hLQnj zx$6ZgY#=|^>X-}7Vzd=;FD$UJPetXBW_$GW1b@f_)=6&C9-)>m8$Fd;RPga=Bp5_6 zEteOp8%?+4NF8c?9(;Z|%2=DCDvM_)($P1XcW#1+sMHLrBjkIU0dJYkJo^=C~Ck@LkRJc+_It5y=h$i%93HOFG)90pqd%qMA7J_X)rOoHf(u> zcGV0^?eDyvrA?>==Zq|8aA8{Fx^{=_QF2&SsoL5yG`vwyRY{bfU#mI_;ja2Bzv+sf zPc_2?GKe5Fl8#ywjh7O!z=EMi6SscKde&a{kz@m)qXxQ5(vvSVBp1+^;YZVpnA+=x zsw=<&c0S7~_ru7#kD1+oI&ARr*sp@+j!ofj`HN=x2<6Fo!9%fF)-+RP;-&5X}7WSY<`Y0!0sF^_DpZ1#;;P ziRh5`s|f?Cyl4@Y2O%`lg!upB133=x3{Und*Oi=&l5W};HAnL}%qA-)8>Ub7bd=s@^??GHl2;@tV|(EM z1KR}vBM(E-V&pGZTGi3IAzg}fX00dHNqvyK*E{bd#bY#<-?K5%Y4Ip3RhRC<7`&Il+iNLivK8pN$KT>b64frNzi>l zTbXE*yX+XK=BJTexYNv-5NzR|Gcj`T?M+EIWmHpA-1!>&HP3=&TSTRwxZHDnUHPSN zUTxl40BZt6Hm*L;*!~b#)Rh)FRWf(Mr_AMi*+Kj9&VmtdUqDpeCs)Y%!M2=NbLc;O zp@Yrjpo?1e&koh^`FqH4JH@;~b$vx(1e`fPX-DG_hUvs{-}qmu@uK*tIN!ONFhrJf zBGW12bIt6P5_@n+D3QTxD%2HJSrAC{%K7bx31J}B8&h{@yAEL~iN(XLT`>z_(JR#% zKc)Y{eC)qiXYN~^Q;O@n{qe}`>3AyaGJ;qHhS$_R?N*YIDpY+~4b{c^7#{Zln!~D} zIT=H-R>RD3K<8{K+gFn{gIb)?&TAlLs`vHQ)?|Kl?y=i{nQJPf;G zLwB0A{wRgxo*Q~_dXV5Oh@1ZeHNuV!NV0KRkXG-C-@G?`aPj-Ev7gmm0Z6?tz;fCqQ0nJ#DDt!#^R~STXlWxF$|Gsy*R=q zf7!}qb7s?fYlpKqs;%a-+B;-e z&o7_g1UCrKi*(KuT_I%u2+x^#op8ZsVy)IBXQNs-8Ec*2Aq`icNcDd5 z40bI4UBXd=4=#?zh*PY%I>9zjQ@X{ur=loKvU@Z>TI|NO*yN zB^aOSfkMCbSt+6C(m7}HiNK@$x%y7}O#;@rs9%>aa^Ny#-RI#Pgn`kD`__{nHn5;w z%-N;x98*VR5q6}Owm(v$?W0zWP?bsG*YpC`gi)Kq({$}K zXWiC1i5>=C?&}#6gJ-a)w?ofoA-Y>$ncPRCXG}G>6)Oj=K;>O93W$-PRVMURMNw%I zURh*3_hob39eCGxG5WH37N3t^0>QG0b@|`3-QouRjRyW<>I?loVf#{+q%~>?Xs%5P zTI^Fw;cD3f1xkMu#iX#=|NFqD?nPQ)1oybjmIlFUgM^A8q1}Gkv`d19ii%rb-|o|9 zCJ5$9-pI2b-}#Hg;5+B=E!+(+^Xs z>Zzvt0f9JC`AFX5~X`7>RNW1*-68_QWL- z?PCGXcGqyxuYcAyBY7rUZUAkj_ad2*_^5BH>*uGHkkF{-FvpmZtg7-ZW``K#m({v zHvyc}{al4XkLp*A_|;5``zsAkR`sT}KF1SdJAJCrpU0%RE{d0RV&wYU#)o8nLG&!{ zcSr8f?NbIot?wnbf$p)^cm=xIyf0t}nc_QtQ)P^f3$0+-000931tRmfucAu*qoz}- z`X$e!N2V4nq@5ZQj$AxgQ}UTF^d!SKBQq_*{5SO2hEZKO3Nh9+ncbd*dLG^ZWO|QN zTF)Dt5nxt7BULg`6}I6t^*}|Kw$7&e0@_qgS8mh-TI`GU$Th(R;w?ROg(yj*@;xhe zk9`8~vA+f$%OH!1(MK^Tt^~^8AE-~mq-coR755=4u8a1Z zSgJX^QO9ecou*d6Qx&|AczN~^aTI=n2}@YdWP`OL>M-!nxsD2ZQ)X4J53gvq7S`8p z{@fIsAIph%+3yeE)!pr-y{%wx3j1^)L=73~(c^Y_Xu6QuoSc6CsL>AA$69DT6m4w9 zw?N+%`p1NC))ln>S$IO-9ztOJjvFm2>?yOrZ6nz%a!>X1^<^Mk&Vp~*+H zR!<26a(h-nqQO?V8p^Aaaf}9~#PCyne0xyH3spddJ=TDBr`%$xAh_3M3OoBp;B#Ol z(OMG22z%QT^}DKuaQ}*zB3l8+Sv$Ed^`LklKMG_fTYg)s@Vq@;d2ApXDk)x|t<)fo zK?iJgm0so$9WR3zPB|p@1i2_)@-*buD`)UJDMK_t-9epa*725JgG;nEM&j=1?_h<& zJjMwbg!ysoL)toy)6ddBH=p(AXob<&tW6LQL>guD)yCYp9Ws>TG#%)=%W*^P_AM~q z6-a`?#WP+8F?pbG9Gk?68_WUWKCWGkrMBS`lmtY%Ls$&T?Cy8tmH zZ}}y8+{;62FCVO(Bh7NxZ3{<7^4^NqLcej=xEZrG_OZq%cm#d=+7s*S5ElC~$>(si zB;WZ-lGiK%NP6Z!o`Lhbj+A;fKkFu<9{3_RPyu{(Ind>-sz)I1wgMXQj&u$O+2C&i z?_uB?f_HVHrYHkJw9MmdekQE{l`|mIx#!}gM%RC{-Dx`p&r6DNud zHT9*L^4t6p<@)8QwX6P3vbApX>(`U)5?_W#8O!Mf%iWDhbe#J#^7+WW&_~8IOi=Z} zDzL4QWES{c4gfe!M}&&N+*ePe`?q;8&=FyV4r_Q{gAxk|iV7=rX!{*oTRTwZg8NuJ zSPDQ=P|)vz`4J1?b$@x=eAhxA>H+zTzWCuJ+r$;=B_iD41F~{ zrGC!>K}m(L*4q+xT9~eysg=5OZ-xHb4Vtb!FuXfhvh4b930vjum~J77nKkW*!XPhM z>#E*ss~XH{sKpi`4pY_Jtnos=TLO74frXScj+eH|cPy#tqfGb_!2<*H0O*mi-R zrdcVaE}u=M&J(_#V;pPvl1GSQEgHowITbbQw)l~Ro3SE&;hq1EjecAdAo-w!(w$zC zRLUuK(Y4in){-_0zF+xTjkRhoAc^^5NHKJK2_hg-T~bTsR3!oZmkc9g&k0VLRx+b2 zJOz|EY1qi?S>rT$+$`S0L=SVK!fKHdwJM5`B)O=WqYGxKTPEE8SRq@ZvcUKHhH@DM zdS!3Xa%bVqHG?iubnycVU#ylMw>RRPvFZUbcABM6_95H*1i zS?a5j;n#HQ=f83K)`_M>ASp7sx1v(>s#b2Gxi_udTHb#T=@4RnD7{Itx$_b+g{?(j z2_=Wg{}eors`i9KzMB~FOLGK$gyKu2$ylyIfKZvWxahRKWc>#88HCaED1y$el0V$J z;4qpws+GjQrF#jl`X7aMEwQR&$eGiCiFc%bUF2r-F8qI#l39S=3eWVr2Oh|3UXFi6 z4n~@N1({fCcE~P%9gr8~8*#H9NisiPEhIwF z4Y3RPNP{VDJ0dE~FG8g%+Q;JE^x=w0Kn2|W0009306R_0!L~BNvU%iA8H8xhpUwm1 z;9#@Hha)|zoj!f`0$k&1Y`x6uhPE^Eh*qk{k7idvI&j?OVj}eH;ghql#FM2tj1{M3XYVCvqAiVO1qWK6~(g3?RA2Ug`yYHBsO@Mv1 zG8gJFkz$5xX{&yt!anHlF%MK4-H?R9HTq@=NkYqmI|4mFJX{@LWUUw9cZ|q84duBG zm_$GB8wVTczb;B4q;s(t=~wtFe{4u79tUi@E_kp|Dy9I%`J(SlbF!DAsixv>JTHGJ z^!QYkga;{l6g9q$E@T|mQVq5XX_By}+qJ?eSUHk;9g>fT+s(nu2I(cWY6o2BPIyAG zsLAQNPiLJz3#+^aY;fFNMs@zxv>Z%X?+c_Q{%*o)*^euKUoJ9*DEF2_{}Ug*`rc2Q zpNW`e7f*?ZtWryAra`1TXe<-7Pg(EHC12@XE5ky3K8AJzeuqfRVB^aQ?C4fi({*~Q zFoFK{(!FIC^=1p~+D&?CXbAi6UnLk@&z=lHt(e&187_m1a2+1po(ytO>5>Pw1#iiV z1Ru=JC23Y)Wpb{wTnbYh+Jm2&rsmDJ@wB27;p4K9T}c-!C&Xc{M2+c}^g&zcxi@>r zZs}1VSC(dH4`d$(QSkU~UFuh+v+3aMM6uj&W(=?uq?-4=afXqKPqO6>y8}lQYrAN9 z@bPjS{~XDU=BkcWyzf4BGD{7@>aR{!uCZ61fT1SjyX#t~hU7xzI@iJ*om)zX5D54H zEoq#ObmltWn;#zsZ~o<{byG42E{gyJ5`!CsHIx1@J$&bnBl$KK)=+tM6e0Whyt>sD zsPN%*<>RBz|6{7kq1pXt*08v(%rWP4|^f#cjgGo>AozIb(_iMP)%-TM4Uwy=qf zt&3}e+oXX}*(fx3CpJUiXDf+B3LQ-JM>d^;F+Z$(3u2vkiURK%Gp6K2`!dmF0O7h1Rn%T}*{NDo z52>|aw4=2)OaD*HK^zciN0AoOHfEU=qfPt|H?Qq@RM9X=`O^YhnWVFNSV z@naDS>KoucEIUEjBNZK&-*Hqw*GRN|k3OQ<`8d(1&+HtzYQl9&^s`PL^c?p7$G+c# zCH8O+2CUaz`fWf4xhq2mlO%iRf{08702c>yxRN50)uh)D-(Nj@P|U_1pE!fN;zqRC znOj+xoDRaQ!*u(XU7Sxol%7THC2X%BF*8Cs8VW)EMRfM4^%ob}!9^yPR=EL^Nf4sP zbV1GEx`5MY&e@+XHqCll+Ph2dR#Mg<^Su}KSdMa`xSGosR@EuhS$0@>{LZdT$$Fsq-Abq(200RI3E;ol2-qIHak;^Qe z^1$>|{vx%wd;+@vUOLz)(#3GvFSo0n>CXSof&UdRLjgSy#?C@&xaem?+F1ZxJ^-|U z(O=4=(C3|#!-0Ud>eJREMx)BC-S&BmLq=KC-11J$W)*3UC%pqDrz2)Q$63$U}rg_C(ht^FLz%^{+Af~)e9~IGtjnvTwnpI`kY|hke5#UX`QWJ&{ z7xp`PC9&X9-&;n%J{q#0CUJ|zl>!5?6a*5aHQfSlch!AjpIv=_m&8t~4?AH_#gVoj z3?Z-yO2p&rtzwH0CmT)}vySFPD+pB^9N-xgQ86oy=@qsZsNB4${M;Q^T7H$uaG=i` zEfCmQb}g0kLU#t>%dh_uGMrYCC_?3Tpq|0lw4QtCXgL*&^6&TQO7px^KTKRmlWwu= zHxSL*fIlzl1-X7>K1uUhz=;Da4R|y)6rR3a?ol`E%lZx**IQT%4W!Z{)WZPc9S6T% zeDY?LYwGPwg_fSjFaLrA`jJ~NVRH5H8I4mmaef&; zEc4)w^M?ii$~x%v*+rgxvBNid(1&jMh4M;=Dx>!i^kr9 zN~jn_3WY3uAchmM!-xF5GvM0+%tXkE80PUphoU;MXViqQsi)p5#HkKc-7 z`v1_Weh6%f$yErKBYvF1NPLSd(Q#qy{#FYZ^(w;vQRYUz+dC!%pulycCV>1);&XiB zK|kF>U)RBDxRCE9`4jTz2fsb@blvz*%d<2h5)>pkP~U1&^1L$M8Ieun+j2ttp4SeLC8+wK@!(P<_?w*m5a0*vmb$Mv3)V+wnEFRGgZ0Y3gN zxOJkl*piF$5dD1SW|6W>$#t`egecN((NB~QxhG{-f#B|kjP!1aMqMU6&xZh(I1cqp zcc3>^cDtq|yVA1GVuG5B_y#M7B{L0YSw$e2ml;lxz&ODDr=)SnjSLfOK?dYtv~ip3 z`I?I;v{M+j_y{G%%sHkPV5|PcC|0Q>D}>P5<7$U=T5>2+ z1eC;Ev`K0gvHrzy%hL(yXW`BR^K$ygtk3HOgf(dS65Bo`i#h_B4#(xo*=J!cyAOz> zMkEl|;viof5}Fn2)3a3!waV)Ik>wsIIl_v_-h#dRG!)+htr&+VJtpLO3qNhlAW;d` zdA?~|-`-#|3Ki6uL~kMaUp6-(V_Q*c|K4CnlU#4c6gL3%-NdJOpe?HJEnQHRds_ue zk%Z6fS0A9CFOw!j?k8$nVV_?mQU1y6s$L&ItKqJKmajKrT}X31-M>X}VF5ct;@2?# z$2kn6pNO*>pm4=&P)=q*j1P^)9@dV_^<5D z;S~MWSnieF(Pm(^d+91=y0!q5;Z%Cfbrgqq!(4Xe|Cq=Cf73ybV7);8?wUD4zq8zg z`c}Br2Zw}HDLpwq5KrAdbZ7W6*qs-z>5IU!x;E~COHz)2 zd8c!R!?^7vp=&P+Hch#-c70Gs@HM43R z$AoYtj|OF*P>q6`oZQ8uQrQMto`3&Gw&*m5CH|J`o`Al8;-VbH-zv7%o9^O|K`T(C z?(&PL)|J|bCWXTmLAtY@<z4BJfI<{r8FSg5^`WL$$67bgY~HLI zGAahy-Vn~~989@o>`-phX|dV)ej;R>?9kp2B~Volp64HqBmE^pGg#j<8)`OTkB)Cv zI|L*T+zxk$K;~%vFH^d8sKSs;vvAF(&VEHl+O!}?A)*1-#>hC#Gdc4+WzpR6UEh0fxOxN`+UySyWwL z&R`*JcMv$^{g=Qc?bq;666GzIl4hWrGsit0 zYQY9-HcnrKMgC}xkcy=vf$=#NRF3955j|M;&l-H7^tVi8Vnym=!&2d;;)OvX3RIqV zi3X|s6zJD~zNc>~ZtuT!^lX0!Z6`S?uR3JI)&1}g_|KR>404XpZbgw}^g$QMNBStZ_t8;g^Qaq)W)4%7+!B^gn=*0Pg@M}M zjjeWtm>u$o&^uP+&MI=e3jTG-$rDH+@z3BG_k>ovdp$nf*}(r>%hzQQg`Svse~j)x zPu41?e~zTZ?|#+gaSVsVJS&O`_!+u(hb>t( z$KbpPDh}uG|E?x9PMH%EhI^WA_=EWPbnu1zYm7X!vqwK-+RzdOKfs!P=i0i2P4SBp z(g??sd`(Ow6W_J@G-48jv&4f;Up?5c<7TAZn$eQUH+FxvbY7J~WsE5{@+0nFazucub0{Am_DGfIrscY8YX7K!Jb^k;#g&BzX)X_%8@ zP54SXJFZr@BJe4vZ+zHy`!s)DrK}!?n&vI|yyE5P6@;3AF-bQv@bAF6m5ev}{M2J#YhTAwas+bilVZwHaF-|`EMcwh`t-OAId zjpoiFqMT$vfa+iB&Q-$(tE0LLil@=rQ$`R7Y!b{)2(G(@H{AAz`e`BPFS-}J1QP(2 zC~V1~K>XOKADxzuWs056XV}IXJv3NDdTNz4j%7{NMu4ADHeZIu5RY^m-~QtK_%mH0ge zwME!3#hP^rhF^4)-oNSpu2Af*8kIHs0;*?=0FN|8CTA?2=%EG^pjiK_vHAN4DAR@e z$spE98pjt1OwcAwlIQq+LX=pL!!F!ift8D4QrK5?%nKq`lcnVIm|3UG+lU;71B$9Au{(@?z`1JYAa`sj#RQ(j%QkcmGI!M^OLlhzmB!x|`olUc zjN3Jcg{Ou@r~Ob3{GSdXxy`*pD<6z|JEfB?G93oS60$1|xXoplBn@xy#0wM;$?C=> z4+D-FumdcsQfxhBt9GYu0{(>ttdQ9xQ{34wDwBAJ%wgyxQXZRVP5ethR(RkyuRbw> z)_4BZm)&h)Tys^k*Et;hjEzLnOzN7oJ8~8eCoGv_MccUb+aCkJ4L(ZNBSUEeM$v@r zt3dLZg+Hl536^0RCLruM<9wUXSRLatzI7qPCioFZKP(R9ol$t-7jA)<8nz%ze-qb# zFut;-uU7Crp4Cz8{jP)@E~cTbtcmD6hpwAq<{6c?BH?&rDFqM5go2RdpE4x!nJ4q{ zza!TTrO$tnR{>I!Hv+wPXoVwL9Fg$KLrZ3cd}A>o5g|*Gu#Jz1--h_bawRxc_B^gt zgTk7@YxBr6wB4L+Z@)`wrVUDFcOe|J+O`uY&)IPWc%=&S94yu*kUkdJwk|QEeX1l6 zF#UbPqId7rt-n}a^KHGR50F_@)f!5HDBX842BZcGA$Rajw-k@@Y)j)_I4ktW*Qu^D zO}%zde})cWDkgB&r|QOe9FBh~^?EeARPW$n0?9t@kkA?2MmOTIn*ltWJTgMmez$91^L)Dp7x+xxHmnW>{@d1kW$X&6k(m z9X{hlzo8sAge7ZEV|Zg0sP;UtiG*Do@MGw<0FoM>qnODEQ{3mq3BDeu*@0Z_ZqncG zZ%URq;B_+d4@^e+{71=3GYzJM00096(ft+ZCzhNeg7v6?U4^sN z8LPdlllG}}CSYkJylr~|V9silBrs&T<6g5NFjZ36=u`Xw72O{{W@#+ti>H;fP}>&* z{o?_rrF98aP{kDqB2^H!3WH_^-RwQ7&4Wd085NkjCHi|mT{Zu97B)cLj)qQ~(ONT_ zNO~BkJYxG0KZn7^#o32@*-EeE02z%iYtq16Fvt93VuUtmgfor)O{G0`NSK%n;$l#zXtey(y zM3&q?{@0CeCD=W3df1$j?kK_s`=Bsl!^CC;vPHcxtZhhCOJ}vRfbWYr;LGTfVjFOp zgZN*9l9j}ind|8};W(w1R2R7Ehh{1q_<)_kHa2htXda97y9<2F#*DMBeC*)Xs{}OZ zLf+lK0A(b)mi12P<{iPCx(pWj*i8289H|8W8+Ql*qMr3n}Mm-b*G2f|hyo(D0b z0%;lfAtli;?qSIRqnWAQfz2Q!zVUkItOAygzB#*JQwCCi9RPI~^4P(!h3_-LvgHMW{s> zOsbZqKl{o326W7#jv{5Yc{vWKi^|q7vUSR|WJ#7J?A`;C>3t}yT4~wOAr+D5JQXjy z+b5qy&RA;ZmP$wg9k^1JOO2QnGur&g_Q?uoCrrnR?cytgVy{R#9t`6i=)OOI$M9Z;_W6;u!w-IC7)tK}ZniC+ZIfZB@ zu+k{?qy6UdOJ3A1_tjBAE)f+P{yv&_b!8&W)Nx;H1$PE?U^nsoB=sHHfU5nI{4rW? zS#)&q{6>Htiqj>sG)t}ohCyo+TcnV@YRmn-rDO}ICS#m%az-S2$V>KWKfELtJA9;_ z>`;2+i}J!W-?0N!ViF4$C)l?~b}fAexWY&zj|?y5U0$QQr!Sk#eX~UsNrLlVB=~FB zQYy{)bI$4qkqq)~iQ~~1t$}L8N5y5$fB!)TagoH;Ke~m9bDVE~LHP3?!aMYVSq|rF zEJgX(z$T_zwo^Q~wnJmR05IWnOGhF;E>;xc+2sSJ^--?E<~n%ehv=btUxEvUsPZ=( zxgqSV3P6{hvV4hi%6-*qY~AJ>_PhQ#s-az9KUt#;nKxm> zcHmTyBYc~vK$9F#PKfpQCJ|ymIVxAV1sm^N*a6R>m2SnYzX7<(DhvvYp_p;(Y=L`v!f@ds!rVD>z!#yky zEcs3dvJwlHG(3);n^qC{V^MWO8|#!pZlf==Vb-e+qle@w@(3p0Xm?IG3P|F65(cZ_xR zvmd3@R0rb|*(B9eTE7{IL_qz4P6!^FX0H9kHqqrJHVB5jcASzmcscHF-<;b{k-H+C zqd9W`$`!dFI-xj}@E#YPZm`_}GtUcLS+)l<1C%7!I;z*U`blQYX8{(ExBDm+ZsD}i zA%&^_hm_0~OxK?jX-M=Z^gR=VFVTH|?K%p8{vRZpB21i0mrR9bTSJyo_7Hf}D4gQbg z9ykr!6Am8mzZalcpzI%8P3nJgsn1~i2bW*l!rDLLAOHXZ0p|30`&tyz;plAB z`s$L5<1z`*$93<3DQt}*hDRXf0&FNn7)ZXP*e^@fW#6NHgu_4ivzA^$AqVG;NuOw= z+A-5K7}Q%K0RB|H*Yu3x&76GnMw(O$;LVxYDl!HAB4ix0>g0W*^_^>~)vtn_vXQy;yH_b(L^gX5PANy+y5kkpqR*bR} zW%do!Dcg}}MBUcNp7o6P7x1apKHeThoDiPXr3S|dT96bRX+o5fXnRt1c|Gggv6n+B zgeoOS7vap^+s+Iuwg^Rzpz8ekfg4TH^66wOsZQ7tRIUkcAb>2tDL3a ziO2y&khbOHFi>!JfH>1&UF9P@bsC+S48Q4DThzgzA~PVWYAR&R zMoK`M$TBoybo~s^!xooO7^2(--9bu425(Sz<8jO-VQkYNsHEFoTzmZ}yj~-$092<5 zo^>sC@K222@A}CY+?Clrg3bzs?u?+9re*>C7q^=9w+-2Oaoy<l9K&yX1E^c;Ct1OKS6Sf!8|Qi z3p-I!LG9Z1su_Da@@V&PsI~{g z_6YIm=WoR8@aq_c0k_2`0U!YoI5p#XF6DVjMMk+K^|N4BJtxtu^?=?OhmFW2%wW8^ zcfP_o7ChoCaBe<^hM$Ey`mT)(Bv>)1*7v^(9 z=w|6dgXCI4IW!G4gP&89OJ^^{hB&rhA7Vt6W{$X^;df1<@Xy z!ap~Q(mPV!KJ2BP3R|?Fg<5rUv*4Spojs3Yuw`Mqkp!!17_aqR{}OJ=r_1T1HwV(4 zKIk}VTLL=RTi3SUP_0{ucHs6T&v2DkEL&h?586KTj}HOgw+U8-ZE- zbn#-T>T{SvnZ_@Qf|eOpcwLM!p)cC$7k?BXKAr1*npbFj(Q5G(%jccfvN;jc5Vjl) z*nVc;Dkr%A#QMlrM6OrERi0I~<$G^rP7*1zSsMhJJlU%TR*esy809Ppv@6(kVqQGA zP^9xJrH#SViIm$GQZF%0d^?mM>+=77Z4R}zhXK;6*LaFEe(i962Kc@X60>3HUn|WM})- z8T5a1g{fYvE}JgS4*S~b>?x`t0!hBQ#_xrOaq*(Gpx9t&iBZ;uy5Keb1l$c>9Yn`b z+YAFo{Io-Y-yf}I6@s6c4ln7cymC`t_pz&Lo2H~p=G{A2lsMn6SUWqMdt3-kodt#Y zm7Xj=p@9p^MDV#%Cj;qH-O@#k!P%*|YAsB4)GT-5xI{gefEnNcmHHrW<)>JA~gGz?} zDYd&vdbJrA6!<+yTGUX>M)>EMauWx|z%pP*o*`Aj6t+AXm3%mB^&VrLnAdRC#ZYM_ z7rNzI`lYQuw3<{6zdh!+Y|zAfd@oBuMC zCuY?&R2@V)KOn2{7vF-YgQ*Ws8Opa?oTDHQO^+y=De_g^4^KFKU&k%S>|3I{KmkiH z;^d;ld1gOlgo28(t8%CEym%4L<(=mh(y z@Tydp3in8_PoB~vgYl$L)9XP?cQ#Kkgud`^Bfk|ur@e8Q0G`{+4W;k|T+bQV_}4=b z*o3UF;b`XN?p{t-bU;Qgfa9^*nh8Mpfp0}DC+U*|^EY*XY!moc9FyblFw0kxG+B0( zRBS-%%H?etHh7jxKg;F2Vg&DqB89U6=?i4;AW_4&gLWI1P*rllV+dY-7(62_g_dT! z0WYAZoW{uM<3W^-_w^?Zys8b|NlTPUf{W8Y0X7~~6;>o1AfIl~Qbqckn*6yX1{BdX zSJ~ztvfuYKJ+9Xob}L{;MTvgK=Gx0L^FcCf1A2JF}y`E9t{TP-nt9QYo%@7AJy< zoFUK>|1##q0;K}0d_hLvlb;*`HZ{zW6<{&`mduGt7L-HHR82PY^TbNsnr~P7Bd%&F zH*^h#YUKoNd>Lb!ZIe4ztA;VF#bJJ#5Dea=`xnTj&&5v3p&4XCP%!9M%_d_m%8~AH z2HJr6iQ6}##!xn4tJ*B*Xy*#3;dMOemKEcsFE+Wf2Za#SGap35)% zvkH`dyU9~Qfnw;lr%#(PX(Mqh9%DNW{Qv+1000935WJRKGTBu5QVf7Ok&#Lf7Q#hC zHTENN;C6Xsfx!c6BB!{0Vk%V;7Pnuo z#Rzaf+->?%5VqzqSe|gh7HB+sE?P@VL6tkVuet_l_wxoh3IUP?aoA5hdr*j0|7ToP=f-@O&>Do012DilcxUg00094) zT^0o$S?6O01`Mr~`D61G8J{?8>l$rVTkfxZ!sH}d4=O_925a-=9C#;s!wod)f9f}6 zwIv;OT+8$YhIGnDwwq88*H#tNF%apZ1FdffPQTH4a0_=Phi-*f>D34(Js*Xr$BvN0 zuZ?p?pY>Lik%HA1U*FysERX2qIPT9IMQfIoWJ22&vKL*gxE6}_^b1I4>!xk>B+o_o zhl+eYOnh+9lF*EmOsm=b^0|#EOk~}dkt*h>qq!(DqnY~W{<{pJ!*+#V7mN^5yywF6 zPUUbcTua{+s?Y5D3*+q!I`zm32qR}&Q;J+H2IeHUVI0MRs_Di*?~g55)(ATmjuK)I z34lKbJX?M1I3J_}-`33n12~5>dU*02mB(RH)n3O9z`}NHw*4Qy8c=a`%PY|^%N>=e z3Hj)Al?bNjtx{^0;`oo}$0_oWGZJFargWwj-T-{>;0xQ{B{|KXXXp1VN4>Pm-=eYn%vD*g)RfYf^p2^aCqM$o%GkxHvX9$eBEnwpMxa@kRS^F) zHRsfB-GUy32D;x&!sgN7Ml?ja0~9RP09T8m!CJ*F^bPhUT5u?_Z^B}{fd}WU1bOk_ zA!lOc1Bro++KCN0&d#nv?dGaAR5Ed2v>KlT7rfJ4Nnif{KR_3DSf1Pay)AgtsvhA1XFyRmV)A{pr z>T9qu!lV(_)AI4r1w(pZ7z8T-Y;&7*uy{#_VUa8ON@>o3mQ$*WmG*gZOaU)i(ARg{ z@|Lz1LN4~HK1zfdMWvMe0t7+U-0SV$Eo*}kFr)hvJiDW~F1$Kz;%Lg*+0mt;_o&l~ z&nWg6Urp6naf;tj54XMkX`<-iI(p69_^8-Da8HultXFTz+= zCwSEd3d&%r3uE^2e5>gJ?>zK5xM{Z=zNj=5!l$F{1HZQAyX+T=ImFj|>p70e2ebV` zLXqmAXJ5e0Wn{3%{XzI+5ZN9(PM?& z0)HK8rGW>t{1r5SL$V1k?(b}JkZPUwzr*p64=-XLYxfL))KY1f0>ar1xzdEQ^A43g6%bY@P8<|SQl!&JV!EzuZTjRW@5DS7*f7)_ zd2P7!LCt|}lW_p$5@-3A2ZEj7(5)VqFb?fKJ}Xo>pW-< zec39u{U$5NL2d3iCm4_;ze&N~pdHi%j&m}ZFuP2A68ku`Ex>?JkdgAn=CKSV8U@F@ ze-L15Bf(jDS~-kZB)!sLgsg&h`WbU13EV$5j>h#H?fWij+<X*1iKeY-~iBeMO)d8IS#Jk4-?K+P-uDz(Fp3y;cCqMM$x{Xn~2{M{Y?3u5l z%TXq1_Az;wE0Vq|1^rxQOoAehS2i32{5`nVEQ5+5lKfL;#=v7&87nnQ771(?jc@2e zX82E3B4(scPsr~h33kW=w@6F3D3Qv8V6~${Y%VIItA;ny!Bs216*N)B;0hZg89(om z_C!w~O>tT7nV!5TrOPp|B|35_Cj;o6UqSq|Qn_8Dn>&F)BLr-MuONR%sm<-g!CFOT zaYeFXF{lcL*Ux)Y9p0doqKRYoUR`%%w4h#3{N;*1wCaoGS5A8wFWf#!!7Bp4? zeTyQ?4PdQ?E*nbiKk^v24S>7s=8oi-$6C326JDOk_Ajr$W@G*$N3EYl#+5)U0R1sb z((%hSP;CmkEk|p^eWa4@m@m-2tQ>E4E>TIkjOP+UvP)LUK5L0q&-yRY(J=7S>$2;; z4;uqyq8#yGKLi}C_TE{I4Wci9bCKw5K7Xsfzjjd;iYZ4NJI?xRdmg>WS-BXrZ*3kP~4g%&000930YAKZ8m-MP8-!Pvmt@|C#A6o}(?B}) zGfo2g&*q0E{{&gRCMPdl_)-6Wi{5K!^F#^oU+c$F(`>>1wvvRV|IjALqKuGxJXH-L z$)QLf=LE!E1yof_+dk*e-QAsnq*9X7ASEJQ(%q#Tx{;8sLkSWJN`nF-C8^TVf*>s= zD#*W4yx05v_xhpS#phzV=IlLtp67k{ywAKd`<&S}?Zi5dJ0It=*xN5#gtYhg(tNRD z7pP;5oH2ZK$b-Js*-zYa80`tDUaRom8!KNKeW7OurMG>@zR0v&| zA9*<^V=vR1>9TSrnIM@4K3DVdEr_tsv7&bq{=lAkn?JI#u-bf*M`rHMq8A?J&X*p@ z%l*$$1wBM2s>vS~3b+eG-kM@bV(wqw!u?!#H`O{3l!;Tov$N_HX&3)M=GtQo?7C6; z{1-?ZjgxHUK?rrUR>phFf!+;DhgzZArQ3)G_a9ZHv*=c>yL7@nW;<~q&yMUY^Nq@) zhp99MUDAAfesqdGw-w!$ra@+VPx>v6%djM?-V54bW4}*n;>Ir@gcA^#D(@Q+5v7Of zVNwjCXRb%oKiNX&C3>Pu8MnBiM28{#oO_6iej>ie?=n)DQ59pkG^-R z3sH^tS*JFPW+_s|bb(JlWDb3rcrj4o&~|1++led=;i?B}_H9V;IWJxwA^CgZciMce zzHyj)MmbVipuu#71uAj?8_5fF{E~`CgorGK1uv23F26;9xOmkz<7!PJl!L?2VYrH` z9cTHKq`jkZzO6dZl7oQmwZRJ;nW}M8u6DRYRI7f>3YQ+tl5;x|RTEuddJcE_-X`Zw zmFLrMOmDp<@Mwvy5FdIac7=_HsRJ$T;zI}1N6ynK_f7YtN5XDKdAn|d-i(&pw8P| zkKji*9;ek`7iP>?9b9t^YE^gVSEo zdiUN&UBhY8rLf|$Prba08vVI~GV{Y&HGjW{bX6eY4fy~L4J%Xo(s}t%M$%#mVtj1o zDW^P8=#bydC!yxsaAZZzMiADE8|bhG0cGCwFGvbj6XZkn-mES?Nc%TwUf-gUWrA_M zY^slJYroPW;vi{;{8^~nT+lscGCvV+svVn-HTp>;)szLjpiI5k9B=y^Cv3;`sqm_@ zT1eh1_AWaPjavR?C$XB)(8=lguvcrS_3}PWDLlPZzC|?Ql^IKTOP~X>1*Z?{#+QYi zcLlYpxJr@=<#dv~Ww76+7Sz}8vJqH4vSco!+fku&MGEtZAi%!w+F>ro zV-Cj~#HR`*3GoaAYpYv^&5TS-259;op!2QEvEaHbO~fflDS6Hr-|rRWOlv88Ps)zb zpqfWHr$c+6C^NrT#h$sI6&rXvVA(VKmrC~Wz3RvWD3kE0VOl6o1D9kE<2ov8Se^O> zRs&K+_F|w!-Il#f2VRKYpyqA~QwrjTnI0D>*Hbsq%9fVwun;ghaBl5iF$%u*@RQSx zn^xy}#w>}4KMSX{oM+v&bcvv2EuVeQ&R3xPZvGzdAbJdp8Pu%l>d7G>X~A`#I9Czw zIlQGf(&18oPBHGLU=xP+t;P9g-Ih2;g0?b;@5DaXG4obk^cr-vU*kMqVj+@%v?wlb zyR(Ffgmt_9Qa!I=^O9g^C*oL1pGAk3yZS-iR30Lg^HPsw)uh?_v5wdk;l-gZKjBU&W0JsH=m(q01mZeZ?cOu>FaR%> z(VoGFDYfH#?r~Yljn8I^K`+5h#ig!Kn@3t9Ki_J$9|}{)EMdplbQ)2MIHuy*l|FWF2}O1f_3u`9C?zb+;@i`nT3D!Ls>#B!lF6T^y$ zp$S2;lKB&S@wly(MQWJ;2yc$K!c*8G`Et zH@ur5+gGe#*gB0K$P3R;ZCnkSjPbb_f4gzXNJT?|G0<3@r5gEzZQ}Al-6v4wN9-qw z2X!*-^j@BJ>vH$k@3+zSB09_p#y9pb(a;d@uVr)yy5d*rGA|*$Cr>pP!$e%|aC>wK z4%vjHi7>MUfxR0!Xk;4cZZl}cu>u#)swhiwKEicMe;Hc>;@xxTcYvD z`cJ9nxl)zH;6|~fN0$f4U*qO|=0}-ov3l*~620@>=in{Z-KgeQ$laH{p)X#TsnzZ` z82WT5sej7MAg$KxRC?KVEzKoiOIJOEv@KVcele-BJtrQ~AUeBvIpK->KSspZj zij=m*jiiSnBf8=POO^b?A0_fVeEf%m4%ea$3;9I?C9fii$9YBW5Iopb4Bw$t!nL+B z3i89EvK3dbGFTG!Xvv7-a%Z|8H({1sG-mE=>MXzO_^8GtEr^s$Qr?oxYX0Mb8!7Cm zIo-7fZSeVeYl$Kl2d@c=uBIj3Xs9D3qY-KEg%e;LsJiN6B?xA@udFjmOUjQ95tLWs zCLC;+_Ht1QYhEY~D`+K9rEaRYN6?>!)%*@V=HhZ)jGRiL%REu-InR5uQZmklUeA-{ z^2fa#X}lB#o7ooCbSnJ1eh zDRT2=xkn-N3|lc?&*Ed>WABSHz1%_N# zSH`gd8t53Z!v;!7H8KljO`Z?Hw_Y8)pSJdXXV=;;@1C`y^FdtwU|FQW`W?zwpT>u( zgkp`u6BMwF?8KVV)(h5kp654r5bY|bk_(l+xUoP#&zq{1-C0^(UqvH(6FoaL8nMyB z>AF?w?L3(+Jmr-zY;AS;%zJ2DiDrg`y8J|1&ywaPjgly=>Q=LGLZ267Xj7Vmz)P-< zEx#}vkt@_5DLSHXlqTYpk#_aT5ZwYVafPQxaM$$klTeu8?6%u1+Rv z*msq@t@7(rhe#rPge>7CEnXo<2vbV(y^So4W}#s}H@6t;%cvTKj>aV*0WB)eRaHSL zIp8xByEp3sA3>lgv@7&!vGDxmia^AfkQy&EV{dGJ%jy~Jy1w{Z?yS$2Rn2B+iXJo| zY)&s$?6N0fyRTSUbw0C44o~4WltOQNmx^+`VysY%HT^aAy7_kJ%zP3a!Is0m*e$LA zPS>zfk#o{P?~3W;HRnqU?#T{PI&(0`HOvXJ%^_eF)l!m`ux|H}f>t@{N zy2O@B?tHKD2%^JtSakg(RMBEJG~PlC);w4{{gl z;}p5YHFLXmC=#E?^GGJ+!)1WV{wtS^FD_U(XS?$9) z(yJF953&qs6w)sQaG_RzN=nhi+*0cq!s_t__Oyu&Q@lKy^^e<8+(T% zX1uy+LN?b5HXSp~AS->zk}U+h{MO($#W`8TwAvyhF{*9tZcl$*zDqH&U<7sOR}PAi;qrM@qh7@h-}Uo#*~7 z3CqFO%}E5soW4pzX_ZG3e5=E>vX>#~Ln(Nfp@pW6Ru&F-0_P-eDk9O1_J_{}jOP2L znkW^&xzQ0>!yY)MGE88y*MQkNy#<)XVrNSnQ{tv?mLKkQ3`@9d7QJ`C-eoqgJ$Es~et@$uj`rh52| z)rI_ZEoXT04^&=W2Qv7A_XUcI(izc_w&ln*cHwy@`Zb$Npx$s!In5x+E`*k@HBVrJ zHUqT4M*C~q=B(FK%Q$f`sHUD{jH#hY5R~eesYPz8rcB!If3O5mrgxXr`jqGTMYQ0j zW9F#Cnh*7F-+5E{bdpo^XpRO#6dFThCj0>QReP_homxw~u5&&iR`!+2m<;mvBYmd! zY@=B9?kihY4&;h)(TdmkJTdSjrp+=Y7QO;-l;a* z6p9vQkwprEV7o+KoM+=5tuS&i*=6^se9&I`{I{a>(aB_WtD#Y|mT% zG*2CE5=frCLfdo1;wAWWyPYQzA=?HMWlo%5PBUqRsLA?jkuahJPB_yx^+C_IwpNs6 zA`d*eEKyU*YfEEyFvqJzxrzLqU&1_a{ovs*U{|DFymi5AmK_4_TS$FH823y8K~a}C zcedVt9UWJ+^IB-r>Uo5Vm-co)!_s*eFnwz z;K@&8CL`ngAr^I0V7T=(zrLzD)DG240}J8(?_Er>(8?xTba8L+cIdyf73ZbDnmmcy zXQXRWyKcIK+t=RHtLxV(E@>=*vw3)r=+WUt1?YA9YKU9+wwQh$IhGXCa>3j7ga;U} zcVWXB6!e%DblNX$XpQ)iyEV?YSzH&w-8>h{E&i&A=-kWQ;7?V<_c!YU-1kzXC@fGn z*MMK*V_er!e-CEZyA;GN>^6KShxJKO&17%fW9yd&U#`uG(5O=V6yD**tIaOA*B4`I#yb)|ZU6L~eXeCw3#zes zz$lxfoRRM&8OHW3x+bQhfbpDnON)}V2@bC9!DcjZkbS3rJ$qxS(P07>hhyR`nE}I6 zb+_9ptg^aBfdszbwL(YcZ7LQYR)#`G%iyS5QS`A%w3>~#pUm;Ei00l+4oWaosmi3B zb0{+yvmYJD&Y)d?U)MpzYBODrnl>4m?^RvtmuYb&p~4k0prD6`u6R+o0zo0A?|m8V z)p1b+`4M=2OzBlEy*@qmcXICWn6U$2wjH^x_y~>T!WG8Fie(U@Vv@s zCmbb=Q6XP5NoKwG?U-g39QCq1Pmn&tNV?o?Vi~z;R)o-|%=PhcFdfFlaD1vo>wZ^O z(lCTnU#2a)5JI^je+rM6_GKGp+izsJyi|wnE^)Qlrr4R3K{*Wh3iZRg6jCpL?7KcS z8lTH4B!Jh0?64~2VSvJOKaoY4?gp0@x5AVj*p0Ed%|hPyS-`?j#r*y7mj&QH!BL46 zqItZyx54jlKf-oATSKeRs1ooxW^T>9G*&N0C2rnV+O097n=jCqf0LXD>LcAnJ~yUS z7jJ*(@gTvQ3Q`+X2l{hYSa=Z*oZl$nn8>23aX%ci4X$x#c65f2$}iMNU|k;>dEG|* zRVU-K!t`oz)+Y{n$rBJKAPoov#TSy1V73`hF!H|auJ!F2CV4xZykKhi_HjK$#bhuex>jxNwE`xFGs%l!60YU@5N4E+bT_#ILHMN_{K*s0#{$ zXWK(sjy#myIh4wK^x!grd;Uj|*1L_EOq@GZjZoFpyXpL^%d3heeEfMxl6#7D+?{0B zx6NUxugl4t$cSf6N^X2?sW%%Iw&4t2p7Wwq-KxR^JD&5^8K{1wRGBr=@r>BT&JU@Nk|%*gA=vLO`64n{Ak9hEG?gb3%jJ2cfmq_mB^^AC?tr1zxe zy-;|oUny@Ms~jiG7ivn+^T24V(%Z#RS+oqEmI`5UFP-BVGCM8Xcfu0Q?UJ(4OXY?Hp-x)5n+9}R!uumz1_H+_A3w8bH+ObJ8 zl9}zE%9c@WqbE(Uf?`vafgSio>GxGOS+3l#*?wY&gP35WjI85rt1*ayhiW0WRG6QF#$VhH8>G@x`?z6Qy{#2AfWRo3Oft#Rp+Cg5-Fpr5q;dgxv~WRv{GZLdGzgkL~W7u8+#d{%DW4$sg@sHP{EG~ zs&au}g@HlhsVL_n4nf@B+w2GT*sYQ<(1}$W&kTK;o zwm4qdOaR~PZVK?)YIkOVoLLiwa}ss1quSt35JT8F_Cc4w@}wb%pPm@;-lZ>fn9~@c z{IG|bAH~oudleTua%dD{E*1uYnA6}(%c|>_aoj#H_uMoXTsXu8f$)sPKGk=Z5WA;g zgP+&LSWlz`ibO)XpKz$s#};M?rdS7QzjtUc?!3=l|J5~Yh-X!?5#Uo{D+_K$yIZukHfCvYY)N9cp^)$G0( zezy(fNBe%D*qhy$IIz_n|=U5 zH~itle*=WXXZQhtz5t-zpMai*RWEpZ^1ve_e{G7Zil*5!LuLEVqll76Wr$M!DhNd2 ztjg;WS)x`+)z-hB5}ynqvgUk%lT zfvqif%RbRJy%cJvRS7Co`3|DJ~7v!u<=k6Q} z0%1Z>WWSy+0%0H>iUCE)Vd@g7!3abtAY#kCe{{}qvgxla{OoQ(fH4?k1<+ajlg`iT ze{UI~`+MmmwZGQ^GkrrN!T2?_@7Mo%Ururap%p-@5>F+SQTe&9tkOD!5IKQ^&Tm!l_6>r{L1AKxDB}CY{1iH684f^5(0x4Ct**||c z>%03M`UJ$m9SXMq=C0zIG^Nk7zF%mctH!y<20Q+U2*qRUKPn?6(_MZ6Jw8fuC=vRsp_j^6BE5B9Bca1TG>A6pCA6aBfqzFRFk+Iz_bG}yW@WFDJ1i_J+S}x zhOhr41Q>n$`S)5sHvJD}unvIe3LvihfaqpoFx~vU5izl&5_r7J5@hDbRsr1g?@i%T z|5*mq#omkOyYT%{<(~`SR{${3eOS?d0RGg4iE05 zcq*G^B?K}CNDBCme1XKR8hC_@95De{Tuy|}EJURe#P z2Vx+}^B|eX25u%01pcGpv8nZ6%;s-GK_FyV6?_T}NFrS4r{s=16NcVmAWSb|J@)E7 z=EezK`<=HEF1M;E9qI;~3|^qaF@^@n5o$sWMa(RR?>~55-XJH=*j-p+*skc#z=7Ld zNFK>cMU^=&K8>tt(e@;-o%7NILf&x$y;8-2tG>6!skU;rXYXHc!YY2YOZsMFV{3s_w|9@zpG&xMX#&{46OP~ ztT)dmlfkpGb#XwR(ne8t1b&8gF0#WtDtQ->3;TkGdQkZ)#?!tx`~&7Wo|tfn)=A!A z>kqc7j-?{xCXQ;I=0ui`pg}(>_84TZy9n)xB3HL{ePhFLIX96M5 z<~rorb#t?omwo$Tjg?nOav5L8W~EQ5!5Wd+|UD%L7c zZ3Ty@T0|98!1s0ui>nN}+?Hi0;3V}h;PKyLSdMKAUZ+EQYh1xtO;@AdLqTn!VE%B0 zkYjO7GLJsodvusL%poU<=(VS;Aj+Ho+)PgTlh&5G0I)-sdqfuAN{B|3FnL$?`CGi1 zk#RREJT39R)cW9Sx6Bz>ltMF%E)9UU=JjnkhMy-+!R8MPnntibT$pOUT{SU^(5+IG zGrMGd6T#UX-v@0gJM-?Pc9IOtdl?_}+Bg^*o?_LLQgehnG923VbPlhc)lFKj%2(HM zOr1atWEQmACkD;PTcsBV?u>|8q@`G@LE^aa-#d@&J`QBA4jX9{NX5haouoZHA4~R{ycqVsuIgrMDQzj=9!S6*tPM?6m ze}4K_qf!C{DFa4xj5aJN2<-E@M+F3l?0Ln0H$JBfN-n3HPU#4x$+Fzs7&@;@FEK23 zAD#{-w*W}Ne^I{g6_9{D>_~A1Z3@Hx|9}k#qWJIQ7UKEujhz4!6-YmiCJKU)e~)(( z-q)}E0$}#hM8O3BEcqFrz8eDU|22xnuLA{v9?Tw{@MpyHq{jV!RsPvxx@iyy6ae6^ zy!>I*K0yOtGh?s+JO6-KfnvQ%pD!l|Ks@Ag6BHWKL}0pfDXtSf}(uW4eB=ybwJl^B7ZAp zwL{-UE}qPOj&)p}{jZmONB`TqNi_pd3Iiyy|3K-dSNvx)j1;BjRw3eID&m`>BaoiK zJ_8oy&H>iXw@3Bhd`sgcet`_-QE~-Lr-T$wOJ+fCWTe3m&N)j%fEO?MVT?k39~Mf& z;n>WRU!a5I2+#=>PZhR^5`$J%RVdyCAsiC4vsy#{+6clDS`aIhSNB_C?Z2J?{OF!P z{g-1z?);j&Fd}doc;hd}|I@2K-U9I^fQO5CrsT@|KeXz{^Z!&vF%&z-n1CYclHb2; zejBM)(`WfeMoM>QZMZBXD0*?0Z!24^aw zOZ~Q~C$IuQSoPpKQn=r0Hkq)#G>h>kdOiZ z(M>#6DYWz`Xun1+$l&j;Cb{I!PGR`hGw{AFS~h<@^uyi#8BbsZ>uCPsA)cwRqA2&z z{Z?xy;D`3Zz8rsW{=Vji!Dr|qRTSR4*JIwN_(RQ~)6fwEuz{(tZlpYI<3C>Y^E)dF z!iW8>qy7P!`e^6?IFQcxS#izf9Mu}e@jvKj@@bVGr+&U_LqRZRsO1U;o_9%6?ld<%xpTRp{8$~gJf=Fh?Kp+#~xd{%a3B)M%)EbKP)&ef+ zq@W;rfca6jax2p6CqeVGyUPIMo5Yufo*0ob7C;1a_*Tj9BEo^{X~|(H1}p`*eKoQB zXMq11H2={&*m#?}<3Eo5<45oX01@cJzUVGL3DciB^?Ro{QJt@<0C?1w{bz9h#lU|w z=5HvVemu5M@n?X4bKx(U^+)Be_8qy?=4{}O5(QuJRFAtbF`cjfv>DZp+ynXBf$Ybz z^iPvZu+d_Gr}~UuP!O7Fa6rcb+KZBzC!2BuV{}%TT_k1tN5P(2ARR9ts z9GHS!RfU2o@7Z^i(Nq5dIJFS~47mFCZwDs>>=)p`M8|MH4b4Bj`rXvuJn}uCzP<7@ zCHT$8|3A0y{WkQcary7T9nTg*&o(MU&nPNezjc++$TJmzu(t0apmXLTaFoviA`r{& z0}DS>5itDb>g3;!N(R_(h(Pk$Mr8{6*@(b#RHmF!RDOp$+o()A!>9y?r<9Vj5rHGk z0WyKqxBoj4fC3Z%5y(+IYY{lk1n&KIR5HMRLj;P>C@POflOp!B5rOY;XB3skB2aX; zQCW0`Q3;4ZQTN%1z>zck#ZyZVPay(dlS8;UtQZhj_Urlp01M!O z*dv?M>j0A{XW>ah69Rlg@MyMP|J!kSv_60%d{R8n?W3&c2=Ek<`D@Dq-vJeWUkZK= z5DHib^xyikjn4YBjn4WrjLsuxuAH41+!9ZH%=mAL!HI(dkdd!X=z)abS>)-3fS&pn zkf{y7b=&UW4on8vFTj0Y8t6VnSpLG)`ukkH+vfLG;8);|N9gXe4a)Ab4a)8_3d-Z` zst5gSG~fsh(12d)|Ct5=4;79k1%oC3BMq4N?V$WE4VXCFpqz+28x1(_wi9O?loMwg zl#^!|lt3OZ$$q99FlF{X(}1II>H!+?w)=mi0c*bxyTm0l>n*V(`DI0Y?i1sU-a;&XjLM0UZDq20pBuUI%_@VSod` z1?K68za5vqvoHYsQsD3uky)RqF?~|cLV!o9Uk&X3eI@v*N2V83AK@wz}3 z@+rddS0?J;lJqR(mETu^-+)6o)1b^kIisNbrU6+fXBd>$;4GBLv(bPf>u!msp|<_c zG~nBuAPblMtTn(8FdgtT$!`ZG1MD|6faGk0k`(<+HGuStg7R45NY5xJk2Qew41*Hr znWQCWqX9?G3>Qx$d;1d&n3zwt7$c=V?(iWubW1@XX5+7q2>%!=&qT6nZ(w9yYEs*;F8&~lxI>rBy9XU+0HgV+0HOP0X<;rJ{vs%)DA^dJdOQldhkckgZ}RKd4JUfKoeB33!;3r^~OIW z!BLMX*jmUFzc(>@w8|92Q6+#q72x+2p4wBDgOv$~W&-XV2CB%H?hR8ZZ6C zd(jzVYsrAoET%WAF;*qa68rO|G}E<>E^gXpn|3cB`{yM1#Yu$nl{8*Pyzx+ZP*&i% zIwWT$NEEsP&lc^(9QRo3C@{%dB~S{>(-oYE6tcb`bjx2itE0_4U+N=OqwQHN0-?dj z6-pipi(h6$&4O=glZ6DPA?3d(57fupinX2wnMQmf`9iT%Z%n)Y#L=wTJ7(WC>PE`) z_z)*bD_oTy{FQ6gg1mNmUVhQ6J>J#}A=2hX<^$bV^+*sCY0(E-NH83eUskf!8x`sn zjjsph*x-LCG1^DROZ2+&bRkE~=#A__y{tyBR+)*kMRJ0uTt-)|Q@ET0dS(R8ohf7{ zF4Eajq2&E`k@$M517iCDQH4X5!i^`gT}gt7!QGe>ffl1LGHO?;rj%c?zlLKVE4P=O zrHa?tqMC!I;`M*xdzX#J5`ccS#7HhWTt@34Y!ZBsyU4TA1_OM$R(nZ?0zVOjFJG5s3h;(ol_opq|Mp-w&b z3s+Lj19ctUh{%jR0J(ZAUn9dqftZ@V}+B2)%?LL_Xzix?CdQL9TWn8d4kGFI93c?{*6a6Cac|Am<#&!wW57~8edcc`rnkl5}gz2>Z7uK99yO@EZcc) zX$@$!!87>9rd*?S8n#r#*T1XlUAw=fmlpGmZg>r5p zJ6}5C_-=e?Em;$19VBaE$sMNcf_7X*wYHa5MD^5f5B2iR;8{gh7e3e_GGxuqWPBJ! z7SQVBdys%rqr8mSi}CSQMhdWH?f560`w6}kA+^|Fl*pSp${|v#oMYqHg?i(PgAi&a zr(;^C%sh-QKp4)VMi)K)7NxJac)4G*t$l zR|nfkhh26w996ZL7>d19{+;ceoK1)yg}-OHkstrHr#eQXf8hNC&*w`l+ni#leS&OMQ3! zc$Q(=<;!8Q=Lamk2TNpxTvFc8sen^rDi_C{UnIWgPx)$`RY@L75_>e?o z5r=b%-~nxn($1SPSbM>z&au62jAxU$(iAM2M56MF5AiBnE6|56B=>IbGA*L-J2Qzy zz1<_5Z+V^V`!XzjJ)Oavjwe!Q0zY@+Vug0R7p#Y@2d-d1x50{xSgVY;Cx9$}_;PNI z!$a4bc1YXaCKW4R>JvA*zNm(rbExAucTjFo;8vcMCRW5?E*C?D5Ei)h*nKns=dfDx zBG*EE*VQC8Uu*saHnoGscdqq)$GSAkCftH8ic&YewEuTes>Z?;@HL-GOf{RTg+8( z>pd)_%Z}IxcA>DQZo|D7cUAMb|4?8*61JL`?tROQPud(J{OkV8BF>IT$hQeiA5A^o zaK3u+$;{m5eBH}i8NocyGWr!_qhen=X6TfcODznfGJM(59CLk0Lt4J#_*q2p9n*^v zzv>;|8P$bD^TbE2Wdm60!D*U}bdPVbU+prEAe?Y7nxww}f#5uACNcpWPpbB65tn*> zYXwe>r%3(bIp;ku%`F_a6&S$_@EbT0oNn>GJT5VzW{O$fCv!>iI|7?6lqVU zcMIl^OI7k#0F4^nWLTcV6FlJIF83HviBn@UA}i6*P`x0V4qFrs85wgxuimFD4;SNa zmV4O{JwdMBe$z%HyN}`ZCx!}UQ7!^d#X(gQhtB$EW|=k}h?b~Oe1|}%!leO`ytnU= zJuIi>?dX-bL!YX3)n1%?Af*|<<)^KfgHrzD3X+S_-N<(%t8Lo+!4Kv@_IZQ;nPI+d z2m<$!NgB4(`gA^fTv%E&OMFFt)zv|Odj4ZvbCiq>O+wp-cZ=AXvgxfv6oCzL1KiuF zIwa7Zw{&pX6tP6QT%%@v>IzD4YSJq0Cv)U>SLFxO8o@NJjZJ4#!_%uyYt3RoHXdtD+g!rifl`39) z9-4D8^oB#A{#6QLVkO8zSzvSxFo}s4&*HWDg-OhDO7-V%FrV!rW9c-4S?P5_?b z@6T`QX^F$oQkM}fsGQWVU%zP@380>0-eILxjaQM?J>YH4HiW$Vz6OLbG)O(u7xa(` z?K&o7Y2v-ald=JJKRVhAuo&QTiiwHylgzsrd;|$M3wIm&^*6}mMUL?GGQ~90a^J`L zmR2(FJw9OTsM-{Ut>A9NJr#=hOk1xE&v#Azw!|CZ4<%bXq+5n3ql|xSl+^EgLh!DZu~cl;g05*#Q&L|JOuKqvT435s*J$O5lp07tqh=4-R%&2C@(XCt`yz}) z#@*wjn^Zyq0NM%SS(m>qto-(Gd_~nC^LdSJV0fx96Uk+<wa}lb(Gmdq&()5K*fgQv*2Eh-Yd33oENMcWm~vUmeId;y4#PBM$Q~0{5elLB*`N6yFfq z9!|ZaL-CJ@^;oKsZN6%${XB}{wP=#_BED{oA{3CX8;53Z$5%3VOWwATosc_(3E=Jr z&eB`?-Qk@9MtQkF1Nv~{kwr2@4_X}GI&4pfFzddt0m2^uSe@V|!eam=Zi2J)Pa#y9 z;ki;sL)hz;j`o#i*WFDsaBA^Ej6D4(B7h+W5QqQ>oI;E;BW^h1-xGNe)C3vJA@8b~ zvM*p5GG4zCB8=OFc{TYme_rV;_l^_MfdHF^fb0P}r_du<-qHz&iLW;ZKL&sVBvAhp zA_L2h){O6^poxx^)TLHl*?VV&aL?O`ySj`{NBJq^$K77q1mY>$nRif7gJq{9d>y2q zko`pd0DWZ_46r+e>cH|@`nv*zz-?WoG`u-ETX8%A@w>EHtt>YuRA49p)tb*=#*<9EoT#L_=;+Dp$SOEgIrJtoyHVgg&=g$4 z%-Hn&&{}xPGKl64AE=v2NAPHpz(BV?H~=;o{XfzQBMPsV*BpjPefsbcmlgj=y1&=>UTm1+{;Q{ zmEyQp$xklmqiw1>*Yw|AgoO;ar&&D9;a66F{@e-Y|Eb@6VV8ye2WPEL62gU!rdSZ+ zY`U{Al*0Oo60;Kd3-!j<$oRYLZ+UI>>4NDyR0$tazi}2Ovp01E>MNzY8lMgV2o*>x~Kf1>;;4F{Rs7YjrVp`__J#~`6qmqa~$9d;hV26MTUp@45 z)2kG+b0B$V7FMeO!aS`LQ3By?0GwO_PN!0uT&W|4V{51kIvFb9ER7>)01Dut_`B&R zp#RVl!@+^J{Qy8f;yg|vIY)PS4&TS{B(QLV#|EB8aR7-UtHVCoy^J_AFd8uMG!l}} z?>4rdN7YnIJ4$E7ut)TmJi&QfYhA{Wl>V|+0Td(aup+R6)^N6W`UE~efCm@_0gP5o zBWkz~PQ5eT&nIdw@;L+tM7F6e-EY+|)XwlSPqb4l>syo~awTy#e+@zWU5Q6EAw8uLpj0>Oo3~tr#%r09c;j zPooJi1W>TB)2PK)1#4wMX6Ut9rkx@8)ZK2<@rYwQ}ExK*7RJBP75S^0yT%%;u~V3<`K3_|i()DHP=-clo%^@qU6?VW-iPU(V5P1NNOp zF7o+ZbJ_~m_KE0q=xyj5As=#0NThoDy!JaWKib}5Pyr9pm%^4PM^DtZK&0h>%c0<` zaP-qC*bix0$81;BV4;am5EPDA^JEctuG6PsJ;)-`2XZWc_3aT_IxoF^O= zm{VF-OX(yA;asVU@I`7#=%YT_t-SyPZY`i)si%>U-_ouo02s)=QX|hwyN;3*K)X^; zAtt|~T}NLpKC;<_<+}%~zXi~*KLzx=; z(e;Fo@2r*Ci+yprGh{hrln}mGSsfX@KhDB>1C`d6C5&!lf=pAvdijAN@F0f?5^`Pq z(bxxRlu%@&H`=OD)$cE1{;xJiKml6}Bk9?3Nc3*#yo>Z~Tumv~--dYCwr zppUOSHOjZ+qB@F21Ac8b+khj4xI%LdLMPOLEsQJl>_n*eeJJi0fQ_4XEHQWHLcXV|Kb?8)VTVUOZ1}@P;1Wr~)1W6-a}zIFYvp>5pCyMUXP5jn!ue4IC!{?dKRd@I0wx4)vFP zm_0Jd8)cYiknF`p-r+k%)40bjT~XpLW_!luDa# zMPzB#RPC;Q!tw%7^uBsHdM!+)sf5hWOL;vxWqrk6Ucj`9ejjsgnUHMXTXH{}ftYn? zPsAL*Az4CPZ)2F@oa)B?ozBp!inLyQ3GdSJ6I4rYGZQHiP1_n}VpHrrv$wiAl$1PM ztd8_Vy3BXt?KMfiN(I%=zO?x6t!Wax&)`=|tT_lqZEyU@4d(DYj)Zw3m zk_|VyX6gNsF%YK6lzj8aAm=I}f#-UjlWj(;bFsiL6FzYkne^vT>BG#HEnblSv_n6d zbeTjkAKB(ew0qX{T>#Me5yM@#KzsDRfui znH1NhLGk3$!`7`)Igia6#tg`#6-jL^2;Y^BkjJpAWX!a*whNV9iIuy)$n6@=YSRfw z(VD2n1+E(zdwE}^Z|UxmgZFAseX>2^dvP+fDqqNitH{x)`%?DY zA1-N|D$Zih12wr^D!gnqf4c68J3+kaCofC8Xh)5{rSwS~;!)g8pB}N$g|=sqein^Z zqkGo|ghu^e6KSZJUs1zWrO8Di#`^+S`y%y5GfZ}-5RaNXbZMbd)_yHOOiq|ddTE-R zOfsi#XGGmr+53RnZ@psVDIO{r{XCxKOi$z;dmkdcY^vNj9BHI7evd=c*CEAEeGTMV z17^~$>ORL5N_~X%QJrAL-Xv}?@QsD2^4;z-*G?k6cYE$?sv+;E)=&b}O(ISo6;i!haCeK7gr$Ut;c`0f4HS$hhv_USP2}z=Fi13A;(b1s2#6aFx z8&o1WPG9!uF*nMKlAP(h@_b!A$%Eh@YEiw2gKj!((?UC6U5>h-%``IH+BuNN_7seW zQ$<2m>>br=t@=oeq2n$4JuZ1k?x!$#8jPi=0D4GUW8{3$l>ff!2VvBgX?^mY)3Gt@ zufv!&v!eR3lG;?hjIHC=g}NjUc?{d>?bKVVL04p^HSBhKxKR{r^gzag0HRM zw-iem*$l!bjH|2lFAwLtuIjlH=^YHmx-RH>CFu_i*Sfyf^GPz`8yMMc( zkLZPsn-ER9Ld9*8K1EU& z?z3-*eFJtC%yVrVH%x(;zp()Lyc)$loKA52x`0l&@J} zOiCPR%KrgP?RHo^&gGkJJ10|F2h#-THJM+pe8uaMIhy}7@d-2R9`-`FdFO3}KyJQx zK`=Fw>+%pST@}y;7ly^Fb>y+7(KSMH6Th;mjkSfO7RTc>5UF4$zDnPAY)!z|zahiZ5MzJVPyhoUzHCq)X zOv#VGCwFHbpa-R@sZ{6hdtQKqIQlVn&C4Tc$dW9z;-7q_bFguO595e|zP&EWR`Le; z>1TJo_Lz`w9ge#>K7TTI#bjoF#<~Aj-ln*+8Kv*>x?QklWHW1Ycg4M>Om`z*=kdmNp8|H1 zYZ89cXrNJuP+zI=1&lW!HZQD;CvaTm9r=wh_p7#SMVub;ows)nuC;u3`_`F$Hw80t z1#Jk|T=*D1z}VEM*lc{#I&2E}YwG@Hsn`{i!RQ(`Y)0GG(Hb}Fs|7vKZc68-n36Kg z3CUc-U&84a&S}cymW)9$RC?rA8(5i@=wcfv!boMtP{&&LN&Zt(^-?LNoBn!N6KIO* z!C* zK7V%0$RMEGkB~^ch#lZGx376dJgY=bBOCj4GACl&cKz^zTN1Y_0yAi=V$Cta1=)q} z`1r^Q4v78Z=p`JTr_z23)I*&vS$yun0od!eZR<*100f#c6P@Fl^AI?o8DS_ll%{|HO!m#H%)n zTIDpBBh(kg)16R|j%23RWft(%!L>u3pM%AO%?|FOod1Ydkhct-i%ATc{jjW%)hL|; zmm+8qByPX81%z-)t`!JrUUqnL>Y}e= zH-&S(jnvpl3*KtvfiQJG6MJ){{Ma^ce5n1EA=QjgXM%qh^w@nE~6j?0)%>9Tl6;4gBNkXneeXIrR3~T|16!GJZDPcUuIgG)z zG@?m(wW5%_uAv5`mCT3~mI(?lYt88*Ux!*jkUfdN(sG;)IEZbOdEisRlW)cvRbgxI zcy6oSq|lxoxfJauaROPTH4=oZOW+e=c<)g#{;}gNla) zBYSk?u)Y3NeOD5`0w1O;Ki8BL`T)DORJD>w_zb+8gU>_B{g9u7q+nsZFC<8`p}Yt7 zE%U+@;cpH$BHtzZrGrX= zZS7gL!9e;YUlPrUMwbfl@PZ_4+hmvJPN}l@CKScgYIi|{9s*iEtuNt&IS`PSFSH^z zmyZJz+~71Nd1j`BO&Et==(|YVu2x1RiSt|??YZ=BkBuRg#4dyJO~DzsF3R+pl>?=+ z*Kd)pGV^VRICH^xrG>KrA@K_CkJ46_WaUsRkW+fhbYF+ezH-69V-z;FXst(1*YmqH zvDSM$bs!as_@Y)F29Pch-}W{++DkP3{N-_3g?Qjdo@=T+SAeK}c+%Ng{421f@?FlP z0qhG{IH{-RXNu#;S-Ulw9_|vRLxhWr*&1ALgND?BBs#vCYq*v zaX8HORLYzE>c$rhm#;6mzZ*P5MjhdBk|5YMth5R7SJwGvkLCmYOyk4)w}8r4=pMq} zCx)DZ_D5j~5tBRxUc}+pp5GsowRuzVBbB-=(QGDqFc$-443_*-B6qlb!{rD&)Rn$J zq7k1r1h6ILkE{WgfGTuvx!H1g0&31m48C1Q@VIZa_V_N<*c;5)VGPb$*G|5 z0L8%6Wimy(R)bLSPYsDx(eJX+l2j9xs$gqrOc^F6stvBoZ6(cI5GNdKe??b-`=q+L zvuB@|e;B7|40<-!Zv>2#NN@Nt(*d!Ub*aoJgpoI)BHazXIsd*4@MJZ5jK1et@+@Jj zoo=>%xa5$7b57rpPq1=SABIzZ0A%wSJoc{FGL$lvjck~?Hju*dZ`;_8C~roWcVY-bq0%We@Z~PURPQ&ZFr}GAWA=ZHPsAk>XX3?!aLZ2XX9p0DA~^Q? zJgxDZ*P>Iulcn;Q(qj_4_wNWl7M(e(jDrr|6Y-7z#H@^qP$e_&E}ZS{$_^GLYD-F1 zccO^1eZ_OG*FLSjKa46B66c2rZ4)~ii^&JlA#TT^x?CG&6^OnS)}!*+{gzOf(jdpM zw*u->IvT#47Kj?6?S8qz9hKnxC8y>B%uoqs61|3+9y-6_>U#v-+#;g^g?SBYzpOA6*rDI?hRG{cm3opuN{!(+Tx>kq zTWOT!>}I)9(`iZo#X|!AbTn^1 z(Peh&oKdYMECG1}UI&&OGQN|6dnfN*Y7HwJJM7acve4$5ct+XDonYjRtXi5g45hrc zFg*=o!4!aQYwG;TLPB7WVFRo>{9Ao2tK%5h^ZHYeuE{Q)q>lnf7@1f;WDyHSJts{- zGO5HblE`ZP5a&4X>p>pn=uo zW&Ok&#SHCB!DF-MMk-QyV!lSxt2K2Z3p{gX0|G#S($P%8V=K&ZYD!vF=BNsrv!Afh zRQ{Bu{e~GA2;4Lal<_&idIEeLpK|UJf>f7xO%f-GLYG7BQ^S$&JKP4={l@1i>)?*_ zmUafsBp05JWdH`6!liRd++7s|)NSS+MT7SZjZxz z=D%J9C;+l5B6(|Fi`)Z=Gb!B#z#p%?BZ;ab@(n0u z^K2VgDNiIgl1UJu#_IfmEs!!e;jFHU6>C8;u!_^k{{IFP@F&s^koZISAG!LTyQJg( zX!O#TvYv!a4FJam%R>9Jo;9PI3eRN~Rm3OOR-)?QCBmg#zs)D_B_vS;^#2`}#SfM{ zVD2=`f8bjdi|U8Q^8oNX2mAjc2e=_#H9-?R{BNWIFcp5Z!+x}B{sZm8EaO0ViL=O@ z_CK=#oCH97ol-)Ueg3>$b;|>V15AIK8?i9|9SAVM%s)2tlc=2```_{)K-B-QCcuB$ z>U2|leH3&Q~_l7 z$DHe900tZB=kR>Zrj%XNnC2VPw15lfSGy_1Y$PmYxSq;5g5=E zVq6HIgjfpLaUCm8z#EwXFOlot(EtN1{t*8Yp4*Q44|u|V+G79bxPWAYH@jK?G+zB5 zhwFb`1iJo_{Ymz2PyPo6T6FGu2>|*{|3AfH&OVC>Y6Sj`G@#m#u;-8P<$oZYgWzrJ z|BnzYD_}(0j%izXk9eCQEa-ndh5z>Mp;mv?0|9e){-ZU4a&|ohkH0Q&SN;bAw2Y8~ z14tvQbWe?ce2V7p2U+jGc?19jKU4DH$t2w0AIR?=mIHZqolfHCpZ+yEUAGYPe+WAh zB~n;nwF)R&j`L3*r56~%k!6m&Vs|8<^biachb7#LgVOj2jBkQerk;3_#FJIr<1Q+% zYUcr^1u8QL9H&5o*bQl@!8g##0C-pmc-S#oyHudm?RydoV~!WV%aW$GrbEUTLi-I3dtFFO962tD-XzK2Rk_!d zWu>&xOfIH)Y%{tb*R=L1#Vk%}v9+nTidcy+%-$ii(q zie1E;vc8nEp)~tfu$etN z7MXL52MPr!4T11m<36L|nENp?MdyqSrA0zOJ>N!bn07t{!jZ$s?Chh#GW!pLVcyhN zxzMtISHpRN6%Uq)XBlSb+SN}*DE^dP`y>Qv}+OiR7gA2thtgUx4^zWA;u_#AI7ray8HZvBk(5zNFJ|3h+1MKs7n1J98H*vFYe4t z)+vJ=*X~i6^TyqqHC45juopAwPm)W{U5MD6ZNFZYfY0{&g&!BvLI`v&#hG7qMDbRe z8NutS${=4)GtrChc4b=n#*OH6<~G7;U}7$g3-WcIlX$=;R6G#eYICUh4^<#mdE^WX z$|ljIa`n*W;uvyxd)XV-OX5TKD>NE>EpT1=wm5=&W zV%vOe!jCVW<-LhGfqTIbU1=_c9ME|#x1YMHRPXkkOB9hSDBzslwc&0m$>V*IR#}*%y$b|VYxJETo1DqhZB#@g4_tJuyL!BCDYdoai~rYR;!C|x7{rQB zp5@T=yJt=7cL_s`I#My8(+5h?Z+Y+DMjX-_e96e?lDi@cz^3baK&qs9i<1}u*y!`B zcuW=2bBEE&_X|^*gA1AIx;Q1WiJgPnD8<#fbk{w&44}G&+ioe2Ayu(=d zL;}Vpu4h|bQq!t47*Yta3|%(awy`VNZL$}F!acxYccP2AHbHQKw9=mr>ZhJq-g6_R zF<6?gf<8YrC0;p!sBZQP*VZ5P=Ig_$2fg>3Z2kAPXmM&TR5$n;&kM7po~NLp_|bHm zS#+Ik%w3W=xaK|5j|ct?S^;*CAv$F?ntsA8=f>ByrwtpWX`ExUrthKnBMc~qAxh3^ z7Ve=QqfiMr1V84ig}&&sQI;H#^zfHZDqYyGAEuMrQCZ)-Gyc$QJfM9HZH7{n4w0l@x2I+;FAFvBtf4510 zTpU&f$6eG4p7%x8tV{hY(+3AZSP?J>s_JfaZFdID8EbN%JKY7fNPF}Go{+3S3LvdJ zlrbr5-JCx^jLCMbTmO`b+m&#})zs}n6e&+I(Yr0!4)kN*v%$=?T+Cz=M{#(Wy(=BQD z+%=$74fh>XP!2eJ^Cgd^e7FCP8SmS{h6d)$=8b!)e0pd$Qgg9Tsv|tzPtN;X*RNsN zkniw}UIa$>-bX=UB42F-zB2V|l~qDm*@fu0stmFvc-*1VP_?2>{_<%?epR!UR7V0* zdwhjNqV&bgL%n{wYm{Eh%Yx8^(3spn*Xp>5_c;)JH>*a-w=oTL=NPX=yid5%j)=u& zK=edQL;3r6Bk2@@)*Z)KzkYQK2%PTauQe$WB>d^7@NyywhqQY3 z(mwZyr>1cP;4)7OmBvFTabTV`fb}2uexmhLcMUmj)~VEYe=T1|r&HZKxi(`#*HLwG zM0#o5mU{v98uc=LbQ?ZSVe#eK5}o(1cgK}%c6&sAs_af@Akr19UM(?j(E6({5=Ts1 zB6pNuT8GqNjw+C_u ztFksF(2*VY~W7n1HbV1^L1l=a3-UP z~RK(O*tw%)5d8SNs_`o=;FZx281>CDBB0!kv7h)Sfkj_Etl=_mFL0s6c zu&*<%4FsND5qh>_}P zZdf(#@WjYtxnkFEb3ka3ip(lwzV+C77(4haKF7HqBS)!)dwd(*c4!Y-N*yoZguD*H zU&zDwiIY=^oa^7XKh_BE=nIQ+fWjti1SIvjFdqsF4P_*7{sn4k*@A={n;U9L`?A0( zRZFPQqE18*Y2d@{l@C>%o$o(lC_f%5n=nZrr@6x$Ck8Q|fjjKt z1iK~q3b}UPb+=4y8FJ=+xh^P8?zE>HOFkmNoL8Hi*%DAxJ)7dRQ=x-*zX?CQhjAyq zYsi)3E5mPP&%vm+IUP}7wCL)RIL`cI)&Gm|u_S1N1ctS9HuDDll zBIyl5QdE)12ww7om3m^$puxx9Rx%~;+F4iivzxjve#I37LUtlV9QEjxUY0kxrT|9H zrWcbaz*0{|=b3(mq1bQ=ih~)Cl(jIxjUs`DSCu-(CPfX{vw|Nk{kHJqZ)OXDCigL- z2fb_Gkt*i8Ym=iCXt^ATyb4?|y?8eK|?tUX^5TsC^@%~72>a4nR7 z(b6Ursnyu<4EO-v66QzEP8#cXuddg76<=i%zq&ll5s~=Rvy|GjE8Meu+4(QOP)}ozkq`H(^(`_Z ze!O}fQZaD!aZt)lg+cvfd|@Fs^c~ilb+0ayMfKUf>aRWMYfcGT=~b??5|$%h2@rI>stDSF_vR#3hWt^ zJY7bN;Y@iGn%_`sc<~;N0Rvtn2KD^q(?w!NB(+M0HWTlp=}eHmH3@-klM~R#2m>?? zjTIUc&Qh-fpbIO!gH@!Fe3Ks(K=Z-(d?Kg$#Mo%t`b^w2#}S6P>mdeJY2{Ih8J7rW zyFs4ZTB6K*9ep%We)7YGW5>fmgo^@Wzt&QPYl09I6u%dr1{9n^%75-i&Zcn+Ac29e|-PW7I#xTczE+X=WT$ zf17m*NEvfYg@CQhcEd$ag$TGEyBVGTQzi=aUfC=QHq38SsHGmXTNue~kW}Wstdy|r z=pa4CmL-F>UEFI5omV8S&A`L9U}jhNEN3OccC28b1bgk3iw^_P*GS-O>V?!%}r?SXXyJ!BHF zvwN_tLg} zgC1>%STQ+UtckzdU~IGoka?K_SYvWOmCpt{^DeJ&o>=WqAg_a zVM1a41zs}(X{(FI!fb(9A7kc%^ZUu|z$QER>y&12O3Z8$!n8`d?unJi9%HBtT|yG` z0{6b3?pIWmNQEL)3?*&}rZt5cQ_6B@!~Ak9L2VP0L{6%fv7h_ylu;h=gUssH-;Zu< zJfgplWjiuCoS_JE0axhgcvNlksbHSV1e}WtI!vdRWFXVA6dxnwz}=Ovz3lrji`2iE zU#D2j3{S3!yMoP{(_Rsd7%I8#PCWo_0JUj!nik4QSs^|SKKs9!D~rmIoPbbJ-{ zU1hRlmEnJL|1IuqcX04rK**f>RG)NJZ%X~0*;P2mU$Lq2G{@=-sANqj^Hid`PppJ!n4DE|t)Iisyt(N+DGveWxwYL=ly(PpjS$bGF#7BBg&3iMj%Vh4=`rvsYXRtx>Aj=4QU5A=?+-?zk(#lGmAzH-L zrQe(Ra^|6y7&XjPBP2`Ujzv=Z2Kwn4tOHg$1$XbhQT$@i0qvfbv4#y%*{<+qOF9T5 z2jv%>tIH#-slC*nofD;EHu1x;%0XwUY->eu#8B=W(?B6Y+bUidCvfJ<$fO7g-wlBE znIInph5W(DBFjs~3V&9^U)5Y|KkK?oWR_?VxNcvh9z3?l}aa1gJGQqSIs`CqzpnSq)8y5mb z=^4k8+DE?&L4oA=uocY9KosRQ9^6`+2$I^Fj|jPkCdXvWe~ks0;@4b7a>3RhtIM%z z`Rss@5;*d|O&0}xH6+Wy9O=U`Dk9a+8EK9f@oT_E+!dx7(PP!PZ*4{xfQ|4R-tU9ERyEBi3S76a zt6Wk;4$kFOq)JWd#Cq`(WBTiJACRbtKRy22?Pdi*^D)l3XyBz2l6oKKHR1~vGTCx3 zLDX|2xL230Mm&nvu7j{1^_Jtjb5e`M=5-+IW~2FFaOoaw#R#Xoj(PgKVGK~MMCg||IC`rsw9wj;#s zP4I~qMT2qAh+Z8d4@e1tl%(BG4CZu*Ta6sF(g>5EgxK4;}S3qdQyd2+Q z({v&1%&qfUBwo=KfQsr=nmd*fUa|A+$Le(b^1J{<^;) ziPdu~9k$K^B!%KKfuSe9ONOMp;&F5aUrfbVU%k5H3dinOSy?JBle~vO`;(G;b z8-RM-H2#*KgI4qHZ~iZ2ZX^Gs(EfD*5;2^YGpO6sY@%h4IY@J3E7ji2?+1_>Vcy1L z@JG9`lzyCTyH6Xn!oN~I^enfo@$Go0Uz=j@82`M>tR}FI8=0?yTB9eIN`_lNkDMoa zM*Rr5b#KTUEgimcW-c&k3aojYo1Ij0VU^y}v8l3Yd4x3y?5?dYYBG%ORMqRLU84`_N<>0UhJ-u_qQ zH0W~hN}s+#9lO(KiBpv1^#XeWA`hyeT8fyJ{4PQ$iGU90Mz{69F7YQ5sTx{qem1$U z%ta1Xk*=4atZll^l1+Rm_JE=`Am_>b>*u2eesFX9`*>1W&I#syyyWRY1VWlT$kVqn z8pbRYl|6Ku6Q{CiY}DWd+QzQ%J2_cI2)sSYND2e&__sk7O27k_Goi=bR_o+sA%k@; zW^=qw$ZDmoNbe1A8ry9^zY^UzNx54R!LY7McF;GcyeqRNImkmn5MARK z{hn4rk(u;-JPM2T^#C0(Lal(cmGy!sd5krvwQ1*tkXYPbkggI?I#I{5YaIO*&HOet z?ZLGLsML%`e2Lvt&m;x+W7kT0RkF2oWXJV`e7O`W>bJ1J+fio(!ZjqcvhNKZmNZ8J z-aNtpNFW3!36H%@dlS|M>u(>eKa*w5e>n9&A{Tt24?5R zHYKw0$cPPRLs&oSMmd&kseyF^&BJeJqs_f8I~WJ^D3}Y4b*f5Y`{dV~DZp|vAepKv zgRx^Th1b-XYWB`3uzutZ_*m2&qB@t>@=h&SmFF(r-fOYU1{6Y*vx^@m0zRbgSD`50;vg*p&njCD z4n~CSVIWUr7kAhEk>I~qvno~oE{$oq3^!zd3TszFV?O1v-6Wr^7v(a#v_SI|w159_fmK)R_7(N{ zl;exJT3Nu4QNw=sHoG3o*VFBJAv)Da9kp`R5ihy(ZxXnOG7JMfRV%v4WgSI^kw8eYwXk3gMa!MbHg6 z;a_feYVEUK3jIt#=Yx2{$Wrn_oJTBbP;SOkU1{hZgwL%#yI>xk7e{~imzHH%V>*;D ziy(!d5_(5ko5RTSz%?DDutE8k`gn-14(yX3wU4K_!+k?{pAe#m#+xk$8TE#mP4!EY z^)8dNV1D`6T8mHM`RvCw@&;<;#SJWs^aj%pEK|mUi^W=bda=EY;tC z^b$I-XEVM~4g0oKsCpsOY~&+`2pD;sXWvwlZ-FyX=jI+~eqXtK9`B3(D>DWR01p1- zLeuBgsD3{bg{fy&EJPSYEUGjr4eIwr&G{Gl$K7hji zyZhTO;Z#4vDUd0EMN#X}O6lF>lnV(&Cbll@J}Cw*+KWL>BG)IFV_UM}vdq>~!P8Xi z%ATk30KzH-EXj@XYdsNdh0hAKnjYlYcOrluG?al?@36Sp2wN;X2jgZ8+5w3dsRXOnYQ4Z$dj}q8ZY7MQ*4v)t)caA5-jlPj4YTBUkq= z+1N<0jo3L6F}r|C6~EqZV5(dq({nI+RzQ*ja!{*sB$WcsC=uN0Zw||F;UWSpPEN%k z&U}B5QX>T3(iGD5XnQ60B!KsynV4dPCYDdtMWV`u#h}m-!Yq2CAq?XlKxM@SZBy`3 z%H}hJOiz~cm4o!EtzRW|syl$?0|A+Vr3IA0GEl(!KCff??%m%ZfFyAQX%3J1rFi_8 zNYxx#A=V!>sdT+K140)w5!VV-9auc5v4)nM)n&NP=!p84VxL-v&&p(rk2grHy(wK@6@;iR5nF`=N7S4BSMWpy{!}+oZ<6w+743#kVE=wS_cmZL8_pa33`h6jnrT# zcimFNdMAPmM?W+)ECZMRcVRjB4zE*Es+sOae*%pHe`)|`CtO2Oea!TWH{nwd^4Db~ zArt^(>-hMBNi7Dr))|%jdOk%6+*UMi6u9j6wbj0$lf0-NQ-XeKro&F4wKe*d_KCf{ zpd4vnV4VPV4R_!?CQj~9vRg%0m52CX6eCCP{t>`INc}C68G|-gH=VIV4=Okx;MfWq zw{I0slChpH;aGe0Fu9ld%$?i~a$q(BrK!>3RFd`>2NIcn85FG~KS#JrMk=$xfCWR< znU;+zR@6004C0_?z?pTG+Qe$#W`*wO^y%iNBH+DH_$SbOjOKQs`8e^p7bE2QmoY@G zD<4er@>7oFn+Q|Nj!?4H!V3Jd64hT1apwZuN%SO=S&OP|(TyWH%OpyI4|1aQ&USok zKzxs#X|0amuEGN9b%Unzy!|fwY!rX!k>DCgS{4lX{A6aLPw7Q46Mq{vlKJ~7)qplV z)cvvDIHk>Ld+`lHdfada-u-4%s@xFr*a{&t(MkvCQ*9oOVYwJT<+LVbK5SP?35|?R zXWU0u|KR=eFsy;D*;+^_6QpFOv(*b$p59J=3x}cYl0gNy^=!{_l@>cFcYH?@h+A^h zYU)%swDY_@Ql47g#ct_!@8Du`VdkH;CU4a?Eso;*=Rvk-1Jr=HRM$yzc|EJDY#zlL z5CAz1yU}Xhd^;$DwNh2{4Yr2PA|FFp4CFWN=H&*g6%QPHU4c;Xg@I`zQrT^lRtnc4 zcTJyU=^xb(3Pd+;mwBn*@6F-JZdDBUdOaeq1G^`&k(q9Uje6vCS4e+9(DodftC zHrH3D4Xuz@BcxoCfYFGrVP$*6gFdMC-!T( zhDRa{Q9F(PNX1Ak7s$oO^EpEelmFdZAgdOn^o<-2mlLBVSs0-=!iPZ!CyTm2z5J)p zZGTV2tBW`lRQ|dzF@sBDqN+tb(H|EF#{TAkENrv(EprKI28vD%`>PUO!1ojPOj5J6 z-QiM9>_Y1uqjJhd;sLMmvdaD4Pqb6mdYPT;F#sXkVA`euQ5>E%zB;DOzQt=ywNTVP zFG>n#tuV$g%4UAy_;Vvl#K(17$l5a&2zYsgMpAU9*MU}5fc)Azkt1CUvIDY}qf>!> zJ@zAKY_~Hh;p+|3L^1931Wq@)ZK{*I7tA(AjeGIXBy`aifMVAobT-iRnJ8@tkUXp6Yy)z&YXQpJ$d zhM;L5G2ThqS@HxhevW@X6ps{pZT!942E6N%XuhN8+_XR4qDue3rA8r4=rc&Looe^K z#?gvLG<(-TiE&gF0WhjwGQ>da?SYj#6RMwzJW{`p!((S$pcQ;qb*>U?&ekL=APMoS1cGt=U*&Ye{ zQb-ulFuEt5%&g*wse9H@O%(c39ObtSEBqZK&GCKtJLmqI$+uX*IoJjefrqnjfY~r8 zGZgKHA_FIy8rcJ$HBl6MsrsFVR(#R7m^+R$^xg42-JF?80CGIXi*$*TKKTX&y@m{{ z6p=qS0BQlU??B&e#NQs!@(0%HmC`4Qb)@To8q+q+oO{3sh5sAw>V43yE)~jcliKW$ zqfBIDVtHIteWaPB=gvI<#-NgP?kCVwyM)M#U8iPYIGiX?We00;4zQH-zCn)SI4R#k zM72fqaO~Y~Hk0Kh<#Bfa89Wc4M%jqr#Crv&vJkn6n zf2yTHO{su1tH19Ygqg2kDH>aBSZ3?did{UW+L+G+OSoo3^YZb7Cl~rg3OEQ=CjE4T z0S;PbV45{KVyO$*2L6T&^^Z>*tvIdWoB#Et!E>~zKxBCPfwn|C)DSl{5@Z-jWkd5$ z4Rmfd2OE=LMLg~iYCC=SjawmcKKEk2-fM!zF)2lWhKdIMPJHUD5_r)cR9a(Gm@7$a zQq{tcr3=I-^{DlWu-V{vpYEIP*~@pVlcXwoOza^fhc?Q|Tcc4{Blqd$2q`-c?{ABY z#xtDCL%n$)^fGc0qId4Pvt6z%H1a+V4NIsVIiuu~WzuhMHpsyRw=P+lhv8w-q{; z7k%zUj5?^8;F6dF@n1(_z#Z$mu79Li-s-CJIwU-+wn)XvBdX!y1aa9lms+lrltrZ8 zL+g-D!0W~#I9KYr$)nLxr6hIeS9(4u-ta&8m4r#mx4xi^S?l|z5llHR?( zG@lBKlds$4oxH&Z-bfQZe6r%flV$8viyt2v><+j;xD?1~fvyElSynQ(F#}xW_B@ny zto-ZM1ohQnGgO14p4=P2+(e!V^d|Rx1(m@w4_tkZakXZKQ_5M9Vo`NjCyCk*^GT`F z^|9n7NpOQrXLKj*&tW+5oA(O@uvqv0Pp)SW(TV2XCU6Y0!6<)?Ef3!6<|uNc_eb=r ztDNjsaB@vX9R`?v#y1wo)-X)mXo=U3yl&7uR7+$E2S;>_R2p|s{t!{i_u|-t8T;v? zT|-5Saw{KN_aje9ImPgf4Hy3P!-H1~lhL2)krsNTw<9>EzYz$=Q{Uz^jNfkudzLAk z;<^4LHr~9eCA^YBOp5s8P=;U6b3?oBrHoaK<7WODROLcE$DG~#!R2v}r_O@x4D*gR z5ytEe9eNtT5lx-R;3GDNwxmlY!dYie%la$IX9LUEog;xt-9=dsRp~aDZ@G9DKGRjI zeye&Z3&i@_RFfY@Ub`WmylwE#{?0SZG1FUt#zRdFgPLf!=R?uke^6C6N^fCwoelx6-mJ3qb?6+l`iF9ZFwdz0ax({IEA3}$EHJ!Zz2z6e@QElMIY zLq1;OkFhir2Sv?=Vj=%_&Ld1jSva|2Kxczm2lhz9e|6BbS8Nwty+z-lMy@Qnx`H$J zVK(!QU;s;+!1TJHKPnyHjkmj(da{9bn#FaJ&a&Txl0S$|DV?LV$?m9keylD%jb_E(NZ^10uVY)MmI2gT( zMcb<5H9=|uGM;^NC9NeEmvz_^76RATj_S~;#!G*vY^eM!ok=E>7c9+eN`p>2o26pq zHv&Kk(=-j$vj#2o2vMx?84jicI9iu>pCX(P{%4**EkKW9r5g!n{PP3!(=l|d%q54s z_0Eo}5zLb|#@f>aH67~&nX>YXw0ty)29?#@uoxn3c^+CwmfE%j(<-HG3kS>898;}| zX2yHYX>;+t*NiTh59F64U7gfbHr=b(OG76U1rryJ%{4+*T%CnI%=VtykewkBg)17Y zJ{t#G`U;`J<=i$X;zrfc^^xlQcjoB2p6 z4$_t6pwwT3n66BrLLXZDGQ|B;+I>Ux2kGz^%@%dh4`v`>wLMAYDc)+REfum7Kyor~5^EavV7zgwRJwEry8Hv9;Y3e$lR#QvL zKfud@eOs@yX&UJQUyO7bM}!o|T8Bq3NS>*mGae}y%0rXk&BIzl1Cb(U_#jUzZ@}Fx zbgb53yM?G}l1`BTon!QhB{%m*ot+R^e2PZms|f=?x9GkEY`{eUdF7Gj_y-bv?W(}% z&lC_w3LjSxsO@hGLBf33A)E)0R;mTyAR5jA_woE}v~UG=MEQ>ufJnWGR)4?hjl?l~ z@Qs5(`Ur}~1FR|E9@vKw_zGRm&;e=O`SM8K|`<8&yr;oN#Sl!D$tV|F4?;3due%uFkB~&vK;dl zizrs{D)x9#ex^z@fWL0qnDSoO0^HisyMC5F3ZADz4{)F(QO%^zn(K69xc0vA=4m& zBf)0p-;W8uYcsp}GA7|8`nc6}`rkw$Xu@aH5w#s;9hpzAeuH~85f0%mW3CgViv^9j z{uxj3+>{81Mw-Dp8kE?R#|gzX5IS8VF4R=rl3S`qVigSSs9li*#-fxZs{!breh2L(o^QaeADCx8qv6 z86~UNmNZ?L9Nhfzn(GC~m7u%aVowJMo$ZRf z`y-7%M3W|V)yeecvXMn_PSrID+rd@VY0?=@_D*iIr0^MCVneA+=&`=a-#ADy9Ws(n zGo#SzJym!o7VS7yT2IA6EvTvvghXZK~`G2QvaOusJcllG#TXa~fD5w3DJsuDX z{nr3W@gp4W{P4F~>^<3dQ*Y!UMvJtLUBsp-YhGfWVr&qtGh*6Alfim27=w;uFqlnB z0yk*jMiXu*;m?fYzC+UeiXyZDSE^-zP{d^NlY6Y`_$?9qUeLiub3l%t(xV^!(tEOJt%}mJeIpw9^gsL@Qn3%BmLC?;&tRJ z_xOO|N#BX-TiD_KYpInWh9=a)Ir&B*L>a@`zm;&vm48kermSh;69lFT)k@i`YiTPb zSDd5Xd6W4Vm-cE-+iA92028`hM8hTEp?$^OBzmt%^ZD4N8(VQnpyzQFR}0l9Mm}Z%G6Nm? zlf8JsPAq)Sw}70L74cUU05@fk0RTYMa8r*_-TZeP-Q3B}{RxV6?|H=0{{VzQd%yBu zJy%9dB-+e>C5~g27_xU!XQTxl=^etxf!C8+p}%MFY;IZ3seX8yz@i(6e_fb-iDYi$ z-AVc6hY%JDjjCS=wyHslPKWZZAN;&<3A?C-0$_rx-Roem6GYx}JnA;u>G+;)9UdP- z#*|@*=*O6gxAC!_z@mk=fP8Q()9(in_y3}tEsMEOOG0)c39PU+A=J6PcMlbY48|-( z!K0z+$)c)iFh(7J`Q*pHmLBLm@_MJYJY@E=R2uvCwI3b4ys?ZxI>?y7wME^nbDMK( z=b&u2%J2Oi8mQat_q0D5?*WsHO-@Rdj9ip|5eI{*F9C8fF4CiS@(|=2u2Qy#uf%O( z!uZ0#6|dWZ9MiiV6S)dHP%{le=v+nX8({RU@nh??n~kHMir7w{E7-B6$g9fsuxQBr z(u-mHjB@Oaur>r=CN5n15~+e{Kg?GKQoT=fyQ3yD#M1sIs*}TXnSbdg=aMp?& zJQbA9mZf!S$Ha|_KN9QthC2XiPyi6XntT8N0|Q<2d-L%HK=PNGDmc1DYTe`&z&0P| z3&k{1^)R6>^?jDk{jB_iXthj$LtIRm`1o55ehNWZN+Kwlu20V?%CU^tiN%d<)X*WPvB(E zq4#XOaEO^H_XPxl($?q9LCy7vCskB`r3-ce9v+$bJYr8)rr%^`dxl%%@GIuqukTPD zcsTylbPF?V)7`7uJKmKj>638L_BsD2aV^lqM`Hq24#^S2ajgh??b!u??77o~1pJav^OHW zDFTs$$D?){XQt0e(M}htaZ6ynx`{M9E(tyWT;(N2#8RS1%DSA$z||2I z{%QDOuY8%F000)87XSbQ001bOTjsP`rV#m)@130Fhn>Yj|IWUI)1qudb_#`F%?};6 z_*F{b&xr3RrH#X|)+Flq9)kaD=w}`us;JLB2894pI4Bs%ImgfbF_Q5SpXmv>s2Ef> zV_}k(dN-m|$&wGs2ZFM-c(((ZhV|EfLCV9M3Hj;b-@u3Vs4DYmj1A_nS4s3y9OFgy zI3?aUV%kJkW&`rZ-L4xA7a_5CXkP~hj9Lngx0OBkABJ;umsY4Kpp2o<&=eF!rw&8g z9i#KodigBq4slct!9+xn%QB^Q{4{}T-!6!jbM0fZq_jIO50#s~9Jd9@j!sOhT_XT# zy`uMIf_?LZzyZz?E8+kE1dzW<0009300RNUJdd#%ON0WM{5jTOT-^y7IRzfn14gDbKqWAwYE&l=6m(KChS9& zW)3(hC$?_xyyp9&b1S`FpoHiO*jTwFp5ZWmlrC^0ieVg%xjkr8!Jf#-3InRyXQXhP zR7iQ%R*{_>maZ0E_Yhl0*WH0!4RzCx0S7`7_=gF_pDy@djWh%}>?CKBjqT+D=fj?txcZQ$a!{+E8}gvm4!4EJ=t z3-;SN50H`Z!U48tPf7KJ{tnOt!zs2~^Z>gW4BeA$QO+@mPAIl9Xr$9A8O#=I=KS?A zYSA{r(BRM9S6d^25Ij3B#De$MB~+fjZliHnX!7m5pJ?4iBpIF@kamB^BJC1XGG+yZX$Q; zy3yXoUf-@hYHs?$s&yw-ovivD8--tno)w8Ee_+y6(hScr|8z=K-4f}`itWmW;Gkk1 zO{@tu{o6w^PGTRId~q?1c)Wy10}0&}UbEsn5#HXDRniDNbUR#1E=uKikZ5%l1c+wf z_4}>V$&qO(ETmB2manjVrjgaj2(2WNAn?dTPGx~Gaa)rtMqms}+Al99Y!;HAucD}k z=(CJg1i*ojpruVHUxm141q+%zY;>GZ^ zxD9TlD;O?Tldk{k5V$3pr!KNFJikP)hD5SqQgoRnfSVAiDrRIVAbhRQxX6&Q?zBz_ zbQal*!rrL`wAp_1W8!y3PS8aOA@wJq2~6Ce>2yi7&0K=g;*M8cN-Op-8aeFd8X^$Vhm}5Q?@L9y;BIZe}nWNxImai1@Q|uqjXf`N`Cp+HNUJ++vJhl}IBMM;u>$;)SQ64qo^CT9O zVFK~&;OuSMEq^y+W!#1DBWToE^YyQW?~3DYU(&wm8wCKWQ*u_~vOD+X=EvI(Hg2n7V8%zP5Z_+x z?B8FCrO-yT_;2{o`we>X`!vcK(?kOGrU+Ohc%CP6CX(6G9@x;kgxPT$ITG-kh`56d z5NQGfi*q{ofCNsh;#YYPjdu9{n_2ZhxuVf&>~AK;k+19ha1yT6PVi^vnEApp-n_P} zeGfAWlYS{Rhy=(c#7k1gM*yaC>ESK0%Yy+?!!!=dz00)JLE~EKL*GV_^~;{E8B(sq z(JA~N9lF&2e@Wo~qyPW|00Yr{&};wz0{{nW)v-;bYh75F;NC<^pZ{==xu()|rhAqA za^lQER7D=Ea2#Fm*)a82$~fB~d^dm5bSk~}t!;i!=h!@|5g_7L66Q9(00-~F)NqDA z3z`77YKy@+Z8h(^hP?i&KBV<2ZX@6ln`Ov$!Wd89Srm#ryy=w`zn=c-)Znxpr?y}q zNsVM5&;V_q;e9L-2Z_;Pw@@k4(loMXj2x?xyAIR3ekkWM{BVGt)Q43%OEbd;7c8T1 z=A1FkfB@-5wSWKs8nU`0-!}DQmW5@AX}00$xeQ_c-hI(dO-H$20kl=?WOXo^Fx{pH zaj}Y8p04obj{cj=2S|Olw;BySbn_+y$lQQ#cXDa-CP5)0`2KsE=ibImQxzT+z7>)43Vlce>r#)Hqq!;k!R~Th? zo82;*@b9)<%Xtc-`GYRXn@zl%gWgw(QH?3{OzTn`hCU>W00_Q@ALJ8LAZP#p0{{R6 z0Py>D(j>FP&-TigDxr%xxvA!sp}6M;cnV8^B!638`2(g*!R17i*WgzB3HYh&XhoS{ zpPof-tH|}j)j3!FbRn!=3@rhabY&;n>=OQYiw^olJ+hKZpKxvl6^wrjFwsGbQw;ox z(k+6DBrMnF3SbaZMe8`VM8jRTyrJGI^DF0#JD(;1%Y!E1me_qG@b+l%jnDH___DWD zoQl{ZzZnKO{ehyU!P+?T%rfY40O(tJlEn()I@xl!J?P6^GrifoO+X!QS@WDEoJy9W znA(Q0{=5jAyLB#uc`lTGX*pxFXbXi0&n2{w znfUEX_UjxJl||7WpqN2cx>adNYEAn8tauyDN^`|hw|$P1{h_2M?yqQVkX zaN7ZK{L6bYC5HrP=yh0~ydna8Gd|1c z^7RzdLcW<^*ij_5WWBG&d`A_TzfQT$EuV5g3$3ioS@sOeiK*~9bCT}*4#r;%?JBYFczekZ z`c7Nw7`I59V!mc=^y|7K8bZ$*JuOcVm)SE(7?fiGwKn9*trl~2`9+ed*cb-qU>M9P) ze6{lgXx9n;$Miypt#x)JmpF2l@bU@%bgkFbA*;JZjj#JrDLHjXVMYTB`qL$^AXKs; zn9=!eM(_(NO`{n29r@n3Hbv4~rpM=Be4Bd_UzJRLB0XW!YFYJ;C&f(SJpUWUK$|A6 z3{;|7A6X<~ZrP&{_%L9;_qL~kHQG}k;^#RuGOza#ik<2n1-ie@6qrmho8&VS7>*HG zPj~IU%W#~pimcR&od5cRaux0!P}hzQ??|L_hdGdJ`dGe5poA@F_+n$9Sb7i+UqMlB zo7RmIDclY16`S;m%|YZzsoguD9LAegt#rdtT*%K;P!F+;M&7Cl-QqfY*r)&z&rdGk z|E9re$Bl@!t+gHdchk_wtC&k2%sqh~2}n>z--_HPUfFnHl<=I7O5$Qf^|gan!Qtly-|g`uNB;brD(aWl2o-jjpI49ohue%F{89`}9i1^svM5$_csBT+RDI8&q! zK)dXgIo+YL@jZkp6%dES`t*7$6b~R~f=0;Iq?nEE`%WGVeFc@>AQh(fjC&pIsOzt> zUCmg-5T*fkc=rS(QK+y|hTLWS)ys(fDM4vi07LmNd{BS@00RI5t46V4xuRWE8<)wF zpiOX0dlOzp8K_T=&)Zi3Twd=}kJ%JbvvOW zM@}|f+1*|Lf)Ck(ls*aa6pi9$(1y)GR8yQ{E?s3pKMnbyS#?QZ z)@WhPC^NmCEL=~KT3&_fTGxdnor>AA#d(mx@Oq&KnfbK5s4ngR;DF2~1P*jGFMTA? zbp46y7&$=24-=Ar_UgG)k4dA1k^5pL_+f;d(HTk}EJ8Uefrv8V(9Fy;)&K667VbnF zJ5be1a^b|urLqE!fi_oELwM>>vE}QmM~2dj;8e1)r7Pw#k*b&T9=Ekd$X4HG**5W) zI2ysIkr*^0&Aw!~g$7|S=~2U1aDK2kO@GqDJDv)kc);KQkz9xH6MD_kDP9mz3aTyC zg750zXkLz*!ne~TvF_4$r5jj7Wdae8VNAdx${yOE1n2WD^_`fgMZ>zP+|FpQtTw$r zN6kx?|Hn#sZ>C}#ygFJt>)GC=@E22^=Q)!>Ey+l6%5Dnsk2KG*Fz~XNeIBSNLmzK? z?A!ub%(|Uyn^rLUM}PnT0{{X^x#e2kkIY_nZ-#CbKsNi+ zQj2<%E(4Ov;tOA@R+(2QzYUvy5Q`_50U|fp212i7IzTPY8`<<<6D=40RJ4ON!z}Ep z3e(IE2@2T*GGUoxodTUY*w%V~n<2q~WNrNShX#wcUepAMiZUsZ@95u?vCt@|4I@+}$N zQn)f=_EjJG*r|*g9o4G9%Pqt%o;;}&fu+*QU{ihjbO*^1`c>?Q>7I@ejJp9LPt=PY zuh`ezT+lGID%A`jF-JwjTH>1lCK*bW4lGNlgSxL^78}i3P6mw89@`rNM{ygODgI_0`#(&2O@X8pQpbhTT!`j?`Vlvjl;}j%dHc zF!bvH0FFsm&;S4f08;%_&yT4ZUdTHvZx{}io#ek_>BZq=P2HJ6yEK^s2)wmqo!DU2 ztf&LQ?aDC0?FNj$qY@!NdlvD=~)(wU)9+9L*V^LOyf_bKQ ziidT?Y>@toOjPqg^ob)l&UHumAxjHslZh00RIb!fjupo?kv{NO-}) zuT8G|P-$jVT+Gy|gK*M^-x(79cAE=)?ig1ho00~C5$$-T=wr&VxAH%w!>dG{W4(!^UzNL;*NDW-jk6h z6nlloLn0GbWCqeBLS@Cdj&Tsf*KkjL+eCo!zf-kQwT-(TWoN9PPEt31v>E?fVypiIW8X~R~Ntl-m`8u`sA$RV_@UaYkbA))E#jH#YD zTZBH#Fp=A*ze29`$Lxd6i~JPMrkbl+AFB8u_fL#rvrqSiyV7H%g5}UMVM3$>*E0t`RNOHRpX5WfWIwyy%W+S3}VpJn(!|4|^ zsxkaf*=#vXoRP%|S^nvYnaR3uiHn{8hD!a|!TI6DtGP4e&SMOwR+aRVd`$yQIK{JC zG?Dq!V#Bx^#LL@3uVow%P7RMUqSeQE-$8KI&ex}}tN>8D<7M#%lkOg{0iM=a000o7 zU`Y@!v_N=bE=lNRw@fb0mEg2S3Qi*@*|6r%c_ez>_;Vjq0cHvpxm%Da9QQNTKvrUO z=bo-No-Ha->aAH?m4w7T_QLb?%bNJI8(|-x%-sF;5@|YA@TMv=-D(??5d`5EPAzjE z&GcBXSR?>L=+xf#4WR7IVaO;_F-6gFQi!fIC`^`CnF+KGXpI=p`fm!3;%Xpb3Rn~V z64sCM2{=D3etN1p9sS~;(zvQmKZEM!6wZ?bqx4s{nytCH^y;Y9(wr_N-b$8miO5dc{qmpr`E(D+4$U7|G0YyK zq7!)d@)(Ks^>{AF6_(aQSJ@lb^9d^dNS(@oWFraC=G8vm!IWv<*YOfNS!*goNh*#720&RAMliHXBuIE z{}U#0x=&Zzbgm<_GZr8Pc!TT9vx&8!0c-+yLhhOPlw!iL+Ni{}BBztwVop_V@c8={ z;rmcn!JlLtSo4-A69=Bw{Xt|~*49RIOFvL`_1cDy%JUC=#r2L&6ly0uKJ@1x^cu$~ ztF3HLWh>ort6hglO7E`jO%luoXncQ~t_*Yd_zGvR4KpkF-KiMkiB>>kkUZJQP~Zk; z{F6Jzi%{Y}4B&hI^$yMal_OF)C9hX6w0pCLRb4}xeK0u+7-ZH@`TPJau%#dX08;$u z!hsI&0zT`$?qi-X6VSIEW^kPrOCJSU+iNx7=V&W8+ zYb$NEF?Ia7j;ZDBHdob;ibfU=r3(moBAqajiqq6Y zcIHR$kz1{NEk)PDpbAa?(Tq-a(^i4AC}fSA=g@4|@c;9PIDwa*@%`a_7BT(kL^i^? zf!a~UeuCrm>ckS4ynrhd^b3;G_v;D8273NWr=%9JqG<79dpPn%i}RS)XvuR zF*A3MV5_EOi?HAb~!_MMU4|HH2s@uhrbd(Vg@l&c#xk z#7ZVRe*p-P_qew91&YaeTqX4B+&>HE3f;-$urSa2`)NmKUnRXyjah!BLtERM6MJnQ zDZ|KfM=nBJ{IPI+=Y%3Md4|b%_00Oby=4>Jjr$B{~zXrMwUXj^gy#7VkmJwV(&XTu;3qbT`D)C5dFre9U)pmPbl+>ICE1765 z;L4%K5guLnQI|}2WiuNP4r>3t$sF5OA^#di)u%PelVUpb2mE>=mU=ju|NO-0|SNl zU=Wol>@G^mQEaL(T+}MdC;Rnr)sq*lro#}*vmRS%=^YdYOA3ltGJTC4I{U8J5v;1br^oH$8QFllE*VV86~6guqpn7!$f%%RTaR&>y;Ustf& znv};s;|ckt1sa|`Z^ShzxF*=YSeGBE39uWDT@?5KaNQdA8x4x6aTN`o6}e|e5gtj0M6cLp<>UtWn&cdV3O2>Od`@r%@A9gu z;2D7W(FhsVH8N%hX0(T;(foq5C$t*oNF=CIB~uJEd_KqPrbJ}>X8`olvRC)dY zRz;t>e%+%AJO0QaHHA0OIQN zk^2lHadQK1VtBT(_Sn~|9tMzP;TntfI8Dxfjb@4P`&C)N)V{Zv6fyys_6;w#JfEhd zm#Q9W2K{Gtl7}3L==?d1rDXatHGzf#kPv`+OyuDe$Lb050o?xo zB2{&f{aYzZxE|3f{WA2_`)E$@?Bb6oztVqxKld(r-2b5c(yEd|(ykSf$%>SXylKYM zLGP%*l4^K|z*ZbfwuEa#d)J@P=KEtV29;TZHPJJ?CFNK{Q6f-*EHwASLkqOusNU8x z-)Oa{^8SXB0cg4F1uASHKiBG*3(aD*6>%>tu(3}?<&b83^z#IN$OG0%Zqgp1mMqrD-rR zyf$okgm%>oOYQHxo~2Ew1m}z_XK-O!;<|Q+>rrx8RjJzAGBmtVPgO~jpkJ#x3gNE$ zD!=K9pHDTz1Tu&qG?I>56pfb>vA}|%M-#Vx%6isb_K{=*prZ!5OVX1sG$a?$m*Gd# zi&T0d_viDfh$3x{sONfI4jO^4PC}<&I6^Z~L1DyZq^63RvRcqQl$b^3(2b z?RAqy+mHnouRNd(_URA+OGcihEua7Z0{{R613Qo2hfBYRsWi2Kq3*{FP*Wb=>|l<< zN0qLG29_QUleP{gpJ}<;DgkxCis)yIelUkAwSXmOIaKsZtq{!o@K|L<$pS?WWA&Cf z2nBNK4TmcO;thJhNhImIzFe>7@XxjsN2G}~Zb`oZxsAs@IPM+8Cuu^<&Q*cF^U6L*yFh7x z(DODB0vvhmILZpI5mImD95fH5cN)QYL#7Tex?j;qz%a8yJ^8!dBCY3)EA@c_my%Z` zDPw!#00Y|v03#1W(PHE;S6bE4@oVS|{=Z&jNB{&rCqw5MIizLo6~9qe@R+Dh(iCvbZ(eQQSpaJSLpH8H&)EJDSJagjIaM-u!KcjSeAz+!@y>z~Z(l%E-X~Yc`N6iF zS99n;e4&HQ@tE_1cuktJ?&PKkSbJtSPj+1`WPPf z0h+_ApE(&ru~x&(aX{y6D%)3+HG^85(aviiWvch}*4AW??a|XYXz$Fm>gpSkPUqvQ zPCN{|VMBMCwEifC#A$of5@Z7rraB$ZshMXh8WF`~YxUc`U;{>I{|$Xj)N>@f_H zXT3PWCV$z=W#jqs5k$%V^;IFBLk8EoB<#c=-`;B=@y}_ z7VQ7)_#gtA6obV8q)+b?2aw0wjU`1diPf;~qESuICy8>49>|^O^ciDxjWC{@+rkdE z_?oxu&6Dc|&Y5E?r5xSr*hwum;HJBEj}DxTir{P<^nM@gzK3aG`EzE|duxZYII6AY zvf4XjSkEt?-~=}a(2I1=6kQ=?{|M)^dZnHOlYlecfw;}?{>m&^wuNWGBw3A2S~m7 zQl_45&GRM1JT8-avP1dbq=^0?083G`zyJUP07CzN^?rit6-ywutSeFnzK2V$BR!Ru z93v{6)S=@_qHyLZ4-yscG zph)$8@(gw?|6RgSgAXo_#)wm_xH`c$P*az}arq&z;xZW~^goBU-7kgIDB;%9nNEdh z8IMLf?O$vEvX^)}D6&)yvrx%j`r z*mv_xrw=ZlNx9Kb*S$YCShqy}%8d5wIhkvjLC4iX?F@O=bFNPcalHM#&kY#+7rISU zixx-iR5y#Gdp-o?4BrLu+cUBb9Ui+sT(7XvwlF0g2aA#s(zd5h9{w1xXPi^03U8<^ zV@P;`e48GO_E{;R=h8W6@`=Es{JHv0`b`4Xxu{>4FLK~AWZmcC9E5?(_O5tkR0|iQd6vd>l+5h{%rS3&qU$h!C<5`U`HWOo zPf`=%?|rYKxC~KPiU!onA9c1{pXb)xZz9ZERAU``37)2#tgtCfcJX#7fWt^_gUllm z15i*EU6$R-V5;sfrAfUC6XD#t1d>>CtV(cNYtE%?Wp5;p6I7u+qjvp zp9g!An-f7X*e;;ZGlv(gkQ_$p#vasWy%+jmfBG!+htd2{!tLr+9o>7j%5Ls05^fsq zN5#$Z2sZ(o)BRk9L67QJjri3}iu)@KPgeD&wLZraV>^AS(Vxepxh{&Abzk&$*5YdsAjrt`Dzh zw-(mdZvNa9n;*-GciHa`-__mirM<0SZwmW#A4Clq>CxkMcxbwi*_@ny{;1Io*2h|C zJrr$h#kWA;6#B=6Z`KvG|5zAU_IZCR=`6tMI%%U3qLE8!9PY zpsmy(k3k1)b(LP`5FIar7*07P_5`^oUh*{L)+=Z5Iw?amLES-}XV&qSUV}@tHAdp@ z=_gf*j?>T5KR2KC=V*n|*Q`wt5JVbf^VP=Oxg9c;<1`)Uy327x z?e;A&-xWxL!NoIP1~GY{ZycM$!TcOyi_jNcknAJ6gk-Hlwqz@)-6Kf%BCKXlDanrU z7rOv4Byag8dECoGYcC(Hog>Y1*KG?&NAli^*FwK>*0>q7HTJQ_CwK&X`q~rg><||F zGRfy~v?Sm8Ns`wr07!b~Kc0c}yN;B4Hb3hoq8|7nH&6k5bve-Gtg1&K?zRFN@s4y3 z2if3n0`Fnq8iIFqp{6JULA1={YY5xaJq%` zRTC$Q4K?+pneyBG66N~ksI{y9O|rFa^y}A?>=IvwM;XiM1&;B|j_+kDqX^U$vcu58`D-ZITQ03qG=om_e`+C8(oM&_!SuTN<*|meVpm9#r29F^F zTgE73L<#`}mf-^ch+KN2jypV-bkjGqah;SRz)J3i$!E8`YJD9bUcCdCdowG|faR)8 zJJ@!CpQc$Ur7oXMrOp$+o?{$q_>xD6Vl5iQEjbl6>$dojgqyJSQC(6?sjM8dE6}C!bA^qqQYvC6SXRekR-XNnWGD4saq!8{#YSfqq4yF z`i62D1bSs}(Q;?u%{7BAQFYC~je(o7akNvI9~;XQ@M@htX~szeQb`h-Xke<~^30{? z?Jh^{`o0DBG~!p#&o{~O`*qq;Pm)foX6`BAhk0^*A0^M6~%dt9q%yXcQrC6uFQgk zB?&T~mg_9FQD3Z<9=A8*oU{n%x(LtB4bNpGHsHmWAYFNq%%R#4#!)El`)&hd-XjQ~ zlMpq55LxQ0lHu2M>*v35`qqi2L?9_Ly0@ZI^Qu;Ept(1#-CEv%59ttMe<;04vbpmT zF@>!~UkN3L$^R5QkE-^BL%y3B@k?_AeT3pmq{&#WL4Z)1wYccCy=46c^cjTF^C*JO zu9838x!^FGIjWV!zomN#ulgT_b}g~0W5}7)fQfgce_iBe^Dg{_iL=HxpeFd3VYIevjejSh(*^w?RQ4Ew35zJLzsGn1WBLDj7Dti*y+(7Oy#qiDk ze7I9!WAk zUM(a-&<(K*`ACB)Z95_=%r8QvD%!{5-Spv#Nk9eM{Qv+10028p%)z!Y!LoVeP8oz~ z&!5f%7gB>xQ;7@`zTd$B$-LK{{~U|DPt?0VnG}!PVBMAIQri4a{rFyDoUJP%5SX#rdM|O>?rBp{b_g zZ9Ff3DD?PLmV^f>dK5LjjV@#y)=~|&3u%(DrrWi`DOfp@c^#6Eh}+G<%m(QtwQ2`k z=T3M+v8c)Ex=&}FJ`1b725fNLT}E~O)wCQ;S?>#^CH`*0Y1xk}e_t*#g(&xyL;n*W zz53oyo1cl8W*1M1h^$geYNkP?J7_Euv`<;@%_U#yT`R*vd_IPD0)B@`%wXfo3hd}s zRnv8Pt1yB7_0qj%7WHNe?AlFwX=n)h?q4MsThE>hL9LkB;TbN2i*Owt+@1__Q0bBf zwgqp=iv%Cc%_V78UuANxvs?;O9NL4QnWpB=xAC;16XD~skX=a^D<{NZu0)OLm-Inf z>A5$1$ZqLTAXk=VXAfi_22t?%Ze8kErnBkb>_oBLZ)Oaz6{MQ?y>W(-ichlT4!Z+K z6l=R^dGPUa9RD22jpnM3RlM&$buvp0!s@S1Rj#pDo`9hyRCbrd1{ z`MkQ-6{zsxbmilt&;MhyPHcS6c%Rw9vX-AP3(>7+A6r_AM=8o=FaiBMoxGRr~opsb07N=!* zXHwcbGNLx^2>W>j0p5d4qb;jHSu{=-j8A#BM&q(P4L*JJpTXa?fxWFv{tTm=>^ix( z@}jGv9d3o5d4@9EacZg6oHMVaSo`3LJ*zNBTl8Z{S~RI(l~2`bXHwNjP#r!g==1Z} zU||C@-0@=(3+fx-KP)>z*&`Jlm)~(zKi5dKeUCn(*!eior_byhxoX07O7yc%9`qdc z{>Q%GgC+KG4+gB)UHWZ62DvLk2$Ljx=Yoh#1ppTZbGVWslGUWw5Z_-tdr-{A9iKRZ zyW&Q)*qK{dmz)m5tiyEsmtCAsK9rtC?ImolA2BmRIvNT={Y7;4sPz{Y*}+97mR7j| zl1UJv$8-@1U)XwKQ6E;h}2TiUxz?^aUQAM?E!DrGAG8$)!#vE(hA;}qFyLU0gi z2?~d_!bN!ckhv^>6gpQU0+eaW2e10DXp7s^0zfswQ2(rdYV!@>R9|g3fVR?@wSbaO zCcW=8J{Q>$M=Kq>7<)C0009304_I&72eVp z29e7wp7Ox-RQ@8hxO@V-|6V%SDAL7n+Ap`Op6Sm2&Vm0GFGB%65XR0zYPjfUL)uvY zTs{D_fYD#dqtNG_lf!|4w(8T?BSxdjtljo`j6+6Q)7Am=`~C*2T#50E7TkVLK9B?s5~;hEK_{5m*ET zbPRCpaJa4?>9aF=iW1IIcBXm7U5D096u>oX;~=KIPahT0hKo*Y1+JHYV>IJ!eV?IgqTEK||EDd-xH58t{UG7mg>&yBM8`oP{3k{^wBGkhG z;vEOSU3~IplxynkONEx6$1nea1NxC$FJW@^@fnR%Pot<^KQ0}(a$j`N2G0LnV(_1Q(9eX+wgdeDb%`GxXIhbtg|j#@h%3u!5RnLk98CeRfzS}z{1falmq$Ys; zOX72U;z2*%LSNUxX}FN@CHWKb=Lf$%^K{+#Ps_73A`%oNIZ)qfS-XCB!vA-~U@hDV z5DH|bkQ{aroB`-cYR6HtAT8x+r@<4z@Lvt>v%LKJp}elK{1SNCGl(MGaU>f=(E@Jq zY6verA|A%tK|`?(WqyYJ)CfY4e^{5T72EC@ThVDIK(_(%cmj;>r^of4l4A;cdM~P* z0|7q%F1U4~v)Gc0^AP=f=4O$yOUZS!ii9ZAZqZMa54k60R)OH|hm7=YiAG%}JkN&! zmN*XeOn0C+RCc?jB)ihG&SHX^i}(gBhb1!&XIVucn3ow&k-#{>{imdH$c+pWYe5F& zV6<_Y>-n0CD6~@;xA+Jp#mqUT7htRY#VB6D;@h#C$Ze|n`_$p?52QB9D8w0CVu!DT z9nm@Ij$5>pioYSvDs29;t1+H8;rjdykVuewYFu11M_nF$gI!n1%x$d`4ZbcB#Sx%m=4F~%h_jP zF1rtiqDCYT*Ww^w91@xp>eI7T47JMY`;p}yCpp53$lijz`!p2a1FaZ`Cp{+QdJ8{o z%pg$-)p@>YTi@PbGYS>dnM7|P`Cm3SA!A!nYyaM0N0VG{#uPUI_1(m$c%Ut+?=4+W zm3vzSOp%1o?N=Y5pD&XpMD8bQTVbDHB~kv#>#ANKKda%cf|jp0VqHjcJ>9=WaA5&E zMB>*l{>M2Cqo0Vg8lZ5+Yfw&RK#UKK%C#`GN{|3*K$XAD<2w=P_1WAhO9O>;7Uz0{ zg>d7*byZI~=6>S3e^8P>aWVxVc4(=CJ;HO&tzSIr<{Lm%C_8M*EmR`gF?z2`1%bU1 zq(6G=)Uy^K-jU*sKw z>8!+%nu=+rbOYJkr-yq_vXJ`Vc3?1)^{rf*McONQNkytriyop|uV2$1H2Xx{kPi|& z3Us|^STub&Y?a{@{nl9SmE6&0V6}VcDrLI10F&WVdd+ndhj_zWcIN+>$N+!SL6Bg* zK>qHUIYGa(+=S%;3dW3s@)l)YU1mhl4G);P#5}yw(MlLgRW6toYbByk&6gn}Vh@uQ z@h8`u_$T5oPPte&sSc{YKb%~a9-cd`OBec9xYY-Tgi|R!IX@6j-9L0^_%Ya>7q97y zz_PkF?tx2Ej(~ZmbB4pX?IfXVFA6qIxwLkDP)G1Jr8icx*JzRd7tr_pFJbQZN#-Tr zbnv~?wVWW?mm*&c=k=$wan-|P6#Y|j_}lX|*v%Q6q)u8IT(ex-b-}~Yw$K0o0{{WC z+259^A+m*Dw6e#9a3zlhWuH)uf|{J%#iLT$23nqf|3|jyG=?Sqmg=5>zJKDP9K_!$ zw$+>N;*UWqP^9kii>KC=+K48F!xllhvz_JCdaNZ5FpDQ{pQY=T^74Q}6kZu~*`D>G zrdP*WH_&X}tQs;Z2HD;a&g&dZxn=B7Zq#Y9+4+7VWSi{J-Vh~FRS%x$AC4paB|%A#HaMIOF}7z$NY1@J|xuEtisM>q}x&I<_BP7)2GEg0 zDryfks+%*%JsoPn25L4=Uxh{fXpWGIr6YmyITcin<~tERSoY5ve4zBVOk`q3>SDuE z;ick*K_UuNo_C1`sr(e^*MGjJZz*o?zjgF%e+X?SIVrC?WW&|{@DTXVm_H11j?ivJ zkz@2h7syBd9xYgUX5`5D(I5N`!45aYbt@<(xQ7@`=zpR^!epa=Z%ub;!vRNFnjh;28IWR=ayWKHS;B|69w~ zWf6s*n0bGU?m$o0DyDyqq{Z)k)#Y&vhr~Q9iV64`x^{;xSvxX-NN}!RMQ2NtgM4^d zI{jiy=MSLrv`!W1C(8xFm0)Hfu#AlSojs*`j-~=L_pp6w3SF_9<0Z$v8dQRe88AT` zA)B-23kq=oHQV_f_K*l0cq{sZd`xAmpjnjAR!og<_0hsFPF_7P@dnEq{4kwlKu_HT z2Kll%-X?C__5+6C&*UW)lCWp{C)=n^642DJ_fRptEN$al1+zi*`c=7{8xyyyB4x7^ zT(_ODcU_#rWPZosya_4}=kNcnCNxf&6BCAenr--l`1o}2h5T!bJhZb%KVsU@5(PiN znttcnx`a*fixbia$CG?bOe7QEwfQt+5`?qFgG^sN*s$Yfq~4m*lF2uAf3|d9l|f~U zKZk*X8zM_jJu#m}6-Fv1tcN0Y`fcfw!dwB&-sP{SR;T=F7CSRajMjI1I`bBZ=biLt zfuYUF4xee5lVVNyN;^BQR<|PXDW`9I*mwIhe_f@l9)_CcE%?0R<>(cJn!jahZ8fcI zQkQ8M6}%KvVFMfa%jOrKD;$o)LI`vjG!7rCco=?^AL9n{5_MXiE@Rs(>Md^vk+I+M z3ypYS3{u_7)2fZ;&LN_lWI%xGU+T_P!v?FPx(kY@(c4o-5D07%%uWcdyM;I0_J{gu zA?Po<7rX=$0F@|g$)G^|*r*?!mXBqMoy}+1#u_~|SVMYhl{AiQfEAnU@496dZ2|c~ zAo)@9&P$_o>$^Wl^U@&zFX2^cU@h+M3P|PHakF3m0D=<$jj* z|6b*|BBzs7r^ajiu?wY64IFa_Hn@!?5-M>HTwdpXNv%jG(;w6ES>0~1{0uI z|Esb2`v)k~h5N}M)<_!17YIzyCQOp&_(ORIZ=4ielIOA9=xfa-0U z>90`BnVxVv+#R0Nb*zex<73*h%V&4x30<7a3oMof0xNu&jC(t!lPxkG2F4PyD-F2KWtb!l zZ}7wm6c5Sj#w8B}jv256EUQv%J!GqPr)~oNg$AsU*(6ik*)S@Tc!$hk=p<4en`lk^ zOF&k5;5V;6F@e^1{?(V=ZDCw^S3mo6lGs<1@Z>A;Tv45lBBQ4&Vud6|Aq83m-y5q z@X+;@+~$nt?JtNR^DfBjaN@1^Fy8EppHy1uGPtZxfvrY4u@4*)slh5yf1tU&WmINZ zZBPWyFUZZ8m)#vc<3+!r95;j|YffW$V-~3PJg|v`T^#UZ=(Yfo8lIz=$p};2=f(-X z9;exXTcGV>2iQNddot8H7m66bFsl5sD^^!0F@Q=Sn?uAJnt0n^>t zHXB^IV96d}6_Nsv3FNPZ!HVNG-vC%;9e2dBp~w<_ZQ1<~^C3HlR)kTZJ?rxrz9Lb?FX5b*XaC5$x1T~ri1_h0|U|h73e3H zoFjtusDNFCv(*`^y{wb=sdOe_X(POCdjeq2YLz4~WVz#Bvmr25QrPHI`~el+A3tVk zEai)*m93oRaP+!Uy}HFk-{RW(2ZDy)dk8NK{K_wX%Tk zi#g!S=#yd_aGHboUxJdA#FUxq={eyzrIu6|xao&xDjfKLoxwIXa0O@{i}bq-e9Oj+ zv#xyX;MS`IH0eU#-M;{3B)XRMPUz+x!JE1a7W&y?;$s;1$T zU?B&>RvexOF{1)$8Tlb4(J=2Qd2^z-NxJJrL{OudzSyz}%z;1X8~qy(O0<#R%0j*2 zPOwI*2hXeGYk~8f8e)=+Y4R$~ zcADL@?L0-OMHoz~mZm@Z$^8a&%%YAWWwv=a4ycRD)-SSk%CuxjmL%-n1Cr@|D6Cp( z+0P*rk>@-WFT2|(pG3}BYUY+oNC6$VQk6@Mm=!bH{K@vo3TG!w$BOOZD}!RMNID)2 z;~wa~KY+>4^qHMX)Jq1ysp`KQVh@;!Uw@j5+F=DkI=&X=P`{`P4W>I715M?ydW8XE_s&n`x`{dv5jNU(u}teW7^f2 z^c9*DAgVcqXeO}IDD|WL=JQKl)GhbbQ9v#c6&n6Nns;?&BF)rsUuy+-26SLI@%<$A z9oc}Y{geDLT5ef%bn*N~fF6p|C9*V2t^|fbYZF_fki2Tk{k^4R3#TSyoN#hRBznk8 z_G&-8Bo{k;q@CIabw@@|Ra(HE_OYQsmxWzB#8K?iY>#MM8#g^6>VZ+}7f z^B%%G^nqCp=V~lP`PaZErdqaBJh-+)W4!<{;dDz!B0erw6yn+C1Euv*uEORzc;koY zp?Y6}3x=rjHygPj?5qkvm!7hGiF3+*)oX0s<{I|9{y3_kU0>vFuzp(KFoz-}YASH? z<^n%iqYRlhVZ(OdRFETlo2WpO98XS&_4g(bVnI17SGffn?_A{usM)+}6x?lsUEGmh zHeUZ|=)75>cZEzmrPY3`7oOk6d_Hi0sViR}87{ZYj;0!SOcNm-(3HSkmt7dtI3PF| z1n;quNvW&U!2h4Ngx}BIhc~W?1zZ562t#l^^^6BZ-M(h_)!B#Uz^?bQ;y>pM36_Fq zEPbX6e__KtEDtRCP6)CR3zjrIj-H!V5%^+ z7LT|4C>3tuw9z4js3r3FI-k~T>`6}5RdSoq1Y?Fvd|_egC=*=M0kM%aNWhjc$R-X4 zDCWAP+(D~+6exnYUc@a|ia`P7la+%w!wjB2V9s%X%9De0=%sNKd#{Z%y65Dcpmy`rToL&6hx-8db7ddo2b>LQAFPh6`8M zJvbI?k5LW&kK-OV4cZe99`L^xpjn{oA6rf8e{!kMVEhM{U)#dkKjI(&00RN$^mzMP z6y9~wzboE~yM}0IDLFD%pP49d4R_VtS;GtjXe-*G)FMLndTFA`?L*q_M%^l_1&EXw z=7734Bq!nMY}5Mcl8oar3DC!N?|><6jUt9eAmsvVC`A}ZzNFYMOVwrHqkV+KKl!tk zUP2)U=Z#69XrtOO(=-^=TOk1cRK3^qjN#3keDp?|R14tEnb|5cKNv18$xTaht0yRu z^*hVb#*YiF3@~-=gq+}3m_O^Gz-JB=)f%ILn(wRB}f== zICn{Qc5F4(CNot{>nmsl$7pG;x7l-`Pz<1`=1yJaqZa%MAOHXZ000_)Na5AJq68At z2x?abZCTB3t6-4>lNURxgObBMqjgpG#mEQA{o?3&f3V|I3~rB!NB(=ux68zwavs6H zJ9JFn3dVH3!~;ejTIl->Nq>BkmPg`|SnIJk&wk<;m`OzNY_&SX#;iBMXN63vTMDcn zi!64Xl&-6srQnIk0Ys3t<>N3=aCd+>(_mfYBRq8)oyNV3#E~h_pJ;J3BB>0&=~r9S z!Jr~DAgXFAWXwiNK$^%hG-7o949~+Bmr)p^+y&i1N<{{5ParwN{QEp_lujNkA2$r#*~**=2K3We^BpqHj*0sR-Zn)J5~*?Do@=@4~1 zQa^zL+5NhTu-l_yC;S8Fy0fnLe7bvM9#D@dVe5&6hhsvx5(U(XVlTxD|mC5NkZGV~M_^7zFX(w#o&IBHu0I|g6$jvi9dtO8G1$8Q=YtpdpDJrS0{84yQZSWK1gTha}F z4-9iieaS0GP^h?73ljhtGSHMTvwP9#a?wTJ6XnoOY@fFMG zo!7EC5z`R191PfgX5T6&xc|iZ$X7(JSHo4FRkh`NZ)8pqDYID{1e!eAs|Hq$51tt1 zED5wL*mYuFJhxD!^D3o{!PJSA+ZIwUF-?3slppKz|9x!^wYG-=(yG^ZiZg!gaDE2( zz77(zHwP(sl46hNF{WG4Alf4v_N*+Ki~^Oa2#@#(m_l&>wcBq%jYVVs!w}uA7~k`l*zIW(3MZ5O*~gCcd*O1_gaby{a;qT#8ZSOQ(yP7t7@C3q)g`BJ6DuA->z6Y zJDhu52u_^^h5419EI*-v3(7?Bxl$(s_{+||c<66-^NwvBDHqb2?V`O+?v9X&t3iDy z(?}ubswWVoa&YC?vlI?M=}RS45Pgl_%aQ|YYyLD;hk61$RG13)NUu+x(j$ZMq)^lAK}&ZwPcekP@NXl(6+oxGahL#}+sh55 z@C01X8QJ*PLlM}7tgqo{=H>2QPF8e4MlXQlvDumlK>2}hMJy-jlLPZNb%1OW_*fj1 z9#j=pBpe{0ZqQOi z`kR{kxg`b^(KT1u<{z{QEAASeQ6b|g4YJOs_HusHXeIsR-wSr(Lq^YoDf(Py0tJZA z4oltHdTZt_&DFp_LO)^{w6ki5If!V5)cpRdC250kU6TOKXYeN0i_SZKQ=Z$E3FgVv9esb9UjKW1&##$`-QR~|L ztMqbIAm^UTFZ{C#lz+R)Q$c}Z=(nd&n=xr4aV;KWI}ZH-00RI30{{@bmRmB}RQXa2 zfH{$oN)Z;qMME|ABXZz&d3cj+qpHR6X7D~S$d+D8kz__|I7FfE@HmN_m|00094H%w520?bVxGUxyao7|J8{_p?*0|C}St)nPt zq$SXU=BM4C9!`DA8>OduFNHmq;W^bg>7oOzZwXGn(RpwScP58!g;?p; z2qrxrg{a4lki)Nyb4H)_R+W*0)fZpi-WV*8=;S!=&l^Q+mX%~e+ZD1GU9GqliuLph zNM`G%ZS^G2Mfit`d_GKkaL5g$O;G}XIfK=Tr39WB)4H4#e%Bo#y{_m zEm+nFI~I--Vh;&`KLn~BhckM3@*I`NVN%sz#|^;3c5Jr&AH5n- zadgWo(J;#$m8l8&=yR0_rs%CwYL(*nkLSlJ@{uzVV$r5_rWW1+eDB~3+ukJW<&Qdh z(9ptShqDP#W6=VDc|8hBh8SOIX-RpOpWO6}JxZAdUrL|a;=n}S0P>51=(SN`i#z&| z;qIq{)Nb8^9)t$E-%P^h(cnfjM7jeMEY$#4i=x3=#Vzy=_9a?yD6wzC zV!VL|=dA>J@!uh5V&wygfsNXU4LQ!vu0rkRsx?$HabL6=p9B}Y(_Bek{{BBe7qT@^ z&(}2F@Uw{*;$?ALx81Z#@`nnGTvJQ+3?bmfZRR614Jyd6p)QZ?>R*4IZ3ol!s2Q^D zm*_Cz5B<~m^KvNrz#PEBQ)k&VZIvs*9EO zd2&nvFIv#ociZxowiZGz_NhKfgc?Pql>Gt(LDt;s?cObGgAy>K`xHF8qqr`-I&I=; z%Gue`rJ?tz(~8e1_7`7G)md?h-%$^@z5Z!iYviodJma*v-24t43>xLY3O%0Z!CM=C z^dvU+)O0VxSXC!@)dvd7V5$pa_VIkH=>hLN^f|a`w;R5wG!(+8qwNE~w&lC*7m7K= z*L>?aj>!kJ{X#;K>Y!&|!4`-pRIAL=e}wQ5Xgl0sbJiP+6NCIupG7$mG-?)CRuU@^ zDf9m!NP;8tiIdmOTh`5d8sNDkY6YwoYyb&@z?BMsy~xcDf-nTAfqgP#J#v9ciV32ebSYG=M|02`}#NY;urlo%X-O@sJNMVjpYw41d&8X_x}S z*$uhUgtO!_M8SXi{UQ#-1Vg5Q96!CGSa_2ooOr5e>Qp?}N%2rpZqOxMc@GPX+Aqmh zCoTZfAnn4_p4=bpIoqg^7i?rFF$=<+8&M*kp_20sl|2;@Rwqsz6i8B}(@0{vu54}k zm0B=60+1gRB!PU0EzkO4Ykte_!w`={R14%*S$PXKe%SPNx?e=0G%|or+mBhA zyT;{fTHviVl=~%=jAjEvjLH=H4Zg3ri5x3LD~lx1P}Qk!0Bym#KTj>KV#pV1Gvfc{ zjqbmt>>nN=ql9dU z>$XW+AsiGEk-uBrnO*ZH^irrhK>cM?(rz}C z)rjKiw^d%Bw&4O&`?dKc90RTtfDYJO2^E&q19PK3nPq`XbyeZDz^P5E5|`??l~tIkR!iI!QP-9)C7)mGMO;DOnegiIJ7OmfKQN- z^2X+|3?&)`$Gd+JU}_`5S$SGHj94VS(qM$Ff_M5Eb0i7eKQ)fV^&9Q`E^6F>Zm98~ zS>_FCKPgYM$p$awsPQ=$&6d{IpWJU89>jfk7h#Y=W;K ze@Cg!?Zm-aMP_kDvSKl)3WnFudsH3Xpp~MDWA|QNcVo1mUQhhxiaxaJi{w{Mdl@g> zK1snV0>9&~)H;2OBFhb6t%fceO6@=L7`F|8yX@wUwYr}n{lI@r;(7vo3Z+0$GNxF>Z5<;>|R>?kViB`}0 zFVfL4@YCzE>%9*f17xBc@n1g#9IW=%FMo59=xjcJtG~Z_W{CJYjlci^ksRd1 zPq`wD2`UwiyIAC!flE$5z*OUn4Pq7FA9!p*#sAy26Mv>NcOW+9l0;UCbs@KxLHq?l z1Ef5O_^M*xN^6H-o0@SO!v9aXD8N}k; z{SQ7-7%+usL}>t0`?A0wUSW-R$Np^&FK6zfOi_h!B`hTA?Co%T&QdbCtdMXJKsiF~F=z^}N)8r6C ztmF#>Ik(zm0o0&%?pqN3$V_o`KkvP9o&e;fH(`r^w&;#qCL12O4Yy5z^YwY&*eFD% z&b;1M*zsEs>KVhKEfe%w9qT=WAk4FXaLe7Z1`l!zUaZ1(KliK@Rx|%j200_0Bj_`EzS)h`{6FynL8ej#*h||yc zjTHs*$9v(qnQ4w6RkhM1cxK-=!i?`K;ne03uZun5U&8c0BhinvXV&zo@ro-ZMw!l<0aB9`*js0@D2Zji=2QV^Ns*=ch8KhvsAt zLk|2!^Ah{IrkZP(0G<)2GxhCqjBb;!M_0X65W3k)rO^j2zuqgcg$24IYGU~7gnPVA z|5%9ht@H+8uCuh9DO|SibjhIkp>i<@;@I`;HQ7iEiBP|VK32Uj+21Uq#SC>Jyhrr- zM&=Q8*F!2@(ISRof%=<4V$!dQ6&S5f{9zXtoQPcx9o7t^9VE-zFZ!X=>}Cb32khw~O_65CxGuLq2FQd|yt=O`p#jSi69tv6#E5G&P- z_M2syHH_BS(%|i1&+61zphDg5ub_h!{lM(CC9;iPqMSa_OTp($W+S5;r8AC#5lw3N zs2AJlZLWb!?mtL=>Cv_M-L#h%+}wg;DGBuKTmn&(eD5G&jwz~94s-;Z|0syUmN~-QIbS; zZW0$C?SUvuKCj{&GIAHU7f&b314XIwFMUwT;NxU|<`sCujey? zWV3VNP_AV7M%amcjeB+U0p_iK-P4ff2Soz%}3+CN&-k&H<=v z(Qqi?Yze{(+jfC}@KtV9n8^c(r?xMASo-Hx_dvl~?U;siA zIP!U1*lB*9D5p;Pmb+!AUk1hT3WeG>l_~wmQ5x`s>YBO(|MfM7g`?MaO_u98M(0E3+ zga&0wgDzBRWN)qIN{A*Js~s2=5GdbrqyUK4fqlM+XY>Obs=;9bDmd^Apu9OwG@Ski zOKRO5*1LNubj=6+eIeU^A4n&lF4DlejK;@L!#!|AW(fN`v1dAWklv-11K-CGBPx!* zj33`BlS=t zbq9%hixm*Ab;xH)CwlqLIv0UkJ~DfWDsnKH?&nJ=15j=C-aHUNBEJ`4h2&-!oIuLs zYRL}vD>OV2KZI&s_OVqI+{SHi7P#f-zYe$nnJEzmoZKLw00093GCvO=MOztu4ZLXA zG+iF(FMQO7LvTF3OzU~LoAj$GGvz!?pUx0AhG`E4iZUr4gm$K-x9DCWV1g_5IR?oC zuxgTat80XyuzUrvu{nv%Z@`eU(vbh$yg}cmLlzTYgt@oF*Jfd4tkfaTuM9QsNhuO` z>fMq}L``|*Vy@0VFPp=t@fs`*yiueciC778)ILc6lE}2UDss>{?Sq;<_>h1X%xTUi{dxv_0Kv>cWE~i?o_ILk@0#)p zuVsRW67o904O)Ka<;2Ws5n(!QNB`+S_iiXO zwm5p#b#Lx3Fsx`jl?UiSN^SM(3I`95$3D9>I>G8X$;k%Vtj}o3Sa(zXq`k4rC`M)# zA#hsZ3sD;G-3+?_*oQo0ivfi-tZ%(a#u;GbWa9Q(=W?i~LBPYh)flL3ziSRVJ-v|y zWl@A}&}9=HTk$5mPASll!|uup_Ms<^7^W6IngyZ%KR9b}%P4evMs5Mq&3<&Ie!vh! z)%oI0sH5d8WVAST}E~7IaIz35?M!JU;h?8j7^BHcG_%x>HiTh3+=-d(y|4wTNtL4=rSfNu0ylAgB=z0F?nq)0^-aSOY%M71 z)N_)H(>`_|KN-E5TlvST5HV*_f%bP+PUr0GCnOjN6Bn(5lrK2}RWDyi$JGhUU~4S> zG~@p}bxVBJ-A)b}pu;59 z!5cY}$?b0OC(R{E^@LjC6rfGV5&O+_>Z6mPCy)%R5SkJoyPM?)>>Mz~X8eetQx2>w z5%O}_PE|mfIO69WC9rx*UcVu_pq&TMMq)qR;8C`xRC;?fae~aOSh;2?C>i5bL4;>} zYA3Rr68iq6BlNj}qn@Ki4x*`r=WDNMa+yxC1#5JBldSTaO_y0=c=ku|lkY%7;tt7q z0IH9S7b!Qno(*azCBOwtwJ6gY-M>5J2^wFL{n)UKMyUJ{W66p_%4IN&34)`y(KqVt@C zVu4$D%D1oubvJeseE@CKD*h|UVXsO&<=^mCh2D^SsgsYt>S0h+OD2S3Qz^Fy_idKz z{kr-9jQJ40mi@X%$0T}rZtqF1@2E z(a~m7x%|9fe8^2x`ktK{w_V9i(#BVtbd~d5Q=J;dqg*8Dm%qoNl82MNO^95%LZ}{_ z*APIX?A6+pYr-9bV449#;P1{HguQLK8oAdlfoL@3U3&oFsJ)7>&*#p~;$E8P4$A}l ztNB)h&7(XV)p)5Y2!{bAAJj8ulp75Q?e(lXh4MdH5pN zGvBUCDZi3RlZlobu&!~A=?BYMHT*bZln`3FilPBn?67!PO!?$WmL>hgsm;@peB373 z;xh|5w3)`1@RzbZ*jz!>>a{l4`9h_5e1g_H|L%@ps5U)>LsbSrl6s8w6|eS8iuE2% z5^HQ>g@F$rZ9z+FU+O$~!<~>ZcPCkr-Da4o+Gl@cb4vDcv$$iMg&HwKN@*Kv<@x7! z8lb{wBUi7+1f^Z>mOTyq+ZC!+o0nz0x)vKDJ;%-iIVRM$Rdi}P0V%FdTjC-bHVgtf zN>VZw)yGD9bWMrD=dFpS#T8K?z_h6q(3=mz=>(8C>$;FhP^fg}7r8BYsp3ROb6|SP zmr14EdT}9oOgh0Uuh=eQEkAFy4A_!>b%;l4W40>pzDL2f4TP}L5C=u717~I5ZX&r(iT%5F?!YVadWPTs3YSHKeTX_= zp8Y|YX$L2LvJ*f4)3t-RwEDxNhm1Da7t%ylF2b6_jT!ok*yk+0qdRCF`&|UHq8Cdy2?(7sq*9ot>=T_2j;7l~3Fc zgS;app^4P28dRRBNMp*>1jSX_uAA=h_4aFSq^WC6bN!OL)v%0T@01?X`rOvGJCS0F zl}is{Za~1B@2Bru%B8``7xqq?96PYlW#=U2G@4kU$*rrqwjoG;455gQ2ES->S!$Y( zq(}1;PV9*gT2lm`sS7cdW?&XvHWygLm*qoYmmO-l?Vk~d%Bu}p9%F|DL+#q@(O|3} zws7kp(NiT7u9a~*>yo&no)l1#^c~F~CEUNt|GQp4vEpnM_wJIl_>{d?<&dzG8YSZ? zWCN?`N)q?qB&S9Wv4Y9}lK%-p;~?)1JG2OeoY}7;4i^4uRZ??hI}WnvJPI0gZb72A z>YU8&dF~4FD#9k?8%d4F1rnZ@4qs`pqXWgLb-cFomIpcQ8BjClX}<4D#wbM-aL%A^ zLhci@^&RWpQjIwzDP#k&iGXpb4(|SG1WBG7mPoE_AhV)H1H3S{?S%(?p%K}rADn&x zM&b$l`-l@pQ5hs|-_;sTO3uxgEu=RZhHsz= z>FtgjkdAmsYi!Znl9eT=KX|BAk%h&Cj zI_ltx-g1+jdtZkCR2ISfItWMgzy|G?PcEQO!zj}sSWa=e@w(T01#CAHDW9)ZG= zcW8jYQ85{-CF%?Avr&O|ktu6a;? z%0l)y`R_etOA*uFw!~i1aPIwDDu+BzV4XCyX~zVONvXMyBO|q+iFtP(f&dz8LmdrW z5d1%_Q2{4wWn=F#(O=-~4_(O2PG=a#l$#iCha6TFIczeI6LveDCoLgM_VPRMzOKI3 zx*6afif5{0R&W?;qL!su%4eJs_*lh>cnUzbr^N2V+I zO_!MU^+9d3$t92=vM=I)*lK{!S)}>MAGHYu>Vnm=Uw{uqP6r=klL^Te2-;J>mU6=3 zC6k4vL=}x6Po4s1hgG$acDO=P0uuzs$S)(3s>jRQL6eWaU|0`pmu`i=^pOJhBL=ic zMjHXb2^#X0P&HNQV*?rBx216oaL>U#H*#V`Nqd=}wYBmOjUqDU+lcNyQx*^=--ANv zEJ#eRg6FxP^!j5^|BT{}Z`qS1CMAPvGcmPwcK<=aqar%i|noZTY?a{BiYMVK2Ob<_7gyu{|?qO)FA* zvhi_(JOl)AHmUbb#^hHTKf@mYzkbg=3gYFcrKe43)}6Rr5*|Mjd;AG6Dl8Dm5)H3Em^>Q=NM3nw?Gm7`MmT0rNHBno_J;hD3Oah`+ADdfAOHXZ0xAFN;GZZZ z*QP%#U<0N3d$ucld}9zxUnkyt3ghW>DYfy(EU8NB4<_U?IbpHra*|8Ox7G)|z3lPR zaqmab^xOzw#9}YtO|^%{=m55sgWzqo48thoGO<0sWSt|j65SDyJ%btqu|msiE^poK z^E$0FL5s%oX=E3+_;EG$gLj;FUG#WH;LOR$~WvrK9jypS16ka<-n1B_o zrxY}tfiL__omsuOt)KtlGzT=FsDQ*E6Hr(^@6|t5!N}7eU)HlifI%L0{BUg<@?(yF zanzG)9P)gH28Ff13{|z7Iz4wYpR2NGEIW2_Qb*pYBquuaO_AL*usg5G8lsT(&@#+{ z4s|bTzHgc`W9A^u22!%=3j0iJ%65U|BCY9MZjy??1Y}%j0Ul3pD9}$|bwH_GXyJ*Z z%M7z0ehWWh+7!zpLE@F}4m%zA1UuT-l?s!UeT|z2T$>FV>e}Gt2(`+8UM|}*!;1E=91U$E7-=s+ zH3hsma3T4l5slx^CLd69s7sqw{3qkUa6QX9oy&2z%pgetkqI7DgoZe&@<)(ls|I%S zgU%AyWblH5g+_J~lEks^YGJik^_L6VN`DJ$T^|VWut6O`Z_75CW+L*+fsO6;A$_BQ zldSCKYKSDpVggT{Cy91t_$&8ixMril$z}geP_12jR3wmxd6}BJSO$r?rn^SR#jmuA zcmk=&Nv{SRA`Zw_y#-31yu@W1^Ro!F67N|6+uO4v0*(L$6bdu^C$`C;(b$}DREDUZjF_hOn z8;&|t7&L<*@W#i!&v?!3fbqHA)ImsYW^EAhgRE%GLIMOh{u z2aElsESF-wuHuLi3LSdwUQ+;vM{U$SQ&V1~_t6^3X3+Y%N1e&g6ef(ABm2_Vsy1Sm zPoEz0It02AyG8^W;i;%_t#;h9Q{p;nAthgN*8Qb?KHMs9RmA> z_g(kFMSymao|Z75w=YKGB#Sp6Oow24SDy*6+H>Pt*+9a%@F~u{YHDc>0WwOHQtq2Q z*XY!y4a;_+YE(O*GT>qSaYDG)9h5U;|~a3x`*9e~oyTNEzO^8k&bDH!#waXFVC z`mVWtGaWU2q-e0NMImPR5>R(;pwnc$hPHJf)j*tU)HC2CZ|+x>K?U0gknxmHF}p}< zAQGmb!obp%#I9gKJUT?35{kSwZtb+W|9*{gAaxBVg}0bTXMIc+YI@~W96a_}Aw0#> zk8q39r;yaq6*+}l={Eo#GbIGWF$)5|D4;q|BHvBe2zWQ)<7P^BO|7Tkn2$>p7d2f7 zeHf8|I>qNEohVC)^PBA`Ml;yeY%Wn>T3I*LtFSQi;-ViKH;HpXrQa_i5B)OW6bBrD zG>T;F5GR6C6;->=CdXIHlh)&npZ`955&mu(Fx`{cEadHX1t+iAvhgb$Cn;#KXhz^9N)XaU>41^)n=k zLFQ&KgIflFSj+faiz|fYvR=*BTPdandKRYkl}QwlW;}ihTkMh~%cDRQcykiyMF~1< z)n213wtK4+`gFm<$k4%{I?ahv*(u#U;ELux4Ixtq*rc!iO!!@Ut&+9o)l-d;+y{mFYFS1O)M-RLBKHg((=VRmCNBZSE!x2!uq_%)w3z7zLeEZN0$3y5cCI?cR>8Lp)z= z2>VUT-yb}&hZ*OPc=k%$x8-Gjy7a#pN6(}?wIB8wdtqZR2xP8uQqkI{TI-kD)_JU- z1u@np`9;JNUJxe8+bxEz%Eb9N&)6TKvk7*>z3zp7K6=$Oh$ZNeV{(Nme|Dca)lqTX zjsG5t#bOq&1e#s!hgQw5wY=7Ph83Mne>oG!KvKI=6;X9FJ}g+#>9^3Gq_BbJpcp=w zoNp%$FMkdevjCd1(h!jyNluW;t(o-D6`S}G1cF1p=-(_W+;EnUf`xxDw(nAU0!2u2 zjh($0QDs(U#7m~7;BJ`4OQzcqFx%*E8#d%P%?~swXF|xE$FIbK78?&jF*Po+fUY!* zip)Q1@>sBUXDM5eA_bU0oD7Fq(BTNzvO z+?lkZ2~n@127m!Bw(XZ{3>1|>qS@+nYN5-@1nxhujdS9pSvd1XW1OJoSf=DQf5%8X zX|dLM@wLxI$TF83D?jThh{Tp`-d=G)46P6QoR#64#(a zEd8PDZrXRzqqQsu|Gz5~vraM@RZ*tXuHE>(ZDyz9ls}4rg1ftW_?^sTX5O25^W^{a*J5$3s`jorr|X=) zef#$O=P=gg6mEPmD{~jpfWn5)^PZo#TBp~1H@1WonIGU8OEzcppi4sI?AB*SB1ri- zOcD}i!Ueui$csYxu+?EiYa8|seX}RT;Y}D7@pen9j=*_K9bFPXf1oA#2M*>4v$+e%8yBJ2ubz$|dz-8nX`F zb8hALx$gb+!e1aGvzO~!ah=83x}<3+JKzj?LJLv$&Br;A$;3*qSG+Dc$on1o_`#{R zA|_-bE$80g@n@{+223B+WVtDHpXHY4w+1n-0Qm9uZ4mg3s(bj2w+JkR_2z4|9`p$O z-;d~)4Vc@`sC=+S6%f7TN*^D*w}2Z_(ZJ)ifVtOsbbPJJ$vkQUo_VB$pIJ6t^xEW> zMH6U;e7K2?%R1iw9z&D zYB0g(BITV|sHI$L;I|RR-^k&hqQh+u89N$9sM+f(vxV0Dlp6fQ>kRa;x$ zS~j&4adp*6qqGlq?rJd}J4N`uM$U^*m@bnCKcJQ>2R&-%<;>$Y5Tjbe*Bp_l;N{-< z(Hf2sb?XELm_%U<+Iz1#f>OOO>{aZ}Pi?UMB{%622G17=Z=s)p=3q^Rgb*ZGE0$XX zG#v7FxDwwOV<+`QHzr9~(rrnEn-0u!aSpsU&FbvBNUA#2NntUw|7hgiW@iwJ`b@q0 z^UAnl&C|-&*7(a@n%NJ%iQ(x}5@t!&XfKr8cc2dOkJ*}G#E%3;VwBScO!fs3l;ars zqrrpN;Y!1VSUv2$NgsLk2pR4=dER;noNU&_a&Fq374g3l<8XA+HCaGw0PPEr^O-JVd1kgg-ZRS<6@&<|ifc4thLc1a(= zO?j4jF9oS+yhH9%TF!Wb-fdL3)&KeqdN-=VfQY_sP5aY)yuoF2TdvXr#nnYA(~lcA)M0$SP+4#- z45%_*)e|hjz4QsY!+PZNa3PWTIUWBTuqM>N$3X483}uXQH5Il}(1?cfWV76}8{-d6%?4ZR(;Ml8*xz>pr z2c_fvxcAziTWQ+m;SRJ(nAxr;bST?k#P`{g%Iiq3bgGhsXwzM1-UKKo33GyRYU zo5;y1=AABmv6CMj)v#=p!TG$O#osTlp_4rMkP^nohOJTWz%6F0iKIIMm2RGW5HT&L z!`{U{)7VeZ8=zRO!LJV?dZ-BICz5g*YQ^S1;iXyfPrs1-fcloqKB%X=E%A)ws1qng ze#Ac&!l@A=aB6;9K3WJy|GJZL2@=_iQ!3R7ViI=s2_u21fVI#DT%vIE%DjO>m~u-2 zB9#z=EMTuGGrAY7XwkOcY4^>NZS*svCkBM{q5P+W58V={ROGJ8>9?dK|A0 zA#S0UgJM3SHuw9_8%e7}&fTqHV#ggTLsbmi?Pi0|Ijf#+td0oZQa+#i>i+Onq{Z=o zjd(E!b8?CjgHp{}8D}9**QlmwFc<1uJx(9EPe?>IOiCUxn)CpR;VWJCeT}l^+G3*3 zWfyg1=vQS7v3P2|SJRJ8DEtZawl|L?0bl8T>MbZbg}TLv{ME3x<`rWVcpyIR%X)Fd zo$97SwBgOlJde&e*?2LEtn7}3@cIGwWJQ&6tAatEqo3dIjwUJ0m)p2Y*;7xa$i$46 zCqDoRB_F>6skF@?3(Tn{oA@3kKH=gJE1Z9RCItE$> zXi=sylO7MLwEUx>5u0lg$^b3aWM0@dlx@NChlyznJ{L0-Xb8x!5F zEW1ONaWOIjeaI3o2}XVBJOWNrM9D`FZl_YBnA&m9kP-^P2eGs{wXTQ|e0n;8>4X zTOSm_gtKwzL+ptjB=>xgRHj>|#!taG*wKWEI7O1ir;$4jL$Kz+rcV2x)&?3Enbot; zJ$!IAWbR&=1pHtQ5hE;F?c3k|y&>1}Uf|6775*57zgIZn2ZZJj))|4INHLt)-J!Ws zPSIWNiiwNNqyux4CxlrDL5@)q>b=`bGb*Wy{^KTOmTmsp<7D3=Z1JeNkLdM=?gT|= z(8PDDnWGhb=m<~+ge^*9xfmoCIF_z$wXM&ea8r-g(-Dvtq|bbAf?Kg(u%V8fm;25DuB4ZXS4r3s`u7UThT4f97$qSJ0w;5qL*>S#=$0$kb z)C%iTp;=3y5aoSVnlK@KghlowB6vu&es}Mj!`o~=M&#M-KP?^FaLNir0~^EMx5R#2 zaT55n`Bom>TC6D8LbCbMvkbc}mG?BKM=!`yi@Rw#2mg>U5?t0X8mM9=k;r(B^qd^>O3jX;FmiQds6KI~0#}7l#v(SVQE<4|UMmq3P)(d+V zONn>kln;}2{8+gD1v(Q=VGn|qL2OW(gH$acLHLMu-|8_AD&ZX$-eA%gfMDUY86!!2 zvrcXUt;qTy>NYSWY9g99FANr+h(WC}MT3?$Lt(L=hjX!zm*=Q_@^zJ`zkHQt4Q=4s z)5qI)XEp?RCD1v@%wS|?{Z-bc`{2hz@eGf9NBb@F z*nI~hAJ^Nl(h2q@};?drW%|LbkFS=>Z85s}#FTA)a}HHs^h@(O(`wy_w1PsTh#|0;s({95GU!edjGb2zVp3NMORLOAG~zDy=* zCn~3!?WeUTfejI+qF_WbpDDCTn*e1^W+ZZ`rDgQ8ZZ)|a9FuRSGeeE@u-#Uht?X5G zhFdxk)l#F5?8UvOnqbHACi%5ORuBm0WwFn9KIo|m-VYXrzA%nQ^>9HemxU>!xy%H2 z@E`;9cAO6FEcD&K>+nfIV`q(3hU4ndL1I2<5!YPS{&Bio8&luNysP`AcdT~KM3Wfy(aNP;ZUEqIKOPJR zP$byKMUDiFnwH0LEEld`&k7`aFffgzvhGP0PRZ_Nm0on5TcwR=w$iAowy~^yn<+-T zd2wdcR$d^>>M?;#ej>x<9M&QKbh7<3_0lJvWFw&9-^_W8#VU&8OUB;`eDTQ@7cnmkm7T1kD$zGI>JcoG98JLlA1p7IgjDA3&YonJ!=XwMe;43sl5 z7Ut@yW95WwkDZ=TtMqc+Uslm0WdmuH!fr-h4FhvUQ0fvJ zq=t2aUeX!O4%qv6hca2n`$Ju=FFz{ja!}x>9!pcW*LR##gv{I^qG^gH}!gZ)-B36Y`h?R z;zc=F*QBDM?aL^@{PamYy!5p9E+eY~5i8%jNoqRB^c*I8^+R8H5pMG7?U2%=RUAL_ z?DI)8x_!oUFfT%?vP%RX(=6JB)uWF#%$^BKY6%qy6fZ4v>nX9R#o5<2A(7zl|hi37It*cj#D5f~0mdmJK~?vDuY zMYdx9@)Eh?w%84)&N42QwcgJwCUcRMF-|6yB|G)uH1p7U`&{0M1#x3V-w_aSu5a%} zhWPqyKn&-U?#(AAB061t5z2D)3l;R%%u}!!)sJ94x7vNz@z^GrS3@z0-c9U=_dU8g zSPx%(Khs!VTklA}K}Y+Dp&JT4gwKgBlWPKuHxWT!*;G9(>S#o9U~n5V%{h)Rg~(x!Bv-+m=|T(i)Rm&hEoG! zf1p7Ax?zxGWg>|~IPLK+$u~KA^Zmop-M7XJl$Vd`FoaoeyDLId!lk9!kM2sHwcebH zkHO_Tz>#-o1iy~zec=`-WWmeXUHt+E4(#px&lD?cl2le=THc`P%?gL_>EyI{Y}|dB-;0<_^&hj~OVq=O=~Go+)z3;n zls40-yV>UqGITotkN@z3(BPRtWXn8FNq#U&-u2}Bgex2kUAa9eVE)izgJ+TDg4T;H zDy*RL=GFu(1JPb330K_B0Jg!F4r!f)qCrnN)z6r?B~caYuitXJWu9Pn`X>{GEULn5 zD0}sYDD-o`cngt-Cie8;?ze)@nBc%de|SoLLCP4dWMCjN8Udv!dlc~xeU_Upmpm11PKH1GEYY}MtSTr*j8yg1*6?CA*E8IIcV9(1~nnXcWu zb)e(Hl}hsH)xn4&)fvsq-(834tzuakL=)ZZWXJROpxl)hGJhtEQVKSTBS-Ot?}!} zO-OlJ2_S3?2Iz^1UFx7$$O{p~ha#R)a~EUSA8!KSx5Z)vDz6bYHg9zz>MVkvH?vLQ;yOY6Y`_A>17l1e%)HOtObq2zMcSj7#gLp#6Lg02;% zkX(2sJKcBJ5E<1yruLs3d5GhD0^OZfb7uJ<#r0sWHOX^~HGze!9mD4$!y@)}8m~&m zy#?Dv#E1cOW6Pi<*otSzxVQDgPMdamx%}ZJqE?`YHq!QzyczZSnt%u`QcEez?2IF+ z8F`w+7O7|7gyTwm9zpA@g-k(EC9^q7c{E4nGtwSf3~krm-9`ncp{IbhIo`LUXQykG>R+aPN9NA%5s8^#YtcC1Guf{@3S0ebN6B*Pg*pYCo;5}?V5&_fGYi-FWOI78U2sc|4 zCSv7@ZayZugJtQ~@6MtHg-(-ECr5cbY4-X|WIbQGjW#yX_#f4_K6&RW+`&02WFIjEO$z zacCK=j|kKE{7N`O6~1Fwff+s)<6l$yF-INQUgBqMRc)G+5p_#-6RrbiJS~UTwbrI> zA@yD4)Kb0umv6qcQ#5}NoJ6Ck4WLPDbgecf7eAN`c64E^qmt!5s1{LsCR z>gzGIT-cN`|Lnlr1hFSuO4%5~e7Z6LFba61saLL3OmJtl@8N*jgrnIv3G@AUr_!uA zc~d<@VPB(=ab#i^2Xo;k(sxQdeP8e2y$Ml>W!4O7ei#&|EyK#R61*Rp^h%OusC-^U z$$m(}rGl#);75TdAqccp;{}uaym31EHtmSIQ0$R`%a0q zx3nu@qtfST3W4I;_?Q<%vnF>YFOIcsnR~EiL#)IV!7XyOpj!2V2TtwZEPu7B?NT4C zFR(>Z-XAA_>B3KS&a;VYefdaer%H^VN}yBSrkf*;R2Cccz;RCWO!L2zlB)B(Y}^aFoA=*GGVn>IK1AK zc*+ZkGREd&G6Hc%=-hK$;$UxV3qTtZA@lvrdmn^cbvg*YNAOkZBad(5 zaS@iQQ3PdTCDM9B00MkM+rxZL{{D9wW))~w6CI7`Djfq13C7*%V%v2K-a|q?@0N-R zDBzu9kMSHoI5eER7(}B9mxt!5%02Uj>Y{srFfuV^f2HUE#f1y}BrU|P?NF`=#gBn+ z__-xA2Yq1=`9OkZ!#=>jSWv&6Zok12ALZE{ygovI7b;QM`OdeMS=gwh16Zia*Y|HS zNcw1rx5ML%&d+RP&l}Vc+r?PthwS%Tl zR5+cS_~yv7IdCfsc3w`exHlHB%lnqR%0>gVG`I7sc>I)YnxGU2o~W9rTj+{JVdqW} zUNxeT=kvTfms~icN;(%x3g6J3x+UZhd5JmmVRskf>+9LvnCHdbWvs#R$1#NK1_ef| z_16d#smR@g^ZG<+N0cR%3bQZX@$$x$31#UER8Otq+wy#p=2K3A{2)CK)p-h#L-a6$ zH+O$^&HZEVd)ZbfD>d?k4S?%D1rABbV+Aki0jyBuyQ^?9f_K02#!T1jX@_foq`vXa z+~W<7m{?f^c;&eaC!2+Dod+UmC6aZ0T&0c}N&jYL8SXG-jc9zDuQnl!e3uOAKgJW% z&+ojS*@3*xvp4F$!WBLfaRpGnddJcZ={**gJ>aMIIB95}qlRp^n-n$OB^E`SXzIpR z3TrlZ0^U2vBGf%Ob6qHz+$<`bZil^|k`svy-^G$~&i^J*$axqi1(4rH@|18}{9H@^Wfz&QN9c-li(J!Hzqd zUAAqK^L+6{0AQJRycfj0eLh}9KYV&`3h#|fs_nK+Q;#(L$gSRhp5MREzk+@?A^~_3;3L!FA8t^W+7U$Z-z;Zz_dwD>g zymqQPjjgKx#3tP^EHO9$zqYOw-35cTkOJD4ozDCgpxY;+A4gHXl>x*npS4$}A{x`MlH5T5{0{o36$Eoh)VK=ii%ZMm~vbz2W%+JTcPn zWJ52nfnO(}`2rT+Lo7b+6?kC_bzF(*dmNk|J-KupTMlMEa@An)zrPGFXO6@=7#yH@j7DrzfyhZYp;y z`$Mb>v)*oERY*B|3|h?{tPLSiqH}j>^D`-sgrM#l9 z1K68!8JrWH_x(!JWw{6$?(ZCXkZyUSlM6MO0RZTGG;}1vge+7vGYJ^l)bu5}k973C z+n0q>yk)ALRabL$;T@2|VLO*b?~@tj_QMV|jrI%`ki=iS+3uto+$VWQfRFSMXN@S$ z>C0>U^ON%|N#n|Wjq6};;(2#+q#I6{p}7wH&jU-e-6+Sj$fU%SE!jy|n|`L{9N@&8 z^8*4w4Z-0f+qgFBKnCo@oJOS4q|Z=-ju(qPJk1v=cHr$Vi*xPxh84IREMVVLLv`Oj zV$UeLU7g-fN*2VVigszD@7Hk(p|R3KzL0`e^i#{SpOEm4+VqhQ*hDf3HH*O%iSu&M z@pK4i%i%@BgDPFC^kn(+Op5ZXL;Bs^XDY(kH-vz3QyauuIbdq~>HhYy4rvxRso<;D zjcg<0L0Z{UAG8;KLiBBp=7n&9UjjvVA|kwTVDT_G%|2?l&2-)`R$V?+uD;NV;Yj0+ z>Q;FJ5A1*-yXj0bP!A5wdJ}xdyh*)HXVu@f?=-FSafCYa>gBL{>BU+JI$rGx(EqEa z2i7%d^T1P%GB%C+GUMyVe#FjG&FzJN^G8cxB8r7kxZToQwtzj2CQ8pBxKLoimnJva z26k# zuw7S39tF`OLHf<~r6-S0w!FQ`91$iko{ht1Wm~mBxC)19d>g=`F&S`r@zxMOH5nmh1QZ7{*BbZP z;oV!&NI^dg*6jszdn%RIRKYp=-gpINRBgn?6a`uA6V_uRF1&&#KVIM~INvTABu_)y z>feExM}WLY-Ue!8h@7zZ^MdbWRM6ad?~*_TOWnX833Qo!q4*TpNFERmwxicmn~Fg= z%>_TgX|w9`YCGGSAP}X7c8sp;vW4vx@z_zl@_Ilj3IcB96E&-&td<4cRNDHM`HPd; zzRvSyd1^pAE_Et^F%$DZ)y$X}Ayss8#X82rS( zx=!uMzkE7NM$)R=U4OJY9U_nwh+X(%E!MoJjNZ}Db~WH-XZ1V1K?6hqE^udL6AL!} z#=R4syR!h=H4gJ6folxw@=y$q8qY}&cQ9}$^&*PMP=C20oqhgjy+EWTnLv1M+~JBuv#JbNgfIY@+N4{78;G!~}c&s~yOZ#4mL z+17dY%XM;EuwWzX)kBAgls(>k?k9wuy}soiDM>UVSI4xuBjw`5Q1)2H^ULn$AmnI%qEW ztjjeH_9WfmDeAls#d?^&X`+t_>HwrpR`swtt^grj8FKyo{R7euHQ8TPOdPq_C!Sjt zz~3a!MB;J)#{l}T+YnrvZK|9zd)72N<|qe{GCz5`-1XjsbE^ftbORCxNqu`1&$}SA zvBG_4T}9t8fPtYiIp=k{K+W5Mxx#ljI-osOr!MDgxvKdgDn8r4!dr@;#>>I0?w8W()Nevt8A8ZI?piCO!+xyed!F{jsuM1oUpG(Ws*P5eL{0h zLr!0UO%!vxN_v~pun=88%<1_lFlHY@+`PP0s;P$zlY;28J7t6-$jY z7OvQ5J-FwL>M*XYbXX5cZTlx5p9X_nTB)oi4xC9_k$F)O&u-+t;`BHA)QIWCQkK8#L*2IxMNz_7O)%YT zz5!!rp=^Yt*Z48|i(`x<_aP@Gyxcgko*e83?yDL}>I|4=`ZZdrgM#RfQOvdSdJEfG z$b(@`4@F;L%JZe)@*1&K%OBpLimdfK?HHlU(__u`6YGT@ES>PR|eyw44*O zaTj72c(LPE9|lFW&(}_A<>fik(Fp_*g3Y+J=powsi6;C;4Kj!n>dIf1#t004NN`d> zI#6{t7mI_5(S`7|AJ_uj88YG*r10tntGR8!-oQ`8X{Z>v6iKQDx^h>`n5S7oe&od0 znIMJQs>;VHW z1)+A3dJ>Wd>?A^MhU{jAppwu~#A3J4F>Sih6G^GGo@zKr%fTw1o~yQ{kv5+Yv;SLQ zIp^n#U5((wp<~Aq=`o84Iz6qPf+^>gBpDmTihH!@Mw%m3$qs(TrX|~Os$dH}ME*6U z-6rhS$>(J_Z*|dhi6E2`ubqswQv;jW)nmTMjVw`s#T5EQD5=cMd^FHwB4ZLLNcuqa zVs0jV$sC*DqOFRUM|v06V*a@p#aem&+%CbmmlyiPnv+s_e>z zv0qi5p>3Y7stJ6gr`dM2T-q1?Aj-N--|hwzcG(uLi5{l;TA}Sd^v)M1<(#X5 zB=T#Tv4FPo#|YJdC|b#2YG3By3o7DgxlCcLU}TmT4#>|EJ-^Mg5RMrS9tig2Y0GGN zjFvw#pWz5+G1)?BYdm$#A6p|DlI1F*6=)Vfc7GYlgtXqFZR)+d`m< zk7s>!JK!_gQyXG4`aw{$k~t#b+VybjTxx zA#rX#&s)oL&f*-j-en-R6>z+Q+~VSh5n^u|!o}=yVOH>nY$x8@jIv9Zk-2x&UXJTo z%Ob&{X+SA~h~nk{kbz$nQ&`y1K^8X^ z>}V1q7;RWi++@LpU7M|RrR<^;UO|9@h17K6tC|?hR%@s?U$V(JDg_8bzx2QizVl|` z@9&T)nhp7ao!k{hq(8%}th?H_>#y!!u9aGac@A;FGe!_0ZXau{5ElA9lOQTKhZ>T| z4C~8{v2PVa=klBf8ha9G5jdlugk59X3GGJYiprQ8G0-Cvfb;E-Nk(aE*452)RDVao zF~ZMO9QpB!_kcrfy(S7iOafWh;-v6r13%uTg9G5J0}uePape79T$>?Ozxm4)wROuJ z{-6jJMe{=_bo57|2=${-5&u!xUi>I#K<9GMla9)MD1aXues95A`F$_2kbg+X)cz=H z!@d__aNXYvh|wPfipGy2I=CN2z>hwlro#`3kRN?$JUHw@>zJUi>j~Z z#kOPHs?DsJG-t!K6zz>kk^MQ@nMVM2r_Hq}Z-X`K`+kix(VqQtUG%Rjkb6xLETPOi z&l;eD9!qbh+v`e{ca>RVYI0|jZtRUyaWB#dCci3arb0BdXi5-y@q)Q0)rgI-5xK%_ znPu|7a>k{i_#%UR&MHb@`qelG!u0F<5prp_+Y;fqxI>R4;lZZIO%ezBhf06`8J_D{`JCkQ@+oUftJ5v;OF(Nxt2)-A`A~g;^~0ktb`p#`}hXj zYe>ZC?ea+|Mts@1-d6d;WGr!lm$*S`w~S1g)^=c`RGIx$&B$vMHg*JwjA46^0=C_q z`@YZC+zRj!&fhN9ShDtMMFpZ#5IdCl;s@!wUUp)+_v4CwjV%J0w8{%-QP{F<&h+5W zEv=jd-o&{ld?bucdCS?OEVLN0^--v%>w4~qpQb^qXrvWt|;@Sw)(c|N0PUm5`U&08u4ypo&H!%VB_CeLtc2u$%=bdHu5`5I9Tm=X^J zyLmY=v)w1R1<|&c&CJ62j}8I}I^0*4&oic$ne5)aY=O2%WQvI!k$oEd{5%jH#jQ!3 zM3ihFTI}x3kA}DEjhmnV)AL#?Mq@$wV*3fSjOQ6-;#WfwX0g2~g141(cg%+R`}$;Y zD~1SfroVytyyJFZKxVyCbb3VL-7k@Vq8U0NR!xd?Pv8jT|7`8x#s_oML=4Z zZa)e9V%=^JX!#@g0MLI)MZf9&xq?3dLbL@TD*Qd-A2lIffc*Sp$A3`=?t<`~L3sAR z<9S&5;|Tww#l0P2h;lH?x!-#sPfCY=wg}{xepdfOXh>TStOE$PTI#pJ{z+B08z>9P z_{7#Ue!rTRFf#lHpc>16X#RZ=pu9ntULee|-!Vga95c^;*^~YNFJ#ULB&4Ulqt5^U zcMrRMV)Xp1fP+(o#sL7NBvt@$h~GN@O$EFZ1aA$3Kl~m3514;s|siDcl> za)5zNvZi4_{iKKM#%NryYufL;#34~f@_Yh3=$i^IjLE>0^;s}jyu95EtqCl2;_RDo zE4Dn;+Ming3sbOp5Qi9%9Mb5%+@E%w)JlF0Q3V2Fxyn}*$OD%a5XPQ>xKU?1=IW=vjqD-2cTs~`>cTe zw}2?3{u3kcIRKpIANpokNPf18RCa!lgn#w3=cgC{a)#(ZbOAOXO!+@x{#&j8Spc&C zS2(->KXBjI87N=TRweu%(f^V>Mc#iLOwgmse|2y4f5-cmQ}t)wKcWfR0B8^X4o>eQ zAano#(;4@xA0*L!zt-gC-~H#l{gA{2E#~h5r9=2Ph=1n=@=f=D3X7u%!V3_|pqFj} z1DgY73ZU;#Rh(%l_nV&$qZQ02%xM6CPJm1JXWyUVCCUAB2qkAdkC_ldV~>p^p*Gv! zf8X!t$e)zHI|6+RVi75l!&+5G{ZsJeKdB(1%=j@cFauyrehk1AyGm}83~fnqp!Yz7 z%Wxp3CWLeYkh{8}T$DY(&jeUl3pKq9bImWCJOp0LFNVSC?@TWTe}eoa8*pGUh>jC5 zhgYsF;z@9nUMG3{~sJ^ zZ{b7uJ2+6P01@Ve{u!#)oL_5T!^Wp)Kk5$?zjOhc51^Vrug<@TDI_E)qIMumhJTOw zXFFgA%-^kp0n&Z}0S5@fng$g3<a}NHE(sPHr)(ARDdofXbZBPksBZw{w!Uj>DQP$K#miwjm!i z08tnys06{Z#5N8^y^-Y0Bp(vZkEeNWTmpfn7$iQ~;hh8~ znO-|nvy0cw>EjXk&JFd_?aP)Ew1aCF`t?i@)wgwg8FuA3vbgHJEf(lmOhjVrr4BcM%E@MU2;#@P_2F$TE1YD3(b_uUGl`un zU$1xZgWz<{5%7mw?(4)$DUL@|eDac?C9En?%*RxL+sc;-)&lo4xA?2?U7h#Go$^i_ z@~7PtFw)=c;SL+a@qT-q3~=dUlMGXgU3u;3f%Vzdk4LvRP?U<8PbAnYVZ&^f71&#) zsfG_>45z-y$*}n_W^h3MFy;Fxo(CPqf|~}$1AlLfI5IHd?2_`FlY9EGu(x*!(oivh zs>n^jEk6k#*sAe`lUzxMiKl;NQg=~X=WgYFPulu|qS4csmzsAc?fUAuWG4Cuax()# z4&mq1=>o3@+7&gkB@IKgF?rPlEYV&?Ii2fb!no+k*L`1?>Z>GFJcRT8wq^7_Z!VWv z6~@f=Yoi_jU>A5@YroJ$!86#G%fqs#VsT%rQ!5NGjKZCy3@2LF=u#8i9DLZ#qa_h* zrVBDVFev|YcKs~jLccZ$Q%PpRmcWiB*!WphVu0R(KfjC;!v$LU?PV(v^reL?Bhf76 zejhDTlq6NMvlV--%^p_jNzGML|Xk~uQ;w-xL2^KWN z$3nr0Em3-qAmb`3*5qKPSmxorCy@1TP5z`JZQ$awana>lc^bE@TXK@2`FTPRw+LCDuvWgAmJh>YR8)-r18m$H zO#_8`XeK0UgAsIWTm(rd7S<(V>&Hk44n|3}%^ADu#AK7`jU5T$8iGAZCLu4_;v1^8 z@hF7Y6yu6mb4%$g3f=zqMY&nt!1Wx%s|o?X{cs|tv=j!HRsKfk&$)$4^R?xFvj zURf&LSt)V9b*(**Ymf~~?#R7gq1^ZO?lK6DWIEuVb+C89mgRelC$V18>@2b`BMIbb`vC8-S*ug&H%%J6{ ziHFNH4uIThLXD!)ut8CO3tk~u0Ox1%c$`}p(nz%)F9`1EZX{NQ+H6GAX3y)M_MUqC zw9PDg=x$TOlXY5Ce9zA5d<2vR0gWO#VpXT0v-2;TiKr3m&nm*tqYzYi$sH)WkNq5= zH3ZNi`XSQBA*o=KpjC>mE4aI-QzbJifJS@ojg zX$8lleHj^;1mNuN!>#0h5rNz5M~G%dn2Kl|$-+v=sg&i#*3pzP3M>N|{MVb?hwrDM zJYbHj?atqv!Stm81Vi0`G4ivOpJz|BhxQ=hAC|?>Nl5LztV?J>t?!qIY_g^rR(^~S zIk#~0l;|O(1A|M7ZdvKNFoB{+-9V}JZlyTvBlvymWCU@H1aXY| zJC6U#Ntkcl|6u=_Wvt-Lf=halAv4b43Ll^w;6(#yfOwjh##_#n@W(!CAo&ORKiLK9 zfaoNG=!}a09x@4|ygzAu4i*LgxG;X{2gd<0pj(f3e{TVK5&#qezH4Nl>oeeBCm1A9 z)6|lFKjiexabJW2bPvRMwhX}eHog{@I034YVHwS7T8RJt(0~NG>IH}g(K`48t$#i7 ze{$;=n!o-B-{ouE^f|*OBiud4$AjK!r*8sqP$(aojSiCF*Vr$1zn>cNh6gbHLi%5$ z=!k$wr2uo}5dJSnWvTwk%0T?CFT?RE9CGvHZnjX83e|RQ`$e%IkS^U;dTUlvVv^{C zH^)rNGJUY$`oCjFOA2CEE0Q5kQ~mvn_2ZBQF!+Zc{0I@yQteesRrB$Ksale|i+(o% z*o-aoSH>ZE!u~;~`e-O!0t&)@e^BX28O;{w5z&}pLvmv12A>@oO_!t4$ zrZ507@~c2f8ZHR{MHo;S69@3nAYC#KON7UNrSSDAuvM?Y5w<1WHtA{a;EUNZAuXC8 ze6XqtnD!MGw2rdHcuPM8Tde1+o&MO#PQh*cqADcs5rf5I;G3&p z=8Vc}i%+4+%f5;VEI>EHmSEDAh`Qd{G}J0`NJ-z@K2aXK8eIvIK=`x znDjkm<0}@oqR|`C@p;+r4sGG(M9K)FWdasH2@}h*2Vaq-9lF3m!2HzwD}rFpLF_;& zS`Xo`*!`8pU#$9{Vqh&t9A)i%&zNxw{lj6T@#3<f2+%y4`MPTl4Dk-`xogA9Du*_T^&(S<`0P$n_9SO10@XL;RX;h z2e53|RXqHL0Upk%_`LyL_o5r@I@H15!$=H{mOo9_lwu)7ER*HASy2Qb8b_y3x-Dr@ zHCdLrF*BG$JpMemy{KO+BT zg<=In0dz&jF6yr-{08$MRiIi$gUDO{1=Met>OCM#&=noKQPcl9J^fAx!bB|Z-yl*N zfdE0DirF3fKL7;6RC2hO245-^wj}KmuHXC{Y!FdHVGukhE!rde7x1(HYTGfk#+V>f z2x@TbTusD>R{fN}ZFRY#^R)ubb+67q`DS%n*K9Q2p-dO!lV2lP@Q^|6zaa>e2C<6) zv19lz*!>>5c;;;A7XAleP~pII`2(mDEOnP%DnQp8YFF+SdLuiaq#M-*pxpdpDP}t_q&pT^<-#h z>k|L${VDppW5moL7Na6LZlkt;nGb)F)VvJ*gNg8O;6hStNRTc7obGN^PKw#rzYPKl z&N90}Euj4)2|&C?#ksyWl1p=c@FE92wWs3pBx6@X${rh$nc9REap}}m>3}5+Cw2hVLsCmd`y(k8GYa>SurbD;S6`uQKKwAw4GSaYQ7x9sxsYyPwqFgzo;0B zfcycSqh8xu|7A-2-Sa=hV&;k$vt0-9)81`=R)rMrxpa{cUVWFoLes%l86>`}iY zDqpxQv9^?BSVNSnQ>Yo4^S3vwg$?$d5f5GpcYyfQhenl~Q zQKlQ43m4U4Y?{g$B@-M7K;rNq`8O2u{6Q2z$?$d6{{@BLqW51U!{oWC8+}Lj!!?H}1j=6xReDGDNa7ttOc$W$>l#C4ZQFsoby-|P9 zx6*&F_&dzlWlh=`jK!d zNnOgDNhINsQ&qu&>Y;!xfO8?|fy}9#b4jW{T?2RykN|Klr0ajoIl%P!{tW1V&S3g{ z&jOln-RI9I$oG^xJ-T%Bo-3b5aF>_Yt~)RtF|>ea(I%5#{94(;LU%DIAG>8?kqq#8F77g*M+5~JQ$u5 zFQhwx_VJAAM#WyRXo@eU>pzRw1U0tYg7`Ik_r*wrt$B$jzvaYN<3p{Hi=*n$EEF83@LIgxJ| z=C?qE=9t}53hVpT{TtWAth4i0<`LiW(9X>_(Qpvx zGA+Yf+l;@73Bv-!1RPx6&!Ejea&U$~Kmc!fXW`5DMELEL{1{^Ali!Sd1d$*|$GAqRZUbg1AP|=JGekUgXf?>;F8T3?EP8Q&8A%~0 z#KLmiLXOZ*xE^BTsR_$NUw|{Uo3UMEZXw{6d^ihZG**$a>%wi!TT`tu9HjBZmm*C- z;Ym|-HZCM}rJuPff_r9Z;7TDPUVnx&=)g=Jx183i5It-zXNz8WyQc2N7ecDpFBH#> zWkfpWs_$7WaSP=(IMP-2x{LjlE!V$NB_n zqkl9DvzTqjV?PudVH8_j@=kNcQEXX@by3B<_efUdrME*K(rr*F*1a9s7-!gOzZ_`z zkeZ8<(6C|x6*&{T@~b!-U1L%xM?~O$F6Nus;e3mj7aqOH69ZiF&MRzw?krVvHim?v z&Ev8QtiXDd0{ge=b&g4Cd_x6y*+!jaRv(1&spg5B<~39^?{#*Qw$OLh2*sDNY*%Ab zWQ@{tUY=K{Jy=_ATd30=v4X5WK%DxT(}=n^q7Vk9wTlX7z$p})ce91G#xT?nzX*={ z@;TtEGvxVZlYHWb5;QmS3RUTs3UEvmhF%zc>4UJLYO_|FVUJzPsoTpM*2IP^HIPhn zywif-g8U1TvM_KJd#xxR%{w>*SO+MRqu1sT&T=>R>k z=}Vf_tDadfg5UTSLe2#K7>mA3!3yd&=hU`8@>5be!3Y5j5j8u1iv6rONh-XIo74j| zg^ZU9h&f9pP>Yl#G5QW+YFs2TTb=+LaL1|50l%Xp;fJqu8V2tWo^oBTwq(N4G zz}{Hlwyu2Pof?!!tkoV2bI&R4z6f>`KhZDXdB8m{&$Ud$Q0DQ@U`GT4qZ@s4fnr;6 zMnAw?d9VJ_q;&<#;D=xW*B8L=j^7N;$qFYE&(~>xcu#KVI*kmS7RzQi)~y6w1GbkT zC3tp^=H<1tbRV+$qZEHIy*t;0_d(eNA3N^y0hGfOWjGlJw0r&2V*lOu7%<~$ zh1&F8G>NXBe2E?A6BSi-kAXp18vqel$7UmK{}#_bu>yTwVYOpo87w4IWAL+%0h zY>C+PFp<{USVx)!gVpuZn!q&+^0M4}g{@HL5gK?6!&(NSFV_kcAA{bGYww})x`e8V zqP6F-GEZpIVZ8iMa7#xGY5DxL)dyv|ZqC{28%~Y1 z0nbT_H=>^3Dy@RP-@~~<`^waz=Jm2CIoL(PH-F&nUHLI}P^vc(SkSD9eoDfctf;Xa zZg&jQvi7keAn)0BrW7gR3s^Gr>$L=KzYi=8JV7S@+Z(VT zj+pM_d2mcAa)H*DEw5O6Ou6fB?dybj#D;3Q?lLvL4sHU0>WIcWbddD#7`y{pNhC&; zGGvveDa&7O1pCrlf~3BcVSrGaM%YZ zBGwD*tMT9({79>8bJ`S;I0S*EC8>O@Vwt| zn1*U-MthNLQwPeSThM<`vin~@@N+Zu&AI|k@)JwoZvvau0(tgJ>Rwy2Fqey}Eof;~L~_QrQ~6eK0N#oB)Gg>SK7j~*@s zBZ?$7pK**e!igY<1y4rKlZ9$qX&9m-J~+@>(1;pBf(|O$I+=q zt@T1PjkBB8<(D!Bec&2d!ZNMzggBcczhgq!G<--tGMr|5(B`nrxvDL$kj#DSovgX& z4e2W7=#@7n9@gP}e)E}Jt6~oVFStj1Q~HMt{Qf3*0t5nOgOfVD&M_#7Pf0l{5Y93k z1gj&n$M>!P3DVG2H!yNR>&h0r#)V-Idin9M_yP9w+^RTt)}ya&SqTY*l&%M}KkKP} zuJ+Wm6c%TM`= zbf|;7(lekqR4g=O>IK5foob#LJ$2v0fhua_mlKOxQTEV&LK~WT_6LyD6jDwD0{sAi ze?svezJX`>hZo;9z%MV6fXnJ{f3RjLkx=BM<$R`hCG=i0W!RUXDcHDhT^(u3Pt!03 zGeX{{mWCb+h$#TXoW$OcFah@!c6kU{b{|fA}x`+)kTwc17!k41!7Ydnp9tzxq>6bA|3{~-; zvO-brhR-LfO}eV$dr84Ty#6$qpyQ>4ULx_`KWzr<_Z0kc;8KleUBmh=PljCtn63J) zGyL@co*GD4pGeZs896&P3VS&ajDZF+RsX#~q&(b!p)@Q=X;KM-fhb^m5$nQ+l9e`p z1mi)M@$2YDP#Bq59fZ=5k1qx8g@RPuf=>tgmupHw*ON`a9MrGiCcl8lVVPCxmphlF zFHuE6Athf4cdSWoZ+Fc0U2L!Y3}WP0s{d?448nPSYIbEBfI0y)_~Snfn6m6NJdE1f z+b~89TBD}0erC~`HAvSe4MZkmKe#o5brA6VG}%eG_BD1BOisx*7!wc%+`Jn9Ie1ij zC-0wnK*p|l^^se(RuOM6D@cMSaA#tWOmy&ad}GH8N?rriQ{(`Df)xW4Jpw09oP&nH zcPcQEwD2{v;u}a*<*FhH;^H<9Q==|_6Mq$m53HG(I0<$q_uSvZ{(b-^N|S$yxAiep z69i^il%TqC^pxr;1z;S(4Iu5rNpL&myMOr;5d2PNH?}tQhTsE?^gN7u@ViGK&__kc z9l23$PFi&PQ>DOyi24CBPXRIKCl^p>z79RKXqEZh3(bVt4#X&EyDYn7?IXL-grURf zLVHr^YaAwr^Z41dPzU?3xFJt3(8)UVcQDVv<=E&}yQ#4WAv(7B+`A_SJx%oSMjXKU zyNQDH&zl{ua5K|t?P9>fFBIO}4p6lKNeh4m>P=7&xo-Isd46OZ5;GWdio zpS?)f1*F*(>V1(5tRXnk#B#+hb1PPVH?m3$_mL9^&XCpqrAVTN;QD2rwbSwmJkw(i z)ChP)=;L|l^(PfZMBzbcMaQ zpqLS)@gVMc!NI^-!Ln;`6wp&uz=E_OfDXX>t(=EPzj(jX2k9ee0)BmIZe-EOHcyUqtwiaQTCd^Lv~B z(sk=ZlD5sx56d6A(0dQ1c)FZlLM}xYjP$yWJMqU@nW__9uENIb6s?$$(Rq{1?OWO6 z3%bmXht=EJUkDE{s|p3bH=rC zZX&)|(?g$S8%iDt)x7l9@DydRmw=Y_1t%Sz2T9-fC_>M2A*RW3=zVhz4tD}O2q}%i zg;2ocp}TP=Y#+(D4p603HwJ{-5w@1H}F*m;zSHrFN&dz)&2BqMTY~lp~V~ z(DCp*RQml)IVT-~tM}pgsq;G>Cs7XI)Fk%>l2!e>L#f?pOt2&kx2~C~yqrPu%KGYu zyMd%?^0k_7=adA2je+zW$yz=K4FC9;#F2@lYhgs$Na5q2cYX5efS);IeS;Ql6Or$; zKCV5YL2aGf^H4zp1MJhzXQZR+xU)$7F3o?0L%3~_amY-W-ASo|6$S(}h$Mpo&rifZ z+sCI7%?Q)+UUkSO;2csGxJ+G0hzdRQ4ooj3tKx_v+AwN;h@zuitkYo0rfDvvdEX?r4;EMG?E^L9|=RnlIGLD)+ zTu&hGd64uo&?o}v2nTeWhe6*N#~+~ac9zS4q8NPS+T6x2IXsP0`rcal^oflEf{z4L zMSzo$(au4}?``6Zreb*bi46-DnOAI1@*H$nmTwoC52{&(>~UUy#h3MR346zHihr^w zSkT2{K$fFO0*d5+M8!8J0uuVJV4+rP`GZ|~O9p65JLBs+fR6M$?c%2Q6+ftArEUfbyLvmFweg{Fkc@)F6 z`yzM?4db)~B4hvw1fWQG9`gJKMXyY95YMZ8nI}q@JX)k->gTRp}QTrqD{H)1+;<0n+>cY3HHPFHk&Qf`Zo$69%3eiQm@ZU4dL=WLDxP%sb7K0DFJ! z0KgE1DPi zqePPe5c>BTe0P9a0muS4O~iB#BL49P`%JVgb)Np^P88JXN&Tpdn_Ka>70G8h$M!I% z6fRsxK%O9Y^}O%ztRgZWa8vPxNCNSht)j(B)wSd5B2Gz~n}NXVLE^Y3jG)?SA<@4q zyZ}>Q-z6fjL=@;qh2YQzQIFQ&@xPG$V2>g|vBE$BF0K3XRZ~T4gJK8wr&Vrd*~-SQds9U3!J zsu*gV`Xdjt)0!7XRU0#zFu2{n;N%1`;>~rNUi30j2wl@ie;u6mZkhlrpIjR)al1ic zVED+5nWK29AWJsT!rKr`aB0@u&o@|Ul zp1vOvkd9824!i2n_k8$TXq{yIRM`?C?9(rcZBq*SpDqL=92k_2@X(|sQ6WX#v%X)h zYg5z1zcPTT%{LpbGBfFmOI2QW%LRSR>Kfe5FhoUCOROiZ!{P_1c;q>?0$5JV27*p$ za93alFE6E!cVaND6@ExSIY^SYaTzh;AkriUIy<%FXtvs`6bE<`O z1-r7t)Sbd{NyOYWg9~PI5HF2&qpOvIHfb zw5ecHLsu;7Gh84ev@0E61SOO`G}NM440F@Q>FgcG=>=eC+rv*PhK}$za9m$}-dh)O zsfB*3nSqXE(j$A%9FW*m7Vlyq3i1>{Dw(SwZ3N~iwDiM&k>YGbr#f-g`B%L+pl+X zS_x8?X8W#i%&K2mPGVW=zIt=?Koy!+c$bSoY5ne|D(n;tV(RU&D-*W+Y*rpP*rcrl zvNvAbS7G{;E>uTkoNltZ!HRMx>t>h`$bAn+jRakpuH@r(SM2xj}* zm<`~OK4;P|R4#azbP?ROor#S3%UY&=7_$Q#zdjQ%HH!l|6IySj6LlQEyZng2)7H5! zKWN*e*G(9asX+thY0pi8u$m7vjPe=OcnK0pDF}*;J?7$VlMgV0GKzD>8dKuKZW<6= zP-P#Q3|Glz#6;ie`g(Cz0E?>AyFNzy_5&Jv**>=LaH;tjl-5GEsg+*E8zg41`IKZF zt?P%dT$%Yeh@=r13>=YMoS{|BcLzu8@5Wg9fr4t}X*rdglUGrr00H|$h?LA19}?GdSN-!pN2CE-4+Tn`SwH}PIr+RT?nBOf*SYs z(JtE=zb9m)U%TDR@6#~=*10hMkhm(9YwYa+$gVBf6Id$&>~WV&dF&|vZuR1~i_=9V zDBPDd@Llz9ZzW(BL62V1_CjMHY|gJeaY9uQ@DwI*3j-P+J4dip09PH zXWn`cLS+%=RrXAmdJsyPINoJ$HUaG@2vW)kLSaD|i-1(X@iLs>$pMbwk4qb`yJe&G z7&`jK4u*nYap6f=E~tAg{Hg6Y1)Xuj3fmuy0UJ0v%p1{VprygzDfQ-H46`Co`VM{QcQwkyX<5$M+?c z+@)xIp(QL?ZBQ#mnvY#iPGm(0FPuY+&X0o&2GoFAu3q({BL!9^erNoCeFEL$q&G za^K&mfafhi{z|s^xn@D{#XM{WMA#5&0X;zsoGu{65s-2YVtrdA2n))iP*Cfq5Cv6g zY-rCPYSc588r7c=8t733z>F&B0TBJ~p>$#))G6Qo^oJX{u;`F)@BigAgM9%6_5}i; zfkfcTe=ZO)=eO6yk;p_>XW_JVn%Bp)N4g4AYd~bvBDJ~qnPjmZE$j^XDoihfyJ_%eOrUO!g`%0PSt31gKQx`o#l%o}NAgbx&XXDR)d z9|=uKW4HoxU}D%$6vdPRh;kE25W0QV={QS^hCeg_>}om>_m84nP|ENH>!y;Lcxy4M z{OAKf;}Na_BJxC%#kV0TQVKD`wf8J16sL3Ck&4&}K_MS#Zg$`c*i z5!+ZMToxMmp`dKi#!m+1H=d}V)`K#X**&=MG`gEK<$%omsAGZfl>oH>`{d5UnSa2( zib6{GhhnL>lSS{-W~IT*1G;Hk=MW5CW8-{)Ff)M`xKG5d91c`o5^|;im}Vwt11id&S*t@%xYdp*djp ze`y2xGZ5!LrC$&@S^oU20cyy1I{nbSnad}S5`*k}VtTYhfaCykZ}M{IhTriH0LP0~ zesDKpZc({X>5hs0c$A6f$1WCNQ)2LN!-=YhLIG7yA_>>M&q}{Pv^!8bn0wU56?$Tr zKY#e!$MCR$@VO$%YRms~?nTt-gOJMvF{wYJ!)Ce+Ndx;T*zXYC)ww77P2QhnAFq=O z0VnI72Qg>Go)`(RFZfA{ewk(m9G~7fNOKnI!5sJUKd0qaaU@niQv%S_>-wqCE4DPE zt9N@@uF8rRb4vd@e#`=Zp8gro^Lc7|h ztvQY#%>kgNe}2XQh5iiaL4ZyHI0b#P|0VRuAt1JB!;{hkdo&0JkY|wf|ARa%Abf^M z@*TAQSLFF6lqrM2O{DcFrpXD=2@D_1&x4kKK)YWCxP}(P>SCl9pdf4@JwG&fu%HSz zKoI~t^K%g9C&SKs`KQ9}55wCNvjAl0c!CLloy8fD^L=^egPp}00COhTon?Fr0lEVK zJB#zPT)A$#fMp-aLMSpe3#o`)>|3F}F ze5|uS17FU>x_@Ep?9Y#upTs%{aK->*A^U>=n00>|%^n#$==ZJr8|}cYfFxg$1c!xF zU^nsB%MXx#g2R9@)&zd36ixz|$3PUTQVF#n|m;ZG}(O(#NY6xm?7N z&@~Q{&l2sXwKpL_)h?O_fuqBofEdS5P)ZDxebkV?=K;;x(MMc~g?!R&D#W)(4GB*6 zI|p#i!oH)aJo6Je1wuEV#R<^D^xwe`cA8+q@W;&q^Bf2dI6c2JFzEY|{w4hmfXGLU za0cT1XY?}zv;a=e@BFa&N%Ru|1Oa}*uj}0OJM~5e+30p;NKqQk-3nkT?{DD;pDU8! ze;WKw!rni8U$a7Wn}Eg?4&8WXAv5pZ?tP&r)wibK#2Ln32~=Yk^3yxKdN5%s4aVL} zj9A$jtG5gyW-2RNf+{(c+;`!KM|fGkkEAR2zT!Un9c|kW6+!wEH0b9kFMkM7iiB)0vEO=q`?J$kI0}~uULWsA8T||D661X-TxCOJ_=D@8;IZGM zqly;V4l&J6Ow`@cAqkTGB84JWx7;R<76i!}#bZD#zFQkL+&Pjv{MwMgzS&LfX;~>N zgJGXbZtuWdjmva&b*bU;D9feAL*cfbJ6chuTu7!tk9K4yv|8)avTeBx*&SZTseV>! zHz;twsCUQlA(i2{SL_0gfG(t9X&_LrO>;wY&HXOEi~Q4x3|QYz!*CG~7rAcsq35`! z%tA`gfT7UVR02dP&fkltU+#Cc;xYq$xnL5o*`Cs0@INN|t=Q#N71)}xwQ zOQFyVa3zT$h&}J`Bl`>)ddl9Znfpm!#LVB5Q`APZr@Ee|lvhz(jRbkk_gMy$U3We& z|J|q7A@;ntgxtl(^kr5V-q9-cPj6Ev?=-pHeu?i4tDpON>>go>5p0)aoM+M6&4&{i zFzmyRsUwJB$pShjbd4UptXB=4U7qUSFG~W07c3_0LmpmoX|gHBLka9j;+Od(`JUTW zAaVUEX+3vPBK5)Rp=CU|VIN-&CFHt+F-yeiJv1G2yCL?TC%ux8wl!Rxh3j*J{GV=L z^(8lqNlKN1%Sgesd|~X0+on0~Jf|zk^OEmf(liGKAuAT-X?l+{q;gM`d9y)$E2Mik z5{C5Z9xYLEL+(4F6ce^(bs4`&1DQ9&RcM9>Kd`{_qLn)Yj#Yp=F;z?3^e-l>u)Wb4d5 zGLo{&@Yro2^PC}|d?)bs8iExK6>Ie?H(gxFIB^`u`{EGtSlFa#=Kbrf=@(#_aB?Gx z7xXx7@q{@b>2=h0LKRm=m2mwf9#cHHwz;zAO*Yp5T5veLcD{w}C|gqi-HF*jV4Ls^{4iD9x}H zwv?C@4TzLb@MW06kO33~16Tdp^-jc{dq+#X=sx#EH2dsdx1uCfdsy@>(6?&@5&>}W zO9v;%pU0k^(J>zB$k3+Xh-m^hrEMX39=(RS^-)K)69g%<^H|1{8sZ{H#(40zl%iLZrMm@9eI=^u);ne zW>zTMF6@hXmC*z)_Hg#h04TxMJ8@M)c12vDAd>V^OUbE*%UhPJxhWB_M+pf3`|+bN?HWO5{??X4V) zi7}4Jf({r4w!IYcV}ZMFfIx4NghYf>#=_rv&u{rT(>tU-Y}$|Ua+1a~{J{m*s$D-; za=hlJTqHUDEUY{Jy`JB8anbs8?->Y$iduFYz*G|!dUT-q*jg94vu=|bt8OA;pEmYO z-U0ZT)+S9VBhi~n3?mq<&+%45tnCgbWi8vFqBGj2YZ@#%(_n}73~=G(s$llwHVV~6 zCN281>&4VRRt`dZ03AKO!5r9pr>| zLXNDCv;fbT<^N2Ioo&08i8|$5#s09$@7tSyO+N@p6R0!rkXioEKoaP0HYE6U z66i-~XciRE0jwy=|5p@3a3VjdB^uYSbw$3V`OpYhPRA*dVUPVxp0NyZHnWeHKhvx6 zDQYeZZ{Sm%7c;mb%SWFkCr7U2;#mA~l3+OiRZ)Pd<#UgXPhaQq%UzHx^|XE+$|EU) zQvM`SjsZe>Kh^~@JGznqH$$G#{C7+QmKti)vwpXr^Ov?ee(bkUB>7q38BE_PAT+}> zIc~sYqP-Mm67QJxSX7?ZZ`-f8bAWL1+_x=Dz4gF2AtE?vTgrLTCKq3Vz*cueTgUSr zqZ)#rUnGY?XCm~7A*$w|en8*!^2aHISphNzJjGc3uRwEV00zaEO@$myb;2SCLXp8{ zDM!aY_zxQl$O8CReIDlg^JUJUQ~7t)sQ~^}oBc!=cNYEu&)8P~6b}9KXKZ7EDg*ed z{#V%fzD3W0zax(W;IH~$f#%HkQ)g=ST08EIqaY3mllO){=$Sy}Fpe$`fN7{fI|u&0 zvxZ%C%@N^*2rl|Wb?sUBH9kRXoMJI?3Do41i~f{$al}33z_M!s-++2BlBVL1Wr0|3 z0J;K25^5#?L;4|*4&Dnb7?Tgz?Tnsygl{|3f|Kdrst5gnrre{}D-%g>Dfl@!Jclo2 z>wg5o&ZZ|Ph{G!n2u&1zTa`zCQzIkH??<{p7{EZ~=;@yBe?^}&L-Eh9u(^vy+lJzV zdpStEfHHuK-REJ^*|-?>Z25Zq4_X(*o&soj2xtlX&$x(ybg}41p^vv705)UkJ_nzu z0r|gOdj7F3)B>suaIyPe@#yz(zaIQ87h$EpN&M57x1fLy;Hus8uLyKzF8cKS4|Zdj`++Y6eKM83DgR?#AjTsy0=}^KFTRlRZ+?m6gaUu- zIDcxD6W=_(#g`zG{Q4M#|N5tve+>p~)PcG!+tlL0Kq=0{`?!Qhc0Y7opd=(157Crc z*UhYkXd09joGs9hgq|La2R*8RzI!bQm^UZ?aczj%fb0PCFO%ni%5Rm2A&MM(^X0PN zMTZU8*gazD`|uwGqf&J?(2P=eKU~4QA$UoNw#zUDPy)^`1r>?c9t-?y9*>{d0UkP? z{3&$7Rc0-}&7Dj5w$2v~R0Vg#W-ooz8Sd7Rj8p!@9<7fA);mw012f+OAat(h-et>$ z^8`cugSzZ|tS`ah%N<7-6aLZ63K$WH4s0|t`7>bi=SN;)94yyB)R(0tXmk$J?2Kh( z-I_WerI{=GZZt?09&9Ip3S6mD}Q4dlg&53M? zUK01h8kfo=dDsIz>Lc>{Ij{+IAAa0OU@{OGJ{8;I->7kaqQR8mc4WB==C#bzpn z>lUo{%#C?uuE<{IcR`SK+AC@oz;u>FNX%1Mj;2V5Zb^I^AZf(=Jbi~D#(HHI2Nd(+ zVcm5Or$*vOw@|Y}BVWTelGHMPR0F>d(&?WNz4kzr{)VTZCrCe`DdxVgKks1n2&V=j zv$)S{5LZzOUU>s3bmy2vy30pm&u7)6(&H!3ZDsgPEgz+kR3+B}# zstU4PlP8|fO{m8$BpK+S!p3gs;rAT*I~~UbBsRy5Gs_e2k7hZ%#yZLXxMZ#FYI5`I zL1b|I{SVW-jn}=c6lmCKW}baa5>9xWuDyu&aK-4u4kQKN9R-t3VJ@39<*tiJtQPzm zNS*ZLZlS@hRp`267LK5GQu@a8=l3Q!WnC8H#_nKn-NiNW8d2`Z(`{VCzplJ%pZD@o znI)uEZxVfkk<3tYcDP4iM{0nGbv|O?f%7YtNTKIjUlJYdir5f`6|H+8KELa{SBNNz z-to>l(K;F3Duo9EO+wiofL+IaUM}Qfv*B(&{ODk+Iy=wF_6sqWTuX`0fUOga*S#+P z*=n_im9qHF&xBrQ@hq+t-CDhtYA}VFE)vebrFymheEC<|; zUw&PzfjPLH_~aUx`7I|C<)C6^=fDLqN@qNcY*yplH<#=k0{r4#i}Y8p5c0@I({DIz zm{1N3ywUL#%}(T4oryNOV(95*SmBr^d{2sS?+I=FM3^FapAmX={k=DS7{Q00j5lM^Gjzk^($DQybQ`W!`WzU#>esRL=D`GW;SL?@3p5a@D zI?Etc&Zv4<^!Vn#zhfiBM8-)I8uGN+PwYKrrS3y3l?Py%KJRNP6rC#11?70J^s-Tn zP!m(HYuvu4>tO%+6HDBFycfBZleiLgVq@#wXrTx03VM^3q;mLmmnpG?Oa~-#y<$Gt zA?sr6AN5ob*iDnpx4N#kveDxg1AJ-ts9J;TheccJEbPUaO%3lpY>^w4b#z$U5#QAM zh)~IM;DWK7vqhy$7S7f$hS0B_Q~aRrr9K3Q+4RDjr^EfUy01c_3YJi)b8pZgxXbE> zR-wA~viR8|_py;{s1mt&Qcn^I^2}g7;S>r$Nxyl>lgZT`uq&0e`53~!D=N)kGaJJt zCm>Am)(Epp(5u>piBVO4(C`Y0SvWcPCR(555w=;;{#LgvnIHbb!%<}7H z(!o!I-&-rQg2DwjRCs@}jN(tFjLliri}OI3@Hp_r&%XTmAIMpWx8!+X!~A zzVXpMC=*Vg+bDK#{cIs+mT}FV!A|F%$fdsM11m*Y%@Wn^w{FoMuey7xV4Q0CAC#$C zt0&A)Kf)PHh6W4W#jz)gUt4(~&ZCh%1(6;NzWFnvQ5+mV7T;jP%HmoC@|8Ghyt z?cMC-n~=21QaY~;y3~AbXD?wYvArZPx6y46@ww+*kso2q!==pYI$SU@T~Jn^v6Z-) z{5(OS?~N&PQS90%2g$Allfl?@Bf>Ld7WRC7Ar?BctVk@~z(*7A6V0n8T9d=`vu>Qt zP8bh@QJSuqWZJc`$1T38<$f7mRN}P)Hxn5S&R}jd+WRQD{;EgStm=xjjlvLI7Iq$? ztGx`ZbaTEMYHbvG^J_Hn=zvnGM-^9Ie-ZcWn9vowjh!I}?b)&DWu$9><)k5ZyeF%G z=Q;fvV(S%gadhbcXV#7Rh95uE#O{bi_i5$L?E3gk! zeSIfiMk`%&pPQD{ytvpkRCJEnW}-y4*11Iyd)LA0@!qtwzTC^_A?7`$ zgcT|6>eyx&_X|3I$C@x<}P#%IrCS6|46V zMzb!?GUwHiyexgk;j$Oo7UzXC-&bkaeILa(a49*&9en4DsN6=Uh18;&miTL7-W+uu zk1zTu%u&gj4eMWW^3Bol9|!EiKYn87|H1S=j;GL=$?dGlXWjfMUE9cpN*Li1S=3h% z-hHNgO{6PNg76BSND#8mXA}YB?fhWdI$w6^(zLf7b;e!w{7kf3CR@os0X4w|kH>y( zQgV96)t!zSA13ggKG`zbWJtIk$lQ+>#?t4C+I@>t!|?6reFW(Mg9KNis?TMl9xE3Q zmauDA2oAF}iV!Mj5crmt5c(^hMkrp|pr z%nrgCE^iO;vkeOc#R~$rP>GuIjFLp-3C%Sgfi!V|eSS(FWT2v}1dDZ{H##a_Xj%|P zakjV5LGH<}17n|F6#t!kjJ zdqy?DJHH5Gls2-=>ksg+nu)>1!+j2SQ9p<}4<}0ol~t;b`BMfyLWR5ifdqYdf&ASC zVeOGc*bSL5K7KNnx33hMS}*#lOQxbj>uiFP8w!N44=t-JFSOq$_F)NoBJv=jQR=zx z%hHw9D?_YFcMiG|toxp^O9d+P6M#OrLIS{F3y2*b%P-34J?mLwT^ZhdMz&g07Hm8I zHR`Q(SRulkX-9r)y0q4KcSDlYzB8Q!I;u=7u?4&=CH^Q1Wls9cL>iWZeqG!SIw5?N zFeO!6nH{5YrcB*j-Lbb5sBa`;qY@s1=rtx_%8=-eXCkUCNqPCNcZ zXnQ2<9W)4QCr&_bl<3Ao2C$KFX$$RCe9gk(lmJdE65;^I*N)dsXi37_VZp*|cDE?G zuy-k8FDXz5K86>}!mW&69H1sekz;DS|5B4jGK9Vr;VFBO%4@t4(l->GTOYtTlZjNy zXOP8^9C$=a?HT5T3cV;bB9+32V+HpnM z8&NQ|*bQqIzpdX@kfw1xop3MK=^gIs>== zG3&}<6MZn^7c_}d)+-?5&20xXi0zA8_r1T&6!E>ZA&6it`0QnTbDnkOJq)>Q0xe0* zg>dE!^dYAtuhJ56Lyq{G88}Xx>N@mB55=TTd)NdK4FcZ9z*@qb=dC+bESA-FG~xIn zB-TFi@{sqVU-oJh`6(Y$U$o6bQ~GSY<+fQkcBn)hyjqgEIK8hq$^)$Xp<2YI9Leu$ zOYfI^)5Bvzs3Ge2dBiOxMDHWwzzZD2%R6N8OI6KXn=$+Y)#hPSAd~W^%1o5=&N1#B z@88a`N~gSCU+sJ&g;`R=Ze|hr(h~oU56XxTL&e4|;;P}Dj{Laz+lE-UZ7jLPQFs-yz5bl|NqQq33oh>yxM zKON>6YxJfFqo5#vc2vnle6%bU*nF4!tvxuv*#p`)Q;(Hl0 zYK4nzKE{-Awz855GZ-wKtw?VU{A*I9hw5ndmk=8#EvWeAy=!kqZxhd( zU~GX9iD?i$$QdK)RsE4>48D={YNMMpid?^^fp?KmMG0+&UwWlGpBp(}fdE^v6rl|B zW=ro&_jHk&D$ZSJ>8ER|&o;*q)LCS`Q3>GrnQ@j8_tvj(V?Y1_! z-1C^RK7O|0{A^dVkllannUztIZ1=W+LhcBy9#b_k-^XXQsFnxO4`*%)1j(1m=MfS_ z!;wfvmy}(X))s+&`idAB)Trqiq}RSYjC+thy7jOl5aL-_n$7FRp4X1&U@d-Kt{?R# z)~fU3ORJJiRG*>?s$VTQzer3m^F$1&thZpYwLw_G<;qHTdbKphoJd`(vDAk@qjKm_ z-=mOgd@3jeYu~EV4;Gg^MEX)bHSQ6)xuI=V8dr=P(-hue&`TP4XU9yWax)>NyA4Mn zEkg#63QTY~PvxmjxLGimrm{^0%!IkrwXRS*!8gw8BawuLHr3O<|6KCIUpU^?kiFJG z)*MjG#bCPm*^ zM%>c_v&PvQe{)kde98ar!F=%UDk@7=zZuPR;lV)n{ZdBu$j65p`dVY|Xi=kmQDJ*u zJS|EfE}w0<_e-T<3nmxb+rOF=LB zY*dF9Ng?3o#415=T-*BO-0)}(vKQ~j*m@0D32fLBw)%8)pBE$BD834@2W+cN!X<7p zw7fKJ(n-p626Ybs>+KqC;?dRv#RONWTLDd~QmunXT&*MBwKeh`aJ|&<%hf!yLnGxx zb4hTh?Cv&Cxpj*6iUhTD-1B=Pbfynlj5B3I)~?;Tyr+JjgHo*FN{^kfdv@&y9}xJ1 zo6}H01X{!BSI6oihm2C`xw6KI(3s^(!UN3oqQ$k!5=L)}R|tEQFli;e{qjcGJ(CCh z*Lc2a2bfKJ)r8pMLDB<@e{(d=S`EpU`A`f6FmAUsb4lWktRaz-nZk|*Kv!WTFD z8mIKk8wcKn7Vl5Uy`@kprC*is4p}ADlSS@Lb~M*f>p>Wt=6wI=`R8lpb?v8~;kx5Ct|P%Tj97$uHa!x5x@@0VVIW*}U6s?O0j$V-;U4LF z=TnnJtK`kTWYQ8Y-ob=qoA)Jo!9=3f_;L@m#srj`a_48zrwhkYCtj3XY{EJ)R~(>! zRsb)QC?Fc#?%s-Y3xoDTZ#CPX-KxQd2KekftPch`ZhIezo5eg_-0w_HO|fMwO>gx| z>buMilf`Q4U9uq?9cobI*zjnL^$x2lP|&#D+gHoXZ_mSR1;*?rRDT08)+B1oz(=;pB}W%J*`o! zx@tDRvS2Xeuv``f(O^|ypJvcpkK>7q|BwSvk0=%)s>yS74U}>6mTuGPaYJw2XnWP}C+Y;=L zp(Tc&Z$B>geG-_M$WGX?>cz+T6|<23A#q+aKOT0qOtCnYDihX7Th_x5W@PZg0VNJa zNk;vfC7R9Ebf3`fp~OyU@1f_IlXW0nFd@G6oDOc>hBmO#e`H#s6jj9;ULIFKeIK`| z4r{qx@u^QqyMQO1cjh}Rlt&!YLN(RpJ}+)*JbfW(WIXVW_2tO%1O{da1my`z0%d#K zybWvUr7s&8{UDhhm zOO0{&3hiacW#^Y^fV)J&GhiAV)9y?Zhz~-P@$HEAW8=1O^(AL(6I!97kqdkGY2|Xx zU=-i_;n!9h(18_1`@xf&YUq?iNF_JwQK#fTxqN65QI5e7kK?)>t-={65=Jg5WOUmNKoK9^QLHo$b*NCSMy6(*3GCpo)THB<`dmn zG)vK}z5a@kZ~Bgz`ZbTXL~1+1s5k`V8v?LzooPh3Fjsg z^tUdP$aR@e)lw+wzIo`|5Z2H0;&OoSeQUNS*R8}!aow8n3!lPdr^fPB1Q+ftwT~Uo`7;lBu`FL zSluEat{w0w^GzaM^H3esO$n6{b@_QQ2Hv_gv}tFmL=Q6Gctd67oG*TQyPh2tNp(Hm zI6dFmKhiAMN%EP(_S>_OO*Dw~<7PBI8Ud4d;l|~h?7;gy(d$It+3z=}=ZtbGY_eKX z0B{Cvd(Ikk^av$0;?OX^q!iTeK)%pt*Gg{5{izfm{Rw7CXLm}Wi{0{`?~IFd;&5pU z7Q#X<&W5aCm|wDuI}!pphW*15KmqG!%PA1(4@{L8$B@JW(=(1XIbORc%yR3`QL==& zoq_ug#I+!&$j)pcnCH<$_@L$rLSbuND00H^Y66o52698yUnkzinSK@Q4D`E_R{*9cY{f-DHV;eZBs(sspRG0o#qB)F z*jx5Gmmj{CZ(TXAYq!PBCn!DHRNhed54KMJ95}v+OIbS0f*ucdpDH0uV6b_=!|vr! z|C>m*cxWo7_KN@Jra`(NL5lA{f|DbbXc*}Z@SOv}8isCBlLCIgJg(gp^_Yf$O=4`I zXg|#FC0g&6+D0kWRE3)89a&A|&16Kgyv|U`cZp89PnV(2VlLoUk4PzSHCh(a^jX^v zWTHwCXKh}YGUIgaJCJ72!?D^Jp!wih7`OT_(ZtQ$st5pVZMy&cLMXJwT{zSycaoi4 zl>sbg;9cGcdnRB`A&sYR5y8OhrH*_T)*Ssv`FS{jL9|c zpb9A_ICGY~_Q2MB5qld?6YMO@|@U9cM1~c2`N0@DHO9@NmABd}@I})6K)RdMVO(@V%4)?X-NOS^4x6vKnJpR{xwR;1-Z0IE>HWnRG)R$c%p!6NJMbEQZZJ z+5(}+HY*?aM;{2DEA!L(a*_ixRJmnXi9Ke(hmsM?LE!IA-Z6)Ktm3zEJNQP}D;`!N zJO&K#4q@Nxct9qPJoKiSYf0nyZTho+q8!{4jDvb{Ri1C7OdZNP4M^O2Rk~#TgzJ0L zfEIF+Z+im+o=$fsCrzq>IfH0F#!C94At$e&P;P(LrplLsF=c3vl509>X_|fR%>Z_} zdi53TA1COHQjHnP^M*l)?Dik4p$Qkd+SRi#=je^l@n!t4nW}gK_qBp^s*c&6CB#od zy-kaPAOHXZ01_zP)}zc)^==ewIxUP%#bG_No#zC;m!(lq$e?YM2YeoA;amu?ruV!Q zvd@@Rk!IZuRdHGcd&u3T3Ah$c%BCpj;!7NMH?{9~9+I;ru4-~&k^Q-pA{;H>Je^T(W%?J-w_PIv34{OIXig`G#}dYM>43_+TPJv^tINC) zJz2tvAt>~RZh?p~ATsLhwS`KRHo&MOZ>J{~^n+GW|N9pwzk-uCwbGf_sFuGu6klMVgAv6KbU(I3JBzBx z?w{7D)ton7)HZAR;`d-IQ)bsW(CyIW@b5abw-n|Fa=UgySq;7jUY+rwmNE4Ca%S!= zLPul97Lxw!QRyvf5SAX7kg`n$=p0^$LTvs2yk=-^l8(@_R zn?$HI-BDEU>R)IBS4a}M-O;MDuzDF`+6Hr#T~m!O6Y5Yvsp4Ix(s%{Tg;ct;4MsmY z86*!&fk2_qbhGhW5)f7JdCQJ-anD$oeY+j0FtZey@nLad|9Ez2lXs+$Biw^?w!N9M zINH-&fAzm1z8BuJsvh;r>NhL{Kj$3}rl;qe;!PFHhX(c1t|7cQV<>I&+hnsRI0K@} z>2`p?NN2tUzxw7jf|9xykb%tHk|vR$*MuANWF`xC8r>^%%>Zu^9=W>+8zeYWB}I7b z;6Lhx$2T_YKhz2`7WL>w1R@m$@Y%T<(|>wwxgZ2= z1n_0xaccxTP|8A_hC+)|6QAmPb5g@2>bGs|d>`3n7>?cj53!F*suyG1Wp0C4sIaWo z4piQPGoVcXpXWXzehi>!MHwCDs2^|Qi4yC{5wawRy5z!#$?VSdaLbLf z010Wx8dQ6Npr~Yc=@G_re6UdUJVCm6*Sdtp?h%16TqJ}(GBax&luLn0PxCvi=r?Wi z%kk8@dr;Q^Oi0BdtG|249ils`G3yp9os|G?S_ND(+1Y-IKT849vZ$zUUqc;z+2Smu>oDS#s&>x65B&0#TgL&6 z$oMO1n`{)8<}~deHUXc@G6{5(iwP5=}MDsk(z&v)}-HkIP#M)uZi= z58}=t)GEilmQe3_0m_6<;=KP6Pj7xglf-HZwV~E61OKLMa&w>9H42G3J9}OOpbw@V z^K>}n2CfGmegnl*pZlZL5;y$uIl%`3O)$Xl#jNkJ=T zf~QmAob11Oig}{YgJ{ga8uIXkW|ewoRN`t@n?cqZJXzlDj{Gj7IU19 zDJnqr%AoH%7p&xUNz5_chl86Vn5iLF`F-S1-A5!&s$<9wupk2GO_qf^wd1FYxie## za*gva3n7fFgZvR|a-G?vo(~kk^AldJbzpnsLFt1&pSOOK)o!IX2>OV?Q;((S;_3{n zvpAI;@QQfVtoaR=QM-J%AQzF)QNLIu5=0r4rteGwb-U@Xg@fv6(y6$U4$sS{JZj%7 zaR#Nw7CC*X!#6+&XMvERna6?BEZ7C~Wu|MNL+VW?281K}?T~%8ODf`dt$bbaq;Fgidk#eHObnfwnjpVSF$@%v*i^5-0llDbG~)kS|KlXGgnN`qc(4SnK{GHbR# z9gVn&Zb-l8rvEbbnG^Uxf-CKhdq;J9g)Xj?nv0~RFT%qxcmE{3Ur&&dd=C>=SFPQ! z3~p5*$F^W2eeKC8F5L>-+caLX`gn4RWTw++xJ|ZsYy0x$<;xOtk4k|X|wa*=Lb@x<1g4}fb2_oHt-lCoCJLinV+HiOJ@4wv# z=t*@7!}4&5svhx;B@D*dhsrwkg`<_i@6#TnBtar(g+FJ~k7vq1t=^4tsXVIU zBXC~`!-f>C-$fd3keVtEKJ52+0`@T}gXE;ux?9^c)Xt~oro^g26z+s{kSjVvlClSufYprd_MWt#>Qy&$HzyWQuQRdy#-)^Ib$4aoJ+A zngS0FIQ3NR3J*z8Y(l8GvYb|Txn1dtRKiwe5L6;EM^a$@eH9-7ZB!WZ1m#Z~-0faM z$BCBP9Iy94jvoSHo(oc*q>wtH&RFTZ%nR1OAHB|BN`rX_dMHOM7r$a6XV}>bp_T_1 z#c7vAISEQ(nW8iOwJM%-%>V4}sVQ3Fk6FIEMuVgIQoTNRj?-u_h?EUt{F!gNz7q3; z4vo$iFyD1d6ap3CN1|#nO>7>x+ZEgBdkUu_H?D*FxUexmI($mQ5-Q#n80R0Kbo(F6 zF_3v~VCtDcx+oyL>rD0ySob4JDIA+#jZ!R)!AE*pOMjg`oEZg)imuS7AE=%V;o*&X zZ87{r`TWUjUa9_X^gEs3r;m$xnhHRW@2Rl)8iF(k-z|cibFCOG)F2|@8LotJc(7Nxs1uvm1|`7o=n{B;K#lYK!E=S#MB^ zKSVy{(COTtP5%JXm7h`Iq42}Vdf#P5&f)xcg4#-@D) zj>YW(zwb=lM0USziT^>=w*{^u^pYc2LOc_-9C!9HP~%NhD0G&;GS?<8MtK|V%SuoX zab0sOP7SG! zj-j^_)&FDM2jdyGEePJ^bsk$mN#~WgUcsy@8Ya+g%#UNf@%hMr!t*$J8>e1M;dq<3 zq3Ig|Dw=n#5b$WH%&)!*rU*CMVYcew`RWxD%afLeJ`po@A=D;Ho7MZp`eES=B09bf zqn&=;muR9$r0geJV`@3E7+@XZ95KNs@J2OQHwbBs=||t;za}+wNUcpYV6kN1)k8I7 zM-OI(uP*{&Tn6%yI^N30_0yUaw5`o?Ri)_5RC$?L(cU}|0ggNTY4o2d(4>Y^0aEnfWV+?aA=*9Q8Z^IuzNHsMuXGc68OBD?& z^HS6XDzd*i*z#D&%I8JL3xRL#t~^#@dqKFu+;QQy0^Ma`t)B~`?7;?^H; zmx9pLv6x;~ynk3q0>QJ@HM8vGE%Su_LS_K{pcU$h)VOB zV!(t|$tn1(%CkIel_Q@V6&ot?9s+<64Rh-=i(;2iZqDs_hdWGGX4UmlCWEYBP2P~H z+FUbr}cUzIPSU(Yud*srSNcS}kBqn!)U7!E}1nZ_p z{Vl5mHpG8i@Rj)WU|~$5J%X=oQsXEkf5T){ITmE2jV*3Yf?Y?@PR8f5utqvjQrY{?S=bIXe@D*?F8k+AMw}x2%XMrFwk$4r!H`DUjFyN z?k+NTK&p5SfJ;OpNjtJgC^{Y-u2lO(UWw+iQ)0q~=0xLz*fPCs?cDC;L-NGeuWEKx zw7A2jnZ`@PY70dxLea~H?JP$NOK${O;#D$2XLbVSFWCp6@JD552VE^Shdh$ry>;)cAm z=8|MocuBRcI&@UcD=EfOB!N1$v>v?&SoCW@y$|rSXcsthcMJy4lZ6_oQj3ZyFfu2w zc$Y8w;rJY^6ro9om^yAC*T`zvGlUDvI=+1JkhOyzmnbi--nH?z^HDS=is0z|_0OHrK(WS|fK z;s6r)|Z3KZMZxS0lgxPqKq{S8u2d+JbOWMP zG<2F9wqQDb< z-bGxn_+&t+cK_Q=GCt34QS$2sA(iQ%64lMhQjQ_`-9X%;maXTJMl@ISl zuP%s2OmN}yp}S5wh|YFJ;rR#riLdh$m`A`23ay_6mfcIR0oy&;9=H9f#!m)GX<;P^ zl)0E|Cm7Y!L6FW!*d%r9K{a||4YV2F8ZTTIVyC+fD=_e8S{v=12TbOySG8$k?)I4U zZiOW%D}gkSz}1<1b%lnWT>zH2Vr6w>RwywDo8#Ux6z|jMX+lFLwsY+n?*T}^NLoBW z!OvJvB^cfvg@|%SbxFY|MA{(ge zMWaAPz!b-~ThYQZg0uC}Z=L!pvHlT~p-GTDWIxcOwXDEF5W)=D3L zT8mSp{$SV`qcfF~u$?lue!JsPowtDf5FN!zFmXSlABw1$TvH+Ibi%@&(soU@BjI+o z>>x!?!-Bv6yJQyh$@gr4M(GF|5?N*CC|I*wdPlWpU7|&qv{*&pwcUP-cid)=FBFX; z6?i{JnkRyyV2gzV6G3fHFsWk3J`0{{S6 ztc-Ju|Mg9ys2PP@>Sn58oB6AfcwmF?;Qw{aq`D0BSwt*9y!@l zQ@q{9>QO4?FlPkQ13W|*#);AUOp)KN%Ow|^J8HZNtA#)>;|W{9wyC4U>6?0bP9AG? zRH!lET;OXvXD|1owOX7Vv*!H=1V5)cHA-~vuSLj_N+HsaI+_GXu&_)xh(+2Bu!IVJ zX!Pj!68=P+je7v~Ss$iuBS1M;?;v3(>J{)DX7N=??Fj)Lvu(p>QH-6hYw3~*F5j6A z(2V=xb1bMGgAHo&rBN+Xp;dTo7kevZ5gqXxIAz5|oP5xTA<=bv%HFDz336S*Arg5z z*U~cKNKPOS-e1+TR#OXx^2^KBXJ0O5UvxM_#! zEg+RJbYyY}{%+0B#;GTtx%B}dfcB;mfMNd%YzCO6CH)f)%Vhip0RV$oMfa%c&9 zGpYdgN0kgh$d5;V*fLO)bEI!-lxd1wcB?{*{k!6^D43(1&hR>K;cS zrcD2?gYVHYaJ=uO>)T5>c~Qx;ru32y-wTXlBhfDk=(n02vf5(*f*xZGu7^|ih9j>S z+cP^$Ba&~Dh>Iz>x|I=ZumAuI(_kch(WJW zM#uyB=iThLG4a(9-*fPa*6w&k zy~$DOK~u|Q98W#9WyYqjAgjpJykxI?W0qTh-CF-@#z14?#FQyrf1|b9sz`GCv+iGb zX+*P*4xi&wM^O@NEho$9(5Ks@L$-P1FfybUOn6*;SP4VyN+Fgy+(WiKEmgl&XvI-k z!5061=&n(WoZ!c=2E5<}oae?M2Z+&jNB_>8wC1z@Y2A_iWIJM|W%5d5u?zh6K{>HWfsCd$wCa@ck{C346o_YCi)svCwqf9$?`4C-oy?cD z3!reXr~SU8RGGeoyTWk!F}IH=3_^9%l$_y}$lh@iPq4Wu`q}WA?dfXvwrwV|`B)F` ztSpbMR1jr7Co$&1$CpdtNwy1c??<=Voqls5bcS=>Iy+YDQ9-exC^0;77p3=6Bq?cDfXP9<$kA5*0m6Z)H0pIUBq{w%l;CE*d?r7ez8vR_JZl}v}x(zbOmbZPSUD-2Fgx4E!XM&CxAflD1#$Nz|n zi|6rxnMrU)%rbfYiA21AyuDLw7t~XU^<3!NYmN%cMsk0m7>54DeFKxwAubt&c)6vi+C}+<(3;Ux1hk1M`vojbPV*!!0 zg3I+X@1^}h7R1VP&n~A;&rt~8%p)4h*aCyt8CxpvaHn7lu5q3dXR#<^xKvwsTH2-1k z8JZ|Zx{0>&jRtig)k%^5@|&%!0fX;yt9&W|0CyVz00RQc{)rHN%zkbYH9t({xUFBk zg^96@qXxMLSVBI*0IS8)ytF)-_&$6Hx|-|5sap=Tmvxpuq(zt9Tsg6+BLtyMLD)Fc zZ7XsybQk{};`~g@_?VNiySbL4)WrF6={Csg3zF4N;Xxqzg>6&Uxq>i|b@HQ8f076t zRqZ%_W^a=rhD#=7C(t9{rZIS#awB{A=rQLO$tbDM<2Oksf$!*p2;8X+ zt=%L?OHHVveV9G#QTL7?Z$3v+!dZeDc+gNo#b8nx3DGinvh%UidpnSfZLbcu|A|$83|? z{_qd~@$~y5pPy4OR1B`@16^sblw+)h_YQbP$GFlwi5*hF+N zDkWdVtmQR$R^pPt+DbuMhFh)gTHLKzLOI1hwH)m9tGIs#uWK<;?zx)++--bh}*%NnZC#Y*Dd~ImL_%Ip7k- zmC@Lw4Xh399^mYX!=qdB^Z@x3Y!@GKfK#zIeaaZ~rfe|B z>r`F(#1fflMFo{(ahd1Dzby9M+2&*<*@mpb@Tcv-9!l|;2gJ??8Uj`=6Q}p_cNhu} zZG;lJXB7{4*3|1&C~Vw2HzMr(+HwG+Q}`WX#; zw9n9Zk?-(NyLBs`04(0*Z_UWjo3x*La>3QOzj(Mjax`b zF5Wx)Em(RwX>(z-YSHD-PSmj16QsE&z+Yeh0b+9i00RJh9PmE_PKFw`jhe5Zji}?W zqK1TkRdsc;7yeMVnCo@UCtuZ0GB#mLWK%_8?%TF0)qgt<;bdyvb>S@)7SNpwYvvf< z_UMXz{UxajIya&gY;#JwAbD|W!lcvi5k!kTDpR_+B2E$k7p*td#7KIC0RIrRlC5)X z(%*nJ7%T}{r10s(09TA07oI9dpF-@Q0i8+d(OK} z!|e~+o;(s=M#rqr8#!bSV{?HxVh*uj9`x<-u)9F$Og>$BVzHY5em*Sm6_b%B^8D=%zoaD$%hDRY+D5}XP`Xp zg%SeD4tpfB*wK zMF0Q;0e#GRY?=WMM2+>TC1h2_#gDM)*utIDAYaeSvnZkEjwd4{U>0 z>af3v!T-i<<9tN^LMkZ#>S@B1`F)zJD2pg?S=#5e1eQ;@*`c`A+Qgoh#-Y|~<@DZH zzeQf<0SAA+BzzF8msY&L9c3!A=5n@Em%BE}WWat%6@!orfpZw_pqKUV0}#E9gq{qj zn}>!3pa1~nSO5S606$MC*fHc9^I8C!^t<*4OlXO>7KZsI5^XMg0Y?C09evK~Ffd0pm0h{DvX3&)7KnzoWN05?#9)n58`;`oS=wMX z{@%v4EpwP`-R2K)a~5RVrkKL4He-TfNW#~{NCZ&hy#zc`>X_W=F>Z;-52$+g}Vf)j@i@{oz%O(zOTT@ zUwEjN?LyM-PnEYtGvYo~eCb}w=h-Q~fr-8Nz&>(B$W8`ilB!pbz0jmJ?I*6BXPuL~ zA=@WqXfCrYKE%s_W&i*K0H(zN00RItMk}=xw&k$2A*Tb_(?hLRWr&6tb3}hMmKaq@ z2(ndNt6Pa5r(;^jbpG=Xq&iSK14^=e77k+iF);~Lknwqa18}YxQX+w32_WzZVW%t- zRJ&&zNbqUcjYP1bk>M$_)0Uey^_)4Wm5e^*hM~6DrTk`d$4`6URX8w36}hN&@l+;k z-)PI_Gd?1}(o-a>#*5jBxk{F)ba^ZkLNV-5*~J;?S6h+qL4wNNJ!*XrF@l!%Apf&J zL5sIN%;`(v%IQoJ9qVcDObKIdf|Sg}M(oi7!h|eAStU8ML#TV?U_(o>u|B$1@=H}L zCK8a}gd!Z3@V@}Nw`lk--eE7|{c{_!D{&4F>;hb<0&dtLO~tUfp9q^LGz7$~IIVJ2 zd(->547NWKlJ-o}teo$Jmqxn59?L+>?)O>n+D`1f_MmO~!l-^;3Q zs`m90ko8NoA^a zn1DDhkWXaWN~PB8KdZ};+>x`NHsk3jRYbf@`uf~Rbdmn_Hd#n@^{|5$_acMeeDgi9 zGC?-uzh(^AC0lg0O-q=hgoVR!`ZEeJ1;HmReInwNO3lgxErm7L4cPUuL?!Ro zM}3f&K=!kOkQwrc51!v4x-pq}-OcEn9?k9prPDQ^%4x5>j*T=a8J36}M!FN-eAPg= zk4bT{l%%Eap3kGtNXeM;IpHO85ACDu*DRNxt2+1;op}Di)Nc+GQVAHAx3-GM+ilOs zh=9O(aBzwfL9JVRVO}P7Gueb0M3+BTSiPiM0vngM`!^y$39X<2RQ!Md06M5HUuK<9 za_9`buRb95VEDKS0i_R-#%jAnMc7o5h>7O`rRvE2u`5Oz_MA=y^S$O0+4fTp{)U3# zoWIjFHu|2|UZaF}E3D8sj~k!pH$Vc9MJ8AL(HSDxldAnPzw|>Wq4!-imUCE)!i_YT z>(0VoY7rEF>MAV>*ML;7=$tj0BntDE^Jtn7r&Z&U!Ss0v@!y-Jr})#yl@eD}83dgp&c%NJyR+Aa%r`9*6aJY3K?yPhR(zVYn^i~tQWd)pPgI_M&u zi%ca$@~(MQ&X!BGH$Y62fIsoizt^SwR>EL^&OiSE z%N3``B1C+wg6nPs{HO_Bj=k^GeYZg6)x_$Y^V*Z(i=v5xf*L&CR7&P~gbz->JlPFh zWvbTumRzW|^=P!dZ-nIOgXCx1sk0_=grsh6Qx4s&aV(#Y6>Q21nwYWlg9A2o*)N~?h?R++iiIguzldTA$Z zD^z2iwcbITk&`x$7b#{DXm&(_hIDfS1_&GY98wDi)h=W+2?FxBM6Tyi?C~YfJ%}di zM%c&v{YiB0<7y*zW6sA&-1N@f%5}Z_IVbVYC%srI z8Y;OqXimf_qk6yQIbzO?{Y5Uc*tipx`E`4Ak2jH~j^v;`hy}lC$P3xE0Nc4h7Hh`g zvz5GmOw6J0ZO;E5WZ>X?_F=z~37E3ki1jma(#M7TpgRc7#s6uZPJaMe_Uf8RBCf6Z z>^`gZYA87}4_ir?EpROd|5L}RaQ zjF!;|>otnfi~rUp5Juk!+}F|RE!s#~{|mj;C^PF_ezDBkMn^ftI3ur;(#HT;Q3CPT zDcn!osi*2s$0V37&=s`r@(%?HGQn6`sc1nkG%7g%&^f7XWY%unaIK#mt6}{!cV?iK zI^(HaqAjxxra3%MRX8Iv{mfQR{weD1Lcb>w_;-fO_MthPzo;>STo75L^rFip{tS;w znzmDJJiYl@_z5>Hmv5Bx9HM|wDux*^_4Frz^vJ1bJAoJ}E`Vu9b-#CnweJE}X)uR) z_Wa@&IDM$&zDF(mK;THN{qfR4?Xmk;(H-WE;_OI(0009300RMA)#xk;$y*eLc7R!C!}X1eWI#}N_3Jii2Q3o) ze?WuH+aDC+9GLRjGGLzjDsMqykb6U{*KF}Nw)DUAc8%>2_EeC$C4!9W3B#{ow9tlt z-aYv3?V$2Jd-C8g7{U3)VrL*5dg%;!wkK9jPx7S^KSMRz;3pXL%aaI|Y?l*xQB1}VQR5YCfo6onX>wCd z0ik#fi)6-Cm!MGi4V-)5$Fs=8ygbHix^D3&#ec5;hNt`mjf&(daW}fFAqOc$e)GP*#ACC|Ai*fxD)ipYNw~HyqVP@@j#XK#^ZAC46I*&9JNjA-ITmEE8Cu^ z7)<>=@4kJYIzdD%mZi z{1yd(8+D>LWqbBTk9EJZ6(;Qm|I4_Dt#Y{X!I3RA)WV$S8QEVQPv5K#GEz1WS^q5$L{p ze5NJ3FsWh=$=L=DBlzzaaM-5m^}@Uj8FePv&lHf#fri@Xa1KR8y_-RLmfv&NO0K{; zk~;Vtk-k?1&ol6TuSn6dB!jCYQgJ=pO?sd@fpwM4&u2EBB%Rvf$k3RMpf2%~g{`cov4M3LyprGeLS+Z<9smJYGJ@_9-rJMB z&fVH!#qXoYddqLXF%ZeE(aX5NGrL2Z#ADL>@p<>~O>9`j`IrQaJ{kT-Vn5dbn%XXE zm^+6V)TNJS=&BdcqvrSQl*30*QIdw%ktv;UfM4@%$`mC!-Z3()ro;7sZ%OQnOzIb| zyvG)W-nY}Nv9Li`;RtWqviBJWvBzu9hvd)@a=%$p#`OH0dn^~fNuTYnO`!%;LoGKB z(V(2$c}Kl2zhimTI+&D{Wh!C-KF``w-baH!Fd+}lNDEZFsHrP0HmH8S7a-s%{n%1%_41@S~=vNI^$_~=z4JD9yN z5K_NuWbdlv1q|p$+5#D?HuwcCG%qovyV`-bx@78c3TRyzZsOj$JtFD=6Sap|vSpwV zeXmGQ5@B*SP8L_S(ZB(cm)KTV00093B*Xf^000Yia6V+kRT9AZXMoVUJS1Rl+)a^B(qNcjFD zK4#Q-|nz5Edw_V-d*>zBP*mX*FZ*%5;1$tygyUPv>&2%prp)jo>~dXbH0V`e2}>N^dE zfS~iUF{{92RS0ol*Hj1f%B0CQxVceS9W5JAx8sVi)X9Rnl;73rNK{=t8D3(upsfk4 zfYKUJ0JVdz`10Y?=0m@=)V}5U%*1$6xmTBQ7&P`&>VV7=zPD1{zofis2_3H=8*$xT z55>BCj$qR_A@xR{rEK4V@@2go>Ouxi?;I`#n0nK2uCvoaMoEXBR6e761I(i zUgM!Rd`awsnB4PF)XD>jHYuD+OWQ+?qEW)Wt7I-%M81NlHvf# z!e0$2C{c(Gg8*Ir3L)-mrwMOPtRIjj2BnaSyR5}HzM#Ji#hzEckv!z=%39{VR?_Wl zIA@H=2QMw;K~95wTNf+ZgcOiynlpo^dk@txlR|(e%QFm=I{?&Q{@;j$;dW|K&xV~p*P%3nRLY@S>PMvgF@lHN7VM%%& z9=(YA3T;Cp6->MhP-<1IX1pwFB>ZGo_PEc`^=~m^yPtooKltY>myVfEQ+HND)*##t zMT3kEU9dY?MwR@I8~GfHWV@#Qzm0|rtlgfw0moc6Z1>a^5l+C*`|tn&JI5w`s#@HZ zWKGtD`k~n!i`P#v83GOh{%O%sFf%knfz+xZ8~ZtX&3~++4(mgOV=fC zKdadb6>Fxq<7WrX#A&RfX8Ed`-1??3Etkc2j6X7WTw1M7|q@3rb4~DWusMnML#?CNB6g_&weWFXEG}txY{&wSz zh{0CkF^N`8BfKUK38Xz2*Sm@Cib<@17FxtEfsU(aE{(x_WBVM#;T_=o8d7FPfypss z={!p^$-z$5sz$L8;)kNOHI1E>w9||?87nRosxjNXx_k>k_9&c~SQrm&SAc+M-e`|7 z!bXXtD{+zK7TA7*$T2*3A;^Ti$(r0LOv*$_HjY2#VV?pH;({YsfDr`Y1!Tln9MM7I zqd%dWJ+N`tT@~wW5-Rwb(w0O*vCj^GCN zE~*x=wNNMiT-4@$Xc7QblHqMuUAYS6Bf8{3*=8<|Xn$oJ_Gt>u0|C$SC~6Be)2nim z@CYXV7|i2Q0sDqrjFU|!S)$hrvVf5se2qaxwJ<1sN75pPxA?Rjs7Nf15=PjjYD}1D zXQXLOD!h&-dG7V!G@`Ia148eH5A??~1jeE{$ElGbNF++v9F~B+?MA(`>LoKKcCO)B zH|CZ}sIf54Zgl)q%4mEQ78bdS)G`&>+km7c!yEu3*}F6*inVw}l~_7!F+itF>x z2wqU99HClmjM#11{+%;zD4l5ZoqW6$nzd=r~8_I|R7Ax!^S9aGB1^t`Hh+6aEp5bx%dT}hwwI&na_?1e`; zD=qj!(Yjs|E~Wn6^w~9F>>q*tJHn^VUhg*g*W&SK&8LWmQs#^U&ng|yq`N4_LoGHq zIs>M0VUjqY5McX9Gg`b6WU3wJ#3YSJ4Ww06Y#Pr>-E;Q0^8IP^2WC-_!n$cm!|WYe z=hq{uB6bp|vln0h6Wx|TIJ=0{eCQ}VmMTmVxy$40dLs~-I;0~?nx1}z%P%TJ^!WQD z(WaQIxC8f)da!;GDwgxvE}am9In`BTcJRvrDWjR6dkMi4)$v&tmjL>}RWQP?0Tj*x z;648D6sLSD^l-GwdnPpe4g391MaET4$xm?CG@O`KWJ=o3;lJD}7`r!$koU1hwuqq< zhfX7mA<~3!CM8LzMDvIU6_+29>20keU_aS+$duOvv*m%T=3l+cG0o6Mic2G1N;Wg0>Cj$2#4-aof5jDaBkvwC6+;ZLaqL}wxm?M4Rp%~leiz+nkT6c6tsy1FN-6wfs^`qdXK^>4>{M4NBp5)6$9ZFrckq5xk)enyt_9+I_%krDjB zBK$Q)i2|bv3Nraxma7Z{W!nsfzdaCvKT{7 z%6T|0jrpPS0nvpl#PTpyD`K{Bq`!4(uA@hG=0I~HZ$0^xv`0^Q$xeybrhSHaDYeE% zDNwD-hCcwrBbuWH*TFxy@u0?Hek1T>B4WEk0#MMR_Idn|hf?6=$S;_@8#7Z-J-Z}} zMS85Am3l&W@*bsJ}IfoOE z^ba$UkdvPgH$4EMm$y~(%IeWjqy>J8y+J+U5Ys@I7Y+VG40`I5f5?;xvldJf#e+{q zT!~&mGR5DLN!I5_%AXjC^y6tFBxFY0ie1PVCz0p-<8poqZw{<1$%8p$S>iEJ2L#M6LGH?AeMC?%MWJi{aQoJ9j4#APLv~AfCtREsCn&`WnL(_5E-( z&%zP$1I`Z~pV6HXFxj!>0iMN~P%~5;I6mct5`{V>!6<>h{q?SJ6<`ArQP}=}5WVM1 z85e12s9Tz^?ysf>}) zYs(&PK-19H`V|&ggI!*a=q!nuPANTq>`I1&^Y-L{Ar7NE2bE`Vuu4{voE!*}7~xFW zZBSo{AlMYG5HkzVMqr8(7PuJmtor9O$&bVL5v#Xa9C561O{mXN?+yW!&e!F%K@tgd zb2o?*VLY%>Jd7L=Idtg~tBB&D*f4y1j)~|tE`7-WT9cX$qP!L)Xc?i!{ia2x>tjDK zwg6&4oxeT-+t@q;X-tQgB>u6Zk|wYBz+|iqwECfp=HEOusuEmEmpjk=0k#`4^%Pjh z{BCQJL2*9)9uCGaIvmA7a}foh2VWYv0F1+x4?rBGLdBGYtx7@3T}5`xI-f)B9+sZvfpWHi;#NNVK0m*VHSiAv=oFpG7w-MwgI6f}Yu%&thYa!6)EKLS#>~Q|{ z5ENU8E%ix}aM&o$ms5;4nT0o%C5_Um5G?V92%DL2Y{OZqEC;+Hc8NS1NvX5U>mbI? zuQ{eI5E+-svBt=yvmSfCaqEf`ykWzV&>T>M<#alQxU=#~y+z{7qU}x<+L~IZTg`GD z|9CFkf}@fEG%&vg8DAg@*^3+lElE6kn9H^3mBBUjh^)&MBlDwPHNBHoBNZ#$@9+YG z@Usy5Xaak*n}pXgP$|kr1#`Aa=8b**9F*TAcNFKY9ai(b(#+!(YS^f(bbHZ#p#8sg zNl?LkdWFOVyy67=OT|z>6Z33yGeDUqa-F?x$Lii|Zyom8Y@a4g1%VP{La-uO1X_Ii zg%9P7Sz7!i)z#;@2_RDTo7U28CqxOi#kINkN3QZ{;KVa+^3-ikSjNwECr(@vY zW;FW=$aW3>VsEA_F-+SMHsEpuA!JUAc3svA#g0epp)<+9$K@uuMn`ars2#20W2hrA z4BVKXL*7amuB1z-)lcnLETX_O@bW89M;jX;01Nt1000ah=63#qE8IhKPn;cwoW88; zJy~*sfL_d}25`ef4oeQLve&vxDfnV8?Birfxq%^pqAAZ^?dutf3^bnzy^=WU2fQa5 z;>`2+$qPqgD-MP%tCA=ZgtlHUfh5|#s+r@;F%Z8()(R=b8=X)8fS&b%(+15a%hZ!m#R8)p8(@qci-74iK<*}#tA!cm zNVXNw;CaV75+L7c_t$&r24d*9gFWp2Nf@?9-HANv^rc0{#9hxUn=3uDl=R$HXvjc$ zW7*V)(l9kM3!UgcGhtny0J z!lH_XZk&Ym%xL&76d&U2nvGk3jrkTR!nGjOMa`ahl=KQ3a)|0$44HmOw;^_*Jrp0a zR<>J-Q24N{>ScD!J$zcugevh>f%Dk`RJRgcWrHQ(`M(jH2`pFEZ*hLu-WVKM?h>?k z1kSp&6&))qlZ%=R=GI^zP~MSj3SA`};={tOb$!N81>)+jE}vl9BdQebaIjxPqu;i6 zFb+!U_wY%1R23haP0XG9u|c}^e_`V3U>)h*TmW!=rABx2Aoi~rN9I~dfjWks(m@k% zQ~tpiK-w@!pjNymK4b*1kWzV9mOJ5+)}l(;`=8JeK$-#lKbOy#NCmC}x5W8QS*l#; zI9%|5r8==v&hP6jP7@EhZhMZ5CzA?r`jH`6go({$3t`6ij414T0p2ZNVuck8Ng~PJ ziQlp^7xNqDRg-2MKV@L`qNEf#HyLsh?a~6m2(P};j=V*hqZ#xh^%^&iSS4FTo6I0W z$7hvm`B>c5V*(oHrFG}?q$1~ zhFL~M1CkG7?##wP0LWRIvASVW z6RG)WIk#|4Y)T8J5rkC?dv^lR-XbssG#7T|cjPT2n^G`+MAPu8steI`Y-|I>8uj#U z5oUrp8AWv6?@V4ulZb*%ED^Wwld!6=Ifw%ZjsXbVVqya>h>;>%gH%Z%T3dEM(|ZuZ z>SJx%zy*KNnlAN_RUvRnHa({mv|th2$%Rh8hz?O6njOqQy=0RS&D!FuL^Ib>DW88# z^|K9T0#mbO%hq8Pd%euRJ3E{{RSMQi(vBsHDg=5HiI}{3`KK=2i8fn^P>?m9<$&uE z;a!r3GSvMKq~~@EVKnfF6rBkJ@o)pA?@(l8xPX+gPwCY#Q1>ZR6P#Q7EWNE_0otA$2c3+Y1vUN0qXPNixtTK`)3v{VWm)B13DZY$f#%BoLVxM8Q z#gW2?Nb}ODemHI`kAEA4MApItr=_Fq|&Paw#@us z^&w!OP_rzSenEZhUCLJ3QI8n5wHjV02+_|JnY>95SbmIT$}S;GW_>i_(7Nn zQ3FD0_cA3L7%a*h*?CjadQRzW)>@^DoKSS=UA zg=>#8SVs=bsYGX|J(-Cd#!nSmMq=N%RaLE3M$P?kr0yp`r$^+8{{~;H{~NxD-$)-Y z#jyw2i-=vqIcU&)lnyx5brAe2?he0F6R!eCYR9`Yp?90zfmLEHHqcu3MGHq+#c(TQL zZ@wBObUHQKH4FS4j}j%-INH#MWEh??N3yAe!9SzXQ;q;bAQ=`AuSZ#GsdMJD zn8M}jeL+E0_cryJ^N!80u$(%?Wi~uh9idr2PK7XE&O{9TPnrLp2g5w6QLbYUk6o~B!6W9Q048R%nfX`FsK9(|j>`ynYy#Jol5?E*Qrh5u zg?vN5_158~g2@lk7Y!@t^L_Ev?}z6TGK&;oFsGtohLH2IzO%s{+glby+Y7swzaDMy z-QcgwN4O1nKls0srwYaJs75?}QHFO|;Um$SGQPg^rgVeq z*N8`ydU*OMjZXe=Mm9#DemwVG2;9PD1>xam`gW2nT5C5{jgCh$~HXr zzdu2!K7GeKstb`!pnLaz>bCZ@weF+BwyNWv>3CAA@Jp)4;5kah7O-m?6Nyca__jyY}p?)q!)yPb^hEOz^GPcgEw$(RMsntkt`vOpEH@E z)%%A93EHFp24me|008*7=$1Q$p_ZRJfJ)0oSO69EoLLX5$GJyGn!){nf4$%Vi-ixO zMDVQdm_PLl=I3T}x0A9d9sF4$V`G`@wtYO{H3EkJU8sBXgRFYPi|Z{I5=xlus*kK# z|7h^w(--71Mi7l=M&=!?6?>e&z*8p@Gtn=aNPWi4CyP$1F7`(FKq;}b&0Dxvo_FUP zddu45YP_X2G^tCKg?s?fz#MW%&GQvqy1BGait7`}6}`>D%v|wrfDz?O*8};8e{c~? zD^n1Mhdr(?YL*gKJIgTVVGY-UkjMGCxOWw-(ipgLWTwWZ^L3<2o@bMB|TfN9IEaNrR)#j@P zVGDl}r@-X%&BC2#CLsh^lrN_P%}3paR0?o+KPg$3JSlO9lmCA*MBAXYy^%#5xTM)c zq+-#l+i~dC&)I?oU*4cxQm!E*^rq6VwtzT})$^guvYQcGj?X>wYt#%;eV(!XV$AK6rkiwv3a(It`<#Q<#NHQeM9UXCW>0*me_Z=#1{8|?;R@eXMZtWn;zqc$8D5C*= zP<4#HrNk%`VJV?}5wya{F5K3>v&_7#DA3+ZhX>}g7V54_N*;!X9C(me(res!p%4ib zxwPZ0bOqnxJSUU~^B<0h&N`ukSR{H~LDeQs2>Nvw8V@5njcB zQ`0H#Kr-?+%>kZb`tdNN#fG9N{aPxgI3uuh0R{syfg@`c>)w!7`_JFR%3!i%CU)OR zVbyhA)~`KGILqY(G`dSW2TnktCx)NCK_2^#UnIB_;b)ju$2*vjlQx{|zW1aX@_1wR zg=q^Wxt(W2F?r1Fu$DgrG@qPs^-zEUq=B#y<8m54a01V5C}A3p1)K8cQJA1vvr)Iq zs?b^xeboP-P1&RdCPo}czKmv5gQ=VY3YQL#oSS~Nf zx^Y>#=&;(l&v}_~OWtyw*2n&SbNnho4g1bfHm|rflDi9-U2Yl9iL@ZY2TiVN+7Ntm3l#!Yh0Anox7e} z;5A$?z>~;E#30BgX6~zfxEnZ)?NsA!drb$_9Xa;K&WdS4H7Z>xsHz8_^Jk=_BG1ex zmsypYl+Xcj=KQL}0`VT5-DPg?X~cr74NkgStzCcF z|ChnJ?4)R2{5d%p6~)4(PBl2=xYP>HHgb3p4xVGLStxR($|VJqMOQXP^cFmG2|jk zAJ7YUL@;YEqH<+@eiCF(Afrb!$>epExcGE?Yvy;N^W&JUs^|8nD8%kAjkY45fTRA( z9TZt%*!ow@iZJ?!%pp4M)m_;llDnY@E=N_ikrg44XTFkq+JfD|eWVHGg#=lg)HS*-r+3H)VRn4_&G8tI(>sJw%BuoCGlibZ+e-kfl_|PUhUO$ZPEM z3!2)D%5-L-YmA7S0Qn00RIAXZlt!FwFsQk{Akei?*#{7KNyg087-h zY5@#vG9>B41NVirVX4uGPm>vOXlpa<%=TQ%qnyYbY3!%FN zLhV47Bzw8k_QN%S?3PGgJf0Uc=&`G15wf&Sg7=WH%9Vky{0w>_d#HdENtIg@>y=V2 zhMl1m&TK~LvswCUTJOMO!Kl@3qAX6#^%A?e*l*cGU>uMh0Hu9uu>O+e3wX}+8JF24 zovAO!C8tr}eC*Gq-@?PVY|MSw=-tdus%LYEjBBTYOcgkb%T%yKk?SyRi8nBHOQ z2ODI8aEXZgM_$c-pKko0UYu?E!_lU{WGM#K>+`=PC2Q_^vXbgW7}Wu#oYZm9)A-jz z!&ri-+PF~3HiM43-eelna>jW}2zgohnrMp9$K$l~{vd3iqGBTw2tL$QNq#$frp)tYgv(A z82tl+RbBzKWB#**@G7GNlVNGmAc!D9=J{RsWZpH53Nov?$F6Fx*(RS!Rrd!27QB(8 zVNwJ8SQcSsflOi!aci!tCPH^jvfFZ{eEY*|Oxoo z3uNncP=~gXt?~BQep-SnRmoua2l9Sy7NKXU8xbf?SrG~4=NZo)hdap?=;#iy;V?CG z-MtAgI!~rrh)lsntND;@j6xWYbz#OG=JMe#PPf5BY**iQ!|DhPkWJ_rcEp%mmXnPm zL~0f$>&}^^14s#J`Ihe?;l06f`R3Sv)Sf^D16P1Wh{XW&0V{7n(jrcY40EX0i9g%Yr@Vc*4tMXd}CcqjOq1XLN^zH>dNO zT@-x^omv^G62b_>(ZO;JbTH|`+SRHNA6!Q5aMc*U7$asztt&)${1 zq11JQh;AMV?ScT-HJjNHHd)Tbggf*qZEoYF2ijx`H*wk`Pm`>X^tY<(Ufr7$*EXq@ zf_wj~8@Rxh;LG0&TsW$enma)cXpU>+Hd&~dYO+FzjJBPFq8@38i!7BcvU(cEKAnX( z(H=kg>PMDpz+fQUhuaf)&dR*s&1p;9)rOLARJ<~%kdwrVO}QRXu@bueP}q08B-?VL z181Kl5N(FWh&#i|)lVADH4+YN+Q7srn%)MXTOY1xObJQrNLNm5I2R(NUu1NFa_uXT zrR@FGYKpy{w3@%$A+_(0P$qn1{d>{RRcy`g(2WfQYM2AGw{^I*Ox6DTl zJoLNy_C;3fgG4vnS253Jd!$s%Sl)LeG;&sfL-6&rYwiIc<`n-=Arx|T~ zp;SOGvuUV4^Qm9v8h?vlP8Ea<6{F?O--BLA-psF&|=|I`>7`P?`y}t6C;%AfJ?0EB_kt16qlIkOFK~(KAj8y2InB zZW(lci}dXl1&L<&Tbioj40(EbCBn3vEw3k;2f{3(Z*{PlS!;QSoaxiDzoZ4opxC=3 z$QlkrQj1OSD+K>*#rL?ox~BA&w!3CXqd(>$N8dnTZcTi|MEptlj|G4zDYP3oXS@rk zO331d>huG!mx*?@9@p7diI=M6QBeZd1Z-bN>J)HxfRU+zX-khuuH3jgB7k-z^baOO z7vcwZpwOX!J9i{zzU$YdPW;`-_bU0AU;BKaJ7_K5d|I&^e+XvQvD`>co14kd=Zu)N zjXps4{G!*r+P+n;cm3gA1qY(5`2UB0dVfIirH-(uKj?&0=>%A<_7il1I8n@bnNq=D zm5_pvdbt=ztv1j{qS_ ztICWZqr9~}dw&dVOajZeS)bknf<w zkK?xm-QJQbnDICaAE*OKvFP92%Il+-gbMNpxOniSG<_F>w?TI2xDr^dsEI-qau z(<@I*2uLNSlj!I8yY%p9)h~i%zIfl5k?oY8;4p702@@-Wty03p7BqF)OkVG-5!dJt~io1 zzAycG=oX<}5!Z1XGY14S{5B}_pCKR{L0uxp6oz|r^Ctt_hIj4Uu!V0-aCF<`Z3yRR zag$2n&Yr1%@)6bU_5Shoo(kP`$u-wzoPHC{Yx|h|QvT}&a=nl=2%t_kpw$ToZTWUb zV|mMDT&QYfD}F}jfmn1m&MKu!r>#Y|=P`BY>PCW@-YxKnuoqVaFq_P;&&uGM>rXGx}rkE0yl(df=4qz%G9#B!WL zQJhu19s3^O#wc*oE{;TN9}V0>o+`qoL&)J$k6s7|T*f8Y(Q9whNxN|V46{OGN8Q`P9=ef{5U{+yaH|W#^Wzw0}Mwyr{3p$>Ej{V$gV8=H*=vd+Ks@7h%r$ zhi$-KwD2U>X2QZ%D0*(p{>B&P$NvRz%Z1MIG5_!M|C&?!?e6KWn${V&im-dP`#+wo z#&0A$Ll$P)6z4P26w*=ac4HMBf&mwreJc---9K7ET@9&ak`&X^8^69uk+knrBHM&6 zaBTWf-*h*s^cLU{Fej{0U6i|dy=UP3qbo$w^dqNeQp-7S#o7bE#*V7*>4%@eX=Y+4 zB{6^^qSjY#hv`gQS3ZU0ffL%2#UxAd#`r7G*X4Q>S95?&AQ0U`_ez=`nc-h@so?t7 zFU=g>GhskzhgOmQ*MtBxhZ!_jC$N{rzIs zWUji!v+aIZ=y`$hPlFg@Z0ebRF{`bU(X}h?bO|nKY`smzN4#| zYI)A}1@h6aQ9oRCXG5~{GBrvV%^QSrtM6dZEMvvRfwoaA-YQ>b!a1CK&z>nsAPqOeMX?%))JAtI1u5+S6D_%S*nTQ?2|> z$z)|!jbdC+8i`gD*5>edElSk$&mIuI!>^I-Z~*JM?8&+KNvsFIA55d{7P zA#9UVZ9u<95Xr2oTS0W&?XicU(Rkhs`~;&;aNu&q_Gs2H^IvEaDt2zJLgRWa&7KBM zmZ=ag%p=S_Nt9U2wGVg7O1I@I#^^>wL)1v$Wk{6WM)lY|cd=8Rjs((L*=4ZgA3gPe z%0qyX3xN7PPC=JuTg7o_TzyY;51vAxHO2$cNY>lU2b#27h?mAo38*YH)jpuq|DcZ) zq3lbM@)gEkU2M68qb3g-j%n7;dYP(VLX1o^4PIO0*96^(qMYd_FiPhf$4we4ZNDaa z(y*E^@*&PmgWOY11F=@~m)VR^0oqvU${wTHSY{#W1T?&<*nsPC)voo8R=PcP1c58 zm#o2T+_TxjHTqXqhdrEr_Cga`3?~*Wn3#=U5tK)*Kia7r4}*%%%>O~fy5}5JF{52{ z`Ui{k5DAp<;ZUUZb?bXdU`1=!!-4y9QvD5S#~D77ln@1(wRSNTc6nYa%Ze(1K2x@j zaISm69BQNyN?duzJcj2#ue=CK2?_RMyn@O5PmZCKAxTZ!>&W}C1vjdSXwbYm%wAd|I#$uRIaj-yPCvst8ODEF0b>$|9*-|=g?da|D~CmV}s5OhfEsi000pS4(Nf5dqg=0 zHEE#V>#S52YbuvWSUN%2;kb5BMRg^6oA`xef^xCnZldd24comJwNMmZy|NSWa@&W1 zaG)U=l4d9?v{IM^hKQAJYDnGSn(6T z)xAJ!rY-vHP5c?8KCZ~q0ckp=Ty%xut*zY#8STLBNB+E1u6o8{MMdo|lvvW|MW8zg zvJqD<@UwswB&t4~{6VJA*8TKj6s+hOLf}-^+h{XUt%Eh$&`EJN1KPa5~rb zE^LLZnV5-en!Hy(`F}LdD+=LR1a1U_UP!VAdQgpU2nVJDQ+Pw3#Gy5bq^+xl;NH<3 z;s!w4hZ>Kt(VG}mY2jMKeBKZa*Rm*93S^jP_RZ-AKeeDG6yGdM_u1psz zz1j2FN+1#K2%j3o#MVb_`|jJ(YPSCV!y0#m1H zzA#@jS;-ChF85iYq=z8YXs@aL#W>SI0Eg|L;!L=%u6X6wSA#+T;ST-;Yv0K@t}%MV ztT65yM$1hAc{rX)pLaQ7^*oi`VLXUeqXo>pE0!1LNg^w{|I3}^{Ql5)Hvor5K8 z)?E@s_Q4Vo*dTh>Ap-As7^_raOv{@dkkMHf{V< zdG z*95b6zq*`nyFa|GSlzYrFK}7q_9@AB5P&tB7BqPzlA^%fW7jnW+lYt1uW=sUvjyO# zF-GM(gRXNBs+t+`QL8>M2McMEm(}+_I?sJv+H;Ji5B&>b=bD%Q$erCe`Cb|*APtv+ z>MpIAGS9WC!@adqNuG1k6c&*bqY6|yzU8)*k4r4Qj^M-?pjHT9k;Uq#uH5L>Zc*J-yC{K_LIC+zZcsBtQw!%>(FY!IP%TpfeI zty}oVcsj@$v#efASyQ{k@Fyb#ycP&_8`0=8df=T-au~vDIEkr`o~{%F8`6QEj;NsO zH5l9je<;1C+%$b>)8IB_xpiS%qrH>Tpx!E&8{Y?}k-%64pfhz@$i9AbJUW}_R{d%- z?dQ*@&~S=Gu8lvqVeCB1uhL3vLmgNI#ez5cW4tc-R{(6(SY5ugWX@3(_f+HQ^p;Dx zqY-@?$pkw<006xGb$%Bb`@B#41fVAo&*fa&?E)(chZ}Tw8A)X`?&?8SWVuLoEP9R{ zve^9K4q7&L>C0ZpQ$Gl6;<0vLpx{2HPUC<+7zd?0wI)%n-#AR>0=ZX;j-AjjXq`8&2i|89|V0 za41cdYDlQr4_RQrXvUrXVa#-8A;8UmXErZc4+8Wvn@|1c8IrTdxxS@8({QL{GJG|w z3I-WZzAM1y$#t)F6!-gaFT+8W9;Qk!6KNS*6-ACl8?1PXKSs9r_E3B10HL5JzLgQ1 z?Yk_ImnaY_V`2tw<}{vD;O6Lc&NDdS0i#Y;=haK}Z0FD1Id)5v1%Z3ijj^;)`X5Zy zP3KF!69@<%poV)lVM)%-+`@|??R_yTkNJo315?vJxEW6J+D7Xx&=t`zA=@?jI&VK$ zPu7-nuCXEz0II`Bn$Ads-DXB=Frk5M@wxcAI;I3{5}CC^b$|-L&0DXfic~L5E7uVr zJ@|eJu#)|9hXmM-ffAPxpMvJ()H*#)x?Mgjh2?VP+V3C_$l|cZA$E{Y))+?bb9p1; z>fs%30>y)CcZzl#gV`5V7`9+HC>CjB41hdAe^@#l)fS$c4Aqu&NrMqZhfAXe77M88 z$QKu#erU;Mvny1UYm#yj2U_Vy^Ey9pNj}jOEzvIZ2PuR(-+z_K{Q7GD!44y(o}40W z7DJusbD?vP%*Vbcjpoc=yosG?w4n!0qUu!H&x!LbQE}cKpk+-YSjIwl=(>I!Gg?Xe z;){)B)a=kyXFMeCfB|q3G08Ar9_v3Tb#Af#TpzU3*W4!QnjqCw0(d9kwc*zRzSE*< zuMG7k43FjGa{vm-6)A@ImV#2!owoy@y_O zKlK(2;ZmLLQwu*CH$RbTo`6Mg?kn5XsrjsO>Wb(EU(!h)P*&#oDvqjf@|d?kt^C=bAL?W?%L9-bIuZ|Ll`u zjzjX_SonGk3+$jsr7bWEei5C#8A?oLLw9gL_+HWlJd`$FLfVc@2R7!H651S5RvX$a z$MlpDARuN)yAB;x@Yy8?iNLmhj_Ub$ZKoFF-jW4-WjiZn4osmRt6*%7#%6)kE9`J9 zec&aXs5~SWG3-W00D8+@>}(qQ@zUP=>0d^@6wUP7nc~#}yEcP;Zj3Rwl}uwx8cDU` za3&-oP5_xSK%aauZlab{Efh7nuOESW`5@{3-}r8oB3iV(Vv8D6o=b_7(`N&of#z|Y zMufE{7z6#Jq~MHccUFL;Tso~Hw2T;#g#dNh0YbT>jh9x zrNW2E9rrCAe@XS*0eNWh)~AQY$V4`oaH(Srp(c63u7W*~->`MJv;C^fqQBrHtiS45 zRe#aKbQpa0?{DtY2hW7n1NL{P;Vq{M4TeAs9B8w^Kc`KhLxcOqCh=bx8$08T(PTL*uki2C$^Lg1C%Ik`y{K~hQPK%V0e!ES z4df=kEA#&gis2Y#a4{VNx14pMAh{8F?WmjgmkuFTk4_q7WX*ro^?%cm23P<90{}3U z`Y@O9(`w&pObqMQ{wqRL6!mEERhuPLM#*ys&A07JYt~(Ia$mYv>PRN-M<=PFI!Am^ z)^bS1Y@nT-<3el6cK0^w!WpF2oQ2qJwyVUXpfqr4eISZG1x1K+Eh~~)8aU&?6kE4% z_PxGox(-=}1k?X0wpPMys_D1t-xQLieKonQy6KowgP}{y&|8E3p0#`iK>=uf z3`Vf&F2#aP%RG|${Eq`Jb!W$O>C2r_o+r28_+G#bjDFC3blA7feRR7;8onl-vKHPh?p$d-#eILoC0lP%Ll2vUX?6~wTf+2Fh z;Fe5(&!9-Pyx7=4GxX>%G^tR|uI3+CF8RfXp)~pHl2tBk>5{$9*Jd>thhzgaPfRJ~9 z000930iF7BD+b&rITrI4lv1P0sr#CNZ3{!jQU9uZCbNMyb*J?ExRdXZ;J=2eWS7o# zT6|FD%%u`00wozPw4&PN^QtNcXo2?&(Sl)MB$2@m>vZ6 ztgRFKYFx;4q#Y@v)z8d+hwVC%>_Zp=Exlk%TiJT1*{rtDt>A+;K7^drb>_nFT0_XI zJ_Bv)1!BV73_=|E-<8+=I?ZW$YkN~+9EElOT`>jNv=UPrRF_)qQk!cs%z_&t*d^+d zRnb=h&FZnV*S}IzJ~#@uY=O6b+!26GDu^jBK_jOG#>Z0@vjw57&=%&u5*rHh82e=$ zM-8=`sVK(0TR?mly_DHkQ!57ac zIn&9CA$eG6@iSVM(J`BIs3Ai9$-c<6^Kdk6P-Wwm%FQ1=7DqE_NGIvQ9YdyJ$YG6k zd!r=Tb?^*>stl1=JX?Qx(Jh|XT#M8TTAbF)v(|;hBUl|T(;Mrhc#%_XqSiT*67qC5uj@O9NYRrsBC-qY?r5eKt z90o2S;sHb^xOELH)6q6g-vk^DQLr)tsC2Jc-_0Z~*xC7L4=6ry!fd5HDS0ry*jW#t zad9zH5d9k_@TUs^W9iY}XQ&qQ)@x(-a&l33Y!||gkkwALwTw9pS=m^g3p}kKhpet} zRRH?sz+>c!E!9|RtlCjZ+OY_v`zl%2nB2@6gM97wuqsmb6Zl#pArzs3?0f$8aS?gG z_~e4iwb(AriQtL^jsXhE01&AK7Z_2b3ZY86_iF;u>mt@n-kG8oM$wq&05PMHaOh^- z!K(x8F>M^w8O)4JJo~3$x5)=EdpZ)H^&F|EJ-R6wLr(Rv#g!v0qw(;HX89>ApIk6- zf>=6swI?tkL9?2mkvty2H=Ag6E!slWe(2>?>~5_I8f9>^ zNCDnwUFBB0PJ$92GHa+oIvlVq`)&=%C5M$NZGOHs;?HU#rzi)SR@XfAykmoT|%I&jqfi4NW81uFE z?Du^+#&@G2M&Ph+eZ1{TC&~jj1k(ZN?h_qoWJ9n7xYcprJm+ybeXZ@;mBQIw=^u>p z`abiS#d-JV3RM^O;V43-uGauw+huD|b^BcH5#Y;n5#-8*iWqw$2uTtoSNhZ;Lktuo!=Feia^Kn~a>mZgD#69&QV_o^8xh4#}j3 z2ko##ndXuCuIAKq%y*3ae!pLPBYdn*3BqZ=DmZMc2IUm{)0gRQF&)nb7^=LPI@7@h zs(S{=w0AU(VOq&qsxBLV%POz3_kCL+UQtGkebgjxrSd)@m^ju(!z%SKkD!7KOSe26 z#2fE$kMF7Pt7jGG{3Tyd3Se~7`sDZ%O3B+K4MIy1!eqlPD{k-HR&@m8p9-uXD9Us0 zc;cQ_LbSa_7>(W(PjNH=>@ZNc?_!jDBiBs{|Ko@l`SKl|&xE{kRM%e#e3qGsA_)p? z$BMSv)cPSndg%tQeQnCij;DO=hX1Ae!d=UG72*}%q$|2uMd+oF5%``D`54u+mpyvJifLU-_hr9kGmssfbKUYoz;BsUS~f@#j4oc_L`i* ztzIM!$|5$KSCt9#a));B8x5tPz3xs(&b+>*s1d|9DJFER9bUMIHbXUPa0V@X8y6DK zoP}oV99nMFR-G(D0hWL;B4IE@F~{oHp$IM)3|S_BDs@Myo*s5opd8h(zG~M*w;ZWs zC(?Eoro%;}t7SIf1451Ul_{~{CGI?>gD8&riEcr0DGcb2%4$Fn)Pe5Cy7gUAOti{R zXpHIh9mr^%?TtaEf_@zS!4Uv;+(BtZsQ3eaP>?-m!-TRmO&;~z8v-yP?8BO$#M*%| zZE@hHX2&LNxW!EK^N2%_n?GocS#6VUM&O##JtCd#Ifg0vOMW+Eo^reGn&CkgvgWZ5<+(^ADV`!e zZq03YTmS$A000S>)a(@Arw%9GwXl{Z)PX9lfg#1hkPiRdZ0Rch+xs%xI*kFddJs}P zxlxva-Qg1oA}2(w_avzhF*5t+2aBghQ!U(9QmNTWi*VB7zm@aJ;s(qhpo*csG5zkL zod_tFx+Ih|_(Rwp9JV}vzfww{jX?@L+FX>AC{ut5a#;KT00RI30{{R60mB3lDt0B# z5C8xJ0ZTD--zPZUm=Qdb@q6f`^wdqOpU<5RQkTTg6TyP9vr_-mK^XT-1^YUPVISUU zR1FzRrU;gjaZ^WA{Q|!9Q2(6eTjlQs!^)T&up$59S&<0Yj3cPUn-Y;+b+iHqz*i$#nn$GJ;RpN zm;>?O^0>trc?rSAC=IjZre{aWj8xYDjjuloPkN?6&RI`MU;kO2}k%^tFO z68VN0WHmmvRY;Kds(tRFFeG{RpXRs4e1vA~llbwVv@pr&&12-CEdo#uV8X@m1VBOpiXxMES*{`VP?Dt%)3$}4{x~r6z1(T6MM|y0$sL#pXWJs&y-0z8-x4{8lDU6qWZ71#kN_ z=l2ZIMs7M39>6;ijCXtS1aZh1%Xjq|`s zqvcowovYDBzI{5N8>Ij89}|%z97nDCywd-SZj_EocQbk*Aywv*A6u`Ddb9=nk3(Fp z0Yt#4S2oy)94(PF^z@G&F1xF4E}fIUs$YLw7lj{Z2~t~OF1@2GVrpC%!~bKN@nr}9 zgSR%S>I=AOHVb1aJOpf2^{y-jD4ke+`DCDE;O@GRO7(4M`(4ThDeP9`7~3A{{iYBO z?E=kWS$4ktrRj{V7v~MTm{xG=vt^OzL|S+iGb%{ytdEHe(ho_#b9kzyHlCeU3#7Co z?X$jd?BVK|<|f-6T(!&Q4ul7e#nz>s?e_LwB`e$!(-HrrpZIejX_su&OjMDTqZ@j( zj1|&P$*cO!(omF*wqM8Be;C#YaHc5caUHrmRLUt719ZqEGLUaatop(=gZ(~$j>H)> zNurXP4x35w)0C#OL}X;7{nm%X^B*Y#yy5vgCYIY+`QY9&k0g6z^eg*ee+5Frm&pfL z`Av4E#a1sQ0E>)Chh|OpYUR(Y{zA)?MS>ipa-uBkoke<q2u55<&D63O zO@QR&`2We)t@9^MkVL5H`Hv`&67qiy2yr=h7YceNGBZ~Q(pddmy!^E>^Fpx3ND|~VeoxsU zr>lr#dr8!2l&@rWwQi%NNYgJ3B4JO7Z~XJuZ`fqvUpr39SlT;%aItml8~uV@+yk z)^GNbfzwSzzfapDh8U=l+?-FbNP68I(nenF2`&VogrYh?PIjNDw5{CbzIcxGfq}}* z>6*KRaa(^*~mZgJ&fZZbJ zFe5Gqx05lcek$Q)veLoVoQo{y6hD<81pt@vKJoiGk&+u57*_m%^g@7Xw7H zHq!hQPDaqwoo&QK7uKSaO_{5FtD>f}850T+x|i7PV@o1>DAgy^wDw$6g>-aPSs zGcCbLB!~uN=|YI!%uShQ>HYGE48xyzKi9a9(XHcDgAfyWh?I4S{`4cTCVsO+OZlNf z`TW)2`dLIizx=VoVfosrLHfL0+z zg;}I=R0VMI5`Y-23-s{t*pD7BETW(OS~9isU`h%heg(T>cJ9-~M(%c|WAU%PuuasQ zmv>XvjIKa;IVP$F>^Lt-z0tN4ksgnv1Ixh=5HEnAgViXink*e!&eJUhYdiqjK(5;% z?ySJ9HhZTXH7(Y)KX4%&^awEescU{zZ+!B?D6TL|8jjDp*ioZ4KXnKSnk&saDRRQ} zxdo4wi+S0MLicZp3-dsMSRFN5M5**ZB%b za1W_mF&ZhrW3zZmfK$u_873r7moPh4FEoJuc_3#><&Cv& z4lek#2w6Gj*N;ed-cS-vrsXaYczT2Ky}&<1>qQs}YcfaOYBGa|btZcKt-*mZD{);U zM;R#k0B=B$zgUSss{3*)G0#ecHwD-Tr=h&B%-?^!*@HkWg1qq@4g_Q^HHjxqjD36{ zfdRuJ+Br^6Jq%{x-uLS0+YDF$HmB%bxaz0EaW!2%*AfIcGm$dZxFM7z--{l6{L%F@ zS*Xnnm0UC*JfYVNU&d1!*MVyuU{cCf$-ouBUOqKNq4UIpIHz^r~M1x;RvP~?{& zGzei2lYvM4Xle4dcfKOz}He0Sp!FT(2#r# z$X&4#88)mS?28Qq3!BFu2b@m(hGRm=wYvToJ#ff}3=x(d@D|m&#?+qXcyGV}00RI3 z0|Ddf2Iy@=&AV`&>`(hA#=XpRIcE|qWL;R03k0>)n}JWJ&zt6FbU;6W#8g7s%j&cb ziF-oEN_ZBA&8jT$nPcZ=(}fMEMKqe6&0?M6zu;3)H+i@>~(Da=c3zR`2 z@bP;6<*YLJh#WhYyTwxZ3_&;KC>EdJHd~E3%EXHcb@9j7R%dHe$Nk4zC{=vH(pt|$ zK}t5@!7oI)mK>M(>@+LYAaTE*Qy;_oCucqqq7Dm9%|mnHK)EOxze1^5u-stxhd z)T3jABi)>Of?p9wuV`8d@42WEt)En51x!I>1l@~DA|`4~qIU*KddepCzpb4iAbij4 zl&tl|sFYJxYFOsFPYGjzLn_UAE)}y3q4N3^khkmaKk~*Hl*%2TZ>e6P=NTOFw3HoY zZZyd#)zk7>gcsqR7fLxr?^^QQ4&~I=6fQW_G*%OFi#k)9oVHKU_0(X65^Hdhb2`&H zRHl!Y)^7*$0@!$^1u|%r3GEQU5C4D#rMKr1aPK}3kHSX1QR;ZbTm=b3tGGf}_UXzg z>DGP2j%Ab2jH!_$2Q+D5?W@jd4mX}^QIw~OReX=QHJdeS$;4_m&hH9zC|FI5Q5Ei! z_4POZ@Eo)i!NTz(0w3ZsRYkNmkeOAFdT*ZVBq*d&~VhdWHj5&zp3o~&S7$EN3Cc@4?+ z5WSbUOHD?k_-;uyk|?GY-s1THyg_M3Y%630nf|0(5dPCv@El2bEN=MQi`z^mx|2>MN5o+%kuMd0CQq1#h}TpUd@cF3pC8!Spfi?jQ2R$9bHG*@#&sD3i$#4NW$kDK*h)5?q3VY z?cwsiLv6ZwM{><;++KcI!J<^SaZc5H=xcaBc*LGE&E?m0Y}eAIVZ4ETr4?lPqb1-0 zkSPvR7lCvA`M}T)Fj$%BjN#(YFd-F8;XRDY*^WBk=@L*(P%TP7YTjqukG zuXxXodiVNCkuWFuM-`rf4bL*^4LsytrRQW#i@CwG$_x)YMMB&v`Z;O*r)$v)g&hkR z{Hek+HE8gx($KaiU&knm5uX;-u zx$|uVF-3WmIPG7kY<^wCCo1CSw^-ViRF+2$Nz`7Fb#WHA1$J>@dM4QeP(HgSBWa~^ zJ&;|FH)R{Mt@VsGe7_l!q3RizLHhf3I8bKhc67 za{Pv9AH1cq3CnJ4c=uk|S-jm~ZOa(&rhZ8a6DT^rFVpMeQ#OFie?B;_xgcYl5S=LG zPdP0E2p~@^60OSnPiaV?#pBcNrXi-{bs0-L2Zz_T=DP1`xLOH*zk-6npYC>6up|2# zf=*uRNBN(g*Z^NE-EahaV?Ij%2AU8OBCXVVOmH!;hvP8aS~K~N(_@j)7~T@c9|D$9 zHJ7gu-kwFWC%^OR8m*X3LU>y!li&zFK{WyWvnuJC2as|1^%QbeYi^L3ecO8}K#tfI0U zy#JK-D>*((3Vh~|@a}4Q9Qm(xKUMwe?i!KhsxH;$ineS7v4?XY#@?YAob@_jf@h(i zQ$s<1<0l((@>ZdG77g~JE=J*rU0tX<9?t5k3tl6YK(!h=iY8cR^H{#y6f_`Rp5Szs!h`S(n=@r{Yilj>Jdd-PU1hy>Fo0h>m(=Ie?I} z8WQ%79D3VBZB!iTz?VKiHB?}^QSn}=Du|riFsFzLMnmzP49wF$xGH#Q6@!7l!qUs0it0c z_SrFCT5ysSe%>g91JGoUS{A8vj;Y71wVo@9!BgIZ1qoCp@mrWt zocZ#ZQs{=@96pFZP&R&jFDu1ba0cp_b&>jX+c&!(TO$K1u&U+{{%u+>k!%KY^x>;f zSWM?(?y8$H&YpP0T>onyet8u&m2=!58)lnE*g4%t*HT){Pxeh!U#|>KAso5(r>{Df zTxbz?kMB`YRlm+(wAe^G^r|P1TzfTsr#SESChInn`TAqMeClxUe<%FSr13(Ns-iX zlWNoJE1Rsioec5H6mt0elnAg>2?Nw@lf~Kh{+@#G>r}evG(mNHdW%y)!&5!B97Wlr zDPDRWX>7BJK!uV1;jVYU%5vzVGIqQs?$F&;Nj^PLH&9}xw zKEU>nU}>`1-~(q|9hRdxp#5kc_7O2R&2RVN2sQLr`xFzxkfRyMthi%;_yC__XpDdJCh8DT4`4VG9bzJ=h=2M{wR( z?Uyp+$vl4IGq+Q&s_Z`E1dz>BfE7Ko{6PW63@jMr0G!DzLYl0ZsZE#lx~|U?lD6EVyii4qXa9Lwm3YOYIQ+6qmx{>lH1^ch~jg& zf*hnG?IR$+gq@jeAPz9Rca;SsY?@u&gy>1x+r>Fnaeqd{*UE$Gl+OFot385sXQ8|f zok#7O3an{7PA4=!qWbs>~YK09o18xc-tQ6M3og8(Soh(02O z>;S{+SC%8!jKqt)F!hKqu}-zjuKbi=`4I-Nh~=WX2lRX_OBJIb;Ygvpd|Rfkgjb-B z#W5PEXI*%C_3z5XH!>HQf+qDer0vyLtDvR^pn;ts8+&K4=${d-l~}m=p#JE{=}S!3 z)?YEWNy((;Fle>1XSL=1k4MwbjVIA}T0G{zH_>)^3!Tw_1>LsK9JLAZk&eZwAINCdmmxbAV*^-EfU)_Pi$~<6$ z2w(qdV6si1oX8KHC%C3LZ8`f@m1QCmfgxoFhm&+hQYjv+U)8*QBD5x|TZ92BXpQ5K zAWtMM1l5Q}r)FKugKbTAa<7yHV0eL`qFTU&q1o9N$dDFDyKZnfR8>&rH@OtIV!LtN z@5cc%?&bUzE$0dYl8(K=YVYp6)8XcBJ#V!!=_ze|2!@NbV9uM|VZ*v+^I*cN0sFJ7sBJYALO{WPS^$ezI?ix2R}1xD7ZwU>(YUecIA z2025z9W_D%W%W7!eEoFqDl0!k`%6A^jkmJwvm=bB*!d|spdXPr0KI-GhJ%yB3Y^Yp1iuInOj!u5+KRwe3W3zM(_V0pii@0eE`_R#Z|xPL z^P(i>y%0+pdvo=ui@bKjlI+gvpL6$l3B}SWQB#Z`Aqd7$!(qaEZlj3g-h`=by7(7f zoEt6LrfR-FAE3^S_~Bds_+#ol*%P%za`MXpJ_&%^ft+9nYJi_y{j$3&8+ZbwAdkH5 z)UXVh1td;_{*OcXwgl26q1j-G@GhtzLtSOiLDT?F-4v{WKH8o=Fce-`4+aoppv)<2R6sj># z;W3}5+q%s*rNrI$e@1SCMns+k2v2d4zKL2}iJ%LO8QypCS)Ck8*VC2zpP`e9G~I92 z38G#|>;>C5fQ-5z9~tH$l{S|EO!%#;I{s@2Dr~ss#Qty4A8{34#p?jAz1MtJD#I>U z^3^GL)_Xc-Xljy}Vh~Dr%fTvTmyzJ)!Aq&nN4Z8X6)N^89QL3r{-i~s-#Hc^lv9YY zY&2p)P0Shuaxbm#R~ZVdXCX@GlHBF}U5j={r${1=|E0_HTKF%_GH_$tGQ(?1@dyv1 z-;V9ebS;>}bNBa^zG8hGC~PxnX`i7!j{+2yp%3^7++E{+AhYUYQbAvWLDM zds#HH8v@jLx8O(w=GD_aj~MqY#84Pmm<3uhL^q@K=rCP*NB{r>03pBrz6Fg1*A1l< z1^I#w&Mc$Y+A{6qFnV`3ENf{PP2JQj#zy z_VqT(RzaMVDQ}^sMbaDm9s$0KtLW#&lI2Q@0-3oBm=rikNdNeSnR1p5A>Ft&HtA@A z_TkoM=D{S!Rk*1?F(gUt*F8*BUfZB{X_GkTwlonAGx9fXXSDunE#_HqVkc6KslAdN z73r~JgP*gt@`bvGpa>Hoawk5efa3K&k*4ex4~RY+l%I_~1_1Q`=j^oMFfaG0RoCjg zLItr5XT}^e6BUJM?>#3fr1RV|GS+fw(%gSlWHal{v*G1mEq)1yS&GI|9m8fPH!nZv zu8n9cPnIH~Ud(Fu8>&C@J?QU~ed4+?&N|Xc3TUjXXuX1>!<_(XxQ^orE|JxkTY}o~ z2clfLKc8|A2Eyh(cJhc=F1K=9wItv`EK-@&%|6>GzRqxL5q6i;m^KET>LR6kRCu)8;3nXho z)T%0g0)Qd8Pv4RCrp1e6@4;WsDl3XVXgH!@A!nNYz7tBLIcNh8DyDVeFW6n-Qe5wf zrBVd+7lLkH{@vOVx!$Suzy(m+Ecz55S`U1hs7$ybu!=ilYCEy1nMesgD&-pOl`8SX z$`sDJa02ON2Ob<46l-1UWq8}h^5n!<&CLVkp>6Qk?8hJ>!Do@7aMXT^sgU-6roy#% z9&4CXglQ4)8sP$GhhG(W`kSxWC*^I~SR(FQxdcB=n|jByRp9!-sEjYN$M}~p9t#0R z@yYSJT*1zqaI@vcdFqp8&}fZGI7QGFls@+8dYRNjURr1!T-4RT&Kwv%`1hTG+m)J>B-P0WiW zPM8J7(|j(dzPqZ%Asm=N-gOv~H+$Te#td8%%{(A(L09woWP9?*N2HJ=8E7G3 zfbD(Op0#AbftW5!OzYKKrI!F!Hah-T$G=;;9PNjJgJwTl0iwxU*sRM z&@U$5i*2g+N!9g8Y`S)(iW9$wY0qOhkA0B?W8CdZkP6XK_PC29N=P@hn`brdY!6Kx zmMntH@UywwKEkvAB_0TQ_CCu!DkKTSxx95yU3HwtVKiv{RP0gGrP3*6ij(_IyJv60 z`0nd_1J4YrmFSVHtS1sz^)$qoB)Z5j^NDpd#dzLh*P3|T6`$L!irJ`+zA{Cm?HMXB z1TTcjEGVmFaWs4}Y88z!d)|9BT2TgY$@@{LP$2i1)EC@XV8Fk#ku-mNQ@%pn0`l0V zBWxhP+7f%T8~M(b5@u2aC5!f9O=`FQ4n4sz`TBApGq?x#dG~W(h&QhQ+PGuLl+>4j zFD70&iqtb`)P&~B0Kyx9nY7#j33SR;7Q`YVTbU2i5p`ni(ZOLV-lfn(+D8^ zGVBOTp~U?JkwX&rT=u&*61*ra;tB1Acuy{dxllt5cCF`QKqA+iAW!kWtr_P;XaFkQ za1HjS2Jm^VqS@Q?VecuJ!ZkuQa?}2x1pYPZz3CSvoX>NR*SLTH00RIuUA_O9yIxIN zadfXD#Z(4JO(%|81yrVG^HzRCP|yGTPp*J(&ZepqAu;ib--BHPKBnv9#|w7b6Q^bK zinna$jpP?OFQIt>fv(dQ;p{+jzuZ>yk^i_rO2BPdaYF+<9=oFTX@jQySEQ%6phisUno|0 z5ZS`gc}NKI9zLT_Q!OWH=1FLWX#&X~jN#ug?dj3l0+9|nRv#>vyOVh5T;q#erKfM( z#0PaGWS@Trer)k#-X+YGE>_jn(C2PWg+v24#QybmG6ScP|J{3d4eS?3>B2Q{YeB=Q^rEg34HT$JL-GChGE{`W?hG3N|n%4xOcO1 zTeH3y-O007_tdV$gtHqosvuN7+=ZnUL(uc0exLS^cwNFyIp7TuapPpKho&yAS=P0~ z2u)(;ROU~z%&vk;=oq2fyYQ6jzqW~R#;ipX&o?Wg4~1@1yY;tfrj1#ifM>tjDwie8 z;ZIcNBlK7b;B}-{rOMWd__S>Z-RtWPw72L8|5w@9INTZn$*znQ?Pm44u?>ktar%Nfil{WD z0xlyLACK{-CDF}Y62x_8%^?aVe3l2>`UTZ)_Bl-mWqYyhTFBF)G$yHZ=s~;@`amf& zfc}+@ISInt29Dw*_Y)n>vE(6-(5*6nP8ZqN?Hj&$4IHmdK8cAxjOiTboU2Ls(FzazU zVRH=RlB6(CDH7!W$ZV}{f&i5bvPe<+ z#7zZBFtIU`q|Io4Q4G+&fdZiLhFdgf2ux}pcI|R++O{S3fq@A}&c~Y-EAjcCo!R0S z@7rF~#S!g2cH~SXsZ8v(~431;8%4D7F z?(XumjWnX@!F}q>si*XaNb)vo+-qT1CJ@Jk$M>o0aL>c*`{Daq_OBRnw>|57U1)Pw z3yq%c|Gc8F-BW%$qT6N$fp@LFk71(-9-tI(Z^PCwQdc12588DZb$|c>0|3QeYrOs~ zt?w?)QR&|6$O+WdU@Gs$b<77-1(T?_LvlC;mqrt- z>Q1%HBeqVfG3ZqLlmB3RR1qggkTrVeKZEd;daxWU6m8LF`tji%ElvTdcm zZ^mo{P{DEK`rBwT59v6Z%L-tCX$3mit1H>W@en8~4t5I-t8=AQ-HjhRTd*C4&Ez}} zq{IcyOv7AScI-C{V6VOZ<>|TIs?!22aj{EtMK{0y1Rx7E7%%Q z!;PUa$?(Lraq^8mI`1nFzV;kIRdF0|7BLox197sH*$Lk;R&>-hg zLXD0#A{EDIaa5MH-M!69gJyC;5cty%;o<%}Rb3CNz;LBXrfLVaMzHqi^oK+|DOmpt zK@D4vdqGm#w-U}bzj)7Q+nH%A@%GeCKV)^F2_`z!UlP&k+8X^eDhUOVnscm8L^z~$N*v< z!N@2>b%cOYcitxlAl-*kfnopotH*r;{-bYJF+|%AresgUxS^pzJ5MI@7j2$}0)Xny zy+rEV@?P4i9mGA%F^jljfFzZS>G;r9oF`G#I4}mg{WR0h2r6f;C z8LiA7UWo6GubFG+4c()U{{DEwi^oy>{wThk2S#Lc)GIvM+`jBnvEVUxWl5axEIOhC z{wR%=^I=Y~ofwP9#ude>TV!TL+)>!{NO@N|H9IbZ4=}qjD^uDipLkulU?}__Dl~4v z+?~`>DecUZ%i9>A*nqg|^ay5k>+*OzcdmcS@$BIbzUouZi>~Me62bXfyiq9i3R18J zF?7!I>qy4Y%G@YL_wQnT6&&>$hyvge78QP61HV>ZqBOpd20k8HLif~G?#^ndzPx-< zoIF@KP^=E|)AK(*KX{1qSNPt{XJ1w@YY2ErHwuM-$bRiuX2V8jvdyDQY+wVUoczAQ z4PR{}%GzGng?EvP$u%;!fuEtB$3^F9-n z=#UoxIY`raV%GEDSy=dw zyPEIpPw&5n^)uI3SF)@GnemyCG}cDMuZOX95nxK`vwS5>yID`DY3C2q)Q*KpRjpsJSY683x$vT0 z%eyv#l6~kI*|n~_qhUvz4z2IU*i%t& z`VWcR?&|FKo_iS8&lCY91tN6Xu>^lZ_RIE)1| z|BeIZIOYGKX13>CIb)KxoMu6pNGp{ig|d9{WIYGTFJSv)pRIOtRLV>f<$fZmW-FJR zJXdme{!G-ljtpqwX5n~LYA7*K{F*kgNr&=+Q0==2w#?ws6xXX zN{hN-^{)C+Wh@@R9qE0;l`uA4Ix+fMA4clg226&{+&+v5&|o7rH(+A2KsoO=pJ!
6)}AaEbfkCd?vRMgjed+1&(*It2La)TeT%|bNs<9 z0guNohd*H=HRpE^bv~R!9l^$DPgx>(nq6Ju(lau_P@4Z$`h>RBHGWxed7R~>mFDes zo^|?LC*XDH2aQu;V2HdC&`=KB<}9++Mmx0ZegUnmzGP*hpi7ee!)87y%bTRX*acMd zrsP6*Evho#o=PEUr*HwzMsi72&O-upasa2?8j7-Zo?EWRCuEDBuzZ9q__GK@v&p4C zM7UH#vq5WsL%y0to6XH>eu%2HWV7v=TJL6Kjy7Nd!u?+WdcE1vWo7>s6gQ=P7jVnN zJwi@Is1_#Rf!rf7%cm1r*W_L!cjrH}z)9iVOysTa~Q2hpFmuEd;-y_>Y^8DAjkQ8Al;LZyu(?v%6-9 z7uY*&X<06+kPz8$FVMnAKclUQe2Gm3j+OLa%4Po=Q61L^85f9vD=t6KHqT8wfv;ki z7;G<%Z?~wgI?!rUAN!5rXIYYyb6}v4+mRB=-eMk3XkTXjznf+Qmfq74>I$zAx5RCj zZ#d`<5W{BGrmnK{+!p;Dqwr!O52ZXv0_-TLcXT0v;K%z$AVPDwy7!a8Mf7Z|IjA&0 zp1`=1gL0xZE*gy{>MBjzS*hDx##;WB z+)@a4hfGg6fhn&R5013`6iIXD%Il2OEn*^q?`;WJsf45Z_}uXdd0mj;LapF zMRiOuUDoQJ@O?R)#B0@%Nc!N?j^8d8l3SLAfS}3usx6m(s`;g?Gp z*N~;OHSt=#3Xx=$5WBI_NqoENJjnI;kg~|SVOU+BllX6!kmSGl25-)dhfj$HON1Sf zWp;umE5O5#Ib>%=4=_^WonQ0Q5(xY>cY&)D(H90Y4tzw74B&Hjh$&ycA~+rb8SC%83s zTrJU)+!P%N{L>Fp9GV%IErd7<^KjFf6_&-TLRMOQj|>}XjLa7eZZXkpVpyw9md|)b zY*2>vP;#MGKj95zd|@BQqkcHT8&jMh>?E|cL()@ZbU(jDZG=_eR?T}ldDq_Oc*3Fc z$?Y|jo+*@BKOnjV_=Bo7MaBA*L&==qPIj2WAG)LuCGW0xRLhJF0Z1OeShF-47wA!u zxBX9XTZqIZpc-07PrqP=Li4c-yaZ_Sf}4_mFg}NlTaoO(7>o8kg`Y@U>hY4oQd{qk zNlq%*GH_7biy*4Ox()eXAfD(#fd8eAHdWOFry+$@oRO}-f~{uJnKU!g6mblNzpiD& zk(YrI1eYd}A>d%^-h5`tGctK)f9icZ=r49jF+cn&+HU$B+|75#y59D7ZD9Mj;LW5X zswmz?Nitx&`f%v?q6m`~-D4T7e$%I1kVc8=IIkBTdid>l>JqJ% z=0rzY5%EPILNJ{D)T^uu|JegCO*Fz8Iux+7ioK)reBt=H z*yPcUgiBy-Z{xL|CzO|=s7ku~T+!FndaaGVD(;*4D%APsZ?MPeGT-wL@8-wVYGBEuiCAUT7(@_?`> zanh>NM%oHOXh|R1TJhYG;-)>$#wJadW4ZT~ju?e#xXOlVoiqtFMroe9sd5pyNmVy2 zE7O-^Uqr9|agWN8C|$xNo@Ue$KwFV019HkNIUDAIcySrL{q6vg+NwVmaM~I;akPj z8Ye5`|FTC34*zj^4zhQ0T~z)HW^nXQ(giLb;~#-I9FZViY#BN_XBPzJuFgY##S(AO zzsV8@i#-XX`jBEs?T`8`jYeVpKsQz}l~GT=1pyS{WrOUrIYECfqSNlnjpld6-wbYO z-t)HV6aM!ldcEYJ|IMn?D_0vbD5o`F=>^jnL$WyZ-< zib|0!gFe)tR6t{j)p{j|Z(_~zSSNjyWi<hw?obIi$fQYXKqR>Li$FLDa`Zf{Wa-D%ZqaZNmR zpjH&Xi_9Iid{>!X%J__IF<0-+|4jft>&hu9Ne|FcbCGESH(Aj>*VmNflj2=J>szHyQ3gm@N!=v%a0fM)!OEt_|h zE$7A8lAj0`$8w%CG{$lYQp$GM=5T;xF#izwJ@Mw9p|Nm3!Y-zlqyg)AXw8eOgpUZ< zlpVYGN@Lw9KjN$D#OUN0aK!~yqXPT1G@G!3Y!HB9yiPXG+<4b;DBT2SzH5B%G(8?s z?)!?4u_C^+vFknd=4xt~7hoffdg9=TfDk)+r0{>-cSO@`#f1lHNio9DbugI#h+l>_q3DnWL? z@cp=G{>_N;)Wd6nV^*tP{0XcgDB3nlg+KC>t?15&_CvqN)pSXT2t>L+J>xOm^rOg3 zo;PWpHPrk>P7frgWJ7K+jQkPy6EK)4x$<8{fjduPA!d1}0w>v9G2JIK^c2UYU9sb9<5QgY;UMZ zj~fWPVu#}k#&z7qz0~ZteE+{zfD06$I!BK>2hkAo?9?bT%BlfJ9RFy>k;(Qh6Df%G z5}de!4ZSc^ggkm99e5^DV0?Br-6fTuHw)we&Zk|bgC`?0h0tAGB&ut#g;88(n|$a zGKqo&NVYiCUZsU|i6Tn1fcaB8Cb~w77sgCTLY`XhDe5q;&_S|}$UJRvjj-vqFW2P| z`q+|{BAMI#g7f&(Xsj4sz1yuR`Tor5x2r{v?Te4;|!S^b8GnB2`Ow^G|gMauOXlH}jSdv~BS+=GNiHtP!nE#;uoDtU4Z3Srq;IRr^ z>?VLaW~7&@(!xOwKr-4_5I0KiGl{$`P}rTcbB0(naX6ftHmWxgT0jWHo<4bA7!hpd z0yADU!QfwuEiHsT~Y^; z>_(tI9*K9--8VR6Fi_364+ugD*^-AC_pq3Bg#`slDH9?WrPA_(N#$DljfK4T8r%t$ zXaZEpqW$r*@IK!Wxn!^zdFo?-0MjOM^4*WZgkjUkKQ$5%9-d}0q%q3;_2+PY2& zI=A1`v;EV>9pbq z7T9JqCOGq5e$cJMWW*r_d zvc>{YLBUj?pTqP92AL>(jA+3Y&7?_ z)_`Yp4yD$iu^zh4C1{%Y?DitLk_~ja{|c+369=QZ3Ui;pS<&oqxU|KK9CZk%Rd0j< z00RI?;6F8+Y`^;hwnQUNorG(SEJ4BR!9Nr!0_gxzDmidXc;eJ0oT@b(>`6{ar`qBv zP;G%Vzf)p&&+>3=l)P!34`A7ALU_Eq2if9IeH+827D!k;}z8hQb^k~icga?pggXm^|Yn+ z!D%LLL*41-X<=zP7XTe9-(&<}d^(|Fzje|a4-JD}LIR3AG^SNfdKuFAMi3Yj5~`$r z6Y1%oXzSdxMgu>#nPBlE9EdUdXqCshjaBKGYWx|B9X<&$Ma}sVHk)M`RngbBCTZ#! zvtI1SGm&xx2mK=yojMy3jCw8@v2t|ExI9aM35~zn9-h9Jtp9z-itDwMjeq>BDNn|U z8{8=rI2My11xsO%^jdAi+;C%bvyq=kIqW$PKD_|pJ3k2xBz!zCQU{(Q=YZ0N`E7`8 zGn-_RZ%cs4R_GWp=6f+u@Q`KT#czc8Y%7@4h0?E$WMiCnF;H+InNGVu7V%e`-puR2gtpZrex29yZ1X_@35O`4Kdms8q=c`4&$A*#6{tM`=) z3g|4DbpDveto`Uf3Y5z54=&nCupwokdKOf0ALOY_N*iqdUx{RRyMv2;$+|VvcuG3# zJ<%ITDnF#gUe!v=4vlNrVGk@swp?*Rk&P0-h2&k^Bkd&tb2qD9&a3Ifr>uE=fB8Ci z7bLYR97L^Po*%=~pe}l~PE=qAZL;8QuL%72btoEf(Fhg3NTIZII4k-Yy1EPeG0uqm z4i(X^XJ2__21O%b-lBjbj<6f^^Yc-*O8Rw8v5446ZWTpOJXi<7Mlw&b*G5})onv#J zThu3a&%9f?)<9es`}HMUb{3@mW2`+gTn|kG+5r;`IFxlGv<~7o9_guqF%-S+Bq5l6 zJiEm#_S0P76Kw@_qjRb(Qb|yH)*Vn=xJXSdfD(cLaY3j#;6cWs-sYC)lXBtMO{^uS z26vx&_9^1cqKO~0wF4epdlSn8pJT3)z4$Cg0R}#0Qq5DN!9MMfrHCoA9!sT< z*4#fkZLx||gQ(`%`?vr}E(O)jk#5QX%b@=dnO8i*Qsq=nm%vW^0_@y23%hzBVyWSOzMIsOA33N7yl4z&@bg=u( zrRGa6h(pZuT~iRT?A-$G@l$+We(3LuYPM(ZA7Ei{6T73s)yLUt*8^?0l=b$U5M{6o-K{&cJk&8L53@J zg_Zu1Aq_R6F)44SB-R1Gh!ZR-ZSgi)2#cAthg90gv|%j7nlM!X{6$d66>?x8r6&qZ zn?Ydsy!Rl)pe>esG_F8{wI=9`;}Y% zL(@)qJatx!?^ROe$E@s3ekojWbPepJlpeP+h4H6NOFvL~=uBFK?94M5TJILIR8fT_ zP~i6)ZwH21i`4kUm-?`n=WvAi_8U}m{D5tXZ@qdz$iM_t>w#daJ6TOmKO^^*eSQoG z*}13Pe_Z2=Z^knP(k1Z4LFi9lehW|MJ#WpS$J%***GdbuYXmO@`kLH*)NZT3EW=}8 zZ9jJcWm7^|Pv9ds5z4+vZS!e15i334l@k$I&j$!ILYXaaI}*8I67|4;BvU;p<2 zRIpYqCoLw zlGrWcv^uV;GDdx^Ir=4!^G!0Em=30Q7`wwpgo~!96^@2y=Rc`*L3c2~=51COi~FDO z?iwF%zU#x}j4kkTR#*0(X-0q&NqIBbxPv#Y0!=ds0Q8vMRhDhF?VL$>G&;nDw@}}-x5!M zc#9)K*W^W`S0MP8l57F?S+!Js;X60a$l6W4BhaTYIf_)+qWro-GEPNjL;s30`N5`{ zBh{kWZ%eYHr!x1EGa&38kWBkc@v}vf^tYF_-Z2TEcRLL~?&7&IWYlb#Bo)kpV0AqSYWE7M%gC~2Zr>4Yr3YxlJZ;&*P>w}~^F5I~ z`A>$ZjCXb7npP5|vO19YA)9fs$i zku0FZ95aR}1^H%L8vD+6`2@QfQ7_6@0u`>SK!U!U#zwSSyyEm{?IByFxz5Qxxdxj! zV>qzRu6Q+jxNuMJ>(qFq{t*w-kvX&+lgJo6aB#5Q4{2b$L5WgNdUqw zZ>{h{IB~((6h5ra;!jDLGL`_8h)cA1)J@<(TA9WDsGzs-U3%h@`Qp?0ne#~|;MKu) zIkEp3n)-{3`(fE>#yMLtz0py>;;0G@MX^BG_2L3-zLIveclC+t$WGQox5V3^k_^L6 z7bpYDFfJOY!5nsIZb7>maCr9TWJriI;n%X8eN0S*73}Qbk0}xsm)ZTNRT~WN@=qgY z%Y2^IyTnKqzFc;B{E1y1Pe&~PBSsm9@A>caFr=ay5A^fgP@eI67^Q~m6hV~ECrXLA zPC7Iiid?y#Vb}3Wc(|Gbb~4zFVyT>m!WEi#NhK(n)gg)75@d1&7QuHpMI*X{#1x!1 z?wEwBIwB7w@h*|6j+m<|cFvTVgOmrlINSGVe0y;lrOpl@b&Ai-AkY9$yR^tSj;}F} z6IrY=NX%CY5Noll$^UW3kP<$*hC0H9ecO6l*I#IstEVeLyPe2r{pw{bpwFf84EJly zT5NI}Fzga6pf1T_QYo@g6)9**x0HOC2u*KFX}540S3D^Z9A=y6^qBJ^XYd*9TVe%r zYlHL*5leg^cdlgTpBs+5A*$+aJ4*;L{DoK(5Rj!0i=pViuKxNk8Ee+XI$efPUPFv` znRnLux3;A6XZS}A=F>{%@dXhsSPzGT3j=4p(!GevF8cc~H18Wcva#f3IGnbg0lL#Hufp*H#PJ!hb-R zx<}xn+nC4i+p)ar9&8qJL>mm~w<<=!CXMZ(6}&pHMY66#4C^&$-#9MZ_f7^kzan|@ z5Q-sv@u{mg6h~5vB`o&_$IM;w+*EqQzytSDEH1XK8>?M=HhaxH!#T6&F4|9djV0jhDWQR_O-n%H(uJ(e0VjV7dYiQ z7+kNPusk%QSt#eWe6cM%TxnuX>gR%^R-#QSW0sk_F|8u0^M>A-x4{rCKANI)W3vFc z2Dyc3BQ#%qpUJy~s>cHdL^3Ik>CM8I79a(jtOhvIqb$!Q zYVs-~bPtkY3E!;$?p?W;A@V~t{4+X?w{f$*-{fv|0boYBFb8ZO>+1}?_eXke1-3ew z8`j@|a4*Z|ck@5{wUUpuX7Ju|FBb)NV?POwmKJ2suMi0@L^q~}Nu>p5(gv^E;*C@& zJi}q{CMqIpc)+6;XrXYxNlx*5d{B7n7(I%J1gW;&gQBMM@|Ry;;qF%}+iEY%Jn(GM z!xY>8W~M<}xO^56LZyHpO8!?*Gf4#)croDDmNvlDZM7HA-0}QI_wttGDu_szCFtn- zZ*8cQR2xJRE=s_#HcpS57q?5WWK08LYdDb0V;0&Thst4@WYsdUTfDGbqNVVSSkG2X zs{=ctg0xLa$~<7?8?%Y`_LgIW(@fLYSPoMAI0yM*&7V5L9`YOD25K(>mI69N zV959V>4dsHv8)#tWtn6j7#E8zb()vz@$Bf!exI32Ahdy=f1E`M3B<=M5rNLbK@cR~ z;LYHvVKVxXt;lcg1}yD(r%DAMrr_rfqD+>rRzV_8+*GZ3PQqp_MzK@KeYKFo*E$Ky^|Arzwcix zM4IZ$5cGSTyU$o6zEbZBrhlLa-cX*ZOr}J-7UKzDDW2suy6x6xB=3PzMVnBBDK@} z=O-@!3ZLd+ynYTKv0;ILZ@D2b=|B{~`@=WTW$gw8g3_F{IJ^G9Oth6`ktVAh-EI~n zZr4QxJP)&j@qp7Aqd^GDU`o;t-YziFlSs;f)vdh!ixR zKJ!-(Va_QV0v&zeQv^S3`QJ2XqYpweg{VG>Jv@Uh3D#4&x_J!@SxaHB+qii8*|mym%Qlv^X`QDMze%9gQ%LnwKPDeoODr%Q@H zR#1q|1O|g)pq;=;wTmd>$I?DK2O+u3MZVK38qi^V~^*dW4(T*kn4SKX8 zj!2D0DqUbaNFzgJaeDCQe=T6BO5G8GF#>^c#Tcx4^0>Y1~ zXAg|nB%UzcQXB zqQd?F9=9diO{-954?SSN*bLy@m1b`6Mcs?gTTv23ouqAJG`0E-uc!ayFe9yK9y_+w zAoJQLrr?Pe0=@h<%7QK2oH4-92GNprB*o|knet>D_At^3G_aFNISB2?V2Ap`%kAu& zno9v@iInuJqoZVQDHF@4>yWI3y$Dzs&LxDj;(!4F>AlEt5=g`&S1vjfdpX=ajq&Gb zm$q?s>DCtYsVNF7{?EP&pEd|PeqpJ(yv@nd4WYDcuI-8i%#{W@mM&<-#QH6DHP70@>53B8A9(05gC_-|_*7VSy8Ss3!mk zv<9`|^mNFm0HW>$n~gapT&pTKI?Twm6pJNI-h9D)*t=KO{`U;Qv*WLXvO=*kB*2XGO4A=VKT$0&56RkgTLTb7 zR>E0PB=4J-E*~B{$#n>FMZiP|3o4iO&rF!`)K3A?gHCr;Ht;bG4ra1u+SPvfMc0#n z^DujsZ}-~BdvE?sme9LxuJ=^F6T*qtCQVTnPi@JeE$n{`gc5<~0`?5-OdK!Dv5{75 z!8x3pd1p_+G;`>ZF4uhtQ*M9_z=2jvEJ~wLUcJT(Liol}wOl>;34_^8DcCuQIh zl6Sq)7+18`RqmzLLy?7xGjxp_sjfJUv>_&+FikRC>FWN>z=z5G0d9xht_<7Xvw+cL z-!&CG=plr>do)yfoK;{L>hQUJo&iu5@rD!(Sz;2x27oMG#7UqG4(f?+Qm zv{9<<7**lns@Gf0^ZoZ)QFi(ZUw0?_-K-gIyPZg-|1)<p!7dvhOl#i}bQ%CGK)vO_YoB{gj7sbU#k$mFeuIDpcCsqk1nsT1vGcYNXida8 zK+)b@t_PE+Yleyo>3bOgB1X@o97-w3AONee316wICj|L|U(FaLvaZK}1}Lm%DI?+t z^%qJ7(nJ%QJ7W)$?f`N?jlW;gu5S~444SPpCpkb6zOJ#Kwl)cFd_-;lH8}Rf#SsoT zAj*@9{%9oB2oN>oSR>&< zt%r}F*S9}1HljcPkQn@p#4A}JZjVO$kzo9{0{N5x<>YI4e9l5_PQ6zpz3l=K)xX=F z){n}CcJ*HV;sAa^V0CBIL4Q>)tu_KGS3L=udGJ2wGuA}$Y!C1%O*Eh>eSiLppRaBr z!p)HF-Hsc$3szVwaK1^w7y{6aBow#S9A zFNpyzOa0?_(J^2z+IfW-)gF*319BeYuHJr##yuvwF(vDwD&XdLEz&jQplBLx z5)TAl?W_Z_7Dtg#B@dP4*7pVsA_A`phFUo^5Q<<{@rZ0P7$r-eWMvgP&mXH;3buI& zhmXlUqcZjb^T9T16)<$YU2$x1Ip0Z(qs zYq4)!0*e~)QQmx+adNnJ&I?7SKzO{d`^@M)urJxvpP>s-(A!u-OofTD1VLb8B5(TF|w)LYB?mS@8 zSQnhlKTMb;5l{Zvt>cdSz`=TE5LL*=Ao1YsCGtX|*qqe=;_=IiN;Fzz@`}p}_%5mL z+RGb1W!&^aosl#f*vxYtdlR@Fkzhbvv!WoH3rSHuWgDsT%pJX4vAe~R$=AjvZ+j6XIT zN`k4|{W1`*g)j6EXabI-ycer8c<})dm}8La(cNs2)J&}GHjs-5SvLK&7H9{#i{Dd# z3ku|uCj;}8;_9Du@|BA>qi)%%yj)#9>l)o5k*E1|v;W=PJlU4fv+`z>aUO-I(C} zF5{nq1+pZfY)R150#1N5)?7cH=t0OdfqOZaMnX7=Bn5q_ltGN^ot5QfU+O)Kosif1wkbz}i01HKj6kJ)#y;)!5qDKLNw^@RN4w4646~4Gt$JVQpdfFfzKnboylt6r zRlycrIYyKn=Jgz%YN1Xp8~$%AsSXxxqGM@LF*!>N{^8*-#36!~P6$G)Mms|JRl6@< zD9Qa6)1Ku77#NNl7$j9n+Y;Mk##iTgo8m+yASPuQlt95Zlta+HQ|`K_aJ^ZR@ZHO} zG=%aMO*2xA)}IO#jI?-{P(xj$<5PX-Z?7t)bs;7}lRa;_+sW#d?A#cI(lA6HA&fXL zZ(MMrE)I;*xwzEfF}r%@%N1V<(;??&DKI#(rgWM1X7UV-?6o`ze1129v=t1s4#L_Q zy;};|eWEsEKcIUbO;#1>n#bdC5eP3Ra*3;q00eA&9EA(kU}*RiF#rGtl>whwtaOV1 z001uRjA9>p!7dvhOl#i}(!)P20Fy|9p+*CsCUj463B;LSD;!Hu4^DVgH?Cm=RV%6T zqos3B!R8vqPoH3b3%D96DdsqErGazu++d)EfH~eFLmQEJfYd|T6&p@oC%kUJIfotG z{lkmh0s03pIgU^ee43{E%JcUJQA-WLpsV0n=>?liln;Bc4AT}@e=5sTA$TVbQexM# zva6O?1L0UslQ^*GBBy1;XDU{TwM7m1-s8?^M92iD%1w`WOTM}>95mTz6{Hna!26Hf zRIe*|KnpN7w5infCN5uS1Mun?VwR@ws$c23L5SVHP#L~){X{5S9faGR$JdZ<||CRCRD=jZ$XZFL-$cE;enG$ zL`nW-Xl<}uu1OzF2b;pY27gUyS7-GpyLJc!1DEqnMqUe(I{+TgW||=0C2KhH0in&HvKJTsBgrWM@>PwG1lhCtXwZ&!Gk>(@F@8y)0<(~X)Qb3_V&(uA^1}#MNmbQ2e8+Y? ziJr71J9j!801zd0=Rhn}|HFsC(`^b+9GVQOY-UWuKN1iV&lipirrpKz66-b<)d2zo zz+KuQ3F{a`oZb`|d2S0yv4jl6)5@^Y``uT;{4qVuoZCZdJL|`JXICons+Dj6t2mrv z>hur6*m@6Lk^F`9u*|E{E+E9KILi`ElEjyDM{o{$N@gV;y^S|x94DIsUG5by3ycuj z@dp$M-@B9`q{P|4ZX1G$i0RN+dM-5kG8$RgUe%ce2LlsifwH*{#ER9$C2WB1fS_`& zd+);NP*WL$=gNHah2* zeYxWMO-Ce?r886tbuTLNSV;PP?(FTajs^9(!(nGi*1sgEvLiTdmik3Ig zie1?(+@|3NGWfv_x!u>%d9x>Iz=PFJ6Cj7nXGX%Zi%6Wh9z$(27I5Y4=oExrN(sMP z(|mX`5C*-)L%c%vq!CzkX9)pB)ui~Tf#JfJOz0N<58YrIhZT~bE3Z{hUsG#id5-1e z^+TYU%7xFEhOj}ysr~akSr*Ui8*|bH_u1U1MG>S6^c_F}yokL?_Euaj(MVdeE{JX67CQ1`#i7(CN8|ZP>>MgCx{Cglg?e(}{a1DOq zbiKuGB`>p5c#YTX<&ja=*dsoEU66JZZanigbj%}{ST9YBh*!O1G$goWx_ zPZ@DKKWUS>TzRkm=p?ZTv*RAxDXsijsx7&2!JA5%6_hQ7(M-2(m(3&(xyv`1skU(d z57q0>+AI*F@VHg3C-GP4AoA1CfcwaHe5wJ~xa=>rGNBrnD0)6*Ed`?=P>{`g$~5dd z=HukwJiNuN(1?$XVU3k66cO;}UfPG*jE8O70(MMbpx?w&EjTBcK2P0y;sPS>~WXTU%PCwY9Y-Qvd)100aL300RSU&pi@XrC!Xo zGa^IIOkiL*)4F=sr!t@tLhXR-qu%NEpUF;)fGatGNPFog=Jt|vinr-fISx5Y`Qt@Vrt<=c(Qs-5+4vnVMTB~FOe%D)Sn2Hh)Uc0b|{-N%;38>XRtJqHef2;s);$~m#tlL;Fc=s5?J;KfMK?8vZ zs&DT;i_}l8q_`e&Aw@5wm4F$XfpQd4huP}Nd3hUP9$!5$?fwXjfLJ%wX8saSeQvAA zOaK57Fkrxf;EZL$D$yS$>3lsjkYCtsW4iBl2HoA%l@%BC^r8E;Abz3Ihoi0smpupA zL8Tw*MNO8-az9#&%de!`!gHXrV`(=k_q4|Z)-$&2X^{uibc6IXOvvFI>_+`C0Ku+{ zRZm?O&b^zL8y0A+008&5aX5mt?&^!=0KsGxalgk$`T^7)C8>eaYMGuIrUYnPl5Zdb zJimjbdrfO!xkL9G-cUKP*q8|l0jb0ccf zc0^o^e#f+pgkT=;SMUc+001CWL7QUdfdZD+)~Ri6Y?({|00RII{{R34_mX||yDMsR zLq02#U~RiF0ht!0=N|jB2dL-+m-+QgP9t+1OoNkuf_=v`83xRHu{H3auo=I>vn4;A z+{0dm4mgB)IWb1ma(zAFWS&^>46I$z^I0v{gfv5lWR}L$;>c%#8`QRJY{#>4rRV*n z_jeo7O<|aks;b)8C;)$?!8M2d?}mgoN~T>O1`(J>bhN`}w3Wcb!R*=(Knk^kU}Yn& z>d3F`3%WRAqPhNQ@TuM=l&Cm;<5gbZWiR$V`N-&>@r&^QsRlxCBDEt7@Oap$RvkX$ z>@S~uJ*^w*`e}I}{FnWJ)B3K)gXH?_FL$`QaLm{^#5_!~+;BHsAQPETBg`3bEPXTg z6pVk&VOzFhBsHpgf&^s(bqN54>d2kRVIV298n)yli8JLXOqD`OmLlOWP`2}bE4L{@ zM(_s&VBp~(+X$<#$#!u}F-+7|cKW415!FT_8({R3{DaHV0OCh`Y1$E0eD~YPg$7@+ zk8lRc6xWOMb|u4_cnR6_G8EaXO&}+4<|4+ENyYT+#STLo?S`Hq%oTyG{4r2=l+;3J z1ow!l{gnz|2EtCwCB=xMmy4O?f=~g}bZ&}Jw#!8mR2^A0DWV0)ODiP*(#wl2L)6ai zUgWdho(9hT8kh#C`kUGn-@?5$a)e<7z?Vy7ul21cM@^z}eq|G08nX1Gcx9((QHN2^ zJARiuY+s;%&xoeh!p?<75~+w&+_tSxzXMcDNxu}&T;xs#4RaXcC6BM5nmNPOg9guw zjF1hGYrUUqc^^{RPY(dfOn$4DDGt~V)Cx6=g~p%c2p1j4<+(S2Gf8Dpx>>(>Av`{a zj5xa4oFPQo%)|N`=?ZSDKiLvRUJTO(H8sUMl)Wr$or|SH5E_x-L6K(-!}v@?Q+O!K zobo)4abW%Z?@)D6z!fitq1$tGdQVB&pHj-?dXUhYMLQSeI8`agCiJkYaLm1(+ZSCYG#mPOhA*@y-+4X5#BVA zfeZU9^}4i!8SU@^cy={G!-!V{`B)8HFC4?_rLED^`MU;B{!l9_ZV3-EZ95b_v6a~tP;JrPh#?N#Qx_@J! z8Yr{mGG6OVdXMu8RHa+?z)lWk3=zw+8~Jo&S$KxCDR^ZL_qyjXDV*|D8ZkfNI@q1- zD1qSLrwfTL)UX9(J;nF_mjlU~cYof5gKk^2yHDn{uf1ZcJyIid`b%|&N!i40P$>n& zlx|1jNgw;f6{TtAWiQ!4*?87k5`B31kJJjtSF}_lB`BZfMemBYp2uK4?+M*t&L2lr zzqIWT)%hX_jGSDCXT>&bv^^>CJm+%+jJwRgA>af! zaN-cq#dgnd5|Y)?S13t|2~Incm6ki&ToqaScn>?De|Mgj7Hy|lj1D?r1z}EXl1oeG zPxA}%1$?1_+IT1cf`Op4Gg+=`LMJ3ii3DMFNwWk85zIW_6aig{b5%%lOXHj%rs^F) z#Yk8|Qk3u)P8^{ZREmjKuTf4skrDiCDVz;~yfSS8E_4Hb?>){?}*MSJ=EscJ1MSPXJP{DeD2K;Nv;m~w6#9L{vkAXPK2T!!5hPhKc zljL2l#c&y#IIL+xWRm<23Uz;|wV9Bs6EwbJO0eC90s7*LBd=80`V~LzfcksS zHxgsw>veYeU!SrLmJX+iB)1i{mD0BiC@gHcIzLQafh;q52}KB3A?ghHW>Cz+RH17c zUHW-AUOx0rw>p>&Un(5K2fm`Py zKwu8yH6JD&8SU@>cPWGfF;@6}Yv>pJC*ob)EpjCjw0UWNJgU(D4$wEtR8vK*cEh?0 z6fABtY6Phe?JMQK4zMf3{3&;KGCO@x9;ZYd6H?#KN}h22SAF8{CRoKHdq=YBB!jpd zjnQk&g;d$lqh{y+?i+W>d!(#DC7jC=r8_h^KCM?q-fCqN*CF^a7qlW!foBsynoD_& z=;rx2OIWCNSz82^$8Zx-XEj3qndQ6XA7YLzYsK=6+9YVbDV3*NPTr3}X+v;mERvWl zjWe^ns$N3d0Bo$xi;sO^?mX=Fl_}`)jPZbI*^8;+7@5*MIzPxlWhSsI`D9Rqe}#zK z68+pxay_99&M;P&y?(?dEu=ZIj+N%>nsmsw=JnW#9QC4$v`1-q2`37xq`K3naEY$L z9W=Ig^l~lEfj{-4_!ZJGI+RC&D6j4+CMI4e_HY3w^VbT5M#C4_;@kcCNs;BW4x5I? zMF2!jX%9#Ic>#;?-CkC1@(5If5N^#;D&1@>flL!J zqJ~w)x4C013QDmjrf)S)remJ8^c&z~=U>;q`amrvTlN?Wi_$8P8X3#C z0|eTMcEO+~o`+qrykH|>R`1MJV`1356{J*-qfufVM09?7pB~D&iW$Mjr}6?lepf>P zL*^bc%Y}*C4MUXES2D$}Xw_a=I-6yA#_IqLt6;s3h!Wjvs_4pb7O@$-C59V<$MiP! zi}0>6wd_aJsNU}5V#7{P@lS~SoCa_k-m`ig*5tfe&D1Y(yTLCRQ{%CjW(!G{ad2^k zH|V75em4ON*D(YPZybsahB-&>RG2^F1N$YA>!L9vSHWZ~47Y?-Y82sZ9IExcg9);Z z)S=n6FqAq%BTF#m(FB?LQw8E8Ktv^J^4SnhK2tvp%1c2g=Z72YCH(-1;iKA=%giOm zR`?2Q^h%4f2v&{k7k-oLZ9(!@VILH4norM=oGp#zwaNv)r~vU5-&KvQJZQ>NKk-c# z3W%S1*8D#t0Pj>|a_rUjox}?CUS_~ls1SRk9+^c0aHTMCWmoS|wAKh;r_{ zCVreEaTy2&a5h&jSh(cNyU}lZxc$J;@)QEwf>n2zzj;n=fFyOZdWc!59c^+bx!w1)TRmb6)3#BXFmy-llq2i#xi#ERuF?>C1W=?k~k75@DKwSrrp-jC>*Cp7F*ws%8nJpPl^A%&@ZX+IXCly@~i)itAetZ z^E-ke5j`P(QyrmLpd!UAMa9XVMEWn{qmtK1SoFOG7FnoTk^z@Z>byWg(9-3k5X!Xg}+O5NenTGsSr}TP&{rF^PGEBO|F+ z#Ptz0s$=z^I4AAz0rLCI;}P~)$st7xjNy`dRAJ9~Zg3{hD1h-XD8)N6_uOZsD?xVb z|7pV=Q%Wmvc_KO9+2cSWViVWU|Im!GyMSLwe<`uJgM&-Jg;gCqxqqu!27bL`aT8iw z3+J{A;Ypd~16`&(1SAymp>G~P1VgsI8ov=)g-+u{8HZ*jZei`Kw2#As3XSTL+EDs! z1#cxW1@=2Uc72ulM73Fs;cBafT!Tb8Xd?uaPO-21Pj^+rm0?nOP6@vK`|0wTfvyl9 zy$gyBPRWmXX6+dC8^$>>Ub-r|Q$s2&N>MoLCZgf-0%)qYp{@$uYM@sCf=XNQWH|WY zsu67~;`4i?kwlXv7EL9sQrs(MO`Jw%@9lMD<51DlSIi~RMRhPjk!QK0y8blydt_Bq z6}bqtqo*=oY;idyTsF%WiDpWv=}5d}+CCI-{EjeI&_W_{*BGCadCTJn-Xn0RCq zH_!L-Esy0UQc|cIW@YKe|1a;EF)MpQ<(WG*-XSb(1&k6KQMboxXD|tWq8g2xM{@4X zd8Srwy}$U`TNq5hZ~2ena(>29HZ)hoKK;B`Odzqk8gB`6u!FtRaM|nPW|xkyp*s%Hv(-dYW%7uaR%vw<~**ikMUpLwK~P& zRD_1KLV73Bb3t7vIsg6dS8bCTIebz`YSf55=_+{T>n(fkId0N8*^4bYT6*Y#UUvJA`<&)!u~RzgW+RE9=l z=Dqhp%=-}Cw1MK`xfIuP%0vyVqWQI0%4g-zf29N$WdJwGHbD211O(tP%ek0zN-Z+< zjj%5@*$02vdHMWY(!@H6(L>5eM7MJl0J?l*i}`6pYBeGjf^^jVy4CV-Lb zGf4^Irb66U;^b2*A44AfGg!-zHTIp|={0@;c&+xbhCf;%4vSgs5vX4kM+ z45!WK{{*zbQI#Kv933# zxUn9n-7}(zT3|wyl zlR* z&43oP?=&zyOm6PWOb1%ny0LvGKWu%#@FvannL~~ekq?$RdKjYOZDzlDd{2E>V%~l| zOJlEhut0*js6qWV;c!MDIO!>+FjwTFp-ua>Kfw{OnA*&wHnLC#xMEM7Fp{m&dlxg^ zR`NgB`7$ShdPWJ2PA#PMGYYiH{C0)nmrgY`$$Qh(2(zbkI~9|g4c!ypWfE}qhMfO_ zuxugxkuYa3^NSl6fFY{FMO0Z*Ji`lB@8iwn8cqNrIje$F)apv@D^dN4fn16SoA=nq z3oUV6O?v^0-S|!&NUVQ0zXrEfyO(R^$W$D&K)mR^N*)D@P#oUw3G|LSS>-{(;XWuXj3a*dOq%7uH<32@8pK_l>oqwvg1 zX$pai{NFtNL7%M7LmI#?_&O$JG)?jQK4sP7FWAm$!#&M~#M){v&9G;|OhE*;3svpZ z-yW*`IOA$A#qX~3x$o5hP;piaGDG89>Sb|=;Y;1s6F5f4K-S?BAXX}J-J(M-3XZSI zLew!1Y@x=UEgTw07#gGBOqkQ*d`q0^l_wr}-`#$`w)4W{RdQ@oLm2=_BEYQxe9}nS zt+NN{1^S9gH8u;zvu%)pD}E;))!49PSAzU{O!B+6VmCsL=~n~Q|Ekg)m3C$3<2Kr8 zRC3-C{G(d)SdK7s8{soEz0{*%w+}_jt9tDmF-RlMICS6?kO@=94gS)sfiO*qBW+(!-F3gFdt@?o}~Q zb6-k#HaC+r;y$)Xx~BRvr8j@ClYeP z^dk}`^a(+>a=sG2jQl8mJ?<0_d4@#g zO6memy{^xilj-L$tFLWkHji4`4t>Ip07Y{GGqr-<>JC~Ps<>*Aa5_Dnr2m+w6p!lua=;Z1-2?Dj z9dDYpZyKFkH$Sf>SX{JTj^2pbC1(yhwv`CEGfyZ%PW?H|t5-^*GGzXtrHu3O&3|xx_Tq?_-$>1+-TuWs2&7(WfEhEM2gqcEf zZHl9Pu}3l!OAqC>3|Jb7^Hx))!T{=sA}2g2-#ByzJP)>U{g9A#_%lpBb8>o}k#J|C zttbe-uS|9(j>7bEsY{`zm7H}SSR9~0sb*V*n$(|^c#5{Z8N{CjMrX^yGWvie8t{Fe z3$w9fqM-90IM)TTt2SRE77B_HGyDw%({@D;z@4-(V<)fF#G4r04DQ=~64J|P!C@J)GrVzyQ*+Pl;*?#}fM8&yEDQ!6~BgE&wfAcf7b9@+N z@V-fpCdeJmo!bWtsV$$MNj@6+6%J&WD{4CsyzbyrR{IK_`wQY2OGH*xIPu3q-P#5k znzTK&^GLKzlS!d2pyNYJ7h~&Q z=_D#b6F>w^CrA$vT1p7Wlxsb+L5)&jb|)NA3aTa=B(zglQr8ElBCWK5BvONF%x4yS|YT>0Y z=DSd&DxI)}^pwF)sJ!oA{uS~4ONazJ<31YNykGqEI|;Jo&xvS9!X(V$)mp$IZY*Ip ze(*PyAX}sdDNhBzKeT<*6)})ovSfk!*uy0 zZgUp$qI049q5WlflpRox^NUeZ#>kT6q6_%L;IPI3!*rT<|7=p8a0%wFHn-4$8_BoJ zWGV*|Pm^Gpwv!V+G;4)qZJZ0k0JZ6rIqs8=-fbWc0+yLu+qVn;<1nuI)s7_W*7Y?= z=M0nU2tTE$kaMX{{2{7w&@#)W#9U4ex?f?3w!1+eeE94JU_1G!jX+kaZK&>}`L8fZ z=X1ZkKVjGdHA>2-VPs|GE?h%0mVPAiRSO?YKoF?oX|n=C(lcWIds)(85_}gCxy)H> z>3`xB06{i{Pe2wHmXY>nvRCXsWT5=4PX43XQ1qIkdSzq$Y<6XHA|wb;>;ld)gW9l- zFxZG(<}i_Z+2LDW_s_09Jr)<8Wb;0ZP!N1!fDq=k#s#NKHlEg(CQoFZ4_EG}MprKAP}lz^~L@cKvPWC5Gj)`7iO4 z;1|_wgVqpzL>aZY+0nVyG!KiVafmC6H&*9nyxX6f^Pk9r)R?EgecGs4QvIbmqF=g; zTCm9KL)_(_%v|kGYBD*jzo^FhZMLqE!wC_Odx8WMmwo-eEGKx@4%-%}0ZY>ui?nZ> z;9={mT1}-iVz;N<$%)G-Y{MyGofk_VEC#ef!e1I79Y^v6+7di4)>1)-euy;n&7SKZ zqTG+&M)X?MJfh)a7_-%85!2<=-pLN&4J6i{f10hArq?NWi;0=P$8%JbN%z1xc-vw1 zKxLM7d{}e*>qvCK{Zx@}{hwa!$U}@;q5SJ;Xew7V0zbnNn;8Hun63nJhTT-f3FJ#_ ziFEZ>9>ep_LS)sUa}$9?6f(gA<`?da^QSU9-Od#RzsQI74kCj>r(DOJw=eWW6vXJm zVqO^w#uAuwVRRP;0u_}ykO&3CQ<2+?C^#ut-kE_S{@Zwdk5GWCzhN|Wrmqz#bp1HG ztz%wbSRcnbOa8T0i=p>bvcgMQ*k9xRb;V}C6U-*Hc2XpToEHefYM%E>`EA1`|9e~g zd!*|wbdG{87kYQDktXTBmT45z@`NXRtp<%!o%8q0O{tUBqQ_?$rIy`Fa4Bcnb7==Y zn0}lgWpBjD^t;q#9TFtt^CP9Ob22)o0}L7Mzybpla&wiRy#8#gN-WCQ$xAIJEYW7M zKU_K#EZ>S))_?WMi#Ap>;<_=bKJ1q3F4-{VkqaGA zze{WT_3mY(`%H}l6)cb%u9*_++Y;YZ$@+^8Bq5`PU(F@B`*g#xI%D8@=p82X72Wi{ z&g&(@n!x+zN^;WyJO;Lp_~vI>6Pg`xzPZg=1Rc00C_n)u!pP@r-h(laxwY9%JyerE zsA9;qe=>(-cvLl}q8IFyE~cje1j5(2GpNOB-z$I1JKUAKVrn}A-GQr?nkIMMr6+z^ z%Av2+)>{wUh)e)B89UkAkx)gx)W9*kB7Gad2lW9+52k5+AvC)#33hU`rsVC*v=65W zH*}@IpUA$#-3n_>EZtBrrp2*a7MjK0=7=IV8^$cXN7i|Yg4IuhzjIOJMrd;lKvMg~ z2yJn9AcpAbT}&0j5QPN9Yo2*d38KN(WaP;#(uZ4NJCI$$8DaAx@q;|Il< z3dB{oAS6Se2GfrhM2Y#Yj>DYbT_0QofrOJ7U3n`%}BAKxR6BT`21y780OW>Io8BxD+|pP_Ml=kFRY>S4Z}b%N-UW6))wID1B$&uW| zck8O0kq)P_{$YNxw18CWIesF%l{OM`GXZ}s7`j-kLdL@-Wy#QinTzs|$4hP`YYiCO zr2eBLDD-3a9R44TClfu%V4Z)P6zi)-9 zN_SHDv&QFa?N9?_T9cYX1vPf_;h!dPhC#Jl6$okh9ndSBln@ z4qML?ZJHUpt;scuh7tYYf+vDcCs+l2|KQfCGwsmKH;Pb=ipj7QlSKLa0?Hhhm!ifk zg>8SX04!yU`}cVGS-v|xJ9NW(XPob7YSRFX28nv-ZSS^A5t1h>1xw0)LEV98fza`O z^^I}-+3qEs-peg5K>Y`hJr?a2K02?Kbbn7!`-vIEnr3fo-yqhy5`3OLuGgiizWig7Oj)ZvHVP(Xm-y$bvg+ z3`5KDS2>iE<87BUzJh9HCtlfKJs!E^aK7L^@5x4YDPn=8@idnck z0R&5<9X@j9!BMy)%HWaW5ZviSLy^W^_dKSonBSTQEus#an)+<)5~%T_>wcu-bXbDQ zzA7NVUuty~pQ$6$6`uZO&H4c5GNKp91r)0c)aDH+Xv*m3*4$sXtiZDS>k$Q8acI{< zA!k@ERxitD0X+d_cbx$lf4qCOGu}@9MHbz~N!j@Zy6lU%5pq9MQu*mtvqvBymZ1&d zNJsC6rYQ^pr+&;B(1(v3Mg7(*H!~D?#n4~U7XSb(8bP0GY2jUvb7JS3{n!YPb_K^3 zSu=oAY5oouC>Tr$$XUWuVm|CbCuzgVt z@8gkFTj3R+WZ?kEBzs~(4?p|y?LF^jssipDf*qW=o0cFtq6$VAox_tN)>)DRL?`IG zB0K2v3+T8!6>ZebOpcB1X8q2IY zp7KA^1x(8JUFd36aKGiB5&Y@^3_NCM*kGL7?q7g_zAN{yFp-c$oc~X!tA48yM{ag5 zDfl<#(pmkeos4@ulF!iEjqfKfQwC&s%~FE|hZUm>eeRUsU*X$e>xx0(=}Axwj2F~X zbf&|+w`tHKzD*r^Rf#E+P%<5mAG#wrI8i|Qfs`ui6q?24e zKTa3{{af`6Ra2_>%MLPtV;0ncO>NzM(ZDe_G^I6m?L64@=3K9oz+~H7w)f|968?0% z@c3B-sDpBxWB)CaB@zMru*lulbB)FnO{0@i?n{7abzjm9xD^YuPP}lyTsFtMfF7bp zh9@Qv-h1HZ($CvoaqN2sT|?74{es*kq3=h|E*r;m)YJ-10L3Z$30yOm7JL+#Tk&Ru z5u$wgXWzJ-ats;%iZR=QefsN1g1x&SP!TzMgzv4=FP=^SV?(C$8>!H%4+(9}j{J{^ z({ND5L*QEykZk%#*AMC@l^^6(M2zXXZR(EFaAA5W#Trh3qITb_*wp7H!W=eCE(`;t zyWQa#T>bH(!RdMAb6!y_-*x{c&K~v=Zh7&65$uQb=RYxT)Z{abdt?l=3jeLgxwJXk2y=zQ^J2(Qw zhkb?CnqL3Fg>bGqFN3>ne_}*7je30rBgU)F8h+l42+Uc!2a$8#Y~v~h9X1xOa2Rm& zfRzDZOJ)TvExLOb52@&chJq#I-in3xC@`f3PzZIbd6lHLmGx9aHBb~|J_cNhvQ_li z2)Kk|9EbZ1TF2(j%>J?5M)~K5{j6}OJ+omA{rio?z#3*1^KwAQb92<%l`{NP%Ri0e z$PB_iktH=Dbm`)Rt@0uzQ!yBL7h8Vnxz@y~t2U#`!)T3LSu;D{sUwA`tN=%E{l<>0 z*Ba6Fc569YowiZ24#v_S{;dm;o^T7AbytL2Qw;GZ4b9k}_7uxwqTLu2rkqz8%Hav^ zwiW7e#**h9F{cgidI3wquL>vIH@JB(K()w)d8F+@JYjY+3ss= zpNR1cjAYbNen$^_3c7I5w9z%Akv>1_IbaSTsX2q}+%VD%g<)G}mk9pAW1PSZRl0j( z@(i_Fv6g&DIv890+T@4-TF_^_Zd& zuw$Fecvh=wfD-eWnq#hoNvffkj{`Jl8%Vz)-haOz@e3n05fhpClbm>3B|_Wv?t&ld zYo)cY)s!Hd$wcYG<#PSiQkjwyGKDA-6^lnRUrl&rSBo~9Q%ymIgM*gRV z2@c<1@^=O)J$*Gx;k#<-M8vKy4K1t>YRO`>xeVjDX6r{;<;u(2~whv;H)< zU4|+d2_gqvtOGyNRSW47o2K z-UuyDNzi_)(Hr6YKG9MtSir#Zc`SsqaF|)BHQ7N~&Ucr#xGY^Aj-@W$bi;Rw;0)Kg z@v*A+6PR^l^wQ#_Kb(c>qwG%ZFT-|NWj9oAreYjLtVk&c2=UM5V(%6Wd!CFduBn0q z;=5mWK9(tDFc;G6qs`XeP2NJoaZefZ#n7r8>iz0UTYPC3YQxLSwkL2jQcZu=?o!N{9LoBSEJzWZmJd^ZFm5qvA0{7(df@re2VQZttge- zAyLcRx0crWNAo#2<|+*iyiB!ykhZDSYeCvF!XD%noRk4j^~Xv|qy=Vqcb&wzgJ_=| z|5zl?zT=LU-Cak|H2*d1z7^kcNiy#-Vw)7k&JOFJc2abBw9(q!gaaEWas{@YPmPV* zbP*I%3u}NC;DxRm9jFDN*BVpO97_I*G9LKFX;l88td7uKdnrf^rGHi&ch_4$@)Q?9 zB)_n`Z{G>IXgH9oRa6e#repaIfqS;|G;-KppC)a9m|I$K`$*!Q9X#Z=F4K&Y-UPSx zOYEx!@*ZG2;kw^->Y@H+ZIbZ9C<-4!U8#4HeSQRBoZ!41v0M!y%q5jQy#{bd)4hnb zp9t5|hJe&=APmj?6D+Q|lPq}&aY&2dp|e3IBRLaKJ1fB5c0|Oze`@~Cw?GzeyP^zoq8P&+!xIkaF45jR zW@xtG#8!Lb9z2klgy2ZanK1dtTWCkir!&2rs3*$nDyTZoctC!y!x{PEMho{J-PyA6 z7}4bUwxI8=Ajp8*=H3j;y&|IvikH7S!&dx%GTYOF1$#C)*pExtxis>aN%E9N*MXO8 zLX0Q5@^mWBJ>CABs-yY5sty293Np@QooHaqJzQ`0RQF);^@l~ih<|@^4J7aJ{Q+rTarGF4nB-1jMq1$4MJL~YCLU{%m*GCXU7yy5@)A*!&WP2F{*{RKml7MAf^YxX z8$MJ?)28FE_f5^_yF?<`WYe+MU#Vs|doSKquQd$Cup)-)6J(DttQdk!P3uhljNOG- z@Lh~Q(TH#gK1cpEHWqNnt_iWz*+rz&`FYPDssNVioxX5=F+PrlzD4QdY!q`{gcE6mEgSYa=S0@XWd|0} z_E$%?8)FknC*SQ=t%4I+_nm}n@KvQFVGg_0rmZv(Lz6;-!C~C5=_1APt0WpJ!dk+I z>&Dde$ibproc>8c&VV)=}JG2yD9kBF$!jL6U zrL>?$S=G6`{u48PMGh)M-nPl811F&_R}fh?#o)T~;$k)nG$qWqt@_SP>E!-`cKYZh zbU*1-Y~;DO;0aazf{5PN@}PG>E(Q`l8qOR;IgMZ%P#|`Fh1yV!aP;=6cRusEc-?A_ zISbO0iSmXbds9+IbEjg>oSh)WEdah|2WsXGF@Ms)<4R1LL)1kZ1YrIYm_rLWpA|qYRm~=9cW(?w2)_{} zqh*I)L0LdaD{5ykZ4FDYQ=0J;%HpWA6=7#wLHplq828vOA36fB$a6>l(*Vv)Iu*#g z>s>u^ir!07Di8wKy@ldQugkCyaU<85pH%=TA)Ia zCd!L9oX$X<&n>jF=t(l(?El%Z~Fgj|H1k*z! zWk)ZP)6U&^K2|Asm*>X%#q1e{499}Yvg_CdmD7~Wf0`23Qc}5kS-WOFibTjT&K$00 z2_cTn>C=j@0E^B5D%_GxrVFLlETqx<5ix`(Kx#3(7$-Dw&{N0#aQE%m?X=w7Z%MSJ z)ad9*5#?X5X8Q(PT%1#Q+JrvgR5meLVm-I#$Jm2%D8A5!t@+&yyxg7r4PWndy>$8A z=A3Ec@wY?r{4Np7GoXqR|A+iwuuMKiXD{Rhm=k=L59V%m9eWg?&uDFbEjf<3xT{qA zJXd94y6^Xebe_mKzVN^yaBR+Wm_+iZnA|OSjcUuYLvAivYes!(Wkqi_$M&Wrr}6r% zx;Qc_?P@PFpqyUo$M2~qRMs8b){tZ@g}a@-7BF+6J%d`L5{x1EP>8C8YZ`n;+mEz- zSrledGK(^Ap+Bf$s}9RA(z4&@X-+x*YMSEz1`SF`dJRvHv$xX*IVtiYw*^*YDmVH} zgixu=DL&!jQ*ZekszC!6dv!7PM~e-MI7hX(Fx$9E-v?zlu~4sVJ@ z3PbXSG0`-zjk|q}(|uv2(UI`{pxL~95VwBs>O z^#q{gNLup!WVoW^xLhDe0U(saSSB;MkNJDHPP!A_sZ?L)3QCLHMOzY? zPMHL@(G?=naGqgOvG2vPj4;~&{zB<1Rp8puc-UGtugbaazjPrD5k#t9QlqjA3WgwE zar&fv>Zqf%?EFko4;m6At%PsXqter;1HS#pkxKy`#%gy_&hoV8APSYBM_ki(>tjag+P|#SXz_z|78l{nYtsFD z1(y~{84$;|z?s%}+EljdAZDAm@O3qBJ}8$4t*2~_2d4<-+1Bb{^E5iVJpGm6i_(<^ zp}0t9g_e#-=c4%UpnCKfjKdYTgLtfpjhw&!Xn*tC0Bt~$zs8Y>eHEwEyx!vE1=8Tl zs@4_ciLxA466unN!Qk$vs4W+4jQ=E5QKWB?0)twVi5Kry#;@4!+s+` z{!`OcYXbJ7eb9(PPe%9QoKPfd@%Pol(0F$>T)pZ{QpJ`YX3=;raTmVLDu)%W8p{KM zEYi=9Yhs(NGi7Q+{+%|CNsa;d$f6K~8$izP2zjy!zL&0+X+?xkuDC8*)(d6>8`A6( zuJ(i!=Ht`0qA4jFI2kW==rv@F3O}ymvkPOnHa~(Ly*9No`HI@qfVC+~N!om+`t{mz zdb||^D0hPzJX*;V4$$^CqhIk=MKJQ2xTuMiU6U80=cn;Pb~Xk**x@?dT@5CCwl!~E z*k)n&GxbHQ27Kqu}#-8w5_+W0If(a3I^mD-4|7sbIiij8% ze!eIk*^;*=_~(XjY_jjHV8pO}-c^ByAY3o_Qpx;?d)?SLe6+-Z!^;21rGoeW&1F-rLKsPHr8u%=*12g;wQbcaIaQ@a0xW?1!1M%qG+AnxVI1K zK7RrOY^IXzmag*M8Hl8H1jMvwIk^)5^>9ILr-8=a0kOJl5X1=vAXn9&cO*15;O&UN ztBEmuoQx?z_<4itorQhCh|TXqz#33pckdyi@`&~kh&p}}h;(1;Ul9hCOe~A;GU*%c z^sse?a#hF}(a-U6%f41XJG4aT(#yrT;P=)Y45T5i`Fi36$AP3{t$x z+&GdbCvQEQZ*y9jr6mTDN$lVeKS&$3aglEobQhQjwdEJo%8z0TbF|mQ`JiG0-g~2))KJvP4LXbVId|Cu`$q? zz#0S`lELNZVrt2#6H(3hjgE<8zO_uwL3I|}8fjoiXf6`?T(UEiD~B4~}?#2V&zTOEh9kF%W;NrCAh(71oqvhU3pT%oeH z*G{VZktA}{g|;$pv46g}YEO&Fu3Cb0@V|o)4u~`HN!$L^J`I{7_o}O}LZ*UdDV1Y3 z@xaUV1&>BR7D?ql>0QdZ&)@C-bC|`6 zUVG&9wsH;jz!MtOhX+4c7Y z{X^*9J6S5@X7ef=ObYf6yIkyu6UG|lMv}-({FWF_Iv5p?>&6*0)J}lkpUXXX6j(@O zkSEyrZ3fg=QvvegMi7wGff2{xP3kYo7%nnkEED4*66B1&7{D`7Y3jY){tCC2w(`qu zqf$x~s3NlSX-LnSs?Y8bI034Zj6T^QxoL{HHMK$C6q0vBxr6qJ`2^7sA3`dAFgS($ zc!S%ncW({~5FM|^cX6aBV=b|L1qbGQF%ox|#&+4B(Y}ZUzwS2*U;w~f{+Y;fI>j`R zoc2ssG1nv{$}W~<)d|$OK;P9KP9xzpf>DA@ThiJEC+$3ahIS24=h_tbO#=&OSG+L$ zsb{v10v`N=h~){UqdOSwyd$BssMUN3Cx=PG$9_T={>}pQNdI8-w&_Oq<(o2i_&6(N zhg0P7oV`UMRWmN|>DkF~{M+QPIx8K(#L@Np!>V4MpM%pce2Hn2lqLdkhFF@8WK-Lx zHBsC7N5v6F&RF%EM${j{1I0;MI$CD0&s%DP$+gJWVOw|giN=9uW&&=6wu5!sJDmF) zndnX~3XmsY+G+h2hsa8dF*-lc0J$B&n0s^&EN!Lh`VS!^!=M0GX`2R1osr%E9=<+$ z=DBbNvWAzvZwI2q^gVFvsT^EALi>v}vx}Z5s{C(vx|Lkyva=#TxSjK--9RHnuo3(a z!fTXnM)?h9*itO$hVjf%k01xcnnRuG;I=~xS$9tj2c*B5snWUOna)iTHpv1&^=E2p z=07ifZDMjTi#d?xJL@f>1ZO5QuJ@NMoJDD*VyCyV>LS`XN%!cS_cSJ#Q{wB^+KY-~ zrpvh-LxtT+gI(?YQ!NFt(eHc*#C9dWCJ*f}17B-2 z=(egupZVxH7p%I0nlFSWob}on{8b{UT)(%4yCweN+zpGS!ZnL;1Q2QxEPS2iUxlYK zPi(U_BVD7`Q^B0icwo65GTaIS^QV1Wf9I36y>Ib>9w;AgAhd+sxlmFb82+0~4qnm~ zuON`cVtH7y{^-L_ZG1)GhrGPxn|LgYkFG;yzC;XXpCS;tF8w~reE#Wk?tK}JcIpGh zf<{5%>{i&aDJVH1UTd76kfPD^LZ!z)Umx117%cdmL%-Chw=(0=nrCk(F(FD;|Kaae zbD}l0AZ7^emh<+9CSU91`GycLoBMi#t(L6KkM>r|FSs~T1d6)Qop>yOzjnYpgftP? zTgDvuxG#!V=LvU>G`F+!`^I@n2nD}b$~IXMVLA2ubl~(MTHA8*pHOlKe>!K$YLKf} zxs7wZb8fMbmxqSvacz~#m-tTpyY-qm>&9COCKJINNC){?a#C25jXU@Q=k+(mgm#21 zSsIK!gYH#Y3oaW6i~cLF||Px96KQZtqhk-W(iF$@p9R)!!|hL(o;sB>|Cy2nN=#XuNw1>#FQ6+JOkaYRkijU;+HbPZbsT?3E zuJ&Md9C>aL;7WgcoY*fB_qSA~4~&hu?Ou7&{nO1(5Z6ihfqpG(p~q6n0M=^9p1%Zo zvfrRbVBKMbVtqtY&*M@8-A6D=m&qU7GE}3@Ej#OuI34BbV($23%jF*>AzCWQB5-Gd z0SNNf7KvsBsUb+JB|P3*&#+`U!i7PIhp57%fQ|REiP&)NBiTB~u3zO4IF)ge1KGxO zL0UL+B10^X+bmjJ-L8@5p%%e*qnWh=RW$FO7{S6B<%j!aOmFs`J}?0}ZA!U*6eemu zErXRNP^is9F6tU;8V(Zz{ zq7bCu`5M=J+=xU2$dg4{fgm*fQB~g>QOt1MG|@k{BlCKdeVlLV7k;6B)UI^GzBt-) zP7!Cdj`vFt1Qa)WMMs%hyy&hp z{ekpNd+4of;>*pK^Owy3Gn?#uC2MK?e?Z5y(0}Jd_BouJJ~~DsSpIXY{bH9fNi}&M zb5S>{!*q@x@3!-ay{k*Fxv735wkTlYh-5<0&dZy~eGyJt>7~G5;&=>2A)YALe^j)j z`$rQXGVDMl2G(G>N&5nyu`c(#sI0!48sW$5CQW;$TEL>!@m>qPvk&FO>5Fhd3S!+$ z;LOCDsN_FZBSId)f^)rscn$MQiT;Xy-Qz^EK~F)wVuh(5NYePUWojUrG<5(>b|)o7 zPs5;FO7tfr%D1&4jug}xp=qaQBx|$Yp127^nVeFE^w~`8Y?^~S z`a#62+oAhvR*0=M?q-maYM)XTvb)UJqjSnbJ!F3=ixyg$b?NGS=?h(qO=u7xfcP;~ z6b{zyn4gGhVcXg~0QK^PFy(0N`KGFh#KGcb2aF^yl3ADQE-#5QLXB5WAPF4tkJnsu zY2WvYSn-Gfde|DkPv~GT6D5VJs$jdw&{&Xf12zfy>j6R4mi+U$21Rjqq|ty;(Ox`B z;K6mu7B`PKJ2Tlnw3YQYhFEJ)4}y?f90pPlwhf)C!Q4AkW?nYUHN<_LZ%gg;Wg6wJ zr34I-PRmkOtS`rERmW(d+rrj(NOAXZuL6bL8IqBH?!LkKy+t0T zLa$LXKMW&FI3c29I{If{xJU7D;H3WS@68nfE~I~r|Mb0H?C~#8m%j|c-*4SQxuyo3 z=FHU*2s0>fKMKE2@Z(bm;1^y$IJ2zFcidXeN@kmUNo#q?0HDJpym$EgaIDZA?9QMO zS@b=U?{ZT`)?Xbwrp^5UFi!A|eAlhvjOfI^XJ>l`!1a%v{? z0Ng=?ACeYF(cJMl4}>e@_L&>7OR%qswjGrJyYg~UVe?7|W|=?be{QsL)#eOw=elzi}fk1uwmf2I-xa zqQaniCLY-0G9r$KEp*oQNY2nbfY!?344_HqomiNS{otq0zcm2zSoU1Od18KBvlM>e z>H@OodRvyBai^0WlbDEc*CbvfakUr1FPwsZg{6k`IX~A2_C|C ztXW%GqxLNt+_52&_wrbF9Tsh&8T84Ca6^&HsH$&FWofIM73B@Ko;2D22j>m*EV#hI2m7eTqLW{5yAa=y{Ym%lC?{4YZdaTt0%}2}7lW6W zEI63&p8Rycs?&VCkcf~}3$Q}P;R!BZovBHm7?wPp`$}MR^lw|YJ~hC< z|3+Oi>2u26XXlHz>LL%_g-O-b4q@i-%v(vay&qBDo=VIXEGX$hoSKlw;|C8{n%XKE z0W;wrNfyezL&t~E?{KS9krw+R?9DNl?AIA=z@vGLQ4MNxW7=+S2fNDZ1)ks{6hSdS zy=Ema2s(q$#9|Xv?%D0k(fkD$dDKJ)zZS6uZtr;blpZ~h3%!Bn3Sia|qZI=xeZ$Z8 zKbZdsmwS6$Mo+jv{dvZ|4PW~C2LfZ8ROjOGpYWFxlm{=#{l+Sf*+sM;nKOGa(@kL;~1 zEJF#(w9;#kU=ubVGBup_T3iPX?35TDnG|_;BF6=%YL%?i{&GI+x7DCCv=b2kSiub* zu=OW%@RC`35zS)R$E9yZqdelrb^jCi>X8%^mOra;-en2v`asS)n(zi%a9UweGVieG z!;1@PhdKNHBhFZt?=#Y*t??y^F;$aR2+avWt3I6l5vkUQ;U#tN(+XZJdCe?p1jXa( z!m`xwumo**{$-4Dl1~GZRX^M(?I&He-03_(Ckchvz^S{ z;J&y{5q}+AP7O0zfe$^Q_lTS}r;Jm0zomGeCD_-pzjlz$sW4OfM9flS?;`z>hauMa zPOaaT?{G{nH>#uj#Ndty@_zY^c&$?7VO2yayEMGrqPrhZzk!NR(7-1ZMWHdOqTDHX zNmz8{ngl$5f7bssG_>?NaPUAhyQJ~2`hH}umRZgV8_~2IMC3_K`6pg}A#pr}>96av z$X*a~!ZoJ_)95%FgsQxl2t_YH|Kq9x2Y4+CcS31$(lcOY%ruVeTrLG;(P5|&Hh(W5 zO^GEy5Sp4)U{>{=y)j9^>Rvslx1G+z+y1O$3o~Vz>heIAEk4Zjsq(HIr|ZytI+YW~ zp-zqCl+h2ik~wxWnXRfb;i;zNxAW@3GwcbmVFGE)+q1D_=1o`WOehq1a<`D}$N@nm zPw^N9Y0`oB{5YGfL!Jk&MxLQD8=FHIHqD)%o5vy{)lYyh0k!Yt(jrF7nOTD+=^QZW zx_Ph&jh}*teDo>>*)ZbXbN)n6tKS@eA)E6Tqof2lDRck;0{|ESj)01N7J=Zg&z_De zP0_D*_DS<={QPr~Kkuwx$$j@ySsETq7NFPuZLIqDS09(!5@HH=*#F0=@;gvzc;qJ# zHm4B;_xRYD#^%!O+?c=IX>rL#Pr@BSs6gX_uhx-6obV4SkgY}YDoY!@!kc~mxwqs$ zRSGYbBo*=>NJ!T8CwkBNjNm7=v2U@BJk}PqXktgVt})DMA=aAiV?N$w;b~a@ShH<1 zVg94{C=GptnZ)$QAYOBJfYCg)#O&oZ{?Cf9k>h0nD8pH|QixLz76(!ErT1c;kmB{! z$H(!b{>HsY6G{k~5^ad4>pDK|+}nER)5!ajw^59K*qwY3+M#E=|7wp0`f<&G%dFiS z0!TH32gEepNT0@<6|&tEd^Zc@kI=YF6vET`d1-5Vd)yW&v>!qFsoWU^K2^M!YR*{? zp)uVreoq3d*H;QB+Zj^{fM4uc@LKC1%P)=T%Glzud)~zqt8HLIRQ-EUqS8bxtmu;5 z%wfJGa8`PV=AB$XUeD?a`*zM58OX8=NqdDW9LFc8X%va1^1LSl4@al(_%+Z{dyn-zX1fBpk+zGs8^Le&{GZLl+ z(=K#pmG3-zi#ZBR9%_?i=#c}eEmwi#+#5xnUnhbBnbbW?WFEuh_7WJs}ZCj zI;uI{E?*{E4#^nB3E!$dybcXUK;gSHYykJ;ZvWivDyZnpCGpwv>n_k zHcWLKV~X>o9)GE4;k=hJTZw}sU3UJzYn`?grsN;&TIH9|aNR<@7k4tkThF>Kh-a(N z+Z~4`z=M$9&h9UVvtB7JM^u^4T^$V^>3DjaMMYkA(NqOwDB8-R!g3B60007u0iSXV zY9hY?06|r>oDOGxNkNPKwX2BI7O!I900rd!KB06NFRKE|aZ=Y>4 z58k>YG&gyg#Zh6H&$%dQTouoYyQN4e`<=n>?1oTaK?QIDX7n7fq_cj1A>1p%vk9&D zQ|6r`=R4g02lI86+{^4c{{Vt)Fvgmx9J{_@lnpSOTYq5DNc!YO6Gwb%uqRJdWXOl! z2ej`5V2qTPMFc3$;Kn`LrzTO?kyn90SBG!n7+mCzn5~9`&KdoYsQB9MOojnm<0{b@ z(~<8T^nDrY=h_I~&sS^L+MG&1zN^YuMQCnv={}H20~(0})GYU`l11$4%2ZVY;U7TulCNnWT0WaCP52UGNbL2>8tyMgL* zk?UiWh<#SeH(EhP$*vU$eFHkO#M@Il2BXv^YmpckfP1(nT&+K$oIwz$z(|6Yec5eji}n$cKDT7AhNok=e*{?3 ziX>WBSdfh$RqjcSj!V516tcevM1k{Po<903bdYNUc*VPRjYV@drzs;>MFq_C6#QHvtpq>4(-)^z}sm-bS& zaYzHDS$zyPB)$*}dJ@S!nwj&vDuzhrR7`JlbK$#qg7e!l&T;)*n(!DU*$+sZ`gjb> zh?l*F0tV}5T`Z*{Lz{LNldbs#vQ_35wY|pZ#brDBn1M?`eE-$5b9N7)!s4vkuZcsO zxTIU$?XzLLuXsV7WCH@%`+5a3s3ipe00MpipK>f}BEJ9tK~!X*PLD4auSR@pDe<(GZ8XNVfx6?hnG#6oSGHO_Oj*#Jbz~vQ3 zu9)??+Z7VCU;fjw&o!#}^i`qXTE(4A{9KRU*M=E(PzYl)%v$Gi_X45`9}4VXs)WN= z5O>Ohz)+8UJ4qd;CvxyW1@sARSO*Oyzad^Bgv*Jjf*2sBv!Aq%S+2lBX9S~?1Gyt*@H9ACk2jz@$-XGTh1yQTX9{>OX&;g%vOll&( z002Q%w44ev`f!<|A2PJO78|6X6F2D~cGM+Lu1T>dG5v#1&&zRLmjzkz&z~0W@%ZFV zQ2l_TrZ)Rt*Ca~588~DBHT8YjM0*dy5n{iYY(uA^Kh+iN6_c`aS#5xzqth(C$HQUy zaeq)vYOa_nU{K@nda$y9Y1suCT{}&{d`N?cRv-zH=hj)4nSD|!ek5oeHuzGHh*dWA z&l;Hfqgd=_gBGp?6x&^#exTO`0V|lCkA#JO(bIvUcri;OzHZ8f)m=Woz6pE=Hnz$d+>z~Vg4i=*n zACz+b(ssd{e6PmL#4;=3pv0@`_SPy0Sc{n$eCiw#T%BQamjnjH(XLKF+AuD$0besC={ds z38z_xl(L#!hEZ}zCOCc3;avGcr{=O>@5_c}c6v0=n>h6ZMfRa|g2T zTkj78WnMsFCTra^40+R%LPXXiTqbkXcN0L!YY`0lsoHW{WjU6M!dBt}x3jGkUSf6+ z@^@8~^aP+0Y%18!>lKx${dC=uN1n!}a3j8CGB&|z@=>A`A4(+oIw^Rsv+)@<8y2KB zA~(-SI@W^(5u}sP9?fnyU*?p~jC6|s002TY zwHv0HAt^q68g9+FJ&ogufLGwmss>)Zj=J~wnBl(k-D3nDU{Dt9i2yCzlFtVdO*9h< zPfka=zF3`HzI=bIWWbVp;+|^}nXEOwCMxSAN~e~w@d-o0`6$3W8hC<@?1xLDlyulw zJy&u;@##yQ{r_KI8f>2W_3ALsrfcafRm+Cxq;RcFlwiirnY^) zE49of?`0s!gV9xK_#*x+c-xt93~+%)Z?U{hij5WvKFFEdct z#5kdWa|RfXO2@4r&{%!d zpWS>YdYpWdkd7glO1BB?Y(hft2D&2FWvg8;YlCNq>g*u34{)Z4I~jG>AL^`jM8zS{ zY~+iSCDUxc5lV?I&EUpxyVb^5xO83chaj+2%7Tx81GwBuUZ~%vqCKZnl|Lu;ieyeC zO#|XJazn(mG_1rz=*S1~0-LLtot41<@r`fs=-Ovhft$So46AyuC*I7`;20#@MxARS zPAN0_Pq)QTGBCW?lG|IkEbAdLh`*<$)>2u0k>QGGg7_ngswORt5ZLO7t}Lk;PbCN_1g(+3_|W0Y5oJ z_XvS^r#8ZrGtS7LAT=pANeZY!T5@{Rf;6{pv=)v}?-5Z0Lc@UTSmz1Z;3q{jck9N# zk7UQo`I&$K3{QqhXIhm?V59orjE?y5KIvmsOQDbD8ef871+CdaCAnHV&%0x&3B&R!;zU%NpARTSRr=$l&C)l zZGI+ezq74)>z506oZ^1(a;Hhu?TtYkOsG~0u;@hqEQK}G>yzjXd{%faE zlLC2D6R_T-F3BC+H;_aOhuvdb!Vn{&N<{CGIQks?uM_=Y8W)-7HXp{fAZDo~p2x;} zucK(ijx>g29duovsD-(n=thzD(>a=eUs>>HblgECJM`O?4u?t;7iU?piVt7n*%jbl zqh}f_gAL5a(jx_qO4Cm)(Jd+P)_niD0A}>Wc)6A;6rGq6000NJ0iSZrbc+7~06|#O z!r)aeRH74{9YVghew}G-92q=8DDGnC{YX<#ch~+RnR|l7pS)Lvz!(z&BTO&^7%YO2 zIC+jW(e*<@Yr@)gHq!~V{G4P<7cWA>4{6y_e+P%90^bqdds34GUJofM{;65ECYU}% zgK?#Y^R&@}6Q+`BJhm-;cmuwH1ol;zU6%6LLk62;8lvRZDq=GAH=DdFubpXB1_4M; zOS26_`wR!ejN9e1CuCp5d0(C2;5I<=co%2X>Jl6WgO)%IX?d+gIvhqCVU)a8#^Rna z4`e^VX1mM`3mPSXM(8^7c&}yg;h6GoPf$ircK84aj&6BDWs`EEJ0dsP!;qO9=-}4W z!gYmg?XJpUeaEvm0|XX?)`Lm5EJP{FD!9!dH~tML^Q;L<02@m9{VMZ^Tv<11Ja)h2 z(GCU6>d@j{#n@#G2?S=WCY>_5NA+Qz6_mRbxyjFvbgqqX^XmknBofX??<4-C4HXQ5 zs$iN3Z%WBFVm;$r^$&(Xt;xhS%T-BpE zFVRG>XMcO`lMHHiQ-=mBgP+!KU<%@GM2e;~ev5X-Oo?Eue+>14&JpToIXD6K&|zb2qf*{PE1G1e|#?+3L|=g##qsjE->4aEI~+O{)E(En=|Mcrrc)9q4vZQ|(_f17wVy z)at#+U4((W~WT=Lv37t=zOxDV*`PAZVK>B|_4lT|+~dNyD^$+}3c;%z*sp zsy`_?Xqo@3F%^!Hy!U4e2&^r)2t!rkNHF6{Ux`LpLg0WsX$lR{>0kyUtS~oUtK7b*vQDwnJqM zejLWJ%}Q73`ahU92Nn_21B3LLj3VJJY8GV$&N!nvnQJ~Nb`LyX6AFr;{5yGIRF#`# zBC;ExX?9b2kIP1>!6mti|M!Bqy1bv znsf4q+*-q?={krBQ44l(;vH>3`p%@r1`jc?ne9L%l&hQ#QzADQ4j={@%ZF9Vhw1!c z0)udQL>;VHF0L!JhS|r=MYt9~VS_aY^Vxvl3XM$q z_F)xMgm!c)`j*%`gMjkBQr9oMu0D0*We9aFQ2yA) zppnLng~Kjl0_j{TTdJW?FF>HCN~xwgGzOCBAOY41I`C1~aYke1Yq$+D!AA}+zs9V} z+ac0)enFG2G$M}2ojZb&2W#5(F!q_}RTM`M7E)Hlkwb8}_!db7ga+FkN*rl3f)T|e zkr~Y|5jJ}_K>dTA|7C7ZqK0R;er(0bmx}mOcrI>NdR|6g!_`&d z$a3xKnXX>jFB)kBx@B=(lAprN9#FNHbEG@~$3+dDcHtPZ;(~opheWo16B73Ar*5rc z6RD9>>kVrE0)=Xn?A%cRIU?T{jd6TDw29@j(8lIL7%4uhT^585xldRmTe{lmQL+f< z;pp*nR>mlxnt5z9NvD#3W)}h%eCpn))nXf*cqnI0u^L565ZPo>BDh@fEbA5b**-X>sTKy}#7B z!WFgPBC)~}1nV2o+nGEH@4%tMw!+PRg1>7h;6I-tcfn}9MEY&&kvXx-5=)TK?$zljJMlnG!@hpyX ztOP}B^a7iAi4)NK*jNRqcC~N4*A$7`{LI2K$A>8+@Gg3WVc~5M(XG)r z%C+STnDHn_1N9zI3J#@9BzS9$2p@&zr#1Aw;l}0l{WhgaJ@qIcku#>^AqKP`K(t;C zgya2#*3kx4X6D=bW1LZ-YPL#e03mH>gSpqT5kz+7J*R7S>{O3I1oZ?d7&yuC;|DQl ztxSZM^PJHjH4)&FH5$)c)1Ijg5B!twz2-}ni+%&h)sqSS$P=b}KYIJygH{cN9X0BBQp)2Zy=P4oL)(Z9Af?+@=+#!;w%2B3|N|sw=m8 z<$Coelm37IT1FXN&6o{Qog#wJO>+~cfX9t7XHj8zBW5o7W&EMdU~^?lE!J~}Rgvgp z3@EGMF8B-8@p5{TJ^p+6w5*_wiCPc0A%^WX#*iU^;U$GZRe=NoIDS*2Gp(OA*_|Iq zaHdzDUCV!h1C+5-7bTKTa|A|k^ewq%UL}8`V96~oVsqudTXBVic}Lkj(Zx4`Ns~E5 z{jFMTYwdn)Q;VdXK9QEYlFR`aYA^9F5ZZBwjIt$A>Z>->b^Vd4{hGmfptfc{$Ni)2 zRB+P9hw&8D*Z}2x9Rn}km@TS+B@bt=F?kVqW4}g7bm7YFdVoUPbnbmtl@!V40)B~< zmbUZ9Cg<-CR*y^^7ygxOeBfA@dAqgJ{P~6^W(Iyj^G~e`Z%Pf7+SjWfsbK^DN49R9 z8d)#6sW@pEb?+BChceW9@uCZ_415JwucuFu>b*7=lEknGb*KeiMOAf2HPJ{lbkD6_MwmYLp)p9i=KR9Y8!v(Xy?X8!B! z*L4()2cDIe3)b+>XuE5o4q88IT&ld$TmCip5~B+jQ@t1dXvS)Jjna`U@GjRzH0MW! zj02YMBPPx9Gi_`^Xk@L|Wp-iiHM@cI5r&xk#%Y6B%Xb2n{PCGhMxi}opF?Rux%`SIppnPX*IT_A^%H27gIA4@PEQxEQKd| zjUk&$=VH!|@>P6h-=`*WPoJ3|BQnGy4PoQqYoB9KDbon04ep6oxv>kFScs_5k5}v) zDB;|FdyOpe;FuGT6briI^m_#4pH!m6xK@@z!Hr3sC;^^n#eX~jKDwNQq>pJS?7Ny% z^d!MUgg@_iW+HuFHx{L;!_u(S#u7D=#ObmM_8V&OHg8p2sGWs7?5#^8C?2cIqu|_MZciMx}ZWRNB)2D z^&W^(6Z?}!HcHU`)kp4V8MzGmfh8!R)=n-i=eR@DP}NzGF5{4=QbofiA{Mnz(`}TK z^mftWsEp||Zc31!hErM=9cS(ISX6zhN&^rErV}NJph{}9hi5mI$e0at+fP{>qNW3b z#i{7r33&Gw!c}=8Gp!8|2( zu*eEFwcc4EHpQZ9kJ zmF)ocHk*H&`ruI%p?PHl2)FJ(J76@|Gm5c_CyfRvFO4r}av=_W+FjJ*4_dz|); zO(%)0d(nddl09|dD?1jfA(rj!Pn596@V+2NF@tYn-JlpFf(GBiD8eNp9HkPb{{(!@ z4;<+r?Td%U%C^0Ri)ttUVIu2)9i_Avf(IY<-*rOu$0}v3NpY|hu;Yuf@DwuqhZ>o^ zaI{go(D_pP0>afvm##+&CrL z3N3_Qwe!r$phY(J6b&Zfb4VneKrRJ=RoBrn%)w+M7n?! zKo;b7_>IV5v^fJf;L%mPl6wFXb7>moicbEQr?WU6G={gzguBnt3Gtyg)Ln8i4SjL= zqKC0U-H@_eu)cFWwkcSd6R$7=CVC-#+UQ4wnEtoGoNGZ5lGwv)YXcVzE#I7e$>gWR zfZ&Vc#ZKbmHON7Za+Z;XVwlBclhfpz*z`HPD^;M)cGV|V+iri?^)^Z0?frJpB{cMH zX>S^S*?j((O-+63>OFv&9g0w@kE~h~jnQvRywN(6h89dUuAfLiL@A-YnRS!$q*a?vo4#Drn!FmOw6gVjnS`63*^>_6G!rI} zVKBkMFb;ESsntsH!Xt`jib-e0z{|DiZwL~OBcos-_CL>yva1?7U{9ZY5jj91VWv>^ z-H+E;S}K(%YII4${#A^~i9#Z`gzLr)0e~P?@#1fc%#lnP=;`a(l1{n} za&b+c;HzJ&N5v zrNo7Ltf2EG?Dsr!TPg$%qS}*5W+YpCSx%V!ZA@m!ZG3B;25^a13{p+luY5;|((_Fl zTL$;bJi3&Z*K;yCfGLEdkeX5C(fxoRIWlFcNw;MxSK0_}R;f!)m}NfVhKO-2n$HTC z3!_&e>Q%b8);9GdC*)^I4HcB7?TpNoEMwX-c6+cIumjLdW6towyp^|Ah%Z ztjFA|jxKH91yw&w1`W+O-&X_A@^BO0jHbnGVybwQq_^HS}pd+~Ul$yuZ7ug9&rc#mLy-lxhFX|$j@fYJR4{yQ-sVCiTvw9tN5h=E(7 z3dY5K{n>DF!dE^{U5z89_?CqS7y>{#XZ}`0NbTX8;&_>Xwx?(<@)`?>WUC2jFuE&V zrEAL?suX*nrT93XSQpJw5QgvPP85PqN#b_Tac>D!KTO$ooFwnH2SJ7Lth^9(FSp5d zo0wdHdl-J2{x1?-(YMPZx=^VcXXe3!rWYy3yUG30r&Eo4Gdf;$rLu!o{RUM^ZJPJ8 z04w!)x>^f5A&i@33A9G3F-0KQnCV?>B7rAL1YLSC|2_yrk-9N+Jdk5K%a^Q3d68&p zJm}w+&`}W6NbZ2_7|`7dAvd@+2lsu&S{BPkW)WwvKPA9){(_X+qO=82rDjjS>-}{y zNkvqPgL8n`H@8vV46cObRPHdQXTIvvUI^plI#zPx4Hbc%5L-|3QUPi)rP{X;CzsL! zf^G?94-um}`gy{DfMOLx3^3man$&G&N;MMKn9S+n1T((`)TigToZ=S8Mud_F%{FeF zyla6Vr`#h=Ep|0>%12xTmu4tVN!wG(2+xru@~bSipz8vpcY)LUR-p!+fh`%DU#&2~ z-bryN3G|9P1pbw%h#Goc@goPs@{5^v&mHH5XMM%~*s_N{zP!mijw&Q6(GvAG^seDk z8TMk1Fs$-()cq~HB-)cUI!Xo4=<)yvq~~DElQsYYKnw|SE=~!9qIf{0JqO|e_Swkc z0Uls_B)1}`$W{Ta%CeSU>wN#2+H&r_2>N{aJSY2qQ=A#EhDXDO{GT`aEZh*ZMV?d2 zt#hi$#LPZT#FCUz=6{$$*S>CP#Ln_ww;=cgr9=~94$gnud?{LUY}{{|BWPmJG0Jo` zrTOTE*6Gq$6Dl!s*q(RyYjpYCjWD+GRCSw1LkY0__O;$?*wRi_{4)rt1bux!vdRV{ zntM>Fn0GwEk%HSc@J>!LdwmQ+gN(E_{pS1HrF0%Eo-D9%j|l>6%{j#s9=Hn{J3%yJ zQQc#%9my*>$J0ip{i-NF_NFy`CO(u*Go2BeO|Y0##1|Be&SQ)Bn6Y(to+;CiNU*gHf!%~&fa{pa&Ln7+Xq`i(as^P!QP*=?JM-79 zSQcEiceRy!;Y_jZ30@o7-Z26(0lnGN+$x0ecL)lN#h5DV$DPjme%jdAQ9#^YH~~4`hZx&?0IP zDpzt2{vI+2;TOg+>->nO5F!H|#Karz7J_GS@#}eh#92vRM(MW)(WWbz=d|qzkfnS< zW#sm=11r=8d3UHf@opg`Wbyabp^x|&0fB417;o5PFBwxpN9frsr*btm!3zLqK$yQ$ zRq1C$fjm@~DG_ev9P)T4kjw2{FQ6d6x|jjr*}g%*^CPx#`P9nY;(3gV(bn+wGxNY& znNZ#zeb+1D?~-_FIZx0QnqMyj%Svmql>6t6TB3^+K}~UcUTsAKZM7heS$K)-Xqey( zj5&_x9?vAQ@a72{i>`(Tt$S0RAZ+yOoKJb_#toptK;AzlX>R;KG;{xE3fP{jgtz9B z$(}=-d2crR`N&Jq8@if78P-1?$YJ#V=ZtfNdiYb}8Dejl5ZzEY%|`0;Mt3P2Aa{E` zM7|yV=>7Y1wn<=566H#gWvnqaVHFL{E8g;dIttj&>OP6n>vR_Vi=Oc9Wao z%yM_F)OKr{=~|dBb}d5_!w%*y%z$T$tMRkf#|UGlYP0?C7hK%{qad;O=pO=Gb91>o zyTOBedjnPY`;!>GSTwu&WNCD%k8K@dR7tAB?9UcDUIX&u*y#jA(SAY?ES8*)CobFXK$ZWSW{;)l!kSW&LVx$+ zw7h=1j(x3X*@Fa@sPfd+dQs7NVbKVR*My^)drGw(<^@=-mEWaOBg%Kz>Z>Mblk`wA z=-9Zu@EyrYI<-uFG8ynqC(6nkhm}v@lc>%1_n9DxQbcBm;h z)eBVMDCgM5H56s+R-Y=21wHQs1b*e5I21OdxEFloG~P5Pr(a^D5jNJI2y)SBz3opf z+x_`5fPAvU+~$ZRJ-Ku2oaPoY#^9cW+YU35hklUqd<}xGQBalV0D^G*NN5#VDDq>O zu^^;h^*E|Xu@69QColC^vJFnCJFPf@s(?86*tnllxrKW7Zz&F~6yro@>g^Wf&;V;= zxL0`ZP5AD#d7ha6a!=_BRHocVD8fv=N0XTeXkV>TzTz7YyV0VR|M4EynZ7gVU#4-_ zVtwT!yag$J%s=17oZ}Y}fhaDt@H) zLBJgKh2^}#v6)4o%_Q|B31O?{zfNsb1M+mY9KmONs<06~CvT}S5p?7!A)hXF^MZaH ztsRbA-uYFFLFt3gW}#gq4y+k6BS!9O~Aa?Re$(5P-Z+UQ>t<~&_2tI&e(@(z006t zd;JZa0@)bNF~&vNbEOL-uZz4RT#?0z<7x)`u)QE?o4Xc^JgMYbLqtg}UlMLus zydaKxm)O3Qy7Q0qQm?7IqY{f;*ub^1vxKnJp??{t-ZE`K%Ica1-GrHT7#_dJ%X0f_ z87`1-#S`~)Xv%}y81m}xDltnQX33aDVRBpTWBJ(_iz^q5*6R^53I5 z$wQD@w=2h*`!*xQFh2IxT9)nsw( z2n_Ym{4+6vFgJ_~8dOTA0p+)Eh&z$QY{0&%U9LUcpslRK zV*-CFHf&txghe2!aOrr-!m|S#K};g}{%}?ZLyIEyX~@4)Tvy+=v=ko=W-G5RbT^{c zj?~Z>u68JwgRvTG-q@t2=vC%n^d&?HO>5PsEHLEdL##dAN_5U9UDyJZetYV_;SZ*iI6g(GTH;uEeqe@5vF*Y>^lsj zz)gie(nk?UZ_*Iss=x3tcFKU^cO`DRP#b7{C86m53Dg3#ffYB7vGnK`1(M9g>|z|2 zfu;0a~hg>2>*_0iGc{_*KH*$!X@& zc>AN59Q{swywgn4csN*jq5pzn!?rI7QXMfE<+{kn}d5ki_G*&4zA z&sM`MhwpS&hY38=HBR3z8W*ej5N#eKY@i&~aN|{p_LD=xmhpyS>GYd}WsiTBCx}Xo z7c~gtK4k=wdP&AoakFU@;elNLXtP3e^k~GLR$qRnrIs7 z0JWFLnM!OhqKo%D>``*f11ojW{}PXt_@gpi`6{atBFDk(_fFs8OmPhJ z>}|o*L#W3+3bU>L-&cT%H2Mdozw4NO+2%CAnoWtsum(pg&32tdxtzapmV)}Z{2k0- z`3>k){^1@_8!a#(rGH5w%i8Ew?H_ER0Nj$j19O>NnE8T%h0;@9D4?dQ>Y$_}*%^JZ zdrAEimE9gJVf7_j-mFVmVl&Nw^OY7W{2FAXifyc$Q}h??rkisoROKn+S))@2y<^_x z<=h-rggM3?16g!>5)IKWcf)pWLo?p6x1)lZ=+3~e*5e&;1briPY$Dgmc;6a1VfdY> zZGFXtzhF6rF&FW8SvR65```HBXkSythI8H|{}B2&hI&loRe9` zs_m=BkoZr7>d?osio;F6)y8NRHqR7%5{t~kZW*jiRL1BzE|$P`Hag0 z?$sfbBr*`Gn#M8!4jcngPsTRn-TAgJ^5fwbW&0lA;g2KQGPi)>iyb+nE{`SuZnIURv6UPT%=X9n{v4(8RNnK9LIrHrm{cn%u$C{CH(>$zqRXqw zW8)Wh4pi>(2UIR{7K`qkmLXMNP=|Cgn@5AI<3AQ08o5qeNtJVt5UIz(78H?tx+DZl zlL6<-uMnni!}EA8v(9Zfg>%F5y;X9}6;VP2zRNz|{Jp_?9*wt}#U_^<9zDJO6iNw% zMQ;nts%-S+hNe!j?!Z1gV9U#ym0qdZ(~^{~O&W_qv|d)BzU(p8K@&df4eX)K4CWT;NIi4@0HAlKi1YzO{ zxi#9>lmm3LQfA~_?L~?P%vBjJDySR@t*%P+8-Odtcb@;ACnBPb>6Pc0TnWs@D&8kM zZRMK_(|}Bu>Y`gy33qadif3s?3w+)Rb1Hw`wfmlwJnZ3-m@fyjaqx2CG86HY1*Lr` z(|dlU#+1o1+q3R0%OExwI>=nA{LlnG74awu_mpjYR+WIE76zUq)oag59<+zU2ZM0C z7}?Cw4a^;YHY>Dgkk0qt)@rtHoO)FiU}HlpOWvot+Tl-`b&C3Q*2n+H+bU9X2}icG z5`3;r(>MTDJN1oi{g8Z!?(IE_pH?b4QZv7qL6>!F9)4Ot^^|~o^n=2ZHO{0_`sU=Y z*Ef{rDJU=L&OoMxmn`Es6Dp98%wnlE6GORFYME5}AWt9<$m9o*+M~A^PB*794vcau znFG$xl=;9d$qrkK=;#jyL~5%iSaqQlN?*2sUPE2>+x%TWhr`mDSjb+pA9)NGzs z2F?3PDV!eX-jGV$=r_h&c6BT7T-n)zBgt4y5Z*I}Q5l^RajYa@`#>CLo`qyxpW<-I z2xMGFI==k}2(dD0>`PWN?+e1HMeV6nE#LAgHVb@4HcWIRpWpyuH0DsQk$3BoJ*~h< zk@$d;!ZV{zi%UyLj~|FczH~BvRGE8nLJlVFBm^018`@oBZBHS?kl-oGPxW#J0N?9C zVZkwKnje5Mh_o__Rj?=^AD**r${4S#Gx@w_Ych6TuifWF6L2xt*S41av%Md z=)CTbwXCgmhF4862$jm(kGO)J!!X64vo8GC4LkD_wv@TWV+~Yjz-GE#fD_ zL$?*HA~CPcAY%x0@nX3!fZ<(eAz4?$0f@={*z*IX2?UuJiwBP@|1!1xn1aa%#|>-& zf^r5OE#4-XyM_E6*_GzqOMCWl*R`yDY=U5voiwl1$WzHJ7!!2u-n7{7%&UbLQfvI2 zaZW%mbFf+}Equ~9-<#=?jeet;_E2P7@qmkJ#OlQ1QxnDjX$&>Eg&Bn-Xy$$0A$qHq z0sD%-b7S8A1e-JK?0R*Ij5cDj0#=N)^fNaHh%M)&wVh`J)~oU;Nls)>C%<0abJJsr z8k2s`Gd z=ii%IywQlwWd!S*U!4I={KOoVz#n54t<~i`g7e3aesq&#L_S$}elDqPf)m~l^(#=l z!OQqyM@PL;6nu8v)Qq0o9V<&wCx9CWE+PsFV;x8UDBoyT)F^YQQ2J+SzYqsLBm2#S z6Q7^)t2EgQOl+YwIeB%lob(miW_Rzv9|(0^fgiPwi@j%9+Z?^yea%J7*N0vY&xv;u zGfB9*lsXkH_{M0=zt`#uGYf>@Yt~(1oTsgdFmo8-DOPLf*<<$EH7{&Y=#|ba19*#) zuMRP6T?NueB+(kOb!0qdzuP5Q8&jg+>(TUOcpBH#`Mc11z8>60>m94f!^UE6p}6;% zA_T_kW&Zad>ol+1phs*8qWMA&@Ic_cnM5_d64N>;To+aN1Ek}eHfp!rJ!o2o;rZ4S zkSeHvED(yI_#?mn!djsuT8T4Hj#3Neo!cc?m%^X`$fcMKW)yOYWt-iwh z#yL4xWb%BC0{;e-oXF;1;(gcMFd$zc#m7ZbNhYai9=b;jj^V4c5PJ@2=Uj|ttzNMR z|L>HI_S}o|e!UQ}72|f`2<&5T2Ui4%WI7mpoe(S4DEl}04XbFAI7VEJ^+d}p_;PRX zqYGNmJp}SS_qN;f*A`ysJ;GRVULtUhM?T4fpw4{CwI6j zZrAE+rBN(8q&zDjgBLv3 z`*#d~)3r!(r{g>jeRMjf$_nX2U1VKacdu+_z3t=$+MqQi#dJii4ag^Yo{CfPs{eOj zhGac#J5m#9Xdftv*Y>=X!!9C0tx3qIhd#kwow06S$G)V(JegxZ@)40nFGM@2ZRT|; z(G7Wx;M{CHS=LqrmJrTuZR;c*co>L%IEic>-zL2m+27Qc8&O*Hix^Q@q>1xjHP7b{%{8`|1ImLJa`mgz&7^K9k)$1KF5bCQPyjvh)}y+W38%0Dg^| zn|WJte-`)LC(Gm-l#G^Tz&kc9Q}}c>{6srho%cqiub!{)D;*mwzvBZ@CQT5PL~a%K zy6|-|L!*sewn!upZILzLbOphm-NHTkToRV*$mr{6gf0N8HT;hr@{)3ZqV@*c-`j_bdQ-okp73B$BR4dyastcjM5EMb( z*Z_lKn`e~ul^?&@tL{<@{_aPOjsPXa3xT zS;`&pZ)R0G`F*9LU1t1=vv}&N%48!DWKtSgNcb3?aCdjYdi`HvB^!{T-OV=12%NHu zYBdZ)SA-TY4GW8+x2G~k=}-B4<<6RyGeV@}#p;Lzw#@oheOo;lFMY}Dp2&BHiEU=D zFGU2y8yjvn-sSOYP3J7;`55EM!~SQeP@jO?pm`q6LO_m5sA1 zil7UVmXQUhBQA1IEy7d2<|()bqbGg{mqyJrG&Vf9#v^c044tjri)2c9mO16silqbw zS<^_9Uqaixv!FTx;WZ4Q=Ue@Vg|`0ln!7CRWf zf>r#IL2AY*2bgYtU|oqWHFG+EG+fi73-gEmEs%Xv&R$7Pr-HqaHp^<&TEn&`9#V<7 zRjJIaPn#i+8QS8|M^+*7N3=1#*T`^~CGFI|y#RrnId~U;^&<8AuF0JNUN{%DsX5{S zTI&UIlS&@x3w(?q>tq_LzKhN3K9Q1a;8FK$d+19P;G5w=M7WJ>;=3|NUdI3)DMM`W zOcmpG8glGa<3UaPJG)LiIer09#q7BYG~ZCz&?m}2E?;L{1%$+DcU8(1;>*}dDI1Ka zaMrkMixn6EOm6y(+IpZxcRS4R000+5L7#g}e4vUQoBsd+KeNc`?d?q|A9w?Et6|mG zBD=w`#6$iO3AvZqd6+-+pP7M)1B4w4O}lhCiNz(0FTSj8WB^)IYhBL@40$1VgYIH_ z;*z~L+?;ujpk!R;J2vP;i?$y&`ItEiv5enD=Vk(j93^P5Khl(GP-V5TrEbp_=Y z6Ee#KqQ59WmW$O74!~el6z#Wq{fw1v*39m!k)kIt*Ig8+KFu7`V~8}hb$IJj#-)oM zxigC8by=-546@E93$1KVO;AfwApbvFGt*yC0RQh-deg>%r>NNVQG}G6z}4Se68)Bx z94|bO4C_dMwHmyzdQV|hi%K>O67Ece#hi2@vB&TVF#Kcs9}FEfTB)e3AZ)|VAi}iq zV0})|vfMAxJhXfKEuNjal^Sh&H7mb2V4b1A4o}3bC78@*dZ$U#m34#CP|6{MGmvdXUn3_rb=+ygthpzFvAwCg6V*|m<^&aitbAzN*7*;&^d#6zl<1b1N`VP4 z&W!lT3Mx53XExu5m98-+9#h4dMcB^+P`=e>gu6<&=D&Y@YTYoltB={t*;a=` z5L>J!;#!!O#InV`{tj_o6eTkG*%p;h0ZAKh3u}@dW%wU^olm-`cK?5G$!Gkjvb+6Rszt@2#ak3m+f>S{0R-qLWHAm z00xMR-|jl*Qgqt70b8*L8@5j8T8{ zr~GdSSsqPC-gQ^9Oq5+lbs4Dv_?|xCn%j&prz`IJONsZ@uc>*SE*!nNfazC9_n zn~W_#->o&fko0Nv+0HZjDkbYz{4g=LggRf!U;6g+Nf5qm!91E|`#$-Vkp7rFF*c}v zo3m(cXg<*+%cc3d;i65Kc=+tyo2?Y0MX~kwKn_eZ)@rxN`VqtwLO;`N@Dzc$gxdvw zP$-cAptjJ^1L%2w`9_QL27lLr*|fmsCVE!Z`g>ZnWt?Mu-H|c_3qie>LxHf72bf?c zOebvPa;;(c5P(m-Jt=KIQKUamViPN+o(uBe=|{j>5MW9`VTVOi7(sj`?xpnxV~jW3 zjZX?;q+oMdQ*=K^89$}?l+?1xh%d_Hk~tw71N`n9^iy9zI(HlUpImUmlu$VE$nTbQ3)d@4qNEiYX7e|6*@yFk8=^(>i+^mc zl&9^vS27a}XP_BzGY1_E1oEVh*m>YPeqjyCRuIveQM|$AdRL%B&DSNocfUB6-~pJL zagrroeU#ud;T1rT1nY0x*5Sr6K*k{-kYoqiCa{7OWCCqybx0@R8at$@I=%q zGrfeO4qYgC^W+h{=q65n$O78?+Zgz+!c{qwpMR!aUqqQR)|_sByeLCAi8wDSvmz?e zna!%aQOI6Jr5WM3n2j@xUT0|W%Mh`frCn=QCj!;3>yYB$e`-#J!Cc|j9qwtQDR}~i ze8JjHTRAR;Bu1=xiokgDqSUA{(RalS^6PHyuyp9I#8%6Kq~)+lk4U_GQdZkG7 z;6vAk^^4NCUbd(91c{4s5>wFMbw2~VmoPOAztnRV@`X)d>Dwi_7-@7>+h2RIBnI&) zEtz5Bg|oY1$53tTN8^!+0!SG^f?a4_Hj>eo{DuMA@;wd&h}jHK$!9UlLlBr25GysK z{QDcr^25qvRUZ16SQT}4#HMlqq#J=1qxKk-W#O@Gr(T?Z(U$;7vJenxD#q$(Xw_mkT)V2#S9x7wpUxMaCBlxi~67(Vqw^F=zywv?kyp6hog>Ie85g2W-O4vS^P zo9CL@)fm))nYsh9S8boJscj@H5v=%HVZL+1wsf+&Y6Gc5%jXx4WE+{L!Cz1(Al6KJ zSx1xc346!PP%&|#C6B-&7Hw(LAn{5wqEjDAMeuK1)=fAbw$gnu_QU>XZ>ct*96G^+ zvd2~K#{He^rkuI%!q;<7DB}5|i1$=I!d_%lYD?z+&@iBL!9gX_S_HQ5^Yi~JGxaLi zIn$hQJiXSmwu^scjQ?oErKKK6ghdQ6!CL{XovkUM3k%fO!Vh!b4L-fe0q|pqZmmIr43m~>~IG+Gc}Ai9+Ouv zB|waio8`9=XGt3nMV^w@cuvg7xMR!n6n6)PM65huikN}vK1VX0C%7Oz6O6B)x?HpG zRaiKfP%Ld#Nf?vg8*wPH9x#A=9AB*TMH!P?x05Tad@}}==cje+NjZDr0_3nDu@FEI zO~huOD$`IA|C#eK$1c{uOw9Ob7m%@&Pf9hf21Xa489l0mj@;lmzQT~R3@FqEj4c~l z)O0V~M>GR|3Sv{#Z6OmSJ2%6i3Pn$^DIsFRnn$F7zGcd9=8D>!x3YGGhfKhi`fx)IR!>rUu=hEFN7)M{jS2my0_ z9!>yPX`?r^%#XaU0mMFLfprmGY8#Np!6@x^qLP{YAaW$Ef2aLPLNP#O;jF5S|1x}u|AR}h6PHyGsy?Hpd;bE6C!h-G)?Nc74 zV`Cuct7_h*BmbZS2O&Y4+lf{3lHAFZ_#_gq)reJxK^)e~13FeruVMY`sT^m!oXrP| zk=(DTR6}znRF}>nv`+fS`tulEol3fCUIZJGi<;Z7M^oIRHOmURtaD^F)n;~vg0RU>!X zC3?Ns97~}%^|Q$UU82=@WhGbEX8K~r44PqR`{`>MnsW=*JuUD%q%;B zGL5vnPfr^LGQ~RpWdMblT%HV_d+1F|S($wne@it!Y8>|?lu4!#>n2g~Wu?AP5VB|v z`3WyPF^z@UUz46NM<%j<4)z`ZEAbZufOSUpl@P=QlgY+ zx4#gd&c$2eeI!9>z2<-b0C=E_03%7=EW1CPr;Yr|QjS#z`dvf*5&V0o-&|||Jz6gv z+;R3#uIB=xTecaZ=O zdtRb&L?5%dE@%SW$VtgDm2d{hb|t)Vv-9$mE(t&F{w_7Hk$Z~`N_-h8(;nZYKT~(o z9*#9@-So*6C}7`!J6%Spld;ypymmmWQZiHhbj1mAeG^-w^b#1hT`282XlO`qH1_8= zj5%)9W#8y@k;A(3g{Xr(e&XT>kVSz0@8c)~aPq7}9ic_F;^X5Lr~6XN8NRl+BH@J9 z%kEkrI*cufDHF{eD2h&A)@ilOU8E?Pm+r}-`a13|H7j`Qq|!W1yAl%wFryKZulY5- zFs?PjRi8dX(j`l0N%1O(n!Mw%6itS^(7aw=D_AQ*=;l+S|3oEul}4Q-U(E69OY{Ig zGa_wb7LFPG_0;ltlFAe58rEsmA6?h|A<0WnBHE`?wVxTb1jzi;na?Gr6SwyWl~nKI z5!&Xtss7s?DYY;4(0JO-bFfq;f>TA)PGp+ z|9XO2Rwh_+9BOXJ6}u zLTPq>+iiB~@Qj2teZapP&*MZYz}ei+eJ5WVAax)dFljoAo%6yaS8`wzyF7JoYf!M- zOo&O=t>*^OvI*GEx>XFhBV~W<5e8%vQ-8VtY9c2)&&!^G`llqZi#z-E1@=t3@t3m+ z&xttdXM_gcJmYpU4nBSKPD2tR4-k--y6a@wfQI}yiL+S>gn?G?E<0pq>eNnsvA8Fa z4vSfGsDc0=JOu6`>Pw$)TrD;P?T9#q(E$5?b_+-EB#1A;H>G-2UgnOvP0wPW}7Gf$Y7v;8J`sSX&o zEf)E1?8NRx6STvC73jJ#1kq4&VkJH_E}t=-6d|X9nSu^gl5i#a(aT!|zH$+jUgKQ% z_k-=4Z~GV^ygLUZk`>~0#}nNRxE{ErUaOSi2DD{@MK)?VpS|~HPChGBoKg$*ThkVZ zueBYtZ5QA)GEQI%e^JvIVsoTdJ#4^~f94ceBd-#`4W*?(VPIlBPZF#)%zK88&rjBz z=rs17WNKnXo*>gafCqb$Wd|BdY#}-;;aaAy-S*li?Wg_l(5Z_@k5T!L5ByXYGF%&0 z96b2dR<};69n6|D-ln7a#KD7idY;v=cOmbmM9zJv>2Q#7!>*z2{%)N&ZDb!NL+(~M zdbG8JT3V6}D+A5J(P@KMdLIfCxb+kHW6UrTJZnR$ni(n#>hqZQ`;{+KYs3+!RkoRI zurX~bBLC)GghQ-NLJ{pqTQ*R5g!8Bw;$(urQ_ga;Uunk?&1Lld6+UR{quBI3;i{bw z))u>=G(4TNY>AOVO$&2@!Zk#i0hRw6!aok15?fe*EFn51pTLVAC!pQ)*L*CtMAo78 zssNKKYFI5BPL2O?NUF-zkqM<~F2onTd;oT6v$sOo9+yJs&%7zga)Qn{co`a`-Ay8F z3rh!xGhSo^n!Wn!$rlUwEtx@ z=s9~Pk)4SP`LSV0kuMIE#cA>B6St{P#+EIaIQ)eC)6OmM1^IZ<|5o4VIb!nq(%f;F z-n^SF8k{(0IG5>G8MkVdYrD;Ti@@yMmp(fE0!hQqx|f%ME?;_u6qNviuAb9kEA!=$ zR)Y9!Qi>qh06kBvm{vFFrTbj5ARCM?Di?{sU;cix0Zlfh(&4 zcI+nEPuzL2_->zK=ezA6Nvwfu)HlMZhu8wL*;+J+1dQTj)~{CJl^BD@*pB3{w!W=H zLlWQoS2;RP&K0{&d3P;t7ZW&zbrd*y(NX0R$nK};!- zir@oXn&x8^xh=p1Vl$a&2J~@a8Z&Y%i2HlUS^nBS86~{LMI(nQ-=NWaz1xO)C`OE$ z-3gn1_$qx{4TGY_#_}9rrXJ{bYB9~Bc5=P5MkK5;g&-=?kL%1{K(KIiK<1I`E_d+q z7&}|rM(FJ4694n^Qfk@_n7)TLtAK1gZf-#N8j4`ia#NFgz#3CSqbVlbzD9KvS1WUq ziF%IIko*NM_=!_dgT1&6kT1vCKK#-9=+D_$103l#H3)xusDnW_0W;)%IVct=lDuRH z@v+9>%i|#z(8Du+pgtHkU5_1+S|wGr`8Diq&jK51?OKSlb zRBs6|(sG-uW&CM;WNdy^MF{NP_fODsP`b<>Hfe*NrbN-7#Mve7&W<%cY)`0|CH1GC zqFJk?Thi3@+y{g^`^n8w|6cmI^YHjB+Q}5~@ae3M4DLSH_Z(#gU2a<;1nGX?>A@qr z6MY)qv{F=cZlGBuHF{bNty)G-GJfJ=S%5f!v+DP}+8akkOiqqmXJw{e)%UDF+C-E4AN)k(J~+(bOvIU_a;7Ux_dM&- zBh!I@A;EHd(V5ta#qMg)m1nNEqLaED=7`I+JZFWr`l&=M$h?RAsFzX1`AWV+2}#*r zLXLgDH6h8!j6U^FqPa#o(^rGF$JkS^E?1M)Jlt+PjFUJ&E$wu#ouPtbnB~{2H3pmj z00W%?pMwl)BEJ9tL0X8KS9yd$vK9!S1uRGmWn9%j1oUY>YxK)c(}e~8212L);$KTo zMl_Z3ag^sSiSOx7!Ytaup8?G9Jgiro^daD5h6?f4u;@Pj=$v1Vxw8nBekd^b$P{v1 zlAu}u2h{S+rgp2$*K2v=4>S};x>M#M8m^%oK5uBz)Ck}^TrtOS$3bSUEaw{M%P$-> z?4B{R-$FoFIM}I8USk?cM!yN0Ad=S^!NE!l*`=@%Zq$Zw`n)w166c*B0GxLKZo(td zjhksM009?4DuZ>#?MMpj7TcCBiVV`qBo*!prF(f{^;bzzFUaU`7ShbWtaR>@_HR6Z^vd zTB%~}#Ju3=%J>#^xLnMDXE!^q&2$+EZ+Z3QnKlv~KS@lP@QGp@(o0vzur|?3(CdI2 zIDD~XQC`GB?X+!iqi$7jn@2%?x$c3v$_Ccr>`n>pS=`VBnzeu-aHhY;OB5ZTU;`sl z@$ucszC;>XsX67lzgn=Uq&>?4e()Htrtp9&<=khdos7y|7z2&eo}eg|uxBcgtHntc zGa_01?_;bY5U0KZxIplMqD=Zp;DB{<{o7*Tm;&;=0LR?Cn!@@kQB(qW6@`?_GtsvR zTNmq_ki)r_nKk&YuG34mev!pyWKziLsfm*Y1H7xH`3)Yuo-n_@ssI3FQbZ5ZX)v-9 zMWD79xR;?a(bjYV#I*~R0Z=YvX^$-+{sVKs5ws1xi5!AyJ?es);~W|<@u$Mhm%ai~jD7s;?uDqlNtN>TV6IsrzF zA*8O$qny7+h8f3*5vw3iEJ$VNnTsoc0mQZyJhGrZmpAVkj|Sdbz3cRJ5u-ISL4pG@ zunhX{S?Msb%}xmmU57h}RGdHRoeTA|BYU0!_aZ?(yP!L6pPSW#s=yCP000CH0iS~` zY9hY?061-C<_%;QmL$Q@2_Rb=9j8De=Z+p%F7#PfK?RHT*W!QvFbZG?)LH5% zSU&DrdOG65kO(jj2F$6HY*sU{wUFXx-#%4CQafy_H4rRy%t!l97tm=j_xwAM)LP~; z3YD30B$4+@*FoF6TXxge z%p&-k;9!2e>{_*?HwL`n^wQkWXe%C>rMkz|-W*u17CX17)CXTu?y2h{(ZcoPPe^-Q zbbzaIx!hMX3jY-i6o(R1TF+zW!^@N!**+m#Hc} zrBh(wRN0FOO#>+CL;^TR8mowR@v&|kO!TK-ldJGl}b%^F>{RUk0Od7M4FjBowL=deBdz{KwMzMoq^yE0nbI|2O-e_ zBYa;<32yi^90D@cU|fM53!ZNLbLoWn!1+6f0gtxZ0%M=MaeIYgD$S}#Yq~Ue`4L;_ z#drY0;bw>ii*?P@EAUVdq(;_YXK6;ZEXokJEO>13w3_s^w;18zY&bu0|Dpg3nAdB7 zy34wZ7|7n9w=5(Zjp$aE4pO%AJ; z0{lKTBtYz{WV4Apf|S427<*)ZLGPn{!I*p*LQ2B1LLg}3Fw6nGVdvws_Sn!WGV62W zfO|1kalQd4B0vCcW=N(zyJUSP63~T zY;=nM002Q=D12Cd525yLzQ7D#lLyL5EX%{nC3~d9doYCWK~C}zloZ~DWciPg{AQo( zyp>rboxB@COuhfS8AmLy5(ftvg=#7DG22s%SUm5#usX8%&$AlHu%Rd~g_|uKT~D;& z%A9B91`#)+o-ZJjR|^vLalg{+4kwcf5tdWcUkB-YV7{Oi zd^SmLho$r?S6ZKvP!iaJhYxkG!J(Tb_e=v!JOzZe1Z;oe~n95X5u91Jr(UeHgdnvxr2Dt2^%}w=ZA$)0UwE!3Ed;Hr{VGmuivks z!%&EVdT;Pp0CF@u_42oEiWNc`2Hf)XmHG$eM-VO`;?>c=QAVr2{YMAy77o3u6`ua0=6w z6k3KV@DzRWHFa(qLul9x(RFtYIQ&uboDEW}NcFgaL!!+V^Hey9E1#9(NXmspoq~-T zNk`dzjwslHaPC4?%4y6fZ z9v1LdVwp?Qoqcd+rQfk-g@u$CVKg3~VXhp>DIS5xsrvJ=SR?{@8`dM!=|%96PC-Oo zpV{8-UuhJPyoHXFVn9T}EpF&`>@Z+hbZ2e`3r#+{bSD8JtogXStl(fwezdG&829M+ z((w{_l#n)CIxN!k5tf+K1Bxb{JFw)~0aU&bP66=~ktP96D;_0Fjv+PfM?wK9LS2oI z8YU7)do$YpYs*P;IJjJXV4}4~$4NB*?MN&}7o~<-R!+vf%tovkqVL3nvvSw*f6kk{ zvWBBhl8&L#PEb~9l4ehC$=l_=oXvNt7x6b6*UoBaRDS#s;IN9x7BAU%{%R8OdOY`v zW#8CH;iuCN+WLOsIGN~kyzO!ZQRn6EC%HV-y={QmN*E><0QLE4anlJL$&1z@i4~EM zvZe;pt6;-iC|aC@#<30^jW)XhUX=|JV_jHsp-T#&IJ%p45)^=-$--;Dw;`_+A+qQV zgavDQ-!jExNQDlZ3IP3`9zZc8V?AXvKejp;(bO#9#8l~Tl_Hx2@UOgHqo(GHzh5kQ zfo@nb--P`*k0B)7C1p}OB1I&kDJk+^fc=3PqgZkqMX0T)S-a0udOQodJq~|D$_vhP zOeBI1PX92%J5@9JTRq#C$Z8j!L0Zy`G-~%b%+IHC)hC2WotcvbT}ut_DgZZi7tB({ zGW3d@g`t(dbi6t(dJMFZqzxcTuX~s%tr=vkEvd0npn=J08X?qlKu5Mua z3L*hdqX*mu5}8T%{LeanL>!|^iJ|$hIjJ!f&UC6L`fD(ZOQTf@@rjYQ*i(|ES6Mw> zN%gp3cgxHy$F)^p@;5Cr+wwKLef+=BrYx(#T})x6B*&w4h;Aa$IL(y$N_0IPzBaK> z=|E2{9LE#2IoMq>0}!!C_DO)1C%a zeK!9{wIX_ca^4u~$Au@CLDZd|UL`VQBW_GA@?r7Ko&nfq)K;?Kz zFrGT3Bp`LtYz^ZuZL3_9-BWR*D3fFsy+nnFJ%1g15w~Y3HipP0k{!D$?GCMhm9RNm zXM2$gcin}8>UPhBQRZ~S7`_h<=vdhE-+hyQqEhqrawMl9$=kfP<<0_`VXLp?1|iAu)X-IJpNucBFBjsC4t_9J@JOd+BkO)aW76O|~5u8Hzh zArIdBYsac$s?hEcQXvKHxX+;DGYxnPR~Fj*1VDDa6@JKzufiz0O^{{)6&{FW06ic8 z00xx-pM#8aivIurL0%|ospaSgQ;xBWo$<0e&312ibIGLBjtCBc)2 z*p*70%h?Hk4HiBZ!X;MeOLZi4rA#hUk72kRj}XdgDxYjC?=6SV+b}CT7^NzgG`|fC zZA^*enATRh+@{8agzZ6l=wf)^kBz~jZt3Q4wU9}zz$Rr>vHaEbryzV7(0kY91cRlv zm1B!>aDE)1DpI0LAh9H|7$5+kmUP;m+p3V>`ki2N5gw9v)}exwVRHVonClqTrXZ*B z9)DO>1x;t7zDvALHK0#1YM-LJlptUGd$0IJyW?#*gzr{=F8`QU2pmTnr4$C((Tf*u z`|SWsK(oIbuo7;>d=>A;$gxa%@hU;MO34Mb09x=&H?>sXG1Q!<2o{r8ol!F|S5mCq z?h3rm%ZzU=2eLYON5-|KV9S*q;0NrVmF=Xt5~vcrlZR{@Nbt?Aboj>paBO+3Diaig zPToL`EOr#?bZ!qnRBHsd$_9}JF0>8p%xh*24g&sT{%1GCcs1Y#mhAi$=>&xn-391r7fDn`JPta~g_ zSp_rYXe+O=@WIk*+21|~Hz5moq`Z0Fz3D2GiXV@fNS(kaQH)8hU`vg90pmCQsESpN z`O4Cg!KGr3=vWlj`uq7(vUv1+#71D{lsinxhkO=GC{ECn-ONU<81V4clGZi~)&qPyiv`%WZF=yH2!l)kLb?e{r z$?L1zmR&Dwf`=2ECJ~ER+h`7b5u13|O`R>vmPLiMaPO$iIp`A(Z;IL6O9#&4=j%+J zHDV$%Y1TJCHR*yR&^y|Y$c3_W5pZeVmB;YkAuMZ9E(+-TsA`0M(J*O~azdg99mK0% zvg~EN1**vynlu5_9Vmfhuiwan{6y%2Y%%{-u6p=;!E!JFX{;vGN`Gz6;v+{d?q~Ev zD*7iaH@ShI?|?AIw7(c)^yK|Z$(Knm7YU;8^%Pt}Yd%U->R%z1hLLtp$YbSuK-}SD^Rd1&&L3YT^V+K#`5X*C>SV z9xiG}+ub)}5|aU%(q6j@IdO-tqbIWW(AP8|jv7W;+?hUEp>vV17?r zLY$}`uK=REwi{k@dfSeY2ET?tbA5tM@L()i=6s2jamJ1RYUt<8c6s-fLX(uV4(2t9 zlKcJa3Ygg7eRZZ8l}!j-X|SI^1m(ZiFaZEGsg=!D?GrBL;=yon2+?~K{TS| z4b|RtfF7PUh}7tsPQh<8`nd(U0~V^U;3qe8f!lonyt%3t!#$&Gegk8qWT;&0@!YkB z??vEd2EdEgM;CUPFT~vo=K$3g6%Yn~Gp5S1V*r_O^%W8n0&8HJQ8HsyNyHQbt zWTFIc-@CFvOXdD&c^aK;;VvTkr49U@@4Fdk^z@_=dov zR-Tl05ah$hE6PQ!ag(DV-=Rjc;OHi{TS4u+ww>Lz+)7^N3*1codh_3*Ntha@+0_q( zaO0BHe8pi%I(A8~!OLHR1noj>vA_0DTAkooO^WYK-8F;|S`V9Pz1D7 z^EWuWJKIJ7^O8_H_ngrX#DDaV2jeuBaIwk9%>V!}YeAcYW}rY@TBWtMs#_*g00093 z1OEU357}(ckkGam!^KJj^r$Gl}k)oaw2$o-|rx&@Ci&%J85TfV%B2}RflNYp{CUohQ&r5KxM+)A*wESSU?z5p0TsO1u@HogMMB(Z;Wu>_hN^|+DQLVibV3}bz-Piye09e#$oWdqa zt`(j_n_9b^;5ChwL0j5CT%{Lbn2^W;^@4==H2Na9OBp~WjyhO1=~l{}4ARt0(RW_^ zKxuUjVXBmjg1YDo6>SiJB43h@3Jt#PU`B1i^!^;maoqPoDG1t`ReJ>3NYg@HBri7| zBBNT+M%}TKDyc+xfjTZ)qgl*P%-Nn z0k69I{2yOB$!zH1i~j>YR3UhDUu4{BbGAk{b6@m0X6DwRaW2+443lZuJAZ%GyT3A# ztySy-T971q38(W6;#b5H`0pO5%|$t_9ZG<+SkZ5ai@Ugi(>U=u_ODxh{IvV{InsWA z6`-B5VSFcI4r?q`vWUX~9aJJF&G_dVc1SJ?uCDB+-W28#3&MbiN6{YJ{$vh0BWDXP zzo%I_bbF1OXSzdpj5VI`MZo9qeg(2C9%pzCdD8xL5bb>6$!C&fh@2!YmWOBB@B{cv zLo@v}ST2=cRG;JXn_z7eiEr*z90+wMxv&WmRxz*^ffiyDO^8Z*v>D8qo!N7 z0jeCJ^HBPlJ+Ur=i6mS3GYY|k$4+05-|9-9=WXXJMxWM|h@Ez8!RUK}J<1B#V$?_x zx|YOoT}Zh0%FZ%sXy#bc)`ELDQ-QuJP1F)at(JF&(RlknJ_0UGKgos`9v^isEq)i? zXRhglZ_o3ah0u=WQr=seZ%O`W!M>W!~qRbQzURK=;86;hej)Az_S8284IS}@F^{k`tK)Flj za7Jg3>3uqr=>IyYN2R4FRE1)64yY#!pONr4+c@l=Hh6IC+CrBeK6>M{>kSR}Zr2-= z+FO78FQ*(8tGYrM9~fwSBcHamO^;aiec9B9b@NyF>Q^|{(oL}DTtUPz%r+8j|5R_T zkfvQjfT+#qV~{>kdamkVzr5X;nWEL`I>5-2TF#IpN<9gyHsoHx($w`=(h!_kFUE~= zugD8vxV;JbKqnO97$d zLIPv>-ewrBUgG9_l5pr#dbmM89Q}8f=4qA>Cf4gIku@LRTu<*5fNynv5tR94k@q(JZzxOo78VBWp#q zQv3mewQL;SP*xEKh<91|iG{4l0JrMyGDM&6kZ~!JPMCMNhm`4YbZnvnB=V?)0`%Hj zuzTDSpwis7^C4P`NahJE;zYC{+O27rjke>yYBH=?Dms^6w$oR-e=!YeoH4hWFA|Cc7Tg*hN9MS2b5IG{dONciv(Y4# zvSCRlt7;lC)Gxe_$XUe^ejN?2C*@;X+U(lM2#gze)^cLZiG;k1+ePr=9^34>f98^m zK!LbMr4@v{fcSSCwv3w9$-+s2t3Mmc7?JjLJ`c{AFyoT0EhR&S52wlLaK_k*gvQ0G z(!6dPIHy_NaQ5wtW7&{I037``5w4R&@8UP3f+tj)AB3$9soIcSNSPX8^1OeJk~_Ka zr=TP2#u8~`e0j3ANj}4BG6gLD$hQir<`GZdTQOuCrr*dQIR)P~SN1GyCRY!7oF?hb zW8KnF5EDROAvWI+xWk~cz+_Rjn54|%fcW*aSNENh$*eRzbuhtAX8TT_!t_C9>#Wfx zPM!zTrz!>$Ym|5rT}+j-C()d(a(e1UQi`$PQIK(QxWfD;4o~@wgynythO)H{n#h=p zQK&NqmXtzkfm+wbb|J>6~9Jgqj2N965c8g&VPb@$%h zUxzsDGD*Ik5SGFM7XjqjG9R+>sC`k5Hm~zZi9yaGrBrWj`L`i9*4pW?Z7zP8GmFP> zCc3+ITJo}u?Ajf1o4Thwg4)0pwi=renbQ%SJh;n)hM_rzuWp*-kG$f!Z|_@O9^ssQ zwYvm170z!bB8&V;OC8+7?_=9Wp`VNxgfYVOFO=m>m)stJQ-ci2ljK^k zB(>@rrZoA(5cuZ~N|`x)fBs~t>uBJs>hh%#rG<7D=2ajR{6p;6-*=QH^Y8MF2y1}t zjt5C9qK0gsII>CYD%7;W#zi1|Uy~2G_7N8}m(vT|ZF_+*vO+{xt9#R^(|vA^5@roS zo%-^rnKM|h7e3!Nj~Uww98P%H)fFTp$-ey^S*F!9QK`uIA0b=bol8HXDJQW(TILO6uc7F7 zuXm{ym&rIuL>VnPDB_ldMfLIA2gf6q zrX^kOI^dy$av_EcI5V1C?fJJe%1QF!aOs9fIL#w~8tk;e{?g%zD!a0_Yn=^5e5Uci zCrP5BI#QA^%~S8eeydmcssCO_|A;y3SvhVS^+vq!N&}kByZE{1U%nS#63ZVjuGRDB z!s4p%P&Ci5Eses`cck3rQsnM8)3+Sr7-_7#kV-o-68hL!-BUCzbAm3{P$FpqwvjZN z@nU-?dYS`wU+GfXK>G}wn&I^i2;4-O45^{N6WastD=iS>S~&{yi$3eZ>%)yqm9OtS zwfstew9h1`tzlusX^gs;|9t-Ka9Q#O>C zAL9EQ)9rPlKTyO8$i6-sBgeT9nqra1V)^rofe1R#D1{Q?M9En>4@}w&^Sd?%;wt1r zk{v1bz#?PS!veqYd}-9EHb;BYFT?H;D|<5{p4-EU?D5M3v-9H+-DOz$ImNpgs}%yv zM;j`@x5k&}KM$D(4Whg*4K$mtE=e1FRF4xOi3%p5$}9|J#wdvo5{Ti#&X%HD%bD~{ zsX9;V&&|ju!#?%fu!-T}c!p~9=wf{SL9bHk_$DuN=pxnpL{^0Am||$pFvWgkA+-a# zEZq{ro0kxFgHyjX!n@zcTjSGuiAa_bYqvkO9wZj@d@6em@&8sQ4Y7kXw9Hr=@xJKX zK9V5L!_cFKM+)JVQ0HEES^%Yt$!}uSS>XO}F>B*blO_WHA(`P5W4O?`UwXky38Nwm zATq5fJ$|y?YV=T>DoY%M&S)z)o5gp;p!ShuM7v*P{%(jcPd)aE$l9AbWAmha;RXJ0 z4BXp1=_%oGIHF;fGT)%jI@_h^NeB!N{#afN^EF=A*pgxa*QEX02zKM!p@3h}ubiwa ziXahc=XK>4t;2$j$>t|CYS|502}J1zV2g)9tcrypr9{ud{am8SzYM z>`AE4f5%}&l{#qVzUB6`3)#TS$ts{&U^fX`ra5sFUsWhBbN<(EeAiBQ9%oI1hk%CJ z%hzbzOxR`6(msF`Ldpu&m@gz!?b0-wTt*k{MqP=yc7NOtE4>&Vo~nD^+1*FsRKy9( z_eOf(nd>%&14`DobUYIYE|30`TBha5$szGxmI140@&wQm1e2zwk#ez&S`Jpqw` zmfjoOd4-}hF~73=^;24MQALqKjcE_Hp^rX*{sL)QLlzQ%Wc!b5bg}bSk@6o1LdFt& zsPjSl9vduYCI4x|cJwI1FI#ebqdCKDvqOW*E74x#$4$|n0B1JBZZR1+aT6iqdTHBe z&Zs4-1MlM;CsZ8MeH(uX7nmBLB>`>eq)oh!cw*><6ssO1tud*s+=rM3d@k`}QwkQ~ zqrz^M94+$3$=yw(MjvrTmHIQlW@b5wZ93Ni zT}^3szxMH@PysI$3cO7cXlBRPd^u)&bruwiubjqOvtDm(H*VzXBkIKhdchkWV?~x} z8n{7mfCh$i5mfMtL(IYyIj&C10Ra4;=@@=7v2B3KfXEhE31|n_^ykinTRq$lj-&?5 zw=REF+he>~c^|7a8e+kIn<9a%P@7cq`(w?Rq5M>l6hxedV>uq6y_R&`wPQ0~g|m>_ zaH_jH-HRogW~U39w=h;BZ*Rb3f%(4LHBOG$<-EbKP!yKWexZ6EpCH2YB7R9HD~EOE zJEVrKiSc05DP4CIlcbTuFKzwpapVid*>1uL zin@p+g)fQ@8lL+b55$B?Q9yQ2v`(d>oiK8pFrHFvxF*OEi|1b~hPs#|?7Q~U31WG* zN8P7=CqP;(Ff586yqa4uNiyCIcksGHE~L0pzFsuM6-8%y!S;C{)rEHdTD?<1F0FKY zb{rBHfocMqs)tA~^oXH@Y&`Obn)bR>%F9z@7Y2ni>8PhOHlcUSFzvt{n@Ji@Cr{!!oLj``S>r=>MtDjsIX(h?er3rT5ThEjHZYm%xyKyvek|P;fPM3 zj>w?;BF{=8Ns|6*LfDr)0OJESM}*yaS1a8|EOIT~JX`l=a-B!n{ugJC1B-`mS>{1h z#b~<4Viybpp{^Jfo+rR10S?on-p}cec$H)Ax(Kv3qKK@IPSpYhIiwqM>N6 zYi_|eecx_lUz!)ZK+uKDmgy@^U&IlaX6J1XG?%5eZbB$`o)E9)^VJW5(nr}0Ez;`H zbTqnMa5t3kq3q$%4PAF(+SQPvh`hWpA3lZkCNALjb~T?J8JA7~LMTLx0){4J+B{_u zG5W-SfB6D_MTX3>(*ov3u;5>G1`41qno~G=^=(UyX3RZjc~;R$%`}L1eHYaWUe(`40+SQCsR(G+|Z%_vvzOyfBwRj@0rG_6z&R z5zn%WtN(_6g?ZMtV&9(iwT+InxE%oK9Xx_t@Lv7g&%o6`2cHB}C)0^I5GnN5U3%!2 z3!Dvhv#py!X&;^Ps~0zTY>D+XlQT~r z{ZP_JJ%+zKIJx9?c(bKQfc~Pa;SRS%ajlePpaLamruQ2~<9C+CqKsZC5FX0d52ReR zQ84-0xa%$GrvPo>zEnq1CxQ6nTQ9LX?x8XXUt{|}{{m7@-02doW6+M5cqLS15S#F`$XZ;kh&j(3--p7F$LF`6^W%*~e(nRu#j{8rMdsW~g{I)4M( z`9^xOkX~YQ@NqLPK~Kt-((1|XM-aK0c$ol}&?wTG2etn3Vy9!2xJ%wgN0X&RPRRTc zSXg2du(?3b zjJkXI?T@ir|7hu`+kXa|s6e{B@@(4D2o?zxpDobvV0^K>wB!x!;VbG!#02bZg|F|NOc;&qE`0_horoBz{60x?E5;f6bD^zIeDWQAx`S?#-NYV zUbcQTcT2OuH`_`m!2XvczFnFGuOu1EXXo8{v-eH*mx+wF3Mv#!6i2ql+HKqx2~bs} zuC63qXnJVx(%3oJf&)fx_lQ?(cR6C!SdM!mNgPuywvGt6p+)PBp7eje#U%KuEE7YL zaXAAolnQ_b{5nZlY&SaNvAzLcaT>*RdK+GAUw>(7r-3Tp!@V_7ccpyQ8VBO1H17ln z9q(|7>uPs;J*92h87VJn1EYG)rKhvZE7VN40Ju8H^zo7KH|}nEHH;#|Ia9gZ!-z{; z)h81$iBswx+orf^6)dW@apDBN-EF**(*m{FGjv7SudY9ty8Jp%l%DL=AqTdB{4Y_^ zPi?1=0%Ju_g!2w`h&GB>k{cLh+^aclMQ*=3BO&%U0CQugD6Ch>plwmHy$(Kea(`>rt=)iU{*_`7!3~pzzxvSC%8FoWFha$hX#QU_EvM-?N&X!76jd?(Mjs zXB=jtrfu+iYn$^Bf=3t>GyBo3EHI&b0I9^UB5i9xFaESoIcrd}(u}uEwGv$~1$^VW zN7Udk$Vf8ZvbEg0gK!-~^e`@7(hrhvBbUK*dn#r3TVp~n~Hp3iCf4<;M(tyM-S)y4BUV?qE@@w>OEYV$!YbzHAD zlpINF?MJu;PIXCWUN!&$t_{(M>JQ!&tG|KNM7TQx6(m2+tH^A1;1)2S-L*F6i)#To z6*V)_pzOT%?O7N(37S z01%>C0~%2ES$vI3ZLFUMN;Hf-00A~;+^S!Gif1mBbv^Cud+niaO+}=Y&U4}rD%~J3 zhO*_?v{&JP#*n^BNt{VT$Xnyj8+CfeOtZ}uiD0#cLqLp|lFnb9#`!H>7qLEGC*!Ey z`FE)TZMCSpx=|&xp2#>Wv6PbE@5GL-w-DZjSpWFu`4M8`!>En zo>=<*Rz_E7(b^-q@gOM;RgeI#cONObR4nY42o||iHgCWK@@Mmqv#Az&8&pE9-6>rE zbwgjmJzh>Nm}K&SW7>oHe5Q-*H8GBQ&!-Xu?EKJF)c`8b77!rykZq*-t85~~kw=e@ zH7T2jmyc#vEpEaCy6U4kH700|9TY_V#}Hv?rgHD62Ibw%4J7F6ax>AjdBD9+78aSG zX9X|Z<9oMh?E|uU?L{4n#xXwvS-Gf?2jL3?6-am@8Frza&3Io`4lGfDm9X$GI||87 z-HoCqT9d)*H!@*|+Gnyo>06bkJzy9N98Oy11W=b}1`983cZG5Dz#E724K zQjP{VB;KBQUsQTObQLQB%t)%l}#3ZtWbER^@AwL&1P=uB027`n}NA%bNs9nF!L{I*5N zWIM+?^O?quO)aFGAa*{Oz=avkEV4XFI90~|5{f-1rK@>@{Da9UBYl`c_i!v!i}w4` z6aW{>Zi-Etkrha8-U$yDx6O9hZhNUr+IAG+5C^vsup(|@Ps>id>SZltK5&|=)ziF@ z!(xotsDjcTwKfdMxCGN!2mUOyt!4)OP2ln8{RUd`?PVLc>vxCcLN7qPO)cxE-SjsH zzsoWSwdu@V1L%KLUm`Ibkfe>r!iu? z<0_R-tQ<>fU3@3ylF6n9mu8HR6RRak${Pr%H&BI7`98ecKzhC6s&9r`z$;)0z8RY|IUxpEyH$_jQdJK&4biJ zEj=ZP+4W42wZj-emp(gm1p2-Av0QS4Ko|*bv0qLHa0h(UbgCJE_rbabZp6+O)T3P% z#jgmU)A|X4Y092#9%c~@Lf#oS1X9^km}L!~Vl-|QePS4Kt+fs^A6(^)BxNSxl(t^m z?mUPOvB4&H4o^njGj;;)xSQ|9m&dfJ=)~Rp4&J$%&-P95=@sBk`o4H?z&S_T5YM$^ zA_|uF4{tGumv444a<$g874@GqBz%at=6MWZ3eA#7t`q2Jx(K^r)bF}hXP=US`5a`h z1*9TM9#NG>>|Gvyl^@QgRev2*i*BdYJrIY6PFfUii9ZV=9aneWjEza2D?o8MPW9+I z-w@b_54p8BT(Yo^ke#4fQF33D3w^Oc1?$3x$g>ot%_r8*?5wm^s)DRyZ04Z_O8p=Y#W;#`c$!jdjGoC?{F~%Q}NS`U# z?VYbZ`H|3K@Zv9Yg|C%kJE*>f9{2(c732h$zsZBDB<-SnorJSugY;({b*4_iHIzoj zjbnS#4;I}1YAVk^-LD3{XagNkWy4Y#I&4zbFF)KI#~_&oS02RaZOqc%em-#fHzz?1 z1Zg0gkS`mh!O)=wPJzno1~KXq{ST4T-~7) zM<4j(DgQAsG@0SN&}Q$*;#7O?`v+43BQj<`>wbe4Qh(_)vQ9)LwN;o?%XPLw$Ox~+ zG8`8&3$qv@BtFr%cSgVRP`Ji)tyR;IpU4h#MvEjY2S^Q|HNY4TLW|=bw(GinoI>QW zZD&&E>1_4Dbc-Yti~ocL4n%+2>yxv_u*9Au5imxSXuHW^docfozRj7Vb)2CwT9x`( zFe}|vsz$!>jcb~5kIuJPF}QlHFZ zy4i7>6hIU1Kzr-atDi~+NCnR8}Eo? zIspPu5VhDI5Jy@McycAwbTCmXxD@4$!{V-NJ=|~ww9)X3)uaUtKR=RPQ3~Hg(X=lR z9Qk#btJp+~0z9}2up@#gh$4Y|Yl%Nkx(^|UVJ8B3`5a!a3kXxStW%)`8J_rP$bwMi znc-6lMixV3Dk?#K=nwq{C`qf;q&2O>M`|hC$_m(Ow04UJ!u97k>pOHl_JS*OnPed1 zyUj`ZB`fDqVea1A^sKd@$ee%c(5mWQInb8^OZcgQ75%lfgNlbSVflRD(R=i=AJFdb z0X9j?Ni8{DTlPYsfsm=n2&B729@{VO}rLZh~0&Stb3Qjp2TVzQ)^cM z&qbRnu&gUa?P(5vaY6a%9dX(a;oLF2`(s*iP<8ONsZ{+hiz}^-Rm!=4m_ya-2+SfL@XpBSk#Cy##|N{+%s413b|PfU&nrK%S4M zM+)(IPri70Hm_uz%vCOO(-h7wq!8*m~6Og02>W zUS+Cq)lok~c>1anD%p_er^Ao+D)WT#b45TU^K)N~U2r0?792YRez;7}_uwtWtbA${ z*Sv=&U%>AKigZGW9ml2VgZ({td^pcfhw1C)U_A@vIGiU1!79kyK*cuhLuVj^qrS<} z8)@4Ez-)l?)SYtZOK#l5Z>luT*_`t*xXmb6 zi_CLl+1ZduAF1etgzv^)V^T(p6zmc9u3Bt5<=%aWcV9aCz-kuX2-X(%P9znL%KBZg z#1}L((-viM%r$WpzQ9ol$7@tTB3>o*V`cTDWFOP0I4pSPgK177rX(cQj)sv{-YC@u zu47xWt%>z06Yl8VwzE^+SApZ}SbEK~56*_lKOuKWoEV12+M}UJCqs4LeKwZprl-DN zuYDE8dbV`@=lifuV(UIRNO0w}67QMEu2>sa?(i2EN0d*~#mXGE56&DHmeR7$MOBM} z7Fa^cUMKIK#jHbQR;V9M5+dB|p%Re}TpbIXd9N+r+9vK?{?asJFKB=!t=_!HlI?|vnBJy)EG%Oz+ z06TONCsa}NRupRVu)NPF0g>>tGh0ueGv8|fqCzc~weUm~ zXxoOsAs4kDqutrhgaBxgfoRhB(TX@+3=aaXYJ|H2>*K0xe{8-726=E8#Z@LZjE^b4 z^!Q(ST@Fz1MaKix0kXKxsP3+#F#bu@7H=e}O!9b0uTuK3dpFS!zhK|=bV}dC4bv43 zKLj+PY_t#9U2Y*h?A8S4XJ@nCGW zw#k0qUe+CXJA7{d)2wSab#qAWI* zODoMAtzht1++-(eME*5*pe=M(u(x$;@9v|Yb$UgyL+F@VD=&MPAGaHWZO-;nVuct> zfgS6Ta`;s?ST}z2{S0lUmQPonV%pB!IiOxPwKBFgn;FmdAEzL?ruQui`ddLiKXqNbFyt7|$Ty1H+*E_*<`vAHTxS{flkxZ8Mz0C8D0iY4F4F!Gi)NDhQM z$JonEDbOQ3mE=)QBo=9#F+djAYItHFIajJG#QzoKXYYa{J8k4YpaOuoY6w)~J7#1k ze!0tyIX=W8>~F&<*W*=Ao0yFODBbFZ7FvF44R5=-Msmfj)b-y3t%`od5~BRs&J z403h3n{oR}N$}&nRAG=3+4+(%7fS4!fh}9q_MQ>iJ~bTn4jg4shAlek3KR@>ZPj%( zoPM%Bw~+hXP|&!zfGMmY<2v$sT@POR#hZ;Fx$E=fX7VW+nc5*|Q(bZV@I()WB=+^o zydRM$@pAPPyM0m;&DndI_-(~$Q#09=j zc)V;Ws~0iqM48MLAZtQHZ~oHG(o6f3>@Jpf_ycSI>T$uxPY~ciWt#2&+6e?y0_G&x zei%rS@qLYx?FVQv$`UZt%aIGc5KAcF3n%-3E=)wuc4l7vqz1Btu$_V2rR^OGaZlFV zRZ(_<6*PYuZ$nLs`1?8HyLDb2*aCNj)jqvIp&yJ9wQOu~cvvwS-Hko~L6bnqe2S@< ziqwAsN?qm4mP}utKARYM!)x%6MIdSB7^gX4?)yQo5B)5QbC!VZ-oh1VTBpL0T&04^ zzW?6WWZwc?k6gP!! z@0N`TVTaK|5!mQpnAYd1tb9P0X!@KU2m`N=d&D+gmsK?Y`cVpuBq=ix7)Y*G)en{E zH+A*|v*tN{ApK+5BxxKoDQ{G)_LPw6i(unKze(YFbLPBOeK4S{uDj%e%)Jo`VBnrD zukZk#3nC^{Cq8r@s;a>tPS#-H3W(^;)x+iwIqoA~oKr&i^_%maO&Q-ub=2r76zE74 z2A@^qt^+R-+olYTifhFidHxDy6Had1jl8NG8K>!q@#wMXSQ6EbN&n5Qd+w4Yax^V2_<@H zula=esPYJ^EsV9PCZ=>>?dJ?JgDWx(+XNT0OohFV3v!BsZ5Dh^jyXummw!c@c}j5K zRlzQ7c0ig3?CslBuWKxamQ!W5?Q5$r#7)(nORYZ2&v2vz zObl6%H5b`?^v?!Rgg$l$4>Q-In7)G$LxCM6I;MC{W5PPf7u5!%e*VBqgsS03_ie%d z5G+&~M<&k2Yrjo%`;|V3_H|q+t|&0QQE*i%7f)lN;;&>f;DcvIoLP^A%YB_%dCi2W zWh5j0I)e_@{{*y%(i?WOw}*cHOMT{eJuY?SH>h04g zkK!sBaCp_fj-Tb^e2-SI9@2v78f)vdAx2Czoz}VLa4W;p3@`Y7ub2i`**EuKi9w6IcZFjw3W;W)$aCW;fUom?!~`0n*K`J^i2uBkGn=Mk%O* zgM2#mh)?EG-qhA<(U7O1`{9bXOwvsA0Dy`dW*n;$pEeQRActiK6|y?Lh6VpDYM%i$ zZ>JNrk#CTIV((MYzb=@4;^8hzrye8vLS!_+R0j?;H;w@Z7A1ZJ5p6>ZpYt?oi)NF` z^Pp;Gv}|Y!u!NL8d9~M(=I52j1g`BYcSRalAjU!7A#W8muBAzhelLU=)nwSu>nPiBfh#K2PoUG)1+8w~=v4FT0yMw7CoUhBJ69Z@) zw=EE54k+6O!PRnQSr)O`GP_#RTrsfNs+peJ>C|ZOv4BQsoR8Vk^a+4E@kL>{X>GPb zi{p(_xiP$CjOvM^UuoW-1yxN`jZAhnh3Bkzi#|<{y~QYT1<%`BsLMP^S0$|XfVf=7s$r$#0imj zbv3?ksRAysl5dA-$0RRblXlIa&7|RYRD<=I8nXowqaEe9Sq@jX+$@$)Wdb#9=XyX+{CgB_->q6oin`53f%J)Yhz+*Qr)1HLkU>bJ)T%{%B!>;Z;WGOGjGQd@> z$*D{D2xSnp!34Uz31D5^7eyp`X6~Mz;;U*d(kSN}pnFognCu?40aI`;;d$szrjW|j zb2?H_UHO4ct$wRc%PoUH_%+>>33>KhBtQXW%De6Bd;ctY*t_x}9)7&`(`R zaLUxWDkuN`?1B^-EZeQRo-SIFG#jOr3|dLgWz;z?C~UlK#?5w z@uvBUsjXGG=6+CSEp$WQb}XRn53yr<$acHi@ppG$Vh5kvuhH%(aLsp6vcxb8$kcJn zBqRu&!ER}1O8Pd9P*&Q`BeLJ`UM3RlIP_*0{a_AJyn| z#%Xf_=;7O#G?)>>%RS#;1H|u1z&Ihd>N=!u8S+|@*bifJe3|sgG2Z90J64Ln-1nYw z+$WeMXu4H5u1?jWJ2CuoafmVhE2h27^=PR>yIXi-7<+q?}$WT zlGn@`wi0xJpa}lPuaf*Mz(n1&L=r_z9pl8WL_!?oQ z`3>91ZKTU+dd0-t1+}HMR2)RQ5Rs=3rhST!1_exOsbUu$S}APa=GgOkEQ5;657u_m zw&_t;mGueqrb%yGAEY_%GDQWG_ypce2HogwqAPlyfJ!S!6tvQ>5aIIJ_=qUu41^Y~ zjo6bA3z`dP454vzaw;r4U}8~K_ouq@P1+1$V!c?TN!#t-TG|g8K5n8f((1BKxZJ22 zkBL12sgxqBKBW+3v>?t6SRYqVwz{NwA)7vgLrp~2t!1enBVE#U+p%}e3$2J+e_Bwy zwt>Pb7Hubnb+;$wa2Q`ig*x>e0Is8}f^$FFHqNxLq*h_*^kkCi#xETEKb~x2il!2K zF%wG#x%MR)i-)F2N9bf+0sR$uv*&y4MIA?QOe2gBfM>@xA15A=Ex_=_U2ulb`VWGX zlE~;lJbXU*Yt+WuFlexW+!s-@`hB%eSpZIm^_$fIA zKK8)-d=CU>DH0F|j;N_bJyLYGoxF8P`4`&M<^|89rXI;%8W8J}(h%xxU<)lAMNQ6% zz6tQ;i3{lGedyjGq25K#7$u`>bjlEMfK{g90)9&_0dalI%$)C?nnFsv^v1t;NsU^F zl1gG;Bu-MCE(F(RSZN+iiy`mYrKnd)ZTkI1Eugo4!9OlMp~fQ-*>Za5V(U<>gi*6i z+-xiK68L}RAO`fO=rUVN$+eka*_u)!IW~JBCEgxbl}Y8H=x1L&)ZlKW!?7w~+uCFm z+wD5UxFqy>b3PrK4t>*)qGlZdGb&UuFGIdSv>@{i-)DUOqoM6@-G>A0%%gbv3gkeg z)Lkt6Nl$#Az#u>ewrP51b76UK%+bUr_@kFpuMRNgGv2&pH(jiqh0My9lq;3U@Qt`# zf`uH@4I&@|kh{hqe!-0YZ$J~MQTCSy=a*%2GrM6DNEy#)9jvecRr4w!%gJMe{h_f% z76AA@Cbqn#y_H|k!f>xSCZvFl4y0csE*jK43|v2uYJ5W8mdVFEAWu*9nOy=?fm%e! zsi3v`%u6Gf>~-s)@jDXzawXPF*BCs(RyDD<#I$?Y5Q+XArr+ysHK1h_XTip^=Oqbl zrQb(T>-L@&fpw+3Rds;ym*pbE+fN@FXDe8n zSb=QfYsFo5|hBvd#_>$VPOt7K6|}0_$ylXoz;dl)Ro}^X{38po;;3!;dYXSUAI7LlfUg z7%Td?Bv;Q){#2mxDCMloeuclx0Q^6cH&-Yk&kll&jcR3s%l|z{E|8It&0<||i+IG2 zrimLHtAliMnVJn10sblb=~>aYo*VY;SeJ%R9nemngT{->Y+_jk+TLOJRMjMj=7lFi z@=`FsqY-QGXE{j$M*YHRhD-R_LGR?{6cusI?m^OmBd;hCft#hjQnSpikhO{Zbd$T7 zd4!1DVS~6aK{G8V>+u}&AEe*OE6U=HR)c7z?4HzY~mr?rW zWHp0p#la7>-!k3=Tn!#d`PeASNmwCsLF<{%2#IdtbvqLPi9mM07<;`s#0Rq!VR``X ztVPegFW@t(9J(-Wpn^lmY<}{vTS^h-r^{F}6$6~hj%>TjnowEs&*jcjMq_X_1?Qvz zqi8`vT2J4fhQ;vzEtUlbKA?@PdMS2*1KV5|Fud$>I{SktU%I}#q_e*VV-g0VGJ}U%3A}-khfV$vLaAL@Q!?ZiI{9c!C z`^641G{JYl&KnCfZ&aAKHtp!5b}6X&`&k}25;UZ&2<-poZKY4o@z<^e8?j9GRqk1)@35Ar!pp;AVcW4VGh>hOw%Rg|HkkAags^Zc+P~RQ#~+qE2zPlywkY7 z>i%0&V*43krf>9(tysZLDf2L7wV8_WI56@q*Mw8UJ`#@Np1Fi4fp?d1o z9!~xN2vC6wCI>@Tbu6Jg>X*)e3?n7n`0I$JjDNQ2bliD*-oAs~nC>%4U2doXTB6@@ zt!O8puIJ7bl-u9Jm2Q94HuGViGpw{`k!;uhVK$yrU67l>1nvRG6NQ_ z9h7?bToweBM)q`vx|v}(pZ|m*>4rDs^?1vzmobbD^`X8NRk0WS_Ot5T7tY)xO+Q(( z0P)+fH|ax@eePN6oWIL*uNG*h-`<@YSmMjb>B_4-zbC`uA^osjv!4`=V%=%*XM;gL z+e*!wqC2%c1iPGcNzVI%MIxr5BFV0gSfPq#Bv7t2)X} zG$)hM*|iDHfhtO71s*89UV2V)>D$zjv{#bi$VJYjm=EXjMH+-w;Ux9QN}{H`Ki0-^ zBt@pV&U7K(Ye?O^tyru*B@b7Gq6e}L$p1IVQeyBuVP*hOQZs>Kj`h?{e;ti?Ip+O} zSKl`iwlTwSaR%`Kep+jE_S(0}2w!%tmW}s{z#L+(ym{u>3A@VG9;xyJOsP_h_}WxT zZg%p5wD&D5HnJKdMI6qBrT7G~Wb^vn+tYOaYsNEYEv3vk+&=8(F z!zH7;AXqu5@{iN*(9)-W-pi9iS0u<;%}Tm2wJ1B`YqMfYrpX&Yyf-D4;Mg2TSPrH1(+{ z5B+)WlX0IdJYnx>`-A!CL7_${=Utn`Pfbm2h{{G+SS)qy!LC<&4QXQI1ee*CproG0 z<#VnH$(x;-0NhuD6!76|7mckvJ3bK-xt}zT@OcxBQP1X1T3{w=7&MDG%W%HND{=Oj zC@2hZI#bhfW=-&o-0k-(al$hJi^`{{o%>}mc44#7LO#ms(?3+_MC7EYV(a>{Q1z-C z_-w_rJId2|J3@SU@<4~rTHF&_)Ij7vl5$hvqtHuDogM>wjbGD>UrIZUk+yacA=3>^ z4CIOl!gd3H_3c`Z@H(tA&T(q{Y)9$qRm#lfB}bDlSq(4}j`>K&5vgcsI>U=NLE{I9 z9W)KtauJH3u$>t~M=JE;IC%6K?H~N&Bn%zi8a{$=Rb?|a6aD<}b7yDkc9n%Ge$JYp zb{qm7Oa*vonCrateWp2oVCE73d{ksBDuEgvV0n8m3qtZ_E?+>zR=MkKKBC&*q?3sP z{CJ2GYqRnA*ld2WmFL8)oZ1$=V+0u9lx1X#CEH+OoA3w%1iA+5=g;#%-%Isv)dXCc zKqqDQ#S$RJfYg9ScNpj z3fA#@0s=E$tlBWOph+Fdi#>}Fuj~O#JTL6?0A7aniRt+aNlwcDEaObi$907SseY)R z-0iIe;)9WK0I&~SP)Q$Ur&2CMLQj!fGxir}-W48lqXSBHFFoVYrwY%?8dDuVZLhjD z>qewv!1@3y@1TD%3;bJy6E{k! zSo(%GRt`iPWXVXv8~P2J1i9!i5DqJao_%!$_M%_`y&o}DNVjp!6XQ!ir!?Sd*6jrk z3Y{QwBO&^-&_k7y;Mg666+8>bi-@`@0l@h)&keyw}R+Ice6%lBFs?GU-;Jq zteh13g+Eb)_7x$v7yW?7w1`J3w?(8t_+l!lRJ+&=<5C7J{|k#DtY?|<8WTA6yiUL) z&P`UM-=&~1A2mQ?0W{p6c_gxKpO(t=s=vI`zVEdLKia&H{mX}=XJ1|3VbUVl0`%*bvEf%RGe9qIE1K;cV?_>;(k`X|wB`{3JJun!l)DC9Zvz=Gp z45=g71NzuLRR{n80{|sDgOXb1I3!1Rdkhm^XlIuk)&z}5cZ);#V(<7>)49E}r+al` zA@wkv5m$!qHcgT;z!PXQyrK}E;y@$!(%W2+aKo^cRBCK}@856WvMW_)4el-49PIb< zj0gC-zDdw%@$NY)EW{FVZ6>3&z%Mh^lv2U4;u6lot_oSV?~CgRW5RyNB^_-&RKU1F zR&HZ3*J-bj@0Y``_hCQI`3XV;s?XlbRb#FphCh}Lh>%|3(yUQ~Wm5FG(*XGNt&+vLh=%XUMw_$u=|LYWZlBR_{mQjz za+E+cVF$d2$>|6m54}hZ<5muA-qnHZjprE4Ck>Uu6;I2qC+*57|67vLLv~ngR( zLmC{4SB2?5iyhuudCR}&b4>qH;aP*7=F0+viAIF?k!;Iar1JM{MK-YOhfRAm*Lm9a zlW3p;#>corA{oR7ru^KvUnfZzeciKcV-(>F`JZ!GW#kg5{{!sa^**iyDFnZubXd6apwL;fUeuC*t2bW$5;0q?>39^YXG>&JUPlMh3%V6hRb zzJlWW4v$cUaLm&hRtTpWOL=Q5AOEz9tcqL)^Fjrp#_U?|?K(ZRe5j zF10GsZ_5;GAS83)D`&Hez8?9A_}5&|kR-vf@2mwf8Lq4p;7SQIXs2<-&%7Y**~@a_ zIe-5B^;zhMw}dooO!60+T%MXU4tA{gg3-ZUZvYiZv@XeF<*sZ$wI@keYPmyM`R?pz zf$<^4A)4R1MEFAIg|me_t}(7Y*UFn{-W%jU-S*z+4HsVSC6Jm#8a4DDsLyJi!hGKs zlZHhYpC*j-JELI77!qY^Vv(jrBFuad4g9zr)qaq`(F;83f|wSji>@q7PnXjOH@fx%G_;#-bC}qMTSRwz*ei zxQ5H>!Sm9XyKQPl*`nw$mQf*R<2}(3zIMKByB99(nCGo8MVK4!Z0vNn{z~}CtBJiL zSMU2cuM}x$!35t~TT+ryi$I|WUNXjWE{fw}q~?nj{;sU#0C(h14bxgO z>6~JDAe$5Nf7~2?nk4)m$dekvU!omyVA@2PJKI35mMsNen1$IS z{25qaif*J3zPzAztA_0cF9^3bM-;$d(Kux@Uy6u18J9V5m`(m{#Wt~yda|(Agi75t zuMKM$vD5Ah@$DYfJ_4Y-j4M^Wrs@k_aRc(!IjVo)2C7gYr9VI>~+Vrc1fB~ZDbU67Lfjt2p2dm2y5Yrub99_4@hnY%NRm-SQ+ z8Db-$`JTc1+sB%8x5ibh9QSfy!iEII0rgLqm{GL-Qxyf1WH65Jnn!PDn|vL6H8r*= zmv=!wO}*K-uo11nzW@LRECHXB%xWUP002TbO%`a|M&9UlPXGYjgakiT@D1>jgyC8e zAY#3RSjX&8ajEn%97GwL1XBN8z4CfO2?WI5a45 z@Hvtm1!Z9XMVHk%+n%V*x1+6et&y(j(hrQIBoxG4xz9^NBMCz4$ZeVQ?A78Dwi=-t zT`tfLc6Kk+c&6^AwZJ*_V^vol9|cMaU2Yc2c_d!egWLe|d;>7Sa5wgvJ-K08?Z`{! z_L&u9-QWRQ$_{)-@FTCBUhvBaP2AcEL;CiEAX8LQ@nmZDoh;|DtVa6XJ*j^R39 zn4mqXoEDCadLq;hRgOhbvVsHr&gpTk zd$h4oq>t6IOd0LqB`r0w`E>*(1>2Y+LO=w_ZLG~xz2qc*Fr~;ydq|=O>kc!g<&%+# z_Xmb5^=yS4##64Upb`{%(c$h~dLt9HB@37jSW2~R7($Hs(J?{~$OzNGjzK!!os@-@ ztblwR!6IAs*w8AHZ(*!!(0_+)PX}=5vewosx?BV3x-Ft^<*2uX!w$oYp_M4G4L&06 zjipY;ruaw;CkdATfgEg%DaOBWpgqCO3VlR34phc6KCQHo4GOr|VvZWdTspTkMDev` z;0=qsf6=JX7eo%B8E2Ea&=Q zwNYH5&E#K@gTSAnCXzf>_C4%{hoBh}QfS;ks)Cqj=-^YXmJ*>5v3v{mh~6Sl$uE%&b*OzFm~3#3k(2v|Xk_uceQvvPv^%9;_Zg6Dki%>Cz%-cP9cOE9 zSN--EoRI;2Z};*bYI@Gm-WU_}>cQ2Kkroe(yQ)Yqco0mj-Cx|`PSZF&`;M$grvJK* zD4(Ij`v?qUMTl6IkPaw5xos;3iI@WE_+%c*g&R}}UL2bm9;6?zaU^Lcn@cndJ0Wr4a{UTky;H?0BW`s?6zqjq0q54 ztgi*)UjStY;sC$Q#D2(B_@a91`oi>A@bF4gc#+y|PY?c{(BB4Y~(!r zXbiMQ*Z?!gJ!v)nb!g&`e1ti$GSQv$<6DtU>F4WQ&G*00n;`MPV*+|10IlEJyHr!M zoOd2;^{rEl@(R(3iH_C*BxQjM}n#v002Cf zgO)=$-gN{i00096!WCi{H^3!Ta1}qlM{7$cp0KzO=xb&TSq{9aH#!f;jpeX&b%+g& z+&Z^9Nbs!_aHWyhf4Ii?En(t&q z&b2p`Hxfl(7!J`pc+Wot=kwOkcSTpR7g0ZwG*@V$n{rYRu7NI11;+6C;b(us{e)y+ zvLUb$M-qSxLt;o^GZh4CrJ+k&JCMHs91$!W)pxA&)>)vOwvJgD!#HWmBZ;pwTdPqC zXBSAVx0W2}5KWzqax?`_Y+L{|eIF99&-$)^)&e#?9xC0sJ4E5J(MxEwTg{no&!NA{ zp8&UJ&#PA~i3rx&zXJD*W*^SbwHGwup#Vj;kz>|%x%W~z#ySwctgmWf>C?0*!2;s& z=e_8q3irc|k^G$^CUpNd-64!un7b z`8yIl{#U+Dze7WR{~u$wovi=cz7cRZ1;Vc1Zq7zpg?VelQ#p^)f-nPzMn@qt1OA%V zzd(HDT}Hy*;R=qiCe(%gJl7#CE;qzLJk)Q=6)^+T%|T=6L!<@s|85I#nX0z!fP&p< z39*q?MCxI}#x(1#L)}U(`Dv!*z5qf@QGFFYUYI#ksPQmkG(W7bO_OLw#cmHJL+VzEFd~5P}4O(Z2=934WBkh8ZL-Mb|4a4K0CexO_d@ zd<;(-1`ZM^Na}lQGNwfNY#}m*?}e8$ehsBN75BA(@Z+172Y}9~KLpR<09-%-00eOX zpOh?givIurKWgbQJ1`u%%fWg80Aei+DACcnc#)ALUTiwfzr){{GLX%>vJ4;w@?pWi zcF9)F4zHt>Ay^jHR|wpGADW~`0Az*E?%0~ZGM@KRh`9;Up4SU84;^DMEXMXwtbu_; zbPvN`1R^Ngjuhf2oC-Ic5k^r`h%P0RmIJJ5<%~shdyMeWiKYPsSlp3tE^;{|*$WxfR-KF(|$V0Ku>GABbJpv9Ie#OcEDks(+j96 zQhhBZEJ04GrQ~rCh8pvN|CjySUW+L*d})HaIwiq9TnOlLVD%J+MjWonzpPrqws-uQ-q*T6zUTJg&CAB`~e#hQo@RF5t#qZHLY|8J|@IR0jyLU&^g?=T~& zvyfv{-VD!;Dag!Nd4(YtTn*wBh>@A#wWJZ>|S!uUO*%oZ~LffHV(P;z;_}h&O5pM?VTw9X|rU3_l z3p(Ui2{kZOo~b2*jU84p>uG(~aHcU)@_j`MelCbU zd=|M&>W0pc5gQOB@jDw!^QRdfeJP3+)PZB#>=T3xrQK!AL-v>(g9{(%i4Z{ z`}7owN$Zs(NMgB}T7GmwCHPW76oT--UIB^D$wBO* zq9n&QHqgSJV*p)%nlzb=W#5fY0leuJF|C4J+Y6F|ZCPgus`| z*2HXNT8n?K55fAWeHVSO(RYcE;X|=ZL*@gaZ1255dWFghjfGA09Cmk12LJDhDFB^d zeeMNziwTdDn{A|Mm8RW_WQA{;0@Or3+GwB*n(xdh`o|mbhyL0)ajyPuX7#MWJv4GR za-zYNOHb{2us?uy=ve~?queZHBb6V)W7rTI&GY);6F`eXg5Z|-#IGEe>rH+m(tJn$ ztq35ydgisp>3_Q=1s~b<=n!kW8GVsIxnoAg)mzy1U8m~+Zo$}(%41vnv=E6=1~IHi zDu`#NI3W>3b%cc}v@lR^h6lL`jku_x=K1ha5dy9N7wN3`Z0f%0P=|bWt*Stlc_QJ} zS%!S5fG3KCnFc5K7wusA5MTE1od-Lwf7#wuiVOELCCTxc^pzbv0(sLoHz}ik2~|Zg@($CY|mk0v=pwbr2(;_2DXco6#gLM|zqBlh#*5 zOIcA2mF78dNHNcmwxKNlxr_Bh-6&`Zq~B+DtPI;k=UBtiqJdbn&^r>2P4gCTLR zzyTEOOFtX#`IhI3!LT3Cna~n7V2*@%^f*M&NNn)gSgzZyeh>g|*jnUtlreUx=Gd97 z@LW#M@}exhdqnmj-(l)Awwqu#N1a&t2guh9T?4^xC9QgEvuzga_1M}TkqdoWHG`)A zc|_~g!#D3UQoqK^YxVARY8}PcFP`C%cq<&Z-8AOZ9jEx426h< z78SK`22`2iNk9b?FwGbX-%a87dAyVB){l_pW~Ka*u~fc2Ucng_1tKl|2fX*%(IMz@ ztS>6hcjeep3@r$_#ZYddG+^yxj}Vi91af4e^wo};gwwF+67^&~&mbJEguL|_(r4L) z+E;D%ijOW%a7ZqaH=ht>MA`K5i25pakbO)iCPOmlzc_<|#>0G(1(>Z*akDy14K?|j z6anr}t52fGJUlI=MohYDG-Y@9Ee*QVhj*8=vVwW)r#RQ{5~Z}%ez|1-i;p+vs{4vm zK@!WhNGUYmViUYRD(? z532QC{(e5=Wg)o$00RI3Cx=5Ojc$neNuWn9P6QAE zTDHeW?0AC=1Dafy_$=0i-ko9#5r$Gpokm;00x4CTzyJVwt&1lK1_iq0Kn}*ZU`4W6 z5j2owJxTVw8B)1cUgdYY-YNIYA33dd)1RC%3%TB85`WZeFOC~RnleSbp+ISfnPRHHFq$=6zV1Qc zJT40d;`IQ4)}YXoiC6clBmJPygLZ4#o<1icYEGesT>45LKmdh1;SOz^We|0Dg7-3F zPyhgf6h@;2tl+I}XaPBc0E2)400KxspPY<*po$-g{{R3t{pPShfal;68E`>fz*Z63 zR}SE8krdW%h9PbUkk`2=MbuB#B&b(EqwmE`$PGXJh4 zT)L4I*7?g$RRekv*|o2lP?os6k7#_MvJhV;x5TVa?|CD)7O!@atfD!g;}8`m_M^HQ zH=uGLCTLnAR_}%(I7GSj4>6nRM)SF*rQ!yV?V)rvbPQl6E71sP{h>4FBv;=F_s&{mu%=4PKH!l z!sSoBb8s`g-QyX!>s|0L`&=S;C;ux%i8AOYIJB$yrxhv>8UBtZ?~rZ*P1n;F>|A7m z9zUvc&A$~X1h{mX41+4R$70h=z@)fCPd7JY=#=G{98)R%apZG)ejeyoQOrKXE(q#; zxIZl2JL2?6J`(}VhBx6Dn2dSKM%CS}9iV^XZj<)x-w&3ON}S85Q*9CyKmo_Hor_uz z+<^!IOggEs1Izu4>u`{t%|TH2S-AQ!Yb|kL0M_27qRc18f3=0tEtnc0Z()YzJg&?+ z9`*D1PSzm0iEN?wy^<}in#r|3=UTu~;E8Bp@g>o2fOj4M;Y$VZ14Ap2(>d|OyhAzD zH=8e+qH>)T;{_-H06$xF@#P%axC(Z z0axkZw7FsoN@Q$PG(0Chpa29U46sU6U|#^fga80TD_gD?dw>W_!t`SISpjcDSWtM5 zIhr<|KdVwgvhodqa0NJWh#1~i88RxFjd-dt;lsqnS0<{9-Vu;JMB@TO$`eu{Fhb%S zPhR?vxU)=l6w+rbu_pjIAP1;>f*-OiLD$^M`kx($XLqg-7p@ajwoxAD2Y(0+3jvC#4usUi;`CHSy4pTL zJ2@xx4d+K5M#?@QWlXB0K6_ZgB zL-`L{Wk1Z;td-1NzYW zj0(1qy)^2njz3mxyMa4-NSEm6xbYCkI0>)! z?Vb8E!)-dHOrIm|?fb3~olgIrKx9MSEX>Cf`|ceyO^!&J8&-UNfsn5b)_>1M$Yq4! zZOl+vQTn0zjgqB~435zrUnuw`Q);cXLM3o5^i4!Y1?qhIvto3HT-^hPr~Z-ZSkw;rb}1t(V+yec#Jliwq+OM6NG9hOe*~wpVga^O z1j*|AJ{cX>85SwyJpd0p)#HtZ=mzMOuLVz{`W!B$^He(6b|=@X z=@qUi69Md9Qb9{WhU`{t{g%DXSRiu$bPSeD)fq!J!C@No&uJlTwROfIz6kU~E_VpS zTZcp|H`8X(BKAotG=v-V$w^ETvKj6`ug>m~EbMq<=v@HArcg1_X{Go4bbuc1zc@to z!a#!44o0R!?$_{Ai{x8TdC!0?yC0$cz#ZanVCgzf+*)Y@e7BF2zweJ-p>Hh67kOh# z2PSo0e=;p$x($2CR;EsED36?0LO+be4gR6+R+-62$Pl0F7B>uGa;IPE^78Cf$dZ+% z`Tj47Z_1_ttbAwbAEzS&-r;o2#5LA%V;;&ZH_r8xebD0tfjZe?6)zQdmcdig355<%1Cg(6cs0HU z`3x0szPF4UGa=&#O-el2Zyx#EMEWSUIEriW5rz1op@?*??V>k)iS-Eq07DKxcy})C z)~$PijV?8gYk92$;i?>REwh^ENBUJRk15HNCNpeImq>X+=3z*Fhd2@XX<< zaNrv6ft>JZd%SyhhukKJ5~!pt7=+~qU@lL)CW6>_Cl2Q)F<_YiQ{FmYoTTN6oBSvl zEofvNGQDlyI8#t<72y$JAhD=Uni6IN4Z@~^$*GK=Sxl}Nz2*+1WGCCE9>^?1zih&w z(#DK=o;8sG3HX$c9#ll&7$@>-k4N00};H-}2|x@MzWoUHWje^BKe5>GimskrXwrNf1=Em6MT!2~=f3&Sc(&;9a@K!k2J znglD~w3aLN1vRIhN<5m6;v^>#BtwSvgQ(tm=Heh~jso2rYRqy!f=4uK*lY#($vDU3`a+LmpS}Z+Z09~1N$Iz+cZgfDJwrKlhR0!u}wqDq@V zEzFUCKBxbm*T-89fQThwSna90oklKVN*|k; zqShAI&tp&3xqF|Kh*{bzXK1-$@EB^P$o(GX){03L;aDJMe%Qy@Y!sO6_DEWc1JCD4 z1j-;sm^R{3G=~Q>hV1$F8AOjpLd6rA5LX6{((u496Ol6fse_7N!s52`?*3V3^hQu| zI*{;dmW2K9Dn^h)^;>f13%^FJ#amM5@VS~`Q_}Ue7m<#)y2~BN^Pc*{0oR*o0D#Ox z_cWL3^LUo5RCidXIx}y)+JgS$WS_kB()o3y{5~x!z=``S?-AMW;#%6?ll;csM+*nE z2S=oHOW7o##dAo!?h|;z=N7KsAfI4JHF_$Idz!&*l(8~d+3->VLw$GW?k1XNu_WSL z(SJHm)IuS0vh>2F7~QY4d9(6wm~u=IHPfS@4;@rWCri&VcWpd|t>rlBxmn4K~U~QmlmIeKYIhWFXA)g(e z3LlnI1b%@Ws_e@He|}V=3Efyj1@3=z!msnnbJVRN9@UG31x^t~_p-pZCy(knJ|p** zG}SpC$U54w%Q5qf$h7NORWj_I>mMQFE?Hl#UZRVt z%+jFR-c<_#Y3g_Zjmt!A1oYPRpvQdIPD_nC6-7?77U{VAZVb79p#vhjB|Hpd7)cMU z3$F-P5uIrb0Z#0VL*Un!zcf(JP_@8N?V&!C&Mc8XirNL)k6FMB6-r~JQI-mkWi7Qh zM7GCAVx(K&PXKkCZk*$^^en@g|3D0HCCv>KchocYvkYwclREDfw@o_`4`gz;5eA%YqP=TE#C9b7NLI{wSwNj z*JscFlcDL(&ymIh-VfHYJ(v4}P1ww~cBg++2fHCUVAXC9^)LSUD~Nmunh=aSYe28_ z5PxVa5(nWWqNIZH< zA_B%v&m-O5S=v|V%NmO$b9za+WUZ~a8cNEQmzW^IOHN>vwNZQaN%}3du>))yl^RXi zrTPP@Pchi(Fu4t-#t(Mrxr>B#eQr&yt7ZskKAaV`Qk31Iv(hb_c} z_ZBd*o$I*`4AM1Dv?9M8)KX-ptm11zn6{JQyw(4{#(F?x>{M1i(3U{^XeD7!g;xnV z$rOBhQfHG}+Ypl)RKxPeU-~Cx^LD2oi4&aWGD*SuuBQ4Q#UPCv7K~S54gnyCso2ru z*wZuC{JsOUbjE#h`}XoQZloi3_ua9Ny+yu=dQS#VL^({E0ZM%X=ZA-Bwt>2X54H#B zv=SwPMGZg;7Zs5~8J7ld%=F>CV%)e}E(WOC3L&u&W-sW6>%1zy;S{W@W{%tNIUB9~ z+7{07;#ABB{q_C&kNNRe9$}e+@>7O8Oi}tZJ?^B}nzqaSM+ls&k=x6Vgfasj;$-I# zQ9@d9QPJn^tzM7!ry4u7r#BtXk_fECL+&S?daEoZq8$(B7J8)Y4{=1T=Bd_TZC$l7`qNS-Hu@ebQxM0G zB74X6zJhxJ%^s%*92%yit=%U1fD03~?DCIl>;JzhZb35U>2SIg#)!51crR;9IUKJJ z{N8enz;r8rTBFZHbTP67OV(fz?qnhk5J^49Nqo}Dh-|Z~8!M;GQ+)ouiM;qt;(uw@%Gg#G6n&L#yP>UlMNE*wM~EGUz+tgA z4yLTC%4-cBiTx}t&VZdhNrFqR-UTQ#x1mm&LWVoaC+cq*En`jRKef$2%ll0GEtU`u z+K2Bw*Q{Sf%T(Y$j+A>n<< z?8IiGJX@6^Z2Hs?LPzl=AKc|lu_Imwnp^Y9k6T_EoQ(|& zMbBoa!yz!o;jQs~G>i6{mt^w@;2x`ELypor6=snGi-4t8Qg0OK6}s4eqTSM1gRj4; z=c2wTzT!yvNX1cCTwG`rWLJ@K4g~t|f2jPv!Ot49GuPD)yo@^6gMZN7RA) zbUbTXgP(ZUAQwPOsmWg@lf`rFLX(`sTQDUc_(uP5dDVZnz?`dN1szppmuhkY2q1)+ z0n|`!=xywy+pU_GG!v6Y0l{{R8~Y}51)V zbLX5&aqh$61cutcv9DGx$AeH+az>23({)kEJ04cJ$>&8S$kzv^{OjDB*gW}bhOvPc z&tm;i4uGoke3q7(JZB>4$dAX5uZG8#%6FRB?r5XRKW_zyo^9#{v~zr})_VViE8&Jo z2apF@fV%F5dEWlDU8?U9(~L*XP1Bd4eToJ@6!RjTLF0`9UPAsB~@PE;0FfA z*k!r2gDD@)<$8zue6C3p_{|_^zU{@3*<&NGDjonf7z0e)yYgt>XI6hl8raT5DTI=? zQCz8uku;4%YSNiuG^Rp+(?Q;u$3l~6l+lhpUqcgjAtCFN#^>#=-1`2EhLrAuv`f=pO;JtFF&A_Da!%b0SftzW z8S2k@`0^CpsJ%@6Qj_gTBym)wio_y`pZ)20krWchGqqx7%lP-Y$F}El=15OC@2;c} z-L$#xt$uc;iDotIHUi>_NV>(=Z=WS&ye17x;H-y1Mr+LjwK1CUtcGe;J&R3dKXsqF zV=}@+M3~VF1@2%4*)m)yMh|ya1_c`vv7cRwQtlC++bZxnh3UK|+BjZ-^td+k$O6?o zGX$1BW$v+mg!(zXeTj#sU*W~zcJ7b&5*CwXpLV*9|?4HJeK3S*%Pp_G1S2)(-3q@t2IHutW@ zJ$zut947;Sw28zsVc+SraGmn9YXI?&O~pjuv2VYCKFx!lqH*HLno`fz=@CEA>cm<_ zs<+HMIbeCN`b*h#>RT<#ge7spqg4CS%5+@ zXbVEp`lsdl@4#0Qq!CcxHCw7baYSV*>YyzV$8L<6gd@Zd>?F6%wT2|{6{TK$< zmOprsO7Ys1MTEqJ@CYAt+UD_fKbRnmTyC?Lm7D2 zgvcPMe|d^ES?$pm7i=xtuH|izNy-~JlKXJ)>AAp3i*%r}1=n}$ycswTf_^VH@G|S^ zkChwszW@cn8Z7n0-C4%a9pTX>gl@M4#||NHfcrXZ39mUQMF7AEkzdn?kc+B~%42A( zeR{fa4{B|^&bLF;qIenR0n_W437r0g{6qmqU2VlSLNxRAC^+hLL>ZZvQiqPw7bvna zTNrd=AVZ}W2#u9($(Og-`GJ){joX^8$uD_VyDrfw{~q@0;$LBC{BKT!OGvvZ!u511zfYG)}o zu(eTkEpAYl)&aw0$=004-z_|$oZmj4bHUu!H2|`R>w3K9H2&yQ! zkw!3vPk|Z)BFJaSTM(p>2})#?=B8<5h6DzO&4E04X@@?|J{ZGEow}g&yUO$z%(Vg} zgdA801`kX>@>6+Go<>-IBYh?6kbZdxK@m@t&O1o~#lih!D-t|;ORRT1%C1WiCYu-G zsA%mavpp5lUM1IZ>;@CmY>aihOW`RegRzjGdqGSnOkNnE!khJfe%#t7c{HEx<807U zuSxIp1h`Su$^e>>-(O08(YuSZ^qJjF_DuUrM}*m72G>xkM|J|l43I|W4^jlFy&Ry| zn_zD!%6l4k?zxq&DNsKbc22~y2YZ9{ifWxnXLb(ZTS3;Uqko9rR6;nJ(21uAG}$t;fd76j%%`7}wt3 z=MUS4(p1fG#tOZhm^Y5QQocc##eR@ThoyL+MFZT9r%B~XQH&eg`BB!{HQkIq=w|p!Wky`8_9qd2+ij`JQ7Bjv$Jw%LxO&)9qdVcGT2yISSTsloTbTyHQfEZY)Y_ zlDjX2Xqjq{he?ah1qSGleU$FBAP$od+*lN_+&tF7?^Qo_C9@MXa?+oMQm8;8Vlwhn z&CsEjUy4n*e88(d6mK48G+&ROrKdf*LjVZzr5WXp0%;d9xI}>+Cu1#!%wK|blL5ejjj^g!j)%#wi}}iU=Yg0-@ib*b_Twb5vwn7 zNKhg?2;#n_hye{P^)@Ara5b5K$6`n=G%2am{ExPBjiO2Dj}{Nh`*e$g=JE|4lc5Vq z?UBvai7%%$S$&3P{AUR)j#=t-aH~QX(=Zm}sM0bbldo66R;O-$h!1rc4AWfp?YaUh zDblP6Qz6zCHxKlueHvO30|M3OubI8XL`p6L1pEqTEFYjCTMuEqWB{)KDHbELQD%F$ zX!)8J>cdAalot!Rig0qBDn_^wsgKH9xW`Xll+1xQp^Cw0XfUVvsEn&jB^K2tz+p33 zUf)7(`lS|ctDwb?`GRo*``mJ{S*S45+sk?A?=0gTg$C;>{TGqwhoR&_tM0Ze6?EQ+ zNRgi*EZL;7-k-9DWA7n%2Kq6e99QhLRZ0`;2>=ZF)lnw_mO}tPurAc?Side@$771& z^sPUfgrnC%^2;HWxyA;V^a21RKM4JOF)`B7BDo9G)J^Ec2GU!a&>A;qjH6(ukj{0g zuL!4x)S?{}>y|~Y$!0!3ZsMpJ*mE7+g#cYZqQ4%|ezykmJk{szHJ@>CZ%iXB76QYUOa<|G|G5wXCOc!JKmz272j-3i}C{ z{o7AV6?s&zH_riZi+YlT*JyxoqDIdh8BZ*b@lF*A-zW7j|KN19g`@?G_Bn7wwlhWa z%UGsWm62^xE`wE!#S7A-%z~kFz&arqF7;bKen5-AcsR1iH3s?IU7sis8<*>Zh+ zn|j5;;j)*(KBDK9+T5-4|MB8y*|O~{BaY5ZMG6O9Zgl;48*ueML_jW z!lJM6wu9LfvUh?mlI0+s@>arQ7!!62Xuwbi8fra>t>`Cf_R=zX2_g#t*`wp`??S!c zAPuy3?i73 zIY`WX>vI>TpZwnlJpqX8;s_K@5^9R#wlheNkZi0td369^C$Xdz+jaSc!=^qNtQ|-5 zbANdx#eER$2)d>ZHl?chRP<^fUq#SuIu8&J=_)u=r30`j@%}plLo>>mZ_7PfDb!HK zAOi5s!G_qg9f+tDB{6e~N%@p5pkUfqZsvi65xSlSF(B}q4PhF~Rvn<(QtEVJN>)j| zw53^eGX2Zmer)M8dij}VD~Zk3qmN5@(Kam-oWckbpf5nJ`Tmfl^PxT);r&&3nCowM}u{i!HJ&g$tfG{14O8S|P z+vT|r@@_hL$6sqX{64D0Nj|FsN~7&1Ptrz6**otgnk?EY*SF`h#gJR$4m%j@LbZ?R z$p{N(xc%KEqr|-hab;y_n4kE8fxaM;c1S=RQplts?`!_#pcsEpj7*Ai)0>UpRO8EF zT6vxs7ZR=_M*u*t>{kA`C8gXiFDb=f-{fe#L0Pv8l?v|E(r+$g@#Tn0Kh;NrA)b1X zgAH;7Wz~LzGR0pNt-3Sl=2P4x7KY*uR>|!+=xcw~-Yr%RtPzxt64a(ajs7WcQisds^~0#d8p4-J0o zEU{c4!!cXRrJ^ZG=tQ%%;);k@m_Z74QW?SB&|rn%(V|)z_a3diu6_ zyqwc|3XMpX~hOcFUpeV z>xpGYeV9Jy;N<&N0Nt8T>oL;YetkpUD!>G(^`P&=f8q+0sa;`|^?Hw7PfS5tSnT?cPkGwdN5}*TSN=cg1K+IZz%}`f-IM})VJy!hmN6GcP+~hYy~m;zRvSHOMbJL zWu5iw_kcK_w-N*VZDQ$OoB!Zc=Qb$TYm5p}BfeY1AH3SfTyq99JKYzVSz!`P15#6eJ-b@+s5b{uyT-Uz zkh7@YqNoq+a<~#CJUBrSLz{;!$`;p)r?wC!?;WBcXL2ezL;p>>{|E%}njtwE0dDrs zqt8l=8niL*j^OgmDp>o_00!C|o5>oP%tV$N%>>{+Yo!_HmGloDcRPv9 zFP2`&ECzr6Onc{}R2pwEUSqPKf<$@}Pk)S-*Pd=4U$L=l6>laX!BH!B4cCt;@)hhw z$+KluN!sZAii#p_lK5v6qN}GH5Vf`EdVYCy6b3(^cR2-Pk_EQQ$Ye{VXy1^$FQ4!F9zg3AEAnVed6_;J)B-*`1!q7UuYZa zT+*!<|Hw5Q=9UP+1viA%$dFD7R7qf*QYV;`F7+9???dJR?fdekMFkEay$zUZV!)_u zrSf@y^24b;Y-?0x&p;`sc4Q03;rTM5-P2r^!|yLdtKu>KvqngPNqJ?=J6{&ErC>1f zYE9UgxrYRU&Wkx73Rrr$n%KH-5@GB4QLD=nqyUJ_h}qH+vgQFkQXp349@ZY{?Yt-KwkW1f~3YpW`X4+tmNzXzmeD{x0zY-MUnV<$TXBy;S@j z>JuU7@z+&-J!ruR118Z?pii!Ztw%_*^AE-SCEQ-E#+)xTs5M?{62YT3eB9dmOovNr z{qU%3>PxHUTemxY~=PS%dxI|tvu9I!O}T`M*!`g<22&Y zK1#2#a_Gv|9~4~WCR~0Zrl$hM$#lBH__r@NbNii~8rEeh zL^!~=lr0&Aw07YBH2%F4H~K~%^OvJJ9(j>5#;SjOra04X&8T^>ZJz}K8v`_Y)XdPx zzZ$nyd1C|j{dY~a2wN!KRQsh3KK6m4Ha6tP(nO#M&iCcYU92rGH#(xjN@ zrP{O*>{gRb7_dcIsA_>!Dgk^qhGqjzKoAswb;j?*2k#S0{5)EZLH?3IOt9KYeV1jV zeaK91ag)AQzxU_vsNcI|E*m57`MCIWuy47t;SrC60ATC`8Jh z+B1qF^=b}dAJ5G}n~kg=pwMx(AO`BXJ(-#;E_5H+4NUnfP#z6gO9V*N@AtmdL&)%W zZ>p9ZQ9$Y~U^Ntjr`2|W}t?C_h4~}n@-!;2!Fz4biVWX?S?} zP&Wi5=|^v=PJwavsYid_SoOUjL!{Jwl1DHmGTVtdA(ig3XYxN|fsCE)fr6K)B@EH$ z*Td>xt^?}F0G-s{zb(PV&|Nt?`9}$*$du^J#S%H%x&VNwSO{74)DU-lo$%xV`Djj) z^$vcMr`k0anKR0c35wfmk2J48Z7t2drWPypia6bU4H48Yc3M<%J%dm>%+d{6H&8?R z!^7dI`@Lz}#XzF7#-V~upHOKVUi$EP8sc=j@Kh4+x+U5;=ArwqeJXS(yr=xjY!EbK z$t9V&{6dr~T?{+2IyJ)@B7xSYZFvCK>EGa*?pf_g3Vn7t1M(c^S+AE)M=j;zl=F}- zWnt7f0?LY(+&>TSl@bhQ*>RX(nbd8qNb0XYQ-mMnD<=0SkoN210st;QdfT`SL(Nq^;B?Ozi&P?P}ckfJ<^c>F8Ka z>mce4CTbULS36!aH@IH}z#M&aN_R5Z^oG2GI6NIE_ z!3}<|b-e%y5ZBfx(UDts4~?e1=JO{5I~6-xKENxVTu?e>^BYH%ixzG$Q-h=TC-=eB zf!TXfSj+SCzqp{R`wPs+UNdsAsojNca~eg2b-)Qgiaw~@T%+kEks2!`z0ES#`(o~2 z?)V?5jS*Kj+5f`vw~M1-X=4km3QPT+bH?BH(`Pz10=4@AdJE`}6>1u+q3M)8vtEhx z9%J!0g~C10W_HZJhPQ)TtS~Ms<6atXE7v){uwvOMjz5ZGGM# z>F}%*xIbaP)L+?;UW?`7=P7fAeKfMIX@~d@kd_v33&nK1;8w@dVskUZfsztGvo0{u zgm@!loc`+b1*eBAR?vs76HnpvcYYyJ#=AKAPy{o3Hz#*qETpON*uEn$%a(_nT!i>E zg7)A|`mCySf>G1Y?M4xIw<)&2E6`rnT%Y{fPuDJ)aNJei=(5tNz-l9KxK*XQFQXVZ zvXKv#Sk&8o$$3G(hN-(Y$E%U1@J9>Ql-vo^onF_qTVjV7W{@GO=@F(*C1CNBuABIh z(J<}XondlL%27#Bb&*g8vw34%IRyA}akE0?RW+mEi0nkZ9(p zPrKL>MM3a!rRVF0vI!q4?e65hs!=Ym9xrM-__e?XJY-EVD_~6&I<;028u5j zH~788{%Wo*pB0Y3(Qe!lATbt!ELPjJQr#e0B(DC-ugA*Ld1|I<(|?0Uo!(+tWiZcA z%vbKY;tS6KCF#@=d>lY9GBDK=&BKw80{{>y)wFck*432-^m4k1=9I1D9f?`SR0T`raYtqf|&6X zy!|n{fpbELXGCp8Dz%Hui%!oqO@e!4IoJRTITXNG%Qtm~K18M#xKfWYe>Se%BR1@U(WhP_tjtw7w>~ zneGbU+Gt$#NR42AWH^O@K=+y0KlPDcF|&lmaB$ZI;cz_z6JZ51F?2I?^La5e20^t-IRwQdUV^$q$hY7VXw z0DQ>xAtzlHcyj5TB7=e9?KOdwja12N-=1SnM?m3;Y3{7v<2!g%`HoarZ;ZoC7!LdtF|L<(%;>r(S6Koq3bIutBmea zXHft&Xv@n9u}Ymm(~RvcCfd?G8+-O_0x^u>ah;uKs#s9m;V~M`oH-e_(CFwkOMAEH z#>?zoKk4LUso_zyc03iCBCf*8avT0x%aU!q&{2m;$4=lz*tO{GO*!GKFxg1YL)uOX zbjv3Vf2r|bjj6S|j%gF+{zh+6?soF1NV zRmQIkG3U<-Jr`}M1bbvmRh^K6rLGk{^Q-i9mbrf=D|buMWI8#T?5g*Oa~?KTZ%#!e z9PY_QlhiV2Wu%vM@n5$qauwycoZzKZHq(Lu6DNp$OSz+_DWTIH46)ah(IgNPJr3j1 z(@ALNf>QpP+5R@$e<%%)$n*iiWH-Ow$D1UHHKNW^Ej=Py4J_@sC>fVRT_&Y>t5W;uVPN+^Z^^L(Z zX*7JN2k=(FT;OJY0zP;`zj8vZCT9Q`hrv35TWuCWOb8s_4~Q)tA(+FjS2h~IIxw(B zc1HLyM+W?cB6c(oCz$gl1zBU#{4HnC4?UM2yxivy^Z^g(w?B-Mh9JMq=@LBb&1!CN z?TO+*xUmFxh7{57Q`aziJE7`}F8>rJk6-!uq)*RTE-6GLH-V`T^Nh9sAwHPmkf{3%$6;DA6X+{BCHX6lCc!Z>Rw>P2M?QhSA~ppCREW zg8jhk?c=KMlJ_yB{hp>iBFBRBFcU;-YtHpa&lB3P%RaV-u0PJxiB7BJEkTKztQuty z9opUTtrq(3S(6KP(r=&#JxfJ&Z&B$-@1VY;Tdo&AZ(8-$^tI>D@rxPO#5DbwHm2lq zoCVRC$zKg-_odsVd+^QM)(m(cr1nWS*9|-69$T>!kQv_iDk@{Xlo<-gqX(N~p#dkiDEbMKCO&9tw?lllxx zVHr61=!Uuj+k~uRQQmPu_wAL{8$TUrd&WcM!1vB2{%%kJ39EdBhF^}i6d1JR%4ilE z+=945O#vPV>}10{7RBHl+Q(=^qaO`&iU<8r+*rt9&ez;$a3=UvEUbpL{~n&L+iAm& zmZZK--mNQu-`!tpStuw++X=vhIw48+q>t6l3!F~?KwRtlb=C4HBUg0`E}yH9CLb5c z8O?2?oU+faWxO}|^bRs-4-!dPL2}ba)b=P1dHO1XJoIR=_h(M=(kkEr>+3}S^c5Qe zkz^T8WbhKru1xoPJ|XPqR2<-$6ID^h?`1Bfwr&o0(=>{`dX z0G%udOppmEe-`XK>$Y=C2Xn)54=|p3+C@3y-Vh)?r+L)T>Xn_WETu&ip19#{=uH$s zysf0?y$eHNk~BMrj~(E-uObuLy}$&&xuj;nO@jS#k4~u}p`}=O#7I3AwxUEY&z6Za z)l}sI05dPG7V-W(%{$YEY6e_(|Aix}gKKIOqq0P%g+^KMD1`%XzfJTfzSDPo4dOqM zEjAN&mu=<*epoSkTIzLiovDn(3)8odDA_+oACo{DD#D9P)0+*X=9bzgB$XDNS=Wdj zmxvHig1vt15m&p1_0H#ODOOwvYZhg}i29-u%u<5$2~M|+-Mnjj0H1G;LpxxQ70-NJ z|H1d)8+kyuJ7C7%xduVnVSp=HwlXjFk<_R9;%!)0bl-M5t@@>HQp)VnS6BAB4*}nez30Uy-}iU%k%-9CEDqsHL34HV}DH z_yzq-+HABUblSk+2H93eGd@01Ym=kS8!w4~ zx@*s)zo(xEB8k%{q~a3a&!AHr0NdkA(uI~J!Ylw}YKaRiM*!3ty@i4t+~iC*){MU+ zL~q$_mIFn9^)9{gFT5kMO%v$)fa*Gmvk)HSh#Cu7l!h6i9H4zaOZGB-1IH86i@JHO zQ&$Ro7f1oAHu%S-lQtCm;F^rp7`?ZV{(!v=6gbQuD@1Xw;alMff|>VuCS^rzfv zuaW!mX+c07i8Z&$cd|~qn{RF-m8T-d`DFOjdp9dbgmi{rp-Sz6SsphniO4hdsAclnr+pBRn>noz;)qm&Wf(DN=~dh5~&pf;sO13;o|bPTqk405sDwo;7Gr2##{K*>(+XxRl9s5L>ZVR{o$}FZ?O%F$Iz6%$J0D^ zY=e=q=^=uJcebWw4C>D)11erW|Emk#ibbpkw&M$Oj;5w+FZ&nmyfQzR3H6u$o8_ zX`rEJtCIlsqqaqPovahT={_n|7I-_f3AbpcyJ?3d+wRK#@S0ZI{Py1aQ%*9-P@DP) zgBgV^g0>yZ%!VsZF8xsqtoO|{w)l0Bc-)n!lU%>%Swy8cutC7-O7`SM#gJ!(^)9|J~wvk2fvG*q$;Jfl@pn+?bXSgznVmk7Slw$4c;g4 zDqwn2r@I|8oDqs`bVopws;sas1a46>^NeYO<4zISdg?%rwbR!{K8O0WUNBPePf2kw z?R=>5fw`)vjc-r%CNG%K`c^V4sk3Aj}bI|h+@QA~m z{CI-jiGJH0J(tBTt=fk&yX^a8w&L44YVGmpx+OX$40V&o8ftP{*V!%?L=PJ)4%uDQ z3;5*$pSGYq&PSN!G7LnfICK72AJKqHFKmNGDgyRI3#_a2&KMN@V`$6pke^za6`Cl)O*I#;u zp(uOX4n(8{51Sxq90J*j3dy(ZCI2!>rz&)Q<$%)PH7(C`@AjHU567bh_s2|S6aj0R zj;4+y6oH<0=T(%|-sS_O9WBv&qrBwqU^N1%wk)Ug;gP41&L>$w!#bTDC#~$A-@KB* z#5{xJbZ`#@PsyX_Sf(DV%oAB*Zt#J$;%)$6Tn#3F=?ipeUZdOH2`<0}v=4|Us`B9$ z0qL_20bdKNNzYTKkMLCkj@wDb7NaU8$Rky0Os2g8^f(sxaSIp;j?qe@Uis(Kr2i}* zFRY{+FO<%|Gp26}rcUVzno$8`pRRsh%j<$C`a_oI#@BfA8HeUbvg&JM4c>~4E5+5k zm~8I?hdF&JqSBT35+9kWTF(b+={pvOt59)XAG9*<1)+&!z%w-K=BEdn(Pd*rl2zlr zRz(#@#d%2s7yC{6L!2hc#7eIwYOkB(tMD7*gG`q~l%{^fj^sp*1lP$P@ z3~bAoPxiLBwAZ@d*={)10KO$_V4Nv&d=wb!Hi9+TGd2?9H;YDw9O7v(t_)+vf>~U4 zz-q1uBHifCw|x3S?AY9Md(_XWBB*`k6$2+uoB@j{v27&rbfx6y|98n>Wx-Ba^N^OJ zXfHWM^{!@XFqW}Y{Ua)q?|`p;zfrc~W9$p_JzOJqtciq`lfp=x zs=qC~%@k4eeEhXt=W2$$LDbfilN6<2pl?AlE!JhUM!KBsAws={RY-+C_(o@#{JL?l z5VuYSyOAR2P;JSrHOSzeA0shVBCmVrmKkoH*zk(uv=IEGLAOYIUPt6MSQRbMAXuw= zpPMI)@2dIy5PXdvu;f|jzWo%EOsXV#H(U3(q zrXG007h4>-ej|E(H*NFejjTntDs(8_^8&w8pEhJ>vJgo5NAv^;JGrh@Faw9Mk<81C z=h{)67m1;{$cB#H^BtySu%a5Ly+3^J)rvoqsaZq&_l)UTRmovyNX&F#xCx>kuh#qq zaa?Hl+2;_RjK!F3E&YZS4`BA_={;4r3O$-lFd+Yrt#FGc9kxo7|C+Kf*IcZ3~G%jA0y{NY>5ccOggzbs!@s2Oi(a|aG+9^4^Q!&z|#i(z6>4( zTOJSHS*t-*HcdL7Y^k~{Wjvd)nsb&VtU%GR>$SA{q_{8KJnPLjN9RN{(^@{HGhyFu zp3d497o+AZn2wGl{fv87`!iSn3xr=2CA*-!u-b@Eh@1&!H;yEtSn6|~=-j7AYsVWW zW3v1kcb%u)(Iro+XGMR&+DoFQ`9y zCp5&^b6z7JKioIfo{G!ICrl!g9qPx4iy8j>X}c?;z?$Mjob5tAt8emuMx8~LjYRwg zB6ab6XK0kjp%`QWIBxI23LKBLV`JE;iNVE|jaO59RZPwFTm6)OAHqx^i^H2U?gHx1 zlxHkLzfFO)^LM?FM_Zv;(L-2GtoNDb$GWSSOI8ikyj40^8?TA!;12|>_L;p0B z{n)GXOYPuxnAv4fi^D0_Jg8mmkr@d27meR&mn>-ZfR_5v9DrQ8G_lfGtTs%uzf@lU zk=S>(J>8F@FNffabm}#yR6>nTqiujramy{iQXl?(r4xPmS@nF?W?|O7ekIU)+tHRJ z@O_|C-J5Y#6Y*5Ph@q`@a}m6<0}Rh*Z33@Mdm5*q>RB$NbR_@oPVSCcMNeO{{;f(D zPuyBL))RuhXe46uwvOrIm3pp$_P(*wG@P7e{VtoM%V+GPJEc}kyCTwr)4XK@oZQ9& zeL^CK67+nBE|#m4X3_h+g*kZ)qqqCKBi39)g=}~M$zB4DTp(pAHU4|)w2miC)L9t! zZu{-bZGewx5vjbZhfcK@ugXh>8NMdRVP=a9kht^O6DAg4Q7a4F5tNMj>V%0&mKTPN zbdIW?2p+q$!28A^TV`pkZ?12bO?7POZuvg(tv z@kcc=EF>N&(+grBeA??*fTuCVZSCJpbn4VylC=7m$jBJ%{km2bG1~pF z`j6=Fc|Y%a8VQ(BV;^m{6Ga&nU*G;F4Mj)^>Q1~#%$ZUw%)+~4ng;60OGe0-aLja% zpz#+Eco)+kS}dMh^Al>#B+N`A?UxhT0?{ zHT&$0@a27Me4GW(zIQCtzVU?ix$>jRIr?O3gJNP@q_SL%FhqTS;P6ZbQF!Pr2Ite8 zEz&Zce|y1EK6hof@E-!c0)9xsjfpK+>5XAAz@8Hw(z1?I+ZHKHbavvav=BXe!w2IQ z1%4jsa}g4{UI^>=I|5zP21`8QMmOSTlpv*c@>ju+Z4>CEhuX6T;G55FK@(zH>E!v; zl;HC#gmD|7ZuP5SgQh9fJYDrgfvouU@2k!z-Ox+a@OWp0o1BX-Urelrt&X;}XUsj} zHzWr^>8pB=mWF8?lNyl=sLDYG68_*l<3-6pXVvfRnfXUhW|F8zCJ??GJyOjL^e3?jP@RDCv81khj$vJG+^Yaq}y8^Z_Nw z152nfxvCqVBNX!*{K0DFz&gz`PkN?R*hU=Z%`NHw?Ypw00Nmy z0BzCdHo`r41PQ1su($rE_7UdMLqBc~CshTT0Idtz9D#Eb8Dv5AdE#~1FGH%ZwTx(f z=Lsd>i`G-vdjE;4Di~19t(p>Kt^M(apbtOerCFJ!$Sa@MZqoXZWP$OGskZKL5y0S$ zRq`(*y4v7RnyoG?{~hU!O6kT1=;$P|3R`t6hgr2pme$^g*0}{sqOKHBxl%FW!{&c} zNN@V4nNagP{cj&r?bB%KF&ZlGOX;A^B8vK}r5hbVM3%$IRkNy5a>FB4QqWAjOTcGH@ z@;A>?`7u#xWOJ*qWy)~;V*AbD4}WM3(C#h3XE3I{k5ZHixxfIXO{e6t z8y*WS9nw+_=UK>ssWgnFLCI2wUviHx^UwB)P6>WJSh{eLcq_kKsX0a&3PM2}vi#F# zw#o-+duezq8U}4+7K7%OtJ^%}+^qf~HoMj|*Wj(epGfosY~p8=zRGAl3_iS7;9}MUi2xC1>q-!iy_UhU1=>pc?~0#cu=3u&H^8xmB+9O@1^o zkqlAf4~u{Gce~@(dB9HDDr=pOOtnHUwmIe^bhsbqRTpWUyFDD}?)qJk%%ZCpx6iTwB{|f*+(BV)4kEL* zLk+rjM#>ntoTD(%4d-fu9Uq<;<1Pzs(&Izz{wj;4yxufw*$jG@6S`Lmzajn{@TaDT zNZgAc?tpGA7c9^pX>HISn8j6t#N7wnYeZ6$mi|*D0f4adLV7!L17dp<`H_sA+u&Fi z6>}3nx2~0zfD`Z1V-}%S5lf|Z9ZEB;dBktv>kbJj5^!F4pYCH0 z1CONghyeFZRsqV{zcAq*ywhEi%C1?ZH}X?uv<8OG9HF3DefnjD0$20xR@+Zba#)bt zf+bc%jqEDjoClHx^#D zr~Y6fCtx^Z4C=s2|J-uJw$07Bg+ZhZi3=_np6E{9m(Td38)$Ykw>?Eo86ObsFWzDU zY-#N0uD%DI4?64IZ?YxyyOHrhQvw4Z+(gj-?dSU!0E+Pmx~D1ddpFWAv;0tflJX zoO2I~?N^gv{VzVFZd#;l6smhl78^<3MrK)tS&G@Y?v}`@**mx19tQ~JILLlcyN!2` zMK!VjLztDu;Rx@M_5>T(g6Gg;>-~f0b(r>Wr-8x?TJZiDA%k~8)zrkWo01XXBx_mY zw+TQu4_<6gFtY(R_D?6+ zQv?El`(1=);YX{S?QvGnAVGMDJ$>$t6%|hImS?<3#2rjXw%?-+-CZp`PlMIJ1~H?k zDUQzKa>J~y8W=KMRI@DtgcKSzZ{koo*liox3ahfnx-ym`@E}09r{fe6ZW+BeXC4?C zTj2mfg~1Oj3P(mQyNPu(!A|wNl%+NMX(jYeel!GJ^!v{UXMJw0a6L82izYA=lWxWi zmKH~II#*7~;azc0)0d_3rR{&OL$)u?SD$$sw9{k~y}41u>Y&;L3EQJ<|J4#lvN6-HRHQ`xhxcvl4RTOYGvNw^@17(e( zms1_J-dv5l=R-`_WrT!{fCR8of58|Tw(P;V6M6ybLn;ut>|$A1KpVT{>+1}uB>RNO zRVW4{87s+YTrza(lIQvs%`zDpJT*zvBKVOM0T*TE6s8VU#)5uPjc!V%-K$EH{%489H% z#JKJ&{zd^a^{$q29U~K<7DEsF>1J&l@pMCN$0SEu2#bwHpadVr}X!GM%su&D2m(j4GGE1tJn&482UJZ z#xgNiKt~rYUd(%-ohB-1wx4qU8@qv5+ZI2)yf_=#O&GI`zCEm)WObUchIvqgj7s21 z``?nH&gV3mWI_$kQJw@3>-|i|&CZ|z13b2tds9=eu25D1giOyAlH8D;l9&}#B3(Y| zjuLu&_w4yr0~JB_Gk(U+fyMK(?G3MT%g3V$za+>tDtTG&jrff)STZ-zx5EX4EIkX9+y1I-*iPQe?oB#OiP^h^sopQxjGF zPpD60Iv=Nm+Aoco1uy<6xrRTsZ(J7{cZ zLKjpb$ODPHPMocbg1GwVXaziHp=C4`ZMvN9Z_M%9lvdWnwJS}A!3XaJ$cmAiZ&crD zoaz-B;*A1=9yxq_Lj1Qljj zgwOAdDo!k9GbZLZKc+^Uf8y#nQkSDeZg zd*v-O`J%)E42InAQR1}Jd*f)rF!=1mSn8#;#cBDJo>eC(hlI(1FPq)=#V3wpQo8MvK zgP6kUb}SlI$9V)B$p`t=OC>|E9R00XQiF8mtG)JFugD4^+l;=`)ABo0S&b$=$BtKmi}be7MWwZp3~#7MAm-JU+9>=s~y#r>tW)V9!VL*W{LxI2G|LFjS0 z`?EK}VJ-To+T}}nT@~u3<>Ue#8XMWpJ$5@gs%1ttrlsv9hJ@l-FNOs08q`gf`w~kG zDCxVlO1u)UBnpu;W$Y+;q3g<83iQB!X*EUCzQ4l5$y;Z?nH{ELjQ!;Wq-ft+Z48FU z?9Q;aSg@t2>!$_+LM(@fWds&NsJv0*LyHQ-3+K1no>So|oLK@S$%V*h(bAs*UOZju z)7lyWNf4UNh9^G9V&b3KVvVSN%4*UWvd=!(h4w1KtIfu+kNiu$&_Qv$R)%`2Ob8Fo zO-1>F@56k$xV>4bc2w{-3ACI!6U82EX%C^zk?0Yos8I;2meLdk{m?1mUqo2BU18x$ ze+@vDr|uzrbzT{xKo&0naGB2TIpF7l1-yXi-PN~HAVUiG@$jO}InlKcotUA7GbK$} z^1ED32h3f8d6z}zqtdlU&F4^Mmzoels1nQ*e1+BZmG;7%KpTy*g9vSx$THy5yWK4F zPWg&i#8ZT@pQj5Oj{Qa1aY^4joGzcWHe9azlmgFLwny>4C; zUibo(+F{V==VQ=ka|5vU6D$xY4Gtc9 za^uGt$XGMtV!724Pt**vvcg4SE z3kVEcOiv;f=yg7B85VwN76qduS$_TaQZI2ol*K`NTB(VIAn264QO2c_DLhSKVLwMY zJMXro?_z+vKiFR^Tv;A4SyPJh*DeHhF(`)c?bCcCAE_p_F)@RrturK;wY|Cn$-a&Q zT-SSLBjZd1a?8Ysv@uBq8iR!k0%0_|11nlZa;mGZYr8kLmc0U*^D8!cSS){w_XcKbfDE*MBD*~x(rckE8Fj=TxD z1=^G)=sBA@uQaPuZe5-Jb}6?)tkO_J`su!pnpr9*w$7ywu7>J)Kd)^LFEFh4ywC{2 z?LAR6{$o3e0hi$Csb|2*19%WrCh~LO2VkIHA#@wa8Abq1;4t2!TmfNPZ8iIg)=u!= zxkSlEikw99qsPS@nDp|?ek%={t)NFq+`X1x<|qr=Z8IyJTwJ!=o}C!UC)z3^TOEQd zw3}4eP-*;;R*O7jK%rz_J6DDQV@JA|M(t< zGWg+he$FDAszOi6_@bae#$2%h{t#BON*-|MO9 z(jjx{qu?tz(7VQRtW^Z)iUkBw)inU0^)SYnCQdt^s`rN0==YW*>R%mA68`Ds&i1?J zJ7fjGsO~b6^aVy45kcfcU%&t_7&CP_pBMb`r}ZMLZC}bd=&3Tq6vg&}(K^Aq;cYmo z@Z74v)DUg7qA6Y2BdRw_jtd5Y&w+orFSyqa+SX+W^9HR4x;I=siJ)M zn=DxKZiMnuKMkvTrrbFYuzhY3N^JqT0nU1L?klu4&S;8IhxP1H2XL1($b?|(225&} zemb0e+jh%gw8?qX@k2_tY{Mh9wH4Al$bX&pOpj`dU(|-sZKb;EjW}cB-PM_Hb6-1n z?c~4W4+>dKh;!4~E z@6zR66zQp{MCGpC=LyhG7e8+^FO7U-fAm>x0gOsXwaTIXeTGQr5P0(rzQd4BJ&yN~ zJ`NjUMZ0)G-ISTI#we?x*gF`kL$)O~+9Xc-78*FCEPC*kgk67SRsyYHAue&D3fLTT z==ZIwASU(u@SzY4uyn*q6{kb3dj^_AgxINURexh=lvP5x^pcE;4rvhABwil5gM<`nq;DYw z`s2|plWoGy^F9QQuuh*5q$e{2-`pEbXf4!sv)dItsfDl{bbukGa=PM8zr$*(M7m}_ z7{+^91W-b;A-PZnM!?Kx4hV!F{aV9z_I&sN*B<<89g({;En|r0WbX2nA2ZfIfh(14 z4{4DfjYg9nEud+2X<@$`PqgkI!D(vs^6WV+?PJ~eCBFF(=$f+>pBVQCJ}aVJBN7{@ z3=5MW7TTvmd@El{oZ?D9#P^-NayvxBzC;dA#Qvxi_}#AL<%>9iH0*qx4|i|jCjF;2 z05Cou`jdFWPR8Dhlgc#71AuJUA{+u-eN|9h!4mB`xH|-Q2=4Cg9^47;5Zn*$?(Qyu z;O_1kg1fsrk9%*udR1?K?vJV7t9!b-XLhe8+DXx^#(*&me}N&amvMzGV@y*n914V*&bN;)F}pTm&NYYa~YA zjuL0L$usR9hZq04IJFK&mTB0u93|dl~w@f7Ucc_z9Kux~eSNl~Pz0L`xLG zG#3=PPp$o4mWKKuI3%(S@JcqCp61Tv=)*B~Pg$0)d9Mx?k?~-%zwX zvs6XlE@ih#=8b%b$WM#g#Kw2Qc38RW7PxPD#Pjg2i07>cywAIen(nZw=p={T#meBa zShuHh)em^aG!GTyZg5<^*V8>k3gno(Ndnt=p;paRw5ILF6*jfA$ZHkOy}0T96rzHW zdvmP9(y^X+BBZRJAL~5JPA+`GsSin6x(%oEJ-*Z8zpoQM1|icptW3xA+T48Kf2%I4 z^YRPt*1Sk(R-i;TBDMH!FXa@8$6V#yD_2#0HCU&;_b%ah#rERA#)!m7ntLGpD_L4N zQto7`d89E}@k&bj(TVAV98t>1F&<0B*FG8iU!owIqlYG*%~{=w=T1<@x^xD1rYL`C zMS%@(tlW39V#SjuwRVP|em$i9cvqSR`uo!TD0nlEN9N3x4h(EQ&R`T zFDTQfRz3H>Nx^=- zRLgWFE>xr91vPYWd7aoVDO@rqI2naQb5K5(2DbBE@nUYV1FRA2+iD*ckuHf4$6)0&gAO{T%ifT^|#*I)%>Dd+Y;|_WMbw6{Lvn@9&F`lV3>kM(EPd^7i?*EmK=f zX*2M=?!{60X-`oH-FpT8}fNYQWW9o*!$tb{xm1ruO|3ao2QieuN!5 zb_F{dxox+$OK7$$JQ;{am0>$hgYlfxQMl4WAFvDCMEMd@cn22RnE1P5#*1`q69c+( zl)i6tVd3i6m$LB4H$HzgmqBRh9u8cZAw9m^F{$Rj0jLIDU&}!~u8}T9_LA z*t^(aSTMg4E{JtCJf54eV}sUAyznSL zLr6c#*zk<_b^rC%-PbFvvOQ>9&=p>IJF<~^&5?N_{n-Vj8qz-mgP7qwP_YrnriwGf zynh=@jES?54_FG9kbg4#o-j@{XT}6TL@vop=<1hVaw}7Sf^YpG&q@Ps8|icyWN{^@ z8&H4TqrL_TH;r~x*+$rR%5r#+uTTdE95MML5}5MuT(&b)fED`Tea2#>^|y9vE|ASIg5rgw8Z_n+6dpm!eLKk1ub;`1YK zeO+D{%INrK*h6x6h>5+le-{hZsluLCmxf-?4qD4ODDtCuWLgO$!lh)IxZj;I%`>+o z4L38!i43cVXY7MW(WjmVRq{YUG6)yls;T^}1)Lkr_C9kG0{_bUK-eDhI2Q4AjmoG}hDJ#Bg;!LQ z5h95EC(`@y(=R{Z6x%Z$X|bkJC+x83tNc;S^|!z0_JWwIJZ*$rkTzpi|JdH zEG5K5Y}CIKrs0?IOB%cmKd8SEHA16gh?(k=Gh_SqD^0sw4fAvkSzmFh`5J#s_%1xP z8?)*TxQL*HE^R~WTkf@aTRpF*+;-?DXAp(dhRs7lS`58WV!{Kh0*?v4lLRtmIO(5v zV7SnF7=XN&LoE)nw51PB+Rqq~q@?<@(4>l3;=;rH~b1tH&I#?5f+8 zDFXC%SBr7}^o4K|Us)7P)}0=wz~O&LEH8_~O^|gR)?3oE5`O=@e0CBEKkn|(SxG@F zp^ztzeBEY7Tk>AE*)?ayv-oW)Sk)nLr@N}k)i8B71?a2*usP+Mq=|I!Og$lAk5;S0#m9^RMZj6n= zP~_NKvDoF!jqEneU+*EhtD>fVF02qHOAI5kI4!d+O2LD*EAO#+(d@kuW~xl!qDP}F zyD#oi*9J$0@VIH#xJ8|^DH?HzU5L;riru7;x7m8hsr)y@_W0S2YivA6k^jfHNLPdC zN|T>J_^NF#dNkoxh-1?wyiuGt_rHG>#SSW#>o#Y4S_ygb>5%?N8~>yoF@BqUqNGv& zj=;YSCF|ASR^zo?AQ3H0vp%n^u%>9!wLrgbA_mD7NArzaVq3^y{SLb4J5}zfu@X-% zFSMOmeSGfV8iAedPK0n=#LD%jC(kfFA4mqV*h?#(WpnX4FuoeO?HCscCXZ?6B%$X z#{?N_2T!p~F3R9$N6Jv$98bv3KG*u&RTdd|X#5gbyo`;=MN8lShaizB`rV2+Ztc<1 zUFrA7u@r|_TFY-B9NSHK)E47XxQBVT`+MgD1&`caW9?;uj!xQ8)-leBMH=^@!I*D< zv@$%r2m3JJbrIXHmj1~ElB}8># zsCX7zz90ifaFP)zlKlqz{25lhg;x;$UCna|4e*`;2z#Y~i}Q!gBd%Ee+e`&}+b>}V zx}beHq|wp}aI2?}LVLyoVPKQnMZCI#QXZB}(-N2@kB!((>Xmv9B4XIy($)iJ)TSG4>ZrJRg#uGvQ?rHj@22486B3diSaiZ zsI@2PrW4g$iX3^15BqC%~gh8P6SX73oZY~)AtIH=92m$9|S zk#Cho61l{EQH0Zr1>iG(N|#XlhV)E85jb1p#=SQKNR zqG;DDhNOP6#QUcqoiT{%l+J{`M7N%=LQy7P=3{EJdpbH1xvogG3Ov`D{DpFM;WXPMOq`P-47x(6T9J<1Y=xn@JELy>CNya5>9@F^`gBAqsr3Z@_+K%4YwQ( zqYOBmkuqta4Ba`!?=l_6$~bxhF?>VV3xlpsLTu_uLvxFMc$M!{`Sy9w)w<)K6V5qI zTKPOdrwkqxo+8jmLB6s-NcG3?cD^`814&*(4#_yKOF`gNb|~h@uH2ki^SA z?fRv1{y@4b^JJkRVS*vCkf+L8Y1Km^qbr+6>ekPL?6#eiw50!;ZT137?9q?jKXy

w-PaZ_unFdO=@kIsFQ z`!B)Jg%I^vBEVM2f=8NP%&F@Fo8cHD6~oMl!xbI=N&^uCcYJa@Nyq}6#OZYzn3Fb| zw;s;{Uw2ZW5XbkMyTHx{yr%72(^A~~icM=f`jn~RG4I~$w)h=y-6)+#J<-1lPSR=& zrYL43Le60+<7V=w*;2zMPf^QVA-8m2`xdt(X%>a?I)1u)5mBvjMK*pv*Mwgxf#K&DdS%swL%{5X{1GI(A2&q?>)}uchziRs# z`q?ie#>rrVqjNZ!3V5WWmOV|v>Yynq$#=y!MKtdmqcj7*`N&!M(a`_Lvoeq zqts+5`;=wC6~&YX;gZT^;RwGHjw7>J{E43!wihLJm#p1k{{Cy8`V;9}sKux`h){4` zMRN5Yi&B2leGFv6#jQ0y@d1Yn-z~qs6|txO4t;N2%8#-S zwl2&LsfaAr2?D3uxaMgn$z~pxYVb&=LUfCJqcpWL#$WWJ9V--{x3SJyoI&pFr z*wf9A=`J3uP18#felSTmV7VYkq&T&)4>;jc7RJ=k#7UED=Ih^O468lt=)WxHs~lt} zh*ft@6D_OdTa;K`$(G3t)knK5(w?1I2mmy1E(nqGY~@dE@+=)`zeD;vORC)QK|i_UT@5#v*GLIDP9CYX;kNICfy${%4jd#Wzg?9R|bm zOX(vjpMNSZ)^LX%g1MaOM>j{?jfj_CMTXLn;dcY(wpWEBp2i(|Iz9@NR>A|0j}|p`vvnKQbo5*3S9D6rwbL@VxwdPz6h!8TC>?p- zK;PA(;=%DQJhU*d_GoH-NGjxVxRlded8C`v$+?h+sF9H!7d};M*56Bremj~{P)T#= z+#~R-EbVlKESpA-f*ULp@Q_PT`NT5^H)n4SaZ1U&t>@9v&~wX6wjGZ4gkLk^HwZci ziMP5bjT7OL=YOd>LIHCd&a6ng0RUm$l7Vu0o%raORrxFcU<9z04jm^xa7FQht6k?3 zL?Tp@-$=SVuoBsPhYiDHP2~{Ggb@Hsij4Tfs7t%%52C-+-xLd?o@l4?D*ii-&cR|r z9X;lHoB*=AEm=w%x2&v)EpzfMnjdLmk15^)hPcH0{+LEfA0(wU#g;^DJeFt%MU*?~ zf6_GV!{q2qxB|f}l?1SVn17fltf~Aqk*G85D}>T{n5w*=Y|ydu>x^Ww**11bp(C!w z0IEBqLCJ+qU;7FLGS-Qo^@A$UYd=zWV@yXxnOrIk)UcIm383r*)-C5OG;I4APDHd) zgg3aVjVGj>7+tcEtqv@}nnbciLR14EuZF|tb&8~fPC1s;F{I{2FLNfZGqFgON!DtX zHH%5AIYoR0)ok``p7ih}3D!_OyM5*)rDo*c-SvnqQdNB>KpL)E-HK*_a60^@vVYY~ z(VgSr&l;vE<11R3`f)wN2giqXfmU{?E4bhQQxwbsFf_@kGLbbsr5M|SWVqP8a2`7) z<*y6W^}YKG_|uLW_r+h$A{$TXbn#oogWPLzVmOKPl`}T%XX4uIPFM~zfR@?iY)p0| zwXOL0yeXv3IhB7vQVldi-K7Gj)VnhXdl-0Gje8df1XX=-aQEh~b2{7SOZD4)8mP7z zHid*Y1i?IT7R0izNMHr#HX{7rNGOvK7zkNWAWm}!fG@*yWuOU1!I!6!j<3{7gjSeB zbE39RmO>(bxAF47)BKSaZSrwFChV0R6)yQrg1-tjTJGxNr%QuOSp9s z>1}6xhezEqTR=&Ccke zR-DWn1XIrYhB*dEhT^7z9O>`=nss)70NJQ|yb{Swg@K9Za8rEiJyJqFNMTNwNUamj z`z|OoggkUNw%8z6v^ z@K@N#e1#3&f5V0^!hASqBb( z;wQyo_qwv`{I#kp(uhI+(E^{8`Fk!=TQQzMJ9nR^d|%-HzXGyAq1TuW_~O-$xcmop z+#d04ld09mEV*6+%AvkyH?f4gUB!ioU#d1fsd@X7uA+|4p?7^?yel>jb8C=z%0WD8 z-T+PA2zT?uAPz<2La3g}#F9LvkhLXI^Npa*5EO^k>CLWq*N27cPRXe8CL!Bs=M%#! zVZ#Y?*wDNI019JzON&BjaXTLodoE!5T#3kDx(+{~@$FPRq>8py3vo)QCY4Ca@?bBp#AnhGV90n?xmAy_YAbo%FG@nyDreXJk@yGn&ud|#==$u5aR8e9;eR=VamgS5BKf>SdDpFw zG>TC{a@-v@ys>@BD#K`giAooKMU%~cg<-#wF3TI5gJ>$oFIclZL(#FE zy2-(#CM0wY&K9WW^lx^jE;7-ZKK?YTlo2~6|kr5kwuYEhtY z-F>qwMdF0Ej6yu!)Kux+m{;KEVg)P}z)*Xy5t`sJJFuL;weVEnLS`3KDsXJ?IUJ+vRedggH;>^o5iW!Oqj|I{tu1 zRx7JbEK<<~3a*mL-7P;uIEbkS3cNdk5rRW?$(aE-^rUiYEu35Xof=a%rZP z!;v1SAJl8)gTFj-QZ`aH+h7Yud3BX-Db}f*-K{vpUof@5g zM$Q&}#?{&&&m?Y=2%-==%|J$X&C_x=W#KVuxvkhGVFhen!B#o@$;3S95N`wG-P3X`41c@08=LVA#U{@ zkA(iG;n%_IP_zE(o~|-Nn3-tF6C^PcG}zdLDI@~Jzod+f8wAyXWNxCDGl&(pOsa+` zqS4#7E8{>nUO;E0(BLtnD5#aK*4QfypJ-%6X1{ucoh1Y`J&gN9mq=4-TAM1#MA=q! zM(Y!c0>Z}H$F#7(+X1p)Dm~@qXpPX?b}rZsZcLa@&(HH5g&qoRKlm4RMC3&%f1Ro; z3cm(xfZU09wr<6G&T;YnS55hqr(S`!DY%CUrd&0bT)Wyi~Yk61@`Fr`h`Q?ZEq0|0XzxUA!qO$ib^csqvQtrnu|KX=PEuOw`AWb8D(pI=du#r7)-8^xK>B5sK5!+jihzh(uE;U%$FS4ix4BE*e7NC0KfO8iwi~xNPgRJW3AZB3RjpfX_!|v0HFGnSb#BKpicZZTK|7g`QkuW=pyVA(?h+iudQaK4Y7P? zcXMLgcr~rR7!ub{gJz)P_fL4N*utX~1re*1=foO%sF<8uR<(@J{UEmKMbsV-U8r#;>VlvVj@&^W zXd4N_XTjgxh+H68X!ni#GB-u{ne0O*|Vhg8b6WFK7O7rJa4GC8V2kK z0$)9-v)FKJtA1FdBw3!=dSsU1)ufC9^RHf%NU1<-lvg$d^nANJ9tLuGmu)1O95Y9S zb$9kpal--lTzDAz&4=W*e#%|NMpZEKw{l;9fP}?X{;EGb08W!U@5>`z!kJC~)4%?Y z0QUdWzlO>1C+cNkxJ*-g97{;c?ddCN6yksv^YI{?rwjuT0}P#hP{BoiI^lcY0w`jI zu=wbPjwusIC;;>`?13h@AVv2pz!}k?RUKOzmy=S>d&n-nxS>@^{8u!9 z1L_95g2!|rIhx>6;11GHPSI_q0MHT=Fi(+fBR~o+u%7MI7k7^C=nr|{wC_OX4Y5E_ z3jjE3(~Apr1qj>aoR$YTN)VH->L*f|3Yj8$#gLG~%re_h?pDu!cR2Ib5tOmR(=I66 zn^nfSaT?p=1EheJ>U&$Hlab(wfdGJ1$&_d`-PVUI2InDJsGrsu!tZZ7@s@LXDPvb! zG@rY|blm_E+nL6I^De-loc6asfk+UFwle@gD_93YC-e%Uq;g+ge+7YyE#{x`Bto_= z#eA)L>D4|s{s{t}^ZM!CMN`^CKv0KsIa--r-O3W??W-@su%Q5;mU{pw*IzZ8h;VL~ z&Hv@Hpbr$0lFzQotAO56{>MHZC3ah;uLX<)%JyR|GVcfRdJSppO|9ta>L@oNB(Z;o z0$pVO9dk1Y0|X3w$Mys_xe3m_28>3@7X%OoP9C8uOQ*kX@%_f#t*=`Ug`^PTi9{Qe zFaI0_9%v=S=w2V6V$U+}nXXn4q?->GWa4Q5KyHVbP6$KD^E~2A$t;X?zX_@I&ALvV zZ;Iu2Uht;DI%5r9T|-~uMW6xOHzM5;^$F=2siGRWoj7>*AGA|=rLvV(dHM4`FD%!A zsFwkcGmn)A~bGwNM6o8g^{3r2(Ofj2v#TOp{u0C2M z&`W);Uovw(Gy3rp@vgB4iEhp$s~EV!Ol2^Av7Y4GRoOaHxi_LTfjDEUA%`C?mWRaH zs9p!E*cIqS3J~DBvF_Hcg%~~J$p368YBRO>o3M*;!7|}8pXc(f(el*5#uUfQCL7Wh zA>vB)+NScEA>n^>B~kY1q9t&HV$N+-kRY>VKIvD~$o(0Cl{T6FIj~M3o)*jLB1Tz4 zhYk$JLuT}WN@Mo zKUsS6WV{?g?f+aCWlPne;OME(=+`=amR$p5&(E9))|i!st_GJ&NRkQ(ps=Oxkn@!s z`hj~9cmf0vK>bS(tr^jHt**ske6S$MIhM%xpG0bmv*_igB0}yiqW|4!H9WoyDX{gm ziRFR0L;q_S8KcY8%PfCF*!Hgk?SDYq0ld!Rcy=N0_@EnrPtzb~gsmJEFhG=4^MLIQ zz&j_crQHR^ZJbRE1kWpz2u|zatC3|u{_yo1AZ4it7k^BrRhX?+ZxRXb(*TAC6MO5n zQa*(g06vXK<#B655+&Dt=-IbpCk`DP0CyPFxEBE4S)XhLdxb_axI0v^)B~Wo_?vAh z6a{ko^RvJ%4!DUy`|R7Iyl8vz<|?xBYrNNVD9(Y^ph3FO9f4@Hml_wflbZs9TU8*H zq9><5b04ByVoZ~xP=aKM$G0-pXza~2yQs}F6TeS4Mv5f1=GSGeW|0#m_5i&EXT$sR>S7HR;qqzdJG=mk9HFF;Yh0R3MpMV2Qf?tn--dv-b66nGZ2W_5N-?1bphX5p-tk**JpM%pf74_5RERxLT46 z=n(*5Sz<~#nOI8&9D?4uXY2sC(zMy)2?Aqg(VNCg-#DJ0OIag78s_{O_qS# zasZJ8ECk?m?EYsFS$_sF*ef6;*o?FPyuUky{rky#2tY!}eFXqy^;O9e%*<=Wsun^v zt-oe&<$TIRq~iqp2~X<3@stq0G9J#d%*#MvH-K%3PZ~ob~NC!8UPsbpZ8$DYl<~7CwqCH7E)94P*019dw7HZ zy#TZx6a(I2D#A$;a3r7}02P%U*vAEMY=ES`0{4dM4BTVd0uL5qTaVC0?E?Y06E_ne z%WNx*0Ro>n!L{jNa**M4$AuwJ=-R?ihrwQe4gd_TqfucJ-WE@i2+~y^fMom2%&{*s z|5s~*1NJbKf90>-gZ^U_c%2aZHVc5B7~o3C0U#u1172(@=VAA_n4w^L&m53mp$dO0 z3C9j{1;r;zSy2^oqu73f0ztt5MF2FiFeQr!VQ@7^U~|Nm0YU#+j-D<^4nPC~KWmW( z!0)I*<()jOF_|O&zMB)``u3}&!J$E*l=Fv4o;?Ad`1rM_OguGzCTewt2S};_1H;iR z=*O}$ifxUIApr{25=$-7854}Sisa9@(dM8ZcVZOE0ssK!*X9AdetpgViaaI~;h8~F zY0V=39*70NFKs5mTJU>V0L47B(jDx>SZEo5t<_mLO#nt}Q&zI}+@*{QgA_bKer;-M zqO`YCW(0>T2=?#winuo`gaAZLa^iGdU#J&dr zk|J3g&^k$R0Wecr#Lzzn?r>)KB`g}C%JzMlTWe*J(LCFcvB6`L8Ty#yEvh3Xcy73l zH$>qNLVUpTUWbw+zBqajEAzkEcUfdT3u3@2RVSzW_L}BQa$~nJ6xe{<{*p!bcSQ(( zuJF)<&QEIf1WGmpJ2mF z5q_TdvF{F1&=NV60wcYzD-_FsTtRuWHxc>zv-M*Iivx((fay6`2NL>uKSTfPQV-eB zuI2}R_Ibi$3hgQ|iDf6V#VZ6%iOm*pi3w1f$}HoHIV45MJm7O(Mm zI|+3~{V^;cC+ZI^YL@Kz4R?|bBK4Hy5Wy$bn0#}W8}EJVe8I#kR9Z4cEo!0V-m&hSHx|fxD4pl56 zNmVAeD4GfRGScmP{71>+Vc=%OdaVP8k0E5*f!>LyR3u{S=@T_v$4O2{w*c5sUpI_}s0aC#p0B&m4!aPkzZ{C11)*Z&sJ(EY12Y#RbR^=64jo+r2Gmz-d z=ofXx&&HXF#3ufOU0nk|k}_CIgQ|%2{vuP2Dj>}IR{b}XaVT4@Z{I86iE`m5?45a= zzpA2Z5NfG>)g7aa1w6S((%m012LjvJ@42pd9-*>&F+ZCKk?43Y^tRuls4SI`OlMz$ zVmk9+3?Mi(IU<0w!7UHdMf~nHprY3LQe3zUZ?90>pCgb}a&W4zL*?!ka5sk8$**bJ zz6fv?%Q03!#e-_;>jjrQ(2O}<#?l!R!U_V#s;;j=zu z*6$x zr$#X|%7H|`TR;&>k`)0tIy+jDf9`hJtTU+)u@zemGj$*0O+0a%_nFsH4k5FvpKm1W zy1f{Hy=?8p`3c?U<$*tK-XTeeA{vkc5X;s8lx4=+H}TIlR`yNNIkWz*%id8f3fC@= zQNWrCrk&9pu?gsEkcO%qm~@j1mYHp8p%+23Gw-XBfvyjM503zDnirWNFia2OAKNMG z8`OyI(@lCH=`^MB=7*OP(E~j@Y2=|G+wd ze=XL~#8KLU@3RXqd$!cc;K3YY#Wz~xsm*yqACmt9sD_{{{Cc-!Pui|GT86qm`_OQf z#*4BTxYKZ|x8n#{&xH3^FoATN$>7G!1{8Wf=CNR%^^OU^?0HMCd;S=Vj?$9S+ty79 ze zMSNzH89qCuIaer{VCdKtp+b9$IoI|V9=(k=?O3GE`&Gbb{uY6kCR3eQVVE{`x&b5Z z{ri@9k3NEhH62`4-bIWJT5kyk^VopaZP4dO!BpW|!UD%wV%kq9dia1)sD|a9OG*f^ zf1;TETbm;GW20P!v0dq(bupDBR@HQAJs~r}KRT|+x;JUODKO+c!T5*eFuxIB_%PT* z7?NN@Fxg2Ejjj(K-V?tqJQF=e>s{({9>BFdiP_}J&fyQ#W0YhFZUWp(+s27|X~R1z z8(T9gFpR6#?wcK#pI}4+V5Vu$NX0-N>E7jVc)O0$;0LYYc`u9_BHqCX-^yhPR)}NF zD1N|#eUN#DMG31n?5dL^=hFVg6;-k5J0^F?91NWYa>@Gr(E2oR`XJToJhmmIoVK^;9OwHAhX*lK#2-`f||Z{qtfaZ|_{tv;9# zYUxD%m_BG&^##+sYBT*1);2M{ROoVBx0C}q#nMn99T%NU69_c5(MMwP8aK>?IC4W0`X&H?Wehj z{B~mW#QfQJ&qdq*In{pxx1>g846C+cDowp)D z-<&TjNBu*f_TA?B1g#bqX@v?HH(hzVPI#Wpag8|Sqx$+k{I4aVmtLM;C< zj7kBc^pY?T$EKf3>1Aaqyi$w`=zj&o{kS_i%Tz^K|*Ifct6pivze(K`7d^3 zPW9pHzGJhD+4tTfl9PB?$R0>y(oQ9UKXJR#cs-7YY+1x z9o6{479tyK<-v`n#;hrA?~3Op1Rx@JaX_ZVq)y0v&sYhSnF`=$aKk}|#vyaMYRJKy z=w-`hOx{V-E6-TdlW!le;3H)M8?3sDb^POq?#QBqTQxm^78M8usPh-@9Di^17QAa+ zj?`#h{bv>R@6+0|r!(1bj26b9i{}SWBeX*zHEIt!O+5ONe_X&q4vrc8-vwaj@GW1S+A zyeUSNQ?qnD`6aU;#deq%xu&r5JhJ9d-e9?*{-+Ok?JC!LE`j8~u=Y_kIGbDHdN@mI z=-rC;K9@%iBWVqv?G&M-C(mz2M3@`W3609S5GYX7} z=4~P1o=T5IFdQc;9;fZu^@zNICj!A8Bj&!QiEjZjGFKSKba$@pX5?&nT~6|p__!a#ppBN}Mcf7Xios3=yE%$;weN*U3 zZiS_^!eLrNW`ObOyZ-A{=%zV(*2A-Ol5Rhn$7ckdaRz^mmx^Xk4OabhvQMm#g&vSX z+xK!5Rn52ZNnw8{aR*}}QpKGSO#IPyxxESbdd?0#q26TDH2Gdu-l6%Vge@HghSbaP zcYfcBotpMcPd6^S+bVE7wU|*zgLro9Y-`&7l@0c>%ffF`=7i3oW4N;ub23gO=EIA*h-=`$k0XV{ z;9lstA4upsX)z#)YVJ^PV6uv%|7)-!k}fo>hZLlb>y{6we=141aY>rNV1In`U0AJFh%wlL%k#w| z4XDAT63Mo?evrrB7IHeak>~V~q5b#037lc|Mjl_~IBM$b+p`iuX-N;DBHDa*AVG2+ zuR7;l+S#wg1a`OB3!X?nb~7CADL)sK7N((R&+(q6oUY<}3bGW#Q_x2yEj#5y7*PMs zQFrMsSqC6~mexymI+UBiDtDUknufOHV~Q$0xkB0!X=~d`$)sZ4ZGdhA4Y)=g_VJfS zDG~($>Bg?BygJT^m$P-$OI)tzk{f&0$S-HOoXF)2w|Y`l;0W1;zz2l5g;6Pni6a@@ z{e&hhmZ}aTN{O;)+Us|8+R{jN-l(S{#iBEcr{&bl{n1m^BH__`uvfPC{ZkMJV+5gb z1q(t-APPT1-W4Dlo97r(psmS$^pfShu|gJG=${z4cfGGUo%#JIQd4o&WFs+&MGE`Z zNba784x5#OshkO-q|hjn3KYvbr|Mo_-5XR^^|XT@-0CWsC$Bl=8F`D*F#dw6`!5Id zwen@!Enwg)E*V8Zn{b&?+A)@8WxRE06%9VjOuh*2S>zGwWAu^ zg~ZA)*T27Z`_8%%zQ6M#X>-S+IFzYqGXzo?yxv%~ExDd0?^hD4kgZ=AOBhX zyUOOQh#@g2Q6ASk7cjjf3}pzGc!uSxX~nNV{h{(0NRF{VWaFzm%XQo)4(aE@RKGF^ z)sB+elD%d=)|W(t<`hIkfVx`@`PaprE^+OQ!_vu$p8i5CKTW=#*S5&mOH^QC8K(0& zq5BFH;T%gB-$h3~WnugBFaF{U_Hp(l#se=qDKUlc`E?QrrZhTo3WHDt(H^Extq5ht ziL?x?=uc}bdtD@BAGMCtm60a)n1LjN=Jt1HHz&jA93^v8S18Q$I#f+xTO!Q@v}S|= zT0~SHof@@F-CrsG9WF9ENe-{x-<+uRLo8SQ?R0W)MCObSxEPD$7Ko@%<^!#fe(xSt zu=z~8se+i8#zsQhn<6r}o*(?sJkQb&Q&;*-TTpiwK zReaSndCN4fK!1?8meO4d2>Td|7$?R265xrR1X*K+|4L4kK=I0ru0E+QQK=bQj6&Se z9uSp4%%&x1@TTrC4=jx(c_sz-ZzHO@ z4M%ca$7dprNKmOJ@}bcEAnU|vqB2Wg7EbXK(y+OYXQnBzrQ0PzV>^oe$V$2x7P_f& zom|}xIqn$V0B5+IhwS|fH<(acFB+y_)eJ#4CR&k(_>f9eARnEOM%Q@h&y%<~KP0C@ zKtp0p495&dFzKdF$oj6I4ujq$)P88IB7S({^IO*nV+}8b$omxzQDSXWv>G1NftGMN zRPg9`im~W4G()89Jpk-N6ayWgWG6b?%P z6=f8`Gi7)J-+_L=Jh1`?UW<>~p5Ojejf1lms%pFx4PU%5^TQgpDi{&Nv$U0NfjA$9 z-aL?CixF1B-wwiOWn?c8wj&CB3Mw2+^HqQ7-P=QNnSwcCUC{}-RI1B=aCfI_ZL`e$ z?NQYsFR@P9EKq}BVYc=CJCDE)9^~lx%!OR|Su=&z(1&A*0&q49BC76z2+A_^e?-@l zQI#**-ml}6h4s56@b??_c}%#l#`@;on{7}~fQ_;9esno4+D>-=g0S22&+|n&Efx}j z<(gc*FB7}4Oi1LK?KbqeuQ#r6l%f(-h^??W&}{WFrq}3PrhX3>iGt?CWPr&_jO-CP zBUOB*XH`2F7gK(4psSB}Kdqcja0$4J%&nYQ9v0<$iS201aoGofHHN)2_5qXl6l2g9 z5F4l{*IkpA$JOHoi5XUJ8o%+<_shl^T-N;3%rDy!%4j(PN;Hp-OU$!vpCyPfmv#A~ zl-g#eomCEHK;F+a}Lv-P>k%AYOdy9Eh!h*vq~}D z=-u(-iyIS22Gj6z`#!{Yl+L4bwF9NbQnc`pv*uk;cW(Td+#1u$6JclK_hXZ^)^@gtT~ zM|@Nc^&|X;%NxR;X2piAQRqX-dX>Wwx9-;P%E_HxzWAw@Jt@VJy(`&ckW8i5V(K08 zyw8fnP2uK7=hRD_m)*9 zZ%L-jyd)c=z9R0(%sr`lDV8w@N@>=x^tGY(B-!PkP$XY7;d)x2${K;qTXgAT_c*H6 zd7GYh2E_}Q zF;p{&L*cx5Y90<>elF5~qy0`jzC^XUdW`_PT~ya`prFGAMl!$>YJCTUjI4@0NdXZ} zlQ{CoPw`(bHB9EAU+tikqU3rLh?BKHrOwXau!lie3#*138zx|$!<~i|HRRj50n(JY z8<*gew*RG?E4HZC5am9tLChS51%hmt6pYpkI`HUtcf4aqe0|k%i-t19zncRBOXEw6 zkA%i7dP6O*F@q;bGV9H#D|s}T*fIW1=lvf5YCx60eA6kD+%d`f5W8mp06ZL}`mg=Hpdv=qV{*SHAO3A-wAxw|;(nLU!y^=*h67TB35P`ff!8n~wlaIp|tiF3`lOJZEQe){&w*RdRA zus_SDG9N{)GFNz0R-qaXMWRG9Wq$?S17^FR%DT=-FOAIm%XTr5b9k|SmYVtoy%2*$Ey@M;i*!>kY1-R2q0xA-qyF@0SB%b>LLa!T0Wt3CUFO_ z;p=Qj#3^o;c|2zqI{bVZTiWd;k2d3LzXyt1)!Cu%HlBaKCusu?S;Wnnw9R)2zxg8P z0C!gk)zX!y!qOjr_BMw0PTSt5u|q>I;#vrh!0Nr?wmct0K=FgWE(g8}1hWdzY0gQ$ z`F0g#)5Mw%FtEPGo-aLAuFK?GALG1jusUIMNloXug-k5H12^JeYX0xr$gB*c0Nd1u zXF(?pWy>MNKQ_uwIIuUZW{r<3l{~}x>kf4m=ug2J!{+XH`#P72==)|o{!=>(aOI23 zsz*qnAzCft!~R7SZfh^N zOI*E$r7RgF*NW-1YiG%FsEP^ZG^{@zMsk*p^U#dXQo7vmX1HT`8HoxFVg z{u-Lw!)_z@>7{G^yX}8aFKVGVH^IXME~B9J2T0k&{qv#b6F7^dMiHH7?(ESf7R@`P zY+!k*cmBHo_!QOm_!E%pJdD+gl(}nnqF2@NQ*fco4yM~b1?;o&anhJg$&#j_dav-) zs*vB}RZ+_-7>MuYK2sX^rG2ZO#*bFClX8;zD8Sv$4oQt72sAfe0NV<4DoZ<`gL?%tD~|XDXZj!eB8yHFwo;RgJ3o2-J~>CAAd0lUYnDm7fe3rxXnFKVlQRhbNzPUM zbB}iG_3`Iu?9HKGhp-V7WsTKv7$)bXP&QcQ*b3n|9BOg1_kf{Iwh>HQxb>$L_N$}%-}qM;)Md%(bq=)u?ikiThHl6 z!Vf7!rwcUjn6}Vh7=$~~d1@G#dpdKzyRge~1~w}1!6ijWMUD{z!JV~>1C<*8#T%Hx zUd5k48oy(|eb^$onKIl@Nap}_*7e41d>Tm6I!5fS%(XeHd#fzW$>uJ1!oElYQ3%F_ zG*Q`xhR^B73iqcisG9P=i{^yvAOekPRx$m>RaPMF(6LqAoeOfGKZ*+wE-JKdyPGl5 zmNe0KqcfB^jBl-ize{nq_gBmzxWn$souXZL2iaROie?r0Jo-K`II|*cG)+N`V&NAU zKQ$7yPeF~Mw}$g(l;wxe*b9}-??y5j;w9Ue2TjX#)BuMJG8eJl8wjmhY1m{F)GezjAaFwrlJ*d!05*fM z0tNN{hluG&x8LWySvcI;qb*dUF14uL8Ej6)+B6pg%{_0W!|{bGhrN%LPmFVS=lnfa z!Lz3Y_ZoLzz3RLU7U$m#Tu>~#j)xO|FU)eRac*I^FP8arc%@!UvP!q&Sg zXBM1fEuimn)J*RO_PjgHQpS%5)bn<$`#X)Vvo`BE3oo&KfWFnAq8>lvg%0(#oGx%T zpP1=0?>GrWB}fB#TCQAR!|E}w6Vl-wz+6Nea^RbG0}MW>ya23Mil%pO-QAD4WAX{c zDf8lWt@?3Fr8jK%1{4YRPzdM22(O!6-MP0BCoOs1Jl+xJ6KWpLFrn|e^yyS;IcTAi zHip9$gIsWh?=i@2j>+y)0ntA<_E7HPSl}Yap+&h8OHQBQm1Yu-Z4&pB&gR3-DOZ9mGo>nArfv}U89ROzPr-MZw3{6w^ zr=k$|P97T?d`U$#1?4#M*IDm9|MdR#;pt*7PVzx$@!wUt?~jhv$4MH5#X+0zS@ z>&0{m0q&CmKKXN}{rWCSH$+f^;E`WMP+5tup`otd;7Uzw^(@w1gdaD}YU9!J98;E| z^&|w<&9pV#7Iza%FndF7Dw=)g28b$0MW;*VF6VK%aeEB zuKLzGcT0bNS>KC7H}RuZl(wd-{9Ov!i(^8TsTyKSz$-CLz;5RLBt+0tSS73pt&NR& ziJ)w6Hbc+U*a6|7(7b9zVxfk7G^)!sWK(q9m_dhr!s|Uj>Q_HrrhEI>d&`fu)xxHd z7PP1pkTb2x(0mesHxW3+VqjgE)@W` z9^GXtf@oX&RTZVhO-tu(`9p&B7}N6lo-wc0cab5Iy+m30T&u6*tScH3Ia8Zqt-|gi zAUsBS$9G2h<)pX47tV!S2J!O*cLiBrsqy}UK;g$e5p)CN%rM~PJ1BL^H7)Dm_ky4j zRTIF5M-1cT zsdUcFMa@llv`t>D>mSar%jOv*IstuIZQmB-x2PLH2ikPu8SKRPp_jYZ)^Nh{+7wLh z))SWf3O|AVdKeeq5Agy*q`DbDi2su&J?e1nFqgIJENx9K;V%hLVoW?)7s;S6J8ia9 zDuYRG01IOlB{NG>g)qRfC>i&;Bp{$!O0*xe=|ol!d4UXi1@dWL=*7a+qDH?e=cd5r z+uynP|tT1!gJ7Ti+;~GxkUn3olO$Jft4Cf}>`JK4H`wZW)ykH;c!uDHdFV9~E^Q z2%#klYU^xC2nF!l1l{B0FD0zKjY9JK6xzL}jP(Qz2NvnmL;czct*C0@ObfV=KvVC| z=;-|}Rj;L%>2Il|8Z_qC^&|W^PK?Y%wz|36sYzTqRV4;<=1`u_FP!~R6*TBP=cThI z!bA=CKp&G$B@_vvs)6P_K@*|lq8~3L&R% z4Coc7skoM%!YnsE<{*SS)-I6b$462Y%yA9AzMHb5=2{zY`CVg;X5LYVXy~U#sXM-; zgkA}176ZNJPTo%crGreAVxjcwZup!O0l3xOm-RT5Fk86TtHcrWCtMxx2YW0&ug_+T z3t&#?X8iCQk{HU?8DW}~Ci-EIyrU7=qw_#jC&ZMKrIiN>G*$iH+=wjF$`;Bp3;x=P z(v?B9nSxbdd7a=w5Alwpiv`O%mrP9YILU6F-Z$Ig^P+uITa43gmjL`vfBC~Ypv%k; z-o5*qRbPO9#bx3SEpf;32VneWn?rD+V#-`3U&cu*C|;64wwR&saFm3)hrb^VR)*mp zt4b-z8y{V1V8B}<8v?m-UZ*tsrpn@P+tWTxUre*2;7=$sJ=O3T-BdBnQmzOGJD8Qi zKC1MtrLW`{-}6w)`y_*UlU$_2ruVAqypP`xYc`R=jJ1{O2eh|lav5CdoM~pt444)@ zSIq+(LB2UcPts7rOGhZ@{O22NYpw+6t@Z=QT9k@e7-5)d=%kyFv=AilJI_M6Zv4~* zF)w_Bl-Nq&+V!#sR0_2L=y5XafY=)Nt2p9Y<=nCCiL*j~?B7ZN^DU4;0SsLcY9)z0t&^8mHpej{5=plH;q=Q6Ea9uQ10gaJG&C=`_4VdLz{YCL#j2JfXF~p^m=sbp zc-p_lq;S3HT}Bz`?qct2w{)Q7%jXxi#Hi3cUaeXzK>o}$0*_DcWp zg_&G{V1IUGyRj7G&rgKqg1_tJ);gGlmZXF#_F?M7EwwgWDT|1NQ~6Gjq^damV(6Xh zi7yBE1}a|ixCG&ydc^~;%F(YJ!Bc*KO^RuQ(z?$XSm`LCampc9<8&4@IA~p|mlW^{ zB`ahtIVpgR{$E`Q_nM8I_sOgl)}iBY{l-b;##U>hfiC{b5T_EyT+Qof`s=+~J+Al2 z+?c?TQ;JWLQf&>)(ap5S{cJJE9&fFjPjwd75=ltYXkF_eJs10)8s0JSx7V8~ z628nQ><0n|;1pO$Q$yH`y}6%99y)ZNdfBvXX}0Y#76id7w#=((Z{@;6&M{!Pmof`x zloo6nMHnJ|-2)u|{QC7HixS`cA=AS47$Re|NKfyQ*|}pCL688q-{$?x4Q>8c#vo}! z5nlxtZ$>X_JP6Lu=gi1j210UOlY_u1MqvmzI={OfgSWBy(~j_)Q68&(Y&exnAYRRU z2%R_-Ff*Dw;xx6a!2YW9ZSqJ12hPU~x~)7Ot#tWToXl2Ls%{~F>y>9nU2f{wFHp(aQXim}5I>^EiBtIxoxkp%2H~5h*z3T3xpNjrk8@Z%wg--!IaC z8c0!FZ-vxdiD^q`jJLR)y_1snAE<90g*@L1*Gyaajy!FVSjklCxQn9JxjXh zT7=QHJpu~wXaML203Ie_Z1RA(|2aKv(@KmIa%paNQ1jbg|AY>yqNU;(f;KRllrk6T znJc(80ZPgXZtOSCgUYGf%(0At;9vx#ZE%rwi%kVTyti=vXsNEc0pL;XV#=%LEvTC`(cs1y;0H7zr&b1Lgm=N3I zT(iu#ex>+2&R-JspS~8erKHXVunNId1!tSuUFcNw`n@XTQtlw3G2XrUWd=zZXx48B zZU$1#aYFaB)1>b}GlLfi4N_-aqgUHqjR4cZRzAW%6eUclJL@}81OD^wH|}W+8NI$~ zx*KElC!z=O1Foh)6l6_Sq8!@Nk@VDaPONWKJ5qN5ga@HM_7fOWNW)@U!j7LodY3{t!ry*v{)+x*-c8^xxTFq;|y8xbAprD1&Z5eLJ+ z+=eZ=i1|hDIib(ETLSj@d(9)!2R!tb{|( zE358}F#{mh)f&5V+h9z0+8P$4;8sy5QNF;>bcS>!tp??&c^k95M*XQy7_>Zp7ax}*|A$svlW-a(x>HdA~1X69s85;QDzk; z?-zpC$U8puyS)E;I2k?x-Q=MBGwhRhT&^mhOevp`>>%L&$)-JnU5gwd42!(z4Zq64 z4RGt)2I{E6JNff~odPBL?(mF;zmK#NQ;s7q{$5)5gv~mRl?uvn5bc; z3SDAc0F`_j#l(F4>>h57pni%}_0b;Ib4gI=B*j}`BJ+KN@5hp1U}>tDjiAjdZtFt` zrY%;C&D9~vNH0)@JM>>>Psc!{5gx0Qpid`^gp*7()bvj1rJ22X`)X*9Mi64U2*+)d)asI9y(KO*6K)le@AW^=|4w8`=NtP zSD(g=9b|2{mk6|EdWS54`CruF6Q=OxewTdWP(rW9^H)jjTIBN?31`M3fU2Lidq$lk zkN+3?F&B(w_z^AA%*+kEQfE{<6 z=8yAe$s61*(?DQ(IYE zUf=fkzoX^TMz(Tl1r3%*pT-7_!-Z7R>WMe+(7gc*D_CVb2i?Km@h|pl@XbBi#htrt zI!#E!4c+au&#gF&nllC)U5b6&shzU+jzeD6QyuzL`Uvv!AJWR16~fO(S?ZVN>wgS1 zzeNu=9=>o~$L{+1!p4?#wVtaDJ<~qusLt|GtMog)NRK0LU?Zlx1QirfAsP_MR<81_ z`O|Yau~?UtfhSeP0;RBrkZv&2W_QhR*$h4zT(F$rOv0`h%o6mZmp7IW1*^5B9@`0f zL2#g#!@xwmP)03OYJl}p5c^R<11eiJh4yh(DEyJ zc>U<&NBtYUjv)VA1D2GxJ6ANmWf!aH2uB5fj zXJjvbqZgb%_F)mhns_D_lo(#Y*N@2!hwlxSs=?9-;x-dY za_4k_;ai}|7_z0yH4GPwe&`dWmDgk`h(4M3uVDecceBs5&v(%s>kHNkA#P9+k9UPM zMOY+U?jSunYC2bzQTlFNZ)Sno#B+k_A^k?aUUr$>p`C&4oc4Y&$RP^R8U+X#UaKy5 zj5&DH@D+F~WX_E7z*%4xLyZf`$El(cCZFZ;8gHYsI~5pRV~6H@U?jbn0atGN03{n$ z*Tri524Xe3!eYP$=^@b`I*FT5Cw?-6UW7P}Qra+R2Y|5z%IiE;SDkcn(ner z>JT{aCJNi#^0;e~L2G!hlyMI zV_kras@U?)M)|~n1(!DB!ud+N#|5YcP7|sb?r=7enfNJ!&mH#`u19d$#Ey;q>;@JJ zW_c4N36y+{V)Im2egdGK%&E4#8Z*EGYJ9C93be+Nm@Fj$m*Pf1U*3tFb94jwu!Ok?@A1CP#CoGKT7F<_g#MkbHTR??e`0FWPyZ`Nm_3pB z-Wb;BPPXnU64UGTu<>ZSt93F!1lE{L#Sjm11jmC63oxd4roJVkhBaKTglm`ujb;l4 zGeFxxXPv`f;gM5e(7F^fmy;XxUbWfT2Zl)JYSIL($qBpcoeN`~*@KNS9s>z$nEbh% zn}|N@Ly+go)*`lm;k^j4!Q+#UdTFEI87(i@6N*4K`h584^XxNvC!RD26noT<4-iyo zYd)|^7Q0C?h!l%t#uU*+M%8vH9z6Q*z!L^VIX+_fO5yMx?*9N#@B!M z#MA48A@W)cSmLI=j8TV>GaGtDY65_dtw-`6_^)g)2>hFOu5=aMEB*%PdNPCv!d61_ z&v)G3D!mwBASdV~t$<3jUiJ}`ji;-l&2D;jfieYsc7dc*iPg)ap7xBb9N+d|7`B% zyO-Kka^mXX+G;kyhKOK+d536cUoJCe)&Z(Xyh-7aScQO1B`!^bv9WZd?F9FT++enc z;2bhu1$FYTof0AMu{i&!ICYnNAz4>icI4*LAH`JWj{qe6S1nIhKX{f`s1pi(*wW7J zCJ(g=m9_+?vQ8RycXZcZ#r25x=+%t1Sb=q9B~-Y87x(Sr9h%XSCDFZ^!4Mdz`3NE# z4&nJNW#RNw;Piyym7O%$%j>0F4AtuvH2DR6XqhfY-NNuq0`;Z{P}5RSe3TZ>CRSzk zdl;6a@bSc&W@wPA7#4Z#ZOr~X4o}urLhbGrJ}iFg?}a!P=5`mNd}qad(Ne`7I40~N zZe?|(g++4+)g?3fsPDWpUjPhJQxN(u`2s<04!wU~M?&Gx^z+WB%XH|E)ES3}=t-&b z(+a7KziRl?if5fVA571Qe4(n7-6G6!jefO`)Q}-H6K>ve$1;^;?Flyu--3D{EK&Zk zb!MfCKQ>+e9*G?s9Lo{8T%WsI{bv`4xYdhYLtDRTJj2F~qOYiPT4(Tfr+>AH;o|!7 zK)YZfiT|=!j3RTcgT!`E!xXi(sP8~z84)KVm%aK%K7vTu? zL7_FB$E4w&sq&e=ppbk_s|3D$<)qnUz-QAesmFiWpaQ#6T%}>KD4naJM(sJ!OEVYu zMpqr@$(d#{9O<=@*8?a82i}f+pK$m1`xPdtPM#>Ile^BX7Gc1twlE6N3$F37cV4t$ z`;N9Lj(B0|bRf|tcH}0sUIvcvPflz$N`16rK2l2E18DrhLVDZc7^D(TV=!^iU`CWC@Iw3at9@ItUknhXMv>MyzG4KZj# z{2CdEX}4H*PPwlnRyM3(o$EP-8udNTzXUBk2?loVy=w&{#50SzfDoHA}Ey~ z_B5Ki*KtKvZm$GOUFq;$T4Xdr{Z%;g2kOy`)JyNFZ@~=)#zm~nP(URT!W>lJc_J3! z^h$IcG`A)j$Zy&5a+yHYlc3WZMgFTDc_g7WQ6J6R(iWg*l7X!&6Skf?J z<=balZCAEN#=S8BIKmpoG4b`z!H^6d0mi=JJr=LxKg>Up89=S6GTJD-<;XWSKe%e{ z=$9X68jaa#98UeG+1`es`9&V~v-JJ%<(_C$TGf&Ex`hn*XE?$g;zq*q(U7!w(1_wV zWHHPrm`M6v?rn2j!p!8Z|D5#Sk|F)?ekTCh_`h1J_$m@?E&=gM+lW>-4ddrsC??y^7LrCvG)$wh(@VarONPs8_3|-(wuUDN%{O?iu@)P0`u|WiT}+I)PdURP zC5Eb4zp6bgKEqDuoEXWOlIHdM-1btvD+6ww0l)kV_W3si8T!a3`|Wg~e&36f+Ax`eg= zyDMY!{J&JrCxb>)1Z0ekD++XqgnK=eoj_S;|0Lk$ug51fwCM0@eEncf7MFmOMgCdO z-9S!0xw0u4bI`Uo;(hHjk3ndddKZzB{9v4xk{lCsy%T5uvMj*ow z>}%3L{MCsY!CX~$YNSRm{1khc=^@<)?2|otC#7ZU9ua2zTxSFn$N%J+OP9Q1%T^|% z2iq6j)bDpZml$c9v-P}v{Thq;N;OrDylFf-wF118AV0p1ckpK?)e*pSO%|N&HG4B?niL4-$+71+&%T79%8+R*a9sQB;4Fqzd8Ubvmh9N(U^?@!* z5cl2PMFDYRY$lG%6*HS43I6K!c!9-Hqy>;{Y$9K#OWhTeEZai8J@0+S2t!V|%c^V@ zhwvFyYUaWw&wiH&t;3RV&k4fMt~FUxNw{=z#jy^1*d@aEYgxZCKtjtoqL=`#5W;`{$GPf5$d{A zlqOs}*ymQSc!oIhg}VosbgTR3Kmj8D}C<*h7^w zpdW}RIO6^3WTKQm-gi`5tLqZgx zQCltUG#j(667lU`RscL-+x#`8 z(WbO)zs)a|N0fHwmr2363Ez{MfJUJ9oUeewAF)(_zyc`W?NppUkw`%?u9W;B8zGa- zzy(bg#F{|!q!y^;BmdwcGbvWQ$gWFPT+I96SYgHdxk!= zuGX)WJ| z3f<3@46zOJtYwi?9yr%183SUTb{BrNwQSCpF=3s>c3c z#`Epoh4(jNZx;10J7CwW^tqEl$Okmf_ih)kHFscrb@ufm>mEmtDugC& z-5n$9-7JQ@bBN}sqXE1V*6B9zZPJX3)N?!rc}D5K+ZYT)#}P0}g7E6_5^ML*XMFS9 zc}s$GUyT**ji8k&HyNPEgMq^yD+R!mYQ#kzZP_(1rD=^`t4B?uIy1h%w&-~upZ-Q{ zA#$t&#hLX*=&u~MwM${wx8g0k&EdXQNjMiG_?Bnk?1A!nZq}pq_It?VPL5AHkUp?S zRh#tiAN%}_g&>2?f1C@trU=mhc_ZtFK%gB744bkWy4=fL`Q477YEVQgto?N=T_>g_ zAZ*q5$-IaPuXWJR;21pQ3L_py9WK{~$elsnpWn-r#VhJsLcUNQgP=W$g9xp|i)Qh6 zl!j%n)U5doa)IaWgt%Pb#hz3OC)=HEG&87C38)}SB^{rL$D$pYN(E7J$O?t~Pzmo7 z40Pyy9Qy-9*e&})6DqUt{I2-Ew!sj&dNG15lcA=?AL}?(&X9lNx@+|}*^IK~6z zz^_nRWWp_PED-~QvI{OFC3obMEMcw`YvL|a*bpkF1~s_HSeUqI(2~!pUP78<3I0{a zOj1jiA4O*xaKfarZp5ul3ld|;gzerJ=YE;T01nMKm?ob1PXgBaE-^zW-#=lFKkh%|?hR!9~dQu}BFd5IAefXJ2N( zJDpQ=boV_M&|(e%BHhkk&WCrs{oS@wVZrTp`26tW%>r0rx#``?O4xv|)VJ@ME=kyj zox3RaQ|gd_jIH_LYm3+*cDnTG#Lbu(eDePy`B`~r%eV0JhadQ`#{wm$Azw9^H6r5i zsOFd-n2Tx%r;Iw&MWAuhhIIKir1Yu+@yCC15tkpX6E!#>6Kcz`#>(;c9 zj2@mV+L4|$d>%uo>s4!GGD#v@n_a!9WaL?`75A^gcSjpsc)s>d7Ee#0I4&1n=4!R% zz)(Y|n=DbJMv0tM*@aq05RV_bv$VZPUR*VKh!QF~U*5orePU7lv(T>0lbz2f1U zR=J3x;wIya>BB|%6Jg}trCdFAq*B)~#zlMs}u<+oNpEakj@tHDd=+M>9FmJe?P-oe^*>f>gg4YvxrS_Y0<&BH+!F`b zL#gheO9Y3*+KMxIZ$wI>uYjiyOL1rW8xNr~u6TQ_nP`-uzZfp2?VwDL!m=GO%T?`D z;*2c*filQ%luiKACd!?@^pPVcKm!@)Q4Ekx5ukvwD68A-Up%gyoUDl0Uc&mOFt6&c zRF8t-7PP!r1d_(~zxlqKbzNz&_d%wZXwcB!wWC?Gg=|+ah9uV)T>uFT8v(j+E&acjAnqj9o-V+`gvNTL; zmyzl;+azq`>hLj9g^q=w?krNYtzyoLV5S-p8bKdD7F<(!bgx}wSG#5zbp&=*?INxl zU}z3Dj9gEh1UWTtSXzYnCtW)ngdFn7Tk~n1GY|k_{iG?Fj7GY&HW3=#;cJ!8uUm88 zT&!+f1uX})=g%91V42wjnGaWbo$T;Jk21dU_>|W{y#ydejotC5kFPUu1SJ0|5Z>=i z`&MH&!qjFW0RA*lnqCHlOuws9P9C9H{Uf)yRa?|z3M*8o7p%))@0jS?fABayd=H<8 z8eY=#?JW}{UjBQ#s{rkPN8*^{snBZyLSKSH(^Z3>CW8iXr9KAU!H%V$GeOpy-V#vAce5at{OIcywZ>qAm6pV zOt>rj{ygzcr|2xp?lI~H1LQns_YP4r+cp^IELEexcN3XN0(EWB-GGME3<{0P>RgeZ z`H2p2f$1DbFxS-%f@Gf^BmM1tIWGfGVTcwI>3)A@oUeHHDK}kU8$-#~%$(cqEKTt{ z!H|mjOr_`FQ!h|fVkv>eWvfVRo>O_`bqbLOHBR(5=|bMHi_BFcNI})+I8iu2mz1Jr zv}sTA@MbIbrWT)1BcoB2S(g^C=%2XcWW@=Vy@4hzHl&i^@@YQXVbc9y%-tZomAhzT zQ62~hwQcb~w^w79Ay;E@ye?_$Wa;JA!2^J&M$}kjAVyskA!nX$EU@LiQV06`#=BYm z@mp3f^9FPh|0{011kxmWTd8m6U%ob9iZAmm;GN3ZI(s1+X#O+i`9;!LiD}x-a=9#z7_WS9is7Hy@65@vun>UZH{WPT*Tg z!aE?fY4T(p$Ht_hZj$x0Gw~X}zo0lRX-fP&JUk^@{6%mBR!a2OlEDQ9Xj`LfC6sqEnZ#?VnsZ{gKi^mTI<3~nF<4{*~_5zhj>)?O@3&*TST_Mer$rn+H z_7Gmfme8}CuGpAdMyGUsk=ZKUp~@s+)1FX%Uu2Yl$D#JgcoX~BLV0Cr>`Aqc#TU!njs3JgsIVd{`9N|I^(Ocq@6 zp)oh16Q+8vfGI!ov{!{JW*7{5qis<)4kI?aVOMlh&LC;9*@hV_Z6MW)uu(V24l%@vks8E&2#O~ zycx}P0Id*F%-z!Xa^h558?YNL>(~}$~Rin0l(C)+rx41z98(lAO19LWlt)u_~U8Zs|r>Qgsoa}BVs7C#v zc)|n{JJ^XDYN%fVIBvtVGiq3@aAGBa#%oxNfR}7ds3g~v=Mx>*qm~D=^S7LEIxiYG zmV`I+*Ytezd5(S#6?rdR5okMTKa1@#R#RYg^`-7J+`UGCSXiJLjIlT44z<^*-pOy7 z0V!%_XZ=o$aO!4OT!sIqbY8UxCcAMO3I*0DQh1q&_^GV7#a1N+vZ^=8b|gysOUDI$}H+*G@PfFo2fL5O11qoTz*{Ur-3 zVAkjwsZjX~Jb$8)7ax$>Fd1O6pnK)&k4(qV{k)NaUtg%b!pV$yPtrS3&y1hwlpGkv zRtnrtlrkBOydr`HeO{iC1S!rtJQ*GxE>8d^_vU$l;u3J!|774OF5k=yH~<;(0006C z0iV}Qbc+7~04O+UAmnBjFrFnt*4jAzSnL?uDazc!1si)QWdm46y{e6c@s|)!8GspE z#mR|OzS5iow~qh-Ps2lp^vadnZ@vrq2&(@Eum>U32jdsZ&I~<%)8Js0*|D3eZE~ev zChEREY_1TYOMs9XJOQ=Vmxi)+h#iAzZAFGwXOvZHl&n6!{Noqtqm~Yxv21m5bcbKM zoAA-5tL59&8?`iy8UBwtcO|A;AjfDy|6mXo5m2;3s|}gs3rj`xKM@;Ukbv+=BtkKl zv8~(0+Rwn1lwBFmn>+9gYfs8v6Mc>%gvFy7p{kc+go?{|Td{?Sg9?+;4m}NdKlL^Z zoyu<0^&3c%kcnxSi?3M2MaLifZ9abTofiw`SE(48PY1@BiP_v zNw!8^MuGtlhX?PFa#8BNhv|dr z4Cd)?ilCKRGN*GVodZ=a?TbO4_kqqKwjvc|^#sSY4_p&&&OJsow8!ejfGD*F8GM_b%@=vJLgMskT~yk-nZ;Fsb~-dh3L5(I2oWYYl6f`ar0`d=xsOv z-hcoAGSWet&}N`OTU%ROTU%NtQvd)100aL301w!2JLfRqlINk!*PIeY6#BtOY&`}3 z9BT6qn-%8plWqtApI~M-?>j3KLJlp#>5Q$-&bficXQKThLxAV{@KBUu%(;w(a{vX= z8)eI8B(`hx0>SFVUbd_Ia#-9}Afes7 zOF<{QADW-q42?jz)GNU7`!jkmyq8QX_9(;V#D8}G3!mVSYOJk{cF{2Xr@=LzX0^up zJb5xl`viaOL729PW5KL1XOD^PB`9+ggkcZP`OLq!)Qcld9i*OmL_aYA197ezZW;H` zWR`)lvUvd+(xIro?3cb7Pt}!;oq##nBsQoJHDOf22FXykB@_rM`|Uc&tAw3}&+hFy z_g;B*-8nm=@`CJ}uW8`l#OuZmo6LJJBMNe=1x45C_`gKKpIp|%U+hcQM2EPeX17g- zWH-=MQC0NC^^kCr(28LV9PHKvy{LmYUk!r{Fqu+M6m-}!69=clx4U=);8^j)qxZtV z+|H_+r2>UMgRp0B`X_)+5Tqo;xn;zmBtMkvxw^*jo^$Gi4X&v_%iCyduE3T6U5iPP zYYg;RMPdj7vIO*>83lGm2G<*c!`Le0C(M#$;Sbws4d|LWOV5@HVwk3sQ-kRU<%#ps z(s>f+OK)nMFASBkphV?(P|^K*T8reDjXn4kBjJtoKAa2#5;;LU6Rp2Ju(EZC?xZfJ zR%^A@{K0zWZQOhdBi&^t#wC1NeiWrK4NDbq&F;$6W^5ckjKSfn^a9^_MR-hbw#_@D zMyn3LVS8-f53MY;N7Ul;)7&YhK#(vAnvm@oq3z)}w?7H3dd zfE{&NVBoO#`iRu6d`b?;WHKyWu;2j2o}Uxgy_;k z0n>J#yyp8D&=%MU*|HCQqRCcMYi2QoXC_cp4?zUh7o5aUBtv*cGd6EoVRmj-`H$t! zV97J~(M67r|FlHGEyM)z7Y6AW>yY4tjP-fa<^@b$WMlf_!CK+($=v4AD90`sMlm|F z;0yZ)_9tRO*LQ1OSnEHUJhGI23)fnypa4!dA6pTpVO8knjLo#|>!_X?Z|?vG9M*m9 zEg_00TyFLj-T)f5&mmMg!3>S**Zou{OGG$WwcWMQnH%{nHdyySR(JDSWlc}bT1{ViaS z%1CBsUoucI@x$t74rvtU_~n-UxT2iUwca&U=(duIU41!+E$g@wi%uQG!6Iaw68nxh z19*s<1gW`IKWg7Sh6mKonu%i( zxOdVCH`}&OYKH3p(){TJC)mw%gK*PMbvtl|T-pwyCDbJEC8-^j&6bA{P`lcN=aCOs z&qQ>)_+&3QC^HKc#g}l8MDxMeKl*#?sSFu+i7eqRnYINYw>*lFv3!?o1g+Y_#8y%m zW0t{h@jwk;tC+e>R?ic7xVu+L|6qmS)_2~aEm`n$FR62>(zZi`_94eK1|0+@x&g?_ z+YSYLuhLT+<&|DW=^B&XGHs3?CGBLhrf78z#Yw|*c0M_mg0Tuq-7}KY>q=A-p={)} z!J6xF;3dline~ZoHL6QT&)uI@UH?yJAl8_H3%BB)2W3BEg{37egdD{1X-e5fJ(Us; zDukRS8Pjaz#VeFHi)&#Ul41+J++l7sc~jdRNkz#mMP{UrahP+HnF*hn)Yi1fpY&wm zZHOHXlo_$kbngqra|w9R9;dQz%It3VcYhKp1XOdz@m?`21#}sMxFPt{(>2Kuu~n^@ zQ@$>4FWY+6=X#=f%exq~vq-*J&Z~htql$ji5oFErR4{j>I^NgNe8wd9Pk*CY<6T9Rm~N{*i#pQm{7W6rH_2l_e=Ar$!TMdWsdg_7dEtSSqW3~ zuNoC>YAL)Fqh@3+?;m143oTG64zn-|C!=+M6TE)WnnYJ5Wi&iQr zm#K}sr3DN)O2^k$BNoGU(U)^@(E0H<a_ezU5`Ko zZ*(?2r8OK2GTw4V=)V7BgN;2<(A=H=6d?yn`Y9lX5P`DdD-`=27w#Y=!efaehhlR4DCqSb^p@a$%d^$;9suU7{EZiwgJ2Zq{{h&Sj= zQ}{wO7KKMk&T*LZ+z7-sIV*clKXhoIKWorK-6Y#nJW9q0)~@heFnVzC=|h5!92!U7 zCPAyTs_IZSGFo}FM7-iCm-_aha*$C-Y>gV`VH9`B2DZjxmx<%hb%xEj+{&dvmG zRC#T%)Fz91bJJxeAGfV>v7Z-o?<3~-X*;rwX@e#;>&$`L;0z|1-koLw*Z9E|`1$x- z5#eOVv!}9*OFahr%pzs)K(s$9@dd3hAItMUHkWxeJGfg2?MuBL1`UaDgw*TxFgT#5 zT#&iRzkgVA`8I5z5qVdD*y@c;{4#F|Q{=KP=O(uc?$2a>&w9fvy-OCM7W_0n=n{kr zcM!j^5nFGyk*VgkTeedI3CV~$;E@u+lok3f4jJEY3D~rOzQ8+pldi(iKY)BE3J5ml zsNp{J3tQPy;5ZLNw^4b=Y#5orA<>FAP-G|}lc@G_7xQ%MQ z`@n+VI}}_v6+hXE8+oF|_9qS)K-U)JnR3kq51xLMFuu_0B$4a?l?isxNIRZ_fIhS0 zC9uTm8IH11defJY+y9f4O7kCm~^<+rji6lf7(3wOfkUO+t?*M}EszJ~&1hJjLLnsf}p zt@fh{dpJ}lvHyW7$ZGQiRIHUli~NX*iMUJ@x1kOD`h{+L9J&j^5w<=sDsf3QygR-b zgvkIiTG2;O^4_NN#P&ysWc=9i`AyzYq}_d8ew$z4Di zTv!zBS@b^0eN%1_k}Xz}r3HNT=eteb2o=dG#TC*ggEPpB;&Kb4O!u;ScB>vT!bf~U z$voT+?2f{CNG})$P5Q}26GyC{P^C-r$X)bgaPvv_l4*T7;<+r-IFWQUF*A!OI!`*-YFji z&gV}97_Ne_G~8{+L9vTcqgwK{oU@9kcYKpb5Ib-RrqMiFP3cVJC4L6(&vbJN=S%k^ zoy>oCdJ^iou6OJ3jfOeV63s;4-jvKAR9jGyW2Xn_ny=YpN{PSjyh+uuO%89o3N3o!^x@{7__A?~6&cS0oq?!Vu@}%a z#j}5V)jR7-mn}o$@-`Q}#1{rt$5I=J`7kMQ<^(cX+K5Ouk)de@SNJHsL{fHH<1atn ze|kN=G{qg%h(HZc1o2f~Y?lG4%`m(5IWEKx){iGLy^N^X#toV}S>g2i%8Ppuoe&)` z@g=b$ofZY8q0-L>3sHJ7fJ&L$^lRAg!wm&(fp`_20y<-pVf_ac(M~sC2oBv87kX@M z2L%J^yQ;wYkPUptT!4NH{b%X@-#w+;))EGoj47le<7v1=Mb3;R1FGDKY!kq&CBM^O z50IGqw3ky zV?*%Zbqq_3JQNNTnEi2^r5F=TR4p5M$7{GEO7fU4R=Ve!a$hkhpzl1x$^r+5sEV-b z*OIV=%@_g4~QJOo(K-W+UFfL?zNEI{_rkFj8I zMUo8Y;H5+vLf#pPZ?BuQpw$o-HkMDQKbVu6%8vGkag49gV6tX{vzK|Re#lKDL2W&< zywbb+pKeJN6k&G5*oL`Om}V`LR}0JF8oA)9D-iw^g-u)N{rRb6R2Jc5?p9&XARyL8 z=ZAz}INI!9DBsZkb=vJ6`!@!$NDE=4ZZE-jJ%Z-A8bBWlfIMjowyD-!x1Db>@4Pa5nB!`f%Z?sMB_ObT+}Pms@gF5CK*1DYXi$1hI#sS~$`) z@lXj9+CL7Lhr3|-e2eg!QXX*m*e5L^K&&&q6Jub(`evip2KDYa%~6`nL9pFpPQ&h}?Ec=IC5gS$^F6ivsw&q8|I&w?NzcM9cT{_GHtw66`DYLO8SZgm?dN*Kq2A zLjC$g%=!16S&Fvst}T_dOw&Z-mJ-M|)bBi)S8QTDULzk^gO1N5%*3lp_G0m7mi z{pnEd0azsSEps89(+X{*=|q z&hW_vL+r@p>{|!m7P1`@gl%nGl5OW#Jr(cga}MwfOgW3DAeZh+u!U`;tV1m!`Qn|m zR!#p;M83WMApw|#xz*m9O-njG2KsU)q7X(NPP60g88ji;xhIyI2{mlcUfh+DQP97a z$WlbQ3GO)YrojBhkpv<1WJ=Pal)`}ItkOF4;g^A9A>^B^QD4F{RcJ>l=zr)(aW5_I zH(rndtIENRc24^dF@~5oz)oD*$5@T{X1bkVD1Dye`1gUr#-Kj|Yr2I2jP3RI*EP8c zTyYq6OAbPp>@{i0AaQG8+FK5Ao;XQ}jYAl#%751&!Gwb*pZie|@smSs4q}jGq{&Cs z-YTadc5T?IGj*g^Z~nGo*QcF^BzxeUE{Ej*Uq_1nLFLFP@2-Jdt{V?3HRKqYXT_%x z3A>cAp+C(b{*AX4@82XhvR!eTpuBm~lY34Mbu5&+#@o`dZnp^)2jiOVm=JQP-}C>(T#RO~vC@aUVzuKYQ=4Wb)U?Jvc+%tC;5|Cpsd&s< zEeKd7btj}I$q`4m`C0q&eyKrvw9}x0wpdA>xd9Mf9vCA3cMwzB+XutK7}^M+`_4##P-I2XSShR; zK~G;O;=;m;@RnIK(`0Cf`9qfzNd130EC;x|VFU~s0 zV@80&YJG?(guH;M}|jKBLcdDkOcF;0vIeealn+S|6Bz2fm9GE-T$~OQMoK zFj@LVcbX`^wRdl$6Dakdg)UnMATWaYoyC6qxB?Jd6or*Wlfe@U8+u`J!eWhz_FB`= zT66;*JsS&N(W^%bA{v`4tET6A*~y@fPH(32b(I$#H$S;78??O4LJbR^$pQ`3{3?_1 zaJ>F9hTo|0AEj|iftZ5$p8UJ0;|qTiI&Ds`OaARQ2VP&JZsZQZzE3<%%8Q*ujDvAv zI-u?b#Ax0wQA!N8h+ZIKW_nAFAE>CL(m^oPeWH;?zlaD~{k=!_pz(LhnUXKF>>)-1 zp4c=m!h`~FsMj9p+8_aHqIffnJBb4O(*bzWZvs3H0s{jGmiQk;s|_F-UHf=bH5S<@ z*#9;yOQ>Kl&9?I_9CrbJm5Blu3^xx7Y9NiTA_)VX1GivKh_}WygJE27`1Th=+{5C6 zebUVbgH|ms6PFd&;H+YKVX!K(prOF+<<&yvY$dT)Dy3>$ADyezcF$y%=99| z@uOk{>}kD%t<$a7A7h;^MqQ@@Rp15Jj#Br^g_{kmZYlWUAH;LMi0tzbj%5EJbbVn# z`B(ri5-nP#kL4j~bP9S_1$B4Ci@BuqC z*mi16HOPdbN89Ya$YjIE02y}pIj4^g(b7u0V+iJXU}231uj;C&-8j>L%eN57G&uER zIoo*!rswJuqmYd0ZRlB-*}S<&z3RVS{4*b=;AY96@Ekcpm*FN%~jkDn2jpnB%eXx>=@E;>3D{ zl)!Q;lTmClA#yb40ll;RVweF&ulV;h9MJQG5%XEA=^MfhN@4oqa=EQ{+pE0({d)@@R{phF6YjinC|&JK9eD@A>JkJ!do_AYO9^C} z`faK%Qc>-J#fIw+RIbbedzc7a0&V$SIO&VncGgW?F%4t((R`jJ1{Vc0+<_A+u5ppi zoo&GjX05qWXa}_!9rilV4pUviyy9j%YpHzmu2LZAIGIQ8A{(?So#qtnRhO(_%-?Iz z%`dO?e4=L49Nch4h~(O&JMs3ZO4QZ}b+TyE->*$0kH2^?$SRIF$nk(YPG73mmymjZ z0kiWh(Yd4taYnWrgV&}yr5_vVYzruY7L#QwGEjG+^iD3zMNkOSmU~(ow zthl>9-0kip+w&O40em~BBa*J^#ZS~`X3;i2U`|s4afpAr>Px3enh{wqH2QrFdeEkf z7(My5@iQ9zwM$F;U-ylQwrk{!m;o50g!HrS&FrUXT&8$C6<|aIWeFGDxgMU05=6?l zh*gkClEP(07whlYF3<68dpSIzgygJdQ7$fv2KH25(b65VfJ0ZpTl!s2BtdwzBmc7y zV{0GWa&6kn^e1D?|1XgiyB6j4NC`@O!f87uV1*q$$OU3%4$IUopH%RWxvL zSYX)&nYTI7fBB^fNvirVco6bsA^d&FfIq4`IVYLSPDN2P?NPTA9^ikXgK_h#JBlcS zt6F3BKFRQpPJD$q(1eZJ6p(Vo@5&Q%_L2tTERXMuA;V3qCxugcOulkw{HBbOj(BN5 z8q%uV=$%Fr44lBT#u(bMR6a<_3?i5JM)^41N1wob{I858wS4HQ8T~7Q0onKFwN!v; z5`yPxI+D+o=8&I{eoIuK+lO*f6pf&iRZI+j!Xv4j+CQC`M00+@p#r5FOVrY- zCR+hQn4x4vM3DTQ_T%A3Gcw8e`oS`dDn%M^x@tlD3`a)aCKFh51h@Xvzk0{?3_W2; zKiQnBjK0&&!Z?+(b4Nlf$(f{vh*>SxR7`{~-wVL_slEXm>P*4YCzETeBt?AwIetr!ei=OZJHEB+nEasf#n)?9RC8~Z@xmEwPL&MZP(hL z5@$GW^>?djtjWbi_C7*A~cKZe%t8Z_|!<`tAH}q(0|M}#%J>-$33I;%vo9W7OLdVF!}~g(gq0e z$a&)R67%(Bjx(}n?Qr`=`f5*?dy_QOEBv567Hz&k;SX6Kw+E&6!-opW5=kRMmlwr# zJB92e$SY6H=-({w$$dBCRUB(r5bL)$8fZ-h`CE=uru`xw#wX-XoJ5wY+cT_XN@Na-hD8`SHCDoUH@tGVpu8~E6zdu$u6uo^3xoCz6k z$QJQt^2r)LS(iJhKjm4XDQiG3NR}hC>x_=$3hC^NTc2M9z{w`b++$Nm%Y*6Uadf?> zj`+rOAbo6N(1tS&g0=@3H9XP|w$+TLGI9yhx(-M$WAtzOHJ*AcfD)*%c|uv854fboIx2 zy);l*PJHqSCHU}ZrT;Fj;EYUDs9FzMtJ z%{SfHHo;X4Xwf{X{`2zy^FXY5l=XMZqA7?O9*47d)!2pU_2u-sOTfTHb;hiv%(Trd z_(Zck+i_b*M6W~=?oH|D49(y%Sad^n`Z7f-n1FhgnQ2>%VR15=cLN0(0h~Mg+0f7~ z=HILZI)48=d|W*~F^1hva8c;a2~%l1Y%Gl9SBlfNXP?6HrWdssZ&c4L{_n@>d~y8o zXVD6dfS9dT`r316yQeIX!4*F^cbzjpqVwl_%;M`VX^m>OFLm+SZgsLbO87v@-XGZ0 z=T852v}KJlt+>pFM69eRN^ffX(l^U!LY{B^M2wOa zP#!`-A5#yyIi*MI4eF_#*sioGN5LHD5cIe8Ywd*bXEdPjyijCpzS{x7!C=dT83+dp zQ%;ID*h3eql!F0Gy0qOaWv)2GbqGRs;&q-)r#gz-=qPxNfcx%@VwHKbPqZ2ebDU{E zA3qzfXxMa zO!v4{ro%mqn%8S33sMWYsJHH;&RaF$5X~X(L!j1lyDHRuspe0EOhJ$Sr$yQY5^GF- z>Qtp{mJ;WF+UW#toVSq0EF<}xZPU9N#B8}DVw?1*n_uh-l*pXdl=nG6Y#hi<(+S5n6I^rumIJF$ z!*!ksE&wioS>iL?a?Drrs&CWp;Ey^haD@ka3X9R#32coZ3;M-DShru5wVme|2y%4m zV5j747=&rWzelmsdj0_`%4TYbVMPKIJn*?EP5-(VxMIVy(@!5V)cLx_aO+77g?a?g z+R-i{;D3OLS+Ig?W$m;@rd!w0+MUzmjE;6m_Z|)dRj-X_BW_a>~K?_h()Qqf!_} zW9!tSJklTI#_RagXQ}c{&t#vM26*rut9E59CH6?pU_0N9>z-($Af2|)Tf0^?6LG(# z%0wc~$|@diLO^gIqU_#XI_mQnOLAma_|cEwWe#a5RfPHqCoypdnl;#0lnNw1+^b}8 zoEBxL5#z<)F_ndj1WSh~AQq>S++EI>pDf<4A^aoonJL!Z45{ zsJE!JS=gfd8hD8uatoXBS{A{dNj}@#48A>-re=dcFR(747;DOi53I4GcRX{H8QCv> z`HvB*7+15KUUFBtXSJctmfq%_nOt1GrZ=!=2H;sLgEoDe0p4#rPA^&%?9GlKXnzttb3-32M@R7Z{Jf_k(BG?_Jy4-!#{LvbST zr4K|ium$t>qryo^b+0d%^ZbJG%IX_r2YXENQ0<<0W!#|`X`iYakbmNSO()1}ie^H? zC97TjgJvc8Q{so2xA@+4bCSJiMu{kZ>wOLo3co#unLxvfEwpk$hWt|7ebl^CB^W-0&RQTMekv9*J<9D7VB5MtaM zdd67D+;!hTe$BfH-5Q&U4A=|cU^Oa&n5P>Ovfoc|@YlshZ9`tkF%*7PsJ~hg>cscX zzF9hFX2f-f>-3VahF-q9ua3|wO5zDSbr8C6>qU?nN*t33vYRca=_&CsK06ObK_0t| zjDM2}Vmh(UxzgHk`)Dp8w1P6?ZrRibl%G~!f$uXObP2SlrSYSw8b%Swwmpf&eK}8M zkWGHiPO2S|6z^)8WdqCj#gSDu#ZBLzUiTrkPfKLFad`Q&XyXcyYAPn)AJNDlpK{KC z0SzgWa8;pbQ3xB>(O66*@EMIi#aO&Ojy55}o*N9{h{2^P&8%)ItBE_0W#!ePskl48 z`+F9HsDyAJNBc~P;V`ugOQpC0MT|}9xJ<}{t%MxDJLBY_B5OG;Sg{O798);gSV}0@ zpKEW(sZGV>Z8d{Tkh~weM%ebuQ*G4cyTry~XwKBtp%J2WI|q1IsGrsdGjxOHb54NG zB|9NwdHSt&w$C^T3Fn{cF03oNFvmL&Qnm61L`w4DXU3@53gGY?u^I;_hIh(`?d1V5 z)p*kmCoewIPoFZLGI7IoRnHQT%Q}f#_Tz0|7~zskK`HYH0P{U2W@V|?PmzMy9%3#F zZ%<9+H4S561r8<{HeDdyvN$pB{l-Coi|IQ(BZ!C#bJ>awiC|bQBQ}j8#4%W;feSbe zF@sryZnmaN{NLTu6Kc*-PQ`A^OzTcCOW;Pd*~H{J=I$+(Zb#WqL6mII7QBRKz+Kt7 z%njGv^q00coDq(%>cTVzUPH-mHLc=uc;V$-Na6HS-1!uPR6D(+)$J6=4?VE&g-_55 zH8i~IRWVZ*Rn~poXry_vN(|B&$f4oDtiGs>r2|mg$6yt! zEi!8WLBnJE;sV$c0(^t)jY>?-np289wn%934A~)zmb?qE}%#wZk zwtyD(KLKWAhJXj>{XS@EFZeN`I|AX+KWfg--a6z_kv%xUcgQ@zqY`8C>$C+&*^T zhoQgzzSJ9tqR)LQ``I{~`N73!bny6f=@x+d#Gi_G*N947mE{h&(YE&C7&xM^Tj^n^}P%(L^_ z9S0D|gG}|2z&~Rj$jW_dL#ax0pEC-!(Ek!D1(-BOZv)@n{zvI{oYN0ZKG~=*` zj8%5LRSe_@f~4aeetuL3OJ_Yb6?C*;I(jH%pRLJ-j2PrWCy;f(4AS$%W588K)C#n3+7z(L@W>*^CDMHu=iq!HzRVxNM?h~TCcLKmme*Nx3u<8sOPimQm<*yX zGL!+&PiSoe|B;E<4_=TyLgWAf3yAl`wJwW$EYFOfL8>)~vR02O6SX7}%VaC3E*z5Z zX>YJ|z9o~o_@mz^Mt18+8XoIM9Kv_cTa7$HwaOYBar(18d;(Bo$Cib0fb88|DnOdE zpH7y5(7?$SC6Tg#U=S7hh!iWzI(X~qX%3l;k%wC#KRm}ftpmMh zam`@U-^x(`)GYeaC$@`OZaBv)TCOZ zgVF$b;+NO|tUhi9DPAN5Z)3SPOw5M8{jmKv!msgPVtKFV@*zEOJaWjWTz(J{QW4%L zw6a=sx6Y2sXNV)5&xkyZ>dz0&H9lOF5xR1rBHZp=va>%PoI7WzATex9aYz+(Bm@j$s@*vIuVZpv7PnvTO9=cJ9W(RDO>ZY+ZU zoEj|b3XSIfFp-G)apJuY@I=7DiJSL}rYu4yyF(EiTymjC#m&)&%pxdnh;yR^Z(Q1a zfm)%Pf%kR&&iq=pZQ&G8EI$=jqsCa7?60vPsOxuvi#>`22*n&nULh!c;nlX z&r(>1>t0Lzgs`eI-u&6-zr(iwiBS3JE|1`!#~L6VaLjMpfiSI=F&8nFsFWK_OeZ{e6_k2! zWp3ogor~}&fOPqlfncC$Oqb5~O zsLV9BN5|S&80o#1fafcLsW|EGw!*!vb0s2#9)crVtzAy)7jf>K2oY)^eWvZ)-`h$c z(ugvKzQRpiAPpHtuTVrT{*NW7k-=ACYUT%Vu1)aL$bD8L^M;L3<>7pWEyi!X9-fj} z8#EB!WYdNO6P9!ImLG4Gb`;)p0EEHX%$1Du-vQ1$({Q4B^uWrNjQ*4z;o6kgR{v6_ zb_E5&$-gD$)bqm1Ifnut+`YUMh1%u(se*T*5~+&ac@GZvL1QA`f%f;yDV8-X6A}+$Ry?5z39VUdYnd#`Q^Qwgsm$sHfN?%6rM7P4f}#V})>Ku%Gnw?@NUa&w zW@p;S$UNqr?@UsoexT94!)nGKlBHlXs9U59>n9GyS1>9GQI4k!gI_CDONHyNg>EIT z4z9nN4@OFltg?m8pjgH%glB8fojmmV(Qul!V*>1Mod%j#a6}21Ed?4>s!Ts`__A3e zfI_V^N^3jbeN(Cyi*@zR10zdy0r>i{Jwlce2&LZF?p8QoGI|z&NbSDV^+kvt8TJ09 zG0HW4Nx(K&TeT3n;a|d{l6x-8Sg}@&aECDqMD4L5mfr96 zc%+8z3~N1e8!BZ88xO%w19TtCFO>+Y)Pn+6T@Fot*4tVzjnZH;X@DnvSH!9AK9xKa^V5#g!6h$z(d;u z<9&bTu`O7!0D~YmV$UKRYuy>iacxYH_ov61w?=lN+z!N#_e&V@-2t%E$1BicS?3&7 zr*1TQV8plqyZ3!i0TyVAQL^q&V)NJjstLOim1FMcrh1B25p?y3gd}4;2*IKVx8Fhk zyNgcm7R2;qd)Nl^#s=*vkdDdmq%CUyt-cKU+a$f@BxKscc%s;nl&fr?^j475Ercg2 zk8~XXVFtCrZ9vGM846@S+KD+V6!eq=4R~!zE;heVM=Fdlg49L!)k+A-tM9I9`$}Sg zpa$&3!h&W0KA3^dtG`H%JfOLqRDG$jN;-CxsG2b_GP#IiW~Z78dU(fNWCpAW!;1Z0 z8T{wh>?f|(Vm$3RT}mzjA>)r`a(}{$QUGJII-u&L9)uNviK6mv1KL&tE?;0OMa>W? z?CH2F+%)2q`UM|%ur&A9bXzv-!?M7TvoBO;p#BApDmtT3qNfE z^h0*R6` z`wt9-&V-#NWne|TD|Z{=W@I)Lx8wRac5zmsuj7|CF)zr>nfl%C+bCN9w;P?YlJdHq`ZrlzvM30!zrSu5b08N2~!NjVv6{c*oD8v7?ZeuZtleZw{~vGbHy;Dw*T$ zAO2;N(UHZ4&B4>7aezyebB{l={bEZk;t8>!{dcYXUx)xta78}XV&4Ws_p7l$pWUPk zTwW!`ZEJHf!5`_L@zO}f=-HC;-v5SClel`pgC7mLm#qWiunHiTip7yAUCGA!XwicQ zZF6a196AFR9a=B6ELO8v-Yhru5-o`BS2>}rg`z`(PX#KoH^)k+@yQ8b;&J@Jvpa9k zBCXf`gKP9$QUCy2(b7^tLhk`JN^E%meDGi=yPy1E_eYx&sHFNGC-elXmPh#lTQwd` z^!BQ+s@b~-W0D4Aqn=%zBG8*jv9lysJ%@Z8QGt_r*cIF}B{O47jEe)Qy@^`bKS_uX zF#!BV`u)s#Bi4mbKP-{4VM&ruS}ZP-B=CqFO*xh!P0GApg0M3K?HGHz5-Be?x5P?s ziQ>deom5@dI{s8jolqL3Og$HJExY#=ht#Qdn_ed0N2dJreyd9eY6tn22b1}E-X zkvj7>4Z&^DEOb(imN}nHq2@Pi``xm%o$V5woDMN}{kcSXjql$8QYN*^4Rd7K>bE`C zsmw!#KuZuLmeRyC-jFSUsS@*n26wIzbS%|J5%E3e-F4?9^h55)woIb;EM6tSL$Ev5 zZ7O(%>MVAAJ&Ek<-1=||L_ZKaKU?0FO z4>qWUh0k27l7c00cG(>F_hLb36&2V55>a8_xX>jZ%^waER=h| zV_}FNvUtZ8da6IIRL$Ld9|?9==sq6<#QYkQGrsy=3m~-Fkf6rl8`Bc1wgo-il76L% zFV=lS`855`1+!VxVX75r2-X|T|Xx5!jQN@Zh zAY7*eGt3r$gMIpI1L*1fJL0%yT`1y?I$^L3-_QQH4QQfltxy`w7OI%}Vl}RmQSdoM z^dFfIKSZ{Il<~He{Kr>jOpEz?SZQjPuWmx>CoXGWfiB0J(FmYt*3h5hx+w%rBQpRo zP!iEq!n?(@@G#r9UstGL=ZLEaUgR*Ft_q!Ok6EMD99wrG1EzWV^=$rX`=o4=`G=UX z=+Zl%#88pZ?Ye3ntl0oVPxO@@=m9im4&gXW*TmGOzc=W-VI4DgvU6yX0Yb@u#3hBT z>isD=oPivBt+|DeM4g4F;S){LmA0?pv^w?4i|}01XU(d9?wPv@j8x-mif_9Byvp-h zQqb4b(>3u-=I#kWQXHiv zzt~$SQwrZ7U>lg>>7r4+yka?-B!GrZ`r3oLM61z{gbmJw;=E4Z&o!k! z&n5{}(T1(4X{Yplf_>7Y)i_I{6o6syf32r{VIZ68NhQbxQl1CZe{|ZzkVw1iDc3b2i2_rrqguZJwPtRxBnJLSQKF5g^J-MMG`{=wdR@=Tw+h9lzmEetUf}e zR4Z{BQJS)R%}57N^oVqVW74BSgC^K|m1>FZj|W~^T>FoA*$6!zvDs#KDWk4A0N;{#|JO<1#rYa=KRP)8&QIk2<#TJB#=kE$M6=OmRHpFEC3= zak6K$|KTxltP>>o4Abi}UG^o72NO&2rc(-Ko+yjDzjBWY_Gx#M8vE%A7&XjcV*L}J znuZMI2UaT5U;ED(k;p{QP`-+;ETl$dWc7ANJO7P-DdwK|_aJ3u2-D(IscH+P1zs6E z*Whmcr1JZw9}x4(^Vm+@O3-nx0ya8o&x@m@>JFwO0{Hz9VNT&5wDK!c{%G&V+Co3x zwRLJ0R^u_u9yLn#saY%_>X>wf{fV=hBuw$rH%q!~^lv<_w_H;Lt=U@l84baNw8UJW zZ2VTVv~`FRu_||mCY4TG1_?i)rU3LBs}?3M`!2DW&-QwOwM=QQwnt9@i_LlgrB%frjYxzX|EWJ=J$lOWa?On=NTW^yfU^WCk zDd8i;E*&5Bwg%WVrNdbaqQ-#d8FYiBsSGIG%LAP$>RkghL;vIhWjS2wUl~h@f*hNx zR75t5y$LE_X4GbS%`7tua%k;3)l|3!>IB#fEVBfrX6|I#u3&bXgNoc#W7$0>W*SOJmd4=mL+sM*Iz{J;AAvZ3FD4W$Sc9hFk zuUV%DyiPec8{Ur`u^fOn(ZEJGg7|LErw;u`0s84NvU?M=_*Ml^p*eRL&I16Thju!= zK?Xz`+UMmFyJ?-JLtc{JMs}ky2x5T9*ADrrG}5{6;{rrG6O_`az_yJ>^By?@zYpIp zI?TFIE{z?i?*%oPc_Pxp{QEj@h#qJJG~s4jwL(Y7_?3jEXU>$b5;fE0rVJdeokH8E zR4)J2NoH4GW#V;hUaj6065b$Prqtvo?(z~^%DP=LG|I^Glt!S*OqZmswpTzx4FtPb zfd93*pI?#GJ=#6M8e&h6N>X%GJ?eZV=g@iizog5jYa$?33Z9!&8Mc7jGAF40!=gmv ze>F@sWAl1}Z{)*P9!I^@=m`IgQ&jv?-N<-$F3cgR;^-={k?(!JA;0HB?&-5dY>syO za^yPrp7(wSc2A|i9^S^=*^`cw`&{V#qy6r>{81^pz2~%thF(x|bSWzOLYSaZY)ip$Srwk+z>4a<`HcI z=}O#0f>iz9Nez6$IoU04D1d5y4S(5)?evxi@0dLgi+FuDK9O0kqke6(KJ|wFj7hjX zQ^?`!=lP%wiR@}^laJ-aP4Z!Nh2=eu#=*k&ixRDgsoYjWpQ?#Z^ccmm7yWGR=S47$ z`1XU;TL1fX$^H9!clS$xg&s}ZAsSJcmd=Fg|>&S;Z#*FEuh^BFXScwhve* zYazZ5MKqw{eHKM=aIIRAu~u!?-m3gP-93Nx#GnVI;^AZTB_nHtdYq8kU>G;Lm2lfH zcUSK5B!C0rHfn&)_|%HwEv4`-_<_cyg}?SSi|MNj4gJfU#KS}8{bB#W<{A3&-ArAt zu>Evxko(t=;liIwZ1@&{IU+-#h8T$_Ct5Vj)UC12SI%axcj&S@O&$<-g4RxGdukGj zNv5cFW^H6Rb$Aeez(Ifidp_|F6X+DuHj5rCG?ZUitw=)%>w10*S(8!-I1=@}4}7n! zk>;wxkS!rXDc=|jyIFaGJkb1oihzu*9bL3u>ga-$#anxI#hevpu7CbTd+hG1X`76d z|A#8mMC=eJVQB{VJfDd)?nB*N0)hfe43%Anx1);Jp%|*=nd*cz7|Or0+$N^m0m%29 zh4Q`F+@*FgUO77xM-XNqLsSCT*sK_(8I2Zx7TPR=1lxR6|bRRd~dvdf_>?hh#Tn(^n+I zr*Sn+7xGl;9|kvbTh5m$ueYx`yw)3vWO>Ec#C+xIlq`%$ru#Wyt=(u{8u z%Jb-9Avxe2{s|Nhr4KK=b-~*m4TNR_m~a5}g`}(yC>rs&HSk4o76c|H8;O+GzIj4; zh_ruXHZB1T@CSLyPu0280ZPFdGziykAeh+s7-y(aIXj4>D}aM{oa76h5-s$@4{?}; z`CaRg-0K|>=jEm7aw|43Zwh%}C`CsBNl(a(!kw?Q6U=k^XofL2C*$v8Tj6Jvtibk6 z;~y(?teO19mq2n|A<`@9?7TAd_p?(u2laf<>rDc+`na|n-!jUy$_k@3(*A%zk9gap zVCCYbcBePx`jIWX!Ac?BvbDqcV_2Qil#r&+hSp{p*b2JW3WTk`CUQH=4Jm8J)=33S z8k4KAY}ZSHvlm~Y$Ch?=PYN1r zw$5zFi=f%BLl%pb%jc4lq2;jbF#TVl%H|L>w7g*SXZy>4G5&uo|H#^iEVE2jk~B|g z!)p1P6rT05Z|bvU>`~PrVVd|AGBut=J~rLX7NJzdRAj&0z2wY9g{&I;rf*Gc8r*xCzIEH~raX7LnRYZp{6+Sho z`WEgO$RaSi5^Pr(vATITNYHAtH7B*pEN@DG$6t#fOdL8;BYsYVV*}C_U@zR!^HPk9 zfd(14S3e-t2yg)W>vStIO_&&_HHmro=F(DsA4NiNQ~UoRulS(qFBg#LzHv4ig#GC& zL&K^iJ)o(p_$~#b#YLkOF21iy`=LATwqqys?UU!8u&T^No}#C%3e29imyqxk8egwX_`TxiXwWcl#sn&QDuhlNGnd8 zw+Ui=;e&`=m_l^fa1yIYqE49u&{?_A5ydQ!^#3T98tV8-=o0l5?(nOsu z&Ek_G^YI8oX*Lh3!uvgQbOtO22;EvZ9oigA$IgYP!q~C9>`Es`qWjJpacb!@5+WcE zdQ4;`&@x{)W3$V^+PRL0h6Z>>8d81v3hz6q+P!rJv#fNj|O_N=cA2x$EVk{ zcRokKTwl!38edP6E}bjm*kmuVU{l&EDJ-mBp>8>*$;&;_#V?7$F6mOv5yoO z8ruKM396uiWm$}FTtkYn9RJ)IbgbuiDohEPl!x3%?gxyUk?mXe_8tZ4D>(b@MV1xX z+xBRh-1=A*-wBY{EHmtgOdLL8^@Z<|)l z%%DJiIQiSUR$VOz7|IikuDcd*!5y0_28FD0zl4r4#lbNWTcu^81o+DQ7u4iQDS?fx zMZumdlOL{Vup5YpqP`s;B;j3WhMY+j-&OIdVQU~8h!cuL+pDX&xq2P`hyZN81ymlr zw=X;o?(R_B-QC^Y-Jv)XcZUKk?oM&{;_mKH+@(lyr(E9m{LlH$z3Y2c)|yNvPbSIE zmX+E0Z3G4cm6`NIHRba+k(cs?3D=6{HhEeaC&JORBX6oIbgfv9TFGwb%Lf4}C_xpo zdkVhjRi7@$B`F1rpwc<}FL}BX(xe*F>J6Y2Z30u& zNq6hzsc6Zd3MIckp@rO%L_Tw;>|MWk(M}GEm|FC=r5v;@E-^+!rIB)RXUNZyt=DzV z+RwW7$;fr01yH+j)m@6y_5-I+Xo_kFH~1?ma?15&||gu(rZnzXljiP%k4lxPVz}7QM_|AN^YSg3Z1FOyq+tAeBPRL zWfZk?p7Vnh2fCt$XJ2CUm>ggF205QN^y2Nem`(sHgjOnJ?(F1TnyeOO{0Xzm_ksgKfPhr4QI?WA*{QwuZ!(h&G?rlIw@5UY{ArnVAxR&%DG zX=On^ia;ju((2bwmAzrkRIG8e!L19Ki;P%GxU#!)x;-0)dNrnlK3vKQed7p{Ut(N; zZY^eCtE3I`$<{=9nMXkBe}7lw3Bc>{nGHml%~zo?p_(JoaBJc@pp1`6^IoNXac@ME znHDXZ{=O*pi75dDQG#k9^Rx94n$~vJ!8c9{hXsXjs2eK`wqaMPxSU?TcS$-DQf{~O zF0r`}LQ-v1)Jq&%5p}%BRde3Kvqs~zPj=2!DoCVuc72B~T1RAtq0KmSa#W$0Xax3N zex2*OiYyW#MZ&mTG$|{m_!qV_i)A^ZXR%!S4+ZqHpig;6f{rSFu1+ss%l)Ihj2%UW z(OUOFw|);!rn4P-dawZwznmdHQ<-zon};l^<4_ytXeySH>>2gl31IsXN%w9alqYdk z{-mV;3r`aeI1O*ql8b|S0ss)MpxmRFe<3SHxz$fIuSkoxF5!i9a_FxMC`sX%4itH^ zS^+A9V6>mKJey9-u0NG@WQh~9$1n8xYr&rAP`4z~3M5v0l_*V05!D{4?h}-LeDP)a z#TDxK-F^91Dafn_LE;iM8Cg>!-j&PE5)%zXC71u3?}vl%Gn@wrH{JK$F(;1*ffB-j zQ|DZ{LrO!a#yB0u!H2u3Z-$H{$3LP|>iKMSq6RLa*d$sZDTK z)`}JJW`aNcAt3f8#*86sYyfx+z^}?Vyjz9(zZsPIpLr?1Fl*jS`9ukx(h-B|^)XX8ha%31hAB8IZ^2*ZG(_2sPL))Ss}uL2u|B(8`2^E&?S`3Js$^ zkpuI6JKZDJ-Qta9SMNM6%NCdrW+M1l_cdvo$fpnN_Go?3YBND{p*4^_9@eFQa~-64 zChFZi>Dn<~WzN%xXEzw9$+qIW9N=fHdXd~jssp~0t!y&ld}3Mjt|kLXk`Bq80t9qB zG_)48x+M$)5|v+G7)hwgMTL-HOg!3HCP-36hB|+v+R);Bz7$b@2&?0rNKPe*FvEvO zpNGUWDAAG=;2^b|Uyl&k*1ZGO{af}TB5!3-ffouW#L z>x1SG5pyyBi%g*Fk=p6}hS^p7u|ZpCyyMEM{@fNzM=G4TK$ku@46$dp-fQvb=Ff2m zoim+!Yx*Jos_Q;QwxXf5Eqfae4oYs@`mkU;s^xlP+HqqAl~W|6cZS~+%*Zyv<#=S7 zZm80gAxwn@Cw`+eg7B{B;t#gqV0LKhGs&?20rr3 zu)5ev@u)R)a}Yz8t%F%6V3mvuCmEDd@J=XCJ>jK}P6lkEwibWm51ek;AMoZU@`Mrb z4$Aki(ity8!F{O03bHSR;vAU~8~7ldeC`pZn^}(YtRMaFYpCyMg>^Sm%bnkF*eFF+ z7{FO&(xl(uNqI*A=MQ+J54pqjA$KbONABdgHl8w&M8v;ufxC5&=^Gb@_RYk$2t!zz zYUWp(qkT4DrMJ{M?#!HpE63hwKq-x)=l@2N%AqiV$&tBj6Py*6kY~NO8RL1fBc!T9 zF3fidNv}aBxj<{c%bVS0Ph+v|wCDLAcGgfqB2P4g*0>CfgSx%+@g)hjK96@!J>)&g zWPu07{#wdA#Cu;=oLKV#O9-~+6X?tBIIlT~MuyC&$?&;?16}@Gf(0KOEs8;KnNTX`iKZwHOlGRG zj6CN&kJg}qZHR2Bjm0x-hcIeAPROp%#aNiyyDFU69b~_D)Oi!lNbE13kHBiyk#5v- z2-%f?7Q-a0Rmqg+?T12A>*Y4xIE~(hr?)sZT{*8lf75xpeHwY)leNiO>bEsb72n8}W7B5R z$xNIUanj=<3nGmpVoB>hXRg9UR!yZR`O?vFHcK)$;WAQ#(EMD#9FDp^*D;K=nf`>f zzeU!&r~<&JS+>%x(aVl3M@*sUd#q1 zrboy3VheP=fgytxUYLpWl@PV4Ji{+gs23J`bRkD8P(I`Kw3+Y@vcUNnErs>egCWTwdD2r@}^EiT;qZruUnl zvmL~#lO~bAsd-)uNn9cAQEll}gGnPH-4(AHVd(wz6OWACD1}3RgsLIOM^N6fl`SGG z_|<#!0V=%mAvz}h6&;Lr;#0i?2dApv-$y4!mn3PyqX4>h;YuBF+N;W&^Ran_`Xv+! zyK8DO#1(aL3SGr4gk#L{(Xqv~W&flc&&HoGkM@i^!2|_5#2SE_WBJyozF>#3O3_j3 z`3VJQ0zXWS7Q>;i0CI0+Y4B~Gz6YAw5M?dCulbzBQMmc0CggrR^-?d;+p+w$fF zIds!o7HRoOT_J1H-)*gF$A10>f2~O9A&O)3y96kleX?3j_Y#s@V>126%mkhVfAtl@ zbRarvSUC7vLqPtFDM6+g|K-BYH^z@x?fhwBw0e%mdA(no*=p~Nd4r+j98sdW)HdDw zG@65AEV=|n_L0`nyKp+;TcbpdEX*rAHuugL!;i=ux=rdK;_C@xG}ij@TEP`eF~#W6 zm&_E4aGu*=;hW9F-kxmCWtEFDK_M6TQT}d_py9du^Ap`-ISIuZ94Rtlja6&zem|d5 z=3CDe`a zWZn`YWDcp#qDzCREkmokh{>v#USFaVP&%UG3ghDT?GfD z4b|}y`)a-$_j_06@p8=|(TXm*&0hxvD#muzB2ZY5(`zGeQDX{+OglmbED*0CpmEas z+lU||PA9pTG4g3EA%13DjQJ$Elq?)u(UX!NZi*$d{-Hy{?N{AvRmnXwo0kdfQ#G5& zAKMWSEU|sWZR8Vmn&N03)la)0fqI8h&}h~2-WZQipMK8JcLg2`*hwR` zE&zO})r+avWV{Vd(u$Q`ZUBEtVM8O0fEn;jV6l6=f8WIM4I{MqT|%f0J`y+{bK+-` zymQxApxF*J`3=iY6lWsig<1($dlTZc0#NatPm z)Bi<)Xp#;TBFko0u#VpI|8ti~slfuajOb2_pqm34t{B7j{0mcH{YO2P;nsgog*9Ru zY5v!YSYSHf8LEuUSscPv^ATKO$mNkSG??VsLU}e%$u(M8;P_Wl&r<#PMjC&;n*`Lj z8NkI1n0@#nf^I&R5B3!q!8}1mD zO@!q(6d6+#Bph|^r~`pDElBytff&3f`Pd+s9!_zl<*$}Z(zd=L&tv$ZRRNx(J1*93IZ417AapFxpPH~stlYW4Ik=8uA^+`MF3H`w5qK_524`V`dV>dR6~yir278v5 z{`1_eS6te=32et}u#uDeXh0U&k`z;>#Sy(NQ^l3Ln+B2qwZY^MvhRM7{l8%LMR{zL zM8lCR^Ts@JY93Uj;{dlg;b~=EwFQ-e-T+0Lr!Oy4e6?!Lfo_7@;X5QALvv%FPaj7vl5fE@MOjkb_50jS_W?}#K%>6wr7BFaX{^yJpF{{1 zwjaJqlBjlKMMV`4%+LI_H}G=vtj98E+PUuw^k~8s0w%aHi=b#+uDlg^Pqx4p@i0CV z^wE#pu)T=uU%-+{VPnw-iuqHibZJm04(goX$>=O8VCOlX?V zkn0~*rV`2Afyxus`>)^s2cHiPpgOevG0R5~W+ezBrNFg^noDvAn8VZPw*eZ&4zN;P zKJ9KHo*Q6^Gbh3!pfCs8K*9_qftGFX~g|hflUp!wBH#Rcnw~ zFXw*IW*s*y+PoeRh^TJ}Xd*BGe&%h+V?Ak8`dO4+yAG~IP~(;UJAKAbR-2L9%Ylk9 zi)}}PcY#H<$R28+3EirqSRVmnP{4EoR`fXQQ}v8>ERiLET9>+5j;iB^H#*BKC>p*0 zcT2xrVso#Y4<%XMl1(x+4f8VaUP3bvTzpv+;_>D%;W^PMZK;PzCYC;Fv<=W~Jp7Wm z^F!H+N)k}P29pXE_wz@3if1}u<7ZntIVl6t)Pb_d`f@$&ro)<@tvJ1_i;_vxZ?+7U zFSRQO>C8Psb!(qA%gwrCP!G%h3Ua*twxk%N@4CHtcOLi!9);>uP;3t!(AGiDfLeO* zVSQ^v;fr(ymQgCoxy*&|<0ra~=3#7@aCgKyA-CI#(ug>|_l3hcIymft@4^I}@=E>xxdM`0Ek}_$)cW%;7u&I_H4yVHh|DM1S5n|x@@Qo%cASP|W z+r{1{0U5rWkA%pH*Atny_iu3Q%9h>UAl%qC zRE$Gr-B?SBAviB%uPjyyWTKVXc0SkzAC!CfUpt#Z!pP&0K2ZDs`xXj-^}J2mOG2cK zcu6pN+^Ncn(N+hr(Ffwf?sR-H*2cZk!0y2d1Xy5{WpdgK_7Tu~0{ft$By;FJ;XOfL zcEn1t0;YQEgEomV?TvYf1Cfs_QZucA`)t>VCnG);_Dmpo(HG;gL(CcF8?Ecsz|_oM zR0mFzd6*W(pw3W|d{ic@SLuoBc)DnG)7KFaxL+Va(iP72(6!`Q!iK z06;pwu$;_u$Ipg!hJu0zCD= zQyBnxL$A6cvVL|2Fm57MqTr*Hfg0rLeBBqkd0|>lMd(tffBD<_gM`o@eLVY5AE7SF z0EoGft4fX*0Duy-5(e`^B_;&20zs#pGk|VAR4D*dANK&%j@DeCdx8?DJf#7U!5Dxc z-vbLn7SLbU17-uDCTQ7M1Nf_}8bW_*RXgv9ezeeMu^!YLw7rtnqxCIyUE*N#hjG2Y ziTsd5X>xxFcAdp+iCMfSz8r{OKXmxTZ-^Vd>I4@epo7#=d$y-6VUh~f9gpza<>j|+ zh^N@4yAvFiu&=v0CbL=~kE$c%(U3C0wA`gnY-z^!Su05O#~hK+cjY+x9)R%7UY<8_ zO2L!)_q2_2Dng4l+Z#sBA{3ZnEo%)!>xQ!=T0Q|Ddry``_I7_{xuP-)u|Z5OzCJ2()$E+ zb9fXN_LuUv0AT>6!H1CAA%&6X3qJThvt*@TI3PG0?p8pQG6aCO1KtB+3S>a={qC8? zEXmed{TMIhC&2(vY;QG0wpw)_3boslonqba7~SKyE$?|YES~e6Dh&V)hF*cVtu()( zB!#=9YT2>^C_py#=$z`ljVJ{;7_;9+E2Q_C0`Yyp)_Rp@HCrpOouvDNw^7NBe92OT zxv6b}1(n79<+)R>&V$u>HFhM{X=Zp_1hS5*>zWI3qJ{_J2{ptEf3UcGLb(Ey_37~l zc?`s@D{Pr=ea7*~Dae!G%-bn#I#4;bUajhHN+7xxUfA$CM>kRJa9vL$kNY|(1bO>Z zYt~bG3v2dU)0m^YhHtIsfGF7=BFjK?{-TrYYdR%Vs$TmB&Y>tM9gDyUO0OBB2Ng;w z2`X9lJCx-6767j!u_k-%7Ai~*>&%i}l{1?N2o)16bBg7`V<9CN2maNuKco4sMHYs$ zIim~^*uDRCKsA@E669SNi$oX7AZE5eO%AxEY9OB5mr*52sp(hkGPUEX>ay96>7{wn{*&j2%bsFKG!<}Ffs3=r045p9(KkbkMGV(J;`jYZsk9G0 zDU{dbgYb-?91#7#8!$q`NX1`R0Ri*RoHGCbnZ_eE>AlBUW7kj#Z3%30%JuVDP#75d_8ePf7$){wm(Rc1WIJ+IB&Dq;TD8Jt|ZzO>DBe7IB|Yzq6{AO9o^B=^y8iz6%!xiNr|8 zH&iMhKEXXvJm9=oF9n(UPH?V&0t+c*_mZnZfa^1T85Fmc9YD*wpWKe-eib|@%>||X zR7O0A;_X>n7!@~$wY9_}od96J3R^Pkr*X%;0(`hMoQdW;Kb5iH2J&FkxnC(C3!bXF zl?k;R@h3APb&q-pbHmr+Qj(5)=UM>Lfp_pFfgmL5CT9czx;;{!SDc}AP|KKMjQYTJV6Wu+ctABCV5b=2cF%Tiq*+zga;%OJ7fv`>@7)8x0xuXcSdKsLaVyG{8lo7obwI^8ju5 z%`$L^;6i%nJMPA`uMn-u@PeNiWyW#9s0%dHR2n=P#ciQ+8}c5_{Ktu1^TR$NYcW%B z3*$ln4EvoQLk<2Is@;Ev`X9-Hmh@qheGE<&fUjB&{J+HwIDj$(fGQ0BDTVK`2~_Jr zdIUUrf?!~P4v-fi0HTW+4utf%N0<1g1_%QHd~5&Hf*W`#04ZP$R^iS!hb zDA4~l`cDJ@D}k%S_W(pg+kizNXtdlwGSe&F?{2-ezlSW|daV5&i-=oXi{mXqH`lqwvMa^E^m zgq==G#^SMH-6vkFYC-VyP5dWnPRmF+q3&Re_FR8C1Sql1c|JZDBxBGE&K9KMx(bEH z2VM)wkYk{}2mpL`-_b5AwV(ngM$|vOi__rcs&Sg z6y=^UvPsar!cd57GZ2Nfwo1aR!m}C_Wgaw`Qva8HbKl!sD#FWMcH9(eym8mwaZ4%d zm0Bf~gN;)*IdK!t^cZkv=h~;+PhB@V|Dg-{^@e$^3w(`w!e|Xt;7zis^d+(kRy$ao z@K*<_6;Z@`6M7FD)^AWpos>4F({GTD(fkyLFo5W26k78Gx!yat(HU(O!eaQCrUzC- z1>K_`i7f081`@BLls`E;*^69=01UGk!E%U3yN>jBg_FNqRyrL2d}ar(3+N|+IGQo| z-~{S9kqofn{~xmi^+0MVS6tq4#}DSDHqNGL2@jBt3>H>?Y6^B-^5Rs|H_!*5Z}^$*-d$@@lBvPb*e~_PCJj$9xnObGD{^p zuhKnZalW;)+eFK&I`5S94BC0tCrRYQWqi4lP=#V5UtmE|0cQiwsLx@D+q?&RL)Zd* z4gNgwb{)&YucAck>SgzTUf_cx%5>zvPeh(Oe#d>oE^}W!pv=a&RvshFlj?rLWbB== zTz>I`H2Rx-0^qGU6PgBp{{0l-(E;%6H_#ZhnIst2E7W@&j3JwWJz%z{Hq*|C%4{+V zg;Su}hdcbPXDEN)EF%ghc|{(q*8Zhzwy~*@df6nIV|Tu_QK)faj@QPhzq3nbPUR+@ z74H!>Lo;hH1NjE?wPOW8sPEy4wgG8ey}8pb){uHviz2uNdxO!s zEDER*sQp#9*39>rBy)zs=9-xTg^tAc$wmN-+>g8FYPDI*Y z75l4F>UZM!&0tBzbB~_De4|tM?`c?UHl#&=MnY$L{KK&yUQ^=oTUFv9L4%ANttd&*a?BM z1$ny$E#qO-jnDY8(RtphzO`T-!U%wKc7q(KAh66x;pM#%j@U08wir&faj`4>`F+BEn^|WfY=>G-Ryq8o z3~9)d`13g0dDHgG&LgpYYxTn+T{f7CuOLr}9q(;1c#P>#jQzzX<2ee>DFRfnsDO){ z%cpEx%ZU#cj3;6o_ux67JB~o_b>9$tg3$+<0h(*!HUG+%R!rZ5{G1gi1z}{vHm4s= zG?l7U*015Xl7&y2x8kx=jHpe83EvEo!)+Jndg+~*)pf5@inI49wtQEeZ48&UuyF>m z!;q=oSbPvwen|CbdIQ2=bz!gta3idmq!zcP0R+>c0If!DTfz%C$HHs^p~R zkdYAyHu0Tmi=$rEs%R)g@u&D4{jBQSnxogg}B0-P`=Wi;xOmLxkzwqswm=3?W2nxQ9iB@%|jHcYz=aIy@ z6l^FbuNvQOmQ=sAEWu=^HA>w*zC>rs=&5gSMWy#LA5IMl&zE^R;d`b|^lMC+8YbS; zW3a5WX>NvF=wz;vU7+%nS3KsqE_ykvn5tIRR?0$xS5~Em|I(0cW^D{_n)R&1ZiL^s zUVEsYCZfNONVWS4&%x*tP|V?|8_-kKDi*-c#xxoNc^z?A>h{Nk7=H|#G?PqoK3;|I zv}Yo1Y(Hq_8d^3e@|$s-Xt$O$_QflAY9l$}KxdQv)9TXwB>65LUpY1M{xejL1UMmS zSBk7Fsv1xY#(mk9&9uo_&s(a@Bf?P1bTqHxJEre0mo05;`iYI6Ii1Sv78^N`DD=rB`RU7ZNLVOsntuUAg~h^Bbu#vG@N!JxnMV0!RVc#{2HNf|NW|( zIYIvxag15^#ePA*GU~792GI^TPyc1Zbm99!FTE9SENkm56cO&%)`9d=<#e{mYW;N# zEmdqb)X2>>s`>>NEP@(*{pST>W%7Mvte8_cYt_ce3qwFf<|z#eI%i4z8OUSWK)p(lk-NE??;+*Ni*f z`2ed-RyGP$4j^^uX9U%C&Cd^etG1*K$~44;N(Cv@Bq~kUT8STdr^Zo~qJ>rLJ-rOy z26l?;rCRn_(7pR%<4||q-e1x>J-LY%zTR$bilC+6jGsOU4#(V{iz*mNe`-xM!oVVm zYN2Xos4#z;uZSd(FIP_@ba6QYe$U|P`2)jX<@z=-`wD86;9`{?my3tt&I z{(F@|mG|uiTTnbw0keyNp6wy}cN^)UN)B$DU7v3W`n6{?oj%k(g34eD|l< zQ{wWB>WhXg=jmcd7*OXmB=k_>o9Jm6c%zV|=tb>dgH&$HNn`Xn|4{L7Xu^2dOWO)=>`rxD!GNKdhgr>FSUZp3k3a6Q zSa4z_?Y5VeKVf6A$iPPoJAXk?yb6Kqn@huiYaS5}e678K`h>s(V}CdGJ$p4sT`yyX zec_Mej>zSrD4ZoLme1+5DI5@ab$tQnWk#lUbp=rr!mkWlSY)r?Tb_bhbLu~eYo$Xf zg^ktaKQZDVkMpO>(&F1m__yg(M4EnHJA6196=EF<;h$x&TOVlEv5FoKhI|+F^a{>#b%Ga8L*ymNuKu@_+Ye~?!nvFo;$87W-(cZz4P8yprfKY z?D|l?V>Vi* z_EnK_tQlgrAbF>%z(5FH_-v%&SBN4N^)!Yy5@%v^D0=U&b^$J7SwQ zmb1SoS!cl!SyKz;g_;~ua6ea7is^|Rsxffirj?tjC=0%wmi9j9+C}NF=;#N+A_Y9= z^=9eO!@rHH4z}mVS!2?_dQl83@O0<>ib)yeP=wgTHC=d)7XpNEzUmI*x8%e2kpAs@ zq>#@oG6C2teKqJ+Cbt}1Juv&9;41&Rz$wPi=SP4yn#%eN31?9tDGny4Qle%?j_4-+ zO%Zp+3>1QI$hYM7R?%s&XSYOJhj!RO@$QJzDpi7F@3(9}IgNnTZNr|JmlN@G)R6NR z;JH^!lx^%!Skfjf%VjKxzA>AsiLtKj)8s7DZ!RM zQWaie7o&-G3fQ_Wf>Pa+F^$X(Z&z)#t(m^exnbSrZ*&AgnqO1W#C4-MUk+JdrO_>w zj(YlN#iQR97ntf!7^7L-b|l0<-2Dz-d3|YcO<)y@<&#KT#wzRyp7(inGOl1{{`y>> z-rjN7bM$wd)i8!T*xbUUF^7~~zY}@*#=RS1uPlDD$0`i-SCmR zfH{RqAAs&^!22M}p?wd8vJSw?Frzd>f9b(OPbCDf;0Q`4HIsEh*|PmiOV7Edspxx|R2*cF zuuT4@wMa5P=Zzb+MDbOgL&G{_p4Q;^s)0v!+KO-Ez28u*?egz#Whg=~K5t$W0rTDk znO8(QXdaIjSL#5QJ$a;&B6H5?1^F6_w>!Hc6F%JcinC=Lx?kCgLF(j51qQ?~$X%j; zkD$R-n)?bMH4hQV7?ud-3TAtltnGh6)3ZRxI_#niS4!a};b>Ug%$(QPjN%+YFB4Dr zl1BH#DP0%pq8;WeV4C(o=NxoPZDBD*sLePi_qT7g2)A*SIje1zr@V)ioKPV}2n!W^ ze1Zh8ovjJSK+xHkd<9RWJ|GaL5F=3kBQ{LL1Uvp!oqNZX2j0$;cj>`14ZD_Wp)qAL zm$rR_gPy@Ga8@n0?-!Ox?S8CtQz+b|O#iW+-d1mAXDeD~7CyGt|#4k!kWU6?Bw#KQ}&`4_v@ zPo8z>FhG zN;}#1B(DXH)s88HNPbG+A-`c{p;*6%b*hD6MSzbMv8|8+D;6#r8g-=dw+4_;$w4*! zMzkmwB1KS*3g7U8NJ)miZQqV9ECI}$zgr%{eSE1dJ}b2nPGV(N*_6=F_^2?371yS_ zI_tO4oYj!|=;w9s7C1*x+?_WK+u_j86P*RFoef4bs=%{Fh-nUMBX%|ymk~#WJr-2M zc~^^Q4l7IxqkCwqlKEfr0P*2HFA9rlNe{Kx;~i{zpW)CP{NXFR?{wixNDp+4N|HRf ze;K(ZiQHFCKpCyg;67(t*f?~BvBg^RJA+;DddL|BFj7WMULmges}sI)9j z^U#(jof`$d`frO_m+@t(I@#hhy{|$%(}JRm)EqDH7!xD`8&{trJlhKh>V%YaRP{DW3!Kc7S9`8FtXKpFdMI)^!zd);vFoYZ#;o^MbD zxvI$Qmtd9?P>e5@dK_qSw&C!v`Uz6*&H&l~QFT6+eltz_{?7 z;z!Y#gk_ar*J%fFx1}dG(;vCXfBvl2qojLdy0?w?=VrH=i~0l(R;n6O7+wl~+9aYk zyj`ZeE#F`V3#l_fw)^_oUbtaMmL5YNU)lOL6jj0!!72I#fuC*URzKgMFL=;gLg?{t z+=@05?;pwRHa}PY6NlqI+ybyl39$NG@L+aG+1EOnGf?OX!z93?X<7c~XxshSW8=h0 z%5=>^F?4{pZGez>pNgf`d!`O4)N{1HQHc!xQqSo0Gx<(s6a-&45zF0cy7c=O0(Ld% zE6)Rd7uW42`yNl+zeS4K{w7K12*+Q+X|g+9L`|_HKDHVJ>!LLHzx;Zj+LyiVc^}YU zQaoE_(TVR2bAWPYv~0h@<19-N9zRT7^UC+x zlqr_Ac7O7lv{e8iVpuqUC4iFG3%xgpZGJ*EIm*}sx8^V)GF=dAwWNf2wERiG=-Pwx z_G<`lFX~^6(tN_LqC>?EzU%=Q$~td+9dH+2a*WO3D07!WNBt@UrQfPxWC`C7ibofh z!sMR=eh`LJM_UFjGD<_FD3zkf#++Ab-INY!tyN~Xpa9KM*+;d9H71@i zZJpXS1KBX5vr6tZvBJ<65DHDksOhCi(`V<8gN4b2v`gjn%V*mtDA~WAWnVjs9fiz2 z!dxov?mQAs0(B&ga&mK)1fYKDCy})BJiRFd%-@QrpB3%z zBcyNVd%`h>8azoc^W7VG>%fDAC>9qc=@Hh;_jOnm6zY-VZksR%_?@4@GqRZ{a9vHJ zQH)*r=QxtMLr#_y__DgcSK26U#WQiG(7H~Tpb3m7wLwOz3 zT1&^>Nnn^0uwDiZ^JvTEhNYz7UB8;X zUs&xqANPqTC{OfqCmd2H!c4=*U#}rp;)_J+4Q&&XAr=dZ9LfN?A>8F`(T<`2Sm^N+ zWmdh=l&6;An7Y^mZ}_bq~lkWL?t=<9l8DUweWf!h6gqqMZsT_qo&f(E?i z0!gxNgt)n`WnyW9gikxF;}<+>e?Wa9VKHhI1>sw)KH$H#V1w^v;Z^jdvzjY~`TBTM z3cj9#wYIpK7S+*UzOTkT1Dg{*DL;JZqt9ZEH8nG&t%s}5h5uAik?RT$CaPcgu;;EB zetP1&dFZ*2f?xoq7H&NMX31&O=Ifpm)ksWl z)DEl!V!*RDI-+1FcTcAlE3Sw+gtLg6beuC34|)$DTpfy$C!xWxpt^_|9N3}QJe7l0 zyAC%_ZqIY#Cn`*0C{6Oq$Q@E5+g92t$Jx$ilcL2*a+_4t+v^z9+W4yZP!*LIg2UMO zYRs?oe<3d3v0TnU)a_}M_%MEBqX692Tc**JcU0ftERAOz)gIB|rwvyoolM{A62sLc zlE8&y3LFlmYljWa6-o*bV|NqFaRt*X6-eb?8R35nncMTy7i=X4wR{$F2stEva~8M} z-#u@F6JOlaBI2O+EE|We%bIMtY2@8qc{R->77?>guctHFpg28V9-5vDmoj2I$gy^m z;X?{HVoK>}9ccU#-y>t4dZ&Ww#)LJ~lei7yl z_BZyvM&b9qW`+2T79EfMG0iNOhQFH5{pHRUR7(~(y&)r)Y?=y&pYuNBB8jbnTR4Q7 zYxc!CoKX!oMJmT!RaDt+cp1ZmyzIpsIYA*WFQ@abucOu}M-UR)=*XOx+fMaDnsCM= zt&#ORBg(olwxZixn3yoi-DnMymz4`Qa4^y zyXdkt`_E-vkPKY1lotr0q-@os3|~&;v{;){r}~}Y#cD^s@feOJ;+m+4 zEv8L)$(4Qe2j-oK{CVuRi`O*r5=MSkU6Jo<@F4gHw%;?92B99J`P@7#)XBwKPX{mB zpO$+XdPWGEk}LF3zY~aU;;~vH67?W`BO`dbAiQI!-<7>oEro@cqbkRBeC^S7-w-&6 z{V`X!wKJRXxi%zSbV`hhKmdzM@Ve}j9}Fo#)skd}t*+q{DDoSJtwMgHdP-u2clF-O zZD9b*cjWy`u$HsQJv?#79>V8-yyoVngZhy-`8M%edwMh_s4qtEN7^C}H;=x^(7VlE zj%qR_>hwV8UY#n`l+0hVDoLb2QE^!?2uva)?Ka+Sri)@s4FVZz@!Pd3onfC&$?CN}`O|ikX_C>WtXja4nYW23mMchE zm+gIcJ!rT`kLSoQ+6mTTs?91taJ0=BDY}bC9G3kb0GL2$zhktaH}{YL#Yxv2jkQH?|j73%&nYVw$wE@yf2 z<4ORYFhHpMiyz5Gb7FHBu*i!mL0C(I(VBZZY`L|zUukoDUk=12tOh(a=fIYgV-sO+ zjxx#%qvXp}ET*XSR6x8oL>!AgBJP!oZsh_u>*2ITk*XSd>i$zHM6oJwr=kQ{tJ9Cr zegO|oCFI`Cqt*3Wl;|ex@ByWyX|g_!mb^;?5{-b)k{Nqt-2Wp1!|6e3Q>>G!yQS_3 z0^zu;vxrpP#w3740`EQ|Dm?6HQ$nfRF59K2+jX1!1-_=j@cENxT#27BAnjMUA%?)F z#N;uuvQK&3zv0(>X|qy`Yh>;V!fbhN8HH@33IH0m7%Y9Le)naX!r}{4?iBjElH)Lg z-$pXev21|QU9}*)DbY* zPbatcY`p4ykVDOE&lV(P2$m zPfF)RMD@TTRXmJ3QMy|m@mEy=90WXSNlm%0Ueu^{xdDxJhzJQ1-|*no0kTZDsURP8 z_l7|RFQ-la+&+8USrX~@nAEaf-mOyT984(@!ATR=K=s%s8I@GNLED-lXan;zTTV+_ zcIa=Qff5| zbEJe}4A|mzvppodi%Lh*c>Y@!4-0S#m61Ig6Lo&M2HmkH1>#r2mV?;tV(G{H-DP8IM5;g^adjlxD|r)xoA6Ocymq4Zmtl?l>z6`F6bJ zV@oC{B&W_AOis|}=yy#>l;SWa|b*{tAj92;PVr zqBZnDZ_JN;k~g2aVesp^_MS6`99EY9jL&RfkAmdTU!ShfQ z&bU)E&KCpXfu4@jT5golM?6Q_n@L-;Kut~%*NG!#?Q%6U1IjAB5FZ`!)5;Q$X6bVq zPUjQvAGU@s+_9>fy)|P*vvmWIqFHpT@yhGET+_FzAXK)^tW# z#d#}8ld$j0?JlmvqyL+Bb<$^psj);_OSr{89&gs#!ZWy&Fu_5Y7vUM)#$!&Kf8meC ze>{9Id|F%~z~)*wk4FGd&Gl^Hg_3{^T;a^~NSaBGW$^_ln%(xaZDo1fU4w0?QWWWg zSaocK045b9Tkq^GSVJ^LWY^;g*H~hJUqOO?fv^oMS4oH z5i!sW2fzPlA0_$fvTly=*Fm_@j76I{df-SoV5eI(mY+Rk(a2Q(e+R-uo{n>TDWGTo z4PM%`O3fdd%_c=~5jYsAb9$GbpN&-(Vdu#c-%T46Zy_G;*I)1Ml(dSdBJ&#V@*kwa zik5^i+-}Bh-=nw~Gc$tXJuq|d#0;qtgsC>=L4jwYC|a}_m&~@H!-N&k$m(gOKL2j5 z;${Kl?FxVT#ZO3H8N|B{(27A~kzw|ZBmGZbZ-9;>tR&bA##S)xVI2AbhOT*A*L(1u zYtKzwQ1hq6aqoQJS#KFQcWZplxk^COqdv{0^V#n3$iPkyQSl#Atq^||@0`n>N(-^U z%+!n}*@X6KWuy$1h~} zlQ}(}yV9XY7AN~Y_rHp=rhrBm&nQtUcMgAc2PreQw9OSHduc*@6moH$Bb5sz&n#=< z7PlS4#ixjWGaR1gDiEko?a|^lp%#9&2~eiiP8i(G9QD-4#vb$aHF(MGt+*h#v4Bhg zgm$f}fivkhA-?@zjKGfx&3s?4Tb|Nb?@aw{ru0L&n<{5?KBTxA-TO6vVwb}ppn>*3|8gERa0SzyzJ)nB3A$z8 zh}?jB@4`KuI1V?eL?ycIwW~GNJhe8}4IyRAk;ldyz&||CX1aDFpKDNFuDxPyI6Ojt znbtOLotvIooY;BJfM!Wn2s6fRO%L1NpbCeDO>nT3!S4}4y)=iARlpNiTr(D3T+l;FQQIUc1(p3v4uLokjAlBRi0Mu7jTMGJTKQLP z0OH*qN4(?DS$-|rI?PS`M+j*#*W6C{MgzoL+H(QkK!D6ZSfIBtEDRn_{-VceM1HIw)Fo^`#`>&-fn`-zHNkSg0t+MyWm*TPiE3cIKbcmU*^*6Kp#z(C{m!QXD5%hbO_%=KY}@~$ zF1=Pe&oU@S5ek-Ueh)R0)20^4_-xu?^bff@e(YiBeflr+Lz007H4V1ok}8GR$Ji8_ zRYwu|%GdbP-SsEC{tx)5G~4`5)ODQBNkUlr)-LF#IUDHkTKo_IGBwm6ZVN{-P91${ zQHXyxcp&_rZ^T~tk9L#bKO8s~@eq#Zf6h6;XGepw{$(mHes>j+JSr}+_)%t9k-?lP z5(0GIUaEq71W|5FU4)|mC6P7bkdE$chMj1L`uIM~Kc)|o_wm|b?pq6OlEXu_`m%91 z(HmDD^i-aE8PuNiC$Qt#F+H^40nBveX~GSfxt6x=FM5i5frHQoJ|H{W6RGxGmtw}c zIQ2FRM)ZMLi(j(wRMYN@c4d8M^N-E{WLMkIgiRd#q@ozHf08z8E;Ym)t(7=#&=~gF zY<{!$fi5@kXDz!AZq9{f;?GctV!cl$y|V1hqpY>YBYL}Z&0hb!5E$$*X&xG7zo@>H zg^G#Fr^>-h3P*Ue*BZ*Fzlte*W`Ewh%QpBNS})9l#+Alz6VdqoI2=2)M71riG1;1k z-a{%^f;7AmnW3K0&J~Vp^V?cZB$ScY&JoZFlU-q~7W#qZ#_#G3`MN$y^`j%+E3lwM;(erA zBSk^4Q?g%B{%H`Xheb6BKI>O5{N&HzD3BrDo#@x0ve5n0m>)1OPHkz4hsXS5SeLfW zo zq|VPT0d}{wGe>4F7TBx8R6XB@v5sMx0^+s#^fmgZp$0^eY=BFPFaD*pQW=*jMS1<^ zkBu60tWhjjX58XhTmQsUr@JewxWPyi_FjK=#Bl)5qfy=+-e+5}k_e56rr)7{iDqYh z@A4$A5D1ow6<$T33+=mk7TG;hFLRAWE9l~ItIw-LG%_COH5e)*_{%V+r(f?`t>~%hd@{Jq#Y^a~8UR%5huQSw1q_LXtD55mMgy9kR!HN4RXfO#(9x@{4 zw!#1MQk)GBVR90wFtd7?w`loFi8?x24^lQmQUXI=Y>Hf(vC7im_66a6k70(EaeTlU zoH2>Hfe7ZuIAFpj+NAGhQa-_~54Tccm0G)>~N) z8Ogf~=T9UypaVcGD@5v!W*TKkPK81h?ylRfF^I6)u!PmEu%O;(MPBzUzXK>hvSiYq zn;|XT)!}E?h6YU`1AyA$csy|r1v{0%6Dd2x=<%Dibh%g2eh4D>vG7Ge>*oNzy(z?2 zE)6Lz&qk`YcNA(bCra}b%I^?_#+`xIlrt%hF1IyA(M?juFyG$0001nF<_s=y%N6oS zTP0j8l+eC#ElB&T>M8{n770`UC%v`;E7^Zn-))ESB$~|>WG)Aiv_L<`+3>l6Eed{8Wwg^C5 zI4@LHv$i@CAM04d04zbFcLtm~_ObipQiFl<kznIp3Tjt7^cO(BaJ} zFD}yzn3c7$$e~~z00mfDs<||r`%5`kSgc@u5a2-UHN8Q2XT;Acqic6Oe9TlU?awDA zil$z?8kpdO3wi(lWdFAt-qPa5`^DZ_MM`qCXZUx`8eZw_s z;_PGjzRouMQG=Nn@*REA+_9e)k|JVtg6k=e90_kH0X_A zIHB)EYSr&J>wp9NwcYK!M2`xz)&gCntJRKiTcd?MR}nEAKCPh2`MOfRa7r~Wotr7E zGWlxqpum0(P*o6W2f=8yhnNC<%@e=Ymm{*q8`rE3maDL}Wg(#sLq!PHcP+TcWvjOO z+rF@IOjueS57gl7wXl*(*ASSKc?QIDsvPUSiHe!D3!@PdNGigKr~jgt13aHB412#Z zXWMtB?fDv*ereBHs1Rqfk7p;SA-_fB&?##};&~XDm_e9Y9tLef8nwB7H4jI~DSAWg z{dk1T!}w;%G|h33DYB>l1W{*P4c$uK^9`W$xJab%1#(%o zhOBcWlXj9MUb-VpK0XtLY(_I)M?W@7%@5R`BD+@^+~nF$&>utHm$S1Da{u8BG15$( zeYT~VjH5I{y|}m41UlQS&--7xd~lMiI0#{D^Pl{|5pnS=_ZegyT!Dim4vY*aO6njh zX=5t+mEGd(>}*#Unx_%euavn%+n46>wKK%Je3DrV2wt5llN$__{-V}!M`xI&;=;tb zJm_28%havItLRzpY2Mgt^mVs3@w3Aw(?*zaS4YIFn zr!gn8?nV)~O9!#z@mmY?7-Mm=qa>Jn41!SXsW7$Pxy73CCfpZ0HG_aR9LRC50Ap(2 zV|#!$?H5-52dVyr9S66v*r}Sb4qdyHvVG}oCkvz9+lUo(g54&YNUff-!!>6#Dd;I= z0m@bV(w=bPp!DPp(CXoDNjF4LJaijCqFMK+(GR(g)WoZR(-w+j!h1TP1W0kaG%zo& z>_RuR2v?SO^!(oeXsUK{_F0upg~--%6Xt@0?s^pk2n4ANeht4jw8%XsC4e-erg5henwN6EY^ypaa&XCr>w4vAdi9leRxtD zgR;}J$jM{ov-~}fhq8j|B8)P?lt1L@2$*e0X5|?d#xxqLtkZK2vsJ%5bTZT0kc0e- zX<$k%O?H3YH8fXGajWW(@c&^V{OB>gBd$3MHkZoc@v0Y(w02Q)`xnvnt7OE~WT?W# z>Tqxap!A3{+%v;|ZXm{Dx1b!oKd6x)>Ql`qPSwF-M5rJftO7ZkWUlc=IS0FBUk!wz z3m+@2!V4;c=Oe1IU((K}>zi#ptxW$W=?ls&(B>2|r@2ucuit-mJ%;L(*_P z$F=1>3Scr@9rSa}EfYQk?881~mXW?o;8AyUqQ0Y@+|9}(xEn7Hve57br0_fEvTnC# zci~fe(6tkqU99tvry$V^-%vH+4hrPZ!(pwvX3C?>SuOJ-Y6e&ptDKgFNq?optT%ZC z^8?)Zr(li(@b3dx^ul83NRFlE+pzcuF;JgZaAZAY4P zwKrljN@dH z6-G|Y{?CcK7*ILV0Nxe(2F7Gd2fuZ*_!#f8!U@OY&h_SH9EwIJly=@GvSKA5{aKTx zVMc9{uMhzP3Dr)}pfNQ8P5F#+`u7>#?4(VWBCEoS{%+*uSmrs#L8+Y~5D`#TUY51( z)zng@cS1fQl`NNy67&#ri=AMW4Wwdd@F2jp(_K{j@P2op(CBfI7_0JIJn>xFgYW%Z za{op)-=VRqkMFighy+kH3WC*kwBa*#g-gZt5YCaSk{2QH(6eb1F>R0z+8h&v8WK;c zmW={Jjt)D}t^|=S=kC|HP1T@Jp3~t+T%y3R`+bo5vJ2{!o+@fhrUJv>_fx_ zHZ|Ph^gwa~UR_XzCc%FuRBFsu9cs&dcoD^BXOB&3of-k;|GT<|tX= zM%l;tr5t+4pChDQRGupaR7Wdy&XhM@YE2~d-$}-!K{kRYy-NA9x#xO(CV!uFU~O1u zjFSpQ26t=>{DXoo(@oLP-EtrT(yIUg&oD~QCP%JG0vXJs(RwkI9*ysIYL)ZisCDl{ zTxWa;`Ob{4^521SPh?nZNrsf(6|f3mnPV`$KX96pbsXo#i!+i`G>lh@Lx z7|fQx;O-iWPYW44`BpDK^zk?Bq{&s@d5eO*wL-8qz}k}$hCnrEyC z=2OGjH}pQ|(t#0|1>y}7jdHzL6Jqsn@c+3xW1iA|){1t@X4eQyw@J}pd98pSqkF=I z>oKZmP6b=7k!qngW4PXDV{OkO@lWR#dh))d8o4o1K|HYYXMtXYllN66f~aZn)|sN^ zhNXjp9X4_hVSTg?u&fX=koFUH&yO_(dO*WN&!);43WWO7+@W;jAl2-Af3OFhb0@$8 zbqP(9+lo}GQR&VkSw6^e`(Zey-7`Ei^SxXUi@p0&kc%QbN3zs|vA!1c5z`M*$FooY z-n!;0%|~?rk|-Xy3qLmer9{km@ws4AEY3nEO>Cz8pWk8dkWa(@s(5PlWiL(Cx`OW1 z=u<@NLYyZC#NjCZm|JNKH}wc6D)#6I>Fj83C)+-b;X=n|HjK_uyc&z4GTl>C!a0;t z?4Lh2M1)uWo)z-vWhkOe+8g7gI%+dVoC?J17Q_3cngF}Pe~lhixSEoVd&3mZt;~eFQbBn=FLc54YEec14O!5V^vFSA1 zzxXG}L&g1aC&zD2t(8`(%=8c#8TiuN1W0O9YCEC43KD5kdx)wBA)^|q-$1VW=`L^0 z+8~c8^mZEK)h7C1aW&|YqlA8@dZL;){B*=DX{s~N{OVKm$F9L{9Om^U%R~7NE8Ku| z)&%w&WZSxCytcVyVA*%|*$?=pXgi8=UzNK}K&ZN#khl92eK^+(u0gc&eB|rlOP)3H z)M7*szy^>8(c}4pQ^EzFvb>L1)(2Dxd<)J zj_RLW1nE^6OZa-rQkqV#oRv``p1zutWGH?@#OfM9zGPnP7qm$16=AO&e@DK(sZ4cS zH%RgKh<qntrLL@fh&xA*g$f09QBWt&8&)dK`^=|{!E&(sskKwA-p5`#_I%)$sALbaDa>$N& z1kELCU za99DKpAy*l=&$SvL!0&)q#hYJo{>W=5FEdJxwl&W_POtEMP=i*;G&M3#n}IOqq(qQ zrUAJtFk5`Cm&xcoQvf>?A?HCE$E2m!_PPOOQn{E~PXDGPCDOTX-{lL$a0Sg)aelcsoGv**K1Qd+}x&Gb5M zU7$-__|gCr=2j8Y)jT+1HmhllweIAiZAO8xt});D^d}wakeRN}WZ2vQ2bMA^h4$p{ ziTYOo>buXND&ts}74rbHBiOrlTuL=htg`DN$-O25|2rp@vtuwGm!()UQ<*3Bh?Z#l z(CASLM5{Ks&aluC_6;w8J8BF9JP=0~>*63FrVq2%N8B6Seeh#uPk~vniSv>lhDOH{xtU|F(?JHx~_+gGm#XTR~Y($i##QiFY79E(=3W#wkm}$tRT{F(3Lr%^4OGDVx zFanE_$|7w&2XJFGB)}p_lK2N2X5$!WAib=L5V-|u8jKx2;YVy}43mVMH&zk!A{fVw zyz>?nWiV3{B14Z{cxKGZG%~-@97Ook_QX)rR6`Jpep5gVEBba8>V3bQm=|bfc={+E zw_4S;o!>71T_tseM>rU{9N&-nSwtqQ$;sN~$l>h((F9DtsjC6|s002Ea z_wWZU2y$OBH~}BefE|pVnei5o7UFZ1_S3Q*_XdT<0K7WAHoph@{`=&U!KZi>Ka;<$}nXxl<7_XBogO!zHD{5w_qU z(KBFHAK(yw>AVc=PWIfWjud1%6BC`198`Nqx2x~*j*%(Y;Ky-=bPAj|Mhv!qnfxaZ zD877oJ8e7QEhpIm&%#RGcO{sA7eK0?_gEf#5>1>a5!jgvO+y?|=cnD))(nCDlNECQ zU*c#}ZQ?72DMNnEZ6)~bCX!eH9wOO@u7gYcRw3P0ZwYo{ISU3# zXlHOFKVdV{1MlKmJvSq}_J2qY_W(HI0005fL7Ecgpg>z&TU%ROTP9Ng00RI81U3Hv z01R^%JcOW(%y8#7ABFr5wCu~9cN5_)`z-YnEl36c0NTPkfn$ZH8>Y|q{R#O8L80b%a}2|Z>tHZrIKtD~dlll`ZhKt+$d zL+@0l296=4y>bp5%o0^5dI58&9JV}CeX)+TApij8DU*o2VHSzIK?)vAGh|q7mI0#* zXYxMO;0Flq5EcBPY~EG`TY&xDL%g7+wf{%RsP=szkuzI|?@yIf1zhTX&o}E`&!l}> z03=2@$$(FH7r*cT00sL63zG-{pRyFE;_0ONL-&6nA%KQfrf&hB0%5o4H0203WkGdr z3{+vdJYYcpAsOc7hs3}^^^S}G`I!6m$#u|j%6z(Eb$j9l`E9O@Q@=x!7ytlsy%A!y zfEKE-HYCRbIJn?1(-Rv6Pz*FZZFzin0+-G4P;Xruqbd0?mx$0HBZX{kYqj|-U@98B z3o$(6q$U}rV%iZ$YIga$&QRN%L0_=A1YH0C0ulk98q9Qx{{R3zeT81J*Za+7cebWHpXy_l*aGv2$aNdj<_7C%iO48J4n)6c0rR> zKvi5(tX`g&iWX2*#e)X1t4na&>)Y3X^v;4`T;co;eO!QXvQ0%HpHMD73@f=n$4CU5 zANMg*ARZ23uo`J*_vy+M$WY;wOr_zT{}=)i56+6( zNjng1*123rpfYd$_o>P%v4Ha)jREAL&S-9zU2_C;DXyZ$*-aA?!3W);^laYj1B}Z` zn?o{0+t^>wE|j@ zkrXe%JsJNT)fQN62k@p6Lb|F;OBYKMOL4sO*UKTDKlEVWS_M~K5v;1($@OF0c6}c8 zn0dc{XaWL-xKM#{2BNaL1i4Erqkkm_4{yeq2E?~Hb9a!)4C`4s-MJvEg0Kq4O zuL3=tY6v&6#dgd)b8BfAr}&@G#)T7!&Ia8uxQUrvbSWt1p^_C{&|Zr4z|{=P*D^;B zSN8^<4wgvR4b>1tDk#WI-P!AV8^JK%M4N+(9UVuF(DqHf!$=c%000oBL7E$9fdZD+ z*4Eb6)R{~G00RID{{R3IQiOIa!$>Y0bG(?;C3f9E1h77ymV2*)OQp6F8OSg+C%`IoF25qi`8-ocpr^(fSvV=b z2_L251Yemc37q|H>Y30iATI>21B7Cf~D|eg$F$o^=g;I0p$`djf8C0yn-uqUPBigVf zP@5zD8m!FxAK9Z=CtK>*tt<|LNw>?beplO;iw@vt(X+KVuC5|GBC&YFL~s#O z&tUV^`x163bet53kkRC&@-yNn$kn{Io0sA&NK&0LQZtYfwy<>Hdcc_<#lI@~Jh|%Vleenhi!@JpU@z2=-ZyS$g8YhJ?||O`IQmdZH_iF|y#HRo zHv3|#wUySQ2NmZupJN=H$(X>^H_o60OtvA(a3%ORW0vu9vBUrla`}L{IaAbqIR^9o zwoG}qF3s8q@ugW$+UVwYycaz;OcetfgVy*6g67Xcp)wYAvL=b4JXjma9}S2}!dth+ zkJ&@T0wt*8dwo&t8vV%{IGr@)P0L9K$n(P0zf%Sk~9Dpm-7IXizL1 zTg`-}^7kqw?>oQ%Tf1Z=3$36BYEP1!WXu}bn0K+@IN{sP*7-qYd-|gwpu^28B=-9a zM3q8jW>5+L`daG=qQB^ecOVryg{`5~kVIdvV#+bu5eF4~#lJysS@c@*mM9)!NO*;z zS}5o2jmpcAhjNNR5(qHqRvZ0a_@Bxv2fm`jY_pEynf5+bbul*SlYZ)K+G4kj5wXXQ2jeWg?1v9UXF~{*O&T^O$}i@2pTfCIx$6-A+cvENLlZ~cGU1%87Bv4@M95zPM}`hF@@zsBY-*%ReogifCe z`#Ie#*yE@A4lMjw%xW?UW(zWe#h4KLYF$fYWi{YFWB+0q7yh+-C7{y zqeQO5^M1okyT=%1{WU8P2NmXpfzho^iq>!oY#+V>gsuUsPdq(=ZXc!&wSp2QSyvLL zuY73y=cpQZ$6NBXaeXS>^V+8YQ*6e*y-&c0{Yy7?m00Wts#c2#y$tyhdAvZfEELwd zJQ9#xDO3FC6~EJu^p>sfUdhzXfPX@Q@l!_~I*&X4epox{kH?%FUt@`uNF%=SI9gAV zF0~8=q#w4SK^JETwpT_IdlW7L^&;raeYMl7s{Rz`791u2$I~r;!u=?=Z(W+Mrcz@R zP|g3a50IdVc7dr%nfoIV;d~u(!eV12s&;ep9j;MGp!YV~^(z3D3Nrrq3!gpHhZpxv zoKYWNr>!Lgh|{^`S`$}@9jHx%H@n0P)hE)4s+By3U{47m!2KZjNp)F_E8<8p{s95k z#k&n3I^Wnr7a(fWFAkg*6M+CP{gv~fZgW3h0!e=%yhD`c&DrV(O1_o{`vRB=-o!TWAObFaA@`fuw z{$`@4%jrp93s2p z#yyYC0#JBTT-J5lg$Kfw(0hTaOX`K(mH#vh@^9i)A#XUY!xFJ`H*j1w38HwQ#kESH z1+JUnVM96#wY}ZdmtEH<%c&ifKJ@g*Yi+?lvVwq{3t7p1)fS+C?W#^?NqT6 zc|xmk6$-@ma> IZp*5=XqBUL$a8Q;nxs=r`dl8Ac=T6v9f?JgK{B-mjK(QhNp7A znRzuCV>^3)F!8;FKc6U72!q3?oS}+3?HDp%<&7f00i&5nYnG ztg7z-`+NDS0E68G(Q)u5qXJP!X&s`4zRa@s^mBfVVFMe&TJ`et6WJrso;xOp@?Bi! zshI&D_cY>9J?_9Bp*)9QNfWb$6rEq^2IyMtQoouYbMM&qbHvq0l>3)fojJgS7>L63 z^)o2`?d(e`NW7Fjhy$!pQ~Nz&8KZKq-0-eUU>hWxuB_jRGHSL{9Yq%kBaQw%4qNp} z)pOH%Vu72(_6l*{g{i3swRbfLg>a9kJ%pWb*vP70rI56;l0QXvy*9781=Y7i@WE^# zSMk{$itfdzK?e6$lS2s^kOTOTn0M}Rsz6BSrNenw?}PuWKAQZ{ppQY|i> z_MbFe<8!4eM3zsLQiodp0>w0gDhhYH^oYAF>!PZx9Z+@249ZwoDiLvv1p>H*35I-I z^ji35R0)fW_l~M(RIt6*wAICsBl;(Cv{YHjf>%*t;`YB;Fg@0f7K18i)V4{rk{4?s z-qAeAM+kf5=S58CfAc=1khsRQX7!QFS>_bKbo8&~!)<4${!|IL+Y>r__YG!Sw)1jL z{TGijT;bo9&-&1~bg^<7yk$>V6RDLQmuj{r?8Z8_NI*;9__w@?Wmlg?3IBv#&_*FL zOH}a%Ur`|x6kyn-HTqC?APh>iSz_zgzlq7Z!Yl}V40|gl7)hVQuveDtVW2%nFP?o! zYoh1$>lf;+JA8yQoE#U1#TOp`N0c^`HNEuE(`rfW{7%%V*fUrP;dm`O%|`U>(* zG!$R}umW4i)ZPIWrdATkQ7`d-1tX0bzE}urUa@B5+B&lzk27X5KuQ;0-}wOEEIdwT zG${o>^G;I+1;59@^X`r~TbT@JptLBfqc3Wg*M`Sl{fX42d?sn#nK% zHbbK~53*U#FYILc0xTz9BConae$Nc@O!X7N#<@9hvdWQddDW5Vsjvq3P$qqAR38+iNA1DTkA44z?y)5j7g2XweItI zBz(2Ylt`$4(bv}LeoQ3=k;VpnQ(C(wETdevg>{e4-6>_CSv zMTC7wt-~whn0B=kimNPSvkNjVY{k|cBrj{j!t@)*UUh@}c`qFK;f3L-0ahgeh@eF~ zLp7WEu%m;zQ|oNXILk~y;JOSzD8M#o!z>tyCH)b^LoWG`d+C&|v%*?+)rO)JinCs`u55}k z049>l+iG(ljQ2vOvP9=TANPZj*WAhjTKb0V^#~=({2FgHq>+lRIgCe1+zpQ}fwu8R zbnfb|V>CYk2?_yt+^9*PU9GTa`s>mr!V81b-O!@-xmQ)qMwn;n4bc3=;F*h5B{MD? zfA;OXfO=C{J`_8;*jbn^{gOHG~`>l`!G-L5 z!KJkS`Nj+w1q%C80SwtTuqhHUMLkDEEaecylXxJ{k~r=n(-6=e|L>5qYzQppkKD|1 zxzU4W7W9ukm6v0)g`5prj>*8bDalqI`07u6*4m{@H7Z2^${85C`v4AmT*sp41#E&# z_sa(s}EQZhTiUcV@xBjfB*mkyFs2KEPSEp zA&CC~06{@Fs&(>I0%L)zssW6UhTCYbk!>jwRenxYW9M34E?CDXp*0vE`OMwW+D8MV z_jq53<&4#ZMt}yTItT^(C0*9PB1TR}{@3NY$#|9k4Z(0Fi%x(Z(Lc~Fwx2KOo4oc( zx3rCp-hQ~&4XFj$uck%X_ZXa8C})D6x`L-R_2})q_Ar>c5Xp|1vw`4KLRS9TQzTxA zGAwwqZ#V1lF+WuUp@Ju0qZHq2x+9=*Qu!4qh!~WfVJfSx1P63 zO=X2$YdhG<01qA@SL|0@ioj(nU;ZwSKASd)>*bi>y$nD`fd;we_GgWOo@~|c6!`i5 zpWQT+zzc$NkJk|?)ZXF>bg|cn#D$~?6vm5-+OBB;kooBXuo2hx6Wh);Lo9fPP*|a4 zlL1!Qw#@HjV}ee@vHD2-UoP338m$BmuwruC;i-<`VREC#0gy{#x%H;#p>$K}KR2Qd zS~=W|2U1XvCSV5NW5-BAd9Xtmnvp@yWWd?#%22n6RQei{#894gb;~(}_Mz~s4 z@MRUVDi#7PN6A!O)9x~u-MhOtZ)C)quP$iv);lFt83k9!kD$ZmV!^=QPN6E^kn#9; zu^MPyulyfZM%5t2)t*UrAkLI}ZNxN|AZu;@yjMs-w~af%1jC)}8_&?6)K11AMqi zplq(xI2n8aJ6#o{l$Kuq1wP=X?L!uuE*6ANRwYlpD5PcAntURM^)mJs6(z5 zM&SJjx^6B~bHZ7?@-7L}Yxb{z^#0~z!

#K>SkFipT&}aM{#(Bh|L8CqF#rGoTLGRcOmvF>002Tl z7+G5kG+dMDe}EpH4<*K-!2tKFaGXoM-UVc&B<(#kjbPf&ONCyyj^3lc`fRw>SiWnqf8xTiY5a@B_6NK7;8nxMc>Jl``4>@YP)psK75{q(PwKg41Yh9JB)vTSo3YL6Z=#U_?gpLAId@G7wx z1PID1ki?*}%7lt|5Sqj8sK|L%0${fXKv{N9AlQ_a)GI~N`1Bg0T zHhsX16sr}GE(P7Z0;<8{3@|C-xwR+(ht@?g421)d5s0Xvko~~o7KBiNZxiL11z;{s z3IuT*#MDC_F#%6>o&w^kS=>2d000m0000}~L7FS(pg>xswY9aiwI)*l00RI5zW@Ld zQh^e?0T$D|y7Hf{0ZtPmtr0&J5r*MMpAVW~~EAofcUCCDYJYLzRzUMvW|8 z*$PWbJ*oeJaI!fmW0C+9GR+UpPV^^Net+Sqk!jR5^TsH>UIB&1BTRl|ip8BdYsMCc zy`fq#VRfZjsM(nhQudq2GeEx_6Rc|}LDOt~EBj3h$z@AdB;WiVGW+v*PI+Ux-g*S_ zxw0;j6Zzowd4aeq+9W8kP0|!4^2S1!s zw2P8|I_*OMC7CAowsFLW20HZOSPT3hT4=hxnhP^rag1o$?P|lj{%%RY8kjY}ftD%@ z7FNr&2A;+Yqd?cihPB$4(`_$s5Naag7lq6Ww_P%&Dhc5%hG!iKGm~gGxdvwBveGOT zuSltjD?`*qd{E&{6?1>MBO=wzvtMy7FCrD2DXTQUtDNJTUrJ_`Jgp{$ibu|yGv~C} zGc%jkGDQD{adkyLh)SbjR>i1+B@vC z?G@zY60Na;n{ZLJ05%%elKUU7za4UQ4Mv~{$msWcBlpT4*Q1%MT*EtkgB1>FG}&SC zE1nlKuyr|p@nygs#rPS!9960GQ_X$bYlwvHX0;;nwK*3&4gMN_eNY#J6}}5tO(6$_ zBF$g6Tz9SUJVeRvj8M9yr;>1eI+@r3jB@9-(5f;ODy2z!@H_CMemu{{RugXZAF8aZs`C)I zYfN@8P<b_-zU~$uxEi>n71=arenx$+B2|9?CK=Lz$zj#X7G{8V; zyNda$FW#k&WJ`;^_u=fHp6%*iq!iu%lht(7;T?jBVAFD=s>Z$O(6xBanUF6Fc!j4b z2u3BGb%b`A^f{!19onm(*T(B!ntUU!PmO5|)SeQV9wdWdo}+FKPc)V5aW6-FQmX zNRlGsDhM!)HFLrLdf83eQ7f~dlv%F2D^1hGM^zg`y2%_>_vbd$gV5Y_Pwg_rA~+v% zX|5U$);9vDp6r=+l82mt3&Xg)F+!b%h1@K(P;=5n+yFd_pbQ@$&DI6%8Z0Gj{X{VF zm1gjWcXq_m@PQHlim{F9uHO}ln8p>?n^VDm((xDDH{^3 z;Pp7S2&Oi3^<@xCA?gK?$4u$9ym2KZ~IJUX}r^rTt3}KcGV7p1x=u&$o^S?Ev=Khd>!LxQ3j8^j@Gek?IkmFe~8%)Msp z98^$UMKEGbYVP#3eVhw<0`sJ+QPdjZ`;Df@6^@c(iFToIa&Qk~K<-HdbjP zgNQ*WRFk)Osv`ncT4d@o7-=%qhWdY3)n*ug68!okDUpQ{7x@&?u}!UtR2u<#8^+Wb zTPOd$Twt+Floo|jPV4K3#U{Hp$ds~YxR=3jQKl8BUv6OVNNw{8eO@d7U1I33A%GG_ ziv*)#^e%Fvss)onu!J_j4dqan;oDQA50B!H%`UmebFNA&DAF^9Aem=XkgDO~Nz2$@ zD-QQA5?#1P++FkLq*3TJUwC9v3pGxR>#<2(4^0IXexq2}m*)M#kE1jk5Yt``*!)9BQ-Su%*Y8aOYYE`th7$N~Wv2fjTEm|E*oSz0bjt}-t z6O7W9@0lWtNxMnyc_ zO`}*VI#3g4ILz+ zGbd|=^_;J!Eye>=McSXkMt0=7ACy`C8QKbea~Lfwr{zq;^N6-?=GGf!NIVX}rHXxWef{cSr%qpPUPuEjiXFb~v2rbcH3 z%(Br;1b|GI!q;9b=IRrp#~Ahp9x_lI`n@?lrO>02d&;r)-5wT>vZe7vhzYmOZZ+S` z9=!V`$l89sa)XqgE`mUDC&Qt|DRCW|l%w=d7k|RRQ7HgtgeJ*bz)7x}=9Qm_%AYU> zdJiZS;+0EV2QxC7?^Zoj~MpCW>mdcvZd3r?XtwlL3kS5gQoSvXX|Le zHlbcoCSAcEJ-!yz<4bo(4(+BfkSlKUp)gF*9?D5(>-~LYE37EL818cx zy49;~+PA%<1&!b{OHU2TBK;5==o+I;#6LSSZF7EP+AWPqgk<%&`9p{I@-(+5;q;}k zO6B(hzS;W=22d-PT1H1M5TmYDtR=v!wm)8(f#CTth5E5HE&2XIDZt(|fjckzJk19= zM%y8M8rccb1f(V;G_~BRI^0*!VXav;*~bL_l<~UdRAoX_tTp-&S9TL7X zb33kuAftpmPyf%O-f;49>9DQzyL~eQD50;#LjQYHZE!MV+5TRFp5zX3wp38Z;Hwyn z-#3fl`y8{vH$YdnXGRc~M%YQ34}Na9N_?$h+N|;pL&3>IeICovG<~C!O&yzZ z#W1q5tF@M-kj#;TdN8X{<_!RJDz3_*WYDF@p`>>kClAbM zvs72aaIe2CK;9#|Nd#puPpRm~h~#2RtoahV!m9Q()AIrH?^r2Q;T%;)Smfx6`{+IJ z53A|lGlvtkzxuqslk@oE*mU-)EHfk~Jc35$U}z5M`t4A7Z50-d`iQ&eD`%$QL@5|U zMPI0c*q9NlIV!(=5{svu9h8!mQsqfuqS)o9(!Xa#wM#T}a#uyYvR8{gfV2Cn_Su8{ z{(Q%^$HU4_{Ggl?fkV{%VxPH=k*U}}<<-{bYd0N-oJblw=yhsj{aRbUytC`Y1gwbH z`R%(Z-kzkYzz?UGc?KfB@aTuqt_fv^8($??$H6I6%2OVy4#=_D`dyy=i@ZqM*4vv> z(PNuSMK0MuRq+by>C8nQSn^z)aKs@h|28V1TPpe(>hkmuj(8FRU{!boRd-aSwmFQ_ z4j&+hDsSivxjcE=qbmFKHxlO8$xR@Af1I<&CdqpXk4#WD4Ap7|ByL8p>cI!TdpaXF#=L+3(KPu?Z{iMb4S z(ft=!XLcio`7MsZc`PqBIZMt+?snMg)7oGEs&$A2%>Z8Gseg^(eiKZ7k-=Rj>N*f11GT?I8Os<$r4rTDG;WeJ9HLE zTl!_0^v#}B-MR`G-)4U0qr@(bbV7uhTVBz4vrmzewimLLnn`=wJ&_IhUQH6Wtv0)? zy&a{>T}VeMW<0^5GhNllvwHlW)mr`UN#QCM&Z-=7tEX`$WAoq1CTYvKV+n9>OkyxB zk1MK;cuJ$WaTV2%6o0s+RtoMHsVTc<)f)}OM`j8nozkJ@g{9x{uWwD*SmBp(O>A>v z0kDZ|a5*5@q}!Ssr`~R_OaaIdj|HfEHvbGYiT?~&n~xB!!p#nxD2@?T8#eu6C|yf( z_X{L8ZJT;#okgXq_DwZlAf$D=w8tLIp=`r}!k_OFe) zIj$q^)+Lu`-a&Ta&sbG#bK3{Dn*p7MO{JRxnBXDhU8&)y4R@*y7FZgcql3E$gwPUw za6H;d=k+Am&RM*p+)hTX2qR2#(4C^5goXED0EXO$K(Kw;tw;>rDYbmQL==?tyYfyX z6;FFU6x=irn+y2ZhWCKAQQ%%YZ-rd|^nZqWh!&_=(GMG5b(HiOU{E}qrPepin$qjm zm~vv+j&9jIFARKVen{Tz_u1Ns2|*t0>K)wxd9%S+*YAbmTW~tjb+}bm)-wkf;Bl zp3IDZdc{T-%!tUVXG19My|bc}fFX3d)2X@$+Q0>un>E5a9~aW|t#;cCR9Fo`JbpN`7A;=MIfshr%S7 z+OEJzlPH+A@;y4;{4FPc{DKBpxJP}ala=Bfqt9QMNAXfJ#5KaRuw3hFfWNOm8(^!>)~kNam3{1~tr~vT z!*Ala`mZ+?X*DSIVDEWRA>|+4mBS&QL`8lpfNZQ&Y>7ON^J+jsz2Db_U*t zDxSgs4ot9pW-n2acFJ$4%=QLJ_`n}m^ziy3yETQNCFN*ZqI)2mLT*wBLyzZ=m*a3!+=6% zHJSxR#sk5%H1>H&X~;0~vMx|SqCYQrhx&a6^_>`5eGbu{N>rd%Ob7PIX>c__)w}nPgGl1 zR?~=Gu95`7;AKglm|_1cxrxgKF(x1;wD}5o;rKLD6l}Sya*%E~gJ#Jn{kJ&`Xixh? zafljJv+_whr~I^OXQM4a%CTAV?i6_9j%Bu%Fj&pn0pT;|e3AZDpb$Esx5$dVQsYl# z`Q+2Ga(!Z!cy!W`paq%SL2ml4luXJEg=uyrtm0nw#25N>rM&O`r*qAb)0$0fEp)9W zqLc=vVq~VUlUDTFhb*H{we5OAR%IEb-l%_$5i?j%FU;<>;_bbd>TeTl*8r-P!LT>s zrVY|HB0pH~v+K>>pW7AMn^pm(WX{Nv6kEkIc(u;JM(Eoj?J7Fjlt^<5_Pf~=h?Vbx z%6vZ4JUMNyux7khnG&f>D#$h0GxdJjJts161;#3qznD zzhyfaNiwc=0O#nn6`aQ$#xe1Z$jFy`MgE*~*{lCMWDoO} zvZi(SriivoCx^?*vl%3eIj?mdxlnJBa~&4;&0!(YZ+D-xZoAGUmE3P%!Zw%in=*ml zMropuvEczdN#?yU`h96yw*laJyl=|Sf!d+PWYFIR;Up)=ub%{Wo;Lf+)_0XxK2UP) zujTR%+neNb>pe-0PnRYd3x_|NmCQdZv41L~A>bh|A)q&! zG{y0)A^K*Ug7bJiU&%~&BEl5_(`jq%z;59}0J(8{e9j|)U3rRVw8Bpx3F;PA2W!s# z`s57ZZR+lHjIfT+>qU&M9xK)YxHiTxjyz|avm%6!o86-#&#csk@8Ma#3D@;(f;%gn zI_ZveB2#p_ur+Syqhok{(bdxzt3($;9DnVV>_AU((l-247eFB;ps$GSjoneD^Qi?z z+@y;XZP^E@H;9&^K4(!l!JKcC?mwQr{xB4Mc#v%j3W3BGUx3-L8*=hr)N;oe6E!su zpg8BRMcoYiMjQGdlU&8>_p<{E62T=cJy@H{2P~O0@$F2MMFD zhGR9FYz8Axo}iO{NbSTIc-^(BHN&vzQq}c9du`g$N;X3VE8XVMFy>4)#A)2w9FI<3 z2apXlcUU#SG$MqUZj-@aH{}~Mhk2ENH~ok&7eKw-t_EU|0U4OhBN;;j=E5qzEliI4 zb1$dvEzG&*h*$7Yt5srg8!){efgVExOdVbd_{wI3PYp6ONO+YcAhJs-s?NNe`?O0Ljto(G=bvXyN=W9Ik zAL^g9Hi(o#6sV)3tE=+kRi=SeF9lR^g6T@veniKdYg;7$z0$CA$|kj2F6+Fd|_AZPkNBSS-1 zl}OHF!6?WGRRmyYox#-XPZ~=@2Tt#LZy{FVr4n{u(*FPo5rILmb$xUz|fKx5eAqc4=6KVtVR3ayu&c|}^=0I}A% z5matrSFk@QU4R#g!;i5UwNCk5MqZY;P6N#_1cmM(mqR3NQNt&T5N?Bt<*H`ka-_u%{@QR12SB~@2h6Gaw zxx36Ch9J7^=k=DJO(>o^du=?|H%qn7)7FmQkPpmK2=)g3Mdfp%>J0-L`%y=Q$Lu?F z><#$JPicnfc*07{-c^mCtVzV|-&H|bOJludXH5$G2 zmZ;lO^Fo>);pEH`Gk=n%-aD>2ak`DgF)B_zFFb@n;06m5ItI_LVQGq#NZyD}wBQV$ye`6OXvX3(64z(!F~ zbb7pAl(%1}^0h#22!~|(<+0JSYC-;{^!6yuk#SODj5t5nva!`M`9pM8b)Bi000yw zL7p?Le4*$ei2ncpL9)M?lUr=jCqw}#PGQ>`V5WiZY-a3$*DDyyesGpGn8{N)9N4 zl0OQ}wo4xnX#hgI1|$sZ2%`s>YM-8dUIJ9>$@b*fx9>!zl|5GaB!yI&G|0rAi*s~2 zMq~!aI!OnocuirbM|qr&Ky_oF;GA~P9_%Sv#i|OgaWN4k%VPgL#8LMgmw&JT4d8Y2 z*lW)F2IoE=@C6=1br~Qu)}SWnv+&6yw z!DnalaRGKr%MKMPn2@$Kgsranz<+x;8k~!iS!gLPV$M9!lmO><$_PE&(hyzzM z%@R{a@TiXhLhEwAq1&lJbgevW7H{L0mDM(+hEf`y%0n3W$fyDJ{q`^rP2R&|ojBlX z)R8}{Yb9+cm|>7_@8K4dI%n>}oNH9#EycQCRo!%kxf()m2AA&{bsY^;XTh41oE5P|Gn}HnzhK!9diA#qQ_3Vy(2M`qSHQRF()nHCtJYQf6b&hrj`|&K|A{} z#wCp&><736W1J&_=}IO149jUlwrS{QK9up#wdzd@JbH`TpRKMHbrBZbah!;Q9mBFL zZk*b`{iXuh^PvH5=Bf5>>%ys~=}TEqoC3P$Voho0P6|f3T?M}$6aJp?=m!O`;qC2? zFZZgD7?=MFN++Gpn(l+WuiaOimHaQ{F5>4{%LzT#q3Xq;^{bLt;CpRP_AF{kI>-|# z9<(AV2`VQiXZsI)L$m}_w!LNUC`=ACX`lX!9NPlKfh$-b;^m2HHj%Rsrz0{AO(=qr z>!9hy1Xbf8t^{Z^4u!Hb3Wx$KFAOP1kbI~Q_`+4$y=s;6 zO){_=Fkv@9m`M;^N$ehmNEGOQN5N83?NX!98q*&}v!(cnOWYo;s#~QG2rOjj%t@C! z*%wTkw{Pa3BAmlrJUHVMwaO?`K&)oOd8{5q%*EUjfq8&K596W^aLiD?qS*>rM!cz9 zQWMZWX%|{dx71*VenW^#lTTLCu6i!F5P!+qQRsRrnV>!fNTlcE0aYVbiuBWG6({k) zi%W5P>(?X`IZ6aWaq#pNfh79a&?==OJxkc4w8!5yE@zv6pS8);AI&xO$b!a^vu$xG z<7iHgi6q1)XhYrI4SuQ^jJLyodTUGI&^!Hkecs2g1F#ZXvXBr~Li$AzBHom2(AJ_; z^y7%05%LFabc$zDYb}KB0Ass^V-0D&M%z-$>Krcm;irZ}G@`srP?%+sjGn{af04@_ zALHH+_~wX$G;%iRE_!r2g9>pc)uDzd=0tV73RTU8^xUM@eFQ>q%h0L}@W8zX7!hz# z4dRsPC;QFW(OnuMG`P*j8ztrMZgN#aYK%UOkC^)@g`@flb4bgNP(o)v@gLxcj zbK_Q>i^L8+Du|rHB<$p*RB~@cCp*F|T+Cuojs47&czNKzhfTALZ(!&e2o=48=w*S- z7o|8{S?|-TQ{lvRqNo#WA@ZCIsbs-eJ^Cv zxVNqb|Dlb=-kYY9*dBdmA{sTlz*HTdQ*35P(#!L>vxs+sA(_)6G(@c8%pDtl{sEK~ zNS5G@fuI5(Bt;@Bw+O>08hqdyggu(Gp&ygZTbfL+=681y0YsvS4S&u=0Mvay7cUa$ z4P?KcnJo(wd021U>2PD|Y~4yNs!)msrROP;M&=P-n__6l=sM>T^A1U4oI?KZg4BCh z`7R42P8huU^m#_V(yq)Ck1bJ7B_gOtd55d_|9?ocNr4Ih#(?r?98=s#H|!skS9r3%Q3F#Gd!d^qQqg<*OTW<oN|9q%t zNmZ&(@u#|#_nI`dvNvkj2bqX~PRkRx6Z=7nI>6yJX#-WP27(laPmKus|Nit=>BnQc zVBwqF{q)Aus(D9qZ$Y|e;3V5&<^hX$@Jb6v@3)==;FJ4n2E>|RT05%PkqlY`&<6Hk z7lHf8x&17)^f|>j!rMsuclyO|nAtV@ZaXd=>YG(gB+lvpArwv+M><;d0xA^0WXL$+ z0Wn!j{$|UGfX-ejr8i@ZW%@8L-t+(f2fR!8={ZVBA3<`gnLJN0>DQJh=k_N4rtJ#I zBy_}OnJ2c3wA8OEG}bM%P|kp>jZj4FaIoqj5=>J4@DHZn!|VCt6XXrx_Fyg=rGco2 zdOE^p604gc%|Bni-W>2;!o$JR&sjB1Rx9X>%ArCoAK$+*T?}RCM!eV{C(vJ1K3p{&icg? z-UB9Y|Bt!kWccO@?#_+dS;7f8v!t->70sD)0IGcpi)xEQLVGe}jirhZ1-Nk}#a)Jp zoxd`=UY{bR|C)SO0f9X)w!h^K9$R!_Y<#%3z%$Ri{&OA($WDNLF!YXX0L6z70Ro** zL3_wKtKgqNLe(FE#`r%pKfz|puQExhtzVjz>0O2pvv_wfSrpsc5Ypt-)E|X{C;(xV zh-V8G!Q1EuC&=JQp9$Z8Bpk&4eXF}(i%HqLvO(!ey1m>abil(9X}^eER7!nKhRX!; z`4!-*2z(~4!ecTxel=4UhymRN!YeivvCHq>^Co|B2w!zRx*8n-5NKN`;IcnH#yWbi0E6B zJA1$X=8_pz#WJPZw$R#{ee}$T_Vux8`4cq_#=f6{Slo3vpDRas>3P^oYpWdo$ z@c9Ls&(w$-2aTY%ZA8zu2%#AB!dnJi>2Y_hYn%Fc<*m#?@$KWq#!bJ1idvWRh#1=> z5X|Z72XW-veZKfOC{5)~saZPc#pG&8&5vfJo_uloPN{PM`v_2Pox;3QTnPu$U1Ab+ z%fuFhNR3f>fpmO9+A-Ncv87awIOyqoI6nDFjm5yDjT#XT5}J9j z!m7L9$L+_+^aH%pDrgUD1wj`!$?fp02vaKzLtU4tKyPMMprQ?0b)MZr@*Dr%-Ei_< z4UMHC0~^u9i@Krf6IJiFxhq*b$T2C%P!_>2au*p1{fhPfONyf(>!;RH|wdm$bX*M1~VS1330om#9RGqN&rYK*@=o2f}nU-gCGoV@g}} zagc$cuu*SQXBF|qjR(dmKJ^gkddjz6tE=6a97t=#qM%350IfcyGB!qgYJw98xUDtnH0gI@q&7777Q;7pogUTX>Fg}4N8a;bRR8eEV#hW!E6 zW$J0;q_-soHo_}c9)Cgo3g$Js-}vOS8jF3D1H$McSKA|~F!QA%(P!WcimLE2{Qk+i zvbb%$+M<_m4}hZy)UiEk)jwsO6RTcxUk*%Oc3{lb5&Edgf?B8SKubaLy$b#HACnKM zEa2`^8qWjU>)dS*)Zc48u3cC@qupmHd2uP)Y={N2iD-?i$T5O-lTRZM&Z$TZ zXf{(+Ho}ZmMvCg%i#z5z$ykX1-Qp@dcVUcvNvR1n+L8)_z;P$AvncpczCjm_a%hp^ z$b#h{W+lM&`SdiUN+XDAY*qns4<&At5fRUYBYQl41hxDAB|muaPJ}#nj8^cJUxZsn zCo7pVZy`jmH(i;qJwSIp1UYB=TNW&xVF<{jl$wQ`uBM>?sC0h0Ajyp%CV617QH;rB z>!iwj`J55+T2H*m2cp07pdFVdE1(hcln&XX8{8%a2CnEH)QWHI&n|Cb50$2YB2s*ml*|PABpUWc!}5 zVE1#rK2b}RcX1X&(8&-3@YX`p)DsLov>N*#skgJqN2GkI!$n|;ds>#NgV1D$FDwoS z$haW;H`$xS4rvPIpMNG2ZAxFBqwqFO4H2JB4vbhMektgeG zylEke#Pc}%;}X>_ZM25X>!8g~ZtqM9$^*Yv>;i^UktpdRH4fkK^dr8S-$5V2b_d$HVP6yVd+M{NN^kc{dtGt#yM@~fD##>j|fLH?sg;yhu4bW4o( z4LG1Ci0UnUKIG|@|MF^*tkrwlQXo_y^P*?Ql<(>r-Or4OnQ>EqIdDXZ)J6p(jfc3> z(IV8oc@wZN8bit_eA5dJcofADg?y2D<^_4>8F3oVB?BC0Q}}Ixeq+Xv67YQ)qv)rc zs1#4??=)T9hc(W-j+<$TVB{RTTr`Vg;;;|hdwvM%=-2}!KW)1g#f3bV$)lTeans8+ zf;B1;tRnToeP{IM=62#qugp&V0GWMt`fmtz;+4n*-#W;GK1CSW;eHjk>|fp4@TOMe zca;pT7{uXR7KBVdgTI8KfOF2N~%$aY=uV>VT zB4gb!_^}s((#ne-K_L_=brLNu9J#f9crH@d>p(1YY9M>G2mVb!J&WXa+3}?xNWAAt zShk39%ctU#=Ua|(_!Y|4;2H+lhi*ptz>o%hYi+4DboxHlu#`erGll)t%WJYd(czpV zgeC1~B38Zwz8HzCZ4YBrcUyCo1P>NscB3ewY+^_lOQR*#J!!&d>%JtF4R*~pA!uU7 z4SrG_doePfyjEwvEaT8(cc3WV@sC)l>c&=}Irv6&LWwuTUL~4q=ntX+1mVSil%b;H z%Fl~Uw#9$+w}+d(JtInujB=Kv|Mob_FExH&;@G`J?jLnEE(%I~ajhD9EHtw1p3zk3 z<|ooQUkm*$_9`U8&Z8dCzCgZSJqR;Tl>^VwjN4S(B-9R<5_M8~Hwc__4lk-`eKL5s zRjKr&#Uw*(`%pT?yUjrz)$o8bY#YP)O0psZ3m&-oR|B~v6GrxZM`d08gNJq3-*d+e zQLm$jciK2~Zm(@o0Z<*5?!8w=?6?Z<#%S)f>XRTF35I!dR_$8KToxe7g)$G90WJoX|kq3NZtyDOnghLaM>ou`#a@xj3S7O#pRv;%ckmh zkq4blWkzL=cE~QaB3KURDJ}^WG zl0j5U9fe+X5gHi(cmcWZTbSpe#oRTYvGRPH{1S=zp=nLkwL`WfiZof_^<|YrB_Z1C zET4I@TzAtj5%B;31bG3TJB(@~zW@L|lfuTOtrN;;Naf9d0N8apc_nGK`qg-`F*M|d z^owcFLyb#xvn-*hEWj)?VXXxK(AgV8XhJ5l^R-PB05^toPvXo88R;twx>!EH^Ky{) zisPr7rj7bwFqo>^h*x|#LItz{kvnedW9BJ;gEhKL{q2Ek9=ItKZWGJ1Azvi<)|Ubd z=W{?R;_cDgBb4EoO^7nqJH*4hc_Zir@5;3qiPU{E=@jBTP{QthFVhaLL*^oj>vX>Q zOD2DI3oX*{d*KGph_RJm!}gvKOt|OeP$oDcSJTTEAlpTX!u${QZ)i z3n#o>S(mj-)Lec&E?xtPmTGq?!Ef{CGlBkogYrGP#5oXvzP9 zXI-vheg;%XKYk+;8~=Su3>cwWKTAt?-*}4Gdu=da#%>J%s_bcE@=Fv4t-9!e+$;_Tu{P_VkIp-nvzk@gvm z+*O{PNK`z6w`Cc>YNl+JmNyEbW zs=*vvwx6&H)Sd+GQ!79KIWxRapO=5~9sqnn3xE_YGq^VuD<=O{8DF^J)Xl66B@fT~ zyFcyA3LprmHc*xxdxl>%`PXoNbDS%_wZNFR$%mZ7C=B(;O@w`f?h|V$2oz?v6FpOo zHt;t|cTJ%bG%AJJy7oqALJaF;=f=7+;@LIP`wTRg+2vpUn1R~S=)r}3G2MdvwzZ>J z!`iEv!ynfJdb%DZ-+<+3v)Jm4Dou8`kM_T@EDdOZFNa|+B7Rg_hV1ReFVmbbyf>b_ z`VIf^oWYNLE_t0Vgnln9av{>S+9H-qr(3DI|D2)>%epAf~~bHKTP3aZ~$Cf z`W8B#*`^8uO%G8hq1CKT41kP40><157t_3>YG!iJb*I%ruT9ry1kAI9#Auc~zAXyP zkQfR_M5IasgBn+$00spB00JZdo;%ERivIurLO4mVNSmDU&HMlW0{{guK$&8Iq}Tug z6GN6D`C-{vy2yWx5|nHF*~cQ?VFT1!5IXUh?J39Y@i?MjKEyEig;6!#Z4D{0t@g!30jWGATFYRbAs+U%tCD*s034@XCy`OcAfjU@*igBa59QqxGDV=fV5n#lEe-6SN1rJtGyF_HK**_ruyl8;ArxS36x0pl~v-~s0 zmMnR1_A~$EM;29m|Idz@;iHiFmxvT8{nNQit>r&_y=H9>fl-s&k4ifY5t8HTXtR;i zM@p*=(1E#Q1R*C(n!A9X#*Dk02#nR znmlHpKwDa+wY9aiCQ|?a0{{ZQ000On+tp_`wyn82Pfj_J4M+J0)B8hZazCSL@+_8D z2~xD%hF%Lw#sHZ~hs8Rdo|hx0=kh977Luc~@Ok}e8&x2heqcU|Mw1Ue`s71C6yH4b z?}9FmTpN~9@lxLiB|v!@+=Q+pTtMeK(@YM)BEp+-ZBUI_*VjZ@Gf@=4jzA7xo8H;u zRN)0azygECvOOjT;8Av0gWO8cH)#ocn%=F2Z-%3${WfkGXX7V zY!4B>b78!wF*&ocUr+`r?vA>rb{vf5u)pjQI1A-4SH2OVu{|91Iuv zMEVff8mq19oW*L@#=@r&!STxw*d-;n!0LX<)>=sc3`9yXqI?Aa$;(9j#8!}SLk`?s zs^g6zw#=}e!6JOKZd6KTwRR-C==9UzO-Kz^Ysi28Qh*xY!%)ZoZwqK$r!)PCW>m(* zN%ph5Rlyc&q}O}U0>=5zY!-4?{!dG{=iy5TYmiYwoMOt5K!kjGYP?%rf-A{eamJIA zh&y$}29PE;i|fD)QLa;{x(1Qj-gq?}Cep29do5#3ahuFV`Oe&s9U%B@W{IQkP=|pjC+SU0g z`VZkPbRG4$o{vj^Q`Ee_4^oqsb*EHq8IXViV)mHDL;yCU1Z)ty5vWBTz z)X2Tjngi%LLSnkRF?|^wW)dMB$m98e3*sQGe zbW%;mUk`a={}mJ|%y6zI0XSvk+@ z-LFha@Y#bnt1^=Oe8x5S2`PW&*8|>@ILPwFF!KQNlELwr7qZWWn+$Fs&EiDc%c~mw z<3eI0tU&~nmX)v+h;vrE5leNFRcCA-PY{tL^5XG6VnZ+i$3(L)=#hQVf?fcbxnPp( z5xwT0T;=n)c&MdAz2+kR;G}ZR_AUUIBaJf^B3L1fWPC?lUauF^w|5};H{rMsjfTGdv999zp0&;rf%-p?f)-BZ&IZLyU`aleI*0_8HHNs6ea`)n zbG2q!F75@XDTn;nrATx;9iI2O5N}UvItPJ3BW!QEr>-_ak|JDWz7e<-0*Sg*;NbKe z)YapqnTK#g))Xk)USmiJbi0TqBw=&0E<1xO>)P;q-_yU7Gyr#rFJOJ?_@|>lJa~~J zW!~%{j>NIr4ugx~Rb4->fT_QM7Vr`eQBw>pf8zdU7X$~|0v(Pri6P=BcT^xUjqT)v ztP8b6+M4lE+8~pP!C8477J3*NV!zV7vFnVys{L*9q5ZFdt5dj<3Zi*DY(^xNsvN~p zlXnncB4eln^0A&B=;%P9k{fAR*;59MJ=_V3AbqPVnN0&Vx$ai zl!3(6$*J;IHhU7PW0lvq=ho2~TsEMWaRH3GL?dqSIx_{D0i$0vPH%IQB~7Yb&j(CZ zPiTp8<}y3Z%b)JK99C1?etMF4H1ab_utTz0p@e+V-9jr>prufq5yBYr+};-dc5N{W zx`}BV3;_%!Ob<}>Z`~O*e3j*6cgK7v zG%|&J=Wx_54Z>RY(rlmSb|qQ&%-zM9b_J6 zA2ZxKs>;UkR+7Xr-u&7u%a~xKz-rT$>&2?Mz|--)KkOE?oZeu`1n7AZT14~RM* zps^>_mvpXC&TA363-JAWSsd)Dc3 zxBxQlUKkK3B~3buWXO$|(jH?EF5ZN~Qvydx`>H}K0Kp`NREPt#s0>s5OXqSwI~qkE zu;36;mg9kxO;}_gm3bZ!3(g&Yt)a4Y$4=Czc(a+7rb$3r#x|I5k^-@pD zKdNaqozXknCu5m^0!d?V&t`1oO8?BtygO+jCF|_kU1`Jzx_pv?UQ=C}AWLawuR_{J zkwJ(DYvdU0(tEr>{z(VFj{_$1!y+Df_$k;ZcZ<5kk_Z#395FezIPM=Pid7nP`{p^q zT9i#uld%lT^+AnE9Hz;x_bOkumJ&{TR>ktsB%*U=5&|D>c3qBEQPg2HI(8i#L9Cw}gAXxxq**wy>Wi&=!vM=B& z5Xzn96&maS?KLqb_~G0+px|=xlGo9VTi6{QJ8H`MD&P4XF7wAxOnFOqbFwt>j})gp z37$kpr+am6xquQ7qw<9g@8hV(nqul;TJ=lj42cC#txH1O!Cwo35xoNFE*yn>1}1E^ z6f0lb9xMdI-l1XCaDx7=)`mXYQt0>y<+vQ45izD*))AszBQx=2Or1hFr!m^HPq={17(WrQXY`mPb8xe?y@mt%p8?zTNud}b>PFBF1{X*s6CoY zmh2m^;p zO*u%DI3^7}&YnQaX^3}35gO9Lhxu3E`&Y8ty*YlhY4hf9Nbj6|Vhy059~=TY;M}_h zOY3)jII}8&>hM~a z64njzY{GGnzQR4eS&+^OaQOZKV=aVWOlq_aQ0LGZ(II$~MwP!u{D-|J%)e&iyN90` zXY-DWps?lIec~24bMe)@kD%$_L2$k_#}-t!3RsNq1Vgas@81k4*PI!~ZBsJi;#Q?v zd2YjtKq->4W~)Ff=3UwYUv!PLj0!=s`$&DR#c(Jf=3H*hp`f3hO~siWrB5=)Gw9f9 z3Me`Jo{x3@Hm&E%9k?*}qFB#uM#bAW7(Kt-1XV}vQGy}=-)2y!_mD#30=YA?4JXaN zMQvI$VF>uPjP>GQj#s4JwpHrG63RC|j1V6*oiXyvS=iJmMPgK8JV~sLdK^usGDgw1 z!<-HY<{kp#NknyQZR>B8;I0>%mp4?#R_0`G3j~~MJ1YB`(|J)yK@^%pp)&`*2G9+y zz<$tI3L4nPFGq6djl>C&9J)*iXZhzh>h|6>d|a5s_VTKgkQa&3uTziS;(iEpIQb8s zP|q^r*EohQ$f|vv$=Ry=aoh^_AAE9#yv^e4aTle0>cu5XraY)2w*+=| zP3fj|NY1$58$r*luuCKuA9R_8Ebblu)5H0UZm}5aio?%^9d+Wkg63lYm#~bT-&itt zqJ^>&7P3}%!1BxLQn{9(8+9xSM7qwCB%X(mdrl98KpB@2vOKmR& zWQbPNGiCC8kj=nwy8{l}tO3d9GuuY_9x|JO33+_0wxcp}X}Ulw&uXd|H8h;&+Y$eV z*Y~0DaKhazL>2lYB$``9qq*55%?53H-A*jtCYI@RI*zw$#Xf-Pho60DoS8%UMKpEB zzTR)b-_QH1eS`qGUB0R7Fy2zlDL?Xvz%ma=5}hvyu-;1}*y8d>7Rn1Fm^4T_he9~G z%mtoQ1omY~FRS4El2-?qBk)<)*okyL9Wx_RtbPSdRhNK}?Kfv}%!WY&g#|?FMCya9 ze^$n%f&R#y45j13KtNkKdBTSZ0>2=CX=LMO0-|KPgU1%&6Yjney+?7aLo%s4(RJy3 z6@)x}aDSer?gHJHHDcfP;B(hE8HVaPT?~apHW7y{5{LG(KAC|9k70#o)Zm~jo}Diq zk)aCR$Za7YE-3P{6rYFxtHM*CzYCC!-D~RO9}J2DmQQ2ZQ}~CZ0!k@gAdKa@zicA( zPs~hC>!}}axAyMUk4#)7>Dh`npi0I3APvpjqv`RLywJymCaz?wo`?(k`>=rW7{7Sz zSAc{Wu))`N9n{@SvKw5XHdCl~{kP`nW|rv@-RL_Nx3Zt0FMGd_r+5pxvT8$Wr*5=iD!0>6G{;0r*^r*KCCmJF!#yON4x}-?L$;OmaW$YLY=Q*8%pB)! z^wt>#DDumWem?w}DBZvRU0Xdz_E&#s)EjUAa>Yg0=Oc~d)~B{pkpho8z#Xc7UJA#X z?+pvV44Kr1^kLFuGu8I|v_KxuQiqJ;qgNCbsqzPis2D$id@+1NS7blqD&3n!VoW^) zDc*{>rn@PAFd5`XNEc9=B1%p;w z#Ze1;P((f*zYoaY{^R;UGNY6m${ky+AhDUF!Vdrfa<_qV3>tENHnb{3YS9jYxa8Z7 zMZC+2sZ*Y#nEEIqc-HL3A!B2WL7Nc-yPHN?14FM4wlSoWbK$O6_JG>L8{jYus#w*U zH!awZHWY9KkkHaJUxigIXjP7Y2Awj4TIiuQ*{3#cOEjLI#sN78#W6LNAgzx^o^;sF zt1Xd>{Q^pM$67)&0`w1diHs10iBYMAjvmS-eq$-2T`oC%)NG8DSIDnyw3cBo% z-v$E=dUKF`I)2tCuhW$ayQ)=Gu%Tsh#SbqBC)t4=Qw^I=ZN)9Oa76Bu2T+~G4=&Xs z39y`i0POsZDCtLiLZwM2Zauuf+ZT@pbb9Q$ZZ*d5&7X%8>~W+jl567zCM}84E4e|T ztNp1R{b%&SHzLkrYHQamiN2%X2vwrbV^S*4jXMUoe`#>%ff!IvJ3&`&g{Evb3WYj{ z!c6J2eFw-%89LR|$)^SR;nSaC?atXzeGd>BX_kapXP_6)ywY#Yyjrko3k;?9FP~Uc zYNdZ!R>UZ#4v^NsoZh>YfDSv*(Hg}7J1JS{v53*wzv4fBZv>RBiUDBb?asMW#-rq5 zx>hJ~Lg@&I56laPO?K&10&{IH%quc9ap~5Yc4yMji>@({@^_`D zgbM-0Z}Tvrih=KGRqa&=WPU95&FNBc_LaQGSFhU}lTn;yy^OX`-MX2&*OeMQSxcX^ zC0E4P9|bQ%OY=JwUL9nYzf%df-XgyULg7o}zK^Vr2B26`Hrl3?jW7ndSCxj;E_h>8 z*ReU$3ejNr=G-F%baIQ|X^Ri2gt`)31q=E0lVA0!8?L`mJN{G*s1lRt?3NrCU^bU0 zt^oV1e0lMynQO~hgBjA<4ReEngPmBq|D&Od;LO4t2m5D-se$5(yhb;KvKAdN4o8r= z%!H13NE&PZNBhEH7oBO0D2@da8=+YvR~ zBS*t?piwJci5wnNnAr>~$fu?@93G?686QqfsIxm@^9!N${>2X}`zS&$W=ZjsKY4l9 zWaRJujJy_8BN2GnW<&7rfJ2qL5DkZxBe71A0!~D7a*S9i?cv5Z5f8Ry+aKnEFNoM# zlVxl=X>*>9TqiFs+xkPd14vNBaxt91hX2u-Xv+<%uXj(jT-dsYfU_IobkLSJl+(oT zY=hSCKfmci$m79{L<$-y<)vgRq~3q3eP2lGXIq6B8EWKsS^;h>n7x zndBKZdS}Ny1dVhK=BS6|esbdmNp!)negjb-^QRplWlE}G{hJrKi3~HdHLxp`4Co&~ zUn4LZ=V=}zOc=x_k>FCsTSfF+Bx&u88*SQ; z9BzUWZ7VXqN`UcXXB%@`$fgnZ3Ip7NM*-VsY~I+CB&VfusWzu#;G zA9Kqu_y33D@W<&F401M7+0nYba)K#b0Nc489z63q4B|b8>lsI`07y2Z)P?c9`lxMNK6@A0Tsh25}lyvpcspd4J^H8|18-ZaHPeCSN`878^8 zEm-?L!BVE2hIi=RB&c|FEWO)a))T=Z3H2^U@L(Z=FJMzr;rB)q1gNuHo>49d_T5oZ zS#gLT>mcjWjXWp$#9Gt{pnZ|on6joPdw@Nv_R04WKAjVyc&VXNC7lsK`}=6r0=6+z zfG-mo=x`3EHyL=6J_#43z@_bUD!w0hyKdxYx)fiW>gWb^j2cC2wr8F)R-pA|HT61p zJ1?L_wMH~?X1*3=_rN^)$>YsX+)+84^9HIEc&PtI^5?m&ejL|>Y%s3*jd|;S%w}sM z@CS3=6wdBdzbGVY&3v$7-&{xNsw~1Ra6?2;bdx3BkD|>=k*X@aH_POO%YnuXOj_NX za$Xu{oydz1B^hG;s^xs6P0Dtj5~)0s{>0*~Oc*%&34FNB~m+BOlnylsDwiVN`U$h=Tf24&qpW8Mu48(UkyL-%;r(K5??0pg4_3ZN_YrG@Bqb`G&R=r)~bD%P*4YvaRPk8e`X1wm# z0(tHlHIZa8hup+$WR4DP4EE5+4J`HnONvtcK;fH4c*3=xmIXQzP}ZXzXNaKc2)20G zX-e2*!#2%iGEn_OUr*XJm)dWFg{!PFu{TteYX?UgFg`%g=11__lPFTXJ5C;#I~2bj zhXlab<@;8bmQF16d6b&6i*Lp2VUfnT5p3SVK@fq!Je3$^eh{ZFcQ>Wi0`Lt@O~Dj7 z;MsNfvcq)D)ar!26-wgAq~^r7%x4*qV+wFw^y>tv;~HS*jxgom?L)R|@iPJ4yBoaT z^e7;TLLPH0<400Vz|sHp=W-}{90ncBIffE#^X8LHZKs{+9PNvtj|Z5YlaWeEuP*r= z{4j9dd!re`HG8y2J(LT#Rb2to!MOkS%gFKBc^gw$sg9_B`(_yJ?UHbO@lbQCu@ckc zHH&Y@o||^!qrmZ$pe;|LB!kBwdE0I*anm7r_14G!8yt!)h5&|n)Pa)FN3^}L z2lGiTbBt1iiT}l%pk2?ODWldiUf%I=)BU)gfKtm-?XJ(qVP4~c(JGu302W22fE=<3 z-kFym?Rw{Wz)b1z_a0%7PF5J)v>fPH0M)Z!lPVIdr1pR@wJM#cJV_NA#fnlimQ0+q z`kZhsA?a$^1@RY)_dp9Tnu-`J8_);gsUMy9E~Aj*U=d5pT$CE;J#aCQq=W-1n(dGcc@5+*S;`-$jRY; zcS}Ws?0x%L-)(10kh*yjk0rzMYxI+BY31)|C(`0D+4kL6rb}9tBcKPG>P*-tG|1gr zUElx$>@@~2mI3&4?$;H9ApRQfd>CtWf-0n6pswV}4BkW2{GfqzEaf%*R)DW@GM+Js z6Um2welI{bRtg4#IAXJdN+hb5$WS@U#PszBP7#KzIwCq79%h|zR4;?;+1~LPCqS3% z;T!)ohJ#Yw{9hrgNow=QiyUJ@ttk*lT*ivJ|8fI@Q6jTcE3!Pr0$d`t-xqff4vjlw zDn9MLYo!N<6(2MDixx&IfVv|)DYGozUaon%R3HI_wVZb*>mQIO-d1ThbZF}zl1rUS z@+)8I=l}-Z@I9JsVM|WL`_sc~^Xvq@%wnAV7$MNknDi(`P!Uxsq}UX3TDm@f831{f zh97hdC2IxNlhrL$ex^VcRFDHvO&e=Uk&k>wSqI$_4d*9&XTQ5B{vM2VFVtbbrBifX zeTU5N9r9`%_z2_V4Tv~N2!3ihxUUet5oqahUktuZN-qmTG>P6hA^4v>EG7f?G;sh0 zIvnz5)K_mJ-7%|;4wKS}FSc~Wi}_&zI&oHlBPTd;hqBqy8C5$NR%XuArwI4WxAGJ{ zE2ik_x@rpDsP!y$*kOauJH(KIHbUzPv`jYCEhu3&!C6otN5B9C$-+co;&G63@r|WL zcRfb(AB+-eJhy0=P>~+2sG~LvTOS{}G3rG$X8hA^m1(a=g2i{#=&lq+!v<&Y!wLK(O-vHKx@4n%|Ld&CTwa_?vAb9q{N|iJ0 zrLUF0S=PS+xgaGHjb#R~f!JW<&BY9H8rudUR0EdHMIBmXB{5>ePlyQt1Qn})LWYtK zeB(>trFc)vy)1JFu+QXpw2fN$3S30Zq*lUi0>K5jcIP8NCFH6d&MgJmYHHt7qrhT< zMjbgJW~pY=GnLYhD3pqHtBGpQ!^U$zOyCcVeTXw0fvzcQf4j6w{YV$(+5`{coPZFJ z_H$4lGIIwy>Q_3BJJMn6B0rO(dF6Q@TGrV8K+}Dgk;(kb8MG$}hzC}Vq2N}*6hjqA zUCW-;HMF@ejR@aMSAYKj@9)^EEBSFYq5>bU!ybHKgbCKCNSIi5$aqN^QRq5jM#ZQ~ z&;z#G@Zb{M3ywa{tL7lKoVAwpcj1>6PGnW+&J1HW7PfN;D&WxQFz@}Oj(D$`q!ib3 zFz{%_DhRmjQ2Xg^sfl;tsDX7tl*|eK4Q>eul+l{JH4AGfzMG(8TYBU`3!hkn)Y)C-4(f~`q0004y0iH|@Y9hY?03P*iSc1P}V!8l#L>ulFCwlJ_;0sMaa~6=c zzpWkp^qJU0Z!lVcM%)G9$N%N5PXV}H9PX#Q)&-R>P;r8kZ_Wo0_NbIQlB#;9G;#9rL=~+o9 zyI4jJ!GcuYAOIbnBqZ(lK_U)zz5oCeDZl_LeS84=MsX7A1PB1y16wv3BE%P9&u-oT z00rOx)g}P?i8Npf4~o*ML4zwD-8iM<$D%==)+_)f&rvKpygafp*Ys5+(|qf#7s{pEDT@)IcSqQDDRTJ=%D?crX9}iTzT&SZzN5zX-p?Ge9EgTmXE* z0004O0iH}ubc+7~03S-=f_zqa>fpFz!UQ0Il;7_-1Phr(*K#-3JP3ZJa@mbbVB@gPVz;t4Y zkpPE)000*tL7GhFpg>z&TBWtMwI)*l00RI6{{R37I%mYn!AFf@KjCRhtYdovf1Y9> zDkmUo)4{gR&ckT?0E+j|k_o;#q%( zZVgg+6+t%VgohH1m&PSYF1~7yv}6Yj0b0(aheqRIs6VpaehVCVCUZI;nd{F8n3W04 zv^8Bxf^p$W$%1g-c{)tmh}&aI&JK~zg&7Nfs%;YCD2f&;X1n*Zddq2}pJ|^O84g+b zJv$BOZ{2);Ag`+X=m`C+)j9EZ??r-esKH;pFf4`FUO_iZk+GI6e&puVGksY<}Tm%)R|lD85lva34A6-`PX z_v@X9f9x%smGYg62Ofv2E~`40Y;#8Ut@_!1DO0M(T#s5)zE(+*j@;=o8Eoj@>uFQ6 zzF7_Wbs2e#hmQt?ev$jCAHy$sdG@ z$q6?6mT5)l*y3O@VD-snO`}?T4OGLtqqJYt7+zGDuuyQiJYhsTQ+HsIXr-~)H(b&B zPTx_JdpN}$y^%y_2gbqITT{d!^sR~)l+a+i;vPO?&~HQ4g$)Sy zk&dop4TZpcm_{qI8#uuIsBUAaMEyU~ALszKM7Y*w{!X8%z2cG{_b} zHy{+3vAzt!5hC5FDkirRxPiz8<+vZ$ND^q55ap=zTTIp}h&CoEg*5@bnW>g2D4CHS zdxgWPM@_kU8f4kfwU#xy84_AD9ArdD2!T1&ve*0N%W51Y7KPyKf)h@3MCV%4&I!XK zT82a++-YQw=z?$bboqIN-0=ScbA~2MkyD*(@99+Q5Bm{$%+s9*NN+!d9(qJ2Uo1pM zexSx^aRcQfjSiUH@}eD%iMsK!XMQ-=GqSjG?Valq*S zb$?o;$7EXmD@{2n*}3ZD^#R>K+P$1Szo?8&!CZ2pz_AN=iy~M9K64Qw7F3}4s)g9p zP4x^Qrds+5bs6MLBuaJ&_kK>?xnpSGStX{au% zeR2r$#>3GCnmVR5|4_CxJSk0C>3yu-e@No}Q7eGHRECH2oSit8XR2M{iCF$yWf5vF2a*`vW(lRf8A5H}Y+ zozrBnVe!!_2$IlM%xMEywD`vu|DdIqG)$bvb|Jm$A*VWySJLL5awr3y-Klhxl-yO3 zGD1YAo*F+~E%sTWt-R^OEi6pMrO%(3q3#iflMYW*0@AF15gelJlfWj1xHu})LW4ts zuk5QD)p7X`W4*7bQEs+-OPO|3!76RhgQS`dEd>(Qxs zDCLKd&G!~rgn+Yl#qYQ38^j<-5H@^>-rrKP)`dk-{m{AXtBjIHvTUr*_$cWLJ(Jgz zWndE|Sj@9`aqCbu9iKWluxQel&zJ(X9(p)nk=8H|8JpN>8e70CPz9yfjzI{HJGnm> z@O1nnGUO*yt#BViF%8RRlsWBXj4NviPtTP<`}(d+rlF~cjy~q#6ZCvsGX=QVzFOtt zCzM{S6EleMsZfn=ND-8~KI@PXY;B^CzcoPfq53zhzP=OU?qvJjzTv!f3lYZ&Cjk9< z#ew!#y#F-c5f+~s$I6hoLs{%uJrnBoz?Uu#aX%kx$bh4sL5sX%jw{EzR7zZ30XTH>z~L0FS9N(0FsY^Guh;f*six{vLT0& z9!z}O(8gTS=|H#DhppN^fGQXTOF5;}O?1il(#$~{^s%dfB!|ZVwDwa?F zkO`bY;`514XL82yuJd|WPez#$h9)Zw7#$yej{|h=;FHtM7mb4B8)p?9UJJ@4Dd$Ut zCrjmJ7A;!lgwa9?Aw~A7lJ5Ez&lrV%^x1^@(>M@D{hF}F_BOyUU<$A1MrFNc$~FOh zW0?WCAMBdxQ4lVG1=Qjh2%W^g8nP1ws=ZxON^-tsh#}=9CH=WB>yg=|2l3G|n$L5k zFxcijl#nn}Zb2vrk2+M2<0MB;jQ?LxSZm|W)Yus(Cy3YpL;v`1m0yqPiAJ1Z6ycU~ z77?j1uCKS~0mduN2v7W6#wNKg3>bR-zGF$M&SN=%4OJGMQ>P4{$AO?{ZR z*2KB-V#YONT%ZDnG`6$&g|dT-Cpf}ByUPf*71N{1ANp|(@R+_)MW&Df9*)c+^n;J~ z1I{(=OdMrbhuI$ZVrJsj01xvNI4CrPeiLyYqSs^mKHBNEnTx}9SOAg^%Bbd&fKAPC zUKMixnfxi{S4!0^<%gsOr@eFc|A9^zYD+&D_ z!4hxB2yMj!f<}5({>=U2(0?f58@m#voq&2m-i4Q&6ecO5u;VITz z>mWHnWs@%wuUTk=Y{*h~w4G;PiEEoZE^MicT(p0xKYjsvVV+Wsgh9@>H8u^~Q9n$V z6TLq*3;sw(&8SAwPTcC&iAm_JXqGjV03^>ghtYJmhdx9#L_Ng%@8L@dp$f5xY$9mO zH_QH&f)-7TkHf%MGLoOedG2o0SI$)%MQN{in) z2wawzowk-SvpT|0P_t3sT@w(IRFMU`O)^KW1Wy$=?MI2C5z-I8^6A8h_#l_irV+01 znzpw@vRD=l@uarLz?CXSON=jtzUlcS*F-PU3FDstKg|Y(L6Ee4Eb{^mWznKC9Ek=c zT|Z5ub6ga2X;6U(1%&`25d2G1DV7$bE)mn0kO=~-OO1j?<5lM$IG2j9<8H*6QjI~D zO`T57o;qZ`hYlitxBOV_fW5}+@|)_t?n*UitGuOfV$e#{{qDMcws?^Rof_ZnB-Nc+ zfp1jleo)2=WJa7n_$Oxf9T(b&@YxFliF7bf&);Q!CPuqLHuMow3NO)cwY#Sy;&QmH zVIpP!dnQr)7kKES9uq9r%6N34i-VETlVbn><&eX$zXH8zI9S^r*bp|4o_TJPStpV# zyH9$4#XrR9ap9`D12tE2OS^|`0K&g)u9`PuUDUcv7Vlk-*}FU#QlpVn244Oo=DGPI z#T414l*~p3k0%+Nk!}cNv}oYwbIX+RT62Y>X&OBv7t-x4UEqzb+c!cxuUwriJt^Uz zrB(&YaaP5hhv*Op=iDol*9+hFUT}hBMx+;7N9s5&h7!^Q)kV zU@N%D#v^O3?v5c8=-WJS=p0awXuEvr4g4T|oZWIP50rGnUL`RBJ11mMe_4Qfbd<%}c=7GaSg;AR zR79TjIQ+z^HN{||PZ;kpLw0`$Sylb2t7-s+Xm|MT0B7WnAmN~s4v#l^y8rL)(P-)) zUjEP#L$5(zolmaSVgh^h0{&6)VeHkcOuB;U$FAj(TAy{xz#4*p??0uJ@fAa$4=)x& zk4l`{qG)tIr8lpTAe2xj=7*@Y6JZcODKJG&Jf#-1)vjdJAd?fo7#7uM{|Er8ug7USELVpSKOz$qfLky^Yy$WMgIU>_^!kPk_tz z+Y@qx?qxFoE|I}WmP*L%YyYrW@v?TGc__5$#l&U2AhpGMl*JQ@)pe+hmJ0KI+O`=5 zE?(I}jIsSs(X!wOwys%{KHz1T5Vh}|sDKLMe7=DRV$c$S=bE#m8aHXfCdp3>nO6mp zhd#Y7tt&I2(s8zD9~-(X)95-pm`OH4NTC$>^d57NuGpFVp~kgT1=aV!nu*mP(V7qo zbXrI>0{kMGwBJ6gAWd~g1}K5Keq6A?aB4-9uXOq?JH}_Scma70sU5gFs`kv0QeXh2 z6?hjcR$;*T(f1o?Cra5HlELt`!e_Gy(ZEY5mp zeDAPykk{AOv@y@|%BO6=ec>W*x!@i+yGJ50^D|@N0{j$HM(hP+z7r>$1OuyV+;oI=O9pX{hXC0vo3Zr&}a(n92wfnafDw$#s4ls4rseMk!ZrXzUA2;Va@hc@?Uc2{-&qyCzLRekhG9 zfPEVu#+%t9mXzLkEMnBMqV0Cj!U!x8YaiDQm))Txj%w(H(4h%ZCuEfm_@=XE>^#4` z!C4}g?=Hq;ukfEMKMtvF^Q@O+v!Yf7eE^CqJMT9Y19^~^8PP4C5t}T@g(8LQ&MkK!)-lo1&lKs`i=Ay z#y&tE%mHKZS+Nov*Xiyr5Udh59_wxVCwL%p_;{krD(i6}hRLFuWcYedtH2x;RFsJ|)nrlf~uxKCm5Ub1^` zXMWR^2}{I$$X>`+ZH6Q0M#4^4sRwmFIC(}3S5$Cbwbatp^+r#t-P!$lRK4pN6KE2# zR|cp84qnm}$0cDyQ!Yd*Gl~ug*As(1TTdFJY{Q`7kc)P%L-W>qP)84!I?GZF;I6ki z*}b*`pIU66tIOjKJ-xfpwezp6hJYY2sW$W3-wQ7Aa%&j)-6PL5!XF7yE{JdW^XYIL zuT>Q*p@I_t#`u4NdS%wFJ|&0FkLIUSZ= z;zR5b+-B96fPn?URGwh(`Q<<>?cl4tZx)kaIIjKu%(v_uOdq^-lKu`&l;tnV(86TM zav46o`YHP4!-%qz5XqLc%D|x$BJI}!uH(toNC^sNnnmVd{_g;FUw4 z>Jm_D1gd+|tyXL5E%{BT8+NPi3?Q`-4Lv^;3U-+zy!cSqEWcZ;o4n< zlG?=#_B?GeB@sf6y{~2wFAG#750^yJl#-?a{dSAcAfcR_YC+xegXpT8e&sCnYwU8v zmU)jKb^eMb*DkTRI&BImHer~CiDiK|j5A1mkFt7b-}&{mA~UPQRF8m&H@Ji;hbK5A zU>@kmf4b5vH%M}+5hBH5#;ht7gTD}Gg1y%>f!n8N=?;#CtyA#8CNH_UDA|?v>I$LX z;MSnojt;8;Dq#eGyyR4Ygrkdb`94h$E*imYmFi~2{wL3NtJMNO@sofgs;k6=%ut-F>Vrua9IU}P>V z-2l$Z*xzBc9_xAb|Ei^ml|wR=`wQ9EYl#F&Zm1cw499<}){ucJtX+{Y20{&1K@Ttx z000lvL7r5se4*$ei2ncpGGl|!#PHK`EJoeZLs`9uF(q#J2^sg%fKzd+6J36bLY=5M zieL9JwM*m#%>?6B*%$9rVjH1^>U5^5{S%)8_=OWYOycdn&iMHsGYF+vdvJls#4WBS z!idgxF#s4O*f0is(KE;oORx(T@Aw=dRV^WeYmqly^#oiEu8gbv2gqMJwsrrZg*Bj> zv7OGGk_E)$IUVWylpsUx2G2U?00-bb+H^#EiHNmlw;pH!1<^A(kMF)-3jUvS3-G>b!VGLAASDP%@0cEK1t3x(reJbz}y5r z-r4cmx1#2RK9uCeuo2AM==dFNj~1ciLDd&liWXDjl{vs~&gUsYt&bc72mY>!;Ow)9 ziINrJDwf)FTFrya!zs=ki2oX#b$ql5#=J#Cl;jIt{Sn1Ge?v znRVl^RJo49<2g7`?JY#lZyUF!9;b%3kNV>Cl!CemKk)J0U*KF?IX zkQi-;#}LIQwf)Z@I6zJn#%*3+p$ZX(*|EN_pC3c7REkigqs?m?$SAWGr*5JlC@!2OyrnK) z;G$se#X2A|zJ+e);LNQs))#piAdx6VO`Ww;Fb^<=SD$L>T021}a1K0sI_LS7iC}gv z8S83*g0|aAcxBPgo0Ub)Jrw~@LKBxwg&w@l2#A~DFQ+~Hl3q;5EzU?3o?xNhq|~I8 z<#oG>Tg%m6z1tJeevtQ;UX1>HqHeUGxZZ0eD;iI6G38p3=?T-J*u^T7=9@TA!boW;jy&FWOXof|q1g3l(=R1kaBojVLoagLr)KN|vWweJ<&AhE@_iVRm` z3mnPnN7n4c0X#pm+nZ2A8p63{gl*X1jUHcq3b={|XKAXvHbi z6+i7Vk9e@H+zw5D;8xjE=S42JCL9%q3FRV@5lwZ{(Rt!EBr%p!6QCd zYz7q)ZgYR^OLh}g=R9t#AO(B?)UlD#AZ>m&X{8olxex>&%`fB?tz>bNC|EIqwQ<>k zW5uX)qk~iYEDYFqX^}@{)fk547@!;D%Z+R?Ys3xW{@7y?0Fe&|wcj7kSSif;EN8>- z=RaItv4&wbYSx=$vY$(spJ#yoG&TN@bQ=~6%pOzsS9auJC>QLNYH&C|O+d3Rl7@tj zY}_yCi^q~8q}ww%!9CiN|rZvf~ID@S%sud2Dl0Yyc1P zyTsDgNGP6iSPMQJ^>eH;$qlG*)7M**bq+-uGp%dK-qP&74G6!TCDM=Bake}`r79p7 z%o%}Io#Z#4bvKJ@+)Fad#%qbrg`L~jgjK2M>s3AbwNm<)&`ZrTn=Cm5jmddE4fe}RO2cl(9)Mfa zuh!e^$@Q)}9)hXKHZSXO7Q(gEA9YAiAekH02O5upYG!5x@|K_|W~VuwYb4rj_L1rD za^P$9cX2rty}=u)#($}dlh&@eoN~T=E3VF$e^9aXGn_zxR9u>O_<&@E6Xu>-rW&jizOEr>Vnc|p z2%lAO#-5*D^)oo7ZnmSn4#YW|FLFp1hTq&G+ghstf&arNq|Qh?TkulC!Mw5>MG^kc z(+auAtD3hS;S-D=DF@1_xd*qPGtIlt7kVg>lb;8>6L=kh9gDi?dol`cy$tK}`B2Zo zQwn`w$bj5(e%^R(jDcVLPWo_ZZ48B7OSk2S7-Mi=dOI%8E9!4H zU;bNzxOhz|YZuhrM~iTn(JWI(v9-}uUik_DqydlNf|HRtWi0ULi_+47$q;|3$Z-;yO(f>>r5?633c)4Qh%K+#!Yja=moUJTfK=F z;3tbRZ`@IY0@($i>qtt^OILaJGc+rT%grAT+%tv6PwX0{bw-{igORd_5+*nXXVlgp zZ-zJgHR?uvd&?ep#(b+>6}ASSQmrY;d0*s}x4^dru{)F}9itYIB!Z+bdmI#-BR%PBVDNx44m;h^>s zmc_M{4ZZ-j=%N6%d`iFqMzK03En-;5pI^t`k|@a<)rU@G+>pES6;=K6_{wuCqA&-3 zRZV+{HF?yPm#0!&w$QtkJ@6>W>7yA`%#8Q|H@}7$P+MBtky!!$ck#Emb4k&OeWbe|g%KEDL*!7V{}%3!|Ga2E+y?`PS1!bF}H!if=67@TM3EpeY5T zUKIddf4BlHa#-xSck;$whfbFyt#gSqZL9RBdLZXSdVS(>_7ImwWNg^}EV?-Pf^dsi zYZ9Q!m;Am$nf5fKOWe`L)m8K1+UEcCMZ^E{U`e;0BrHtbpt^*N2wPaEX#_>zusL?0 zIWbrn#5T0&IPr`d^GV(=&z732)`t5~^7s_~~fVm3hrPGH2 zf-X>skj#9^&E@8~{>q<%BO*FXVn^JgRavwX66@T3fCgacu$%}{dJxvco`Yk(r!-H< znVqaN@upr|xJ<1np3W(jsCd1WvPvdZ9j_x76(%!IsCpwuO%!nUjOJ_{l|ZVsdU!Vp z!T@hWwF==6z>sVJs|^3U6|23ISn-;;1ckxB#kxk*IqU8)mEb;eFZjdZad6i>H$7>j zyBlH8eC_f5w3VUF%#a&2G3v@GxyL{MB6(BM6#nfp+A1W~#I1X4~}y1zJWcC9U%X&LP8e2Ln8&o7#tAo)9-FuUJ?eQNz@>jHUop8yXYNWua;50g%o+ zEZ+~@8UkKo2SqhVqQcX}y5OCI0>IjijwjKwS;yA`FQqHI{aZ)l zCiC$?bxK`zeNTdJHTHvp>(`$NW;6Oc_To+etJT!x_3BQ zAX-W^V@wX8%7UqOL>}FjYpi;HVGNCjNY8)jtkqUk(x@s=OoG#JAAKfy(0H?uCm`V? zsri{nCZURDRVe~Zs^ou0FxDDn(9o;pb{hq&a4wP_$fUQ|+egKPzcS%16;Dl?PCo|Bt6bjwULG@ zmMz7qC{Hj+(l~M(4B}k~5x~24HQexbGaD6UWkQW36K2xZoTMB01*QXyMUUG1z5|?w zFqCl@zdfLZG%UI@67@a{Tf=l5FEdF>qt7|}!7e9{GM{0l-dEK+7@<8=bymVl&z4OI z!U4OhEGwXyv)<5qzyK-#t=d|jTZ`4+yI;jOTz;ulEZ8>fp!S_-{{`K|)=Pci5=F-o zzJyQhvwFo#G(sDhQN4$PB`(B%;Cux_smFXCG}-!YvK;*dhpW1IOjP7&h%*v8YX@dU z^2BSOq6>?t9W}t(O$v@fz8lUu_lu65yRyz~+WioA{|Rzu8d(`p~Dw|x(Toh9V+uYQ4J7mF_Q)kT3oei_7NsD z0Ude<6;(`bQno2CqF*=&^LkQ~N_JuH1|czne8K(m>D&>Op9hL?et&nlN@Z#Mm*Nrj z$Bh1Fj;FEUN>s?O*_Mf*vSVJvhW~_j`*1EdL zpEr6GApYRG$wm;sD25CU?-p2LXTzG(jXS9_HqQ?pPm)|5sT6*A*J)-|A>fjd68u?t z$d`wTlYe!rzW|v=ogOce<7-}rTkg1XrY4t1j!HAk=}ZI~>nM;6U0jc>Vv+?DDe)tA zBOoYA=b2L6ghtDZY)>$5@8^RcCjCHDj4;p9bvfJ_R`SvxLbUED-|qheQ`A{A0Ck#? zq($wl1bSCHj-h_843BW@fEUgcJik`U3Pl=#0V~5IY26VH9G9&lDOE{ttf(8#lehd( zQ^bgtO^E!L689j2sbOxgpgP-n7r_hDU#f#50C_-$zdTjERC&4vLHG}$Q5z5;Urpm^ z=ZhlH+sOFNo;iVgJH*}!-r9@fJY0{RZC6OW{BOL8FBi5&zr*7Yv;u%0C;KH0dP5>Z z($Crzi{s*uNep>Z$}G3wzS5evp$FWSUN!A?s@S%qRR29Bj1lHx4X)$q^WW##;!-^E zS;_#)LUt5nMV18vCLiJ=B9LF#j5jn)C=Vi=fA2ib!lG`iigncHc@Py#w!O2;cPbLD zy_f!v0zz$!qkW~&{D$gAL14+=IN7bR%~aD%m2$+6@*L5(3==ja|3{MeKaxKqiWMIL z5S%#Np~V0I+r8Kd3W8;16u_)zZBq-GO9SH)o4!yW*?cI0?BNo?=K=r%AdOs}*xWFW z6CnW5$P9j{*$km-)rqDt#cBjz=)?ED%SXwp-oo!jry-S|b>(wn*Nk`wG&cxqv#N0J z-}g#FL>_*g;sXAiS)e7+X>hjG41y1pMr+|G|197BE*D5`ijuuQeDzZ7JuShVOl!yj zl8>0R_@Q(6fq@=-KkRfPA{GXwa>d!fkQ8jB_0U{$-*lVoowl?}PUIZSque@9Mal&N z(sA|KM{|fWS7z3AVsrDJT@J%^5XI+R1Ki%;FmXeJ5BA9MOyIMD##@#j9r~?pUGMl>Okl|)!Y6I(1%ju?f_xK~R2GzHFY?uJt5xz-!4OYZ*R5;HifIb9 z7Xu;7VesLRGkp82SC7XwD3-uv>=|bNaSu!plov{(a2WUvL{LnsWR3x*U_WL*!w)*p z7L(qluH`sGi>@Z+X`v&)qa+CR8bC@A(eX^PI!M_+QiXAxuZjLTI=2P26>}owxYCC) z`#K|S=O?I8I0Gf{H~o;ub5siD>K)X+J#f-;7QoPl(HufPk+sIXIx|gwM9K#_FnI-T z%o;#c0PsxN(~6s@_d9u`v(d6;reAhSmS+Srw)wZ)d~N5A+O91O^OLs`#3KyibwOvP zmG2Q1J0%Jnv~f-IC%Ue*zx-2#ip4TFb{P(WRT@XY z5e2lfss9lqqK=hAK=R9`zu%8*ziw)TbVsSq`fDT^0 z$$f5DOkm5}jhXv01un+Ts?OI}kzV$IwCE)u(h{U!HQe!t&e2c5ZyuYVH1Gua8)K>T zjGg`5h2YeH+!xW!btml|$Ua0JWt9GErLe5NTv+E!$o+PgjjHY(cmi^MNMuY;RZIl%jqp7Mlust^{C+Rl3b;VamI7d06mC3HubO zYW7NvOWg0hIge2euU1TdUW1Du2xYiFRgCmd&47o|knNLy%VGzmhfm=C^PexkAwiv* z?j_@lkN8FD9ldYN^5=mEYg#nAtJW#CcODeJ*L^r}kvE~UVOcCWH--`Jnl29kCxD~zTNppe; zvW9tSEQV0!w2<4ZskT&j`_fOuy)f}rMPUOQKM~538)=0K?Ans>TOO-XFaVKR0ys|C zIs}BOZcCw51jhXA4L4N6%nOEK=u7}xEqV3h9l^~nS#-E5wZ+R1R_-Kl;f0(!aWp}F z(n&ipBZpC$L&U5I)-P{BPQd^G8P!3WUB;k5TU%RNrM0ytQvd)100O@N01{ZqS_1dm zk#u+H$pD4+J%On%nw8W<7BjoX&Pk2qjwtA& zM{at$g^X)gOO!V)t;yR{Fl(amXWsB&&2uSB^j?>q4phIlH_gI9!RDncoda64M>^n` zs3>*8EhaC01z1N3)J9Dmz5O7xq~bAC%(kPcY>u6l$~R{On=SX@;a06j@gxq*#n$h| zYS93K*@@pQzT6YkR69$Vs(B!cwArVEjluyzd-Pgq`qP&Xr^tozDb{ADpLZ|D(aPb% za4GtMIFQMSGVl6d-=$4RO!4w7Rvyk+Nfp zW5gs`uo$@)?s_^u=P#Z@6phI^2;Wx=EvOw6GTc=qt`3XzHI`_aHn^GPYN+wUgIshG zfc-~g^yt}a=rDr7^j}1;@(vBzRSdN4DSuZMXxf|&a_GaHhD&FfJ^86DiPKa_Q#cC4 z8a{Jc`FKN7N)wvq+N16%H}a4^+K4i+hHO1gak%nA8;QS7m&gz=Tv zrA<}zBCXp%7%d5N#G#6L4M;n0y@=Sh$)ts$p#F5wHN@yamUf8$1+N48k^w^gPk;T* zvVlDL2c9=QgUZoLbK17po?Z_iBPHb84&6uIk?L4Uc1V3=i@+EBTl0P(`V4xTUO*R@ z5m_>yVRuIV`sqlY1q6+RT}pK%Z&DS!|EclW&zinb_I&5dS0#bUM>5AbeoaD zc=}+D@i~BBp%F(kOO;j-D+o@0Xa(Wt4MUigO>Tv9{ohzBS;MWB({vkb2*%O0;23Q? zxPfaf`9Kjb8*h6~nsLjbtQQ>INP%gM^E1dOxqVrH$^NAA&W5-jZ?@0Oj}gP>wWji92e7Bh<^RaZPvHy6yymsnXGJ(G0e)rLCb+qoVs-*b z<|>P9^rNg}hQE@3Y(V!~akS3jP9Ib+XW4U&U4Aj2Lw#4iv#?!8l= z!J$3j3!73@poW%i$~hqXL3wGQtD?U^_JHK2A&@Z4JsWJQt%^N6^pyY2k45!HtsH>Y zxrr6yq`>Js^=7zsu56C141mgeJa7QzJP#wM!>r>nRUZ$DY`URRk-zE*$cGn7foa>? zB9fFF>N@^a=eckBbBx^T1r-%MNCQJ81l`vc*i20}9bU#>M=6v`gOoX>1 zw0O%$0y*#wZAudl5W4*+V$;)lO!N9#ZWJ^6=io0X7qq`}Anx9xl4S4{*h>8~ay)8s z=@gGVKVUQZu!E1|c=x?nP(Aa}#^kb>)=B*?jLnH?ZVHP+OmzIoqzdVX^v>Zjm5w71 zu6Nb#oQ?IziAp#EVNy>~N(2lVnen{8$Imp3QQ*%7MljVVP@j8t{gJ&kW`N0n5pe@z zsVJq@VTJU!$pp&L`3Ak-EWLVv)!W1CT!!*e$tbJwAN(JH7pxwS_uz@;ebNw(S1tew zKUQb%Fbwq>kfh*9G^eFCu$RzIpSv1JU|{LRc;Y*V)OI?5e(K=H01DxBfYJxQKt?8# zOQNrqj;6uf-<)nawShjQAg8`EbLO&}XP>ia1A8Y6y2k8#&`b4w`|q)@fhX&VXkE5Y zu=v`U+t{!-lNd=mG`9v-b3MLyb+_JS_je8e+1wvVr6nF=h)+Wse6spB8U~X~n*klh zxX;ZNEwqAcREFm0hKZKfLZ{%j&A#gAwI~d7g92P@q*tEA5)n6!J9mnPKm9 z(Wn&Sx$RAuDwfo+b(Gr)vE+B113j>WmqU?Y!4g8z8S_hL)rIbi5#X@JF4q@RAD-|$ z*j1^OmD*vWbd9Zky1l`%Y!Y;^EYydI!JYr7xBrgJah^%tDO?D5nFayzBnlo)o?0rH z;ULlNTwZ2)1wb)@Pty9pXy=zSTY8kI1mb0~wmmtK^wl<)I~K1R8FvaZ# z1;YzCjf*h2&Oypa7FT=|t+Z|H>ed3VXacv3;ngv+%mRUm*yx-VmGEc|1<-Lzd0JOj zsU(DqFU(8G0PG)2Oa1h%qBnfc6b)GcD}+6`|4=bTU)7ZQ$3vznC|HWS`8dx@ZuHf%H#`E7ZK1ED2N#mQ9B@bC~Pw*Ovfo#K=J+5tO<_7`wCe1Hb4m#=RSm9a3dQ|#k znYVc4-Ptc4??lm+=S<@dLw&`oaHTv8wZ;1m1<(Zde5hqa-x@vUYkVgU@sxm(d0a@O zY-|Uy?v>k&R>P0uOtR+X1`LQH+>*LD!a#U>H^Q!qjQ&Vn^d5Hn8yW@d2_up3f#ndR zh2(Yo(2h6?-m^CC<@;|!YebsJNP9xo&f}sXWq<%M@Q#u2bp-Z%hIVo?X64b~KUI%I zkFdu8`8TzYNbADxWMP{I=G6hbGP4=+eE&xPUJnA!C~;&$9IO=0k!Y^lo_E8K^3^Jr zc`W%9u?@!1DY4EGbu4PwmOMXP-o=J;s-AI$8*BIZvJIw!GbaKJkP_h-uLw5u30PU; zyoc+4c(`+KM5O{Xu5Faglp|eR846b7&Nj3Fv+U8*<5lrlj?6CG4D~1(*pMrZ&o{Oz zB7n^;${pwV0u}x|tgEhyL$FZ2RzjGC$hTT$sjPG0-5>Q_YxRfZ_%SkGr`W?)dm?S^l_xx5#;_vzP3$na}kGO?jQPT-s&?Jx^eDJRp{47 zV`S9gxHE~=9Q7bVpqNBwyouPWS=qPuLh&h)h547?&%nt}btNG1K1|r6@KA?iis8e| zu*9_Utc2eCOH29*9|4s~Qs+lsk~M|Y0CIccg2^pA(Z!It4c!@3%WY*lGITSe(|h{} zN@(&cBB(Dt@Zv_>&TuQb-E+IajdkoQUAE?9Q#&I%(llNdUb)geik(C#B{%#zu~fu) zSS#5NT@7smZN*Y|0NepodJHT>Y~&#VfyGAf_d8r3;nKeQ+=pO2_`AKgYAP*M+X)Ex z3AhdW&O1JLzTFfD!Tlbvecy@f-!3np9$6*HK&njbcVp8?8}>CF>|%?IrIdNpqYKN# z%GB2Jh1Df9YD#Sf`AQu08#80-*Hys9nR^uIBi%B$BVn#mm=@68G#3RKg7iY{6Nx-vex zNek}mwEDsvJ=4FO=MkNGk#?N{Z>GSIpS?0;jS6i|Ya8=n(tz7T!_?)(a!Y6bbD9os zf*_jmsfaHm3cGYwozptpxKWV;bMd1FXUhVc7XYS=O! zoX5bWdZp3ltNhYIKwJTGR6G-#S!y$s3%&hOtR8yKdJK7IWE>o$T{xp?Z*RY?$cy39K3Q5KDs z++pO`Xe`U!3E-%Jow|CfqkDWX3#y{fvVnK*s3(DPCd`EQa{J5Nz=C9c1{Fy=f&~cy ze9S;xykza$tFBhX{V%|!!_~&+Tkj^Bbs!hRuaLVK4!RQNBdpV*Xha-!o{P4JBIntT zh>rJnOQ3$8VJ@9vQU~>!*GPu^Z@x`g%TuHGQglnB0TY%7sjw-9bsK|Rx=3&WyczR% zTf}@ew}E=?a$CMHeJT-KeOk5{^Fk%qJlaY&br$=E(C&J!7dK1r(kr|@-D!YtY0+(F`>P(Q1Z*8UWMs?rf zWB=K&j9nqUQ@v!10Oo=LFH$VetsPZj_ORQ@SOHr<=`BRWFJg-_yrTmgT}@|oe7jMv z`Z&FZo6Yes0)=kAWiQ5&T-68$wgpW=SHO?^v9Ya@-jic9pcuR{F9eChMaj~lSk9=k z4iL>$%9Z5aHyG42+{NBfD#~0&N*SLWV4VNM)*!3W&i7CBjB086@^( z$sIAP2ToAz2KVT=e^_l?a2l>an!a#ed9g_q6-1L4z3-5{e3-sPpZW~^;Fp1V^!}ZzTlL$ls zTQcI_Cl>MOj{<554?Ufhzk4yh3ZYfn-K`}ZJWYbtIVoUARW{kTLZg1CR*?oUo}b6( z_z;|)h`+NVQ?Brke17ExTEmkKUI*<8`MG$L6J-mPrGdK1H=101jZa3D%DW`WG;Pv1 z01c`fv(sc!`VrBUc!p=<>;Se3uCX zL3hzWpH{avpy*|&p>Y^4R+pUN3=7mL{p))2W;f4dCb>2NkH}%Y=9ATq?IVFy3+-Q* z6ANJJIz)ElLvwBL>Uct{hLYl_yil%Qs3W^W6c^jqVejT_!~G- znQtO|gO81LS5YHo{>~E}5#1p9QDSNjfqX4qL8QkWW_Cq*_5z0JnufNFO7?UT#B>J+ zHLw>a%1mYIlL=;A`B)+UTPlv@VvwPFk3p!{gtkDcy2db=`O0yC1^dA(WZp$~J_+Ix zv=O8TsJJ1g*>ggz^^)XoipH9eRq`~4u~-H**-kVqO_v33Le4nZ>w9+3r!9acl$6eJ zG9S6{RRhe(@+j0x&p~RiB7(!;hnx$ks%fx?IyfVwVBMYV;R%C6up$1My%XWhFkKx8ZH3?z=X308P@pq<=SBe}G478>|J%9;5o{nX~ z@$)^fwrPrhvl$a@Y@D=aP=NxwATOOY0zY>yE84)seJre$paXERF%YFk_ zzW9YQ%U>e@OJ?@21?qqC$}Tg05VxyFoPY+hMObu&0b6W0J9)^`Efvt!#A&b^#=hyM zCm+dG+pnRTkVeoCflAai6|WAw2l%;$p0Zoi3^Ze|!F=x25lq7BJ`>}jWO)vu$nAi#L`-z-JRZrPo(acIR?BdVY%CY6JTkj$q5#c#i4L*tY9u|^_R)ODJ)RmPht*VvSu}t?KGg?{ zQL;scbex?}%6NoZOg%CS;{|?Xc&je*U-d1$J*R;qb680awLLvsLDR4OVl$Z?ZOEcJ z#3}$jwK4+rF~0d@y$L|4RoVnI{ykU+`eU=g*H2xVy{p&bcZ2Hp1u(YQS^!~hxYGE% zrrfr$-)0Qpt$ThK{Tl}t&BolF^KE&APeYQyoNV~6q4_80Nfo%Eo7qtt)+_s6cEGTmm zU@9o^T9j6#(Y}wqHYd*rri$-hPt*oT01}7DbOx_8$WmPsHn|jW67UoK4LzfL=Lj4c zQKI6m|IO{}SOMbTN;4wfh2{_;4R^NF2}WGvY6`z2S~%jRBDL@V4G$}8X3r)|E9x{n zm!T34iqf!1U-L~b>z~E_V9^1}A6oqw@|80rKC;;MDvF&jaoxiT)foqs1)uRgTdeE} zDU7@jM>R)fe1x@nWn(BSGCbIOzP$vzdWRkVJsoK5vAj*&=Snkz1kR<&uaCI)naJSp z#v=%CchK9tx4Q{2yDy9eDm_9791^%imgl7lQ$qUFOk^&L>pE#vyIyBRZf{Fcf}hKI8xWdQcC# z(s8s8|3U|T#kZpj%|sN**nhY+`$zn$V?@rcO5385NZLXn6d@IZIJPR$!94-NGfSKD zk!xi(Oj_29a^qEqNJZr_PCgyzSMUvfjAldtUe!P{>huAnmUCZOV+VdK$tr2NEI4lQ znSGh6ATLcic<}zy^HzYwIw8BOgaROa`fzGyv--uui5F*JNwwDV6$leynty?f0bo|*tTSx@02D7lo@GpYq39u-{{R3!xYQI5 zAzbUkQ~52BfqeD!2l)&s6XcamcRg&^aEK2$^FRBK)df~Ncy&1NSe9mowm7a zU!BpKDL3Rtk2Ol}fL*ONVct-wzy4HGmO(`|TJD441G&qF?!}R?0+uVTx5gZ|Nmmh2 z^F<*#(#({(r7l~w_~NZ!kwMF@?|!25vR5FpP%7Nanm&-8>k!^N5Y^)fb9d5tBLg(l zHZ2?_5Eh8^?6RY+N3vLgy|YGg1v8NY#Ap}Tb-wHx6fgZ48UyfnAIA!logbx;rFuL6 z^~Uu#bpDW7CXm<=XPY#ss@KwDaD6AY<^++-G;ojfkN_v1{=I=o;q8w#i6dL2iWFCk z)wY__%LK*+JTgH_-~YtNRy5H6gVx7u&i)G815F!A_}R1qj93kS zW7$0Kl*4AsgHG46W2cF?VUi>BFJE&K zS#oLD=e(s1M;*(fbAa(%u$duD6PM2rOd4rpcd4B(|)g=4x{E1}@+)$MM zF*RAw|I{&2GYC;pmehB9WA=Gi`|r9Ze$2-ZLc_kiR zq#@|;aJYf!dE%0kVqxEa#!D|!DyU@={k>L_{r_(ly%vI7lZ1GjtnXb#1XfGX|5dA_ zZxkz&3+z%gCjcNe(=$B8#ppS=!&21k9r%2l{!IzIOI-+R{-?r-|}puRv&{+mDVP1?J+PQUCOdVL$`89e}PG-_yPW31r8K>=5tP42}&nh zxaGVLoC0IhL_va^7{CWm_j|EhF_% zlX2(IyIah&KDJ2%#~@**stH9OIs2?~=9-mIjW`D^?2d5t@#<*si|S-@Git!`2(!w7 zhCW>SsZMv@3%d-7;AKHA0_dly^AQQ@AmdqabJ*EFfM4pcY7!kn-w@w%z*b)$kH&v6 zbawQc5$ZY_NpX;OeSjDg&vZ~{jbiS*8`F?#GI(!k!cwM5roztYy3hzK7mafVgQ3^F9U%#niFUN zjWJ7XmPrrI#}tJT=uh>gY1I<_gIcbek*kRm@Li&G{&AU}iL3mDOiNeXH$A0+yHTea zsG8v-(Wqp@nyTh{KdYGD1Tqk}^R;gqP;7tJ*#pMw2^FbbHo1O(ehi(U@Rg<(G!1XH zp7EL^wRuFJ-$Td?fxm85Lubbt${EJ^C+g!Zz)Kcz0Z@-LCe38-DC`#$L#YG~^)cyK zlu2l8;=UcogZ>|LJ%B0kv>^3$H~-BXWE;UTW&eCMEaFawb0r_fvSMT7d0@$l5aNXz z3$aHZoz^QmSN3@fHn4^cQAu~!@V^wBlFimBlEBT}Vgz2Z$gWJ>oa(~HnEj7Dt zgCYU?{-d;Gw1wjcEfN{?0?fv$jqTs&&TmD|B(QFNYB;v&h-BZc&(@A^B{%2cH(20{ z*t(`F2D3IsGxo+ig6>qg%gi+sSDMT=w@G$~Rz7*_CFrM|JcXDCA-{4BfB;g?G3-|h zQ0vj8PF&A<{3GjG*VV|>4Hw>~@NB`NGqL`Mo7*;f2c6HaTU-EqqWJMBK~P@M*B5)s4~$Nu0Ymm_3AICi zxBn1iu?&YP{U&-Bf0SbQ_lo|{5RxG}$#}+xC_Vt;oxfEgT(&+V0=t_LHM!H}G#uSZ z?YwU28<*UwuyrD)X`5AvtRy=kW(SCBz<>N3!4w3+$smJoaE{|62<<7^9Ej!N+VtBc?%m*#Zm zBoqCh3T}(x9DupztXUTY>C+M{`s^AQJLdB-`LLQfoRzA^unHAP232V!p|@OL zdRuSGOa6c5OWPdGuNx5c0)4gvLzzMMDkA_?ikV?{ty3ANxYf~3&GiZvx@RcWlYXTa z-eR?l@*_P-o4YvX*or==A)UV35N|*8JsxZBkX-QZVi7?YYmyBnJc|ml=B`|J{kU=bdt5Kf!;cG=kR3WgmmKm zs@nQY814I%gfB0G3%$fNZ-h*`{Z>FkF>4@E?_s$h`sUUS)eiYBp+YmTHr!-xdL-dpGZ zGHkpqbPQNEfh4`RiXDj z{cD_-Yu>Ch{EhoJ8rNP6yz!*~4yrJo>=`ojAfI1dgC7~A1tevxNHaBu<>|t$wbM#X zZKJ^B`jpI|0i=?6pe7&z-pK9Y!iNTqF7C>Hq2c^ls(6>q zLer_${kg%k`c^7FTyf&Udm9xD7QUaUT@^%8dgb7US9Ys!inq72l(YzSX~LRf=Snu2 zqWAM$BMKVJbOhr@(gX9?U@nsXVp_uCO)dnXu6d#LwY=bKFaYj!F)V`BKz(bQyvx`Pf;bw&IZ+W#4-5vA=!F2r00cg0^m*!p z8P@6iYuuuNCqEl_f#u`;<4zod2o?F2gNB4?P8?SHhb1`mu0S-^i3-jjM*Zb?6x}Yb z7)+}J*)RYHH}|cdR)5JC>pL}$kzJ(*QsW*eQ`oo439pPN+5@Q=nPVIfxdL#2@6=}&0>uBb%DLd;%e9E0x|2~q|zyb0}F|rp|EOx-> zLN^a970gTP`AthFq4QPK|Ix0}$iG%=-)(;;5zj}K#>aV{_&m61J&*_o;)2Fzsl@Zh zscd$mL%Dtt5o_pw9Q68b zSLDP~?6&g{-HM{xU}tPhb*WBoOnJvabo;R=R5@DG?IBH;M>pQ}bYw{JS(rn-(zbNe z-lcvSWSF^$);YyC7&Qp+`^v3NtovUg;Q|+=Ck3LA0MJsOtrG$entn@qPjJ`-DIv7U zsQI_!3#?!tb`jIO*VlUrg;1GTu3`&`D8Ff}nZuVR1gUt8GQX6H z`uk1pNV@p%nmr!ZlRrU-WwGJPm~qPQJ3q(SOta>p0I+We$z~>uxwC4Q|OPB@Sedsa^ zmo6@)#()OFpk@-QLJv#DK-D-+*aEImb=>RqXX5Bk#113^(63~vAJE2>)N&AshpJc-LpBtWM#FnPd_0GfueNIQOz4(!&NY#j6Qm} z(i29@X){n*-aK;0N9Y6;7ri zt+zhuGHnbuj~mnwE^lYM?VPe$)X~Lqk)9JRZxmK)G?9g2DH& zwD_hAqo4tzePdI@f)+ymD=wv3u=<~f`b1HAA4kIQO4Rp^X9A^-w%WqjPw1Ivc=Kf~ zxFMjL{894artiU)LDUJrSG0~+e=8PiVCC+T?tW zJt7G%w45$K+lh<4oNZxhQygcSl)bI~c=;37(8R8ltXp6Re(@)|`X4S4+0*N z<(nIQY-c})it6$fZqdLLE!BlVFaCy;-9V#M@tfSyFCLWc9!Am?)YrDK529%@KQHZ$ zQCjUl44yqVwmDKUAyM~XSun~q@^kZy8%K(*6t0j3_E~|(Z3h~g*P9Upu!z)u zrr4y<@h@qa2@1@*w*{(rK%Vv5z}jaz8+{KBTnQiAEmoa=;mV}6?HXVJ5Mi}n&-T44 zS|k|*X`0VsM=s5OqE8d%Fdt=Wxg`IFu5&Bq<@Q0=5|xYQ3_)PUrHBuX0MrAoE9BWy z($vk(X9@urII>-R4c(sf4J0X1jD|4qc>_`(F{Y$df>5Ul!6IUfs)$C^0Ses!njbJL z*kZ(G)eRk!uR%7(G)Ic`o2CC}BK`e_iFo}l$(L9SjzOB4P-MCd%r*_9h@d9I&5RuT z(qEv=p3GFhW~e+hUgl5LAP3N+TacXd>i~ix2A-ej_{}QsD?TZ@HfZyPS!v#0_fbc{>Zh6Y&NwAgPdp*{%Kokq{%IF&tKeY4cs>@sw z5>`qHZ{n2U?&FV1PJoB+HkgJ95-CkXa;?EH77$WSkIr8CkZnIV3}&hUX|=6fZ7l%% zN{7(JQ&S0EEtgbgE5=_9Nv7Uh*d<`l-onf5U$fF+K;p6rY#YRAfk?8G zGO+*lz8qem?by^+jC*uLhQ=f|v2Ze6`r@WN)3{^AOS*Al%T}*{c^wgsrUkxJuCtdv z=qFQ9O1KKCZN)HFDcg=e)CEh$e{8gj%sPwIl=G!`L}x|Sxw{$M?7bMjO~X4tMrHhP zsvF^7lbJ7k8$@Ob+imYM?d8(=Oorl>0@yV~8W2^icteL?fo4MiGSs{Nr733!QM?XS zwFoR4|1L|H!+i>tSr1?o3=N?k=rM8u#;tTHd4flzWGRREYv3E+ZI<;rPl*Ud2y=@I zQIWcC7k95e!U)NlMg2$;L(jH11}^ZaDOspC*sr`+g)CMuF{A(il#nQN-E{xhV=`_- zKj_P>9uOcQWg;fyEU8wF8^;w4{RKUt+Wk4kpz zT_M!P-b)fkmac~@_=i~4kD@^EsCglaJ$qKbGl$?2seU&?@zfxmu=3or88eo2m9}wG zZ+|71QQ})zXbPPDWLn{E@F~}>5TmGT9{TmMM8akbZZ!Kc^B@5*-v{Gck`#t_LMvZl z>fn`UNUx53zx!pcedh$oD?JuMpq~DeU3WVbJW7*1vxIpRA=K{wOsk?S!|M8k2@96j z=o#4wnAOzSYl4p}r)jW(Ysyb35ji3uTvlA432#pkj5`d;7F}N@x6SvFTDl*U7 z^zMDl$YQ1=aqY{opnQLb3YH~RQc>JgNzPHuS-gi=kklv@Gjg!|!qTz~Q90m1y#O*s zDH?7q4UPyg3q=zXp5_{yo{i<`<#kYPCaHM-URewR1HT9T#5h=~0cqEF$lsp8HHz%8 zF-Yb;y?Ee^o218O^~io=`?&g?x`p#91emkc5$C#$X=A|&$iRR7wQ}o#3piDbSBd5^ z5zJ)I*m?siaS_a-)Q>_$qFLp6i9CbgK>{Qt+Vfa3^3qg{`sU$p)Bh7QlDVgKo1bxe z9H+tPdb~I@etGw*hx;idE~5t!a&7m9&MYA_j|u=7Adx3`^^b* zpbkU`UDSAqo=JkXc3XMBclhRLJq^EaVGcUmTOW78Kh-8xMLu~bg7vRm+D+KzXv2nI3SB3b*A8fSd`i#FD2MBgTn&Dhf7h~&?W;A8%qG_d$10;lQPS_r zuP>a7RbTA`I#{>LvI>A#5g9%PwjGnWWj5)b$WDNPDZo?uyuU;Ki?}nXhqrk{-a!_U z1}rWB3}Au{p#TVp0005=0iJCvY9hY?06R44((Fw%bVEe&gT??X9qUzcdlIMsxe(pVsd@l8s*Ub7x#Awd`cRoIS_}VHL{0)o%UI;a8DY4H(Lo54>p0L6H+s~4 zpvkLAwhf^noel*_B`mP=jnt2B&$E+JLtrrZI=IC*pIso-LXRkG9*)Xm2jcpAmZvk< zNao;Hyus^0-1qWRNWM>?E$04(C#}uR@r%SE!uk&Q1@-`UiP)WIxcLl1K3nT}7N=tH z>QVg1&U@10Q5Xe%6OQ}ALrFc>>7SiJ1)2D+=eFuNK)tbgxKXIdWz`q*Io zb=K4U%LivUoP{CB$vh^Xj8_~l^48Es$jAsdE0D$?40O30IL8UChx&;epaXsY00Dgg zo^5P&ivIurAsMEcruvJn=JMD{|3e;T2+#7wEzfX!eK|^x@tr#PN&(xJ*XD7>lmDKuNHGH zJoT0h^G^>P=tJXy4Q$A?N&CbYI#hfLi+#tV$&!qK|7Kd?ifT6mGJF%d4*ZA5b>V#) zk8x3yA#RC{F2o3Ygc5)nd`A$D2hjZqz;nAAt<~RGoOcq^S3KJ_y!VKTwXj{TUOg`w z&Bcxj=5V94#p(}7!ZD{y0BXhispsUrn*)o&m5%0P#OZKM#BKbfXkB09WV{l^NEWfw zUnjIMz;&;y_uIn6#A^m2;uXX%##|Wy;zV~R7v3tc=0c?*qX@5^fF}a~(gR*5!Cz`H zeb0|co~<$JPq)=D6x>mZOGGQsG~4%=Yo~>dc|dorJCgR;_s9X`hy4l_f_p`v2_z)( zkR}Vo%I0l@(*2}pJ(Byu^KBSp{p6^zaAP3lR;ffirP%2j_LJ_@Apg z9)0-lS@ja_{`qv0bLyJ5s1(muhHJL!H85=D$8tVBXkMd+1|6QC28}aBnwea~yh6Bz z_{)PRmZ;vnkRb2e4~ux(=<{|sn~U3FM__YOM%E6oy>M7l5wdg6>)S|MJ6 zrr*4~T0AUs-zy`GgiWXLxyXN)A7(?RliDo})|6fNj^&pPV5Pu|D9Ul75&#Za0009> z0iJEFbc+7~03jlJZ(>UL1d5>`!NAT}=g9O1mIE^^;38Ud1P2Mk6iZy{|G*jGtH-C@ zM^{sShlU{R{+<2dztI{PE`TD3St~kE92F_b|CvnAycxmkU%w?mel~jHeN581-X?qCfn-T7*eih_iqNQA3rRW|kR2CZB7kc&Hl<*#1b1}-S=9OCCMbl~ZU&(dTP ztCtww99OH3A_G)B7lSnvLccr12K~cJ=D|P0Fb#SXV;JK>obcQQ-=$oJ5WDp?r$6n_ z?w3k#PN|=;r0@3?scXxF!~~_81LqsE%ozZ3H4bD{b1Bao)tp4M54D@>P6PtCDOyad zDB=ue#Q-GgvP6^7h{&}l?&3s4$#K_2mOx_^Y18KrohKHB#wN>VI7(*R!#;v(`c*ZU zUPYKr7O#{57YM(cJJkgdi_3v>M;BR_Cn;hH?1W|;-T(MRhm7_D;V@Jr@hI|# zikL)wV{m1`7VbH*olKI6ZD(TJwr$(CjfrjBwyg;#n%GWW?tS;wtJ+n2_uuZ--FvO| zfe)jaGgltvL?3SHn0U>MbNb%okaCq>OIL6em&5oM;_fo(lPa@rf#uJEgf{7Q`>#dK zF3csL;bewL3A-Oo)XmHl!i%Qu{rjWXfsh-V_fPUqsb~O5U-80BUcu=R#Yy>s&T|45 zyS*J@T9DxxRM1B7SOkkNHQ81Vl2we2A2BA531+-99ehGb+o8iQ%N@qSSr9f6bL^vy+^4Tu5zHhZjHMK~m zbUL)=e;!NU=Nh#@rY+fjS+xJ5(f)rHEhs2aV0QI{gY9b}C{xQ1Z|XndSkc+*$`>;^ z7wnq9*2<=^56Wk-wG##8pqu=GA4aodVBzH6Z?kps1zUl1V^Y-=-Qf19kDt4k``7N( zL7P&_Y5V{KvjD!~pf++{E%}*N5MZz}<6|Dcia{IOg!q~U{-HD(G6C2Y%MSpUj}4_h z<*5C&?sc0yn&XA&>sPU^hDgd0irv`GU2m*iTxo27h3^8B*3DN zO)xuq#&-NbZb#r0{ilKkuQYdinZC~qAgV~ZtrgbR_a^|@A0JXY3jm-tH2r4?K;-z( zOY^5I5c!+d{+p;fvfCfXE7Xoi06-7FqF!QFlJWHPhg1Kau2z8@m-GK%Q~rAuOB?1) z2k>=(UgU6`1P4az1AxM26wxBgbQ>^xlQaVUfN%C-91YA_7qmHtWavTPaB1-_ytDGv zl_*+Tyx2iUBh0rRq1R5tJA1vbBgJF?!X&s#&3gzbQMYmrFQP2Z!?7XlB$47T zJ*_p8$B+;ZmV7N|^l$XWk9|LBx?Sy|X8+aR>#`XJTc52%ItQ&9aJwhvH{3Jm=vi?l^q3U^>cMkA9(Lri&{Gi z(=kmqsO0RBHGGe3d04Qrs5<@}ZlD9RfrITZX2N$1CJwM~Z3BAC-HP)O+l z_oLyCEi(WBz%?+(7w&(zhA_qPEyi+lsRaNa2S#Jy15N|-9VE2W6lhQJsP>+-Vj!|K z0KukOY|HSn5@mkn-B7SFUtnPeGF5ayI;Inp8^TRIR#+xklvsb zhU6nqP~?Om2(KhiP#$Y=)u$B)$^aL;ZOA`VqSy*%f2R(o+|9taR^4Lmb{87zgP68lV005)}flS|{|GT@txA*^c zw;ccgU7;S9#qdQtFACvh{#aK-cJ^yH2@iYR_wAllIwjAomq*)z}N9luk zYnyS953h5Jm#W7f=ePJ43A|VR6TQb%I zEMSm*AG4Kf6@9q=rNre)^@((!1Is`QM)W?l zv%6SxC{x43T@##sNIsw@nx6L+zYeF6^*?^-C(BN`+3(_f!t&PBn(|IF|3c$chy(yh zZC`)GRcbVzz)Z}(j}6uh&prGzpP(ADzC1Zx2Mi8%#-ZVzJvn;5Yh4L)nKi2ZN&sO~rJm~^TSQl>UQhl zYz95ehbPwpQ=IeE&rsGsnqufbPV;z!KOaQb2KY^uKU7>i=-G$o|Du&STM}%IT^o{crLeUtJC65r@*3&%+imkIDar_Up3o?mAvp+ z+6EQ(_~MBEBg-M*fa|l#tZ&IUq^Vv}=A;xwajASQ{U04A(_h#%uC3;6)_)G2>HE#y z6B7TnRBS0eAfc)M66(!i8@WryvI`Hfjcthe1CM8l1$t1EPpji4K_kwRZ-xK73*yYL zg=byiJOCQ!|FEoW%u+k#mGzluWhprqVRYjPA!HRjz zlXA;kGf@3*n!SojE3_g#Lz#dtY%g#VXmt$im~iu>fwqczIOS+(ns0aS?2&mEX$vBb zJDAHc6P+B!@zudKZMkwo>)GRPD;^LMW(07{Noy3^DEf~u^zvq{Vd5rSbLo+_q_Fv5 zZFI`K+g%8e{n?)(rt@+5NA*Z0`NZc;6rc9>B1xu7KxwGQcHW*Qu7X279m}ugK3n=N zJ1@kJ|DfD>^3G&5cpnYFZc@e)?ZWH&xW=;MCw>JL6yx+I9eaPX;scG7rSc zK@L(-D%&&T8S#VMo)#*d~C|^HWVL*_=0ye2=i|Lv`xWniC^%~f_3F

Fe-NiOd+OI(_k!vXHVPC@EEeF!dOII(r0pR_IR25 zXs5HK32mCIR0YkW++s%j866pdp%F}h}pEe^qxLaf*lH(elar><GlBe6c-YM+~)Y2Uw!-Avv%?grbX_g#n9R1Lo&@b8Y^5FEt9? z##Kb9(^_z*WUApZa&lN0TtAj*eWjyNMZv28mCEB&hO9@%Y)L$0Pha{$6Je$`POpLu z?|o2rC95AUj-9FdwAXX)(n&rC`!j=D08QNOAF#bGzk_QN$+H?b>ai&)FTT4{33twM z*%lHr%~p8oYMQw^(@E4judZnO+h30mH!9Df@RbC?q83xi1xlESp1)VLzR(v9o1O3n zsla2!7>MjkRb3scMl)(kJvwSXVM08$)e;NsmNc&>InUTL|2_*Xqw#t32X~ReTg0Y` z!rBn2H=t28Z#5&YA9YHDuO9ZSuJ0$X=LjscZeeV9ZtVB5AD+b5@)dIM(H825rww>h z7w5ivXO2|$vAZ}J@3dJaH+W)$(a|x4TpwE#_(d9Aq)+n}-I(apsb?yA^SQds>2`sF zDAh#-H={oCTa4)`CN^ z{E0*$H;dq88XJmsYU0Jtl}5MIiva@oymlxZ@lgeE#L|O@WfuCCk#|H-wSUAElRXq! zT=F(|=%ehI_>t@TryxERl}BrNS&VDN6_4C@cp0wfhy8P)1j2XXR(cKP-hr4heN(oX=_{b(?51t|iviq3g>@C`9 z84_ds@%`Y4lLKw3KwyE^Z%H2*>|{Fs4Vm^Re z8ugWu@w!kiioCCgbMlpOtr5)0O+JiGbdZ>z)62wxTeki^`f&ovQF(B6MzYK5JI zG%mg|-5eny5bF3zTw+7Og+Mr|Xc1nn9`wMAArnEjSKNQ5Ss!flVTk?~-{|pKBq+bWU^%k@|U2Y44sXtAKFiDPq@jz%{+|Bu|Zb5 z1;|Rixy?eLEQ#o+$QpC?gg<)qdg;iudJ7!GdD#A zI|&&nir;k>d9aCK;`D&3l`im*?&)v^X9DrWeP8qxcp*XJ$>N)VqTi8H>IuIHkj0Wx zmq9HCT~4!2;*92kCkWddPI--SDStsOy9;9NW* zVeeMCsd5r4zCu{^+bl%%#mK4de%)I88(T0WQ!KP=Ke&r&r$ftnXOikJd${7X6)ZkT zlL_$7ww}nsQDVbYH{S^89O(&Sgn>~$+d_N@{3tJo2OF*D2Zde8D!p=HAMcn-5`wIE z0X?H!nHZunSY{g#Cgl7w5j&`m%@E0_1xuwKPLOW#zE2qQHd9itpGDMR=5>X*cd55J9D^F2BpS?SSXz;w}b=kFi56G@|Ch?2&kIH#+L zGw6;i*X2l%JkMpR+JWD0bqzJqswDsZ*q_D5e6q37$d{*G z-sXY7whf>enZxf)=0;EQu;Mg%_z1_9MKJ2EDtYuu-a;OJ!i~D*1L?w(7a10wUb~d& z{~9x71JY9c>m2Q92nPW~#KKvk ztVfy|COxuQsL6`2k0^F3P^DT8eU~k(Hz~y}z2iV6F@%jS3z*%avLZ)mx928uF$Z}; z`fIl6#`DtsgU6Q+L)HfON$PrSPBVQ1o)IbOuKh?=k`XjlsmB-8e~O(7Rlbv_d)!S^ zo}YXzQA|gZ^<3q46wlI2%d$|dqT^2rssl0T7Dd;+%2sv*3SjW8HZahV>k)!s=rzyS ztbP2*brT%zK=w+%J<3HLOe>vqPDy-$-iFENU)zA`HbZ%zr z0|qqt@xn49d8HpzC*fsI=Z-%Xs0S?S$ecPwVO!DKb-|V2k`dI|XYodNwy}7H12>{F zg+J<#vyCT4n++kJRAV-vaXi^V&qn*J%*AQfu$>6J%Vlb#Q$9Ut9Fux~33p|FV+#Zi z@HJXp3DMt6_+!<+5YM;vI|wEl{Q;Rf6% zR0dnP4Be~8Fx?YjAr9v756}^4eQm09@sPDVODE1FZuTG!Bd^Iml42|GwLB&&jGjd` zCYX;ozH|~Fd$X(h4dKi{<%2M=_j$;dPo(qZSFqKZ2v?`v-oYT zj9_-+i!Sj)7KFec>?pQ&E^2Sczx#xq^+yOV$W;~_p2x>t!>|6?uzwrE;V?K(v9wec zsG{55rci%z&xPbwl_=aQ3w)-y8=tlXqVW|rb$Pf$9NZRFl!-pRsH&T@P_0ZMgl zm-%|El{z;hd{h^ zQpwH8*=QDeo;vdi5nwUp%9__Hs=J)r5X>|FrOAk58s-Dg?%SXz$5j4&jBEw2DbetJ zd1FXLUa#9Fyr`B7g+{~EPYcUzm*4qL})GU@5UMUW`=ZNe2WCTFJew(uWR)uE6|A8JG za5WULeWxzQ-C7!x&IkZNxe4TiM*ly47yev&0Y)*#xO{)3yOV_*yC{ma*?X$!>NOvp z>)d&fKvM{{x#xY;a+wZmk@NF~m4?VHh@Kx)rNIvCA7=eLbkTVBZP}AbWfYLAEgQ>0 zC-fK0UiDpaM9}&914s?Cv`5N4<}8Ese-@@MD%LXh#Vs{al@pM7@&cf^)B95|r0jbQ z$-yE@wD-PC5bi`|%}4hw0rZpzR5ly!VhLra3Vqnr=&744EW8NPoIQo2Zyey@Vy);j z#tzY7P)vK7OB2?t4RUdkt;AG$=R08A@y;etgr)o9?mXiLF`CzX-=!9(36my~9g6*t zQN^G-es8>4N+=3&1h|(FT4bdN>%WT$$nZ5k{MEyPlUwUv(L{6~E|=D%)7FEbw89jk zsNfSt#)j8|!F!i0sK-}4LP-FLs>-!}RvobcENYuSWw_|`t~h|v>}$~DNhJsS1LvJr z`dtq4R~^slFCy*FC)&ALnFDe^UY-jx8V-wvW4j>>ef#xsNNs|am3CvD>*BexK6aF1 zQ^t_1o;Ka0F%(xOdJh=dWwhXz*K9^`F86T7RwR9i7e|Y3C4p3enc~SaNo!Dv9@@ga zsJ@`Sg-fnoiy-d*wwS!BA;Q8Aj?sTKBW81PG%INgCX2-bogxK7?%>nUW-z?K{lSA# z6@+g5c5y1q?Z=tNYoG`Pnz&(FfwgFEKUEWH%+i1@ zH@@DXXMbbp+a+ZyE(7nB7+V;CpxBR~viI~?3}-vH>gKkb$=lXFFx&3%F>GAS>b6-K zRLIVJnT4i@*g0-{V7=s?-tNU)01aH>-oH;Nr6^ygF+i>*!lS_DFf%k}Nj>;iMF(&F z1IP)09THzK=v}>;ftzr$rZ4nt86LVb-7ruj=cO=z74zsl%KgO`ooQUlUD&|QBr6{* z!;}G|@Jzv?jA?GpyxeKdN~gQY$)Aonj1!Csx84R#4C;F4aO4k-Djt)e^UsKWaLx0l z+SlgF27%<^ps?HZ+aIHd+v0Tj4uoC(J$|93kg2r+x%wh+(Z91D*5yE4(2bVSlg2+q zN>v(*FeAtd1vEb^j`ARMnX&8(`` zIHctD#u#0X@P|l9>r7m0)I~vyIxA|-q4P_cw|v{jH6=2Q+G_5@xa}?4BBgB)JpD+= zdI<3qdc1VQE>9WBYOwBX`1tE@?tfQbC2+?6IPYlOd1$CS%s{ zQEAe@?!8&SbGXOZTNnrw2ql*&BkpqLdQQ%6z!wBTjul$1hnNGr8JF=|mqL zApLFkzOZXG1~|NKFM3JPOq_a6CSx5P#oBN~kCiUZPCqAMcFW55WSKcWJ^41CqTgh# zq;=qgH(DLFlT}b__TlToNks*qS>g9i2@D!BGyf2AG{pIL9H3Bx-)ryoIIb7pLJjZm zb>4+aGHXSWSbY}Imu8EJ%geayGTXSf)aeFvkCS?R*D&$_#XD({4NiJatW+3dT`m-` z_RSK3;jNXK?v820q5hH*z~ zLQTeJ@ZrbOF8Ezke}G}aEMJBP#uS+4Ro>!;0i%)t(8r`*DuW;8<%v6D3eI3OeHEkd z!StW=EM;5~%k(&zl8~@u&8=N>bN*HdLI-8A5DB>+m;2#!ap*_HQ||bUxb#e8J*5vc z_CGZQSo%TP3!hf*pVX4wMzldmO=lEc2)IGi#p=B<$kuK@1?}N!V;*aZL8n~~^=`sm z6*=`rzGzv`7KP=P6)G#T7WB-U=-!FxlKJ!p4~Z)6K4A}_JT3`}q`*e>dD}v<@6?6v ztuh!f9@tq{;1Vvb!R!CjV8(nDcnYJkoks~L@w}Flv=XHe<>2o}AA;JFD*Q+jP08CZ zX0-v>5Wr1YDi@V1D%MvXzr&j$}0NxSVM%@2Ub;aIs1;j)_tMV$x zy#wYZPW!>+*|X_jXUt3(iV7xzfPW#FaU2|fBFZml^z~&gbrH;7)a{pDt0DID>));m z@nl&0TAk|#!xDL~dPZ6D{nIHIg1w&;UJR zM`uT6%qdblYM7=$^p*fPB>g^T{UK~SS1ZUn&jlV)O83X$RM539jAS3Sld!w%oi*L~ zNalFAAM7=jl8SDP@+O0=p#CqEU^MlO2JD}Leb1r>b=9WUpjbe<(s*Vlb0(}HCJSKQ z;vLIrwEw=x=5A)Sj`@^-#%ZiiQhhGK`<3(jqCBesO$IF=aD|&!=-x&Dsd+;|JCG#Xe3k!)c8BobYWij^ zoXS6{XM`nEI88gPa!N@}zf5ig$vu2ZW$BZs5_js;>R5TQ!6sbUhig+TUUi&0@mTIg z9`8$4FTlX<{_LR3exBo~ zj%v+jMobG}O8PGS9nSPqX#opNK0p+A;}so8nBIY1S*^-3tgt%5)NU~j))vV1)-t5r z3o}VCLyL+&PFdcV0WJVBay{a|w^8Ez_wQE@yU#BS!ZBE;Eq_8%YOE4s0`o?3arpXV=_t<;&A$kriARv)C8)))@|Q; zSkzI$-Q8j;ybtVxHsq3}wVCUt*B0U;-`+QD@hYPs6A=v|{6@H$JOqs2$`t?r#Ps*F zDSj{8|HBix+6t16*Cmy#cY%{hV?s{#52OEV^cQy>ie+z-j*vwqIA^SLu4W7iBC3){ z@Q4sOyQ@fUAce0c(ZeQU=-N{)L%w4>Ktq!fYbvK^yCusp@_sZzUK|1-L1LlehGdR= z){P12_Nnblo+?XAm%xV5gOrbhgF+3>+KlV)WK`woQ|O?|g=0f6oc>!1%m#+0KP5a) z=KO*#jIb|)YMhIO;>$t2l#7=PUgX(k*S~|;7XyHZKI~Z&A~VoSf5RDev!EBs0E{9Q z8+QaDk%?+E-yjcA09ugN3Kx1*s4=HMFdhmM(CUvY+>CT8vP)9nz!uooM|8+9ADErV zH6BTIA8N%9s1pr60FWP+!_Am<$HVJ0+=7(3VI{&l7J#t}`vc?J^Iz82i_>({hd42h zgamW2X{f{ngaid|{>nsxtVIEazt38r%lE8K{jcBd8aS1QA9zQ8iaFq*hKEC8)EIyY zUkLH5O&e-(spG{dcnHx@*1qKOH+vH7U&?D_q#`kEStU^4VH{J|bR17V5uf#3aiTzP6q%#krfPqxO6Tbb&p@F@(I}=b?q=**j9836w3cd#~8g$xpy=$&*W2ui2}?ccC`j=@@O z76Ii?&|WGcX(P(J)t^O1_FRy0qksE#nlQh8hp0}0(9SPrxzdi5%fw5Tmdz0^Q(U;WK-B_CIOs50V@ng|D=

Oh&@TODdQ``5QYBgmGUE8;?L4+}Ny5w=;IrmMMbG*P_i`wZZz3>Wmqk zQJ26%sedEq7|#i`qPO;RF7fTv_>nQR21#9#j{|fzggMCPE!S~WY#^0=elB(IMq5y!|Ksvm!-t zXx@a$8GhaP!D4rV1D_F|rz?PBTc>p!lE>l8PRIK!|HxbFi660V`^q?(A2R-&dSHPK zD*uGF7^g!tWtBo2ss$CqxMgR!AtFZv`ar1466-x^(2GJ#QRe;$7n@9;w!8pFz`06zakbMA=ORRtv$E)c_0{v`qsEGMe(;V-IKI z7k6x3kv#PhJ7nwrCPDeB+Ao=P_6ih#E*SlD54$6qt7@Mr>f{uLvd=|2>jAHHkS|aN zj8%-o+QK;I#$2Fi{hbqX_w`uQpqJq}MlO*zl7S&VHNpdDvyMXqlMuU^z|D~=} zn#qh>4qF2@ZP^o{9RTKu$KYGi`E~X<1-Im%qhmheT%#B3eEIkhsQjTE`|I&Dj7;gf z8S2QI-X%!xL17aguCr(WpwBs=Z{+UaL^gS3@`z=A5rB)dc}b0&9R&gJ8X1=9@lFna zl6^<4;4ppGzSk(2r?`k1=k^~%0I+VkU~W#Cl?bDB_i_`gA1xA=k?&@WDp4{ZhE~J< z7R5&Num!^AxGYEWieK0Ql*~yu8Qb0aB_e$bQ4(<~?aBCLv+GBhAm$89PiMLy{0pVc zgIX*w^?^d9zA(w})Z3^!FV?MsFx z9MSmbHg`Av?|r?-2+D%5WJh-;MU2F_zw~?Vz7Jm0kpq3Zs_^v~G&C{)=|a)`S?d`N z)*b+E1>32Uv{to{Pt8r*G`x3|)M`2|{!{^jMn2^zg8jCx-rKvB*n2C z#(ly`McuPsV10oJTu<_%GXs#DgqS)!qnD0Q|5B!Xwml9et;H78^8g{=PNSIPw70qT zJBy7z3`E{=3YqQE-ENqZL}ok`78>5pqv<6wQYW2*>3y zO>y%qUdinp5V3b{CHous+$Ail0SR2w*w3IXk}t8PFdIW$aIJ0;3}q9>5KwQ8^Id#{ zy*Jzn$ezZCmfaJ7`YVyOW?2^;Lf0JT&P5Z*mCI>>WL2xlRv-vc8I0bx_Gusn)h74+ z0LCQ;HwA!rO>Y7%rzKimd!AA8$o8-({9KF1(*_B4F5kDKW$cHDh7(-6Zw1hcw6|ev z$~8A*bxRJ%%U5Z@0ob4aARAlAyzweChMTre#8f{n+808fqh(KHaXogBl9mTh6esY5 zv{6DspaxeX(PRI(`K0A+7E%oqwK#dREmx^~4r=KaY#Qq_3ZUDBhq<&zs2<#O>>#|@ zCj%Ox$PdgyrKQ#LEXP1Nq597!*?fAZh83fKNL@Xz@ zeNRuIIawo8TH8L4=8Nk<*%cM-H2b$a)2-`UC6{A|2aF!g_eBci3VW1E6;?(RQ-j#3 zCuTzGAqe1>YD_IyDjn2Mq|5tIEPkMLK)sC6+YV&xA=SU(9u>Qdk}I?90{n1`9lesH z$ow?138veN9uXyP>bwz>t*eF}DdM{_4p%)iL?N6pywoAZw#wuqtKcI7)xNEUal_ z7|PXNSNFlQa528l%VZcP)}jl8x0UPE3D6^8V=H4o)7uy;H4d;$4MstnbOmD9ChFMk zXE%al*YNuC%~`p?f4>xXURC?P=_w2*;r{-RU#R|H?=%fP8_13vCMlp!3yNNc1poOv z4ViKc7>YGVbAp)5w0Xt7?*e&Ln|iZGGe=+Gkd?{9M^T%45T$3PdpT|p9EA0#qx(!t zci}p-N-0vkX3sXJ&U~NBM0)@`B$QVi4 zuQG_MFIa6iOKYLHy}?kVR5kN7q*>f!8D5*yHX!^vm@|tl-Yrk8FXkAU-gPqjVEtho z#+XS8Z%5d<|KvR14|IQ;)gbczMO*C)dxSo` z!1@ifKzR~x^5%FyK0jE%&6KR{bJMtY6-gx%?+O8ukZd0AJ*uV36iI6@|D9g|A;{!c z8RE%D^BCVcBR9(8b*m@sFZ%%CCwdPNXQ-d|Hhu9y^bSh`v*?a3t>B^|2XDlcg#k}q z8FNmz+87d~++SF)PZcF<^4Ppm*CS*Zm6uDfliKT`$x_*h(SIgmf|zN0_};w{lz&!{ zN0HIa)(9#MKMwM=8fW$MDG}TpEJ+3fi#6 zGGAItbR|w3QqjCW&5teM7)J9!~yJW+rw=U!g%?s3u!WC8|hx!qyknwjL&+Y4bB??~-C+~LS_tGs3Gynh!(hdST9y}B^R5$WT)dm2rs2!_bCGp)sUc+eL? z*EA<~_kX86%d-FJnk6ADPV7JL>=oekK9gxA^83j<4%k3JNHZ1ZyAE`G@Z2n+TS|;< zL$rE-7uz~F)gNSqoS8+Kc>-wvacufZuykB2OmQ->M)QNQEsZ|3`!z}8aEdL}27%vV zf4a_A%Ib^xXeoj|h+(NMebeB?{p~5NY?+FG6>3d4fj}i)3j6>Mu2c?&yJ~H0Q;eR7 zXw3)16pa{Oi6SwT!2hL7Sv6|1+j7Qn3h93vFvoZ23Hjg~TnqwxZLxK(*9|GzXx zzRODCurAZ0?bUlNcSW$Q#7n8uc^C)#iWJ%65+Zzzt`xg+rP99ZK8*|wn(G=5WY9hs zuhN!v8TXLdcSzxEUo?f%4~x3ghYXIDb12+bRiQDwq*KMdG|b$zQzL{ zeRK0)iUmY_K-Ql(o+@^tM(+gH9891=cX~n^RvAks5tzt_8p&31?7hB!h?iOfLgsh9 zcI{pOuhKmT#Ia)1y@SE&stHT+)mrPQw9i%V)2-&MI&6q!dAuUjh?5V1qP%Ro;E|`A zisT+Dm!%Y_xpppHrE2%tC06b`U3j-Kg0(#r-@}{A3(r4URiP^SGr(h|70(`211TGB z4r)=h-;!H|YpW=>mIX?;-Ym=PN~Rzgu8bt~cOfpOU>#SsQo{_p!QFg$|M5xp&}#yA zZ;uT)(KuOHGt7ima+2BVrZ$8-ZT>$1C=!@$VewY$TWmP#6$&%#jb{pt-j4x?Xg0{7 z=~*fdi`%qV&k>d?zL%k9x&_~Yrl=bl5?0186fPx)y%im5^R5|qoxcZVuGMM{vCSVZ zRmqa2c;x&tmz|Q9f-x>w9^{rx3yhZppk^*BPgFIYjHNYkSa{qM;8LcK*6iY8eU{X$ z`Di9j&4Q2FcQdyixJiF$@D9-~{C#e~0JdNI6_JyJ%>B|KNu4N$Eq!hVvO}@uOWoLI zIwq5jQ;wj|Mxci(adZV9y~IP#?PfJ!DTU}i z;egk6yFGmAgq`+F?XqC~aGdpXzwtjFY+fJr_b;ZX4cu2KP?EPsOrBAqxrLMa*_T`L zfYItM!$Os023ua4B2oP(j8n6~(#4D|)d=4#`W#|oISOTPr_6-0plhDJgEwzUOi8*b z@Fh0ueELH7>eTZF8+~jEA>g+Po_>4twNj4c#Btpr@zP`9u@iB*kq^(F(FI(U#D{@m z#w>M>UuhXX((IKO{+$1&AneP@@tn{BW2>z#zUD7+5f3vq94~rK7sr68_G_yaHm_WU z+H=q9M8jbN9#@U%@It|!2+cH)NIV&yeo%h3Oo+i=Z01Qu(QZTE6-zvkRhsd7FbRvN zu~cyfy{}v69I;#J=3`goE28VUc3eAM9hTtHpMm~wvxQ_!+rFYiFOnUnp(3+n%DJvJ zew$whe7#=Ax}$H&j?Y zX1Fg=sogDRq}SRC)WRADT^rXY`lR16m(N$xH2a+U8D_TS(sB{Ax$q}ZLga_aIcal~ zB2mshbokbL2&J5|OleV2b;at5WLV3szy=s3V-gcUq9?7HVMtA}EA)wcnn0fe|Gldk?ET=x^hI7{7cGqYo-#%7aPfN8l$svwEV^t=*0gyEIk73F z(l`PJ4hhzZZO}yT=ZkTSsr-UuP!VV2yFeRMiq2=mrdSd|d0L?y@txpe6}jDQk@T8x$n#O*HG;XUzT2sEb_rF}1lRWI7^AvUdX?ZKFd z*w{e1pFx}CJd*S<5H~aK(S$}FH2R1B_&F>s>v7>9Yho2E&EKaT?)S95Qx%qc=)jWo z6@eWf!SGL2KbRtVtNqGLZPgxJHG)T#(1D_)ao1YKt_8MznzZq4c+4I72l+4^IX0MX zk%g*VzduxR#0BeEhe75Mf0#=L+nx*z31c>j;x9eA)J?C@+G+>7@=Y2l6PiH9(jR3x z=m7A~K$S-7+N^Vf9-rD#{It=^Jv6kGyoWGeR zlmSZwV6CYF{1GzFB2>TWg?ATl+2#JNVdq@`!-H?kMgZ%=|M&oDiH0xQfqo#Vqbr$F zua&$JIl4rz*QTU>;Oa1IgYVlKs4;-Wv(5=zO_CF{L71Y98g??DS-vYYqd^t4mCK5f zX@IE`n1R~lFro%qYWtTB({m_SDt#f2PxKeAFl?*-@@K|bhmgI0{x*)potc;Uv|EkW zNw^v(q*UH~4Es`;m8XJwb?7*c`W|1Y6O*NwXy0*p$f6#D_s8Fp z&BRK)qg(2%LIkN1LrjzLC;sRaxUsIe{CT{h6w@!gZxf38q(pD-ZNEVIi5nN$5P~MV z{2`5hit4|KbF%kBJ>M#8R@>sozu;kg&Bo;2i2c%$c%tWWD-ji)CX^fsz4*kNhw=Zw z<&zTGfEPGKbD>QDGo&SDkKVWUc@d39xb$X=h+5~3CJ3H#o6Wt^I1s-mHsRVQW^Rg5 zo|J{SiIU(x{(a;0O7fS@%=%$Q5+0b^wcT=CG;1L;7s^QdI|zBPqj=lLB_WfDM|)?; zuH+Wm)ehn;w>Z01bonGN?4^NC zf5dlBtvK7Xh*6L5^3YPYhMRmgJexSC8(@lD&{v z(CLVFv$nDR^!`K;)0-bg(s3Z&xX6ef@B8jEpe^Ab@VJ=v@;kR+NK*|}w3;4Eo$q0T4}q_2AJIq)hBaE~urtQReXcvxHp4(Dth3 zzo5P4=(-fA$w0d->VS%5E#aQxxiE3GQZ;U@lOBy=Q5CabL6E&W{*RLTv=#0p$Fxrx zuM6cGGd=D-Z&rAm@IFVuBaBlp#YXch*OBO$Pm75G5OnCp1dFUpM1N&Ht@Q}plXCDi zTb{6oRyc`^MaN9or0};JNY`hV=-4gBGy`Rb2BaZ+IBI>|`(;xtT~2a5{mY~O(R@E{ z0!g-?Sa`1@d3r%kERoH@_+@J9gQS7f?)vVT_QZ@z9$DGzwqo*%c%QD8j+Pv^Bps^` zy*`9LLE9GS(RX~XZaj^G*9kFU67w6< zQjTcKsTpd;2THh4VjpG=zOVw1SLA0fxkKHFVDcr1iM=iushWup^6xkHINwHo6Ph#g zACbzmQ4oMXgDQk~{1{6aEKFv0L4X%anFw^1`UFVV& ziu+KBfF=BjA*D`#26onJX&bL>od48A$Jmt`XVZKZa|bhWWK9Xp!Jf z+X4zGkhf$#5HDa7Zq>@{rJu_xfJj=%xtbDbt-5&#jImeIUG?2>mLr}aZN}Pvwh^4g z;`qWQ`n0Cco}02Vsjo)c2u`k{hgl9f5{o9tQnSd&crJ|XWk&AFLq!YveY#+I@%-Nu z7xL?^eim)E1y)UJ#iFDp+V9ImvVOv_s?z>tIrw~*jjP9l(+e63t;Mmf|MbwvsGc-_ z=h~@E`5x-%#d92m@9bI!rR?=SqH#XpQ`r6L7a>jhvgV1fe;}WGa&rcj}(lBWtDhs^<;%Y8QB5$7hKKO7m6+9-X^x$jAJufY&;n2@$&h4mw)Y)A+yg#PQDOZ;I2BZoW zH7}vp=a5oJ4w6R?S&|2%a*ggG-k#;8mLI$4rp@bR4r7fW6@DlED8=!^(c4fdVIDUK zk&uXZ4uTnZP?0eYwGk$L>NMM{%{hJ0z+x?oBHA}$J?7WtxxbD3Dcs68JZ`F^IqN@< z<(Dee7HF-@wmCT~v9Yf6`dkR^IUO$i6Y5fhb?LGBj0Wp%ETBU5~v!khY@AqAX=#zDU zsu=1{@lzLifV@v!^O{Mih5YH04@{oVPx$(XdPBdW$}DV&N_{d$1dquCCjfb z+MTdH*MB1)cm(APutF4x^qou`G_J}JqRhB9hlwuoiEF+2E>g$4llw-TwPKY+ zY3uvkVZyDEqJ(McYPs6!wRd-D5UOte8EIvyPMx?7BawMPTLeTH@C zJe>O`+XePL4PTNW|Hf=ortkuy8am|RbisWy$12(TQB9$6P8 zXR$^tb^6E#bAF9*;&Ky11koMXsKEFWkOg(TJS)72$d|?0HWjhg3bX(O2&J$xhWZ9| z)^<`Qhin2hmywRUEm%Qmku75R&GCW;v$n0jtetAdgR3FB6AhXF^w2Bf+m}mc8u#?0 z!XZXu>Y*~(tWK2XRBuz23U>gSgf!DW{t;g}h+s?T!!yr+Z-Ai|@Hyk^k{z2r^XbF##Cg%o}@4r0C4 zkqnv)>JwFo-V!5MalsCda~>c;qX(~Z1$R6xj{XpH@3d1AzFm6x23Q*;^#qIOOw_;J zbwDh*tuOS=TO0Il*3|PqWWwltqAjv^Tni~b@v82FpWnT`d@F?uHi~j!!)b;HUNEdm z>Yi5BW&Eq#d6@S*Df)>YNk%Vd+%Ri+VyW8PyNK8-GH4MJ_|UFp zNrYmid3u_+fx1;FHGRkhk0f)C!W|Aw5?v@r5)bN0n6^fvi`uxQ=r`mcFcRqYQ^(DlxW9mRa`U1xoc2eR+M4*Vh2kNw8SY#oq>v!4 z_?CK8j(^8{G6k+eeK;+?L?Cg&j(ArrPpZ(P2ezBw$+C=u@u8v@r)|NI@JF!wBEg5f z<680ph(Z}07LkZw*dz_gKFIOc-QqhVPna6Zeqv$P16_mUWdM^0ebJn$g0!wX=7(NP zh-BH>2n#8f1~eQ+(@@~9PYGm;t|f@-Q|bc;YmY&A>u-XNw87Vfzlc^;&!TBxC7HEB z&H=>-{4|winY*4g`OAn*HmhR4$MTWJu9ifJ@=OGx@t*?RPZB$! zCm;K3G>>iZ{~GGz$dB*aoC3~L{u$$*P3V=BP=Cm~m0#V&p_s)G{r)IQ9&)U1zi9gvo4q)M#JhKj&1l&6?H+}jGb%mQGMCd~MuinqFGEBR zP?%+=`wJYZ4O7R}>$3<0X*`j1CMnQr;8LgEkak5K zfC4(y0}PD0Atf~keY)y%9I_hz#8t?f1Bp9)T2Dm?OE5^0W-GU#WRZW+j+W~z%LM4{ zZHgzcs5Z^+oWgWLh@5y-8KXsAbXqQ2ZOv_%&;Ck)i+nqUTvM4qQVYG%1;^L(nVKH1 z_cY-7Ftk9X69*uDvJnb)!-B(gvuHF~bYn9R-9GNnx9@yyZ40)<6oFX3*g@L4(>FQ7 zhJE{%5%2_1mB>R9h_Hdl=td~X8-?`k?P*Mv7azTZWUCMGWQVG>b(ivaGxfgB+j~1> z)#6?Zp~|0>*}D)rTUBZ6ldf$9J#6e(D9X%txJI$h!2jX^mq9$+qv3->p2?l;|Ekb> z27E6Nhd$8oH_o`B`KKhM%ty(~M`x$&^ZQfOu~ z_b0EW!9cKW$(ZR?!T(ZC53;&gGJS4va*${DsmWRl)c2% z`xhjWu9w$3B9+lHi5u4KjA0>3u+MwGgXXy1;t>QdnWJ#?$1jW0?v}zc+*%faN$K^! zT)J>L3o&LPG`rqvDj(S#LW9`Wek||<>-EXlCt{GQ;=qDProfZi+guz3)(9?mfWUUU z?&X@4##0`i4V6Z;-)lOKQhbE@`Ko@Y8Q^X%VK}c7W&S%_)uCZgkyh+30(h@f>{la7 zsy(kPbyg}F85ob{nPR>Z;Q}c-DM`&9$vQZF=kaMu_vZ%lpZUcqXq?ZiUZ=zj>S2za5epg`1DuSpUe6-=_FG zFeYort?7Yk$R=Ey~7wpu3vpR_`ymnJ{DEHS?riPno5qtug>VlnU?QXe83y>`RNkO z=}d?ev>W-MBA|0#itisPg*8!NYn(qJ_PJH?n-_)Pw!LXRi0uUEcF$&HhoC_z%vc1% ztn%RY+rVF{6~`eWI?YdPbk5b@ncla^g515(!F~I|ayGZ-!ih7~J2~Dse@S8_^@kYO zAZBRK`%kf&&^es?sJbsy1VqmRYZnu|n5?z6JV@djIPmIx*Aejru>T3DsHgTp5Tu|` zj&|4U%DOunSHljQcPL6_PJ`S)XSOwKj3bp>RPhn&%J4+VFPe#bhmW8+KUm8&6lQLI zDoN0jL;5tob^q+|60td)(@XD*Z*45f^hsY3;p&oaK_{yY$y9S`1{xtUWSi4J$+z|& zU6KrKHQ#95nnsH;-6wbO4g&wX=lt7cCBc;`5m-f(y!xt`I&|b_aA07ks8jh$?aW?3 z-|qj0@(3TGnNG0=j48G0jj{o5zkZ{#`}srns8y*?>%Na4l4F;KBK^5<;j5L;0yBh6 z9UWhig{E%5$E*R4wFR2?D>jn1Z?N3aYs<1Xr9)pJ=$$VQ&u(j5s2=ho<-02A8unf@ z5%=bW@ti?yH?-=6)s(F|V0%8rxs2Bb_>(B_Foc zk>OcHu%~c>+ABe`kZ6{ym_3rIa7X%@!lv>FbWc5uk87*WRd%(oa{bHIC0og#F((Su;Dz( zQ2g0)0RFcLG9$6p&6Zj+dG1O?mW>i}!r>>+paPnmcMnJXaJ5vP?t=x$S8>PB&gG

HNy_yi$2@abw>7MDy}S*{hBZ+%&tN=!g`V%yUE7Jd#e*cke*%`?LD-DyY8=x z>y|08{Ve2?4%d1*U|M(hyt@ok2KH~;vY_5fHe~8RJ?RqyvY@FZ@1%;Okxw7p80eXA zctJI$V73};Bt>j?FvbMp0Fd#0;bFJ(JSK5d9*P>{&De@c#B(Wm{MB-R&1vbbpYch+ zo*~~+{5T*)LOh`AbS2`P7<*#;)JP^D0i=JZ0yh;wK}T)~dSNn{4{^%)%WQ_BOq%`ln<1;_1+%_Izzk zcj7a46^2h`juvGFQhcJU9S~aFg|SFID;Dmr;z86$lQj71`bnEXp6L+H>i;g(%@BV~ zvZU#^ft70LfExk>x@D|cJH<@#JDU(kHcVJ){`|n*J1ztGwiIE*ss#MOX}Fx*z5ZRj zM%qOfSyelECW!me6(el)rO3O^W{1>eXcSp6O4A+NlTjC#6E-lR^Nh4wF7KU+Yo_n= zs##t1vSasYoB>SOg_(-I4qneyG$Xv=Lp?|NO^RcI-p52QHMfm!_IVAb+1h?$UMMt0jHn~ot~c4a+XyE2x{nJ zD-2arz;IH>-(yoipBbYn1;IIIYFfJg3idz%00RI357$}e&=P3G2KsBD3($Em{RJ`YFL z?CyEGdxoK_h@=jc0ve;N>NWv;eJAKH<0wlMOR}(F0TI!`A@21@!jskpy6fo9f7>|5 zJ8N5~sv(ey*$s%!`^M>ZNNEcdJ#)N?DmS!V*~2E$Zp)Rwx9al*Nj?iyklXG=*M6k` zm;Q>iFJ6x_TA0iaE)q9)hzmgLAlT-Uw$GJkpgz?$W&}qBCFOp9EBGm4zH$FjIRhui zzS*_Sr1=B(tK9vMz@<{&LGiPIGSZf}-t$rT{NYo<4GUk@cW1z7I~224-g*fm+kEOr zNU0FU)|8oR$7E;@w$knYYWlt9#CC!G*`U2emL`MW^i)I?k30#NoptQJD#R;eRT(p)nVtRpL+s_4u*RBBed`wnoDfv;z-< zIq``hu6QjPepsO}3S7ZylLOCF&bBoukb9bvnl-~1SsRdIAA~Eme%cP#?doI}W@<$2 z9=Z|ac@45j<}Qp1^4=}t9gpeTd@unevoaR*uwsD0_zWrw@-t_+=?^1V>4X}Uk7N}r zPL?wCcyC)cXXHq&Ve;QahiNPhc;i%{*aqqN+aOBI&!BEq?Cn$yVwQg=NpW?H^)amw zqf|$gxWS7PW}XKx>cgh<0|rvrV#?g}5oK3lf_9hA{mVaS%WU4=yA1p{^af!Da=?aj zV_5i|5}@jg_}pDO6eE6{__2;rXXqA>A-P1ZLDqpK?jSiz4!8!CqE;iZH;ux_^i1K< ztX;GiGrl*a6t4ium0$qcfI>PPf!rt{^qJh}9lqfO6-ZRN?D=Xd;QDL;*% zGu5B6z{5z#5<^&u)xhk8qW9A1-*W?phf?=U8s}t>!&FO&B@{j=L-(bY``6gvKk4p~YXt$enVZ>zB&zni-et*p zZvYAFAJ(?FE!$T`s(g5@VJz9{Y<8#N3zT7R7LQV2*tHtF{rTZfl zgmeU{W?}vgJOh03NB&l!-b)upjFZoZ{OUdDysGT6TirT#*Chg7`<{CpS4w+XpHux7 zHz_zprRA%UMHY7um(0!qY&g)C^;U`|;ua*q7i9cvoLPwdFXwYbCj|$Q+TztO#cQfO zjXQi@JD%sVOy;6crPr-%#K3owTY_gA&Km`wRP$)ntCm^ar%*sA7spP$)L7>i_&(H; zo7&_wdbnVsoC6I~J`lOs=SL*=Is8DHyB9BJ3p(=qM=5;qN`*^=mDIqk7k8JBJt7NDXmC>nF$1pWDN6*j@*6D`@ zQ!e#ca{=G|R-T07`2KpfMk^M>PU!n(+eiM==APXc-SScNUsLh0Zw=fVi7Awl#m!0r z%!a=3BgFRdh8|KQ9B6KI!Otp+wBY7|d3p}eHwW#EIXYEyp3wL!2-R zr6@eG&m(l~GM_^xnjxv#=C9Vrp*Tz-F-@0g)E4atIu^{SO*_#=v;Wk&Vi0uedC_ZH zHjSAwDg_u(d7ZR!z^SH_F#*01KDgD9!Ei0M#A!xCjKm-Zjo?rjTEFDczTVtSlO}4! z1Bt42Im{`W8E9t%rs_E~60SR-Bw+)dD#>Z$35(V&S%eAuh!t&t{w|`WA&1H^>F0DN z9|}cVD-?UbAqr<;V$JWXzn7#rwI{ua#*U@BOBtHRPHmVVO0c`9_P#5qY19 z7wPI#lm!^Ra_TyFLFd36TXUnip`x4c)f5*cWALFWfFFA4yg&{o0tiRhz|tZjv9ti! z$Ca!UV*+O9qg!s6Bsi$ADdIv4%?nhwnjquS+?t?hQ%sCix|Qc3)tg4$;*{z}e>w9Wm8?xAedbIs~dqy^*I zlq?**x@AnwOg@;FU0_8BrE}D!!?3;miRMi0K4o8!9c!tgW$%vBRK*b`idI>0S^+0fs981W3YjXTpma8j z>2J|-7`^a-eb~J48Mc||3U{Bl@1q&Oko0rf^(GNa*F%$Hz+t*$a{iq_7|Tk2;z>XG zR@`T=CSP-a4fxgQ9LE@4kbYJ$nK*%BoLBt-+z2jzr{_cA&01T%ab1N>DxyD6D!SZ; z+ZxN7L$_0)Xt%sUMwzY-BRVhJ&IDsCiTpK-)UkEgIWQZh?Da0){k^-B4)jy@@*Z0? z%}qMpV_OM*JOXFRT@6>1_W_^#OVI0Pp1RC~ASY=k)g*pKuqsQ>8zuDNky!8D#)-pc zeFvABYoN2zjYN}vnlL=NTWjdM7*k{AF&&p9`Vk8{%8O8 z#rD=LlHyF#6zDEsOi1;kb_cC&>Ecj<)eakY33IU287oMCKd?C5KeApZWCH_%(JqOL&H84r&_GzREPRpD9K}^Ex8Yoo z)ITMrisoeus9NnX2tiu`;UjIQCQb-JWvD-6Zki<@JqOV$JO>4{Yw7P2^~<@e$9b%U z`YnT#QYW0?j*3*iAx|?)+}J*5^PW?kATZXz+|}DYybcQ0009300$GF8aY7KiJ#7dbfqzKektH)X@~WbyJNx4iSFM9%J%Rg z7C$3`PSa~cthEF_u+UsEW|1j&EUvc3|bTs1T( zZ0PzpWI2Wyo%f5{pCyCzw%naR-x%n@Fj1mP`jrsp2(YKRImfVf{_|S6KA`4vkdOd7 zlOOCP$WQUEd>Tp9uAitJWj8RzsrfFMJ`%3<8?i$EYq~!%p7d3L_r&bgjrc*2JE_Vt zop)2U0{)`ut}Q1d!f4^LZhssTbok>TUD2bvP&{0$u?3lDP&R70Crg?2&Hk;%uH0|J zt|O%mn5&GyMs?I8Xj4^iiB)$;!hgd5tJf|?+r)nl(KjqqC+r|s(Cj56PAs+gn|O^F zI&mCiX2TUV*sm&zW&XUyh=)Bwc32SiuEahmA+x(#Rz4ICtGhrAgyCYzYZ4|E8sj~g zLcT0lF#JXa1xw=(rOG77a|yVhfC8+M{6l49M%2@pG~_kk+A4)3lUzZT!scEsWvL7H zfBaW|8&1ZP(+>Qn)>2T?I7m)e`rB+f3~&{z5)maL4SSl5J*a=-3;)H?qSn@keqb~_ ze{Yqhk>?56R+w-CWvi}s0zk9aZq+3BsFI5QZ3{qckUIv2Y9GR(= z0=%iQ|H8vV(HwwVxF7$WsylYDV6o(NI+}dG%mRwD3V63~E^%as^CZgqUtMR{IkG0Y zPq<-O`YS5T{Lg^r+$EPudYR`$H)+&gPd;VY5RhAk4J*B`>VTdMC}~XW z;Zls52EmbGbt(W+FR?#@^H+&2PJjV(BH-8!$%FcO~jS4RkK)yKY= zcfeY`arGz$6t~PQOHi|MZ2@3HrR&fZ9Q0_}HyNA}8nH zf|Phq1!Nmgit3dh1#eb+=(Av?NOqP)W&T-Q-IiV6orJG{(A0elGrj`(YR|aO*dOIs zXX3(=r>i%nPkrhp(dFnEd}tQ3Jo7jGfwzCc*a9V%&gwELe!v~BR=A2^E{nGzR_=YH zQGwe&W4$enz*bC_+WPfXD=2xSmOKMJsDv(ln2PkDs$Oz%wq0KJ_^&xTDJ^IC{P;X% z7-Skpb4tC^wuKh-@I%1%|2*5H1g+my9b+7QX(h(OKmn}^!;gCACNTtTVdtzdKZtos178P4jOST}bQeNA=*WpE z?bp}d62^zODZc*w@?b*)o4bNsS*(#KN^qizhz8SYPFbOi(O4vAw@grK434g5DCM4( zBH9L&(~vutYZ_VqKUgtk$WnnWyPYiG0;qKR#HF-_!Whp$SK6n2Ca<%RI;khX;IF3> z(gl-Ii8PxF+%%4Exg_tws8lKy>i(boUy52{tpw6$c5-#QZ6x`Du)wpd6xMWuH~ z$t|?o{r`#aISErH;y{g;T@usc?9;}N17+XxDgArO;#i}S0Lv72K2ytPKlKauK{jz_xfp% z@*kT}Ax$$zCs5@+KDcTmmvJ$3IaVYR@H8>dLew5kw+_aGsW~d+NC_(}&u*zjCDLkd zXJ>c&d&TPlBgq|sTpn$bt%nrSSr%rNpIt;v*Hv#a3U}&+7{A8?5%OCD--o!|$pvJb zjyN+f@g@7T{5<6_x@hSb0009300RKja!p~RHz>aKYEaiUmx@HD(y*MLJhQDp>AI_C zPPIf%Ty`GxKNdmff~T-2(_qbim+skOE@?jFLkRoBxSCGoF6^?q=rY}4Ux4rp%=A|k z+3$o)h+|l*7{BQkE3}h1M*FYlF#$a&1B!R&#*my#HladT)WT+vOJ-4teuQ$tqQAOq zo{?|Oo1EhuVFtNUH)qEDn7Js1zArtDT8^gqrZRc-DT|zzIl^Ua3hj+=a#DgO$*zc+ zZ0bseOt{iooLm8$;qSY%O@N=;NXAg3$(mj8#jt+OzjR}9KUbP8u_ymyAH)zpOKd$6 zcW{3o*u{0Hp6kM~-_ilwDuv2zssmP*Jhc)}tIzh8vG{ky#W=^OMrFpLq3V~ihvyT} z3=a_*A()Z*Ek7+&h@}R32z0Yi4blY>d|)rPb<*1x6{=f|mYkosFhQcO_@rZ+l)q6a zsR(jWf&4keB@N<_j%?nU%Px#B7#CahG9hdIGFVdex$x_Q=+7>$^qt@Mi=`J1TcLv&RzMhdhI$Xg@Rne`V_!rh{FA-Jvf`c@(qEQI%HH`E9v4z1_o0CnT*6=?Jby5rXSU z=sy{b^Iys*ww2gla8pUyMroPf-K;e)5OTS?KjDKT?f?i$ZXkmcabBM-|FOe>11$8W zp~QasUOW|q7teRZ4{2l;_#}$+cBTFSTNi@H?w?;k)saUz-oHugN8gMoU$g+VD5k&S zB*=Kv-+e*YsJNe1F9j*8R=i16t3=jcI!sr2WpXI>RcL@LD==M4r7WG21BHxhNOcff za(v!zUGl{uXx7d_*-7wkRENi=rfSYno#UN>gvFc8$is}0ynE(afTmf#@ZmJB9F4lNtWSuGofnw^~uzI!fq3!NfMr}~8*Ik-Q$GT292V7nrjb2z3* zL*3*{c0o^em=MdSjO#KWl=cyK2XF}48o&zf$j5C)D#VILbD4xapZrsYb|FtHE^Wvg z0AQCKf|U}Y)zV$z-)_IoGU@kk9HRYob3Wx~TJdZcciT~gHGl@-3p+F%(D)oG02T7s zwGL*fW0x*^^*j1D`yYl*wyPVGTl-VQb1m}A&P>&T`N^3g=c;TKnYg(=?Fw)@M6Y8~kFe~795ximDT}vka>f!Wk-#*# z>yLmU_^6utBn?wsY*P5HSF`8KRh3m??*LgHYpuIVCH#!WT8T?-zazBK( zF-wLc!P&)m!I71;h12IU*F-8sAtM-hcjbM6HKO@@6U!w92%dA1pM8Y>+eJ6n9G zSHe<{_>=7(sWYaZlKO{%#OED&^-(Eq{mbd_y$2A7u8tzIcF=dyn6&iz`J{}!8;7VC zP#O<=AerC5LHoIGs`-*A8brLNnEwr$E{0$ZI`6Mvs;o={?<|qke4~9dV{I zxG@o*7AKw;)G#xRv;_XqG^C}c+6W++g{0P~%S$yP{O&irJhS$-`8`K^uF5H~*z7!I z#4Xi!)s{Lvb3f>F^WTNe_|9FNrIp}F@RKTu^8yZ5wo+?|vNF)VkjU;X2uPA<;}b^7 z*lg_`c|}EcMPyqw^@@V{$T?ROOpHNQQC7X`WbGiR2bFCVK2;#8VXSOt$U`E)$3G;e zGt&;B;^fpq!uJ8`_BN3I*OIazx~Kr(cbk0V$OtC&%OL4Y&G`~#71hpx%ao6ShhyN~ zgJ;)3S+AjkLa*tbworP(?M)N7p)xc!h<$Us@ov)$_vXf<7TWe{9Av62i~Tb)F|D2{ zUAKxMBUeb)iMDI6=`V5wP9BqOS5oIi`0Gjw0}dZMudt~En>tAdCp*VRu84G+SpJSc zRpKiTqZsT0sRlcQZ$O6rkU6Mvk#EkhKy%3hKq^mPd85l^E;l$*ys)~E= z!`3fDu0Eqh1TZjj^Q7ZJ|e8_<`EZB)=#g&`bnP5f*jc)r zRC^7>MB*PM|AW016Z2p(q`^2ZsgcNAkDp}m)bl_>(yUl%lsE(;+n? zPT%xEGKAMvN+rm6K?*V?6_#zQMX|`&^Ti7p1$xO!1vocFe(2O8s)2Xo4EHLTCp=o2 z4Qy5v6@BD(#Y)^(!Vc-0bs8gr{vX_AO*s6D zw*Kw_4^Wm+!vCp<;6ztJ9Gjtkj~g~KLo&io=F{x4XF~9I43LQevf!bO_T2VGaFkWm z&CDJMuyc;*EyH4Z_@BE{31cK^uXlQ_BoEt%2H8Mk+}%z|n) z^Sx=niT7#CSn1)vze!~jmsEdky!9uru(HB{n_#9b{)6%zs%mo)IA+yIPRBzCv?Y9z z?i?ZpwrFgijw1(ZcW5Ti;I{%<(u~g`4EuLWpNO)>+P$#Chmpw9>>fdaycSIZW~qZN zb@j@WuQ*d$9Lad3YOY3P*u4^Y`gTpB(H&-WZzzJm-H7>xN`zd{G5!m2AwKBJZ(mqK zU0xNVF|}U)4;>deSm*-mXm@M(VBfa}+XQKxcZnS3R!g1h8ubWrTs!yCL0t~#QzmCZ z^=J*%`gET(VmJ_QP9;{>CoArMG;~w1^XCg_E%KZhe}B8y^<37%4{CwoflDQx+i#)~ z<)n;2V0s;8|A@&GP}dAjDZqu-&Xj)yp-l(7@gHnUS)t;QG=H-$)HSaPIDF|$i$kxE z&x`M;?NCi726c|c^32Z)EIj6EuN((8Hai+ds|J0MOPRvh(6 z{pOFTwgtz20p*yinWNyY9dN^`-~EhEz#KKn1^5=KZFw*pcDjz&s`7}yp`XltHny9k z`FD4>f+>}a{3ih#orVybZddt88;rNKR7+l#d3Y6fbc*&4OzM^v%}>>mThP7!DxV~2 zBX{QWbSKaX1no2?CQ=K4HR;{sg5c*<2bYO415ipKfxQX`RZkX_>ruUU86_Xx_MsQA z-!V;=7fEi7eSQC=549;*2u~1CVt$Fq4}XIA6FLW__Feo6sp1|?=++MfaoFb0&spVo zc!>(Bpa2q7L?m&J(Y%weX1DkI`9eA9bE3s9Cm;|gxZF=N-iE=VghHL!>ajkF})Vb6ulqrQ02DTf_3uScZgUjJMFQYN5>RJ4dcg~!!%iW zAFmQSy#;BkQ3O(btFlk0=fv?LTQGEYCyUHP^e;T{ZD))LUhKIp5ad}+wYfoW_JvROlU;B7kkt1+4sdS7YSvhEr^~zD12G5ehb!hhL zNvFAOuCn20FdDgK&*diLA*TJFHsXRVwI_n!excwR-v9+Z#QeelqQwCkOp04bt8Wum zgpUc#-eT1ACl8~|ib*<<`GHiz(odC$ zbuC^mf`(1VeQxg=TJQ&%PV31Gtqs@(~JwFoh9TR1USWJ zGAOVB00RI30|4^9?t|nYhl=9&M|pH3usvOrD?VIdF|LlCP2tS^xiPW;r^Ai5Fb|gA z{%`pNbD2>fXhRYfQbQ$7E&omUUt!;MwzA&YOJ{wQkT(i_W!7{C=2OkZC9-8Ob*o6K%OyDf zzGtu4WO2c8t5aMv-Yv%bI_ZaEHUUMWJ$&>0mP1DQ#^6?KHd}j66!lO0^2>)-1)**3 z!v!Ub4Yv`gUuZE2NuS*hBWZbPsErEH{kujicKP*bHPt2|1CAW&%>kFaZ#Oj?Vvd*m zV4IE2JQ*-mu4hIA5el!%Dr~DW*!3w0zUOoUQaR#TaxB8mj*~F-3Cl?!h%WPFd=V4p z%o|lKiP5>3fCHF~W`cCN>@G*EuN38=dvT9^FaQh2p$f(JBNxY1zP}_+-72r&E^=O5xgR%71^$eIx=ks5HXY_{XsbOl1njyZQt!e{s)gAa0&nw9v35Li*f9m|5PE z2nlE%Lhmm{GSVKa+3dXWoxBIKK#P6o@vb)Y3`cHcbN-=6-#DMD?K{ zI7~nV0zuoOo1Sc~hJ3S){n9T-mUz*$n9QkY`q^qe+kRn{a$?9#ZcwC^+s)z?gl|djkn=BZpAL>MZsVFL)t;mEF8t3&6=#nQ07aUm#`IWT{7?JE#kP$zyA$TntSqN_Y)U`!*N$)MEJRNzitWnY*U|fQ zkKA@)+mP=z6i% zWc!D6>MjTiS)&?T>^;zT>T*50cGtprZDOVb>T1CA)kKQv;gxjYW?TDzg+vv=46)OV zd5Lj;&oR789k+tbwyIyUuPxviv+Vz26Uch%BtM5GI@B=6V&a+~n6HrcbrTA76u8&padQM<|ZjI=j1ZLn9 z5`19-*9RoYLlGGU8#9B0H@$R_=b%j4xMY2hAO|~810_pU)kxKrNGAYa_MK1*#rYE9 zDC24mx00L3+c}mF4PVv2eJyHwALseilKqQR0X^dhK8~%ALq9FhcHn4THBl_4_qs5- z8H(tudAK|q0-i)Q$7rCu4+mKATjWvkohe|uH~xSE7>`&AH)MfDnqobbcg`{DOJSt< z9HS#ek@rN8gGw0yS4fBdicV)4*BgA5xU*q(>@XjLmQZ;9b8KuuF#afzS4~FBGVwa68kk8 z=gza}a2fixIb-2Bdu+9(t*F*b0ZB%2k>Ew-sWyc^Zg^>yH7~C(b`6&cOj( zAHaW+nVrmUfuLQp6vI*Yqfb@@izvDC&r~}JcCE5uQBS{xHpnL6&bDJBWQUch zqGx-DF7UUm^Z(K=Eak)Xq0A@VEmyZ4P`2T~O8~4OB;!NXKT0p<5W5U3mLW-42#^!mp8r61Lo<6E6@Ty?!g1KQYgDGb@WpWFg zeIwVsib>dY1g-FZfpZ98;CZ7e&2FbN_CsjV|j5^Qf{hthFYBd2kQ?N$V z!Z{ac*Nt7SuQkI;7+hRgT zs(R{{Zzp8~NLXc2P}i5mo?-F|mN8O-)?2POcS%zXewh}x7?*ZsUBtIyy6**9jw=^G zkP#un0q&@`HU?g3EwU*5NuMTr-F4&)m9tJVH`aiESRc9@XDmLfs;%OZDoK{EdusGp z2>7BJ;eKWR+ddI}+|!a+uRkDg``5PHh{1RFnj>*}T44;0=gxYv6ylG_Hk2NuG_rrh zcYFyM%onDwe=hIVzO&c+{jkx$vG4R}K5$g(T`6))n^k2lkzHc9>&V%8k@a@Cw2htd z9PXP4KXCb0p%_|16b}=DziZy*IHe}}7zE3QIO9mfQW<9f3wC-n&bH5&;J;|n^+H)-=eLFsO-8ld`HBJe zc_LZUgnk4Z)(&Fdtg7b^NVWnAu|6}uo;0aliJ+AaU~qt({?iA7Mk0rl&5j$z{T$kR z={Ab(OSz-qoa%ZmMLa;&qm0h~$1q!eGQdio%Tb4xbiimDZXtL#Yyg@O8qLlJWp~p8 ztUA#z(rMFcVxq?5&|Lz0;rAhpr)u?1H2@pYvOPAvI>(!-l6@WW~s=ITrOpwF@BW&bk(1<(yYLjf|4H&M^=2;JS}X;IQ<^X3Pp7;43#@s0;t zxm6!b;N}KvV#sY9`-7j=sI^hT2E7IB`8HLq{S`6s4>wecRk-3 zNva(A<94t}@v$~#BiC0lV~s>~A_cjkZp z=SOS(#f!g-@OU@Q76-K0{*~tfb_6r?UP6x8l8=CjUOv8mz87%4SUyxa3F`XYR;YA&y(?zUHrT~Yc(S$ z#HmHo|DrG12A^416o(`prBjU|WIPW=e8$?}a!4*Wio#4Yj?5XS&UZ-W36r4b$bi^b z%Zx-sZ>HGSfz@O&`HUVzmzosv!}h8dN5LI*O!!H>TI>Reb2jIFLGbEaI`hl3zG#p# z1Zs=ZsT0BJ#_F-HmU}qay*eMCnuyz!TZZr{PkcRcerDZrVsxRwZM=4Je24L`8oxQq z!uSd1AE->@7;$~f{mnx43M3$g_&%PkznBl0=436mq>=P1TNnuWG;>uQtRe%5h0|R3< z%sIIc)7-^od&tTAuP&ha`B}0(4OPbe#TTfWEDGl4Mq0x(YXvq@*t0x90(wd)p04tU z4kT6`H+$paO~_>ON4ylV1lBczhCG_3_m9BsZ!2ix-DMcbetq~-jix&mo4qS5W?sT1 zWY#8}uFh;uh3wD4l}ne3t7&A6+_(k-3GLssirh< zsS1X=gtMnjWJEmChik6-M0*`}Qk`cuQ^(a{*JiBwmx;{&)5?(gLrtt< zr1%Cl${hc>{f=v*g?;kD+ekraa!;8-J10jHuQ=3}Rf~6NcRddgcqu z`=W(>pM+EI`&HY&8liz>! zB+QNdd36tMo`#x-84xTs#9(Z8`se*$wv6I1%pIAW(NT(0iv zgwo{jT-wy7hiQzp&9z<7S;dOX1*(GfI<-9r#)&~LMP{Z_!u7RI(htGNB_Fz0gmmjj4!OJakteJ>G|?M>6|+MHv`{# ztbQtC`&cDvy-#s;u7kW}TA})~59pM4!+!6`#MH$A{HIwqwqF_V4B+oi&z*YMTYBC_ z2?7}~UG@FjJ8sqc1E!a@cZwES{=0a;^eUhRAWn0h_JHMCZxv#07E4kJ*yK*F0C^0L z6=CJ{Z6tbWL_XT+udQw7b`b29CAI{2EE?c&1@kf3UhX@IyN*iqp%3yi{+_mlzX%AY$~E)qN7*J#@LiXvDO*=(2m~ z0voNov)unv)K`@YhWl(+;2+Ei>1@Oz@6p{Y0gCjO*n7&pr@B#wpMMev2LRI92SMoP z^B%IWMX&q1Qm?v{!=giF`2V4A?C^#lILwIh0uh2`>(moo0$nt*P7U9?e26#UqE`?^JP@KSTlHXRX<|M3(4)NfPIv>L8 zDQhdV%#ROIbt`ew4%5)#x7^LHKB!yMB+bfT@%9H($yV&P68h;ZOpACRswJr~;X98iSCwMu04EQ(YK_0XKq&acMhr{%Hq4 zWP7AMh456zz_(qCe934AtY#QUkTeu|?Y;;jqeA z{~FPwtjiv68#B5gB)CQBo;XXmhRYr7f82$rna<;UqQ-3lH8uHTa)PhImW0(e0Q z`z8#s>@Q_T&KfU=4JR$j*(sX*#QUStsAg}JFfVFDs13V#W&JYyUJebZFLE=qjELrK zVFuurm>1r&BF^!;ja0`&vm*)g%BKisq}Hw88666~+A!J73Kk-IzJ7`O{&F-3*n>gcfc`o?A@b}03wc`jiLucjAn1Clt?c4T_ z(AcQ&2DWnu&X_y|*a`tN0gyMlbke-udz`k9<YOV}Q5*9|u<05$F&{CBA%lF^e+!fRJ~J!P06 zGP&GyOp;j7L=-w^4#57vhc2-idpvh)v=AX^fa$bQUm+ z#!P)gpx+3Igw$?3@auo;UrAIgc_n1reTtD?uTci4XLS?875yfGnW)hP5f-CnX$PK$ zjWu=~aF0W0WbdjKV?qp(6<(3@$6It=fHn)_6*w(x1?+j7HSE{_uW6a^7i5ptvj6}C z00093)(b90RU94X)N6?blw!(5DPFc#Ue($PE2xtP?#bHw1cOUnrrpd$xX+hXEY`-)nm@!1E9a zn%!cJ7%CBJyi-i2<;0(;Yrg=TJvy*r^NU`HnpW@_z~3}?fN#XvMem$3Vkx$3Z~Zdx zMgrgA!utgr7O%6aic$LOd%ElP0>dCl<|AR8ZB9W#|HnCScCbN+rfSNec3FkX`3PT> zMe`%iZSiiZQI>bO8GfRkTFZ>-r_)Mg2DE22+rrZky_$?>97b4qtGa{WAQNAH9%Wwu zG{QJG*5rL&KOaF?KepOcTh*D-FEy{j`)eMM;=6Ee%RG}=HI@4Da?^=aKm32CnN^!g z-*kw-<1U7Lc{olJ_C3w-`B?f5(}1dM2HkLgGw%<3hlSwr;pwjOgQ-`7ngJSn#Q4}J zqw1ADq994WT& zyP4)dD5I152y$!m;La|oWWa~^VC?@t$ZNMq9A267v1s=xjXe0{MVPoNR+YYpgWXxO zb}ihXAUtYJs0ep0bZ(@tk1h~27~Xjk`%Tp|6SI@ZgmP>SGH<}Lmota7$;`4I_OU$v z5#tnNLVc{TUzI}y-+H6Idc909d8Rt_OwR4f+W}7f zdR24fw1bjK|MArC76#r-wcLv?DK9-fB+<9d`6`>T<6rwLhMvx0W5JchH1gQQwa$zu z(y?;Dq)W>nmm~yRu_=New1h?RH>CElsjx8ow(6D-M)McU-4l*6#6|zMrfpnbbuY(V z`Q)j!1-A4j5a}yRYUwl=7H3t=(_jDq0{{p%YB%F&$313RM~;V2iK)u&i5|{`GO8)< zI_qx7uDBAt4=lKnGO|=nLT!YT=^SEY;+qfU?iN`Br+9Up>c-0PamrmpY#C8Di3t7( zM5V=4qm81HsA`$oCGBOa>NNM=AM=~$rQKhz+U7UX8mbnu-;F1~Tt8)kfH0^Q0*7hF z$)JAeZO8mNH$eNf+2jb(m13E$z%71Ralv7{^hyAIOKq(-BO{ zoOq0wlD#F1kyr)l;pNJsheBd-*k24Z2ThIE8|*rND4gvZ3Pj55wScbyF7mCsTvhz2 ztzexDrfhVvgC;S8@JZQzk)gS1^6I%dAz!HHsxd5--ku6A~cd^k9b^}^m|8i3T0FcyV!9RsMSu5McbutxIegB|6a033mTdwobofmiNMkT}4 zFQOv4MeWA`oUNZ@T;tXv+_I?C812U4+>n(==5z+b&N8_Hz6@yqJV4278)C58B&@vu zT0BW-k!6meFh9G;dNwvUW&+r!pEpv*bPvpn+}5EG%!4M_AkR$(nP4ei>-eqe%?0Q& zfZ59@E+xO~X#^YRf966QwqIF}-)w;y5I&u|JMx0x+_iIc%IxEim)eb zHu5*JZlr$jK{^8<`|z~Uq;oBI@z~A{?L6cNS#;4div1AFl9bCPET#RJ$I#?jWTO)N zO0cP7uV+cA0w5caCMKcL1&8sV@-zG%cw>0BNdfS5<>k$XJ*5M1iqTGgv$(1yuE7e% z88)#`)50!oJH+fN-KOcCt-4r&nTL#<#X`~}34nXVD`q9+G)5Y-D&B>t-+~*{IS>__ zQ)TOy{N%{N!8`e9wU`IrHmb-*zkwx)DthxuF~s6ErK_%u=ZZe8E&93Kd-|DR+hMK{ zLPeA0(;qf`D^mmbYQ-FWxYGD0sBttdNIiRE%qUJq!REe|eHan(!~2e)BQ?b79Y%vC zuF14>ovE}vb)k$0y6tq6VX2#nH$UmTBC;QUE@Z-LVHL%pR*{S3g0T=d!w!Bw9j;eG zTz{;AU-^ga>XRv`tqyaa5C8xJ00FJ#bhD8-Fb(AOQuaa}E(ogI=v}(zQmSu@+ejXj zr<5zCX~D95^Z~M{O?hNg+@K+|JsZwd+?QnrxJqC+QcP0@o6a9+TI<33GmhiWj@)8^P@A+a|k)uQsW z+(Y^78n%40;K`fxQ07ux#S^juVCA`!uxpqcw*czf8@IRA9>quid-0%8U`(D(UT-SG zuDEyB3rncHqi{In?Se>Vfah^C#CS5$OChZz~fD43Jnu%OdG#}CuY8adqZ1YGbyxtnd)F$*VV)Vm?@k2?b!1Z zrSh1WHsGlxT#S8Ro5tqE#F9k$fmmwLE`jOebkeb8-M9T}ooW#wzTu6P5o)El z)j-pfpKT1k{|MWoa^1rd%Uf4P-lF3se38;fd`M87hN_zkL|0GNMBv@Hkz7WE1AKPCYYHgr zG~wt}GROAc{l25`*L;bG&&AVQvl|~g3kmb5)FE5mwp*7QtK$Dx<7b@eG*_n{NS{^% zRmrB9+5)Pfl~@t1jPKT)*>fA)6=R9}?&41Fi1r}+1AW}np`UX+<@|)Jb%dD-#YW(} zC7fp}fLB~`l}g*RhF}B@3gK|Yq8-}L%kMtL9%VrVs>*T#t%(N>F{A8)#4mO=Y%|oT zOq#sIV5lwh=?B<}6CO!+kzJ8kFxttrWO=}@LJtvE8q8urXD_^5crh71ZX81gqYG|D z1!5-^gA5>7mC&((rOT`D{Wb&MwLwqH_-$%iNANmwxfq&bhwx*bOWuoo-UFau#h9`L%7wT`Ke!ygypcCXx216I|LHBg;*>XTkyfW`{h<%F+kp$ZouND$FXqj zryjF(`)ClJ~hfFUM-Cj;LAKjzc)V?-Q zS{_)O!DV3ueMu*`l45UlR$vl?N1FEAlNmll?ImEC8LEJP#OwlywHp}j?Gh6{rLp$u z@VvX<4EwV>aR+&O;Q8paCzSG)fcbmU zBzU{y!0uU4-WEOp#K>OdrVc|6(0(1p3>{pG?cM;>UlR#zLhI7~(gpD06^89`p9SL1uV zfGu}N{j@*Yascrstb!GNiu5icWBh!G8uC9yvJ#lnHIwY2ueD%HcQ+km@$w(O#=Z))!mM}Aw88}Rk&@$Q5}-PCrHo*K@wLcfiKY_FEc9oLLc?} znV$NS=sV_}9^5};!K3&#k8JCofv>KFh>jnJRlla)*p?9FF+c=K?(b_BH%fKk+uQ|K zQY{Qo_1Yg454C(H0pm*nhUaNjAx zPh`+~{OAO`0Of$$TSkS=No0%#p3kl!Hv=jaOW!|?|;Nc|D{u|~;;f=OH^3r`jQKI4Jl~F(lllBdf zZF{yB5CA>`R}x?ZuGRW3k*jIKSWiq_tI5S@qG7Lx^Dvr-FhS=YB$STjOWk>6e*DlB zuXjH-zvt}fGrmJPy0Qgzdg=|78>Vw->%nVa_QLU*iHAW=^>%G5xX&o6K;12 zezn26OICxcC1Ur`h*dLdh0LciFrGs!%NzgMa*hG1?l5c5rfqGWkQPX1&hyFzOUPhN zTHVGmGGzWT8w1H0eKg0RV3}$6TFgxZ9F1RtbgBe#h@z;ysyd)I2eJ7T>-Ay6wc+oXxt?SE^Od|>5=~hvkSGHTp)%2VG zsPHUKe>VOOiHez~cti{m7^XLK_jLNza;+myvhAH zM70W+n#VD*v4N7a2c9i<*lX(|OQmFMMqoL~E=L!CvA8-i+PYLcRHLZ$#jwYSTmX_c z+s(CRWJb`F-qh|p>|(AyjP!@q{}3vIC0ece@`49i-^V8v3^fX|sQu7=@LvAltua}Q zpHlapJEUnD+{(_Gpt=H%as@mzl#!C2!85k)cI)GJosiLa2VhL;RF=~GJf-y!+it9^ z`fy%n(UUF(#u@o*A36#rA%xW(V#Krx&o5aOb%#J;R#*D$=bN`og^2D*5H;J^TC266 z@*FJ!W5<1BIaQI|hfc9=_mwHe8$ec>-C1Fp$goLuuhs`GjXb(8%G|jm$Cq2%4X6fv zJ=MVDRonu`kYev^*>yCdoI%jL&^uB2IHGctMBe(Wh1XK_L`n8 zh=s+N20vR-=7TyrN-wHxuwwd;=nH&?mBF~4NmaVg-jabv^Cem?GpaEoolyRW6}P<+ zcI71e;zbt2nu^~Z3Q)u(-Un!@Ph0%#H zdRjksF*LKKD%!nS-t>9|Ux)fC^Tx`OAXKd3O=>ekj6ITl4B=2!mflLL7nAMQm>~mf zv+eJ+zU%(`<6Uy1xDWmzzttkwkMIBiP;)kOR!cGf00RI8Brt{V(q-^C?Qfr$CnrIJ zMU4arPf2j)Wb02V?T)>!;Uy>VnmMZtqK_ihTi52ZuW-Zac!Z+bs1m=&Ekv4(Ak$z- zdB3riV_w2dE+5Gq7fU9RC_A!S@WCbq{^vCNrAs`-2oj_49>7fX2kAx=9=E^{+rm9#!XfchqK87ZH zBGHn@_*XdZoIOuF8kGmb3G=g&EU-oDUX}^8=bUEdZ`lD)ra2Y@QK|{ z=RSVv)9)NLUog6T{V?qZV9Pjc0YDE=3LFuXz7xijNh%SJss1cm;j@Zv||=| zFkj=uJj?p7Z+S{&65m!U2rx-_zGa6C{H3PDd>%yl{o#SEjjDTdJ&NypOC8ta~?*rxFn%%z+ zRT;05SFAQ8H4{jmyTyd&1`MRXJX}Q(GjbBrV(Ur(F=P7(AS1YVHlfzW!WzDLx`0vc z436!+B6r6|QcqN|)krT|Z1awI>#gU=ZGftd_BjGcrX71%yOKc&Iq7{Uc>s47dF={- zg6}*(+&(^10kr{b2c06wCySHJ#Z|2E*P_%zY_{4RC*I_bLM`?pmYNK`%gdN$K4tR-9Oz+GFCk>G+Al=krVI+i`zdz*en!rn$B95RbzdK-INmgR&#U~*U z>=F?g*2Hk1V4gnf8<5-^-{*oIfds1=C{bDAOY6$QhHvOKJ&+=wwGB%MJGOA~2Tv0_ zCGJqON|0+;XL+K5WdjC4FPFuqBFn9eiiNdSQs0xhZaEB17`4m^0C{&iWm!Gd4z5hh zo06`;GfN(%HPcs71E8J-ISh7sM=YEJHw(IH1z7UOu(;^i?&aNgxqx8Tb2jfV3|m2| zWg~*L^nNZoI^3lCKs40Z2dmsGv3`D{?-)Rkw%&Y27Oo-P&3Ucu^K?Q2<-K&(%=U^s7ogB&>>wzg}+ zvs@hDl{lxPF{>a1idVp1s8(ui`io>c>Lr&a1+J0(PCM=$MU%>2czjtHTE0yMr1=B@ z00RI30{{R605b5}Dz`0sv=kqOB0JeAH;#WS9}F*6rIzrgJ)@EWrb6pea3nvuThHyN ze0V=_Gt{v|49U}3*a1`z{MivF1@MPh3oQAFP%tJZ=#9_4Fx0i;XQ>9RpeA+X63J>l ze8wT62qi1^ZZ^^Svx<4rCg!O_|dQqHm+zsf|tsWWU7~b5NJ<7JEwv*8<@6E0@xYX#Cx4 zrT|agJYRxbH;FErA~1pOW^2I$DdnEcm97EyOwA{c>rHjS`M{KjQA?fb12E@-`8HRI zsWPR*-CKr4oMjPXEv?92S*gX1l&ZqKxSZbY7G)RFS`)t^UXxJAw|wA4|dtI1?^TA>41hr@Z`~I>DKZ zRxi_6($vwd1iMOe&MFF^xQpzmq2pXT(}(3QxK~qQKT;_ko4rOm#ECJ+CP5nE>iM`4 zZGs-|rqNbKUwa|gc$E)c-YG%NPl{Y>>zUN?`1R{!Qsb0&8;{#F*ODQ{ z$Yni1h4ySHHCNA}^KVTP7K%DOonrmrF@R`U8f@Gjs`BHGuxgt9kuW(_;(X$TdT@Q% zA!;l?zoeaS59p(WriroKmb(i4_Z;c<%tk^cKT&O4reZPh?oBa~&!t)qt^6T%P72`9 zl?(;c|Ct=YWRU9{7Og^arwMnDg9VH^%O{;yV)5td~~YEOUAEIrF6SH-eZSA%`AA@ zki@E7yCOsQX($mhYP}#y^NAP2Jtem;g@Tiv4HYG}?!@L_h|0$-u&x**OCZ}DU0Jnq zM(tW5)|f&c4z@lIcs2;oV$mu`CzPJH$TcP6h|s7IMxaqyQf~FftW<3J91cMWz5-(n zkoE;#!Bm|9-|13=gB~;6TBQtCtKHbZI^n9>)b=w?;yLu#@#&-4J_aIlx^*L~VFPO> zj)=@r8E|(t$V)9Nl21Htl-#7e{l6k_CRk?vO5~Yw^v@nvAy8l=(SyO@FT#U=WC=|^e>dG@)ZHClPEp+VY zbpS?TSF8JL9|+s$0RU0V{z`iIl!#&ZZ%5OIL`&J-{2{z-SF2SQBJ_n@-+WSYMSw(r z$~^ZJ-gJqUyBb%g9y%B4yy{l=I~YaC;0KGR9%<|to;mpLQ^un`)rkkpf1B%xTaNR= zUv`(J;;L4hnWWTzbjahc1Z2TA-uTTZ5&w+bkHT4v<#Y3aua}Rer{!$}lcu|w_r&XA zmMl1ep(t*^?Zo1Qg7&j)rtdLJcX!k04zaLV0Z1RcWbO^VEQXn-so`^~lzIw@KQGK% z7JrZC((9C??d2hedvtc{NY2dG4gVoAzi%FvWwY3pyerT5?F!|McLajYR1Gk!B`_a5 z-nEEt`)llt?G1r|l#V03hWv$~%HBFWq@^?VLl3uC9qelK1 zkp$)A%!M9~euklTs$z7Y?2{*6S^Wvk%)uVc)s$)5E5!RPpJNqcqzvyK)qj^xXt`3T zGo0dJJ6&Re2nZr!mW8=V;TNS@Vl@bnk(?)S^O&}Fc76vvarGFgnVpJz7)FEgws>VV zYd_jG_%!U@j}#8fzNRrDD$?QuyDH#nI}R)6;loUt@dx#%&O5g0iFkt2*PIsBCW~vg z)6;L!g+9NYuUT3G6(Cn5{Qv+103pXZC{{+#o{o!Bs_|q1=E%uu0|q9lq+{o{vE{kd z=B4IctT>{?=jzly>n#)A5G@UXXyI*a|8tR}la%Zs7LK+eP2otnA!2}b<4~36x(4;b ze1@`hJ3b51N956#baUQHtac@d=B4pPq} zf}d#7Qu}T5Vj9VaD95Q9uW9hN@~DgdnI5?%vwvi89Ly|szjzzE`|P92*#AYu;5CAD zI)3x>KIq~g2B3DPUm-SjxkNB%#bzuD`TBsJbiZn2_6pw>#CI5qwc;k z`*-*O5a8c9U+lXy6=fi4ilNQ;FCNrQ&(=95S!Q-&Fz0hVOAEF89=Y)(Ag#}Pw)EM6 z)7X_C{~D5}C^j8zO6rIUyoVXu-2ObZtWWyTq!uFIJ_X=lX0M%;5gsi{)dFJk`Js+h>=l&ERiXVu`u6X zJ0bg8lVy!ED$b6>L299FES-^}l(ZYb0ocJTnMYJ`^Ilz#vTS8^k-TnAV`SJDZN8;5 zI-YwxNCVz@{(TMos%DjmsjdW{8E9{@)FEEq*lM4%d2sh=%J@gGn@|7}G0Q}s%2R6k zcGFq~a|0_2HUtHT^UVW4^d7v3$FzfLo~nmkEBXpPi*<*s4G@)-6WftlPA*CVKNdH% zZ|%wm^TQBam7_ppk^Ga&mp3W)#wuDRJWu9C;LN6pdwMVjb%F%tl4v#ruW;0LXI8@I?8_JO8UW=cTehXwelMx}fwx{VOkZWJHquy$i$)6r z4-V%^J(W38|lzCI$(@ zIEae?00RN+Syki`3q|f`GA*ttJ2m=Hjlxaz)uq#hIx;oLO|lX+$fQunv^~SMwzBJ`PqTQ$Zb9msr^0y39s|5`M|90F*A&|dwL*UIJZxZ1)jABG zC@{>IxyM-&iOxXuZfyI!FMh7XeC&d(VPSRruO7dcZkhdOSlw<;b?%R(^ao7D&N_!# z63-b7QO?vIq6^fum@RRwyoF3uCT^l_?5LQ59Lv2zJDD8`7StytB4J|v{4yTglTZvR zKnNM_Y&>F*3?ttmeGzo0lUP(`N6fpYh#Sw+^@sKmp9Np-2wU{I`V0~4)u$PZhw@Iop`vT8!RG1V({ly1e4;kcX{paD|M9gQ%KFTYk!)Ev+&$f~oh_M~S?v$Dvj9a}6tZt~piB{?ak-%5bI(0qD*M z64zNaS*}(`tksf}GxG~S@R-Dhc^k}cdeOO@{H9fjmfj`}`>0pS!MRYcB+UoAzod{q zb+0&V6z3}}xPNv`t=?FRbN$0&j>3wcP|y7kN?@y?TzW{N&M(GLDB1ryibZJ(WkP?{ zA^b(ojBlQYIfO7H=!4f9v+$6Jtq?qg-EnjjLvJsGB(+9_0`1Lo@7W>ZUJnB0P!%1J za+=d2svjQIg->M#-g+$vXg>u#f>l824H8T;t5?zaSbaOJCwn)SZ2e=A!5V|HA6M{8 z2Ll+h7}AqP7Ukpxg_rFNg;Z0ox&of(DB2v99+6g6MQd1b0E@i$%9?X}-w;>US>|ia z_O%c@8ZWb(($P5p%E!I8y9IEnCCD?l2KBiABIqaB#K7**B%arZ0`~5f8Krz;x9Qvc zZkQdPQs>CA^D!lp`+FICLFeg3915+zu(KOIK+DQ=?sxSuW&H%1g-|Kp5^6gRr>_CTo(+?c7-K zRA83*cbR{JW?(s^Kd$}te#D>Azy5RH5(zr?j9xEV%gY^5<#s7nHo~l70d=}_!6m3y z6Ydk_BKPt$43hi`4RDgAf6-6KyRqk0XUWfRb|K(@RG0bfAEG2|8`EcQV<3{YC`cnE zF0*+&%U+7f;IVtM2B5UAfU{!$Q*p*YN){A=+--SwYC~>ztNWaF*x0tUR}xxjjg6x2 zy9*Zg=n_CX%cM%i++$#p@s-w$O>EZe&{aj(RuX^tbODzozA?4Ce0MvfD>}?}17f>p z#Y>a@oeSbV;UwSvnL^IVXCZ%J9QVldD1V-rUb~N-ox&;>4)KV_sNL^NgdTWP-~a#v z00094UPC^aN?rN0Z-5glY}77sTIERGXNnM8Abzmsq}g z8%YF;w+t1$ zNSPsgDA{G6fx8)sSgduCIQRe@^#*xry!EHo!(>0=e~CRq1#Q1S9~KP;{SK1|Npg@vouA3oIj~D)9FTZJ;`Nq*SpThM$hse4iCF@uDs{Wl z$8et+M}m39{ZsH$)fzoo|HH`@%gr_+@*O-&&xDOFO8B3X}9w-56&+?Yv75flDaRv9iI*>WV2hlh2pz)Ft$>~Ics+SN| zFDe=$46&y>Z~W~JUHTeNBYMb{(-k&}J*6c{KBA1s$cx<}NCZCdMlUG{f?^6?ei1C- z4J-E)$zb()rV`j8RtQH{CWR4}CxJpc5Ya#)U=sw0;NV(S3!ggKmYoS%W6p9StWzFR zID_(?;v2^hQ11DZ?iPH>Ysb`$`&5n?L7cKM&+KFZOU-P35VaOSkm<>OGki92< zfdF&!lsVA|<0K)fHEW>-MMIT34x<%!Rv2EGKsSl!O2AV&wdXvl&g2$n`8iJn^G|sx zEp(9X;UE_BdNH>y0*Q=@rMST4#X-_6XxgTGSYdJ{FEZjGl;hAFNgbI{E~Vbv)F?a2 zD#Z@x<72w164V?mQ_of;s_j*EKH4ORu~IH!g2@&+@47LV|IA?X=Z^gEC=%&n%?YWo zA&$M2rV<0!dE6lnYFgjPlJX;qno4>UiU$`m%F6Lz1O55;B}mhcVGLY$=YvdH>(KqM zZI)J}Oe0C-Rm1*=E3=fi;i{*9@zx3URnz|6@70Z0C2!yi+UqBS=cAGU(S%A9k=D>W z-?70SB(Z29fabEDIAR#nrC{Uo-Dko`NO_lUG?szD=fFgGJjeeL--jpRKPZ5p>m?xxr>A+Wr>Rew;Z|5${yHrOH0+fyF`{?^Ssd~Uz#}P!7s9sJkI0+%Z zj?B)$mjYm>>@MhwBH3u(m0Lq*D55!Hq**8oD=$vL-Eucoo=%SmZDGumTgP`jFILt- zbLoDj7hHTCkm7SFS4}$PYA7w9K?04f;zI2~&R_{mDTO$l7K#gpZ<81J#2X>wqZfcf+62;f7N8%Lh>m)#%<*yxWDDKP^q# zX>N-2rsB=;ALP{(NF6Oa_=fh;AYT@^glG2*nkaf=w0rgJ3K`=b+%htVGk5DGw&s+X z)pz+Bvna}+i9OnU26J}v${>yXjIj`JXjU^7h1J3+3IuKvf)%(`?kwn1yPkM6MO=Ym z7CVfDi{N9Ik<-8Y`2}bLhtxPfzpIG77@0GhY;pOcrNCujOc6TTUoeb|(slfWF{&;< z+hD7;PI-rHtX)jz7wtei(Su^hkzek;zKJJK{&YtC!tn?}zTm6K%v>`Cub=8Rh|^Q0 zD%=g>OxG1|%u^20C2k4#kCyQ>b2PNejp zfgu#_&i+BX3ica;(cv}ZBY^v|IFPojoS+1zz+$rnLn+jZ^HDMLEhadyh(+3>@vE_q zx#0zy2~|}X?c6TVujN-Dwxr<%VHO}xtKdoR;SF6bt{C9pWZ2G@{tDMt1WdVwN+czd zv}E?pI6X%FnAhgBCoYUy05D`Kl<6ztytmvtRXQ-(g2)b@_jR7*{N4lps{`)wMUq<| zK~MdIiiDq?Rby394wnMh0lKP@xbF8=0i!vikDXmbjo!R03+cq*5$ooAS;XC$`KScK zq8Gj58mzN-D~-R#@xW`2so$P;Z4`lCVz=%7mndKhies4Jvxx?@&td}$%AjeX)J)&7 z0009300cntVIu&D(OA=Eq)UftvUKIuYd5F_pRhp?DzyLW9$8<!eQq4kJ zt+fs`6#`JqS20CV@%Il!05+Sad_%2=@Iwx zB}XBf2X8g(X@byH;KbvW$A#GfBkXoqFWtknDHW&3VG@*%8BUtK^O0gy_}+Y~HaS?@ z=>ejdLQxQH0dFgs2Kgsqmk;o2@Rp+zIMK$-j{I?NW~Z2{Yn8h=fCqSlTzaom6-S6= zUFq_G7@9koc+V>>cw*0xo{ddDck`}*|5I2uwrNV33fH;h3Bw^Tl}&c+-X7UEdw{oC zCEKFpjlc7u{|)C4$uQQE?asiyt9k(?P221&tmBGt%LaVs!I2_>P5xmeihWQ<$XpUA=xT0ACuGng2pRM*|Iz|B3d# z`Ipade$ln3R^v4GqknG3n_^*QQc(_b!M zkQE;IKM}chn|jc!+-)|dCcGzLh+h*%pfE?%+_S00Qr&en)peugP z^zH^%R$eNEZ?tf8V+}`7l#mHzmH4-xzz7k>J=c1$=Fp<9)_Dshiwa|t|JiR?ducRl zZvFcpfk)zD_ccuBTEXE6Z>?Nr2)zIzR>#xb2u*BFT)f-AA;%h%ci(j2&GN2N930Di zp6jSm#S4$tKB%e|aEeY1LqDc^`_Jf`qTBAriMdM%x1D1^D6rb|V9Ce0yNv??)Cup0 zVt=h{h<0~*vmB}|Cw}?zAGt@wsm(7~E2szvtOSktb~Hu@k~XW*0aFMRNtyd>;}k07 z5%m0VSo~RfbHAFK9?aaK+!Q7zd1I&n zXYnh}H3EibGBk%YOl=`ogLO$j#AMn8dZk4C2OXw*k;dCv@a;ka!a|TaE&2Q`-zSDu zFIo&LwQ#+BXM1Af@)250t*MZZzTV+I|CRLhBDwysuC$7>pzqz5PM^!*TETAZ$jVjD zafOTs<^%Yg4u8|P%C0Ltu>i9;u*p;GBtL<<)Lj5D2db$O|9L;0s&LH)=pnEMU@T=5@vgsCb~*Te}m z3`)1z#_jfHrqwu6!-}9CscrU~DR`V<6={s$y6WFo-Kq#GC|GlR9N7*hbVggVwM(wt zg?v|6@M(RObnlAjo@1BDwpnE3aC$tia=eK=sM<3+_I*2-qLtct*er8^>-HL4*2-gd zNo}9?eiLBsELe{Zt(@HL6i3*n#mc|lTR@Bc#-%rW8E&{a#1Ksz?cWsf%h=_(Pf;GD zQVLequf_{Er+#Vew5GjXDAScZPG|6WumC7KmpeM17s$^()*RS?00FV+YdCtoMw*6^ z*CX0XSNjT{Yr6jZW`2HTFWDreJ@-EZw(7>$f$ccQd(#cz97sxsXa1>ImwQy`2iZpF zqg>;69EP_=ETF-S<_y^Cr*phBf0K6b#y%V92`3nZvLl-h?X--{Az#FRblJ;Cg2S-t zVM5Vj``uS)EJU7%FG|pBE>laORfndt@o1`+R07qCE~Ltxod(5t#K(R4Mv}&s`d7pE zqpD^C`K$_@&wL4W9X%^7iM@M{CUa-fB`PxP2@U z>({RvVDTE+w(hdLy(d3@qY7|dywy8bP3O^_9TjDlH^^CHRUB?M8!rm@EW1?yjRBaM z8t_<9Y4j6`*^Px;6OQeZ!Wj)m*??BB*}(&REanYX_)Rw@;+|~#+NDOZ7W1oEp7TeX zRhOh#z&QBR$zY>{gV^Ky4bP{Yd5- zZ*Ix<4)JU$gjshp(PFrJ_G>(gmxC#=q^5sxfIE?lxy!$a54nV z4V5U1dJXK6R-VX)o#H8^nKpeY3~9}l*QlH23}g9~+dY5#84@ub^w9ZUO8iU3d-CDP z$E;2ycdeD55PlxOveu@ZQ8j>w0#zU-`go0L%Q`EX^p;`QiGI=b85w28hc0?%R6Opz zf)Yj_B9%s(+~y}A0Cqr$zrqlVUUGAcx|j0bH(RW94=;yy0K+6wt3)PzH$*b z?aIgByrJdD)0e#iZPdjOv+1etuHk-1)CxZ!QnSmBDj^&*NR8De{X(t&3Nj#OXx6v9 zGlh46H#2YS)j1Y3B-&X4)=}0fbfxv4GU*0@1+J~Wu7@(o&kc?9^ia`wWWId08F>Q= z6^xA+Rf2kez-3ahCJ#%l#{Z(;fHN;1$SL$u^EmOJ4El9a zv9DIKr-lE2Pw>nBu3w-h@&kTyuLnGNq5OWUQN2|b#zY2;DzgxpJP_0)=!PCgR+dDH zreCPs@1;ihGj3D|fBzzc{L;)4bPMQ%0v@dPrCUlPBl^+(L!|20gL`%`k`8uDH}Cz$ z&$~>xSLAe7G#|rr;sM$_9js`qF<3UQDP?t5Q+F35rY|Pqd0qX#;FNW(3vyN4E?6)N zv*ErS8lfFqKYE!wgpTXi=#nX^wYk;6&}E)iJ8-aHzKm5tzz&B31zontM6&QGIfM8P zwrJ!YINPl>FPO-W4}EpdmIpw}0JmHmPaB$;w6W!(zAOv$cW_~PAwMn3pxt7q>Hqzo zz<_%YWVMl8ZBGE+*}bM0vLdz2!$#~Wqq2*_yiSWKSz~m&OZzh*bN~PY03_KpffwmY zg`?%BD_LdsHq}<0B0KA)pG@{`fpo1SM(r-P6UE?S+nF!}FF1xnSSK5^Z$X3j15SJvta0)uW3pT4oDNOZFHidt4b zoK`V9J$cOjc6^Gf{oq6P6=m%ouf4g`zHUk|F}2zjCMntLC$}y#^N*lpC2MsJuK&hH z)FeOm(7X$pDBetI2j_;*%&<0i@7IhCYXd0|-nEHr;BWDlhDV5G`bx`2Fwi&R@RVVV z%A?xy%oE$5C%&_Mn}MS7EBb*1e_MMMzJlxhG60ueI@tp{Y+odD(}QyaV@QAmt+c{ zHkq2hmO1GK|CPW1;=I!k^5H4;nL%t;xy-9|G#yQtTOlo#tim<%WnyW=D?KL}8!&V- zLa<#r0Q{8<7kNntk~o;@-IkpIP=2xt^VkvmeD_c)&PxI$R`LA~i}*UlL$~$=FMuH@ z7UDOLhq$T2#-LiVN)X=B_m=m!S>et$@3{~^d*Wn9#&TAwneq^1xpHNMO;^7&*E&d* zKZv?ISaCvMl5 zfP5$*uFf67@&69l42oaO_~FZth5ii3Z`E5bj>o^&0CPbsCc(_a5N(bfc+dgUIpC%vNgdv2pp((TA`E{t!r`)O(DoFp8MO&Jc!4=2)Y$-TC^9)D&-R z-w8N}uTB-}5YW-yUg*s*C4@gwwe&*r^2t`=h80T?z`)VZp1PNVx8*ZE(L}>#Td_Y1 zL}UOYuD(SD&p&-AbN2NUZ(U@-{qO#k&(yu`T4r2wRtdiwQ;fW#ow}e^b`APrkD*!| zm$YATSz|6Kxk{%S_w8*hvaW8Kh1|!iV2^8Z*$g|d)2D78Y#PKZg9QBq(U|F zuZ<$7co$Uas)wH(Ok;wSx+}O^y^7ndlCowc48~GS(&2;HfzM*3go@T*4!&x@tHLHr zyP{5SMH3YRj~9M)fwy2oJe=$ z8mEpG3cm0}gR!7h#<2b0fH(^eQ6VV3gw^6yndaW_&~D{P1gX~G`N+K3OwozaO#K~* zrzCd$>GsBUdHG<_4#n1F7`z^ixCZqZCR1XA!p2uBB*A@%af-sPsz%G8pJm7ndy=*P z&rX4&8wId|6}-vIKc41|pHM4vMDuPe+rabbb_bqXwGmQU4r%9TTj=(4y0dc+S`-l| zM=)JWJ6-kMp#s;${&!WbYt;U49NoX^y$&c(*rb9)z~bnfq6j3P&@(&l2KuNsMc}k% zQ(-EHerF~Bq}}Q%MPW?{o~5`@i`>#?v!vc+*F`&;8Xu1}NcWUvXm~pzt0K-pd1HZ{2X6P$ij8$0f;5Bhdb$7P+qZaJx%L2dVQpVBR(Z(4A2P*k)~9vr%cX z?_BuaOJqq}$bx&hX&**D-TFV#;HYCWqL+LVsyMR2uMXJr#)K5fETC8si^Ftr+Rjmz z#Kp19mBH%KPMXk&k}caAelYk&c#`+Zo(qvFg^Dp{hO|kHLt$v4!`Ij|n0(3Z!HFYBD03XP%BoHSO*2j7l%De$%>ohSTocJ&|G^=*8sF zFHe+8?z%h&*&*1f?z;{%Gd}+Tw`m_7(OW1c*JDwjcB32lc;FGTD=|pIw3^s(rTSip6Y;YZ)KQu6!*4^7}Q{pt3`;qOQVSD9luXggdh4w8y>gf0M~)%ST1p97~<;Nl+;`n~kXA-=BHzG4DE3QLKDt%B@uRtWy0D+yPqXnEq!hxFD9r|wU zCHHYF0Wk;Z4}chl-5kp_mMMW&rxOX9BXCp?)L}rxa{-RLEnFb_uRJ}o-Nk+C16m>1 z_?be%Bxkj(9i;7!e7}?HBk1mi*byaPc~_ntR^5d0M%Bk=qFJ(Ud_*papKKA@X9bA8 zgUQYufjlb0Qa{IOGt|eLME4(6GLa6y2ti&FDcH=P_Dj@!Z8~*W>&0oM7n%ukYv=$K zXKTpu4e@<*+rG%N{`SeCtU=uttND+)ZHc5N-e+dJ@z*lyBYTl#jXDj;IfQ(2psY) zGG+UT4GZhAZ_%RBK*_ggtZT%w(HfA6kBXuZZmt8Q$r2;>$X&Zf#Co`Br04Y6R-wX?#kWk4gI}!4?C<_|JJp5X&(nL{yBSWC8^C$d zB2~ElDoW8?PwQTTtY1}E8^{1UqYr}{aLf)a+uDz6P{M}`DS2@ze1+__@n)B=F3X?Lg z=LD~t4M#_pN@iyw(b?}Vqr*TkJ!YyDUU{l+j!x=+4ukxCwqK8*lI`Jq)w!Hg%6+>I ztXJ7(_hm+KNR&+--t)~VNH%`IHQA;)vjw(Vg0%j~x*i#NADqw+p^}hV84$X6O8*|1 z@=-2jj``2)mn8uLb3k3Gvy5!wfCBM0%^4T{UTzN&_|`IxvWc=6=+BPGmBdY7{Q_KU z2zVjP@#qjv$(RqI=C|GLzhs>sW2ol<00RQw62H3u00RIRI}#8{>`HS^xW2>%SHa_y zH0y{6Q}26F)bP=*5BM)4$aFPo=KxhM+JjiG4I+Sf`nCf`PgK=RK(H*ppti%C&P|U340FUdg$p&q$n*Pvg$J4p$l{gBZ<4XN32$V&i`Mls zmmff^r%l#9z|*%Y+d@b!U;%bv(3q<|?w?#r<}3s8!u26~kYjb_QG@zOeh9>GGM4^| zfs8u8kT{59%nJ%i7-l=?pSXyn7<`uCVp`;H35k~SuiJ()ZMsVf<3Q(CL_hu9`GK3b z*dz{hP((uEm5?cYNH64tBEJ7-IdV8#J3~R_3|7%p*RQxYUIEJLVJ^#Gk^gr-2NCT>U~-nU>^M9Y5tC|{(6(V(yXL~ty(nB;F9<& z4Ff2{Lq69?mAves_S=gTAg^z29@DLFz6dy;t))h6nK1*6gv2PPW7SLR1dYuq@UU@zL)c z5)4mi?22 zV8pLIl0mkuzMLf(3un+C<|lfzNML8Z{V0i4O{ajp9j^o~%YE=|_Y*15LgUv$Rhj&i z?QDBGEj_Gas0DG#xNA-~ozTt9E@ufzA$l$L1A9Kr6d7$8Pct8h$Y(N$Q#)!kJRuxP00Y?Nkd7Dm zvSw$#_J>nJvl5pO`ACc8SArvkRVmR7)OiG3GS7Q+gI3!qA}WA`6HNAcw$B|kjxza$J|^Fo=o`IZ)*LpZak^d2 zsO*3M00RI36FrrN+sHxPlfHdf@1O?i7O5x~&F(RmFjl_y-wz-0SJXmR;^0_fL-FX2 z7uC`&K)d=qt+y!`)gE0aDl1G2y}}B`w!&|twzw8)b!NQA(_)uyt9cAo0RY<0aDWi9X@J3JtIL3Uio-aq>QqJikRH5XRf2rVXORnlp>*aDM41?24UHN2fxEa<|B>7O$iJU6VS7NQL zjo&8w$NxGI4&}{P5RO>tg@obl*W=>0iZ}vdn-+obtlb(P@*Mw$05_MNoV}-==ruCz z+EfJ$DhH!@pq{v*-iSqEu=YnXz(4~+pw9p@rYnUquZibExu}(%r161i_abKh9Kw$6 zFh$xJqai6T?Pa=I9QI`hkp0gEG-J#}idGKNJjrueGTP=oW% zU69F7V1N7$EcYaN|G7Q$#4_1nJRSR72mQpo)9}n+5EUI|DT7Buctd{92=i zs!Q%6(P^|ijM45T`#|Jlu$g|!$4TyG=7c%1F%2O|8V6C)k8lOwHJjpu#SKIP;lDjx zI-R8Lx+Rl7oN!~fwPA!&SrY?r#tA6RA5fC6Kw2VIM3R)K$JB-emM%0@ISJe+>|YL` zAEA5j%i-@Qq9Bvi0LO0nYhY}h8qw1+MX#SRLsL8d!s?rebhAB)vpc)lwE&pWde?Ju zAN;VtuY1`{=LYPo7QI|4%W$DD0E4c%;#Wczki#n0DF5Myx1kHz%yO)fy6QIWvrB~F z`aj<;6@~7se_2MM_X#OpNaNm(^a@9FTLhYsj$;F&(52Bf>qGp)$sl^ruGt&}o-g*Nk?d zxy_r8kw4(=!$?+OEzj^~1wg8m5qd&MmUf%o}_?}a79O31~!?SkGM1dFF1al>MYwp9;Q zR7Kt-ro#S=u*1y2M#Vvdm$p6hDS4g~lK&>d`g9MPOx69^CJxz(5wE!{!Z z)qx<9R6Gq6hubae!+e$@7}={|j5xYSt-yCMwZ*DWGjSJ_RXZwfS?Z ztsz7;*si4$?%`kgqOuIcnm9;Q%yz@x(0&F6%EcJWXg5}>T)!B{C-JRzR1x1wqZu^G zVLVS6K)aHZlBrnkpJwu1x-}hbe+t~t%TjqjY5seEBd|8jJBeO{$jGN zgGcxT{N`hf+0_Ig-j5V6VL+_L8BfDX?f|&Y%Olu@m?A1bt7DSKSadeWKerU+nA%ms zVy!cwvp`I_PSC1?xOX&qyOt{bQB?zTI-EF}^HkN_5fzvIe#xHC_XI#kBbN-F1BTFx zhMM?P5$`tsSbsp9aj-jp^J-B^Qp9T%Tr4Sikz)Tr6Q~w^a~y=K^OAt3mJ;>h zUi(wpp#q3A-L85OP|jtI!*VnTg$%{Ei#=FFk-v1Mp_>VHd6^@dxAZkp?8qm()-*&t zGBuHX+|>ce%?Iw3Jlj&hBdI2lgJzGut>K{4;C!&a$PdmB=sOr zKGtH_JOYl>qW0eEeWbXuUKx6VY)t|+c62PO(Y@$Z#J^AEQ8@2S*k(KBOi=3+O=1ZJ zOE+wq7#n!l^%}6n%-3Bot|;RTrBPO}&M21zN#hy99*Lw)-2|GUxu`z`3R0v^1e#C} zw|gWPRZ3O$fme3--3$xXHPcp^9m(Bu4<%>M@L$pvsF#=Z%cd}tu`C6$*r$AZNeSXX zcMehk_k)StKTDAZG`h=8^wuox7@_Cv+)-s)5(JV-F6 zSYg%CEGQ(CBuBaW;!5)%{8DDW6$nOTTww;tPi|NLf!a&5kOteUfs&h>y=jpmxIZ#l zOSVL48)**2!28olJO#s`8Ru$7PVaS9-4r%Uh#x?1cc*cUnU%<|O?>anyngKi03xu< zZ}ZU}(Cj~i%Ry4}BbDUFNM)Gk2H8e?uaiRo6vIz6Y_neuaHOGfy6m0bR#NO^JrtQ) zRhcR~xHKwdsfXYBJsfNy1K~io9k2&{eZzdcwngyPNN+=ExwHA-%SEhp6PKtSiYG+bqYL-RvePuL5#TZDy<VO{>t7@;k zjleFOORI;o+GI>z*V^ zJXBeX3$SL073B!Dg_cpyuT9Da6`=n05I4syV>jRyKuV6_ScBV4VSah( zlL**FFhN%Fz*sIw7;lyoKy&!~5-f30-y6gc?~%7{BlIH=^VJ{rXTk3L?s= z1cNd;40tEE0sc+rWONOwiilsmRtW*d9*)ii;T1h`MC|CKl&00z4>1hzj~(TFw91eP z_`<^I5Wh&kdi;~Zx+w4>+Jsrc#t7LGi!jL8%0A;meiM3m(#(sSX5{q(?~9P=P__uc zE)64R$2Y(4vren>mIl_9#~DXibY3w>2Dl{*FMq8YS|c+ut|7L)rS+%c)m|{aikH}N zWiCp$-3L(~dkr(U3~t{iYLmI!B^Ts<72G(hT!up0Dis+`^e?lgcYLm6up30n-8&LL zQ__=Jco{sx?$(12zmU_0J`@*mUaV814$uypA8@HrkHmK#fx(w>uo%3e?l^|DpR+=Z z5vs7Ob?hSorU0<_EYi z444iIbDXBx8l#$HHOq%zhC4 zaOo!aO1Xsv_=OBv*T*N9kQfX#h^u&8!#u$}tt+QiS^6=Y;CI7;IjZWkV)E3qYy<^e z>R#ZFJZ6cZ&N1UcYqB)P>vJL58C3`k+k(>Pt9Sy0Ne+POqCML$4Rz81j-dVMZYn4C z$TLwW?$ZnrI@SX{L}DgDp|ndzWS=~KF@*fUD@_5Ol9>vi--+5MzK?Wdg*oc)?nemR zXBfBYLP{X;{j`PYmk_L}$o?on?Gq;&BviC=*~zQvx(KIWBkw?rFUuiUF8zjL=znUNB!XnF7VT0F{UrOSlIYytm@u6b z0009304l%M$iI1d#pGXoCPhJ7@N?F>XpmGl@L!)#lF|}2XyNDXnzahRdqYJq%%?Kh z)RX9|)z73sDVvm~RcRSR3_(L6UrCvSrb-7f2TY;oN$PLSFo5-(zPiERa{$;_v4){% z-rpPd?1<)l+4fWnNji+ctunD8{=LSuA@H$%`Cu0_RB7ApBYi5FkA}VD~TdA0|ZA6Q}xc&}AzjVaha&wbOXk2<|meyCy%##CSJj)yFJ<|os zfHgJwBe`po0Q+GRcAf2}66>Xzi))A`XAp3>I9gQ08ymi0HQwb>qx>4kSkB4K((9A% zGJQx`Y8q`xA_U$SkM73HL|}9vs-D~7TMYFce|`19UBS}nPIzwHv7_nP5~4&oddH8% zLtikX|FiXZt99ui$P7SYRx;)Ex&+#KT2vc`f&B|Q-y5#j__r-d=iioFMz*Yat``Q< zbw|^fjlvoXmSo(!(1abQB!nk%tsS7Wi|mxJ1{q>5CA;LPNg(8AyFFPf8l?5A&CHUb z*zy92q=cWUdMx(KKuU?{`DM1(dgBE5=QnQ;i^snLnyu@jic13QEom7f45Qp3rtAIC zFI{3d=H64w%)kT_gYX+$J~jKZ@mskp0@8+hORc0$7u&P=DA@G947Do8;j>U?`ZQj5 zzUc5Z9+rTV<{#nH5G|$&bsI2N;29veNn@?zIj6uMfNHBssJ)9*?Qn9+B~}U=^^=>s(fP(P z#tB}2#U#$wc}g;bwadQvFep|3Pm8n^3zWlu1F0;N)Z?9hvzG(tpzSeq5;@@ne&^x6 z?RKm?ms9$f8-m1;Phhg>>v2Bt$t2^0rlZGb(b!909(8^nZg%C!(SSU@uR1xXGO(M# zjCd#cgPtKJMd>O}KwfSUaSa~h^MpZ(sk^x|{K!_>_FniYuA2pe!snlO+4jDtA6MUB ziWF@2(EkkdoeCrEOR2>9a8~h><~ZTlv>DDy?&YC95(XvVg&ok(J#!-;gQP4gT}1)hAd`~!AK6lD+yZQL zV<>4DaD+u_=6SugV^G#u5f4X=*F;@#T_xQq;I^N0;1mY?H^|MqDTK;%*T8@Loo*0o zwG;J3gV4nRoFmMbP zJ_l=WNgr-iCd!r}UFk*a@s}H$ro-C6)E5nc<^TW#001H1mRHj743a#ojca{(CS}(d zp5x14Gtuz-DD+V_|M-pIKvGCK#DDo}+^~4qO#*4iJp0WaVHd_#6w(4m)@IF1@v$JY z1DZrV2Oq(f9Oec`N2c{hq~sti!Qs_aL0ZgMua7;frRYnNv|=AgrI{m`Jr>UBfl%4< zv5zKfqAwTG*n|-Di*#L)|u8P7O>Pu)hfy2Xr7yYS&yW{19kUu2po3##^)^hEu zyBuBlJzEfCL1R|BxaC}L{sv#IDyT|lsgV-orF)us)ZWOhTMTCD@a1wJIaJ8_A`J-B zD5AW$l4;k7bxk*hjn>AF%3PZb-bf0D>y7ftG@K(I?s3n?Fsn|SFtVC15KXDDsr4n( z_CTAN+cXRc60Bm|_s9)l_r5r8dWQ*hZ~g*z!2zgXYn!C9NuY4N%6M4cI4V6f^hc#f zzT=P^hpilzM3=T}<@eGf$`P}qislq>2Gq)ZctM$hmWYlhTnm2PQva z=-}9B4_lu_WK6d`Lp+g|kQgIk{5@P43y~?a5Ve>$NS0pJn~j5nDeCBIMz-=n{U>F; zFUQLhpPzmW!8oBUd0meQZUSW(o8e%?{^^WItg5Sd9BBgZ;M{?d4jxT=ymWKUbcuN& zhKmKEAE#q%OL8(Vk;qr)FFA*(>4ZjCnV2TMS0g6%9EqymPZQNK|FfXXN)=8g(gV3f z8Y5sv6;%0kt6QmdeptP@FkuroWHh9I-T!_fGYf53K2oZ+06E)`VWgf!5;RFAneTRV|DBS{c^|kXWE#+tOMh#Ob z1|zVZ+fA0=j~0}NR?y-Tl<5|T8yqdPlojz_&kGisRRtLyeesZ2AeyA`becJiRv_5U zN^)UCda9aObF;`k%^v&2mtzDVirtL{VXJl31Gbey{P}FYsnan-K;Rn1Tv1pIWxPRl z+k(=n%4`1*v+RMO)_^B+M^v$S4EDVUZFqtXojTS=>HOH3a_R+iej{b5=whhi`wNNm z)><7{W2=Wb!|W|2g5$!nzt%rB-7y!4SFr=4i*?J`;K;^K`BqB*(0 zKyIY&%;2{E6`{Nziu5v`32Tez?|y?I9_b`cxe0?H*6=uBBUX&QIWnVVDtK6=M8zzA z!~WAR@w^<-XJF{%Ou7N+I{=_Lmk*R2peH(je>I7OWw1j{47;kG3%}fp;T<$K1_8i) zzi_iV{L%PMdK0~dS)2F$AkCUaxUmk@r8#bm7>^1--GRrE`?pyk>)9oOg0CLPUUZa( z%@cAXCVZ2=1-F>cuk@7;gPO(M*KG9`W6)t)kUrD>(fvNDyVB??M?$LoZZpuy%wh-} z*~mzkX?}X;T}zD_p*bL~7~;rcAP8`vRA0PGCcZOG(TpL?Plv2Xr0bVhIO5iZN+**; z<4vP^doS?)0D(fNL@{+~oU;W!u>qE+pSr=?{h9wJ20Z)?86KI0!+7$78{lo`#vCF6%6GQ>4ns;|nak?n51 zAzYF8D9<3S2BkW|OU*=PNJ~5jk$69{zd17kw^+Of9<$dt5($!V>F51|ZISWdS25*B zSi*$2*!%|dbpl?2SBFcu5sX8M#=$(8!ZI|g8~Cvr>Y%--FL_Z#;jCnJ+Xm*q%^Co1 z;J`zFA2l5ZXG@F}S@+y31btW(0009300RJX-s(yE+x33rLI1}`lhqm%%1y^VhEBQ! zagkGwDyI7QRdJ}y_|za4Q=7yrqV77DDn5*nInp)G411$xGx8lv-J0K*)T3t|N^Ix-SzCdXn>Rr&4=igc*YXs-?;N0 zxVy>Rl*A@2IpaguP<; z{FujCn7jG94d#lXVGYYLkWG8q(7r`oX3_nwWP(BGXb=u#^+F}7P8qY}-J8)&HV^E4 z!0qhK5X1b(Ph7+m&GitRVFO>AuGA|p)4VV;A}oD#%$W87(+>~p^GJxqy|`#xQ0e@k z-sCVkpeTYz+g!hD*M6t{+Oq*KqAtZ{v`j(~)ESN|)?$U3uPxxG^L+f;gMk6lO{BxR zPb4V6K*_W?^hX?Cg9pygKDEm2LZ>PtggDm~?6uzw9=WIO|B#blOJAOSyA@r(8AC=H z?&a&~CKj6)PhRfM+Y;wwnp1aFVg=-tqol*56*96InxPx9h?T~z$hpr;b5@H$oM8nn zdK+ydGAQ)tw-=l>i}iVbKho{bM5*(_$_jKaMv5MUZ?+0N0tCSG5bNl;Es+z73EfgG zcTB+N+e0^;5&l4Q<8yLaD~~>rMjzCmxO{?wBc0JvX%|8){2@G&< zUx{+}ee`OZj`%FiR=@04y*EAc#I zhzygr+f?O-?T&0psYz0c>`6)E+oNm4+S2wpaN~h`aZ-ZkvaY>UPzzvQ#9*H^!-x zCCct_7QFvt;FkOgl!<$M1}4-;ZC&o?SIl+4*ufNL*vD1Vm>MQc#B|&rBWSR5CqK$MHgb!!WykLAeXfVn~Eo<&2_>OUWeSJAv zhi4?UxslN%KI(?a4N8l~eG&5OKD12BdjnoyTD1K)#^%h?+*Ms%cq`E7#ZcFYUP&ZU z8LfUqwot)_6Dpk*(#NE4r!QQG6n^!wMyGtAO7QwNFFVuTTx%S7TB17~3W)UvWY!XyJHS5=IlE%AkuflQMUpT2dxOg07 zf%q%a!wysVK-;x+m|Hp#Y6#1IPfg>P?7|<%r4gASxN{BSDPTY6Mu!$&+YABL53uU@ z%OO>W!~~(uGLUgNTesy^uUZC_$Q8UPMSFe4ttI25FL7Of8cK|v;XKqN_14zA>SN`$ zE=nP6`!`!XGFW&+fIpio3Lv zVx`dhQp)cK6f^Kkm4kxUmt3zu|4(RclcD$V9_l7L;#7e%ySBQaV~VG;s0}jSFW*(Y z2D(YQ#wDHrZTww?XkqA)eg^8l^O`cB=XOkoJq~fbfi|_z%I!6(lT4|<$WD{c!jol@ z5#-k6oifOezW5U7z<0$(=%%D1A2D?jjO}DDjV{C#9P^|+<=5!`nYs-)bZAs*!RXntF66hLOgrZgnlFO9m*A^Owr z<6Qji>)BT$XF7%zBQz+Xh;5Ty>I5W(xCa}4PXDiC62Q1Kion!bcb7xzpG<0~U?TfkREx_{1fJKgN^i6tr?rmcwbYdAJgN|#q< zY5ym)R(%A{7az+*FqF+8%?M*5joKbOb%YWXM;#3DizQcZcJkoPI$%0xNIH@q=C z3kTG%abAYG{5cyxHA-af>-HB1`k0&(n@OJ_gS1k_!S8AZ919FPq?Y3FJsn0H4GL;(7cS-3=VR+m{tGa*H`ttc9x z>w23`Se(XqIAb~f?qY3g+;1*DR==$U;_Qp3sy*n3(R2rDHW6)b80gyE9NPg4P>9d) z4DiPa_+_2D4(&yLSFV9#L{Ieyb50a4e%odsOSazv;s)VkyjJHA#A8S+gw3P^kB6CO z(629iXnD7a&0tMaQb5M&HIVYPLj3Pi zVP;2td&e$$ks^JNac&i`M|NYglq+^I)AfTAQ|&}0Xj>0ZhntEjaos@(uL8^tRxsd8 zYhd=+ZX(&jyEdkdSamFB|3?emjqmp6d>S&8*cvdR5M8i9@O9|}E6%UBOi&nv_B=y0 zk4mt^BXtv{SKKf`oz%Wn{>Yr%38gJ4vt<;z zUDH?7$ERJhBt&)QNWvM0WcksFW27J6a$3kbTvwns3)HskT-PYt=)pUUg zfb3YoTg%4DLPoCsq--VD{9^%0{g9j#1)-Ps2>{QDVk}aAkBymH>S}SzA`4dJ2 zzt>9WtLw|Vq(me_{j2=MC~&sZe)pI9r<^@7KjmcDb0H9pDy!1)^L%*&##j_h<#RY< zr0=KVM|GL~9H&OEhJH&Xejmz*QeQQ=%|ZeW=I$?T_#VjTU zi#g)(o68m^X@mChQVn2Mfy%aK(TTel3@q!fpDM_GFj=Y|gI`|c5FRqy z9_VtmC}bj{fA+GcT^rw(gC|OW2c$?|2EV^Ewz9>RIBcz#yd(%D@DfSp?>x5t=f-6LB!hCo|GqPQN#mLLc!FSKw3gU6{n6ptVOf?S7xoF8mr z@9ECivHJnl-CIlz2B6&yj+g|q1}iZ20T-!vfB>gh|~RZrK^I*iHII%cS-qmep)N1sa+BM?}H8% zaJ}1yU@`Hn$e?RPBZHB$7U2rUintHj}mFE3qE%|0NyOg9mnegFFJrJJ!|~l_6TOu~C2??ruYB4`ycMEP-8D z$5r(@qBrlFbwlPwXQVRc_8KM1YU#+&6;#5N3XKh?aC|O|E?O>RPj>Zgzk`DZ_;XR? zTzXCKSRPxyV6s+ilD7c#PYfkUv%b^sr8OJQIt&P^B^X8`r1%~CJ$xh@fo5IZo^yrYXp)Yw^{k54rtk_mOnrhgm6% zzw(Z(hGS52@43q!Ps~qskYqpHluvcR@%bH`Jd`aufu74`b_XRtq!>foilBH#Ss1B| zrjAeKvo_G6m)w6wAU8|&1Z?scOMH}b8ReL4Z_cTzsHN8`IZ7?TQ+AR%PD^=D((pIp z70B?j#Yf2vVByrW3+Z{d*5kV9(PRm-xsq;D&jgISGXFpu9x5g0)^tOGMQJ~g!*#3| zx=bqU6q=_ffgin;dEt|ukQR04h_#Yh&hhcyhWa0MI#?xx>zY^2J9fT%+PSf|w@~yg zS;I`qk8q^><;iG-0iN_63DzOs`T*46L_X5-Ay=i-$uPmw_OG(SxP-ku4%ogb@|Dwz z^5o&wmIglzIqi$5ZJY@(zHGn`FycN+y>2$9cu6#|@t^%a4uJi}@XY6Z>u4Y`<+bd~ zDjERFm}zJ0nhW*i<#1>RtZnH z+T*j8U8K~l!n?fEDa7U&nU?MsC5qy9-O|dWW*VC-!6P3ycbyW==4}yn)ymwQy(H+O z`x(nEZ3g_kRL%g?s}CO>=YC}Tk~EuRMS<_=$nq7wTuWlH7p8TQY*qs|rm(Uqov3`X%qLmvz z6NcJxydAQ3H=#Y2gB=U&$@|gIUwYylhO{0e4RF)RogdNQ@wWntB3uF}pmfSPdEj1z znFvOH@EJ%VO(;DrVKJQ6=)YMRGqVx>Gxe5Ac;0eZmNb4n%DzSkHSGQDug?c7iDLTS zwgT&A!nY3pUP-*&p+s6DRhTjL@yE4S$|nv7%C%}~aL4{yuSUwzqmsp;V&Uk=@_udu=_@*vHF4SQQ&d_ohD(`>sIwgJtalwBd5?jBP|sXW zOrwi5n&>d$-*U|ox~xkL^`(K^erpT&l)wV$@6k}D>gWY4Q_8!ZRO+#nWC7BLnu5wi zJsX05fa8K30k`SeR41?B{HS4{}YRf6&iOH^Um*Jp z_ZE6xDp(VatXKoMhJf7|uX>xn=1@v#qp1g(uq^!tNS^M?6kjdFKT2?%rTGmTS=ESV zHJh-+^LLibJqy^~Wavg^k-a_C?JrI&nwU^39eGY_Znk~EE7f)tKJA6Rb<~R!pig1U zgk@JW=PcaLk*Q-{C2Xyh`=_d{o2Ml+y7?juTE(E8Hetc%BJDg_tdDm4NoB+#BS>K# zcCHR{UcFDctbtqGl4EbC$4RsSW~xljLv#=iWj4eWng@)9?WSatu!1La$E&=)dGcKF z3XaW@JCBBCkDLnCgq2~yF5h*winSk}SDW~swxjy|Jb+I z%*DtCzyJUP000Hp-Kl4Qz3NvM$UpsWA=Aq7n}SU}{NXWIe&WF_@?WlqfxnWkF&!kO zj8rwA1e&KsNMUz+o%QOWsW5k6yk}U5PmTrD8_5bL}tSxwcz7nL< z#w)8RabBOMsa)hwZngH-Bd`j9Wn73xDKrYy8eYnzbHa>*K2D0%UqSmIx)pj{%UPUF zpMO2A7%lU5UYK|HPJJ+6@+!ze=PZ(8qZE6?u}sK9Af@ohnHJN!5en2P3R}D8wVQCC zD13^{XKwES)dSQygTv?P4Yz#ZV#VKR`}2hWvjQ5nY;l}%fuXr3E z6vksaUAdPm6+fG0QiQ0#p73u#wS!oaUiXF>e=ZtyLR%2GbWcfUV!l@xK24R-+9Z;Y zCTfV@2RT>~o7WIbrodmkS~AjvaPv~3aCWNJzny@IhT!OvxEw8FkCs+vPpIx%b1B7_4=kxB}|eq!Jr_jdT?*p1AYL~nrL70kmD zb)O$6ZWa@s4#*m!*D?dn*iL0`M|YB-=A?AwqEF%`LDrwr7}c`Ym5^KO)7Zj7a}Y;4 zGS;A+Lzam=S>E06!sEnuJ?mlD}W?z6X>@{wUhzd_5h)D-G-F@AG{z65)Mn(qU z$IQtit$IQ?bfJvVlbxvo5@bUt%}kD1g;Ue^o{k~`&HVo>Q@3>TlF{gJYC8JbbF#Oy zuQGn0GjGjEouQ}m;}d(7uMVnzQ8a*N(~#t=VHQg<6EA9xQa2+5URIK7(&nPzf55;S zzh`ll3i@Jb41p_=?NT3^Wz5F9X(G2d;LV z6-axU>`0`fZ8gE@rq4snDqQxUtfT-s+HX=vZyE)HWsicD>NCz2Xr(t?E^<~S2VBmi zjG?AWdt;@Q_>lwNeq96?z3Bf$rr3CBbd5ijz21sPLktP?u?AaPcJlkRI2q$Xe2g>| z5d@zDjCHMJ*f0e7R8d8@!YQ2v=nBzSE02xFq60e9AB=3=suauQ^2*<%excEm)Yz}* z-v9(D<>2%B%QQ^@1K8u#sa?~jz~@wCrhgcRs#QCN%W;6P?xyFRch+53eU|LNJY&Ks zbr*N4zKrUyj~RF8=Cn1vyN{jaw)SPPS(^7im;O0RT0%z+g8SqcU;qFE00093026YC z?fHJnX4)>u@;CT-!oESWE*Z81c?4DzK`vW<1pMe#D7}nJcei~ZaCRv$YPPGe)Hu46 z3!Ncd={3w#QmwINv14Muk$+iWr)3pf(UZdgCI^QwaRl+!)%6pql+Ws7i=@S8_!x@H zZg8pISlRE3Sq5Uyfqa=83%HDTg;Gxc0&F5VFU+Fv1Y(#w-{cXt2lioR%)yWo|1nFKh+&SDm-Gu|85Z@TqQQ_8p7&1Z;)IIjUVoi)cf5l@jc~mHSaO zEhG&~ATvBVZ6T@#kNn#pkY;UYngz`+@R5MXbV?6-O$YsRP|5g7+ZX|Yg`vo>MGec zhZr~HNH?J6QC_UvaRL&|ynE2R35&xdS<>qe^J54~Gn`QN>d-Xyg-}QJ26pvlb3lw^ z=-rZ)aX9>;)AdZ>F(_Ex+!+B;lk4UnWi_YqK;oC(n++Ml{iaHk#(DEZPSYax{y)u^ zvqVmS3@ce{8!d!nX5Pp0(5mzy5cnWts1{*WcXr}ZU_wX%HPI1x?ie$$bnjAi3;v`X z-p)QJ82hC04cP{ZmG`$(NSV-@Wr5A@j_dRkbYM6}bEQ>JhGs~6vt^_&-LsPC{w9VE zA@TYHJya>TI{O`07IIX6;Ctl&&0nEqgf!nh8QTuxk}!j^$ThiLSvuzH;3DGiygC}} zTyKqd!|~~DS2EZlwgurbAohQKbr~2Q!*yt`_{`QHCfdRF1Ti&x4$Qe)ov!>W!kn$- zS7Gqrl9)Ep*)d5|wYcQOAc)6WF$q`LJ0?F&WvvCqs7Um~o0lfc^oceQz^geY*rTf7 zqlWS%3Fo+lWK_wl`n_>Kvg|v-QQ2iG0};@O)`YD$=CY<30Le?F`?94K*AeCExdydS zMC5fV(=SNZ{~8{?3N>SEqKH7jaQRz4Cs>IQN4^&!64D~>KZ|j_U8zNP!lrM-cZGk% zn;9AA%E-T*Fk)<$e2oy1dmWrO^U7BP*AHwpBI`kyE_cCgvWeLEvA<1?rg&IoU(Vl? zjiZL@)F=%K%w-yiWwQDKM|{R3Iu@1JhJ0*_2A8srf+VDH zmvQsE)D{`9M~U!?Dlb%a=L0l5kWh%`{*ZcN3V+f)XRUVDnF|D5c?2F|$ai==Q$M3N zwd5&l1?=J-%>`B44sZo-U;qFE000EsfhOeT=A?4?qzk)fP|*T^I3KB1K^D?7DPu91 z-E^WiyruDCvuK&nGq>1zdMyo>^U}3Y*aQI+AWmyO@;-PsCzK1<&Xd769U}d!e{je4 z^ywRfUKh59Cpx|)@-;>O$y30~vMB$H|p2~W#P7~>6 z24K}<6aa)(s83(b?6GtvpIWg52*5!3JooOSTg>gr2MJL0h+~OpMrsmM0vyyOOex_=RC?R<2qf|WP|EaL(CQ-?IZ{{kfafnZ7zJG?b zAHr?N^Vtj-O@@lbUJy*JZKmWRlD9zmb*VHjg)S?dg2|d3wmagOJ-o9hmBnq+-|QCW zv`sq#|1{4xuee_GZ(Gp&Pam=eX@_c(%Ma<^0><{7Qe&PAa#n?NDdQXNv?Vqur=bb( z=HWMjJxt~7UBJcNr{ZR0S}=2V8N-6xR0CJQImonj&9Dq)b?sbw>rf=x^_c=28UCFi zXic{Tq^tvj+eQu`KeJAq<$d3^C~Mp+@e- ztvfZZLSklV{(%|tBwBSIPSp7~RN2XhHvl~ZW^fQJv_{SPs{ASMidhjlcop_|*B*P0 z@a@)NV>Afja6k-g0z?SOEylJM4m#;BxBxe3mhVf(GbEimnN_NWLuwbme_j(4iu*K7 z`T+cry;8E&f!`Q6SK^ zhb>`bCVq6IaRh)+?)VpcMPSbg3q^HF2J@rD#itog@|vc)g?pFLGgx&r=YX8SWgB}8 z@<@NyP9NliB;%8pH}#YtRDsy9OBw9(HhN7v9HlVNm~Pl zuV^PaT$tlCMc7hJr*Da@>N-U#!Zy~OaY(3^wI?_GDnkfi6QEl1aMK2=Tb z|9+y~ZrvT5SXu_Dwi zxoHKIDD`L~(zzxxN!!Hn@|M_OvvP;icIVb}@Iq($Yo9n4UZQc+7_6p_g7)U&n>D~Y zd`=C3`;!a@K{Jy$UdU(g`>;2Nn|58)M)yZc9fCvId`LWO0BQgL0{{R*<*C8%xXU5D zBF4W_n*RYmCaj zf1#EFXq~&y@Q#|Y#4=a-2V0K|8*^2ae5VJk?Dp3w=RL_>y@EcsZUBFJZC_1-Z;CY{ zalOY6*gFg{_=nhqq)jP+7O&rRsEO?maTT^& zaulnI8S7-m7ln3(j9oAtxbS5b3=+}XaZpr+&mOlBkEF#K?jYTGl}@y=b#9OVLJvxOK5=9FtL%aOjBulFxqgVDIx@C5Ibw(UFzQuO4) za!q`I#FcCj0YrKxzCC~dolEsI<3Hyc1)8XFzL^PZ5Se~VGX59In zUwA@ti^w2_&P#(V0nCJ65fKl>IJFT7`@bQ+BcTH1EWh`C&Sz~7vm!Z>?^T={5~Lia z)lsga7TS``pGV?0@)C0GR)~1f`Nh83TBd%i*Sa-~6m}})_#9oQxXu{%vES+?3`(Nw z9cLL;D&(>;Z5GYZI7rd&K6R`}(7oWPDSPr$vw%K{RW1%6wT& z0>Vz7ZDp(0P_wMZbJM~k*6JI9{u9lhQ`gn`iycWNvL)OhKhZi2Yi;ITr33USzcYrT z7d+{c7Vlt&gW9u~^EXCP>v5tJv6!>s+g}}*ncc0jKTD-&NQ0?T-Z+%TbEkeYRauxn zhjZ#Ww#QOVl;gmlM?Kmqzn*gOA|0KAkJo4xrEW8E%Q%QP@NQ|{D;gQbZ|>?JFJ@p; znRFJW6{;9t_vS-4)xGO);daf~rYyMXREFEWrsVCj#GLh|`@@NX%=Qv2JlqJ5J>Q3e zPvz{;LRaT+;`L7@?=u=cjKd_OgOg}Z+_Ba*1*XqT+C63m5Y5sQIqC6@Q~&@200Gna z&kilx2~H!53?0`Hl8jjsa8Lbj^AdA(&=566sN{~NlcyJAj1Y=>YelBz`w zc2E9A58{ci-zHr=x({EuB*XF?9UCIRp2x~vFv2vFma=13mP~_f9GV4kR`vJTwe2Uk z^kB4pBX$N%QGwGeDx+04S6yy?iQ~k3hhHF_A2N*IT%x9DnqQ577KHW5=umRP!_om$ z3;*D~$0`;-#%2!FBlm$%fs3iom*e=njmRO>hg6o&oRX_xQE>a-Khl$Q;Rh{=`{&2J zN6`|q7V#Z$jIvWa)OIomrcih-&*K6r#GYVZ$v-&QIIPe`ko5z~bi_f4V9)=M;GmB3qr~9yd&%6OkcJlAG3Nkl?1nL@rk;)0#(PBAFus_ zz7SJB5$vRy0LS}W3PA~#>~|%ztiu3PJ_T_oDESHv9Jv=~(5}2f=wE<$jK(F(rdW|h z<5O<%2_<~?zo}2IF5!J!-knpmsauRXxD=qs88gVx4#`a6VfL^Im2!3cL1Nu=PG!0@ z6m5D@r~)8Jh~M$rSdr!-EVy>znOw7im)o1iS25qBkT$C&XFMlTX^|h8M&n|*u#M|E z3dJ72OqQn815(HS;($Bmi)pk7B8~Uj@Bt&abv9z(h@h6@Hd55q{yB{zW=$h1xXXq~ z6Ux0diZjy<{No?!JYQ zjmFh)+b_qaTXGL*>tj1ApVtawk8t4wk{2tn64et+9{`J@g?V)`{2>f5n?Ik*&dQLQ zYEJhk2lJaA56^Vr`<)PyGtK*dcW@&>Uh48cPmB>1hk@5Kfc|i_63ds%)u%exeE~fC zyX%qtqBr<^4NYT`xJfmbMyd%n7Xx`MR1F9`c!K>4ZfbW8r=Rkop_I-lzZqbpDl25( z>)^|5cvz&FA&gs!%pmm$Z-o>)0qz~2w7M3hgc-WGt3$J0k%PbV3O%u;wZV9?F;>@b zyRRBKd9Q==@(DuckT$$eu#)V+R3~o3b2*eUAWc6rv0yDcw>Bk)Z;MVrq_vtkf|X3$ z@H-!s0sg1O&Ye9GqI=MRTIL%Y^)jsbsX%oaYrP`*9Oj^Xl2sXjKD+QYct0qiVr#%2 zG#Ag9Slt^W`6~5J+%jZ7Qck8g3<6K4cCPJ8)EWLTD0BJ-U>pgTcU-x2yAva3FXrX% ze4vThH$Fa<^$QlGbGu>!+U!Q!HWS&*p8>q z5Le3>#db=RoTvZJ27gd?PW^T~3YUbP1^jx5HV-497m0YN5t|a)8w$<$j4Y`ErWuox41c|k7%lL(H-dr5#3aB2#2WeKgjB`9|h(|J_WT6G%c$a!>TxPW==zac77 zRpX_~1W?qIT+sV*!R4$E@vJgHTS{hZWf!K!4Zs1-hXsX z4S4*f>4|^c*gleHtEsPixh3z>o+#TLuSA*mE)~e^*E(D^{tOtFE4#v-T0Hc% zBGPa}qw-pI#yvKiC&O+|L4MV%r^Mg<<-$$xAJbS$WX2IXOLYCD$=T;c#mE00Xjks^^fZ)Z?9)5zrX8{_-;)HyRuKTQfVj!g?IFOK%@#y*%M2&x>efOov#{97g!4XSIKOH!L0009302X)X zAcnGk=y4t8Q;2KJxkd-I>cY2}`VTrE2N%)jiHnc@e-1odmr=?%8Z{iO16F9ut2<1` z_mAShUG>j=Au2@(XXZqBz{NXWod1eBL+D8*H?wRSig2&dR93^n>e0GBev>G zbMbBXWO6=(=!qB{PMB$6QJc$cMIKt2^o{obCxYePJgnCMldf)fj#GCsSp*Gpefb@) zO0-SM&fJfqLN2*j_a9iHOU%*vf?Za1Y%IaRU!wWz2t7g-uGxZYm6m#XcNH?M9Mr0T zDt@CfuCltH&!*t>v;Hcy0-}O*n7;s@^no`1O#RbEiD}Zg)|QzWFf!9F=Wb_+AOliK z_mQ=&+@h?4`-6l;i^lv&^*1mcJzDXR5XRDnc4gf(1^*E$>i8$tFarsU{G~JYeL{o- z^%kA}>ysaOqesY;*pR9cah|9^H)m_y?r#J}^9>!<>KTYXi}cfS>Otr2N&E9 zLOerjVTT6>dF`7A)Zh{)I&yu_yT*ruAm~OVY?h})>Lp`Jg#f|~%iB_+lyGb9Gbh}o zM}zIn$Q!5W7|WB{fr@N9**UVQD5=(lCAcfC<1NZ)vHXJ@_+TAc@<%49ya*}RLu1pz z#LW)dDd7Ya2pX=FGsFk70BT3f2OFd(I;o(@cUYB&PYbI>4|@P;U8uD zT8lS#%Y5pG0-F|i2Og%Hbqa{23Z4xBbmr!tn-P;QDC&@Cc{nYT4!ynIK=*h$)+gq% z-ZYkQ=oX0?^KT*+7(e$U!1xyCX8$`v+laULSdUSYO#Fq195u1e3sKwJ;Al9@r|XNF zn4kiZ()EbbW4sTj?YlFdjJaw9O!T_{+q<72pD-iiyw3f&ow9ZujjkdlM4Zu>i;$sN zyW7GU7VZ{V>9dL;_lom&eeRrX>BB5XwCCg?*F5901fYoo@OEjEH5AItLc8Mmq69IZ zH)E;yVBvx`gV4d>x*B4~-I|}r3oYB^s1Nu00RR@8eb+DSjx@A zUf}!o9lwT{1?1Y|xvFlLfJg5nbdbFe>cg)^hEo3%(#lx4m^j2b7{o9 z$vr)M_*P=Z$k3OR)JUG{RYAe2s&vA=a|d|ye%_mTtJ-+PTV=}Sp2fv&WE};YMe-@K z=`Y8y?AzR~+($a^^cX`O_cEp}nS5ZM%Ro^#lTF$;iKi*{%PjwM#J5HlN> zY1m;{DQp_}7}2H7pW_rfKuI$sXypU1yF}-6L#;fgjzj z^{lab;GD;?JBmsq_q(d1F}t$(cM9gaK!>zc@BlPVcQ1M5{JgjWHWlf zcc#1tyrI4E2C*kQD_^hpde#jcsvLLvQ`BqXIMJ>AAcWE$kIhR^d{ds`!WU|`0}08Z+7?Po12ZXn z3?R{h6CTj_a$DY}cvqbr24izq1%ER+IE=wAw^do10Iv^3G3yHUd`&_v=I80yJ)e!8 zmcNXLaGcRB#r)o{^eg0$K%DdIDmOnk^E^3quiul);>DL9~$@90Pt4T>@WX?|G`-_00 zs!*7D>E=Q%=(Rk%Tcyssqp$!li1<9{@dW0MD229Iw|WA;nhR?F$f}_S9+zq%qq~g< z8GH}|_#L@&Wdgus;?NwpcS(3*9CEvYzz@98%b!o%pp!6h)(2`IFkhRWN$uvOPTSvO z@#H6u0MM{X#48g1QeaD%8BTvP2;ox`}edUMqsGuV=Q4N|TZ?_|QE8chH z)DFYA(6sV?P*Xmd-;YSru2s@bH*kPENtq;b0`{>~ z4I5ca++z4CxvXo<=RE_*@YPC4UodwRCjTtyH58@CLX`s5!Mh}F17JWF)FE>agS8~f zKlGJ2qd&@@ak_UR_sMe>9opq>k)IJ*AMu- z^jTF0@OM9+Exxod@zHz^EqMc;UEix#2CN+~Z@bQQm~}1T7q;t8(&lytH0Pc>X6B|* z1d2CJSZCH>bOPc400RI30{{Vi7voGHCd8b>vczKAWg%fZ#vvxWMsB1i*d-SD7 z(HC3?oZD7Pg$lmPR4U(*Zp~!g?rW5P>0t0rs(L@WY`fs)@OF(@z3BX;$%=OH68wR^ z9glLx9PkIxmdqt-XAyov1CK}o(L2xQBZsWFGoBO|OF~|z?RWLc{J|u%&XwPu8SBTB z`U}(UjRKU!7#L`_A>|)O0-WljF>_CMd98H zg1+F=6rj3EvSkM5MUimAxOY^z#K)Qu<VUg@`H6D)o?-P3vMZBKr@|ol;W>rIKR%-5~R}yFX zEv7y$1``hRszwpN;9B2G*1FCN%%SDSDVNrzkX@Sy*U0jyH&mlMs z!Gm)sZAS4!niB`!{*?gnGQt}KNtJsZ`-C7kI`M?;Q+LS_=Kf_3M_w6SC!1X^4H}9O zgjPTa1eMN*mFvIjJU|ni`TNs7u0f-%I8`S$2z6VhfttsBw*1Py{1UHIeFO25!V2wx z*nYeCkLtK39z8yarQD_V>ZTmdp%p(u`fq;rWsIW@(T6OETn%W%^`NFeE;WhDZT;e9 zhDJ(uV+JCMiA-*Y<4hSLe(lKQg8vzS{-b2L3UNuM2=iP$^^E?FMYLQ?!Yk+? zMU@S=0UHzGw*UvPKEf}qC6C|Ip3)Zwj`_Vap5I@Ana6*|TsBd&i*aWn7z(Wn-3q7! zYP1{cMi&JOAxqd-)m>Z50=3oKYL7XZRu#jULd$rZgO+Uqyq(Hy-$Y>sko5Yiw*OGxRI^BE z-9iUE62Iw!*giK?*ZTJMRqN>@o)Y_znrHdZx>3(^9UaKX3@wOjQ69JTh=2e90|Fn_ z;1vvSM6pgp000931#k9^2eb0GO_z_~Lr~ASmXBXFMk&+I$@&!q1fR5&#i^^jFq(>4 zTbAp;3U7(p{Ny(WOljrKSuey;Z^I< z`_YlqDfs_MjigoowO@#iB^Rhpbgq7r*+?9-5S3-V(+S(_izhPq^8U7cy*oY_GzzGn z4{|xH=)=t*h`8Ve|%?gYnq5-B#?Hixt*N8kir1C9d(z)y3} zw_ACz7c2o)iJy(c5eowIaAa3BgnjtM#Qo!VA+;j;4f1@j6}$10!i{4)WBjS^sAQsy zycDDhRZTtUam>NUm?l3`MAU84&2a%lj49XffiS!i?udW~Rc=P@ zxvgiht$x0tVsafxk2;!?w46cSFJ)OHAum;5eT41AyPpD!idO6|0aq1?IgblpgbbtD z^OrT+ZY?58^PmKQnX2BK%cb<+b$Y=6D3SFPdWy`uWV@PLs!%xE#c$kCv1K_HB~fXM zecsfTQNFj8n|`nkLC{3Hf$Y+ZaRX1;!GGpDaj)TUJG^lCge#+0CaJ^}1%F1QY; zzj|gQ-UK+XcqcRmR!SzV8GRW-{ejqiv*2rK>3!3S6eMZE!5NtSwo_mg2c035UM}K< ztM(k0V22>|`ZD2^^9%3 zET~DJ_Iq~;3agpu3A^=EzdGtq$(qL?gH$oY<3g0JWn7377TbZ5u5M)RK7z*}gsgur0_C9j=uK|ME)4j&gT)HG=y>_ey28 zbXW~5XHrfFBe=AotYzT;g>gKTN@8w={0}zis%@zE)qKX01UYRnGOTI%h@QUZTxNu< z2~F_1r(8$$^lE1DFmYL%fHl!^4~kr46h)avh4}dk|5Kn=2`a4i<) zn(m$v!N3D_zQ2W@#1?R1r@rTO+hZ3A#tcQ25CkC*Nzp|UhLjq2G@=TCTu`;JrBJw` z(U9r`(ZJeY5n-)M{iK7apa=fOum$%08v$yNb14L386On(z-_^O7a_yKO0)bvx8#dI z&@1zuw4zaYSMy0OBFAJMw6CtQU%moiqsN=eng(ALkM$mJ2F|)YSblEHQR#B^4J=Zr zzO|sr;QIUhBxz`BQ4+t-DpsnMI+a2lfSM%4q zBa;dA)B@DCZ5HwpudTTUZ_4QHEPvU>fc)u)G7z@|X<3DC`l|&eyDIi>{!60N_5?`H zPG|IIfx75k-%jGfmJ9eG;E%b~cSG(1m~S{GgOWzb%QV_ZNRw&!OyXk!-YR(vx@*d; zMU=8kP9T<^0$72WWJ0wg_ySNCajWf(RL?CdHMmdu3Q7B z()t_Q)>`v%fewlkw6t(S&buvJ!5P15pFJ~@Wo&qHWbCu*zugH4e|A48qlwT@1q=X>ZB>oJpcd$ z000931T(-b#~655d7`{Dm-f=?>NG~n?q`|$l9!m%nAA!dM%0EkeeDceqqP6k4mM&% z1qNF~$e>}KFA6#v9{!vyiwJXoo=E9;?G%P=27#2}`|l%+3jmF6;{OruCuh)NR&3h$ zp;(i3!4R4?gO*xTy%b1WMF6~c}H;(I%r3E~6H~DrngKWM?-E?2hgXlbr z3S5Jgo-`j+IS$B**LnElkNu09ON2poi#a>)M68KXTG97kV@?*UZj3O59W72Hzi0Nl zk&+6ypY5mbP?M7Hrd^0k+aw%?^eh_|Qd`*-px?E^hpzu%0d_P%)u-SX_lSooDnf6m z(c9ovJ8qBKIRq&&4Lr#vT{!;DT5a8>wAMK63k1w6c46+PWdYB?Is(NF?t`U!S9WXl zvUn_>9lw*w?!_jsO`GFuhhO~j2WmX<)=oCW#xt!PVB{%r`5albtK%LsyWubfk&jdK4)9?{?0Rs&AA){HqB*XtC7 zqDH-uN41oYO>6c}p8ANoL^nzMw=PF(=T59kchY^S)&CyAGY(zJ=Eh)_8C7t=%v)4w zx{2T~2!mQ1a+Vm=ryX4V{pq0Cmv*~WL-xd0$-PiR@=m=@Mn*R9cTJ;;T&~;7Ii7WH zio+#G&03WuG3`gUBhc+dz9TL_<^jTOZM{md4&**yh=5q=!@y zmq&ery#b}G*XdsSGudRvSN5>R5Bkmmanq>_KFf-dv8 zicpEgr@QoIG0*=REBT(uj{8aglxaS5eVgyxy5+5zcHZ$5gb!Ir1_EG1ZAPZ$Y>I!M z^4D7A%)da&@JUjJu#P1i$$il%UIO3BCqzUNe$SFLMOo+8NzEZLk6p&&TT8d6!~eyL z)Z6z3zyJUP000930fL6S^D$SMEdVI>Wx@E$K0Z!fN5bdS)V0PPC942TMvUS+oEujq zh`l{F5(EY-6GZ(!dMrDnK9*tV?Es*YES+Q@QiOl}3|vNCMN#%H(H@nYgnU;&V`d8w za~2s+{Nx-8$>ao$QBKQY%2Ircm$`bh1LUV#JP~fk?}>noYtxp1Qqj383~X7m4!;(4 z5HtByE06P{PPngRsLg99;sHl95I(Z>HofN^?gs==h$p|M(SMiHWz~CHsiU}){Vn}= z&F@iSV^-LKcdWX*52qXe?)Z^r#LE0xFU$X%%MG<=%``|04_4A$!%P@*9>cAhDBCYCgwGDK9=*2}JIgKN8%HOEy4j^k@f zSmDGhHlIjES1HhK74oAPC&z8WyxCrm`d01efR5Mtwo2-5R?E)kStky; z8$@@%-qa_o6X~g^+MHSTWlY|z&Z!g5u*q-gSQLTXTT1ue>r%REXr|Z{i4)Xbp#*+# z0hQr{=*^kWRKPYV^f5ZWqc(Yk1(0G$EytF596=AOG4O2GWE&=R4=>+%C1BHTd1q*^ zSlV+c{UqckI!EDwf?vNQcMf-mL?!II=aQVZUG=BqaN1DAXjdRbPriN zZnpHS$g6!wWrmJaX%z~+!AyE&FN5ddCczL-yx8ME!Rh-97~?SZ)EbYu<$NkU+OZ$C zv5~z1TLEV--{c=Q#^-uL`aLYv)^FgQ#<9Ng(#2GQcGw?-qlI~I{Dc*45hb3LshNE{ zlZAl_a>CycMbYtP7U~x7bAwJCnAetgb%j0}tury?+jf8L&SH*gPhD z=FyMii-~Rv`CQ3=0-qV7%UmyM`vu|~GGkzMv|#zV`kY|2JnldO9a(^ z=APNY8YA##+dGE_W>Tar%n$cbw5dZ7|MuWCA;M`ujun9R-^oUwW+FC{8|?mbrh+{7 z*R0ChZ!tbwOWqIzF2{jMJ;=z#;8b057rVP@g2v_rXSN?eOKwEwP&M(Ny2ukuFvp~L zqBT5&{B2Anx_Q*2`1@f4e8Qr&C3wMR5_Vzl%g5JU8BZtc?US~uvE}6;!HZKk=6Ifb z#{eLiBceRj^QMjbqwJf)mf{^QntPP*L?X{BmOOgst^ySAr<-f=I6Dm}s4c2PnwaKB zPpne{IL>^2na}_L0{{R601YpytWW6*<|kZb^1Nto0~W?!vI@4TYsyZ6N7-M!$Cm>*SZ;X{r7d+%XLq@_ZC+5|G}Y9yfV5be#psgmsu8yf-MF zy)nWWYDnT;YqrxMMM9?{orC9JeIk`+y`eZpVKWF)0+~-AX9R@3T3Ozsld_rzA0FJU zFjYf~$2a79JXG@3g*rsNc zhvuf?sVTo;SMdN;(V%hNtpH^RKs=$AdPWX;Gg<^(0z&3KVT#^MzMDaoe0xy_Ccs%O zPODxdGcF2J>zzd~9uZ@zT#RSa#lftNynIe4#IYiE$!CIp-)gZIYQ7NG4^{fNRa2Zd ziCort{V8RAT2(Xza{?zgaH<#Ag8s{GK`l*6`^F>{5<%zOVvj;)1%>H_IWw8aeeSsu zR?cpYbGJCK%&_q;fh0tz^vbO#uX12!qi)0?uvkRiwoldtFK$v=#gFtpuA~^i`iOhS zI{YB#g?XHF4H+d$Q)M8w^*|ZIiMyHy8Y{vkB&K%g*3eE?qONNB#K!SgCB>T-%%x=C z56`}~Qo?Fup#|btNr{tn9LJy(lB`nMg59`l+8FSg-0Z0_AA7ehLl1J#bTH+A4Uaf! zLWmFfjB{g^k7bnc3gSA6#^#l;eXz87SeTvKkOPJ|4+5Xi7|d1|51%;Z^DC z5gCrcdPS5LW1}auyz$*m;P{2e0%Y88@Ktp0HdhU*A44_5? z*NN6MAzpFrqhiTM6RcbPu@`99&u026M4k7Q!91$v=HuBN1~PuDPelL_f&ImvOT@K1 z3?taYTZ}YDl)j~1J4rl{!gII5gbTIY#6|PR&DcIde``{Iz-)f8+Bx?j6*w(SKGEL& zm286)9)q4oe@vi;(IRtZzX=bku^ARyw~T#mRAgJ{r($aqlnEhAv%>BJj|}I z1ndLfnz^#{AOS0mEurT2y82Kp6v%a)Fgrr@kK|&nkZ>_D!&s{Ipc0u}~`zh|u>C ztjj6*Cb5ftC~yae()X9I{}l;6 zaQKs>-Ee1DjpY|{Vlu5?33k<$?(I1np!;QELdd*=n*rjS-szHp8rl6faC87%`J|o- ze)<}7M`Y%-HA6{VHDosGm{sKlG^{Pyo3CI>Y7}mFna+%KVN2kpbvaqos!ty@k3Na< z*xs-=k2~(R$1`ach=r%iN?P={?Dl^9b&ga1#WD~nKlgV-)FD*P+c@51@C_eN* zEZb!6?f5!NwZFJUx*E4>amLHb?yXmRL01abwS)?M7Q6 zSt)%61|G6ad=6ekgFT^pS#=&Y4Ec_fo#oCzV|QdX-bw!FReXQ|00RI9_oFX&r;-P_ zthbO0RKXT+JPtk`|5aua<{Fubp)R`~xJdW2S6LJKRLH>n`Uh0(wpgqVMfdRa)zQx& zaf?%b@=?r=y(0ag&i{}q(hr-|X&qZ0_hfk}7AmEJb}ard_9NmM#Q9JQ=8jO%9M91F z&JZm2(uAVR?~ZH})DgY$3;|r$Wk!{Et`$FGZ9R6b$eBeQa+`4Y;%$__8fD zRB4ChS?U0VR-)*F8~gd0V<{iOn{t-~#n)1yNo;sUr%H0JSBHmLW(uJ8i#0uw>KbSw zNX&66&Zz!9b`})7l+XFDBShvsOdKR|VOJP!*+`JRP`#F)`H z*MeFpYXA)`O-5Y+VQQ7EHv*`2P7Sn{x7a;^c^M$RcW=K!$9w}GaMi=Z(A+M38-^8Q zSZT_xHI7kai*$<=I3WfU4Buv%Lo^+frqYr$vXQVi@s`mSA<1fSh)`~g(qX~^L4b4b z&wfOSdHAU>^fkp7k)+%1i_kl_h4L7WI$7Z}?isWw8(|-cJY9hM3zR0cOjvoU-d~1& z?aOm}NZ(4DJI^GCNVW;(D|wCpTMDWm$cL6g&bQ3`RT|kKH@&i4d5Y)qR4=9 z^Xb@(nF3FyBP8NCPF2-C0M4FG-o&hDrmtpFTip8mXya|}m&;OO2LdEMPesX6zoA3o zH=%#8$i=^IY*cXo%#LI*ImzK?NyNx>QxsG)Y8ZC0LG)m0uj-?kG)0D>R?&Qe1AR!z z2cU-1aW9t45m%&VS}_37{11~$IX8jvrBV%dhK9RdcAqqeNBX4anvc&GtlGupQFtO; z4>$}i&d4+o&cu0FyVq?^32ti$DbKY!r+^B!YimK6p$@ZBYt2zZ*x0PQx!Mn};% z$Ma6{@o+jZokwE0HyTm#7|^EPGzNe8jqj1SqG)TIz_@-nO0+^#FyOgh8R z5sZLx`xzK27^@2vkSv0EV#BRMgJ}5ZP>G{-^U;VCF?DVsGac9oyo&{oIn_GYY&!2A z-FkkfDcQpy;~O$>sigufddg z9Onp=?8ST|_RyBIp`p4&-aeI4RMcgM0y`!OSIddUE7V8$4d1txCz(P%Tuj5C8XHIp zYFP4y;+HxiUe+iZiVno&tkfN_hqnt?C16Zb>Q0+&(F_qEmNBb zsIf_m$NwOdpPFY^49%LZLma*#!cu2?0{JLyH2Xc?Htzr{nIjvzuPHzyof-tgpyYWD z?$N+pqJtsj&)TzM0T^)Vd+rlOqv?Lqn#pUYlHY&Q`tZGt*N9A$6+&rF%HarD4bLw4 z`IExun;FHfi{Y`g+I9ViyRd2mTvi;I8#-@nW0E{1K`kzrg65)c!>0GQJfHtsHDMX) zjgJ7@6^bZzyQ?ka|Cy3x#-(QwcaM*l#)^M8B;VqHyC?*pr9nBQEevzmM5SI_un0Mt zQyNXv#25+-&(K31so|;A-u&(>^xjw9^vDYV#~`64m$-``ir zA8>rN0R&WO+4}@(2E(mS0^P1sZ9y1T@!qOj zfN+TIB&$6#W`FHUApOy*4HWPx4i20gzp`HcVLatwene$nI+zEGVk$ zJmWA^r3JUq`@E>GxUu<(g_ggGhXNO%jugr9iXfK$*Yb2!=;@odMUpnJ(mPhOArMjC zT*m+#MLu6^ko>Ty+p-Xv;UmDIGC3c2ec2~$%LVI_PF(-472=ejx^wDvK5Pv0SSWl8 zhrKE(hdvRZFVy2V*%Ln(RTZ^iS~PIkwUplXaT#hD6w!Su5qkIBsp(1;hd46{FBh;T zmRu%>bzf(*LhlmWM1f`nP<)AqtNN1l!)YneE-dLR2R*g429+8aC8Ny^GeN`z@pP@;fz9K!Nv_-Q;rQ4fp&SP3MAg}3_P~uE1bpm5}CGA-&8Z+6e`f?pSEAO6+vvQ%(B-3EtY_Gx_ok3 zL4ve4$D5&(+wx0d$Zv8b>@r@%)o*uSA&NJ;?Xj#F+suJle;14u;+VztQ1$0hD@U>( zVZVoBnI9T=brvmUN!0e}6dp6+ioE4{O}XH~(@(`!&T>W>xw}k3!?wJ{i)DyWsp!`; zm+v8v%*~iiht6yIdcunSc{^FCYzgoP@g5G+5e+6E+LT#VGVTQi`36}6?J2%4abkpT z%Z=`WOzfASOum!vIE+SSAe))4P`y7}$elF4J|#9&+>X@F-Sd9{`XZoSLNVy#^9)?l zFNiE#9xURxl&(;z(F8-WCWy6(cK$y+F%~tbC%0<=Ty<4ca-GlWc00-hlWfRJfMo7Chj{l^QbPv|s(M!9~uR+`wh@IpvhB-8-^jKh}Bad5^`CCaq~Y{?eb zBHY_|hCA)nC5&Ktqr9fU&!~J0YNLSi4iZL8)+7c_bAa*oXTqs?_L4i#!)rRNM2Lb} zds`@N!2e=O>6TSdlAJ%b?l6~KqJbztI78KtMgss=d)RNGV^>p0N-Bv_;!bmOo&AN- zNo5WW|74avhT0GOjZ zEgRNv``s*Z*RU5BI{{2LG|@7e$3Bk%+mlVWos=0e3oGvP%bLr-EGmB%dOg3lOe&O3 zf*V`!vaj{b=N=9BobN__F}y;S))nRPQ;4Y#Yq1;tFkqufTuZ?I^yR^0gS#280r2(K zO$29CfL_o}eNnP$cqL(fshY3;B~hAdDGb*a9Coe&O2!^Wb<+l>{0JNtn2o>BAOspO z1t%VN7YAAB{ZeNgWn&CY*X&dGHuiVRB5O)??E`ISGJ=}uS@5-zBgP5xZI|Dcc@^x` zzWPjEZRJg^1k!`ea-U=UGe0(?ryle%s!xbrP-TO42PVqn>vK5tK}_B}q}?lpBZ}NW zo*`N*)aRGraN$<;|6S+5l&6d%i02O1@+ceHe-0gU48OS&Hf(?B(E&(kt0SL?O?V_X z{KXOL$DBd;wd;}sCTTiAf{VZ?_0NoYjvg*ubviM$GAY+0!5Gz$DT%u7EMCZ2v`tzQ zRqGM*qT0zdgFbHQ&iL4uAnaO&pzIWx_7{z(5}O1IAeb@rDE;K3hbapCpD043iCUE1 zoELsZRF{9Ix3HN@dsT~wOSxZerRL%VI`=%I9pr4Jtepu^%8L^A87IoUXGx~D5 zv3H?zZMdn!f)Im8{I1XT_2!a1v0oU*>pOmwt2J<(^|=a#AB$T!5HUnGSCBmYx4Q=d zEk4CH<1olo86}pL^F`a~iUT@g#m^IJYb2*&zq!cNkHtt_ajlJ+q?K>gO9|E3!4Cs} z;jz%zYxrcTV=6u3#FG%v>S%}Jn#Ic0b!)IsRO(NQSeLpU23G-#!ST^o$Q#m;4@9(? zxP1_ReGfvu6?;Vrt<@ghCJHX_pyRK-A)kk@Kvp0Wh|qv=91cYL88r$2TTh^YPG5eO zyZ~C{*sl{U{XU35f9*8M9pmH`*>%&r+{JN{htY?6iZ4a_!x3)@AIPw{I!r3E zYE5kusO9VN!te?Th}j(aWXmBKh3@!jx8oMfM>!wLFt%WpgjcTwM>CMIH?iVw>sV5p zrWT=h4{%+|?NG-D%%=)F*Hdf-u-3cUXDySkI!hWP9f>bpdq(N*%urK(Rv`ZK*x=9h zQJ!j><;UTnQo9G2bhvP#S7Tl7|FiFKY02tHk#@XAwqIgg=A6oDb z1^PjPhM_hlx_Dxlw{7Xkn0i&*4$4-!KQrq5G;y#Uki4w^5SUlKLR4)*zeMpwJ4l_Ua*H5>q@BKARi5yD#>mFD86uj@oT?-3qA8IRZIz03jh(oNVbbp_-1eoo@B-^tb)>%EU@@ zr-5`Pi)*I`QSla{LNjkV!y3&wkx>R`@(<-XiWo{$q*i2W$Q7JkbW2)t(B%$rbHa!G z4sn;C54IJM*3zhZ=u86lGi{!&Z4+-@FC)Z~ftzyUg6&!N?R5H zS#<0K`^h8Jr8OU@Im|Grj1fJ1c{uF`ywj9$X+&f%Q~`Xc7#|)|h3I7&qdnvdn-~}n z&`a0%?$U0OtL3{bk(Ut6%aorj8q$|h5)yZ7Am-4 z+UM>EbvMm{#6KK$A#xa!cB>Z^KBM+Ku< z=3_`+7cvA8yxbUo2=vX+X-aVN{py0pR_fer9Z=0?t@Zaw+r$93m02hhEsNw)}Iv!MVs*&fa~A?f6_ ztx{Mh#tnr7`?|tr-wNE-TJx=U{;D}hMMbA2Qx8@Y`yaEIaAJ`;!ALZGP$+of;`!WE z64CZgCq}Svs=kBVPfFWAKZS2}n%xQO0%ABTHWyc>h~DEY12z#%!Uly&Gd?SMQOAbP8T_rvYK9@uNV>>)p(K2Bgj+Q9D3LmN zQfm4I!Yo9CRS`cFCf$IdtzrbqjCf`?pmLMe;~<%&)Cr-J1w*XP`=u7-}eeH9234qm; zLv^qZQ~lV%q$_|#nP+i~O;ul}Px*Y~LcG())b5^q4v z4VnFOkQv`?`N~};I9hM-`@oh&VdF@M?Gj0y0ybjn+VKy8{ujoDazWFtj;AWNS61}0 zb?a{0o0Z^C)!w0>GP9GqkuK26h^Rlq-t(Jml>rnx!SXr+LyhGi_Vbz$byu#tMP zyYV8>cxO5?(bGj9W?r(tW8`}3ryuQJR|jjNrg!eZgSW3Nvy9xjXtTX8u#&C9c0sTw z?8+<&mWVxg0iwyncnVh5Th4jZ$yrl+o-Odph_PY)ohn6Ye&E#tySfLfcfN&#BOm|3 zumYt-2gghf&?{EmS|7wPn-`mHx2IIKj6%3L!F~1;9#9c0T%SzD)mF=@BShhTqp0<+ zTa^GBq+ORtBCu55NI2VqAZU`J#zGO>8Q~j(e@%}`yuJgbnc3+hN}56aj*0%(zvwhg}G^>$x6pxrS_bb_Kc@|$}nBpAG(f|e?t zS}ZCb2bRWQb8Du{K@Xi;Pn9gj_y7S+tWK@@q6-pq)c)2vP;Kmrg@A=%(f|PNyW5%*@gRHR(S_Pd-@m*UHqLsighDaeHNg92uCf)B>2{L6?y& z+3HnJG-{wVSeP+b)j_i$PGV247zXG|a%5wS9DXPxyT9AdqB8Bz(L2cbqkf3cymX9}lO6|KnxLa<{%8te9 zyqS>ow?d?;5l|YcQ?-l3dgD z9y)`9DK50B$rn9{g40v0{{R600aMxgwwu;UzfnR zyAO^d!55ba8t8meU_CN%5^FlRwJd~p)Jrb#!Pb<)t(CifO!du zT|ek$p64y%v$j+Wnz@i8+t#;8ajX?)F8RBPqMeKsYe?nd?7BTixwbU5_67PeXQt2` zz}`j~c7$G4(;c}>87stZGmorFv#6`G%%R{33L@HQJiw-cPgsF2?hk)@TQGS1Xsa6r zTtAPw4*hKJu+wdsy#3&W<)bq>zAJ)S_&u~1$@lwSjU%4&Hvssjs{u(f$u(!^u4iK$ zJ)U?}N1BA8^4R3%Z5XpmJIne-x)j+WU=*rUp`}fHOJ>o zvwEu`2{5UpF{Z68n8MkFaUPZ++5su;RIBJ0Xib8AgAj$Gb2lsxEQD!CDOIhj`-)<` zMv!0dAA>FM15Dsj!I~g&Vmk}hCje$FVxGldHTGAQhO{E>J3>F-BujH!G?s$cr7SLN-X!OV;y+qq1LY3_U;mO%f5OR&~D6$M8De=oqzxU0{{R8 zsqVp&xXv|m<%6NVljMO>cJ3UB9x7e+Qam{@mmH6x7Vm=)%O}4d)sC2rAv397XlZXm z3`FT3(tK8;lK5Z_lq3B#B1LjJ(9MEpu?B(nc}9OPDBR}pLM;UKg#>p+=I_p9Vb8wl zKlZ{84^_pX>3w%=_L)Esr`xv7R5sb ziR4dP*~hHOaR+tLi8{b@+d*LRRP4vdJNN@m+V)6WlO#O_VKRXYk)0wvwe6U9b!4R* zOKLwJBlaKzsK$})~&!06XILI z$-3d`Q^Y!ly|B5By1t*vMoE7xaRDvxnI-#mVDbx}WhI-va15M5`85%Xub5@QUEb+u z)N6LztMdjoXMoGo{S44hKOH4uvJdl1=DY971Jv1TH=+ESY_^4Aga* z2rF=CAk|j?9bd0F7!mX`V5RhAo2BKX)Q@S*qce5isarEV@@>_@!k-bm^t)cLlA;fl zTc6nm5?;sDJkND~zYTDP(NAty9w2_KijU9B-sjW2fQF1W4UO_7J`6#*sM71dKj#U| zu%RM7FJcghPM|#|j^aUNo*7@DlOph7y6@HQKPm|c-tqPsExI~JcW|2e>PAdvHSCdh zMFjAhKQ_DGdBYx(bk@bp%O9jfO+!qLi-e8~6tlh=l{H#O;$vVy$Y#wWx^YErIhOqR zO6}D22i^JSZup1dT6O!4k=7$4oNe{q_dKVGyXRyc@mU#r(U@_9S#7Q>4AX|M&NT#nU)lH}g5^oO)!+vJmHbvnhDQ)*-rQH@^4UirC_3eRG=a>!7`Sd*{>c;B;;uiywYv(!U|b?r#qqBb z4ss#w>!ll*(g=$O?POdEEe6FYS~M417#OYr09a%nR>1f(k1wxY@}9z5)u7N~ zW9wFKp%j=mk=%;E-F#6+x#97${Qcw655CaM!C{h2Uh8aJyy2`Ga!;V*7TCG+0SZk30rv&#B@E9I}+wo1=Lu>gj=T8)?_q)Ie)pH4mqE*ri8MhhH-& zPg}P$6t=Qvn-Xq~+!LVAhg8zg)ChDn$MUJ*3JM9@9>z-w_FynTqe(8xPv)kKANnn{ zy-bJ%FoSE|z;eVwsid94vbc0y#le7`9YfPMh)lvwn@DD_4)FwQNVbs2SAV%J z+Zakb&%?rBaXs>YmO)IHE?WFj&sb$Yputa;GpO;75G=}=Zz{&%_vIy}$X&jp)*aW< zAD&h3vQ{n;8D_4Yx$lvtzBiPORY{NaP3cvuF%mG`l_!KrM7A8S%8qn`<1CA}apc~1 z+AaKLU;M~f@PgN*bEiwMpj7S(txM2@s?vV@_%LV}!IPE-Z3Sz%^}h%5u)B0VfY z70(8#3=`OPXczU{ho??$XdvkUQXS5qrY8WnwRp>=XKTe^H%+lD0Q;ZE?{b*av;U(0 zhVH8~H(kEiG>jimU1t4~gLD~mmnz^ucf!$>Q1de72{o4 z7O%Ee5s9OnvTdwHW9zQ1!Ecfd-Z4EVNh?hfHahwagA!gk`y004=92X%6KK7$Mt+>8 zk5nzcj{XSm1hn4<;NWHpt&^>?Hq{6&Kxj~VfmzI592(d-i2}Vn*{fY0n_0Ta>$0+g zVohh$oK;z&H@*jX8kMdqQ9hh2tNRq2YsXdFYdnbrG~DH6;jj?<{LShT*g_42xTSq6 z6UU)n{${?gW$6p*Nw>)Y26S^Z0)jhGNfzy>34T?y6B>BrJLUVIScx*1fkWifvcb#i zQeOpOI3AL?e+AJ0`MIrz`$mGhOKb9z=qiK5>o4N>7Fd-)*CGh}E|iJ3KCa=yeZ`RB zarYF39i2>r920682ZN%!1+q7%Edo$tPB;#cPIlGlH>hd?=7O{2Sy%UWH^{?#BM~Sc z<%a7dsr=tpG_^UiO(oJA{@)lo4%9!*DGS*bn9j6Op38XIxl65O(>)O!FQKSwaIUI3 z=`iwf^|tsEFvL0%UW&Uq$>1Fw&@~c|i*Bwp%I64^A%&37d6CDn74?N72T=JLhv+9l z)`J48+Fyep--hH1@w%=+000935|6vG(UUUj7{EW7V&jhf9J+7NwRUFRDu|KNj09ck zG8a1@SQ02VOE%VaHRT#D%Drq=LevET?-sQ+hZ-)JAgk7$rnqT-t$kddWf^K*s=X** zV2Bd*$WFn=nlmKM4nfYyDOQBFlTI`GS$!pxm7>l^UhbX5e3+n>^t3ye@&02*hq+dm z;dUCDn2sYw;Ew;-!!@+UeK$k&#SOEQ?skTEb3acqlF-q2M5s@H#w;{E0PEpk_HEJ6 zcP#zD;KT1XyO%t;t&)-q9lQz3N%h%D8yuVhSM3zhe3f*_KW=1R$4w_VaiOE{g8*oD zcJ-Af6QqN|(9@G^oi-g#`3G-m-6+~e=}WyH_GEXTrwumo6Mpy7^PuAc91q)qRDQI}*+jN%emlt{s<5VGL_b{hnWh#+9Rl z(P)`ZE^hS7q}A7;m77?Nrx`k7AV5u%sH8P?B5H@Wj!@CC4Tk%S-4&JASo~q=KAL{w z`Ew#HC1#!nGM@rbl8e5?0Ihnn54k{M(lh+q;!DgCXr+J?CI=W3v%-3j@^nJ53n}1# zP31E=>M!%Hy$|TyV!F_T-O45&hYIG&zB{}|AKpsc4*q*S>w8+9N-+bqlcY#WWz$6E zR#DagA7X?nx`gB<8W=Y)CnSB^w*$ zAGD8AUPiWHY&&*4|CYn7*gM{7)SUVSK8%&aE|vL$x?-p!e+}R%FI4J|(rU{^UNMHV zR5wJib?WcR;D$fB1EO4U5t)GiE&OJ5SkFER#_hk_i;_n$egO z^j}bY#^^^>S6JM{Wu)gtGH_idD>oIcN)+=5EgYZv|M~;2kx^P7O|q1HpgQSev85b3 z((z-F(?G2YN9PRF)n^qQrUiZd{~p6B7MEgaK-oW)8$5p)u&UWFT*U}nze1K{#{INC zU#80qa0YMWqz|^mabJ2RJ5sStZ3%E1fF%t~-=iDi&T{7{8!iK=XiK}TyS=$IW_AWRNb9Kj2`Lym7r4lB`V-nR)q6z6CQ|j=D-Dn3jmks)lamrq z-C@}sY>n9QA8g+@(-BlJ)}bnY14R2RDMRL`x6y36Jhf;NHO$LIwzyL|TbL~I2%bXU z4QSrQ9=l+rDl}I)3Q6qbeq~AIF2sv|8}VlYWdygu(1J*1em2z`Q3tKPkXL%JuKbSj zghIf}7=|^j)^J|4?ptk`AL7i~2L76yrR>Rg)gDo7up&yP#7@iundu4rL~t`_P^P5A z!Rd4{3dDmN>(TgCaEL0X7z`72-Lq4DyujnCayv5oLG|zv68h_kUw&>b zO6u*k5}Y7v^3G)>J*WZg>Q)(RNSK0xd>sO@xBO8|v$^sLR`Uhss;JInI+ez`TN>tF zFhH?G>C_pclMx=e?feEso9ZV0!d_1yAk3`~m_S1?#j%*9&Bvt9Jzi5d>EsV~xBLO{ zUXms`kZcoL{|qLj@`rdq(bP#gydWog75Q=xcR5%3yBxQKiLM9}W?q_qRB!sj{BmyE zq8vw5#{zHWb8!S*lW%a>)0QmSOYEy0*$fzJzlTXBMjnNGW$0b@q9RD$l|ASaX$o%5|EmD5 zE-#)kiso5oSJq5?P8$Ja{<3H<2Y-$1Jym#ns7lM15O;#FHisg0{{R602vNh$JJvYy>W^$L40s!*!A#}C^ma*K2C01!^3QP zh4gQ_J_cQxoi$bUasi%|aaC8|Mu*GR^Ryj=4e-@%M`LlYmDG9;h#{#)KHcjU%qyHi z(pd!jWgkp2j=_&X!NZhoSN1h;@dT*?kWkXC_x@8mUja{=Fu%^`$N#Q|`%UHG_FbNn z9I&!R$}`fqg^oM)yZfno1|UIt`F0-_$SrxW&zJRQmRcAp?e|w@>)7Sy%^6J;{e3D> z(;g@e2L%3`+4e04EYnS-R0uw~zvQEa30)`XkIl{3_BPcLK)v}~H>URyRaKMg2f?fh z6SFt^{bA{4>;Ek+Aq%NU4`8t*EWsyKBH!J$qwsR?*5mZJ7Ze8OkVI;ab-wZAUE~~@ z=C&C#wUiR>*Xp~n$>EUTV-HE5alb;$;B~3^YkjK~i^(_)ZJVCuL_H-1i=(1>+~{nd z#H-t{G_xNxM#Rjil?sxYSqY+|m?{Qx!&^`-y?9}^z%uxg2$T+h0}#yZJ)J?!9KQRz z`BF@DupAC&z`m-CaG(+W~#HiJRFZ!a% zlyaJKbknR-8v5%N9?ka&Vh=XVP+@Y9J7`13;*wyo5nB0Nxt#8nN9H$(X-kdSh({5h>vx8m_48_T!-ASTYmyoAxCb83Yuduj$wF zOPfJvGDtR1^TK^D{l3{0FY-(*tg$QD+deTPvI;eZD}fl(xIVgc$`~F}g)+q>D#F(o zz$L>%ha`1iD92&n5`TJ0%zrX}E@NtGs-iP(go<@_4-N8>;Bxl_ z|1N8a?hpsEIOn9Sd%bZ^1IlC*e{f!jU(%i@B=I%_m5jbUnxOqOSPsL5(*?#wl_-Y0 z8D3W(=1on?f))2ece4`XNG=mv_i-kJdQ5&uEmOl>V;3llM~#eMrtKtitLR zIX7?4(^rn{52!Ap=r#rxClno(=SewpRVUO>V?#P!S|DFzEIsVq!0BIi=s|1mf(*cT}k+d^K9U z`Yu@0ZBRqN&#{cSFn(jSB6hYsU@00vVULLn@RUw`Ft>i1Nk3Z* zL;Jzqj9+R9ARMh_Ix%KgFe%bq_-FiiZmX!}4%zy=z$HQb<0iGr8uKG+vC+jJ3bkrw z+LSfaFC$^oo-6aopzShGJ~n;66A@7iMUi|8Jw{5B58!zmNqkI?1-DVRjNqQ|iBrVG z+>x;|i6&w`7*taUnKBf3{SsNL+OI3*5bl_0hM^!A_oGx~Ca8m8YXi*KBe!xK99v|r zub&SM=fpCxZzpkY9v3O{1}>oa4E7Z~i*4d0L2_-S$*c}0V~|ztMZz_VaL0f6t%=Rj z{`o7~`EpphlVNpqmNk^W5X^qBjX52=YW*&Z(^ae}m4P?L_eKBa{XrbThc|*fz(grE zMv18h_{mJzOv1jdabZ?XVq*QHh$3c&jWB8q8^XUpgmb^9ho|a9+ zrUvj}9@*Kt>2EyK13Dj}h8=1pRm9^gNfhKFM_^E;ei?TKX_SLjzzveyrbpB-dFM4TCy!%hfJ7}&YNOmkF-7ok)o5x!(X((&lmyKqlA ztxFyqCg8@9@q%MzYh%FAAQ0+4EO{SC!|VYZ1RoV~=amtfQoY(n9c-E3^|!}`VN`Q> zWDEb*5f53&lJ)*wkC<#|McaiF__}Zo{x1-ic@g2fudz+oS7U2@V^#nF0{{R6002=J zBoWx6IH33otrnf`cK6)#*kr8T4`{e_D4_s_2TQ+5=R3=cH-9~%cweAG7qg{$F7K+Mw8s^{3iWjJQ>I25_8E?Un=f}H?xL|W0}>i(RDzO3Oc3_D~-Q|jD-8I`Aiw{SR%RPs_wuuBPpQKSQG_H0{{W|2w2*#8py%A)EaC7u5+L;0)YY4P zd5JnSr~{M*YQi{oChx-(7VRw$?>i{e5ikDYp8(fGn8STojH;9w-}gHd{%mEpTg+md zcv!3_V<>vBLofcYN4blH{etf#9kNnYt;=hD6VzY5*uqd~B5U9`^@zXrM03$qB6h+{ zFyY8NV{EF_UuEA}t{ec8`l|JNw|cxY*%-$3MufpM_u5)p_dfg<#nb477H(`0nX#+W zXs^A3H&g33mSUxCbTp`&5isw$;Ch!6taISK2w|LQyQY=m1Ok32dZSrrZn7A&GBqNH zxyKdO-=OVk(%+;ER}Y|m^s=l64YPG1RLP}H<0Xq3Z(a=D&OfW{~ zlbi2)LxWq{3u-f_Xy3f*5@EQ0n9bA1Tc-@UAHUKko7FJ7k9)m5TT4U3FT{`cl!XSq zmvx~~PnxM7CK`#Lfq^Xk9K|7IjQ(!f1VGz)X8g^X$-vzZb^GLkNb~I%dhd4znqBQ; zS^LPar#@N!ndVrM9$`YE^4f?XaK?Zoy?|)nmA^q{V0d{3m zH8nqua;k7JfT{pdH&qdk(S!&_1vk00RI3g)o730I2ysEqvGV=RDWsW#Nqf zu!(fD^K(^ukN*9>aPxa}wHEcOxo-@d5(+E($jw*vsjA}QGWbSmh z@AdIXMFCOD+#@ZoWlsieDO10C1r+=`pn=u66F8hZZhX*8qW*>H<>J0by|E+JoMp?> zdKsMItG#qyz9NwE-Htd$7}BTg&`c>W)gQ%yn4iOIRkRRBg!pB2_xZ3@j`VwOXGdh@ zNp${KsH}(n`aT)!^Z1q{ZsQ9)1}dQQ5r>4vU-G)-(y zIv@IHj;{%^dsz7`b9@JPrXK9Aco7UFjzfd(0`Fal*drw%7DB%PaQ|7P@H&p{u`mB%)`J|v)kFr75PZw6+n*?8M@Z#7OiL0K;-~*YS zr7`#bw_*fefpfJ}kz`-tuhn@Y%Q>Y5Vfo&zcp-Cz4bn4JTh_ zMml^(6})Bd$ySEcf)b|4M#l5Eq!k|8bkOOpqmz=goC*;Bc;yr!BBlzQ#jY&fN{1x| zKb)_%kUJadK9t_@VX+W2e;VYr)^mRPGR{@@cPjfm+~#60*aCAVS_~|K=_(hbAQs50 zHSDMwkUzLXr(#btGb{Xi&2)VxY%d61I%^?2<|Iu3dlBcj14QzpO^_rISGzxMg(PJ{ zmhFdi2_M9aNqlGQ8k3D+q2t;u7H64N>{bZ@I`;>M{!>S9PD8c^zy!MJl5cf@0ExTF zZrYug(Lt90AdhJ1SB>XIPCx!+8^t<;tHD&lgZjnAb)7%<50hKY3QTL=gC0z+?}p27N}G&KO3Z z{jl@|k24hah;^0Xmpd|G|Kkb#1oXuNDu9s1dBLDjipR=O5mNn$& zYiji1b=XHlh&98d)allOJiYU|eZGA-^Vmhoo-sII%O7R{WE)DaZf;Pa(<$jw3XNhK zC4C7>SGO_PHoL8ALDbJMMvs$t$lNZ?g*5rogR`(rU)NwHyA@+^CINGVO(|m$DS&J* z02LN*F|m(U;jQ+? zICtna@cAi%iZR!Hv+_O=1+**UtC^3pE=>9o z{)A0r3x8Bnu=#}HoE@>;{cmNh$<$=GA{ZsRNm2&Qt0_``gP9-)*{dP6G2_XlgX-^^ z{T}fM%Qo7~tObEHS;teVpvL4X&`-i4Uh+Fztfaj!8g3CX7aC*}as=?U9b%qbmUk#- z`gx-t7AK03n-*OTp9o#_b%M84Nx_yot=7uR^XqA_MQcNVn`LTqz-C<@^6 z$<#3Lc%dUO__*(n)|1z$Mekv&0Oj31Hj-cQ-0}Rmc;K7R$2Guv408tq0009300RI3 zM!5Hse%^yDNqj?^3BC`7hM9PNSx_lH6}-ioRp^RhNSQG&4hG3907PN?!Ykym_Dh(g zF!R;;wOSqslv(SWO-ePB65neDD=8Dv0Nv}P5Rco6&7Xwgv5CCRn%fxeY~6pD1Z2sj z9l{m84u=NY89Ff){;&f@h2aZLYZ_A^w2jv4Ek40c&IlHSCEM+AuXLPbsn3`~JWS(uw%ky@!f|O;fsSiA+83&d=q((!9HsWuQh>36d7xQkg^1Xf zrO6(KW5?OVEze&L?qD-L*3ww3THcfdY9N+;I+<~5-A@2PAr@B_sM{jJm`_nZv4h%B z9@SWSpBWau^Duq{xW$n25@h+8iCPlmBblSHFnT{w8xWcbwLSLGaA9T=Vzj~uTCU!Y z1~HO)Cw{1UPBBO9N<9k+uxo!=jVQo0xVrN>PErV1LEK;${!vfGYokM=R{Z=-Mk00RQi+(pne ziyhuRDYw-2G1Uumr_3a^vVas=BE`$@HgLD&OkFZ_3&0z9h&Xg{=^=ix1!wV}fQ(c3fp(EWdhjYYTnI*(9I6lYEw~6|NV0MdZ$4 zaTe!2(f8Yk$b1$F1$h1SiJewW-H+dc-A@Ik9wY4Ukh}rM^IM6r7cn^Xn^!-2Q{#d` zT@!fs2Z7KmgMt?!STnkPxE7PnQw>B&P##W&mJ>7AZn5c)ICWKfd#O=plADE&kPuhO z=dR4u689_r7&Xaj&H?_|nV?K}f3CeVPzOH#IvfL9mid)HIygW%)32HlUg7fL3$=%= z2N>JC%;OduN0~H=##j8uCK>z<8x)0BBw-7;FrG~6vv}Y&eDlI7Y<6hOjq>Z-iM>n8 zk-gNW`2qMWhZ-czxx(NrD!h%dib*}hsODTbk^7Rl`TAt>y@Fs^JMhnS#|J*nF!udH z0P?%=qfmbADz{R4B^{W`nJKEJ2iX*doKe0INGQ&3J^5Bw>5*VU80yPQWOHK0OmRCg zDI~pH2BsIbu@zP$9F2`S_^AkO9w-ye0 zU6!`2@br?_V$-xBbNixa-cSnKAQ8{VK>Q7Ozf0}Bazf}26vbqlY0gdTr;LoCes*oq zWWMJ974%XK<2RyPEq+w(>*4|sD#F1whEsQ$2A%bP?z^7Lolb9fm)e%Su*!Yx3}(Vs)6{L zKmY&(00B~}ax4D0lfUmB(vHqfLCh|oU3+2?jOWXb-Jdqs#6rkf;#L}dod|-2+iIC+ zRm-a}02Cw2dNqO*&*3(>k-5k`sj%s+(u!mTQsqxBE+kz-M0^A@h1rhLK=`dLB89O@ zVs?;ep(_P9ESPt+-#MYVJ@BYqh1z8bk>SDDa^6=np4vaJjjFq zZ$Oa0BR}{(snDueXqb?R*Tx3I28+GEl%|L9J+Aj8t<~J~y+~)!m7NQ48_VfBk$zb5j;IUm z9msVVw4C>hhf8bc+1mdGOsOBhJ?>E(3~kH)*jz_QYuD=g;Q>U%^)5{llTmYgPe$!b z=xx<=cIY=Hf*Pe@5MPLSfV!mo`ACc*n7uOZWC&wYGDl=PZTveSI{PpDaar$SUaYIB zthu@XuiTbeA@GM8=}9!*k*^e4$w$8S#~OhHDhoXr3A$1Bn8%`bpivBM?p z(^lasFCDxy6`TCna9TgcprFKDvfCNgkSGX?Zl~*Jw=z6;9P@oSBk5PL9D`tMD&ZFL zQdUdDM?nLq0CwQk_HyM5dSuM&BHZ_RtUvWHy$`oxx^Ga~_3osc*X%g(9>rl$M^g@N z53b1~Z>jWRfDf}mrUFN+i?J z>PBY=5!55)(|_u;2Vb_;8k0T)7&$2#1wF+hXwIkRDyXN`9@rENxV_{?rW&QBS=EXf$TF6nD)B4{j( z9p6i(*qP8Kt@CqC3uW z#Ww9(l@A^Z_Rjr|4-A9b7@%mwAlXWvP}y?c_@S0GJVOA%$<71#|0Aoz@s7HWyZ-gl z^xVLefqj6l=JBQR&x@5Cqg#2Y8`YF_x+%Nz@N~vuv$da~Kk1;=n$UC#XnJLP!#LuV zdbhbk>}sm%d1yHIpsuzx z73Ki1chMhaP%|c`n!Z(a_E#D7^!-rTbK$L8((&tqdC=%XUul`T&-&mhN$0tphc%yz zkBFo3KxvP|=mZSH10*ZEieO@fDZ~2@VK7~`Bod?vHusp=Ws=3_>(>bG2SXIn1trde z78=M~${)^PFGkbOe>B`rv>eyPY?v#V6cy3LcZC!STnP%3qKlsbO;7CnDxqftc(8T! zzfjgy1mwf=!9jKWN6=QpS0gM=D~M#!WXF%VcwBSOor7OJC`ga_uOMz$qmy{oO00M? zDMWi{XQ?8-I#j>yrHl+T7%HGjJ|pa3SQ$)C@MOOuk*8{{BTV>=Pz@azmFbem+=CJn zk|DgwxSD(Q&q^8mVS-KWPXMOrdAI*ynl`_(Hnwwb7s+p!i~X2YjF{sD3&cy{?}uME zGj&twcSP264{`ag{pK&85y57F0009302B~wIKkymdjDrz@z>xveAI8Xh#9b|gUfIfYxv0MNk|aM0(t&h0_~A;>i9U4>0Z{^#5h=sZ*ims5 zZbLB3IK)D{v#9pL^>v6-@RUFjOT;?=%@=wIg*S*gR>&=dxJ2nnW5!)!avtfT@JmqG z@z3%&Hs&m^)Pn>SI?@bx8dBgnTi2{eRyu{h9z-zzj;~wuB>Y}-Ln8Dir9dHfk=kV^ zn<)kAN9#q_lCpT8M+xD>+Twx*iStKj1mz*2EFvbR3C2O>B#v5~x~5^S#2WmWUa?}@x&SGKwQ)4>S5 zV$G|Z2L7QAP=BJKy%^2g_?#x_-ZMJNf*)ZlB@Bcs7!<|FmWwmyoc-i7T6hvI4AXse zX^wLbNaA^A8>s6D#G0G)D8?T6-$9KTWi(-H$P%}U?PZ!dWMs~RNu9i{%S_T{h(&kR zh@_O+pSqR&xAD;2=&Ur6KCN5H2{6T}W1NW$P-$HT9i@kVppe|%Q&tmc^42b#sP#Cs zTZa<15aAkzyjt@FmOdbTm{&yAY{}!D~PHcwB~Sbp!EVEYh`PA1=l~ov2c9W$|@WlKNR?osH;)6{C(FtYtxoT>8Hb zUipUMg`VaozB+gS00RO6Zuj1#-y}ddAfx4n48S_6)MkAk0009302&VAPRF(fqgrC< zyg=4!YeTx#bB(y~brMN+c;Djqn&i_4~8U$$Rka)1R|mK=)S)rG|}TDODL zJ@8LmkSb5tHLssdRXwSy6pV%}Ttifov>?L0nY~I6r1Ytbc=Z!;R6xK(#Hs0vb8M)& zYxlS+p10rtdOw;g_oXeJ^^3leGT~TNaNLI6H}b&zO?Gn2m%AvbKG%@Qx}_;O7rV@X zCMlHAd_mEP(|gb8_7j(H9#8x6jlsK-*|fZ#AId^&=3lw1F?{9#gk9tr{i9?lCnb8^ z8Uu6sb+d9?nGC_6!Ayu@4~D}zXh9w>vM!`K_ZyZnvMg6%kdgwd%Gr&?!0OI&rGtv% zcVwWldz3wtZ6UMPryh5~GnB4CxR+HI-U zSAUF2&1}yVk~~PIs`0Eat-s|7G}&CdGq>*cn6N1(T{bazNOcqky-~J8h(^U_IzHQO z=Qxq_dKphwngMemzQhE}6Ep4@;u&G7Zb47zd@XnwP;;w6lrm9!P7PrA@c!`%+{2?;p` z4GCw))A(LVLpFxCWAmo>;Ck`gPX!$NMw=b#*tA>rVyG#9_XDOezr%6`qx}iMCs_dy z9Cj)YslX5w^f?as7^}F$z{VW%0IVE26#y8nSJaKcOa;CG#CYtVS7==Qbo|RnxJ$px z^ehAM3NY5tnhcpjn-J^*gaoIzj5oR)fJlI<*0myr7uOJ+}?3cv!JuZQ8yUR;V_w zwlR{X(XBY3r3HFVCt%RRw^O5*?lpFkPhy{y4si;ywC+$rQ-kq-&w6WTGy4SV?|QiI zGM#5-sEN|C*}dAHv%gt4eRTK}mN_Ab!vnF-7VtPhU=5H>SJcLoN>~1Sit$GV0sLAr z{~fMG*WE!^(#-Sra+xoHX$|`k%Oggmr%c@ z(VM`Wy+=HLDy=mXzt|gHXUjn}x`x!heo!b>tdEfN?%J9`4&9kQ;dexNgzJe#Ic`et zV3`_#x#nD;qpn2>K4E97~HW_47U zas&K0KUZJ?1_a>|-Xef5`&}4KbglpZ0{{R60c@?t&HX zkX0&tu_7+MP!ct|;hja9L#O2995A$>{v5a%MUiLaI~NBUhTCSD8&{^AP6L*rdgoDz zPZ5^DAQJ?rghnMJtB30QpUTQC^A80&b?sRyLFKLXV1TozKfCrm@f*HKD7zS|TSS9oH-piL zy0B$%5Ai9pBSBobv#W23&aZ!U5F(&i8_KHhOs$NKTKq)fmjuiP{zR<<}d)UWaTI!e8F#8j?r!N2TnG6Rv zezL7V4CEkzd}NGfaaUoWJKWD0QK6q?e^MK|KEXG_b4h7Qj=R^>t}0Xb@kOnvqCA21 zZ6!Y0^F3OYrhPm1L{~e-u{6G$;-#F4?C|`xmY-YVYrJZ(^0y}P8GyYD_sCN{>KM#F zVX}X+wQd9lNmF1K#Rh)=I`M0Ov&GC7{Z>%3c1FmxrcQq@dz!>wX2G z?)O8+CH^Tx^jvxXOlwzVj{=ZPqL5H^LDd|tBdu+(%BI)y5c-;i>vEfK$eWv-_aOxyI>dX~XdwW)~V|3_qlE1&i+?eE=JX?KBgW#>g@~iI;K6GY!VP+LH+=ufbX*CrQQ6&y>w2 z+eoXnNzMR{!cZzWDy*$WVo=D5vX*e)cZ~b=^D^iyr$))ZxfO*iJ%qhck4rD`Q|4Mv$ zR!sR*+o_eg{yn`xlDo$;>pLG~B3eP#^l*KgbX2*csuIxaMGUA5tpN6}X;SmqGLQSMuh^n(^$cxNjy@m=o=Mzl7b z&D%MFlW0`|(tUB(+H;fyO(OwKM_v(Hul8deG?iO0|9`-yqnCH6VTj{aCuvm?9>U#(5exW>yCCW=>U_BN>PcsqWz5Gyt+$%dp;E8df4?_0iRQQL*ZjQUknnIG|dyI^uT`NOjTFBL9&cr z?o)VFOggldi|vG!IL|vZw3M9u$JNX&PH!OhF=M%NEZ@4WI?2Keu|zSY;;`OaM$xx$ z81Mdzz|Bj8r!TU`Au*M{llq^H#&fY1u18H!Nu~f6{{I;Ln%?2ES z@~wXNUU!cp*!d3VKqyq`e(ne^GQm@N>lMatiG+Vu#R+#+gh>Dl`>cIKn|EM~%?>H9!CW0{{n)8dzhi19AT` zh;PGE3{P@oCoi@(B|IxGy7_9S8It6d5<=Bj`C)NkF?{Eg;RUkHpv6*J#)i>|aOyN@ zjnwA>z}XM{yxTl3xsyv4b_y*0$FrARz`jv5H#hnO^XNd1%Xe#P6HwMBHZ^!A=1>k& zf0ldX<&QgOJw>ZV2UNd7P|xY0qWX1-l7n2ZG7unB8FZo1#?b`86V$VhmB15>Mb8LU z{;1#CFc0OspXQ39_uW3*Ck+E)i}2NJ>}zX`GmhgLUhj=*slzR83eVLyiM833#k|;+ ztQGS(^?%ezzey&K?3M4_ATtYmBS*KWY|e{u%qT8Y{$)_!sNMk(3}$ck`z!SIL~wcM6hH8kO@Xh%(0#j}E38Nis{a zaeOMc!D>t*qxA6MvW2akxWcmGwYqfBl>Q^|82_ts%1@w*CI+g!RUU%%2b1b0g`UNl zMF8SZRo>(x!oxZDZ(|x1HyY^x0bc$6~!cl>Nk%gjX;6c%^7g zlGCmNrFT@gau%NfcLT}eGHuwG`^-@*TiB``!;5HI$+rA4O4kw`pW=AZzB0MzDrbtA z)Dm{|l~7yqH@zOp3xg6sT617g$aT&0WFdZ=>_4|`4n+B}EmBboK-Tvdh6Dl#tmeYy`s<}N2spCg;+ zjU`VIcO$6?U%Y+WCO>BxHY{%R@cF4aW^cFD7%txC(-KyRy7elLVFfyh7dV0GCzH5jbe-oMj7d6vYka-t(!DZVz z(T`*>?X9@i`$n)5os)s|4?iJQUwKqntf=t*m(3{3=7mKit3Datzm*Kp_OPjcgpM2K zCgSwGadqirQ(wN_iS^fdOa<(`sJdft5+IrW?=41yCQcH=UBLj<$h>|fe|FMJQb>Ng zR}suQ&5!-wE*8aMZSE;voi z!ILk*GQYl-9)K+~SM5MeJ#>EGs7^0#h{d-6t`FGY6`lO4)0xC?+XSQM$nAL3i1BtYH42Jc)DU{KuVh!y@6y&*I;_fta~#ksoDRTi=a zqmV<>h+zAd5dV;qL^Vi1X3~T>|BEuhY6@Zr!|~U?jdW zqlR(J;tO)@fBORz$BYW9l19hZi$=^xww|ag!4IuKfFlNVq!+@aaM7G(u}Pgthip88 zZ@-dF30U2NS}p0g9RP`FkfHjW|KO{`gC$}T+E)N3!Wm>2s-O*c&1MyHyfG~Y{VK6s zPC%p7w`*13E;(1s&2g*oI-_Us(klc~hTE8e{gj&Qb0!5#qh79LXRp;ST1GT%Iu+j2^i6+n`0J)12Pn5?Z1BGo_#^lCq zlO|vI1vsVPV}q1NzcmBaa@JCNu=CUYAk2wA;2qZ9jXYODZDGIJ?|wUA==!ri%|@#R zysjS+g_lT>w&S6x_Hkv-S>>)z0Q2h|8>Ai2;J^7Dvk+Y#qYn(3Vpu-;wmnGQ|B*Y2 zX~EN<6fTd?Azu$8o`+K=*pi{^y&3z7sMdTE_WICkl!*R`4gzFhaP;@6vk1Iy+x!<6 zY{nB}jd3r|IHg#wu5^#UZrFAqd1`(~7&}t47om5>6~lNt4d4&v1CH#7srwHW_lgj{ zQh+LL6RS2L$a4Wx*Bl@M>Mxte+<~UT7d{S6FooY2phevFr$h*Z6{LC~>m>#RIASNK z!pnx|tw3G%4_?m}sM1gc13Oq~x^>63Eg8p9p6%m}X{`OP(Fh`jKf~ho!FqSM_X=Gq zPT+jDSd6&!t6RzaQh`^!@MYULmh*kgHJLtN&r4j4TRQ>Rx5#XVq;DZ<%fd-8-)C<3 z4PjIX)xe%$=l(Sqgmdt<9~4wh&j_58GAV*W?oIl{oBkkboQs>}(&@LgLJJW0fQ&F+ zJp;O`_&1E`OtoupoIkTsw|bBc!kz}h(U9319n1FHGfVOZeBEc7`N~!1u#bjW6zdRt z!}OP+7k#^pSTAv+EM73FttMxYPNg%FD=Ibds}H)E8BDD7#?1**$%Thpus0}aSGCUs3d4lJ^7M5~d5Vd(A1$XPjB&TW5DMAT3$#J1_nFmP zM11lW?4Zy$#@FDyG{BZUV`jI&sa^K0dnkPQ?@3Lii2iAHm(aOq8_0!s^vs<-v=z5L z&nWP_Y<2a!v9@?jl_iL^9gSCWL)0+>7A_u&43Kyjc$x$#@>E5=VsYXpi&A5-o&d*v zB9340PylP9J!3Yg9KNUAlO^k60Jyds2O+LR4;3Rk`9J}g+9WIaw*6%qR5fRPt?vWN>on|C%+j_7_QDgph}cJ!WF={J z$B|(0s81%s#!cc;s5#ovjM-%zn!<=uQDW?m6XhT+?i?WlOYw(~L?Q3>*Ti$4P#^yh5@t*D zX$D3H75dPY7qwhW*gn4;P)k{useqFGgs?y;(tb>t!x2CGd~%=V>Lp&?+U)z?E4OU~ zj3u;u$ttoE1S4c9VrM_W2%lIv0`;TEpnflC(ikAkI+hkejjS@3oZ|bDH7gjJy1Mt+ z;9bpuQEGNA=u8?7o0%lQ-{Qx|B51t#;9ms2_^O>o>H{-BmJ=m7okx4DftgEg!@5V_Fhzap;1UTdsmD^nJ&%u ze_;g$&iStHpYw00oI;9uUY^`{W5s8iiljRLb>_z`**fsq#n8lDUPNnd))l8CZXCG+ zmj9##Cu1VIkfAWb!%rV;#^T^?-G5tG+6XJMLVne0O;wRdSU|x?BPQUWyi2-SYB6Ph zh-8YO56M)wCRb?16#=C8`)%fp^p%;+!i6>R!q{(S3pz*>&Q){$(Qc6QuK-2~21jpB zc;E~;FhWzbsO_q~>x=>S{s45!1}`Uh`*v-d^vu-IQosD)?qdRUP1&07i5MO6>V|tHSkygBfAnLb#vO@}07*(~G z25XUaM*&erF?Noc!IyTSr_?+$(XOl%e2iwPsjZqFx0;wqLG_N;B(MmVmgA=>Q`O#m zPJ<1~a&LbpIQmg=l){W(p9hRwVl}`6GqPG;d5K8h0!Wq#`&I5kKn%~De5hV z#@8y0AZADz~aT zw8I4oUhx#q1w^fd`uFLXMKFz!z`5H} zkXFG@s^gc1`Mv>1ifX`o|95YjHQH$E%B)3Isgn64o-+bZMMJNckyUP zVvh%37y;&<$9e_j^m{C49GnDQ?7wt(?TAw~Q$O2_&pqYBf%)-L*CT?ox z0~xJb>q>{XPG3ayJd#kK*39u6E)$aMw~9}kPXK5Csx{c9dvPA&+d8CPD8InhRc?Ge z635U#z7+GR0wZvu)#d1F!C_i^M@TWpSKx^T-}KXIoGIpUW!*IKIl^$aMuQH>$;b_!{9?%m2*bscdBcK>eNQ4PX z>`O@4QvM`i=?)6|fbqARWP0+gfoQVWI~Rrv{0W$4%`&L2STOILo0M3*bOG@qDD}nB zZ37g0l8giXr|-+3D7kxI3ipN94xkZ=#-aL~L#{)FcB!a0HS?;CQ+GY~pvY4X-`w3+ zcvNcU>!y(d4G97NJ1cwS60PK3YKx`3ARd}~KT3cS677iIok9y&MSgDDB9PbK?9A^* z36CSwnT+rOxVZ z$~<9x9M2A`S>JU)#4wD-l=V>_Cs_8w_=?(|~faKbzJjsIRt+An7648^!3zu6+A~bD( zBQ=Io+|9s_v_X=h;HRqkMeH(Fo6$AXZqF)}f2XO88OX3Lenqe1tcOP)#A;^{$OeEy zg{EVAs(ibs+-6P(GC60Jz!Qh95f=e zYJk?`Zc76gzbJX2*6d;^QYk9sXTIhMh{||L=zv-)wa*lasjDRBghY!YJv}b-%=x1U zzfCkPLO~CTZ2LV6FLO8jSPKA2l4)m3_w{Fj@E=0d&RKn_+RfzVMUVv3_LVhBve)O* zVvp=#P%5MHKRd`h?|25p{CPWHhFOS|{XOp=Cl!V1AMl8Z0q|p2Uzf1U7H5m+P}4?% z9+whqqk(rmX_pQ_)swRGJ%@7IGBVs*`t}@y09iJML=zMewb@rUKcT{CDyjeg0{{_E zo_sut_Gtq^`MNJ^t-{vI4FRndsdAbUMc&;M{xFW&A3ODCA-Q zW4Y`O-xNlQ&SN_x8)W@Up)WjfbI&(nWBdgQ3OV$q350DE#F zHu%RDtMiXF{CSj0&|F>K&FGahOu>TNk1j^Zg(0Aq~+QVkB zD`z>pLj*<@r*gZ6MgDJ#53@v*y4icQuvQ>#%}vlBk>J43arN%&!QnG|C`kjH`4))Q z<8iN(0LQTA|15%dR?3PzsEj34&DNfY@Py`?Br3sv{Keg=tz8PBg-!E zdA9>Yg6G>-ly@zt{NTNfB%OOuVO}q!3LpqEX;b2&NMD_|o`a*HVtNiSRt^FtanNWU znIuhXg{&dpaw{z5mKnZT zpT?-n=502N?k<3d$hSP@O&>T{o>)Rwyn$4T zSKS|EiuM;FuXrkg#^AXF1+XIwCAH7QNtqi;9Z!entg$o`*H*}sRcH*8Z%O`n5zci0 zM~o>`)-QUQIJ?pI;Uy%#5zY|H;kwcE!U)6IiSyx;mA)l{I6p;lw79#bmBS8G=z)3@ zQTdSLhg0%AYm4Uvic5A);Et&roDWAg|2o_+r=jRzkanE*;;XS^HwAelOUh8)kxF;x zU8L=};W~zozXL`}l;}b#NsJiE9#)D7lKa1u97S@oz))5&-kH$eFyNmSi-OxMR?fem zYB4$kVEq4_+Fz$NPJ3608X}dK?NRkU%L0JQ$=CMMv_y!i(74&R0T zux`tC`0aB_Ha(;c!bNeoT-Y!Ov(I~;)lxdpM0%*gFU3|4*8TANL?04^E3;&AIiV>X zlHn~4u7qV4^ReVIsryW1NYLBSlJRlGOH+K)hi?TV5I9Rx&)cUc=?}6+pVqN8ZJ(k3 zWheqIb~c^mb}d8G1y9h&j9;!XP3vz3lDvW+HIL))OMVD#QG6iCc^oCl=YgbEe}ZKa z5oFA;sRyFDXT$VG3sH2kx7@KPspXTRa~YmAMT@skX17^I&(V^1nWNtUc)k8B9s#SLyWDRft00RI3WQO|F6u4LH|-rYg7GZcE`_Du?AqpGx0%M8I+{Z6;1vIpV>5XH|? zjiT7$Zd@^6eZbCuU0`6(-+(4uPDCQoUQ9}f`64&A8-e@ioaC(#rHXa?1B+26wn(J( z&vP>ZWwW)iaZ|OI?Isc_W9Ffb9I)*KwSRI6S?HHDrdyz+gHh%=P2Q!fFYhc$DF;g2SnTVH#e~c%Q&7Um!`%Ze;*ctRb__F$m=XSWTUJv!$PBnx638>(8%R98()PdBbavG%*50LT+1~Fo2j_T)G};2o+g)1 ztlnQX&XJ_iA~~VQOJCDU!KB6?Np7I`{f9!o!yWnWkz%E$gq5b}7JTXbPPdA=-#lN| zcno)26AHG!p?o}9|A^KX)V@7t~@okQNO zaBLW>lu|b=^Tj`|kNq2PX?x(!eS3XKS0WHMQ8UvJQ8FFfSMf&buy&=|%v)mg*xZl* z70Xp!?Q|8HB6)E(03wpB~9po%NQUb%FT9Bb;+EIBKByVl2xy3db@4BX%_%;2YweIx}P%aA02=A{E z!S!1k@Y(?rKKpIhD^H|`RTS2eM`7M@z=#lZI-^tFhK#L>i>*QR#=!!p?#!3%4uxhE znRnyg9H$1f0aP(ll_jl!24Q?7`?601ThJH|UGYiVZ{b}|hT;oavQ%vJ8{@PmVH;3F zcc_5>55>Ad$-TGyVF!Gt@ZBVSeT`%F9nejP0CrTkCg-^Lz_EUc*Enl}BockrB~H)a z0}d~HHrZPm2k-ehlKo(j6lR1>PP^MZ2dPf?Ebr~FrqP*RRjoU9E<$INsmar)_6JG2 zW;0FII!1D4Ic~?n=rHv4SWt5W(gvZEQ@vpu1`L2veV&AuCaE;}q!4k8`?z@O8w$)d zb$F$*CD}>qfT%kk>UBQq8~&ii5KZAu5bbZdp4XXx6*Os1w@+z>({#cE0009300RI3 zJgc|sC%|9;02?G9?8!BG`2i%}008aC1VPFb*Kf)X|1~UZ7J~3tip7NyKmZ&GKjT7G zz@BL2Kwt>j^Qy0E5rQWuhS71}VHL(`S6%+`kaTnRCJN&VhE#%Lq6yNXIDg{zfj}=9 zwFw!2ech3;SbA{8|6GW|`y0JWUBec97h$1uC=iu1tcLqt$G%VKiC~jdj^C@bXlnWW zbAtUrlZ{C$?to4&dkp1NUD;Zv3H#(_9W$m4AI#!F+fo4OPiBuV8!4GgkX(qC#LXGT`K&_P zmpkjA50D(;QZ;0y``#3FZKMKXSBUUc)uP@H8lWLCcs6vNUKP37ol6HCNd8e3+iYI8 zTV;FuCp*D_X7$bh00RI30{{U*?dtpGuEfp?dF?k~00hbyN$G~pm+K{GS`a|o|3qB! zYQ)=03Uhj_6W4#EDgJVKdzfH$#N4Q!SPiWe?*e8kcgdxpAB)bL*h`W@g`#&a+;hfz zL06acV6sWMJ6m_U2RJm%rrc(957K#O1WQ&cj#X*dk>Mspsi3O=pkuGpI!1x#G@Th~ z5IezFV4|R-zExR$fMDefbQ$dQrMxqFgPPZTOsY{b;m7%%*3rG9x}P( zau}QwUyK-N0x){vKm7&VgmH`;odtCR`@#VXuN2*o0&^k?EdsOd3^mvpX)bO;q$IR001N~L7E6{ zkN*Gw1@;7$c_7QyNdw3(5T30AgaoSzcO&C()1rKjpR1pr){#2!tn-Nes%s;N#}XsH z?eMGU2UR(##eM!nxfQ#4I**fHS5?md#hTSHg50Bl(oG@+1K}cKcQ#%uaY0G=%l+6e z#$?ODf!Jlw7%Azij~NVEUR8k|LsBS*WeCt;m#K*A3!~ezc0;%pZj`fuikPji=X0PM~fa6;N=v+sNnJ{4`!i zd2bV|!`m7iueA6;Oy}&c;w0h}y;cw8Dl#P^fMC8`2KBLCCvhy*g;4pit1$+3s?vY~ z{K`cvL&X(&V_2gY?K-h5(YXN3E~D;jdvg9J-f5!1Vv#m2j(&-aQ+<`Y+Y~}9l8j?c z2bDQOYwwk&ibKb{rby<8=GdlJ<>|y5L2YAkb}poXkh^6o-9IjIjWgEqaU?)s5$PSd z$U3v(8HVMBPq@R^QcD7aH-wg4*B`rhvL}Q%)&~CW{@bjXbaULq;yeLQB8hO9LQ-F; zfrT=@inXq(SAMEa8tN(RYC@BLH9s=EjQe!46^^J&ozn=s#H}loRKe+Bl(4#GzA;?` zobVN95b0A+09!#^ACyxExOZUT4mC74AhZ1Pq&W9kG3J9v<4}%^&??8*Emwq|RGSN^ z4zmh;L?qgnf7ed3rQr2KNuy+gp|n6p2F*T9Nhiz|kLw z@ns9@IjsI5d3<4vIAX;=qpTRA0vkO1PW&7b(uO5df8*x^Ev|F9%!5Qrr~A-_Bm2CV zuU4u&pN-&LLn*9pcEx-ELCW-q1=iJ7dj>4~f~L>8x#y0s?o2ZH z<$EC1M9n!D?uYi8iK*SfX{+VDa>Ivgcevho-pcaL?fOL8UiKTkPxg9LF(GbR8@c7W z^~=!mk;b*^ySlH2IzJ^tE`Xg{>UyqwoAg0tPD6$)h0M|fZ@x!KXj&}LiIW2YtA}F1 zoQgB6?pZH)6E>_oXb|2I?X-7K9mqtE>dcFzW{))lFTEGF4HjRA`S!mm&vjiwkEMzA z0TGQoh^zDZ7w5FLN9!1&Pq)xk8s6`KM(^ybvc;2>@SAr&sE7aM4CJ>!xc#3%3iC`{W?ZuLj;9@ zKE_>e9?>2GaS&iq$lO-9glh#@{MgLkurw_fkZKN6!%Pg43O}+V6~DQN;tfBYjGc$r z-o3#V$nNsKom$+wku_AG?5BMa!?Zf;p`>2d*Xz6=I=6ooqDVQZ-mIH=bx-hyYBtBk z6&GrAZ|^VcAa?E4F6BeJfG;!S`sxPfXXFw}<_aSr7<+J&bklcCE02PgTfjs3ImFv+ zeCESEiHWN!oEs@KmZ{BgF7+I$mhenQJ%DvEV?S-95q+NiaCSRa0?b}S71Ye{kW;D{ z9-yBX-%S&qxzMY(mSUdEdJMTm!r~}{ghLS5bP_0Rp z9s0g8+fK(?ud2I5K6WvD4jJ#1ma^re_v-ct41B}-(iyOfK|cZ*{@-B(XgR8%T%b{F z2xh4j04u+)Gt=8fi5D^=rTy;dm7){m$c1ILRq+H}W1h~` zZ=}UcMY0^K?%O1Y-svAH#k*DHOhZUZfKHM2bi%?U`{r<8lg96#q4Bp`${DL0q*C<} zp&{}4rG4R9kR*WiftZB7xdP=pzc;hW@n{?;MMvadD9tX|f7f_0vl_Tbvr!JeNVu7W zxff6nnMa%72U@J2VAzaS1RwGK%F##m#$0rzf~t zThb`Z!>Xz$K)ggY&SkOMmT;#muJRpJ=Jvw#(i2%3-s$1P`CGcW?vz%xvRZF#rXysc zRG@Ix0H_-=-ycU4IW|zy#=}x!<@52U7}hTBpCkuHi}JFpSqa`T(?1giD)W*_hQ&O! zWL-+3(ZK4tM5LwkTIp%i@fsyeN&hv{b}QNRPeMUemU5xTd-PB!bLtQ4$lRYZ?q1bd z$P9VZ6+uvON(g_SrEuD&r)NjP9@BJDE7(r7f_iI5W7YOQ$P#XaMo%f1D9v{t9YkVA zZ@AXmz*l-Zm_x8_bTKzPUVAMFS zWM@@k2p-&PwPqYDPP5kuJ5>G50nnK;nI&&n*V#sH{gOWT5-be<5BH{3KF5+NJ7Ymo z7#0x{A%By#_XCJp>p5hc3gKXCe(@p^Xqys|3rN~MI(Fc#4OpR*nZ+tDQ5i6Ikac-= zxd1ah0!Y~AM8r7q(Wd1#Pz{1?5sv69Q%|w515)w zXiQE{f(^63?h441E}R>~DqY^D$TkktW(1H>k#Oj-L%9C09v-{;KjgCMLzhrU8q>mS-9)o@+JgITYK>wXm6<=-e>veZ#OVwWeSVhC zoMO@^pg1cBd6%!^z1lH<=+~`!5%dl+@~=p}C!pUhB9<~?g{yh^BsAYrLSYHwEmFO$ z+*p=GAaz)+qBWv=BZ-_*sI7?U9{faK>QAOZHb+3%0I%y`#-0r~h=zW6+Zfzf;UWNm zozsA^j?-`~^-Hz2o?<(firFe6v|?|gUZxmHiJa+HcnF+>K(`ZMG%&=L!o1IJDfOPS zIQ3r@yH$%A+|_Gz{w6m9e)yxM_KkI0b7ERll&U{(Z#ON|8G@^eyreMcF88U%Yf^HS zzn-k7kBNBtA=>QfKznEveHil~8Cdo^=a|KbQXFB000#}eE<-1OzHa9ZYLfNbNtqh}=GlYTR0TM2sguG3KL3o#X(KB{m3U)01; zgP+5pLDlIcD*YpyH2^qNP_{QRvklkAja!lhgZ2&Vyy$XPo$)_7E}IejjjF0Mrrd#Z zo;8-Ml-iW14Io4gos$Kvnz9M4+n&=xinXPoQe_io0+M`hZ#Gim>zFF5 zI?4xLAI@ypg{i#B5|LjE3nE_4bUcGL*xx-Y%}brsaPU_{r*Rjlc<>9P$;wN{@nvgd z|JvOE3;c}Xc`97jHSLj1O}UN)q5xG9Eice+IqKj}&m&5~pd^9z95ATd z4Dz&1jj@_*Tlofr*B&0}<@4HJjwdRgNbS05@9DGjHL!soT_z|)yei9J}_A|;; zwBkcv(b!)X7!1D}no(YGM{_;E8Vk$nMPP7JdAWv@*ry!9g0KNn@#0XSV5trPJvt$V z*juJdGJdg4KLltn1-7;}{-coJv~8JB;Nmp~gw8U0A|T2sB{^FTs1kfl;+iDX59m}H zl{^{RHWP^A&Xsxjn&wvR(%1x~X{n3f?=UXdn;9!3bIEF%{{ijCS63AQOlW2*!k~9n zcf65dirq%O`%~*8oI}8h3gDI7g;#dCB9II?&6wuEa5O=NT*&Q&bF|$)8jdojR|O^s z7lLY0m!631U6OHe$qToyB!X#){OwUNgR(3zWD0v@kJ{qG(<~)WrZw`s?1tegWNyZdseYyP)cPUyujpSS_C?>>~n4 zRiuI6U#`nHgKq%~O0IH1{*8_KT`cU-#~AYGyV^xf(}?X*jl02u2HJ~>LDX#K(=k4A z(u6AcisETG(dM_a97J=$R^SL%o;c70vjg9=hF%cYvN&*!lFzdjxPIIg*pDwS^T!h! zWUc!fmNZ(7D@y*%1UgvshTrsaFaXv=OaRFHWUJi_rv)jJ@s42;uos>bc_UNEA1MB9 z_^ObKNQ7`t)y}?ia0U#+UfH48ZgZ1Tp%NP+rD?Ocvj^2qZb)hTXs_&J$=u6*%@Y-G zDr9sivj&iqn>mzCC=FQkPpkK)J3{Lt*I!QT2g~LDar{wRM?Q(O15hY{2irj!dQQQ@ z9~h?;_g%Sx^s|$N0}e2Nw)bFy4n;~qJT-TMl0?0GKuSH_CuNHSt|%o%^mQp&5@i!j z*1Lh_VDVIodI4j1%Hg&xy48x9FmRB>? z>VmWQRh%OUfnf>GI(Y`lB(W865}*<#raVjXD@v{_ucI0+i*qkrCt6 z5a!?tw=_o)lVZEzO@&!iRKYEfvS+GU%0MZ!?8Kf}whfF$7U-lfJfM&aUGw#3WxMEO zo%LR!G|fJ7&^TeB-6S8$DNKexfrw{u$)s=a00W$%fG2{6tb;a)7^ygiS&i>tjHQH} zKJdC4DilW&{|&FhVhiVTegJ(0#@zhZbcV3Q`|)LA>z4*(SSApo4H2{Xe}K44-4+H4 zfqi3wrpDEl%a45FKpMwfheICsNkVV_czw_R5{=vZ4RN=V`c<;ZIn4^ShEqen$ShL) zQU?ZA2sl~dc|VLXiB83EtWO_4yqq#oJ=JT`w1@+0^N}HjaRlAom~#9y0%K&&k3byW zCA#ST91g$QB>gX4XohRN9Dw%|y%fa#y=KaZhN&n&68)o!_zdYgcszA^nP8J@(Wt-j z@8LXTPCWeHP+7}e_kEuN4)g=&_iSkr!nt}ytx%uIeHS|ciRb*3 zq~3l-f;JzAnn-qb$~I~v&{`iqiZ_iMD1H##{H2w1CcTzs1PJMQ>f#$pu!Jx2U*W>v zDU99qFAkQ?Qm|X2UWow46p^V^ zTNdEG3}zQSO8gS(5WdUE$EEejSxt}xFTyqAt;AASXwRe4#!mYVOyM1Aekzk+n(Ucz z>R@{Qr**w~?z2w#PeG4vhXjgBjRSi(^)-fn)xRfG!sS*d!^rm%0f0~fqw)=^+G1Vc zuTAtw;EqRI`X}gx9G|}S0LDE9_qupr*r&c;{_d7NJ?tlNSKY~~`W3t!GLk~6JKn@tJrR&oVuOL zn!*15IV1=X2-k_jWT4Kgq`{N+U#yKMssqpm^fNJZ5|sE^s%+)1oT!mC8J~r+v#+UO z9IdVDVZu$c|LKh`W$!&*fB_rVBV^QRjzseMfiiA)4s~wf%kNAl!CYecnnH^b+M5sx z))c6$%#-&QI!rt5{lbuc-jWu!xy}b~w#EXvRIEU{ZW4R&IIErFrPj|lU^pssnA`ui?pAi&c4J*mk zwN}-zifB;9`<~6Wbjm4|b9;fUSHykGN6*TY)49ROyuSBFkYu%M(Jdu>?4q-peq5YB z?3|w40BU>?`-kEkY(xMf3q}}uv^AA7n`dv%z-C)5CmKeL18Id#GBGeXg9Y3D${%6l zF_X~jJC5E+FAo~A5}5SGg#V~{8fQq_h-EGG4L!zl^KqXLhS30d`z)}A1+Ng!j-54rWBPf;Pa zkMR)n{wQ12!x3H(NxCzI1G-!xMB6axS( z*Rb|2{s0?Nq=u+5d?nxW{*Y6Ivu|9c7HWjoRd2=UTqd zWrZQ0Cg~-;eyiliI00@7UedAkzFJEC0O2>FtW0Q_`HBzCy5Q_%gB?W3W=5``TtS{?2nBy4ZqUc570Heh}lc~#}VvJ3i zqbitMpv-27M#aVg1KJ+>hm98vTDfEQ%V~cMvm%ndnV6>NC(mT?VO=ozDeNp`2sMy~ zUq1h!TvDepx{0ywjy0ejCe3;*m|q|GzXv}C7ezPBqLQTIYdu^BrN`7Iscx18C4`c9 zs4+acZPf3tA`hAtw4cgJnBM{(CR;|(lfWD$hH0XbF1BQoS7!eSqk zNckO&m#Li%Zh`6DnK^hro{eeSR(0VTCEceBbWD|-l^9b%cu(-fB(G%RqR}zm0SSo-8(`D8g#4>?xI*WCrM=bua}QQw z>0T?ZaBC#EeL=)$9iKEuY24h9yW}v6kMr|1ufTP>0s29puV~=39ZMM(OfwT0oLZdz z{TroYChuJj@po39ZmnB15<-d*RI|>6V=%|r-_jZ|LMpwma9AzZWW9akt*nGNgEpmO zsxcLvxm9(%!~~Q7*H1@C;e8BHBz$=F` zRUXv0(*mLL%IuPxn+GbarH3212(x^aOava1t&<_<{LAB5$J)YP zb*1m)lu5$%T7O5Of0aCMZdr>JK3^-PvJR>ggU#&>03mwe%3T22z6;1finrQappwep zLj20%Ja+{kfV_hJC+`iIZIgImw;*0)GP-8lm|y-b7zscrV1Cns7=8bfyQt zifMc*keSY-4_t^qWXB1`ba-K}k}t@vsOSh-rvtweEGaV<_Sl;m8g=fs&1)y-Y1r_! z&W@Wr%5FeUr-wJ?*ftOmrJk3|8kn7Ei)#7qlZY`e9hvri zXF_RH_{PO+6N95FdgI?Id2|h~aD$wLhoQT;MF8lJ>J4;77M@a;ocF&Z#$H0$Zqz0> zo?9L*G3dOG;trCDm12$QvQ!cIIJMbwrQZx1w?QHl#1P(iI9zX$HlOVMqJo!CQg;V8 zQEhF^J6ZhIEsX$4A1wG(rq>gvpmRn7HKw_Wip%xEH>COUihKUns}`zpiXo;I7q62j zxrqwf4>=95a2TMTl6iTT{I2eDU)1%EHH#cl3vAuaE4Td<2oy485j z7KSM}L{V#Oyfev9GPVb`S^@}8DQZ{>i>@EnUOMeqRM@@7frAdf_=4;X!O8` z%{A?8Lr=0b)89_`R1u0Gl$2ua1ra&tpEctU6K7S|e7bxgXFV)xe&5y$nLBGQtDEjU zEUd=qjQCn~><8IOp48A$Z(PuK!q+UwJd8~E_9l*UxCnlP1V>vzmYDBm6=1{WX>K%u zP9XnyJY(C$ho=hEm)rXG=owmf?z2Y|Eji0WnI&^VznMEe3wi9~eJv>;}$pTek7Ul)r;19P@@i&sNyN#i6oT6(F7e?S> zW4{3514Oy$fk=~CGBR34Uh_fJD8>F@D7D-K7TE>X+==#ve0qsb*H9DOnbtGB_-53O z*J*=neR7Uqq-`NdqvuJ19KsWH(aprC3TKLBIPZZ7M@wcJAqyc@u-@q~5zyZ!fB=a$ z#%R^iEq{m&7b^p_hQ@f8)e0?d+R(2~N(Sgk#yB86f-~T+D(4Ym$NRZU=oh0?VH2h> zyQhk0D1;Ob5&uAt)HCsD*2<+taQYO(1M#9`7+W5>LAZWUXO`MEFgp~AQn|wbkq8S@ zf6fKg?t(NwdBV|UHNJGYHjBWYpuyR83gDGK^Xe1=2ML{idnzQW1>FA>x!|DJ-yaz~ zFc1Gj7RZ~30j-JX8VHD>i~6Hpu4%ABGOzJ)AdH;OPQ>wekj<{H9lKCo2TjTh(YCdY zPN?6bhxJ_^K?x@DB<&#XN4DRBx9a>T#TJcXO7p<^yFB8*o%hkYsC~Qd&RkBS<*Ug) zkolmd)B;U>2_)7-50O0y^vXy74~_h=N@bZ$68G7bq7jG#n>qw=BdTjR>i4HpB2X9b z*^F?~6a34NEPacgi_6~soz%ACML`CaLD(rKT6e=>#$k$DRc9YGp?q@8tHd71=9~v; z(1UNJ*7$sX^YOLh#JV$@$Dk`;vK`4#o?sYrwH%G|1S|RO+g};0RqjHcM?#J@XeuKI@J-@Z7Xeflaa+*O3-~Y z01*_&5z1hck|8q<9!Lqa5JfR6%xb#1Zzn{$Feq}0cKJD{E&<5QWo>paY`rl&GGeu; z-BX|;@31cFjCY2uz95pxO`$7h1|L*$9kVBgjQ_A=uLA%~gH@RZbmkzCRKWioj|{}W zkp0i8#86|Ys0iXq15M+6yC}u7dh?i#!&J7yuUW|9=!kacl?NXPz!GeId7#A><#h*k z&vRY<;^K3ygCQGv#fHUOF;ln2Wiwlvg-*P0MS7WxIWy*$sq)(}1aT%6_5rj24Rt7^ zI0$qhe`zW_wUb#)@eqbnuvEh}jc`unA}|<<5^|L5Ry@`RW82!sjy(S5lxx5(zb)b! zXXO-5?JOjKgc$gRf-JBZRF(ji=g=LVR;%Y|8Udyh0)CHVfGa8<7F^5KFg?Prkg^I= z^7o}c2l-_3lF9!DK^y_G`hHf*kj(UCz(PkIZTAadM9$d$5H_<4LB^yXBW|n$@n4p9 zS8tD$ZMmK5OgT2SNW^`FFB`sgY(Nt;u#^Y6hqKl+@O&~LuT;dD-_2Je$}SmzEW;=! z1+U70=g_M7qBl6g?7%_*g)>%AgKZMDYIW36!39?wJ3+43E0{FRe1|&7-s)Q7)XO)d zXoztb0N}&ra8hvVS7gHIZQf(feF$)|#qGDL;8{lGLR^4*o)=1&wi+*B<^z|GJwW9% zr&^3k!eoF-PhYQPaD^J=B30G1iRE>#Q^Dh*<^TYhnCKW1dY|zGFuOU&crSuX+LzM- zYQG6p=8o}A?T&nb+YwsP?XDZ=tBuT6br~(ZlFC~t~TmoNhArngKev zt3VnV#g~Ll{Ur-LBJ2knx6~I5M;E=kfFL zz#30>6`zkVtxyqN?4<#^1Agkt^Kq`;+E@k@xRF@j!2lF+e}Di00%QT67)?m8000

2Z&iOqSRBU!8B~u`PC$6blZGVDi5M9w?RB-Bd4M-Hpp>J`%&+yrkqwLj zui77es6FGuk0Gx_U?i&&O1YWcdD;I+w&0&MF( zbF5#>h{m?clqC{}0RRsNc97gN1|f!;Ztb9(Ae8E>cUc3Nw z#k7HT7eSD$DmK~A$dfB-N_XlH+AOF(L58DY3TPm@t{I+(hYBy}+sOkar@OxVfzFyW zhV&OYD$^A3l1mdj!g2Tmw_dG*%x`;^r987LL;Watxeo9c+1}L@u{}$n2=k3C^(Nzh zFUM|GnSTdmEucO|O{sV7GE)XqBr6t^5fv%M_r*Vs_}n!xrl`}1d*i|S__aK@*sM_h z8Z$KKM-jCeG(YhOe?=N=g+A6;2w7X_t%l~Zt8o_=Ab59nX+jVY0UgBQ84n} z6_~vd%Y-Ft(${CkD3FK@F7mFqOl?ZT6%JXxEwm_+F8{h=LaIS&VphZ8;>>k^Kti*N zFC(PpfJ|WL@H5ZaHlg<2>K2z=Q8gz1GT3}hni#h^h0%1r$o*w=9u7fIr$wSumU!Gv zY>9Zf!{<^7eDaaMk-!rU@^AHS)?-^mU_|=11WC)oI}6n>cA7}I|^(>v=^*3 ztg_&?wYeQYnh zrx%Bi6JPhcWR(gR)KBTep2r(`w!%<9J|3CwDewZ%*@`qxF_5R$hk|_bmF#QSxHN>- z#S`&xg`o*(3dFQr4nT)MdAV#!!}AE2kmdZFC;xUyIQ_V@>+Qp_;6l!}fBrW%z?;)cKe5v;-Ze(WQg53# z{&&S^Lv|K8J~{hd6lzQbS+fq~lO#u^WZ#;nQBjVl9?QZ{M9NrHW_B2x^a^Di1enS> zVCj;YwK7{is}?cF>FN8U7*ZBS$KEV@NYo4~Men}bb)W9UL@Ju}H`|v|jg1pOwYwaD z+bfB!Mqm2zaFo<(!YsDZQ^YXZH=bDt6AYYttGgX_ABgPETiR^Ah$wptPjHzoyO9w> z*?sculJDiYFS(o;?v;LD)sRuDEPtDeKizB{Icq1n=-1ti7A|EVtT8lVEo%k&N~dxdsq9;YHRP%$=W0@HmQT!gPI?Kt-U^wZIyI+DP#yea8HQ8 zh*4%PzIhob`=>8VHiuRDa0|XBT6MG{{c({n|L(rz8XwaZA5sFLdQ#)G=J-gfT-|&# z#B;8WBGzxS((GODo-D_piHzQNTvWFsvYl>G^fUhDWTZX{+_@MfVY`}eXUh86JOorW z!1-zGnk-%#u+Q*@dG>YFIGPtj3qo&fFV4-YsFUJosYZ!@!?1_VLX{i*(CI@Dz=hUJ zL#*E6y$qI%41Q2s+ys3KR4ac19G$J<^jmr?8epOTEOyt-5F5N|hC4rY7LB&tVtV_~q;gK}3 zuygPs2HFGAqGj2kowWcv`5NW$c;hc?W`737x(jz>ntDBavH}O{1BW3OU5K^!;_%!E zre>ilhjjkvA9N0zClXl`1HMx}5YN$}@iv?vqX|4b^x2J_;wPe-`6OZY0H&?j+Dr|F zl5TEgjh)G(guTsLuv3*iQv$tgXR~G;i5`9M5Bn#%`+ZSPidu>yWdL<3xe&1N}CF9>kLwfY@H4ZMPDG-Bx+dg6OnGn~lY_Sm;th~!AH}_m@)i$~}Ii&qUg$K;wc0J41v{F%TOx3II7-y$+SL z=P`*(H|uyj)i0)wgfMp`&vq***Y_!!;Uio9Xl>UZ$K@D(8NrQ~e~jQ{Ie7I)mnZNg zrn?w3ViJ{JXPy}A;`B1UuqN!b4IgEg7a%zsHCO(6jc^Rt?)Tnu<&XeK^q0;t@A%Nb zPf9o7-!o)|sftiWp=q0H)mCZP$TA)ORyJ6rGV(nD6e-n46AQzGVM zER8?`2(*ml#$A#We>XIY9;ul{N@&*!>eIhZ7Sl5(@2TYQqVMOidkW;p_X?4LulHmZ z80_RJYc1=chtfoiKH-wBH8SuKYHye`X&JnjUC3@S3#-Yxb0GpbXPQ``1Ikmz;YHeY zcTi3nd;4?OqdELcuVZzq5qq3#J4LR2y12=uh2*qkGz4O+%K1EL#6{?8#RR&S`@b*g z$+wMOJdm+mU^iCiXa5{^0&lfwbi%5lDdFdd{F&1)Na8kf>`+g<4F_*kCm51yPGz*} zQ@iuGf;|UkX$)A;LyKIw#V*40Jw3?ZQtfXl(=NN96!2*2$#7U24jqKp&br>E7E7`y z;teJ)%etmVGYG?sINISKM)crbRalCK2VrjdC@KR2M5rtD*IN+jGCyeZ zM>H>B>iaEw33FdX~(UHPdel=|dH?Lr=@X ze?Zw0sD|sr19=_M$F1y~onQf@b?mipqPNFWtbg_UxFn0n}?<&@(i$~9*10|7Q!pNbrC$e;rag^gU-6My~+QrGEv z{!&KpOyTE~J6--o>`9~2|Jl@sls@3Y97S%8;ANiEk#%RJyq03VBWJeln~}K&jX1Ad zffavbsmU#LzCgSxHf?^)TDHM^ElJyfa(ICPI-eEr=F2L*<3_aLagrLFG%+l6n$EfP)qSq)Y5-E3tfZl4{Z_6$wynjo7{zL4)pXte2m-Lveakvj^GL}5 zE-mcYccJ%OEJkttZ^I!1>$Z#q=Ln^o@c0ZTZSO|__J#QnatM1|Fdy0mu!{<4SmJKG zHuwFthW$uRz!Nm-`_@bpfmhGOK7<<-J_7`66URni5ziNWI0YYE%Y)3y^BlhFfI)U) zNbJZkZbTsBOED$^=zZeh;O)|cwp|2D+Z;A?7&Y0N+V>U7hMd;Wlug#7OxITnu-d6B zggaH^-*AmxDV`t13{O+%fnoF^?zg+p0R%CLkrivEO8MSlC>vVo%M=?U40?3nPCOk{ z^@h>2WUj-%v{sl>t6o7L4GS^UrcSX)$=2o?I?>*Lgzqekfi^S z4-w4k_zlI>XZ1Sa;r>626g>d+oWH770AQF5E=RVo-$v6h-Xwuo0|Y_)(Dl{(w;_GK z@2KCXwp3>h;#*LLDf5c0yC~G!+eN!Mt82i8`Ggh0`*j4(0hTgMC_T@k& z<{R_PdcJgfe2R~^=48QO08PnLPpP~#OI}Ra^8y(%QfNFdr(1n; zIm=^d>t?n$68T`@EBBODejej#m7!Xj#hMoV#BJSJ8iXpkH1_c~5S}y1w;rL`?@++% zxF@}JUV#93Bgh`%QLv0ZoStn_c<%&7`qO9>>uxW&A*3j0-+v@Xs4D|%a?0d$nhXe> zm%>@}th=v8Xd@CJ_*`pBLxrvCHD%W$XOHVSwY}5r_}Dh{CsKq*APdpL$ zaTJbid@BhF1_bvEhxbyAAngC3(gYN3Q`#@QyU|+X<1Z(1^krK^DZL8$;0JSpJdpSj zRy^%5uM$%mP?AE@GVT5{(f>~Y2CfAR+i1aD;;?E>@0WJ1pxfb`3O(Y^&5r9Cye@CN zum!&rGvRA0-I_&0MshqVMC$tf8OLtmbFGe2O}=cmiF9zCE+rco;ht-69Rg^ecCq| z7@bsLO3?d4Qj3_&ahl204b}z=b-!q_ZI>-*VGC-q^yS?9RuyI}^mrS_MVwwViK=VS zf#sKKJd=P8(l923leUxsTUtYV8nFBBA)P1?zA4<<@S?`+gt@Bn4_D;=TQ>XZbS;W) zJZ!h8XS#In@cq(t;B!SWR1_w(*S0_QFxfCZUP`*2Dfi%Cydd2%5@EhFFmit*muQ?+ z3z#dfj9H8v*|iHa^&~yCg{WS4KoI7l%(g(OU*}jf zm4J;T$)Z~TeS}c$!Mph!g6}hcx*C7aSwuC3C0o!@(j`UD_5@e7S_+?@s9(fON!+UB zDDxgjN}N^>jFt2x?U6q1?R_IXu*tR1N6>b>Q`_8*#*+S-z`%@wH`pRMFULLq#4?CN znE~A(F)s4<@y^%V4=(JiZtTJ;6&279SBk-|EolM)TLyIr1q9PGh<9spccInQP)e|N zD;s@aXDksuscfHP$M`ox5pg2IRrV1OoSJ=GCQ(VPX4rmf;>|<955fj``CsJc!R_sb zo_rc%pMOYL73WTFbIbX&_N@M#xUj5I&aGVFS^9z`?va{4ZV3DnMY|kieAqFz}8Ht?wkB|MM;n@uLdZOzyo={-N zTp^V$T92&zzP5nD@IsVAi~lr7nva!%#5(coqgjo^O}|1T{r5s z6k}Adu#3n4tIv<}M>IJ)%h{2l`l1=s{fcAi%M@<^t-X@GZ-Kj|024<-Q6a6d?rL&i zBd-p8RKq|rT#8xzNl*Iev zt7Kek8EClm&ZOihhweib7SLe2$TvNOZVn4`YG3>;uwpeI$#Ny@CxF5AXL3 z@yVdk?ersc+~GlO6FYWksl*$Z?=hU8Wp#M0aX|O;#gVDrS0&J$K~z0KEkzflTE-|m z?y<_=en=AzE|Q~v+gv-+jXNjri%?y=T=<#X6zzPg@2u#5Uc@W9ddwp}BOUT<0(TBYM0>qAjJAa7I_aO5=1<>eFgO8bp^4LK zd0jCv*UT&3>*${!DRRdceq`}YT8{*FwkP?mP*;5&m%h9S=KL~ znsmeiEGlmQ<}l7eAg5{z!OwLI;WfnoF%@U|r7dl(uE&5u7nUdTflIIq5J(*-p4e|~ zex!D94@M#ZS&v?~9)I7VRl{b}ah_9a!RPX@rU8qQS-WZj5zFR>*S^FU?zO`dy$f@2 z$NpmYq=WYm^|^8fsn#Y#L{^ZNlo(5VLT3<%qWY02M!ZF|_u;2uW)0l;7*5OTCZztj|ceRI5w5i8C zyH~8i@fCyU+V=kuMO}p6Bgzi5nuA)cLwL9YZsGD~x%}*Qa19A0c9oXtK$K(@E6uq~ z9dM-ROBodUG}6qqH!g$b5QH&ioLi-(O~7nCgMc3*+9eS<)uehLZ}XTC=CDIMyipQj z>}WDtxfVoNgC2dL(R*X~Lw5DtsT#T+h-d)yvK}T;7{;s*57q1@O&KN|I9n&( zV8W?WQslyGuxeWtGn1j;`J5qR)N4jaJeO>}1yoy2^FMw=aCevBPH}gK;)PP&-KBVG zaCevD1&Vv|Vl7&VYq6H%S|~36v`?S+eZRl+KPM;I-I?9_%`6BZ`_3xH z@Xm|7dviOrA~q(q|s}}(R+|YAwx9oa>v0O_O$Rw#u$IdjV>;{ zd$afpMP#yMt{%CZw9aM!Lwd*(Hhf#A_>x3FV=(?;XFLipOve*h%0D2y7?IWqRj|o; z2>~#sZ6e3r`csNXcdMw)ZSUQmMK;v9j6IY2#+^vC)#eiZ86wmDWC^K>6CyRPGs1v2 zTjcPHv@7osr^tt2L7?80xUA-LqT5}NUdMr527mV(Sy`Q!;ib`WOTB3PqwlJ3$&C=w zpN~!TroP|e%}5j;*ZyFN#lWzun`n^s+OFp?IwqO@ z8{gZg#!`pM=ey@^TML;AlO~`w^a`zB@>#cvRz`*J3XKH{tDu-w`Xe)&!zvU^Y6Rks zGn86V`bGx=Oti{GDDL-^I}}Ok3i}%tNv+**XbANaW@pm6mwY*z#jM-{ir_C#NL_Wr zAi3|zk9Q^U42AYscU0xzC0aF|Rz$d^f2k>|UX(i$5apj#DKB^Scz&R8k>&p~TWuB= zoYwR+GWsrKK-EVGncpH}iGP!WN%J`7GU$z7ZmFkan1AtUNy{e3;Ryb1>eJ!PdjnS2 zGso-c(vzpnR|=cHc85O%i%c<_q1;Cqe`TiQ!%92$C* zc8CoumO1(^zD&SKmSk21=pK*29^?uvE_Ef$){_RaEI=%>g?kuGm|K!KGn5x7Q}^O%bWOZPCy^@Xk$A;;f^uWM%4iZ#XIQKA zdc(~C%OTe%;G)3uF8!-wZHvNcYQNrI5HP108goTFa(;`1 zg*et1n_c$0j#JUtmFJI!{PfE*da$obzL|0=k5(;U$?aM!bgTL&@ppx(T|LBzI*Xb= z>Q6o?KkzF#$la1ti$ozwqJABlpdOe&vC=9Tm7V&8YrnkKbz^?=$kO(j8he<2TkDB7 zlgPDoz2#SX+KP7}3wt)R6ST%`Va&KYpSZpr@qT*SHc#guu$))M|0Q#IU5fn;L@90} zgx{A2EgO9*kXg=EMK_rI=OKPH)?nzwzzm9u6=8n{*Hfl@^mfE29t_3#FA4kFgE!Yy z>lv2$>0(j!YFMFOXsx7kL-tUa4-Lfu@{5TQxjALypfBcT2$N6HJdEI3FWXZbz{(;?MXB>=D48fPDWSDkbMF-9b z8uyFD?AfejQbGwin($U{3#|;Vi{NEKowWolsxbekVwPM*-7&#dm41+tvD4N&sqyXB z3dh{(Cq=o-pBoOo>8dBacWlsC)Uin{T)wdTQIbNQ?y&T1CnW-UKJlb%~PC0EI7bW#e203Q$!o%fJ(1I>?LE_cl%=Y<757v2iqz4 zqLJ!S=^q6=p^D~llv^= z=n)Jx|0FV7HhEs)rD~KhQ-`I2;n~VJc;CWEiNpMj;Mt^XtzZ)nGgKtbNNqqPzY!Cz zQN6D8O(`1P>bkmk+Ml&DlJBQ3Sv-Gx?&p92F8sktIIZGY;+o`!Zf@!IV>f{UODGs> zJfhI<;uSTH(!TVA56WRyGB5qv?3=-O4!#+Kx@P0pXpE;W;gEQFrp@6k%lc2$$^#`= z6El!3Vnn;jg4dFgN4ldiwHpF&7UP9$aC6ZpTRs&BcG(P*OS_bZ3hJ8gkZeho@q1K? zENMilveC~!o7o#5(L-I6iK)B?o9XVp3MWCA81>7u7K>RS-qze$aVKWt=Am$eI)_px zp~ER9-N8$j>jmp3^oM@BK`uBxS}O*E8gMPk8(A%37hxqDnQIeoiwG_0&}JOvR&O^6h9jXHA`8>4X+bf1QGCdZ?193-iZ`t*=s0p_#wQ zH0Z;A^~yiGrA5T0XgYGl=ZbJz%F7<q(_r?=?aa zzU*R&@Iy0aw&k>a1j>{MRCD!9^jiuEp}j9AVK1{>nZxK+uQv5>^sAQUO*vHuXE&st zoPB`LL|v&QqPPu>kf{x z6CSLdLhY7?PvlKLzEF^`>h}_d8@s*~t%|7sB*jOC_ilEr0}qw~Zz7HK$W^EFF|j^m zv_a9wf_d&ixJvlinJL8B^r7o!I;+PNI7h!8^iwz={~mu*VEa|MbrEGeeSzREJ&J&e zQq(L=-3H-#sDf}vf3j!3U0zi;qu=o8Hy$F@;mtWp#u$v@!l60s=e3O-RD@FBqwA;Q z3K@qB8sxzynpdBZddU+6XA_@dt@S1(BNOHb3$O3xqk0Vq1>@LLo_e5C z2>K(=7WJp_;3J%v9=pw@i|(RBU9uzc?ow4$s>OaDq6xgFf3H9r4_IS!aSYie_b)Wu z1iP5aJ3Mx3!%1-Wt!4`QDAjy7nakMuc?gv`h^oKdCOel>+U17_5l|p#P9lfgJO&3da@8FBrHO$S-ac%) zKCw8LdHHqH=uW9`sL?>t%zlc+)5QK-{RGcb=c;k|lUpN#?9mJAybV^+G6zzv$~Bph zQ6V>8=L+9mS^gD~2VQ<1w2KmpC{7A4UKt9=$?@x_t{$FYKDTdh&glOIOk{uoFX-gl zQz(r>cCa#j)RWeL61J(UhMJ|Wj?#;Zq z{s}6ZHHuWhBw4sb%mYi^RHxb91BGz*ZVT@S5wVIh?gPG9900C!IYslNcbBgs93ak5 zR$i6q{oo^!(v>i1SmhP-$V^3~?ZvJ#--x_WTV;CIaZizq9;-oj`N$};Z=%vMp6i&4 z=5TazTMYXHVC)E9V6r>$y8?)@=X$~qlf0ME2%U?sQL>xLF_`?UIVR#5H#fMlIns5h zKR}AeA>)WM8u}V_&1jK@l1{ldsuizLZ31q@UlAZi-T$dC@@Z0p z8`66_o{2`c`UT@xHInMv-|bpwm28DiFu~d)=(PJtsqfrAB;1o>$Q;YGO8(45v3VJt zigPjc^xOE06`WM!?8RK(BV9>jbz6)a!+snBKC?yzuY2H2z6;N_~U9v(=r2#kqYm9 zr2FJVpgb(O=-f=H25S0e#}D!HLcI}R7EVF8TV>_&UO#|hTACY6^@a!naiPLlR{QFy zALSEY{D4-EqrE4NviL@<(q9=|QAzvE__c(8<_t}_bx+qKDtHL;XrjtK*V?n1m5|lB zj9AC+$}S`cZiR=Z73X=rTMsAz1O$M>02r z?#V}t65XUDaZ5iOdxRgwAG?gwT#%+iQJ{|8!iZre71{SkNq699-UK-=MqG7=7N1c< z$cCG*PaSM>Rbp&=giMlJhz@Na9HLnB%r@^AJRKhcapVBn62xs42JOL3KJkD__9W*@ z)3vB|$%fHdA>RP%k&Xm-GAH1(*~Ce@(@68w(R6)E4&LpnD-pw>1C%Xc?(O+a-it5R z@M?8vM^1f|qTUeyJCg2XQc2EIHtOZJuYEfkVP>gt3|)8*zwE7E70w2p4`;j}=7m(J zz=f~sOJ2tZ2;irThP?xxpro=U*EXo8_;g=1-Eg@e zC9$LuyOI7Y88W7qVlVFzT3EKSXX(+qW^yMxo|4e5cx83A7`q#gW7`xdP@zA54wz%A z<1Lq%WMmhJLNjt(c3{HO*Xu{&`oa*YcD=&!ifrkFwvhKyyI!K~CcT2!iz##Yc6Xr7POY|AV@Ll``2vx0hdr&d1a$_p|d6c`0+nZqvaM^9eqStab1G2$O za_R~eFq>9<4S)W~Wt4)ubu>%&N4H0;XNdSLW|yo*8m}UyW{z&1sI#?%g$_zZdfppX zbi`(e9@V%+%PF=P{(2F5W!|xsI=*4{;-%5Su3hoF*RV$?WnF=L4EEVjfQ5j!N?5o~ zbXZ3}cx1DP@U#!Hek||TZO|&#o{4w`e6Op%#+>&Z#X+DZqvw%+sepv;xo&+-R`T;x z)eN%LOBw0}YdZ`K{u{CPoQ5Y&MvByG-_}d~$*@zpE6lN`IVKj*nk)vE$*}b~IrK-r z%Z~d6C8mvYeRbk|82N6*`o>OcP++@dp^!U;ewMGMtb*BT{3usZH{|O$$*tv0hpDeoYDZG1#_dOLB(L0`2;E@l@tz7_Zl_E_@=q|2a0J)hEB*)8}FgbKNp^9Y3%q%zXbyEU)AJuSuMD*TmoyG{LX@ ziEgUE%2&6CO}-JcKp8_9?lfrmrao=Ur-Xc6OQnGxwx|i?`I2q-EY99qx=XTHp^8s! z-Rmm`{sjT8h;JP}(t(2B7u4$`)|+HHzUg~G6gAkt0AV+hYd_DLMvHyOl}%2SUv!_t zaUe4p@cdMw9-=0xd0M)xN1E_#+}91=u*8r%aEe=K_Gh}wM>-{$?szlt2)5Jduw+v~0n%$w5H~M7?+sM!T-dr&jyFSKEvJ&%)&=<^1;+(NQx=W2f z?+w*}gU*J{H0l#Ri5jl1@)&On#x45(K5*KpERZ9X%s6VHj6*NN(r&%<`ShB2XgxOC zSCDH=;ragM=Y9&lSF0OZd+Dl=MQqI}oXHTDtLt z2L&qQm;|p*PWQ zd{e6BiGqFWzcU7ZZM839;vH=7PSHR|OG)`~s5FfiWxTWScJHdqE&|s=&`I34Yo+zG z(257$8tH%w#uWN1QIpdh6C{z5G@yI&rye=pCH#qPmdY2X!z=E#W0WV~2jgIWw(^yz zxaj?UT{9s`ZbM$jZc&;p@#I(}xg>8=ZhlgCu1SRLnc_=~(>&kH?`!+-EWD8SF0Ds) zaMK-;7B`vlzAqSHx|3*QzF%q~4K0#9yRxF|zE9#(ixUTQR>_(~C$xAz6eQt|fG1Z;FXpS$pSTc~;fPek>sLouu*1hub+ z>TTtBk8MB%s?F#+MNn!GHwEYRQEL^4)(b`DyQ!Dow~_C{&bJw)8<9=qii9O9bqFR;t{MK^N^0) zB~kdk5gU0uCNEv?K-gLIBf!o5e*? z@Z_rI2ZTN|7; z{9;nUONv8vew*D;9y#RoYtf7Q=kgeZiQ#i&R=HLWNO1F9rLs0NRk!yRz%_NAWAgZ( zYT%y2QvbK-sUKI9BJp^WUUH@=?{s)cX`r$W8#BlVU!&YSGu05G@*~R5sYePeZ-rw``&_FcXdKla2%< z9*R8)s?$R<)hzUr!it2%H*^@>29RG)6P@NF*RQ;?ICW0X`}K>xXouiZ&Dy$@ou7H3 zAFkf@%-@vghnl+ZYtE8-|EZfm;G8Hu%s(W4B57lA5dLh3n2l0lkWNVIXOiY_ILcuR7KnS*ka?UEUzW-96jUf#6Y$SKcc)<*D8<<3K8g zP0a^{s1l;6uX2Xp)Nx;puqobvYj!yp5h89TX8`2^B$Bt>x+4Y^Os^8--#4Xj(W`dK zYlnXxq^=}YJ!N8IY#%g~kl0i6hlYKv3~du)LZn3STJy23TQp8aTg1KVo_Xj(u_&l*&Z*B>l$eW*Us1-Ew@%uo)%(`l zB_Kqm1?;Mz`tV6%k;dbX5xhlPBGGq!_!U=HV~btfd73$>|3d9`lI8=^)^U`#9Nky4 zMcZfJozRDC2~BYtvK#%UT!lZEi02zBex!G(AM{cIsDo-A*HJn3+MTTZp3Zf@nF=~f zIeI!zPhjw+fx($35&5k(($wa4lxW_#SH(~njRWZpqlZ)NIRc}uR-H!&M0 zk}TywSBl)JyGDv}19pSH3HReXd_m9ZSZ0|=96HE96ZC{e6S;^EJQ(}%licTvHl7uw zOo++({R}{2!rK|RTaID&w1ZF7*RR-n(B$+hEF<(4AmHJvi$dH6kt1VWs-K7Hk1}** z%}ugu->nwwtm*u8q(dY7=4T^bEN1y@m}x(5G4xYtt%KJA1quUlMO;B_BUF6UKK41jby8Vpf~Z%1>9BG%gd~k%94uKD-MFD@l8boH67| zpN$q7LF4yaAmSS{gtU|9QwDT-mf5Ixy8GKi-MDm-_7yL|Ue(O^wrKTe&U2AHo<2E) z=LwVp?v;j&>kd)0g(a=JGQ4oR`ek3Xi*JPIGUYq04T3OCIi9I`P~1rd3L+H9FLSMv zHIFvgxQZU6XRtkB*tKM|W$Zd%I0aWx;%T{5MOm`y3&+uovQcFExoD|wQW1yOgi`)+ zfWRrPeByK4ErY)}?op`s9W)2E(hzMqNfOcI7;%}n#pB(-Dd5vfmT$aeOaCXTCb{TK+S1hbxeBv70S%@}X~3US zJ_{oH2ED}Y%FSb(Lb*sb<@Sl0m3dc${g2rl(=Uq_?KV-*Q4%C*OZimHt)r~y+J3yf zVB6OU_d?k9b109 zFgy$I&+{M|K#dn1EXaOG=DkR+yF@O9`O?GndA|Q(JRsmL@t(t*1SjiG~xzb@de zzt%#pl-0)0J;04Cg>A5%fa+W{ZnCO7nJ~>a0z{YY+--Lns-e2xN)@^|;A}EiOV^C< z5l)wFu`SEz)Fi(d-Y4RamT;+1JUb_r7W7f@`UB6W{KZK+S_3JdfnqFSoKRN%)XFb} zPB6Rstyfr`FUe^FZ9!hc#ss*;M3hK| z?Xbz_v%WW86e!{{qXMtdTAiIB!9Jo#%<~&`$qh*h1Su7H$pyaB+;(=mAzp9qjN7il zedVxw?J4H+3KaBK=wzc9l^iDt=P#{!2X3C6+_+m#-u@~!=wRPcbD~q; zJZkA~o#uPb%A)9mD}H9P>yuG7LSwPl)gc= z3^pk&uQ39rSeQ~RU-JNCny~5o`Nx3)5>o+YL#`l*rR@3DpCCsC@-KE2|k&rT%Pxne3!@C4uhNh)1w zSz}JNwIa`l0oB?Q20LhzJ74#w6(>ZG>^EC>i+5pJsUo!Xio`@zt{7}PHxALb^_6U4 z#?j8$*NL_Hh0hq)0x-UvohBz6<)?k@$sKM$Re&X_A>*NAx-0#usK0}T>xM%>UY7GV zZBko;>cC82H+17uLX24Drq1+_OV@m{l@Wu;RpYd$gsSJ{jtAk}WR5aqLNBX$?FL;( z^WHvbN)y{RLVS~YOr4w%Sc=EVpW}dTex5>@2RgK47|YL$$_&rB*Zh>_B1U*}T$x5r zX%{cw5SnBIMtoo#?S^o?AP#zt+4P-^vE*=J&M8_r-1kjp5Y8GpmnQ9QMxOk@TIeUe z>0MB3yS?$UU>AqnDyEO>E5|1Iy#?*lie2&P_uz*|mx{2|gTrnL!#$ zoW@n)bHpq+Nl1kqRQKI@@xZed*CqifPEieGZn+=5Ef8d>wIQPS*La#LoROUy#FZfN z{wSaOJIF|-KV8IYFyAIBfk<;G!(#vT1MZ@Ov{#7KLkjfzpb;)zVQ5b{Zts%;V`4h| zFWaH_&m>mWZKA^3AUzbRLj;RzeqYJ^J}aB_tj)jXIrQhHO&dVsc7H@5X{xS{RQ=?{ zi|ts<0|D63E%!p>!Iu$&}c>8e^(SPCrDH zdf0mm?VItt1Ov7YrZ8f3T30#QQAzFBb5o4##U1lX4XP!YFP>0!q9sb z79h$>wO0ex-{(ACG=+M?I1^_F+V$czXQ-oo@h^Aq=cK-7 zIt!e8UVHdy;f(7`@?K~b9I;L5-oHn5t~-an_N3GNnP%|~?MYJJ+(%sj z@R6Fr5m2Mnz8$N>W2B@Vo@0DFd>HLz=u4|%4!C2>W18VmZ{d3BCvk0jbx{VlTT*Y; zq3N>5Gxl3OWhsoh6G7(k6;3r3RPs!H(ARs`P_HM0asgh7cC(>-p6rpG@4%GwJugeUiB@kU7Rgr+xyI&9JTG_W;_Z+INHzbR zyjkddallfwaMeB0Y4SD$a-8tmnwCRj$~@T%s$iBWtGDlv>X~Kr&O1Kfcayz?W-sU6 zOALaT&`v)jFt9+ncg=JX0=WoWRa(zV$!ZE#R@gFvAZKM7Kv)ng!y}GcJvz`5b)gJH)uE&|=peQHg8NpOsmgO@5Bzmhh zUv5?D(@r-*@v)ktp#r~V7nb=FWQ_y?{%mO|r1wB}K{~0hZI2sG!6tb}A@>_Cha$FddoQ(7 z0L#_T_Q=)Ts*=bvB<<(uQK9F)%@5r`yUdcnz9ODMnlFAD(WQW#7wz{dG&Cri_dpKZ zd74ws!ehV-=t|JY@TZ$k!uV43D)_!_hMdSi?^Tq_wTC{{q7kxK&O&-X+AJ|c+i}VS za83#2_(rSozpbH0%@VyFl*D4*=mKfhIk5M>1{qmvy`|1JG<^z`6r zbDA}~Rt+_4_k zidOF)fZeNVYyl`-+y35x+w`E~Cxav>!_847jd++JnAbItR7q(W_3(o8Xd^ zb^;|95JEa$+Q_)yDMt~k1wn zd0%Egjt%;UU*aIXKz^-<(J>UTUBUZT*~qt&&irr6XB0xYi?ve$PyvA112Mux8a&TB zQKwa&Ksx6SGKcb1Y44TlHqi}qxcJlIK>(z+;Rreal30)9Dhg06j*d*fS`(+9~kp@DU{=J5l&tUxCoi=%kKBVDULi!f_^pd=Pg+E z!aqmhAGTv_ZD|-gnj2Gw&ddTRV?^x_4$UWQ1*X@W;Y%cEPoO*7u4YG>pT?-sl$Od$ zbk|#1mu^ATrqkpOtX|Go%G1L3Y?7q`iSAqOd#%BwX64=8b@COXbI!; zxx%Rqt?z-EsH25;fN-pi__oqnD3VBQOZ>4+PViBR=;pj(2H-fHy9zFq$Fv5>iGS!6QFG#>zfsRyY!91k1-R`Zt0;L7<0AYS(!fE!yvr2&*0!P5c|bFG?`BXu@iH4PT+!gRenncMYMaX8Uoog zSeq3C_7R<0Jpd6GuSEVAAAAGodL{(Up*q?%BK(K}5U!aSFUgf@_Tg?BA4N%CuWX#| zn@H$Z8LdUba}(_WZU;>in{mHRf0U|+S`bfRxK@hA^aCTGg6EBt7J%LRA#Vr==c9(| zJ|#5(mw}JKeMMKLFKJmsF!$c@Iug{4$U5mZlsnl*0s=3WA|*7j(+b#zbMngus%CrA z-uZzv+AU!g`E4u!AX+av-a`fds{C1i#0~(!515($NjLi2Oje*@ph>jJA?%KZ0(d#J z8qnpEJthFp@Bql`=R;uwfEPq5Bq=1pz1!b>9E002oX;wu0JbW^ngP8SEK#e*9~sRg z8i4H2hZA>6O_>=07{B8ykOP1ayxI-?Y}R3b#QQwD*z+k!Dc*Y5B$fsdPy5s!SNlT` zkj_h1O^kTfjh9t2Wy<(dhKTc-@NNL=K3#ee8W$FQiy~P6gBj(If zu{pgLMGLaV0}rm_4axI8El1`M<^5M#FsP25v8dH@5=>wwoiV48vh z`41-mc85p$2mT*J$>0B%1hX3%>Tm4cB3>G#JHWA^`0|Cv!RfE934@Vgls3fWIXfr$kJKRq)5 z8Iu@OP=|!El=1{zZSTP7^Do~t;N3YX%>W??j0djpL;js{SY8bHckTBJa}Jv{27rG9 z06;4YSk?al2J?uVJyN=tS0ZSNlAvAesgJxALwX7a z@JMyU7oNR|IyCn+QcTj&5&)|3IK-HYgI6lgmTw%5_K=6v4QM2J=j{RYKN1Ej0Ykc}^(4J-dPscx#3Y%zwq5T4w35H+5-ll%~CjKuG zRt7D|Wro>QLVdMiT(G5P->hoV%YxeTmyNpzygC3sP%Q?YBpfLL5R~)uzMaE;ge_KG z=`*b5L8$cK9STy61>$Lzm*69ZFkv?XVb`yG$H6${RThn01JB_2qtp(~Oq3a?2?Z@o{>elv3eKyF0n%_^v5=#Lm&MF3ajn2 zaBa4paI#feVHGx+eoH_Go6Hvc86LL&-7x`zQy9+IFr5EJjDKzZcT4?djhF0!#g%^> zKra6+!*ux9D=HL1{%Hp>gUsdOPL+as0QjZ-mYYyc#1nv1^50HkxnzZ~|+ATC%9gwF)V3(5a)`+vA$1rY3n z4@AMF{_FguB!T*+g8##eRkAr+Ep=3YsrXMb$OsPdKMen>!TC9>?V1dG|!hA!S z4kR&=;5Qd<@erX@CyhiEnk9J#kD>W}FkWMnk;@CXO3S3|p3z=4W!yJ{dru?k`6a z1>ip`FIPHCW{~e?F7+Pr-maVTD+lF-LI1)9p62bGH54Gh;sh`PgM9Eec>aNmZw6yK zoPZ<#>WL~QiC8HQfxzj1Ljeb%(}qD9jOq8l+B%F<1p`#kumw*C1yF{36F3V<1A2ZB z4q^)hu?-m$_keyMAi$d{H5aP09Q90V{@uF_~)(@dY$u z2E$#~QFtQ<&rnvLQtNpN!-OztARGeRKA|K)KFGZ^OQ2+(#z=&lihtC=|HkAKC1J0? zZN|U4fPp6G#Z4T!1LX$(qr;zB z{xdpy;%TWpkIFp3OW*r8{ZVf{dA&-}mQtsDt7S&!`y!%R-ny7c6RJAdzgX5tCI6Ou z0dSMr-||1>A>t_lpfM904(Q)zrUeMt8Wx8Xr1E-W|Gh+m#i6}((@r4vkcT%cL^1zu zm#RTeVRGFFfcajMLT;hX)_oTlbl6u{ivkeE$xXyd+<*g-yMJ$#!!-2%-7N&HhsNj2j8fAFgVgBK1O82h zj?0jW(S*C%Q6&28L1wmRM_MQHhqma=E^MOe^*6V;9F|gNkF4}^Ed;K#en{e$%)h!& ztNcucvn>>>Q1FtN0K)A-&4FZ|J#GXKNNuN5%Q?n8QIg+YISPw{2Di5pkHE{p_mbl$ zM4RdVb5O|Gl_pVeLs!qj`@l^V&e;YfJAuvqFeq>Mf1S1KZ%x3&0McIa3zPzY$Ee;2 zAUvU*a7v9gy`9J@M~OWCE@R^SKxqm9@{+KF)=5e%xDok}t;n~agzr|oInM+(6VvQ} zH<4kWQ{_pGals}~EaHYgB{>gJfBZ)B-I^7?cAVKXuK;=bWX|*+4%KeebV#(^e}1>hB@;$O9cT@)OvnUZD*Y7)z}3(JYy~i^fiSF&f3H`h-%}PKl~+Rk zf%NxXhgMPp`rnqi|0x5RM7YXZ6Q>6N5bwQ$ z)BiN%B!ViyHgf~NE89kJSE_)>X6gx*b=QgJpK%fVVw(zaSv^S#`SjnwE?EAfiX&_o zpc#hdUr#Qb4B(Ofxh%kR0tgEqd#E7*ZVwa?F4oCIGCie-GMg6 z78C>nJ`TzoLH`?q{sGRR50eQesDW5$I-{}&(DMP4P>jw3EFa#dAuobllgcqbPjkZF z6t-2j0)P$x5SpI6(eB~R{Kq12idS%&QEgn%6ed~-0H_$Q(FNP0>cKV@7<3t(OeR-_ ziMzK~%9^#y$T{Adx%d5ZpESaFat$>^Qk9$)1sU`?zAey{hXGrIu&Q7i)c4973LwR7 zl^>yMw=UaDA**6}2)2`(_-wTb2F}CZ{Ua2B{onkH2n+B#hQKjNWsl1LzhTH^EB8aE z#ld$5El%cD98XtC03o34=bQdeKFfD_t>fw^O!vxT9Al*_WIN?{%~gYnvNidQ+6vFy zwuGzq59?s3G%LXP@QB9Qiryi=v4~GGsk09LP75a&cGqb6rS?%W<`Y6rdh{VUPhqj# z1Ml1qm6Em45q9MU$7U(*7ny;$6Tgah64=blyyiuwc=1K$gT+%pL(QXw z3$vzIyJ@`Q=@t#(80}&~KG-h|9lGm0JTnrKsNSo+Im!zMYw@NM_17(FGVts8+A^{R zUj_w)aNG+fv&d;PA-FnnFMDIUNhv-k2Xv0KOMedjf?4`L^>p9w!IlQjA(5f2_&CcO zOst_rvN(M8aYZ~PD+V=|JUXH{O*bV&9?-_04ih>L2s9WaRzX3xP|`ca{^k8eoz4RJ zTtFeFXe|dIz3_&NgC=rj`wZVi36X}7NK?@a^ z5jPT}AR?OJXQTJu3FZLkF<4R}>>YZBPcLYIyVRsT4+snQxXp(^n)FHSRp8=AJee<= zw}m(s%i_PC04xdi53hYV)1W_Muuz58PaQP|ve)%ADo*Hq-BF=(G8-;3babRo3bwMon2|;Xz@7Nk@tmabA7loLP-A2lu(iO}7e;6A}ej$n~S@I5uZd7iwk69LM8J1puBLpafgk07YRzlVO9mLWxF7 z074BrZOUcV&GcuQbKSs#yfo}k;xMtc8vs^Z|1%iTAQWp#o(=-n4!b>)gwq@DLul>; zqktXu8?|vagGu6(6iM{;r6^jhsJ2lABV!bkgYfz4h9aQ;B{hc3DbA^ij!4e!^O68S zYfa$K@Q$sqCo{hxnPst0k6}O9G*bRw%t$TWvrRL=cbF2uB22H};T_z?pwVfq=-mLj zMNv{(0J}k3b69~SP~Zw@skhe+lrT;#WCH;DR*zoWh7rIHi_50L$cNjhHW*N15{rl) z*jTWD+ksQtl*^Nj`bQEu3(#fl2sqh{V8aHr<$x1pOm*kT&qgtY0DxKG0A{f+N=VQ8 zD;s9bQBKZyV-MXPiow~50*qRHz`Jh@*)Dvme3LUSySpEq^mM+a$AcB1n?smu`=q`p z31|$4?K9cm>_2S>1*$RbZLcGt&Po1N5HwE+;JN|;&OR@xDomUq>BHp z1NcZge?DPF*h?4z4_fvJ(?=XwCRlmU{!5~*tYaX70%+)G_!!J`v#!RupjftwJ+)Ie zhb<7|WgG(l=)I}BMMKkpd3Z3~T5V@$#M;C^ok10S2KP{zUKsv582;af5IV8|Z$$l< z_L6^xw?^{N06x_Je`LLLa3x>VHhN;)b~3STb7I@JHL;V4ZCexDwr$(y&F_7`@7_Od zRoAJm>h8T(_r}@lS$O`*K>`H9yt8@(384Zo8Mp5NphK2kKlgx~0jRGjf3*5>l5wa5 z0QkB8^B`2h&i`rPKh^*5F`9V95GD3MHv>}reIfvlKi7cxt^2fi`Db@r@vNGHo9GPn zrGU7na{(Y{$t?oct@VBY04}T0`zFW#wgVL9HD;&JrVjuB_I`A}aE|%Dg*9!L#;A8c z_P%>Ye9Au3MSFy)QHh~Q+ctSOa$M)P0#0iHf2T?Rk}OLGwEaWHY{@786?Q5B0H-(9 zb!ihh0j|XL16rz(_)i;ET!H@tfmc{U=Ys8m^%VWc|Ir^c5SHHbe>M1@Urg1T!v8tp z+3Ay6BK6t7`9Bxa(qIvPc4H#p=)reGpPzlbBM=-Av0Vs+^H_~nHeg^Kr-9r(0HE>d z0Vb`Ar_(`w0FOrPn}65pOjn+(ZG7(kiu;i`Ovpg6`?Ipc17)wnI)6U_$BpJ)R0y+G z33}jz-3w3GGKJ}b*9*)Dg3SBM&yr|!1bj#-kNQaN0<_TRS($T$c~b-?834L|K(b6Z z6+g|A5dscQf13k-{r7@EJ+Km5J<=Qq^94!yvG)HdpBbp=$?UEDj%DV*y}q~@k)Ts+ z4FL)|BYwZ}prRltf$9lGTSLo0ay)8c6OczZb0|WB_*Ttru6WJiu!6A|43s@6qE3XI zfRyZbwse44xNWEv@<)w(+QTV7gA0tw+4B24bWxdG#L8f4azz?y9|<5l;YmB0)1|hJ zZ?%nhWc181Phe16vsW1f{500=4@nA-+dTud`@gsiLSTwpjUTl>008*@`64vVH7EWJ zs!Y=0$6)9~^WXA$4zF3kkLqzy>c_LjplZc{`})R@;=^tI?}R!VAa)thBXr>PZAt7piwMFr4sh9WAkN zF0mPEqm#dUXGEh|!;u>;t zpeU?n%IWhNYUA_IoAi!U5Bz&$0kY#m`=8OJwr*af3ILw|`2<6P>FcKd|E*!j)c;zy zP^7dkwMiil3kw%^6PnMi=O(av<@r$JnM@FaQHxH;lFSRV+}kAv%3#c6F&veHc^znvEw#X-t#^J{)s%OYJ%RBr=E&v@8L4g#S#0p|a zwG7tWRd3g3O3;rYSBH}jIqS`W%rfZM=TQ7;qZ5(p<8+AH-$Vm|56V=NbNT&`lgdZX zB+MTG_5BXVfeHpqC+YWpr;#~u(YB%PN#=Wmc-;M)5Z;Ln9?^BV+VVbAXlKii`j`1m zs3X@d_6TdTN8HN8p0qGTm9Y-;np*@`Ry!m$jwv-a4bxA;6oAmi6R5}}!UwNJ;yOrN z$(Duup$y|k2(bH=&=&xjB-a6^=Q0F06NQ?N#@}^=5vCA_VyeOThdb1-o7jlJ<}*<9 z#Mq%kAe)p*G(R1){$;}tn{+drS2POCe^io#SSrVzLF8Nyo7C~S^U;;7;9E%hi^SFgIhb&#cmvdEeu=H*VMRrN@*SC< z!_{8|u_B}y&KxB!9z;8dvg6QFiC*7Oo+u(n0t^QgLl9#jJ*m|FsOX2EnAsl&BDk{+ zy9bLCa{Etxu1NbA^jbmqxKdr0*n33go$kXAybyt$VEO_`q7k3}2J*)a%rjDNMw6u( zflWt0dH7(QH|?J8IU{}xkU{iFqQN>G&;ap=adNnHDC@uxb6B?!AgJf~Okbbg-?&Xf z^W}cf8n1gNM0Mg+7|zzruBU_Haq6tLe}6YBM|pE=KjRW@Twmce?!G{G|DTTMowI}? zAxGYpR-L6OW|FAnASMcTh?t*d!B409gQZB&@Opf@3ME;jV?BWhA~G9YU${-< zwC}=~a=af<;0XBl|BZaaZS}$}pY|ZD=UeVujjA9^I*?35nSY{ej*``bFe%7YRD*{C ze}y34O{#D;Co|LwhOoO`1%Mb8U`bJ6;l(fIM0$)ypXvRv z4iF}OJuCC48O)&@zG>1itv*l@yIChZilHP91pZ9DBK16vmYICx@I0Wl2qd<(A>q1t zHG44pU-@`WQo`i zyzS@a7Z-(98i!BI9=sW*KtyT$#oAC&kCi!6>aIt7ztH%hKDm_?tb18MdimAjb%%pU zgpUHdk7>WsoT^`Pbanm{zLNO%%Cr{k7C$N129rf{ymJFz)5CevUD5Iw%MEq|A(cKWP#1=3u#uSm0+?oXg^RK_)rP`bGhk;=Ta-+dw14_yPg@* z6-mh4Yl(q41Qx>Ap>01&*FHSA#XMnH+HG2SyZ%_yF}Etv|3&;&j6*M37GZPfAQy5+4AkbVx|_=ZOj9oi8* zDxsK7V+#fugYDntq8HXoWB)ON#8Q=KS=dKw$4O~X54J3!O}`BxqvYISzGZ$sK9kAL zT5i7MC>Tx};mLFYF71}@{zErUu#tpz?p1sIL96DPo;!|)ram%uZCdJWHw!|cypTlY z(c&^F3f8QZa%1Bn+fkFd={8_zigw#j+#GN zE0veTP{Fyf9>VHO=`aU5(l*jlf5wv)X-0nm9{PZ!(?ylQ8&CDxff_%-uBSd6c^2v% z0!_zt*!ongdfDDH7p6M~Q~+n$dp}$vX0OdD-wgM=&#$fU9E13Kra)j$>JOE_r9ptb z&$Ah671UWFFxP6RGpu24AT9qcp$7q$v_F1o@kr)@FUI|Qq@Vn3LVgk~Wx_D`w&XTp z2Yf0&#fv|JDxTh`x`=ZwDjTjlmJ*<4b7pvBfLZW zHLxV_B;$~cnXn`S40^;ZCQzuh1Q$ikR`PJ9!bq(y8ad^v+gPXyFQRQbj=FwGF4->c zfuuB7Q*J1{wk>^RYns4b7s2kkkX{O;gDJBKe~{6G_Pa77ePiYmv}K&Q~$uTeyBm&k@vaW4kILl^3KiLmiGlSCw>R zVWIbAwsvb+F+f)0?QlKma?RySRaN2LzO(Bqfa8wT>nKnT^l~ioG~C+;qXVjSZC>o7 z)iN<-&WX@#Dg~Z7m~QQx^lkuq!ZI38u>avW=#yisF^L94Fb#io)DPh(!>MTIR)4$t zFAo4oy_;`|y`A_#z{)qjpG#!=>l|cciM8itTL;Ah!D7cIPcC0`#}X?-i93iIQn2%v z=ta1E{rB%9Tr_A;Cqc&>B6o}@A_JRW<;kX14<_w;_BAsD>`oJpxJHsI72XSb0ED4n zN*NVKTaA2E7jpvJR4u5%MO_x-$+ck1u_onXyz=&fd5AmO}x@ zQ0^~s|H{4+5+Y?>cd;GDYzql2WN%IJI2cDHBN3qpW~|p>a>~G0p#wt*P*;mFJ*nMD zaMRTXfGkolm3?}lanFr+qs|ay#2c~21`QS%gcS_`YvO(X#D{x* zQd)AG$W@Ta8Mr^2?7s^BtsVY5NXngfMfevK3t@279`kNB)+#`xsF;hT2Y@TvU{eWF zW!p+fO%d@M(&h`2LmZ(&6$10QLR`zDh-Q;HsCX(}0X9~(r3M3+y*K9ho*7OEW8&Yk zu`N&UK3dH=wkW$WJb4VB2ULd}h;A@lP>otIyDi~Eq*|G)w!cO*Tk%OdL>mpTZdK$# z`_9W;Cf7hn%|LX9u!-(+pNj!JXsexGQ7HsWaZg4uw!Av5!=R2dgpu{>6JQkk z)i}c4O&d(jkxT>g-0D&=D70_+^**E{!9$r}mm1c*BYBy!of9RnM$J+A@zAT*N}M`$ zA5f+bG&vcGN2MnXEpDG@PtGhJvzmB_8dZ^fM?}_6C+W z#T_V$vN$mJ+dgaNelLlMr%pfE3Oh)@wD5oEfY3Vyp)n2}}mY=uC+N z^4Mg=V{XRG7rZ9HspRN*Qy4G_sx^scc++5?vt&(H%>2nfsJ!n!)1rJ$(WNYUdb{7T zz5L=pC$51JU32_tK^C`2bm-AJ;kg>8jCpD3e2k0x>1;-{YPD9vL%f>@J@)C^dq@6J zse*);qG{&jX`5J>++uApKBj-V4exAF1ivmL;~{fN?m1+H1o^c%v{bA{)5+No?VNj6 z6^uvwRUuOB6Qwy*-4miAC}~gd{fZ)cs5}qkE$;0g8{{N@oa)oha!g;%DeJ7wZ?m;^ zLz&~C)QvHW`GQp754R2eE+jl=sz=l|!Wkfg-Q}v4GQmeANQ2ECq7WecN6EQ*J7adG z5SRllL1QOO<6H_a02=6SdgSxC!lr5i`cMFEv#;mapH&=}9GAg9lmqu>L;PLgd5aUk zB(6U;fOErYE>bKKIz7DFrYhX7J^~RdOxkEP{(PU$ESBm={B1_v(j) z^UuczQaI*2EYiG+r6=~t(4b7~s?do=Xkv#`@sHi{7S^+j<xs(F;M&de#*7hGlM zVr3uINg<;e@>4%GiGCi_%0*?tA$SAgY7OYft)#pVVb^0oP>I1yOw1k{MXZuKB3I_U z*@a4?Jw@-H$yMqx4C@a=JRbkOtz>RXW(0-Nb<9whLDMKm-6-KLbw4Yj8P9>Wy`YdE zz1O2DFqy9*+@9alC|1dC|K!GjAerSg$k7odbXntYoXHzh5&QK_2IfJq<`|zYaT3!B z>%`D%#J>3sN} zD2;2!A{G9;+bJ>KRl}P>6iyo&J2z!%;tl7wI$o^DnZtKA|045sUWs`E+fX%nQ&AVL z=AC(npW>}5?D`2EnScmdWZ1YdF}JU@m)B*MzzF@D@I1Lk0cevyly|mNyiq~y$}_H# zWrfpr{dn?n^`6ZiCP1_7BT$Doo`ZOeED1m%jy)vb0yO zuSnmWMWV~VxABR^u_l{M=IVafk01E8rwknMyaK$ow1NvAtAqm!nHtkX(145t&&13? z_sgLc?y^~g?7PLFef7hf!N_l(6yFKxPwpY24_Ya8M8-APwV~?BKY}dzNEC0(A|0S5 zv|lPSUO9muYIo+?KqcGUi4CMGbW6<~kv^(d0_`JO=S;Q#GDe=>i9Rd86?3XGsrFP? z24|@yT!|JR>;3dKg9N{wqZEifb~fi4^9Vra!d-Mk3fewt@u9r#C^h~dq(`f^8Vw7DhzKX;6|l~xi9SbhyT)M4|g919v+CAmMcocnK0Rw z;C2vIcmAmzta)NAaOenf6i7kj1m~4~G9+da)BS-8b9z$v;Vwafxdc{L4joO9B1l}= zQB|GfG~;TjM7`w(;5K!Cm#-MT=VvKz)v`=Y`|<%>Qv1}8P-}7Oyi!m)U3BQHFsh)q z2)b>cuelK~!_vIicmLj6>j0(&-aE5sd61 z{HX)9GQY_9=qhM`i(tFZLI#%i=%Z3?feFk7GDJ!)WD@UQ7!O=$w7@tvSEV~$kAnYV zaG+&fEPdo&vT8~tW~7hvB_JjWY&zL$<-6eA(!RJ%R&j}K1m$m~P;mL7>-Nv;8UL-W zU|+306j^pfFxF0+k&EH09Qyt;}L`$re9Wq^=vV*3D;$XI{ z#pS7{J8w{r-DHzaF!oInr4vbI=h8BFc7rGpUdXW#(mqCb%o!C(y!L=2qJKJ$5Ac$>_$yfMde4{XQ<}Zzu;9H{dWBG37 zE4wVpp*deba-N<5C;%Lni%$qWdW-Bz3%R=i%IlJg?-wC3eSbv6=y(%?@z>6ik_UcW z-%Ad}-5AmvKDKl}fNobA{n33DTtS>#fyVe;=OT=r1d7=%2IiL!B$IoNp zO>585{OK`j5U!CsK9!hUCS3Z}y0t~VAe0lx{@0vKUbGQujK<6h>jLvhbhi5)o)+NX z)FiZ?ZrcZ)WqDL#K8=R5N0!mOd5>O7QFM!J!CQKeqh1oRZH4U6OrMO?rv@R%fVv;o zfy#xE0^UYDs5v=U1K#%u;C6c z+CvYLH<-HjSU<8rRTMr*9%T3{(p2v)mS&{qX(QQD1Y@mnfaa^ltmJFI>)}~a`1u#Q zJYXT#nHc4@QC84-cT)nQ{D;dL=-rz9BJKcIp0~S=Du&G&RR}@fT98R_>1LqC6FJ&FI8plIob@xM5WaEb)CYP(sP^DVBzqF})%;duxR1`7j%2oXA*rilGzO9abZyQ}0|`dFooRd7WjxykVC=>a z#16;hf7?UD&^39we z*Bv*Jo^M3&K@sff&qwzcjBT2jtHGvy;|)ag|X-rK-NL9bP@Efy{%#IN={r2+Jc8Gw@S&>VgZRt36) z3-7uNR>7-p4!-~ZIm(Tt4xnhS@k`y)og;s;aa6u>s;~a=;NA)fu_08!MXH4`v#kx+ z2%S~f6TNULN)7iQ@dEdYut_2J(kb3Qy(TO80lr|LgZNm{Zk;xbeyL@#zfG7BfVe%(6y<`V3NisM(-?^7)GAYA{3oQ;_tGwfe( z>$`V%8xtjk-DL0O$lwlMzFe=kS`&x4-OF4*rFnizEE)C*azcv;S=<>~Bu%9Nyc6K& zf;0dCQqnxy0efw*&I8Ihk=N&DXKV+Ax`sWMh6%J9K}cRPXpGqCNd(J2I(qg1EZaV8 zBj7Y4>Q#<+H1V-lKTNvftz(wunY{7|wGNaT&J9`*1GSq$+0lFS@=5FaTm=)6l-Us}wL% zwQTRP+U95kO2JE0T|+zl2F1BjFf|%10cvUS+_5@=B!^po72HB}J!?LLB@ zweQN7UdxYth~6iU7<5V4KaTa8Xqa-nHdrS`d?y&`G@jAAvBdk>_xMavkyU(_6BOvV zacpCg2NNAIXTqS|g~|Su3mg6EaH>s-1L{{oj|J@5H(Sf12sc_aEVp9mx5;8xGW|m% zjE)O!>BOPtP<7Z2Sfc_))qnUiwT8U4S&(NWNM#mO_DAu;hNQgn&p6qNLc6D^8O<5x z+_x?X$u)Hs+YBScJdT*`CE6x$flG!nK<&jDU`<$Acw8Uu5lr`l^JkV*pGP2XGfuK? z0>nCTGgDP}5IBFn3d|?EbDp`TTYUS+~K=37FjYVrHG@Z$c2|Pb z5i)yURs;=1==A~7rQ2`-y`BCtj2yB_dTxVjzTLT>sMA817hKS6oY+)2`QVe@9Tx!bS|>Wq$#yQ5i<^)~?hUkMT|c2| zCSN0!SXz@>;z{{9=YviVSCZwIF<5}1BW^MQb;me?Q);jD-nzwRI#7=+Uxd4@s)7sZ z`dz0`FyKW1p5u{#ERFFVBmi{vz6W+b1%Rz4UpgIJi&* znmMh$j$RDQT%!?pe0gL#H7x|q$m<6%!KCb3-S#yw$PZVyenp4!w*g1z>jKc&LCV5_ z57!bTZ5Ig8eh)MxM;F>Rbh=}x&opid#N!@DN<&Sm`Ne)topF;6xQ zQ&f8H9hCEZ84E|aIFq^2YFG)Ck{asREjvW#8V}LP@(f3P{8;|9TBGMfdH7I&K9Uf( z-p>wrkV1D1j|G@VrT9{KAC48t>Py70c$-$x-S<@sEfoYw$gdZ>4aEdqb{#GiHR!p~p)e%*5DVKD>nH&LH? z|Ea65Yxb5`RFyxW3lCwK;4>fEe74L;9U@^zIh;iIcp&APaLRYg@Fm0Kr>$>>SPgVY zqF{EWBUTrz+#pYuDLDfmaA7$8l~!GP2@0^SEKp;%MXD5*~BIF z(#CSM2hbM6Tx5kw1wcQ+~`wQbNfQre>uf z?gTh4(C6|bjLyJp%*_Uca|UyxZjj@0HYFf3b7b7YATk*SC~YS%BkCPnD5nPVGZO{o z$?0@k(&$?05q@M)`rj~C0n-sZ=5Zc@&s*^+vC4k`LicPjxNaO61D5{6*4>aB!tBGM zqdbK~m;*t?Nm$>LnJv6VYAS>{k@W;wzbk`3eIBZuSNLag{jEQN$NX09{GzCcvkR?NzTr8^OzM!BghN! zpZsOeb&@tPXO-;xT}2&@O_Cz5XFtlkPrTCT#2McC=ttuJYo5^$0soKs8&L|L?}Mw zpP=D(snm``0!JCl3yK1vtrc4OSWC8}m>tOL73%n zo2&8~uCk@s@ZE1Hpyg`@tRYblyPn~AmWr`(y@_QY31nzV(%@!C%Y^#G6as&d zV{;2zLzII|+%Jv)_|JUwKf@LXaFm30MV`9tl2f)fs4LaVeUmWO%Au;CA76w9-JeJa)@t419DK+QEnOG&7M4W zv`WDlE4UxOYajGc&d#VE?z=G|iGU5Fk1*P{9=?tTWHZ<=c;U=k`Aj4WmN z?O4(s$ev24eY6}bg4Cz`l6&1QVxYkju55x@s%X}5RCH~d>pTc=U;Yo3e$z{COn-f* z2ibDAjw+Wh==CoyIV?-O(`{rVDl)qh3!?qGGVp5s%+=f>Q)^A_)xw zyVpDT$5L$>C6!UTP`%0oiqp$*Y8o${IBO}YOTid%8yu-=huuVH1V6?Pibmc^JDUG;BjVtD0Nz?%gNnE+bzp1RM`8SZUBw1F08q;I8hF6L zSxuxU6sIMO;PrsoKT19@z_OW3QEMi^&MHm~O1Ct#RLKjDrr(i?qf0aH$9INz;__(7 z)K`q~HI3c)JR4Y@HzI>7Ip)=IJyI%nt;Wk-9Nr4~d|Y5p7bl$;AZ=jSCH6@Csild7 zGINROcbkvRR;gK4+yfgB#qKecq?GKYhroo^2QUz0zhdus$ZxoARv(@}v?dApEg$54 zkJ{$%zq^;u4`H(dCCTnkX+G>sjXS|w_6M8%z*u(f&%S2|8`zIHBcR?FYf%J)-4k9wHEVt5w&Pof^)G;S&wp>o z^R~v+;1sFL$;23?iRK!WHcP>$xklzdDc#3WduqE=B}N$~)T~xnG~0 zs#b~fIC-HLgW1>>ziIivnK=UH7VLTSb)T@|N>pMA{oYFg=0s6_pM{$j8-!Ss@#%=f z(8S0I{sG&R$rI{>I$Q^KC0Qpbv27X@Y`I>A-jIa-d4JBNj=xHVi~|o zmRc+F_NtI@fom;ZpSIs}LwLZ6tYG(MAahTK&OQMEqtePjQnm(~#IVpi7>8;K;k;y>0Iw8)0%+<=-|XF_Zi99`M|YSgMY9C;96{@Brkv zwHYT~BdsSy*en5y_ISP+0vhL^$iH`Zy(OnNPS>t(Unu$gpyv=g&AHrh!k2s}#vGR> zl6f-81;Q;g^Jd|b<$0ArrpjCe;6QQw)1y|Hw1hpN$~Ot=%MDC7xt-MG3eavaM^4`|(|5S__Uh||4u#}Rj(DbMro_`VN*4LsXWd4|0oRi--mrhU zMrWQW1Hf*}OCj{3lF{TFt|}y3oVl=cpS5y$o9dh;b?;0xXI%}Q9=Pf2@!1G>p~`?P zS;35oPic+8c88Ou-$g5$9wmq2R1G$LRyn8W&6P|J=WQovVO2)qqw^77rW&o3OM`X< zWTAKm_lf?}>A}LsTW3d&bUjmGLgaO5=YOU3p{tIe7Rpa1!OOrA)OB9f4l52URMC|J zWim?-#-^pKv;0NVD`{6jmjElD&zvCDKrV`h!LIm$_26x*@oX$UaN!Thfj0)95zKYa zJc~lQ(fCUV23xGDd9*1xx#w6ZGy#Ypb1EJj*`Qwwa ztae5tEAcsI0Hq{bEFeV2MaX9)KY1B@y9bv+}}>sl$ad>UKy2pf#ptX-Jh6@ z%+s7j0$14Wc0S$~Jrm}IU%$G5HE>#-J9ckn1rdAdj&p2jH zQ%$5DE2v^0jYV7KOx0O7M^e?1vD1YVG7mq7TmO zbxS-A-nhi4H}71f!@8pCoFU8@Z+j$VP&&vnQ3e5h@+QK)Zx&Y|6%a=zlwr>kWlR@% z*S%7nrSYnBt@Ypi7+42UCmtu8f<(9(x^v`{0A=*-Jy7PEi0XVk%bX?; zRxg5f?KbAh3F!gCC_p7f;*-TTXoe)LUp+&Y8E(?mV($y}Zek(9pr1bE@Mf>N>1+EN zF3LFa$b5M9<3)SuN6KVLV8ueyx(}Xf!n~A%t9Yh}jAEM6L_s&gY|zugrB$*Uj5?hX z`=k3LFRNpFJqG2Zt@ZoM)Y7eSW?+R57dhUf-r9|uR^wnMibO{d4+IRpD%nWO&u-@8 zxH90o^RC56xxA=VBM`lDk#``+G{nnl*f9+9$nosrL~YXMW~+0>BY&919v7}@s_Z(1 zGT72P#*~D%>%X;*1ey7^CtMS8sXERhTkOL^dk-a2Hv0ESwMKjlp;gdV@)o%eDduOS zKavX^ssrlnit^$T+OevAOlLnDqb2fCHj;(TXnu7p^L?mO8ljhqX6OnklNdN4K$?({ z&r<+*C7GHcg&vVLs@?DcZ-25ka|)ry+XXs8s93K!xwrstUoR|#m7J;!aq>4`tyNG( z9mw4pnuVLyXvsA;;|a%u0Bf|eBbn#xaH}5x2tjBgl;#@TduI=@+Q3YXeQ>M7;+ht< z?H}YcW!J1>n&#HZ&Uf;8dBj?x<5Q{uZZf^SLEVT{g1f%wmw0w+1ziWQ!(HeB>j0{|Yv4aO% zI=GdRhiG6qm!xiP@pyUe%-oV}NdffAjUdKVdxqYJmgCCrjK1F>MDdu#sw55b&d=&` z=DgiMB;9TO^TFuS$X0rQJ@hWYsbSp@3CSJJijP>8ureOBs@gigcIUs|fIB}Ty)qu# z{#-J;jYg+2a=rdXJD$-Vcx1yy_)t=RmAuBJfD<^>AjIU1VEuyjh{td(MupoMEPvNj z&5wv>H@*I2sX$o>=D-}|+zPs-(kL{RWttqYSnzR9`gi8xkWb85a;D;4(j5zhccJiT ze3oElrb`+q(@jbKk@LwF8QmJwrb;W)djeUY9{+6nev!qL^bQErmMLI(>l@ki=)PuT&&$=-&te? zWV=ur#{$Mjv?o(73s=aCd!7~sgNX>25h~U7cNnCI0cCSLPI<3h9zdcKC)`IQwhWc& z`dg1fiTS1ijSFh&sUirIE_yELJ`4=GyAC?A zd02Y>g31PAm1GpTn#FS2{eoLgJ2anV=iU=Q>iM#YLA`jbIVUi1fyib9};($ZrSKo{hLUX zMquMK;om&n-;CF=Hl|_VW?o2v(DJ~59}y%EX+5+=22t#hWn)%ng>8Sr)`dQ1y_GH@dtQR5@&5&mY^E9U zSfgpeAuHw%{l2%^mosi?qZt@bkDMQ0%wC3rVHG?zi-v6%Y5O;$M-9Vj~Ve9!Vptn;2%u#LF1P8DZNFXs+5%;>~P zb;d&RK5sDx{sz;O>IABhQBqjEP83FUODiW=R9a!Dnbb-9z1d_Gw%1o-ZGGaSv0Y5p z;eVlm_r@WLY4p8Jq(FNff{z*qtw|l8>$@{XDt-TTE7+Cuh>hcIVc-5%#!od7cjgb1 ziz&(9x7Az=;U3elCZH(C0%Vc#vt|^{{igh9M!%K|qj~&YwUk)7;T$kTpH57Tsf_1z zs7zvxZ8yh@cL0Q6ItQ55@HDeB81Jk~vVM1eCkq}+XtM9o*xsp@e_0v~zfjIDv0D{= zq>6qau`I86C{Ph@bu?OB=A_|puV0R!1*{nLPRI7qCAt1EHNvOy)nVz)NVy=lTjF^0 zS;{Zu6P;3svWF|VXg0ycT1dHwCM;V=3w7d{ihT7?74CPy8HToO z)ztQpzxV0p!=boE2$B(qqJ5IMSsm~**Of>QpBVda*!AvcFeJ^Bv};u|JOO|XF{5$! zHI4+@9#CO`uY4!$#@2rIb<+X2ST6k5Q~p!YDg_V08ntQ!%^G6Q+Mu;a%(;n@_ z4#pOS5r|nWE%Er29Oq4?G`7+Gn8f=J^n7>#EfC7L4KG2*b!LbAwN#a?uc%tkTVM>u zS^Kp)`iuyK=pzZv<*a+_ba}zTFsi*1l?aJ@X@7Bs^54XIhR&O6o=GdbU0BJofIY0X zaYgR7VyAy@wXeWz(R~NSC37#H9xX(sg@9q^LUs}7L0k#M))OU}lfv}Ke?1J_-UU~@ zbZbSXNCrc|q`gj}SjYZyG;1h+g$ERnp{xqI>{dC4Q{|b(uOmRndQwZ-CnW)Yylo}s zt;=ezCYH_RKF&&A%G>6kp`J{TBv-|wm>Lx}()tTxH@GGvvo9BHR`0hZhVpv*DChT) zh}>>^J~MDhj%@MWN4)^aEo!2FK$x$96qY>^8TGe~5d+9uG|`<(_v&!C< z(C|Dzluz=71JwMqnV^z{?xKY)8lWgg+#P9g;bs_$)S4<02s`vc=qab%+kPGS z8LtAr5bosGeyKd?2xvbmZ z7=Sx2CgfSIX%jm=?xzl!$DqDuoGy&xYJ0(zgkA8kU)-?5DSck#PyJMi^b@Z(vE|-+ z&v#dJfo59+*3AN1byuZuYKAO<%uOx|5`!2GGV1fc6SJ$gF5njcAV%?1w94G^c4mkj zkivrRhK-bXFQ%t|ZFZtl0zwu_M32gJfEf~ZjUfk)EtcQTOLQP?P&Ndk%(=y>=JM|C z@qmcb7FMTaMhnSPaQ{g&)nku1TeaB;`@-^1BdYg>=cLg+0a)^_~E8WN3eUO#05bNqPM)|HQnK^fXUG z%6{Z%)Plj4*F~bqSSLzX>0*~hPVf1OVagIttbpsS10lDw+8)@EkuqS~1D`S`VE!1k zz*lX=T3R0KnBRV}5TV66eJsMMQ^S`LH?p9kl6 zFz4b8((HG>fuK0enFthbrUqt}r5v7|HwR;1c+hu*jpj-z_nyGztuZKaQ{?l^?d#F_}!SSKI{ov5b3l$B5E#&-h4A<@=t!F7yS6$WF#FSXpc#zc=GGdV1P{ zHk7x8`*Gmc&1?&OAdQS>17*>3l_J>0Gt1w2mM=Fz^l*!P01{LI^Qq#RHu~yc;tcU? z;c$d!8LF7yge;@uNDRVMl|PeW`d~U;WKNr{ft?I5;{8UDUQoC|_rO5y-43oq1qdD=ak8LUqwM$Hd_@yk=Qo+7xT^p0=zbY&h!&p-ukL-(I2 z%K3PJa6m_L&*ObmOAO1G=q|?DYke>Zu6>I8-wb9boX4f%90wlZjo1xYoC1%b%F(qD**e`4dgVs5%- zoK^8uX#R<@~erp;o(-CE{|B@nC=E9KWZlRbl!HHSol2Wz`B3ZJg!AF=)v|i#T{$Y^PM9eG* z3C1|#+#(^x=HM|=I+|}XOmw9X+#daxjheEL4E0Iy^kN-xK#A#D5~NAfOug`pAr_MT z6pljJeIPDvyGoO(FYznP)2$_#{Ub6KoOS7Uy2b3T8JSmJfp~n7;C*la%GyC{&An9W zLZRut3Q$=Sj^sXrMwz!=eSV()GrW_%N9|9|NpXx=J&f8FJ-tg2n3~@TO=Hm6j642m zM)>sbB7?0wU7nCF8}R3K)8?f0@%Z4jHkdaH&8>F;=xBcb@C!j@lHW2G+3v0F;XMNn z9+xy|^)qQ>d5I;ajvmDt>zM;KLYt}|0o0y=Wz>p6;I8{B-^)9V>KJT1?Wae5pr0_* z@|Y)ns%<@hCb2tcOF>aqQWYN9E`&*m2Dc^8mfhU0&zJUav;aH@)MB1 zJyxOSifn4g_bRE)I%fwiv5kM01~cx6S0ku`{lhuyn;5g9*RYq6yzv!G(T6dKnaSZidH6hM<)JrCmx%7uf)R|j<5=a ziXzR~!Nu8J`URjQsV=JIqe8OOI+YJ{dxiHMYk*zNAV~egym?!|>tEkO=SHV3eM5xz zn0WEMm0hMQ}p;Ajqer`YW)yn{v0%QOB=l>oAg z|K{VjU>YjD4tc_ndD8$3_{R;P{-jVcrheHx(jDRiOzb7i(QkA zhi>Fvy7@z`BI99eUcGVPBHP%WsF=^m)a>RToY}DTo`;-C4HgCFnGmX@5}G%nm}xMh z68Dom^39^)r9;$Ll!hLI42!T|b$Nosu!xPO9@u*F)XakPaE}H>CtpE_TE1I-*I75s zl2jFuqNx|tNg2ezHE`uZDp9V~`+IGy*{m0r&Fu7>=1#^8aJV+gN#@z+Erb2Kc5@()-kUC=0#w-lGf;%GkO@i<@REXP za_bW-0VG<2sQfb4b&wiDgByz1P=!1075Pt5agXg93%Y)~4EvAFbLB4oSL{Fl0EgJK z79Y9tLAvpo5y#3i!$*xL*^AT9zL2nI{TL$;LoZB#RD?QvgsfnKqtTNIM@N9D7fr3$ z!4l!2UA#~RbQ*wa{ayk)QIx7p%FlN{w0QOS4&CIN5eE&mjv}TuO zZz?^?PE~gM!2`5)g#P!VPHHbq-@cxsPULMqkRNsT?)e}HQXKbMPtwbJ8Xgxd*6n0O zrD<5NBBI3quLnMBX90iKnXbE=_;F2{@;PQ@lk%(-_i_f&9X7$jz|7pU4R_KSWy>)$SLYbFdNduH+vNkc)|A1q%vAve zAOHg;%pjQu+nM;KD7)R%!Iq~~`oDFBMk~{E_JA$*fF$6JkN^M`3YbXO!P3L?r%M|$ zY)#IMeW83FAIiEz`AVYN91?6SZDlW>Q(~3Fs(|YJGKG`Pn+?L(O(8%N?qOR%2Q9t8 z^OE2y4DgZ=zED3nN#^(%e7*03Ft|t!=;2C^$5uWm4q z1(N^}Op3d{mkipB=@Q+iW07rgX2Isi9xNa0O2?CM0z|g2=-B!9?q+YmZ!-tkHr6yl zE2uJD&3!4RDM~r2937NB=@lPb@+|=uw%N9t0{Pl!elmd{t$%yGq5UIPEWS{wxPdqL zdZL=*ha&(1{;UHP)Q-fYx80XqBarlPzC9a$O4M9$UFNtk+ z<}kri9{{bn6$#)cfa`dLMeBRaPkOQ>*slO6K5% zB$Nz&Ql3PgR?XuTOU}Y^1HZfPn6~V*NXk3`$6)wA?&Z)V2&HW`~{RUGQ_1q$qH3 z{B}=&DPd}r+UKRI#F;V;FnwWR`$vpaEfA)=n2u0R@C&O-j2Ss~=7gzy{|r9jjT z)t$Ez?VrL87=PV`U>W*+5X%5#04ybd{7vrD9?J#-cr`SX+X{_J0d6?pD4iyu_*}QO zLiX9fz~~r#)ZHmqf7@BOEMf#A8_U6iY5| z4)N}DOJ57*Cd@hh-O33tb-AX2Alttsk>3W>=5D882c%GUmG6-j0ci}+r6YzAH1HyS zsJG!3xUS@b!AOtB{8-L?LgYYA)bh9AK3{0Me32*gof`EftC;v_B`Q03QFV-oH*HIg z49QXzxoI<*q~aP|wlZERDIJLxiS6}jTl-97V#51cO{p~q!R-;`YOvR`F?I3o!J_@a-O0!f3`DsjHwqS#F!zn{%P5yzj-Nl&p#%EzK=mXXzd=9G z`@%=(e#Jqf+&RAkJ;1e4005KyF`lJu6e!})EJd#=m#zftkbISOQWf@Ks!n-y_2;!$ zLM}XNF3%tsvLtbc?PdG_ z7o~?T0%+32X+j-d+g-TjYa5@PuG9kSxUjD=?;eM%l7DzdUX9WQ|mUtHClox_p$8!j7j+45YD(3D#35^GJP5L8V*m@szZMW`_llZ5O&Vs z6fC;w0k?z+Vu3!?6n^3B?Vr+}81g_o-D+&ufXPS(JfGIZji(yC&-)%iI@J)z2OWS( zt>*yaK!DrREP1(RKV<^oXMan`kYO{B@m>tgw7+mnIMl4XdU_%xh_%5rX|}FqKlAX3v~ubt3iUJpPryCh%iF^E21i5`L5ajh z4r-%UF0sGsbUiHLtk7MLZ%GH-6Dpl{Aj*Z@<7&LwQS%||%yrhjTK{Qz^MB-sSZ9d^ z$v@p703QRRrii$l`LDGJ*pYajs4*$%f=zk#N!)mbeNKp>s{zdjr~L!g9EW4xB!DWs zr~8zCHvIf3SN^Mh`yLz97PuN10LXsR5JH=A9kr z-BWfsdD}GjJJ9SPc^S7*)j1^`+KOP5!Nw8ij*z!Tp%j2`&0-m4ySse36i^7fYt7sBjB zpOXkH=soUq7P%;cqDCwT)wlR4uvs7OGsG;8aTF7L3hhzwfB*qKE-5~+;Am}*ETQq3 zt31Sjcv1BYik(F3JANOPe{Qx~vdf({V<~*W;lG#!2=qP9rNHZok;%B+ME`%gp`%*? zG0KMdCskxY-(N^=a+kc+4Z2rg7HdJb3626kL2}kgx%4bzzJ9QBoJCT8bRg2ydcND# z-$%2n))vMBMsZ7lc24(nq?ufXpI-4hOheqFh7`r$=s$Zm?8VdNvaJ!q(^}H+wHhat zd6h&T+R`yyh5hVRSZ5tnDl8DtD03X&@(J_z=1_70OvoG{vEZrPL&o*l%xOg`CbE*H zy{ma8@qEf<(m~nk!gk4`n3JX@P2RIe00I-WRN;rrnyLv2!Ie*zBQ`W#ls`kR8Asdz zWOJyK)2*!wD7zeF-v$aLcbQtq5cXe(i=Z>?@7+)pEao4Jk(-c_WI?&Xf9z2z=N{oa zSsR14i3hoX?@B3(3^UtkM2!C8?IB(rx=};KKcIruGL9bbx|&Mq^i1YmFVvB{GJkOM zreq2V5e8FD&PqG^Mm2&WddAg1JNIEYtN_{VbGzvEpqh9QoyG6LgAo(tVyd@CTW&8= zpB?f1uN1IF!z?D~)TB%rf0k~!8_i}^*7Or-9wc7pBPZh>lQF~Kmq(l5nIB{N!yddD z`6ll+`=~Furo$8u{$dUbLMywXd`-!D!qEyL(7dZ=hl0GlD|eff(dyW=p44d!9eTus zOizje9mCJXd5PcHnmz{^Dk!?BbiMuyS~em-8*3USqaq*otha*Duf5 zOX>4|fsw+=xBw?%yjQZ&FrNhC5Xu60BSs(8n5#J>d>Ae`8@_y5;&RwWDPTSB0P6Ge z11r$Te#-1`(M(jUx~Xe_CSa1aZs4w|?Zekl~4^J6lSMm9`KeO!sYc zA8%wXdlzZ+h%0V9n=B&ikK4o$EW5Bx37!!NZ}2etnUiTow>>gJP=qqm>8h4DS0P&L zvf0{D(sjIB7Ro&CM$5^OCH^{*?J~1PLj*9FUnbU##Bz&`ZF}O%qVX}CN?9D^_VPt5 z6TORT#>KMVRQijq8bM7N?Vl2<4-8)fm}wO-KVWo~i0Q%lRNB=JLLoP>L3Rm&wnEQF zT)Ry>ZF?TgKiVFwK?@LYz%Apf7tfu%)tRz>FW&L z9#rX#m?+HJEAL#!%1!d_GK#ng-E@A9csC%4I5AA1000Ro0d$oHtD!Imm@EcDYKtc_ zjhk{FFOjN@oiH--<0q+z$0g@E%Lrqr5H#o#tKKE5rH>!c=kRMBmSt?_2?g$zgeEDy z1HRO@Nyv4_vlY@AJ|FUufmN`cx3@7#71+0XMo?4RgCGkN?;?>BL2cgBy5z0SoU47O zR}7%A!j=~vNq|<{&be4%YKR=C1`1fFDU`Zb&q(lfit%M`Eo91qAKO1q`v#yeH|k~( zNu_#UQ*M!ftldFf0c>qdP4a%*>9!G39n*fpy-|;%vbrh#ir}_F;BIr7e1r8&YsDm8 zj`$Oe42itYL9JbS1wD$ya~!;x?kQ)%jdAPxuL6yjj_Oc5{Z?&O|Zz!7xJ zh~^Qt6!mkP1;*r6jnSj`n(w?I03#QnCt49i|Mle=Aqzg%83}S9_8XBRew$z;w;F(a zFLRn?eeZ6ar7=JETJikoD@zj_AmXttq$&-4#&^^4_oS!mtYUpMpO8v#o;E;{N)^LV zi!4!9{zi0@?0J&dfG;X{lS_FI zIi33$?%U$wXt0*6@zNSRNgaAOVu*gXUL!KRKIwYc(1vaIUAvQgEfeDOoG`XyXqaVfDm3DaV%&+ELz%SZ#-Vu!FW!ErkfO3vohd~N7qtzROPbq%z zZu;4e<;O6k1XQHBeJ#pB#4KKl`8j2NA2HQHTIkOu?H&#EDLTEt?T-tfeWRas2?`4U zeRi!L&3L7ue8K$PBq{9b2o$@y+E0xLL?;<_4&W20dPD7)`03lq{9&#s02oz-gOa5c z0o+&Jl#HwJIDvHg{`8(yEiv3%H6-_9;9pIGzYv<;aUP&z#or!F04cW-wx2&(Z~T@T zj2e^JZw_23R|srY%9v<6=mNKKG?DkW;J(=cIzVg+1q0;pUoIO4xk;|ykB8CD2YYxs z=z+6M+rke48?y|&MJ+acTQ zh!J^FBqD-vQh8mUF-DJDjo!v+Y9->KPIsNTmx6x{S=5`YW3d>$B?3{=8+K>J>c6^G zOV7_K2nnfgv6$lAm$D#G`*UBlT7+>_0DZ>o4gvmd0Jidxl(&10s9sE>N@bcv3!D(22L_EgRsXUQ<1})N?I?wHO%V*-od5?Ko=FyE>Rez*(ym6YHbF%+?QuOI+GG(ynWuF5ufj0W+BW6N=*LE5O_y90%H&8A)iUwDRKmQ?Hv zr0H61;nAX#qxnLgm!LDhHrG%^iLgH4(PVXXIQJ1UJO9yx_d;*28+imAECRk}g$~j8 zs7lN`;r2do>MVy=e`B$szXMRzN$|Yde+Ho?i?>_&1-&_;B~Tzwzr{lp3H8DrYj{m< z_05~6K$?E}YB)+#nv-G$!}mxlSEQayt*!o`8p0giFHAc^4xvYV+4C{=e(0{uBE6CxxdU6+iM!}hX z?TTlK&mwHi+>slj)(kYPxN9c1w3*H!k~yL>KcreY<)zN8IZ*@w{uj0O35#u!L>@9N zw>BOLOBPR`9+4MA4O!B!KOWRJM-SK6vKZ#7(7JN%`YRTHCVz_o@4J>4C#og6A_H2a zSQnP0e=V@gw98!y^Ka0baU)7O!eAecVczqAVH~_Tf0n*$@K5Fd`o7!88gVuFrl-zw8%s-uCOjRQN~Xc8DV)pIz}^)XI?BmVg4Ve4Aa(1X@1KntRfYoRlIUUS zZEPAJ)c*$vZy$~*JRflOoET;K2xG!j3E@e!z#vhnP%HxVKF;Acx6BrwD>V{jea?!% zv6XC&y6L#I&KNyBgy!lqCJ!iQt!wPXkIlz+ypywdPOnt>p#hXj#4oAK(m`<%&O`B% zXxyV31K@TE#F|(YAz`&dkqTAMo}Xb}cS-w=AV?Py^(5y^n!3Uv61*Mf>fYcBWohab zY?UaVU2OAOZiW4~QdqJXI@wrxb4|b~4K3;$lFdQc_9=&k_PSgqh`O|#2phxC6zy-J z?3SORCRA@G&ZdZ!+t=gS79jCOUv7=VJ@*R&xK*xHELtugJs=ku03=rXNTH+>Jn!ny z#wp|Pje9T$I%@UnX>;H2C;u<8`m7DBpmQ7!+Xbc+uF`d%!n_3>Dh~vI_uXGhy!m4)Qkd2>46CC)VgO>%niKo%J90{&c^P_99-u(& zmGuU`y7%8wRH2xVEit1TtW^;XnD%lh{U5C!7P@NdxoJIo^MpOCa08`*OBm9H5yU_U zz9`oKTKCplSTA6Yp%zHXE<52FR27SONc_}xCzlY6#M#C&S^1$ZP+C%H;qs`# zB7U(_&)v)qVLK*y24X>Z>TFZaHD*?82~l#)ai}$_+`3WJkwMBCPG}%4yx6YuJzXLL z2*!>g{o8N83f+;NH=x-awFPW_I=juJTjN&f*2mugHyfH&4J4?B(hYMIf;46!o|vnf zbi3#m^vwx!T>`t5llNNuiI_=xKCtnE$Rl_p(2FNM+&#wT$cv0UeQvh-&|d#?1rw6m z!7tyP77t$UEUYjQjv#XMu^=9J^%xujx4=QG8$flEpLU`{F*z<(n^NVLL>v6LxPS6A zU13snSj4)Az;`4lcI;b6Png`MBe(W$NYdCuJge$l)fmeFq!Umf=!@22Ts8}AP-iq$ zvG|6PS?;!|ehrK*wr}N^;d(_mXU-{z<6>961l0Yhw4N6b`=0~>#HG!0-RoWU<1Be` z*1hC}-9Iz;P6BP%je}@5+}rR^zhOTrUU;!_ zF|q&!deS?~1a(yT#X{z3t00xl7||qjGQrsHPP>2NQAuEu;4F zuHK}yGbnmRu2HIMMjdhF_KfeLI~z`y*F*Yg(F5DALv49D*{t9ZyZnAL@OOlo!F}IH zTrxtC)k?$J-giyOS}fVd-zQR1FZI%?k5M>;MGN zJVAQcvQK+Wb=WG~W8eN8Xo8%Kr`Y(!CaqMd8S-kT*Go?_4a-;rr&N<3#El6dLWTx} z>M!2<=Rt-*TAjF&a-pgO9bGJ*Y*y(a)3Liwgw;3dR3G2~15Yq1mZ&BR^wQ#z2HX~kI0G>;)fqEXlIx=m~MMSaZI%TNj z-~fKmVg)f)ii5sE#jjMf9QB=ILwdEM;L3`k5fYcT%5i+rnIwuH<$b*W=)c7b`0b24 zwy;z_(&&e^cLUVe@XWEa*z}a$^IpihD1a=nDi0ca3TEtZh;N1gCLxMX%74sDOLjyO z3&?gMvV!RQ*XS2{ybwr;GtMRFnuwj%G{Ic8?xFx)5bN>x^d_W&xWUg#aG-?F|h#MWvptDa6A2G7uVE2 z&NE6ma{vLs_w{boq7Qt+{G%hFg)>sMj|L(hC#HY^Y5Cf%DpZM`57hS@SW3XkQ{}y<%WU99D0d})%0xw)OndQ^~H7a~87Wyv}?cIIzOgYKPKpJ4#YQbhjpPYr00WM*%5J%#-gPI}|MpO4!F_>* zA+(Ty01dh3|E%x{RvCU9gNBgz2&1^{X?>y5E1{UYNSA^P51ZaeLwX}r_j%3sgY5Ve zzfcp=j;rdUq$3pw+{#afR{pj*O~3^g%?sFSWmF_}l#K<$a!kMV8Gm}Yn8vFqin(N3 zgoX(F1*Lb*Pm+i1>KMHB8jEXo*AmjonF4!Tolu7)(97o0cd6i9ZCJ?AY9gJ}me>=& zEk>~w*QZc#ygW{0pd``XV25ft)=UfVJ2Ymers@GfLl8u8^}(wTU}COAF?wYolUs9- zr00C>i}QG)U>oXc-23ys2?F?5 zib{R<+aC#q8atZP$4xyRtN=;_0u?u9G>^wNkU#bG5MbMq`*i~ zz}Y6Hv*+jc?qd~`^et54(L)OTd!>j{<;Mvf+V(Ik1~05%hD=(KL*-khbsM~_-Oga! zolmL*h1_d`S&QQAiU^+^T@)8&d&}GejC3jy>l(c@+Z7N1_O|vjq&z=04NF0J*4wjiFLp$BfhS`+K|RF|>oU(>&RL*Y zz3t*4lgq)xCaIUA~+2HD+8| zj!?0~u7!>_TH30A>58d1^fi|^gjoaEheKRrz3+~lvKCVWLZ1foKDvAcYyg8qAOH&) z1;qT%c-RVg7YuY=Y!X`4R&-)Wyg5t6_CGT=Z5iXw#5$@a!MAO>+jG!vVM z(DWUm0hps=<%_NHc+B4uO$uvFNOJhkgWXlKtd<*620ls(7qAQ<8e1t4QtyhbkDkx& zRFhL9&N~?>VpJl+wTh81CN^4Gy_f$yz#fou%@%OzI)~U2GdYwd{($`HHgx_mZphBG z+%?Yh8@**DX=QXctLiEyj$EERC2@YV(-T&G0=Hf7--nhj1@fJ-8`o!uNOCal(cc#MpI z3HGPLJ4))$MDQk_f!_px516N==5$Ntt8O+B15Vd478f9XJb=b`GRG|SY5C#~h4y(W zf%pMb2)fO62KBaFW)Lm0*CWKZ04LT$kxrZr9kcaB`bkvE zINq1XJu~4s-B+}_{9sGD3Xku!v-8!%=HwT*28iN+sB^oEz9~;4@PayZU%YKBhb))0 zLMp=+T2Giu@u}j+y!ZpT%2;AYuwGzm30HyjYLCk36aDbxpIQj-$@MK?=W5Bl)TR-1 z_@_GezWNX@?eg^+rv0FMxuD!4I9RIW!x2*>LS3=1?&|mG?U<_37BWx18AmB|Uz9!r z<5KC7waKYTdxG*bTmb{-`xqla>Mov?yEb#Pp?N_PBSC&_Tn{rly zj-M!L)xGw}o{t5(?}{*d1Mn;x7R6TDNiM!v*x){P$bF0=&wgi8zLho_z7WwQphQ3a#K@;B5w^`U>wPmj?&tRg7WFODb~xEi_| zC4TI*ixClBP5U_j!RxE>WnmHeLzKRilDOGa`Bb2@Cf92uwNQq#uOQHMemMw2^@YAdRns_DRl6BtE=W=9pkV`oG7;a2h)6dCpB zT4K_TmLr`M<7Z^Y+lHeXR*2&*@S~*Go_WuuWPAt!BKx{N!Nh>yhdd703JQw87}}8H zQcP2&rnBMuCbWJt^LuCvZ=sWRAmkC(My$x{A!t`PYTAoNjvysm-JlvvE!?y*L==g* z3~##>$xZxof<;Mr(Vh7f%dn8v!6VoH{sc7+-|hf>^uPO@pENBhsC*j09Ef3;B0m?4 zO0oj`uQsb+DDg+S+8&<$W)+?#AE)MTwV4M zasw?c5rv+Tt(S)G@YmSMyuR^HySATj}{-Q`%0K%pF!&|#2T3( zx|GT2IttV0Qf1PKiE6sjPQG5HdDFl$I3_UB{N$B^%zzL-SXV}^66(RbKYpcaO-W}F zw(MJH&%5yq<@Y_-x5TXxb)7&b9fjE`GxI5nx~Iew3h(CtoD&B(P2CAD$XlQQ00RI30|R3q z${U$6DmMqQfKo~LnLX`*PyXKgAiOaPs%2$&GxhiMF<6nXP}NpLQA_3CA&Va+U}hiS zWl}+_>e!B)(WvWsSZeZFjb3|5 z&P{nr&Fh7cq~*EY1eA|U9@tquBVW)bS*ZG^{;QP)jvm0%sHuW{Y)iiA9ta+b?&u0i zxM5)%wv$$}1?eA5`UGWSc2?M`bZ)({fQp8m&qVg?!Do!qVaxB&+FYJ~s~%?|f zQszW1Qx5$o+>c|dCjoY_u8LZ=Yc@BgV^amZnk^qR9%wVoQyYX{dTxBE4%CwrpT9m% z`>W}x0hM8l_o72jG&AOC8qyk?i}6B!cQ|pg=6#Pfo~t`ul}}{Vwy&);NMIe4B533QG^kSIM0Be7VX`L4zCefa>4?; z{NH^~1&(v>$Sw(Dcpbp85PJ~t^ni6AWI7Yc*-7iSGC4LUs+8M3kt--hd_s+5fB*oY zau+XjZD5!x7z(AM(aC|8S|w=|cX})etzez}ZXPI=Hsb9>xFmSXVB=vrXD;}VgtRF^^PFE2F0nq zjfZ4Tc)-)qW`j64K4fZysQ+&dqjtgc6ZQgndBM#&fjv++tI@U{hJ?MPXG??n)cQzZR%1HT>Y*YKofnqm%n5rk zD$G)gZ=2EuO&X@DBJEG9Pwhq$dAy;60lWB(rtwH`o@*YdX%7>4RMkNwC7H!GE_$PL zIiLUo{yvQ;axUj5z83k@@MT$J;zP zU?dwH`zWLmsj*+?7%nWm)hC!x4V|5;`3(}<|3<2n5%BMsJZ$ZQs*o4iRlzbdb_RHhT$a6`( z5k-NI6O}iW^CIryvnJf%F~%(S%4TLx=|BJg0|LnEq^~}nWs8k3l-3EQ{-N(!tqchg zAB5y*iaic%oR=+lA~$f9Fn39kpKO;=Be8%&8ufX%Kz{)29?*-OpK_rohzs7Su!>jc zP6+!voT%FwyYR^LrvNkge~`>XZJ7~H%lYoo-$+ceiXQ;+99Z(d1b$Al!a?yVY@ptj zk2p`4o#HcWwSi}k-^ada8~%t)#vnYa^lv`4P@n3^_8=p7;qrpJeDELuR`<hjn&j1sgDZpRmZfu(=|02W&| zjmF}P;DglE75bb!R*5Hr0XTKqAhTqFbP1YhxtAB@V9F|kU%3e5^8tn_pMHArcx88VU&V}e3Hs1zG#!$SkM4UCe4wTrC8LN5%^A5AKaNZQ~4%B zh|l8Mz2c6?=3ZSFEAdA+d?HUkv*FVMUdJX#Fx%D}5;N3AS?5AsoS zr6Si`=%o;6jXWJJSo{)FameG(k2K1cdWvilOO{*`*xlAa;SVsIp=KZeDLhsdXY$7> ze+HF%<3;-RjN@cD&Nlha0p!uw(Lr;@?;c-qpD1UFQ6b>$c=|?!Rm1II^gJR zAnd9myYzM<6FDL6>b;s>&vMA~FRascAF4qk<@x_~z|Z4MWrTzo^pw*sC7W$7YW|?f zz4@!n6>3>PKYBoa@z>$Q#}~3Ck6@xLkMqGKFaSWgEY-lH%dLJP>uxQyv|d62!2Hw{ z#L*uG#q}B4Fc;Ro@;i;;MXPIcJU>}>=U@N;YT^BY4P&m^TK2tIl)-Wy;(=HlCS-YE zJ#iXb2bT-;^oYIglm{h*EX+Zp1Od|!>fK3_M}ZC4{Yun(6at%(TC|nL8}wzq!OiJJ zFmV6h%zpk$1$5{I2Vm0yE@EK17}UNGkP&{+(r(ZhpK{=P)ji@>V|S`$Vzb#$U|5dW ztzfx9V9s+L@d1en9amQn01WV68eCLer>MGQM=Zj%^V~Z($Gr0BNFeRbto?Da+3Uy@ z8JPR+>C#F^pOUzzS=ayo0|Ufa2QfRLsh80rZ}@*@>;_YTPF5gfoV{aM;Y=c@M>y4M z;6*n&GMlW8J0#V{3PVLE08Pu2*BZMmz8WB)y0jdNz^jWy9WDpsfGN9|t|%EZ)k3)A zVjw=12PJaX1Ih?q)u7+(AnnO^yhtzuS-hVgt9qhA#+p-JP2p?Pg1thYs&u%RbILpl zd9};mG-=)nta-CG@_eU&nrER^%n$$pMgj9tB}Rwt?a(-t^Ff>|13G55PMCIdS|??dZ>R4xamuhdLpULe=tN1I7A zoq-kEf!@i$00~MUdn{!8a&3hpT|^`3JH=cbfgs}MvB{j&ApEsOt;?b59D+Js`J11L zk_s3gUu97zSXG0VO0V*9)GDZsxP#tfYXBZV*^J|+$pk!W+-}*}th*oGJm7fzXmf4Z zs}EvUs-{F&C%_WU6=$A+j31;sOZXT_zfFVRXE7Nx(%|;yT*hc(mSwOV>zlzvo^oc&ogy7;QFVZ)R&qd0&y_c_Jl$LZtrmOgMMx4dYo86V6j6vx!B# zkKxh&2a4*^OfRGWJ|cdJ9wvGA(%#e`{i!14#|1> zy0vGH$1~VCqA}f|000Jx(ite!q0CuhXLiWdH72HF0)Uf^Ipz|;v?45Y;g(^xmjSVc z>2_;upk5_75+)zLB7PVoId9-j0N#y35q%n5De?BAgA5qbXL;XnbSjtwiS$V^!cm}p z!YxXGEvP!Pm*nA_001T~N9yK#^@~z%dTY%~tzc*?)UUXj-T$P#Phq8n-t0#BqgN&l zAc=QGEi4vhVS63_?)|l&0bDt$`~yUS<7)2h*)7&U{-!Jd00ROfBK6-3?^Fi^IhKsr zbZpk)2bUqGw#Wf}7yN&uK9uoEws(LdZ1iN7`T=;utgs(4Rr5I3tUpLfbe$Y;rbqn1 zQ%i>;3vB=yRei_rXs=ik5-g7zo^s$Y|DOI-UjYRi8yU5&4RcPo9*lvPq9_)JAOMU8 z+X|bf{GxZ@cshLygo)v?@E+v=%R@;P@ew~f-#=0#eHw2~d{$^p78puqT+w_W$IVr*pr4a%14mp=sQ(7GC?(2Sg8X$MzD}KD zZ0=ji2;5~J=}}MCl*45QGEsa=ei)$M|L8vJdpyGU+(2sqdkaDZcqn~70uPtz?- z3!$YXj(8N`z*Q?z6T%?i-z!>MP9yi^UI&Rc1)yKCaC>Vo{Yg=PQP@f{{?g+=y#5Uj zc`C&^8M-9=M#GKpU=ZCoAWXv!z4{*1GhKYq^1yXR7LVMwrQNf8gJg+^tLiXz)sf}G zJR&kO8}2B8000eDYVuiO8QdPs00PUmT`_=M>^8_CRv>@kXg;$>l{!5}r3JQ2PTKK+f#4l7m<2LqWwmRMR?F(s%lZlyq=V@2neqZttBo_THx&Sa-&9UAnHFe3s^SdD<=! z&s5_Vw~)ISBF^H8w}#yVGou6}7H74il$sAQJ?n zS#8T3+ilVR5siH8<60qlR|#hCm()^;=P(skiMdFq&K~{zCM~^iWhMSxrR)Fz0{{S4 z1x1d}AAwQReGEVzTfWxqz+ISyC_tXPWLFDgjZjwzeiCDgbcOX3cUnKzJ?{U_YQDN@ zGx!{opQD>KVR128mV_w>SoO`*eCa_%wai&l-j{l|k1Df8M<3Kw zXZ{{SXob-;xVJl@`T>{UQMwWkV**2=mMj0*j4a=>!GrSt>*%Xexrm^$z4M1q@r@%r z&T&4^aB%M-=T7&&ArnAdB8$O|y@d#+AVvzl_)~SyTNo|ZHxtlCF7toThkWLNiMK5$ zN!;2AT{=%YHwp7%w94C!3<(NY<`v0GD6#kzkulNr6Jb&1Xv(EXgL@J=k_$=f=o!HG zfGBvlHnRPU3@mim8IgcPbz1)&QDrYxoZdnlL2+#Txy27DTP~(onI5UPL#=j>{$skd zrb5|Z(8mO5%kI_zOqdorfdE#j2w#Us=}%p$?#A}aPH$pFU?)|{U1Y)XEEN7E3s}HX zaL4N-=wscuxG0hY>$`TVpRyl}C1Ed0{E_b1L|+PM*wFYGbn9!$1*B(0zv-DGtzE;J zYXMnm0~N`dU=Mk$8P#(_L%+xQW;R}vj5bbWAyEQ>6F<-r3?_b@3WbB0c8KRZwdUA|uI zCqx!iKtNOB%>R)2$c1MF0DIS}{=9^Kd{z=$AcomGRy4fIQ=;Fm%RDOiOFk*KLUjWO zmMi07fzuB!_zFivo3?k=^0Uo87}a4#YqY=7D2vz9LzO(m=pC!w( z18^y15WCw;R9qUrQyk9DM+EpEPM}2W5DB${ZLGjg;_M~ zvz%{N^pwuWMEke?;N&r}h7mGc272Kc7 zs$()C4gjQo&bsT}jITVyOx8MKfLIMh95jA6qj}mldPX_ZBLtYITl>b0t0i*dIss>+ z3hbGu`()isv_YnN6Q5-{m-CJtQJKCe@gE_Odizy-41|%`?(@= zH}J87^+EF1^s*FTB@>W|n1y+vB(Ggu7O^l)eB2n>4x1?h|IaoJUiA?QPt#-Usg{lm zM!Z79J9s|YM}YE`xQgKr%X)5uks$8{-K)GVj}Ak?=WiDoB|oB~e0LqOyR7BdE2F#z zA6kow6??W;_PVfR!1t82&JB}m4j({-pkRyN36*;uxiS%QkpKoX_a9?;#ubj}32JTU zvL}_Xy*nzy;b^L5j-kwjW*zxrUWMA=zyM8TvWv@<4P?!k(O`u#-I|?NJ^%@7p9Wip zY-O`LGJxZ;V*1q`R8qPfSK`m;2P8kQ3DPm(rL&=dbpa+uVdMNA+|&fq;`pX5suDT^ z?C^lU?<}rouVITmP*+!N4sLeq?&i}?c~@pZ4g>?BovV1Ztuk~&9h}&MD|bZ*Wh;%s z@lVRSp7Cj#hMvy?cH>Fddo96Vyl;MN9`QC0zGDV|J6BX>hvS__qCs4u^4tFcuq5UF zj*LF6_INl-OVJxtV)GG)*symGq>VL>AJD6{VsiLo;OC8K=Y0}ctF7W z5RSgAkUVxGk%S#-%*GY{{N1*b3&vjUoP91gEik|hvhRCU`o4WIX=ke0r8IJ6EgD7{_ovV-UY66y=5^M4mfin zol^fPopyE2?l-8Io4?=EjV6PJDQg8m77=(#rcFVtfi{InIG&U71F&ADW!UyqHJK%2 zh7%#+1QgGA(!a_Up9d@~@Z{p1fDOQ?&H%fZ3c}w^`=1{_7rj@M+0Npnd}g+%0*Pqc z*boI+2N$4sH;cw@0RowT0ssI500g|O;Xnm=B=7(wv$V2<-f3`-d0%#kkrIV}JXwcf z_)@}&laE%FMikgJY1HDlBdlMTivR!vutAy#ZHoULjaTqIeqzMmu|O;Ij~NVsxsw1* z{!URL02Ea0)qZ9mDH3~&^VVwtcuxe$FoF9h5T+9efjcw60009300RI30{{R600093 z00xmMJXo(Oou6%duS^?$ATXY$|0Yn6Fq+7z0VhB?$oY_~`o^Tobj zk{L-WYUetKHuugfsGMs=p9EfM^EI3kSP;Fn-!JH8`POmPVeD8Mm^hP8uS+H8o?2y^ zj~7(4YO9{;q{&Lw7#+9|r{TAQFZdG5PSV;nwYEB?TefAXx2A0%L8VV|r&;#n{-6_( z5_&8zm^d03Gg!p)bys2|aUrKy?~%^ooy+5#Ea>#@R>Gbv0)AQsyx)A7xLo`>I@^Tc z@yF|WR!3@P5RJ7ps-H<$`Qyt6Hu3ka8fb2dVSM1ckt3dM3CKPB>^5N*{BWMANd}(a z3sz13&9|5FI636?0)Tt{Pgb9bjRe}~HM-7zr;xZ;2>7WEYIRutZrRFd84#~Mj6_Wt zlhq3}5bMw2Bv?8*`3c5NbCS|j0p<+PZ)p5pSHfb{Z68$s2$LXPzqkO-?uaJ_u%n0S zDw0QV8=kDfN7SB@{NQVu7jiPa9*lW!Se;(vs8YPiyi}7m1X`0ZD?pArmUWh;hv#WT z4?EGTaa<=;A=Y|lx$vAv`UtOW`Ve?Lb3!@K?r`JNMKNkkhDNRN%6t6v6f~i`#kM$Z zycDqCs?A=gorrd}!DcrKrvF3ja+aB>J)7rX2}h0pbkx zfK$QH61U!pgguAU)x($6!;*$mA5^gdYa;4-pD_446=FMB0B>*;?o)Y`eB2LiMJ za9qVEcStKFj3)=ew}OLw8M6`rX=jB$6+x}AWlO-yfdBvj7(t#8FCSk3YT#^mkpDCQ zMax zZ5n7QS3rFV69Y}+FiKi5AZCCUAy7G4VJt~vItT^%`2a{-IZ6%I09(Yig&nYf!r0J^ zHQpq1P*FU=z8?`MpPJEDHjU_2(`c6yHK9zql=ECn0N*Hk0Z6W&xF-g2YKa}#MR-92 z-yYqmUa*a7))R&yOLNMm8+KnR9}os>#jPGL+iA$)Zhg}4@lgVn0P4MgsYBFhGQbb1 zG?*yXxi-^ac!eyat=MpsgoFTOT>$rH4nU!DBt;wwtY(MdK0hY9zwjo=fKH;;z7({} z?LXK)U;qFBn*p8}O-lbkCJE#K00RICA|L=h;+r=89e@A;0{{R60DnQXsZ;;}NJBJ= zqoP3pjRRAt01%J>bpQZh?*XpV00k|i15^Njo?{CD9bd&7=Mk00RI36d(sz1a5pA zam$PVR;Lhf0024bL7Eupbpiwk3q&!XLLUMUkRV_}2!Ka_K{tfnBsX`8GS)?fwD5k4{jbOG7UXBR9ZU=iHW!e6kpYcVc748nP7v_Fn((ehdsNoiA9OKMn5(mv}r2~wW8(yKW=fx2fGDAj|p zbvlwjH-3>1o}w!KkzDjFthlXHZF}17UhacI&Y9yTFa>`iSsX3RY>oDdo3$n1*kc3t z-#Z{%8jnGPZOe5%I=U0}f%CI^XTCl^JEMGb%uVkB9XP)X07EFo5NBTefdH7};AEux zKjOsS^3R~B_OH@)HHciAIO*5qOadOluU=B@>EMWv&(sV2<;ewCRoa6sL{m|%c zxODeddso|)wMBEJAzpnaB45s-US%U)bMU-;T^ToyBM#|O1e=4KsYXU~(i>JsQTux? zpGJ6h+ljP=iryemFpK}lbHlf?uE|9KM9}iv!ft28pfi_gT?}uq8A`ZR;;sEC1@+Ov ze_qidyi7X3qZyvbvu{95+5_lc@h`dU#~tQb_?FB>YqqMt463WoaPb`m(I-dye=<1i zW5){DZ=Y%^*(YmSLO^`{VAZB>6ZKa19z@gf_C|P;R2{Z7av8RX+G$IZIeSl_g-0y= z^md#!hmUHJ7501-QKCaQtz$Qp#7alYBxMLlvY~3vwI*m--5w23*8lcPlK!`{Z*EeH zS&>fE;2foYwcB>*>I(?UFsIaK5Eo}m^N}Mg>5xlH^&*iBTYIRpKs{C;GwrX$mRo|G zkBU`%@ud0-uvE^)bHoILV}qNmAf<40;vpN5Qdgf1nuxN;hpIzepmi9BASM|73l@`^ zl`Ui)hBAE`QY(My?)!tLne1!Lg9~9{niroa1d0a=hsB#bool9=r}jIjbja427Hytvm2DX0#&Ke4B%SU7Y00RI3 z0{{R601KqV6Asz_d~?H_^(df-FvAU6Z6+})A}4QWX&a?{>%Wi`Cibe#ESvPuy9EWY zIIj}?&VJ!-j|x@amh<^id?>nc%IaoRbbWwave`a%#AV7fv1PBlyAxXGiwRGr?z6sP~U(WuMOg#ij%aC3ZNDHFEVXBvd(z1K3K?E=J}N}fGZ{qPhu)VbuVfw?udk# zSwdTWhtolbjN?2`fY+MkPF8&{p=k0&|AlfE62;T-RgfcagbmYj34G!TlJz=~B&_9!QaI6D=WM_j%n1OM8%mPu91Go=v7l$CCL(#)lXR-lz|+Kl~V@YtH|ts$ra^f2)Jde5W+BCTV9tGq@S>+*%dWW#iOZ2hRD_XEj3qvF^QoL*};qrMi|LZZQJ^=fP8%b=xxe*t*xYD_wyWT-OS&$-+ zrmcr!V@qaCjRLKzE8?D+m3F7A2#>QaSCQAV4qYZmG(6QPFu$?jb8StDuY+62IbK%3 zZ122PXvoin`NS%79k0LF26?Sk{LYbVCJl6|C|gZ=^q*&(*$ z;PJwi1=V(2 zP+w~IMu~{bs6&fw8+{mog4hs9w~X+;mQ-~^s2F0raiP1{Koh*=e#S75f$HwbeBGOTW zZ2z^O!^KqBO<7`OY+40xX87{9am2Heo-;KB9E6V0++gI<6xEQUqacUC;3t5uG{b45 zO?`iS7(F9bmVx}1amZlSK&rhdSZ(1LG|6~4iNWM%xSD~Wy!R=X&PXgClT-g69{-nx zh3jDU%x1dtXvmr|s|q0jcIlE=@tq|z`wa0n-D`-rX^4|K&cmQugNGc+Midr5FK|AH^N0aLlNv zCl}dK^U5F1!jNPZ+-*Bt0L_>~^uS7CG#@mxFr)*xAc^s}zc{n!6Q-ZQgn9xo#LtP9dtHRiKb9h&Epq?>E z+liZ)g}~CW9hY#v^z|G0{vW8bl-8`f7iQlCk48WzUM%Fw-G$&WTAfLXXs*KG{vm^x(9{$DhRoV0(c#!h^i)vK)#;cw~H z4{fa|n70M@jDgjR4KFllTHU^?b4C)U*T4P(kDGu5rQ=GYc$}k4Y`5Jq_*&3XRq10B z>CS`(+$(g;ktOV^RiN^lO5G_PN*Kc!yz_J$oV77U9Oh1^1dKkK2;90$cF#n<>0K(Z z@Y0*?xP@4O=#Dfo;juFY+?Z4$3=2Wl#=B#)@gcZ*QlwW`T|?D9s_bvzfZi zfJ{Bo0}n>@l+;9MMt#e`6X&E`i)&@nb~K1Nq~+8gfz02$bP`wZ!;*%F78C!G6)?p> zjkr@hMsoe*c+X(xXzQ+!96FcM^>(2@f4eEDSgK9LrdAOCc;n8?FDmz$(8=2jifQW* z7NoB>XrourRnL+;cG51697<*2nFB+)1Q5-q$&f3}U5Q}N-ng*l{-ZXJH1B;J?6E0N zoIZFfpMvlnMq3BpcC{*iK}@Z)L{U&R1a>HAQedXZHPD80tsb%sHsar3J-)hX0P$>x zk!NFp8oT>mIN5@Q9%`#;bL!1JLDjHL>GP_4$Hb{w2KZ#4k(V03Ah?82K=|78w6$D| z?eqNL7JHk%q617a+FK&-2u zEj>_s?{Qd@J!IClF#=0k^>?qi!wRXGBK-b$E_#%vv~u{?H)~@(|+MZ zXkNd?d(pT(3_YHJ|NS#&52T+)`?ky3IpvAW;KN;F9Ux5<<20y%pSl{q1-uN_zp^Q+ls<?9Rn+tjJ6pDrW2>RC$m6{6a|?zGvm)N^ zwK-q_33I<MC(z+--icwT4*z=PtvckW*KvXB3>uO=&?gMt;C)`f8{^BK|9P<`pE zy+0&SYKk0f@D{T1)2H98brtdR*Pdr!{XCM9mCJA&1z;RpHpO}f$So;Ao0dYI+4G=t zw%x{~ZbC`1BN?`c$D*I%)*QRy-z_q6C*2vxj&qD{f(SL+0Cr{5N2g0BFlZf3E^A&E z=N70q{g*rnP_Z(Aoed#>^r*l900RIK^*cxt2)F&5HZEF4nYeQR6Iw6S#hfr=o3Ya^ z{OGk7s2BKKrE$I!J;mf(o_{|RIGHH;nQPZ0YhgdB56xPHXOE`AmhbhS?#tBSb3o`> zY}9G*xZO&>MkDuNZ-77MR!6eCYv!vEu^Uvhft6k7E=RyRgP0lh8QxX`_);ezP<3iH z$S>gLrq}1JqVXTVY}4Z-m<|oH_(QF-rb>|a%LN>YZVmFQ#_%U?i8G?^CaJKeP z^sQlX?j*4sHHk1TO*<4ZZyO99biRWa1TsP{@E1ealiP3^dt5`dAR#wC|AN3$WB$BeLLEDHl&X@m|!^sh-LNtl`REp^qM zkC^*g<3v#0{;;#4XV*bY|t2lst4=#4&&Z$$>dV zF^DPK;<=_27MZ}EJ(hYzfChnUqMy8dPTavm_d6M+`cg^u{2W#rMgJrfQHqX^bksVF z7@>as)v=M6TGs3Wbn{^PH#TGz2%11H4{_vI0v-7f zkcs1=0Ko!H%!%9I>wRQ&g{OVJfxHQ5#tef#YC_weGYLFOhC6$ zzC*o>Va-KpX0H#d7Uj*}J`=}D5y};I#GX9x4H;8j_>6YP)U0+T!^pQ5>x={HDc zsi4`;s?V|%P`kh|9gEBz+DQZ8DAd9B1hsp+p|>8(>@1CRT&Qzt&I~EDLW9>8M~{E# zI2hHerZRP2(r-};NwD6bUaG?Q&WtH%)PV`*jPcZ{*-JD40NmaBnCvZz3`zW>w#PIH zSwj|iq>MZ=q6OXDHReZLueO2|vfMfg(IM9gZb8)3SWbdF+GGje`5p$fnZ~7C`bPin zxU;GvkjM+Pqy5WU*dB9^l$&&WmS=SsLc#m#VcMR(;2NY55vYnWtI>AJ&4WB&5MlI{ zYGjXkLbV5&wMvCxvWHibnaKBV*}8-e&d6L>YD<3iFU}~Q-d>G#-z$OzN(a7$jYqew zJg(XPJ>EZuB~3uP%)1MAb^roLw;J$U6mxMn3kh3?8AYh8r*zmv4Ea~tNO^x~6YAf) zKfjB7M7+)$hXID{{I^EY?V5{Gp4Aiv*`U!9j8IV0bI(+lpp3>dt#TzJ3tjf7R9jk7 zuWrKZWc|O_JT)kx+uX{N?egK0WR6?xk5duA0jyL){R_swy*Egu0c#D}M=Sn#GKS=&Sacf(@d zX4zg2_o~rFr0McOHCm7F4CQQC4ONnal0rPdI_DPOp{<28u#y`6>y4SC1u{R2Rrtx` z8`^8Z&cuuCbbwsA;8$S2y9nW)<0)FgcQWqrDD%8siu%kK9ow-d`q4;teM%cj5j@_) zVBWO^SbOn~;$8u*AVF_E>ynRftdyx+#ovngCk)WhB4JUWb`DxJ6;IEYSru!&T0jw) z$1gz)-fj|d3YhC`tU+oSx2k%jxe~>V0nY%43;{E|igl};IT4r(tLP&Dj|h4wmLUK% zls4u+2;4Fa=AU84FaozF_#qPuQ6yrTy!hS{AT^-H6lFrlU=^GGz!r4kUxm9mVYal$ z9S}hP00RI30|0ZQ$)hH32-#tsB)5S&3dp=(N~Clz;jD~NMtkA>oY~4;L3quOQSL@4 zYe0U9r}pQva{jep0$h&ECLB>{JfPr z`6|a_jP!S@RhM$&)7{2B`h7vxDI3DIn`W3kbKDHkmBuq8z6n@bY=4M`+6HA|l914d zW$;3ux2P--ya2FQ(CPA1C!SHDFO+X#zi&1u?c!PLGAwvA82hfVpX2WSR{9IR_mCDc z!iji+#9R>dvOdG#3rmmzn5)tjMpU#T z5*>;lrnE_``JSaQCf1nIcF9;11v64G1h9|&lZP`JFmL7dGetKJ~vqhTUJIHM5wrC3VB)YqmkV{ebo5whE43kUVZDMIU< zkS9n%?e8>KKaW1vWa!ci3{*KXTvs}{`eUiXG6x{S8X1?Nglq)sq|sr!={v+D8-$po z6Qn4AK%IZcl8Oh%54*xsa6-nbW8pWCIgTfLNlTIhY0&=Ww^y4E`cOb79u0 z-`jD8+nqIEfZzh_wXub4LZ#g6Qfxj*u9`id+hQ>OFZ187WDDLc&tWp%Q6+brdl;O} z7coYPu0X^VH$n8_qaw7Pq$?8O+F?(tL9FH0ao4Um$9B@bwYNeoH6^-h;k;;=m^V}c z#`!P?&0S<}fFEQTyH8x&zm+%})m%NM5vah^ zwCUo2SHLVIrajprtbtLZbQBHy90z4vLJSS5c}{Z>M{B~F6q3{M^-+iQ7^GIJZTODb zs$gkC!Wf2?Kx&@TD5Jyq^sC3a{uu50L+3S`2NtUr21VEqq#VSU3FZi&`6_rc?5>%b z5*1sV{K_lE)VTKW>d7h7V0g{QwD5oDUAq=S2LdW_U)J(UV!e?bW|Ey)2P~A5V6i!? zvuJXOKsYB+TK>@PfKoptz78?WxfE{DBP0(e0j0IhIjo9>tPBQVE)|Qt7ML7@ZI@f) zP2OZ0zE#)Veu}7~QVYL3T@JlA9Y`gbM+0AlZMwg=%tnsS7fq<0!d7f%iB`@y{*~<@ZHl&4`?(-!DbD+D7C$a5~aob4eVjHFUCM`%+*@bzr1Z77mBXq4LQmNcCw584O`04k*|3*HTZm z3`X+5f}gtXS#e$ziwAium#*kL@=FoUp`A z>G*x%I}!TeH>vD^Uv1yD0(M$tg{xPn4t6v1U4)j8P64EHA9j{_9RN+>S=yD0RmRoP zeqkXCeH7&CI>_8U1&H)Y=J`iEp%C^y89?`)YRQFfxt1#NWE2}G-O|PmEE-ZqGtF_* z1!Nps?Z^!=C*Zru=iojYbVa~|bWiA_K`|%)!vDCWff%qcu}cq5Sp?G9Iec?7EvsUu@I}CcqEK9X}QG& zXwXU73N3~EPDwk=2#=5cw!1J76#9;lx51QSF2g249mSBTc3F6)XOnOZC}s1I&n@>C zbk1SR@ZEEMBraZ&9t0B)?NMX_3ZIWzF%fhm>kQmxX&<^`mmlT0#2pISA2rsMDtQ81vpsIE+n`x)B2 zCWp4XJqEe=oZU;c6l_GD!ySdDC!<%69m@=jP z#d9i@!bUvpzQ(4S%qd`d1uOAcbFt3KFxlRtrX4?x zRkoniTg6nNuf>={VFBb^Rq{6pP}1&V{i4Z9Gbg+S18Q_y)CT~Tw;(1LK?^E29gOL#OfomN82%7k3yA} zxkMdnhz7sGxhUkv`zB)$Pb{<7*fSw|Sn2(chIIS9=d<2nE`a*XaR9WJw7E9ic0`!t z<_*2#airr`v~FhQ0JsGgcJhD-mKb3h{%b)^lBG2P?ZKw|s`#TxsDdCSi*&4UwJIBG z%=*_dOJwp=d^D)hPL|U zqL#1+lEirca>~U$OXQz9y$sinh4Q6)ku( zLlC3$uiJzB0pwGJ`8`H>BfFa9|rxCm7qtJ%aE*!2gPrKm!6BNz}zAPGt}B&2=zY8~)# z@Y}s>$U)vazmRe!`IiP*Ju=il~ydN*bk{KnDA2KVSpxbldEV8@KMOv_jornbbSmZ1_9t^J~ zY5eWaX^Yk_#oTtT5#@(vaY=5F1Od||E7}sfz0u8JiERr^J z324`E_fX*J6$~@f-M|DZnBJ^=Y#CSPARxbw;8u7ytp2SH9;r`RsbXr>V0C0f3S|^t zy_5E{kErG1!{9+R^Bj;L+Wl~}G40+kBUC#K0M^@DMvz=%^hcf^kN>V4yiklpUfQ2v zkhO?bJ1!{o?1tt*I4W>#`l3*7^buS%(;5=~1`_bqJvKr(jQC(q-$$_TV58o&4%lAhK;LNUw(30s=m*ev!rt1l&F8) zTz0t(XYuhUS*!f(L-#gFIp4{S(3&1qtw^IbE(A9G#2^H|E$JC&)IhCro}K_&EagRB zC`sS;6@<^~Bl5`P+fbm}jYsWu0C@(MYqBn+rwJL}LvSRRcT?cMTDhxi{U&xC3M-4x z`%JDJ;lPbB8OGkf4KE<{>^kqVDO;F8_4bph7N^CgYCT+LUn75+KUl42XK}DF3^|!r zvs65@({uirYUR2w==0f5v;R>r3+f%`6i$2fPk?L-K)r|3a2(A2pse%UclyJlU5B1u z!iVFzJ88T3V7A-a@o6F^9$+uP1Fo{#D}?3$|hV3c)%811K0q!qNnMA0dF1xmi^O1>o8#< zftspz_BZXFpQ4GTj$O}>CN%Si`zOHaqj#bXv(K^)toiVHGv{(K-Y&`N*LU*b3%HeO z2n~Cvani=_L^neLKT22l;ooe?2$|p+iS^&ldZ{tH;IzU)`(u3KWI8lv&j)$!SlD!% z2IDl79u8bJ;XYX~02j~PM+*q1B)R9Sq@(<(0;2qn<9+#F!(rioB~XBP$-&B2VbQp3 zTN`HUGaJ)sNyTs6rK<|X@cD|mZ$+OF%sI8^TPWC2Vk-|x?dZPqk=?kPzPzBwv%OFY zN+-$y1nvEyRPHLxlK>QA!Sx?BkG?3k;CwM5eeJmYd#r6{6IrMnj2gDIPV2(Tdgp62 zm3@dMoa((;dySl4`e`?sZ!`@8r`P9eqHFr;Rv4W|qO#X(U=~oL#ck&3iE3{ELU;l+ zc<|S}{Vfl{jj?0&zgw(%M4cJxLj&zIAY_Qyc`xM0d!0EXL%^jCW^8zBG(Lgwisqo1AaKfjoh@v41W= ze7Y>d1NWDMy-+fHf=-mIj<3Hpo&e-Wq`gy`1AeUD%Clzw-2zU#o-GXtMhQVKKx~jh zI~f1a9K4~ZBs+>5PTvXBmXyKv&Y#G{R|4lGUzWpRoy(Rf3w<`b}419)n+-^w3{}zd+(3~ z5;1+={bRhwV%o&j|9fYjxwrH2v|aY11m377yDyNz~Y)vIhKE z8B0cLVBL=hkm43XcnWg5hE@Fzmius`*8wS9zv}4PT$fH}aYW_=YAz1` ze63y=H-5M6hwy|^lkSp#KP1&rEqf6e0EF(mtw2CCbOvV+r}u`prA7ye(Ns&+x$aN( z26}(^Mrog|>>}&Mc1ui%%4r>!cC8S@oloG1jJil-s(w{}K7cEo{utk`DPozXzDVU)nSce_{Kzl0+K&ZF%6B*B zekcr?>3oJmtdbtQP?^RIAwzfQt&&^Tpq@JZ<>jqoF@y@Ci+NUX52<*w1K`33>)LP= zlFuK5+gEQn6iO6Ut;`<2MD$QopP!ary#k(DHg)gi1Wk}VCCXTQ5Ab)qMPyCJt=Dzr zLrV8=oXrW)$7HHTH3$5oV+#3p%fI2=u25WN6h}aVHo!Cp6l#g|3cJ_<0JX*eAWdnb z$`Q9eh#+ZJWs`;zbotfm_Itx=LLX9w>e%0UjM7;xzCF*-D-6y(}Y&}N8 zpYPwuEBj58MgT~_M|Dk1)8jtIh4(#*R_=x&r%`dmH7>{$@cB<{p6i5gZPJ4>5 z02xzL!r}hIRl9(-ND1fuH<{9Pc6q<`?&In&LU!G@whV3ft$&XSx_d@qVpy#P4B^aG zdvR+pesD41whi4F@9qWHf6H`N!2;E>=&=K3jNW{|^-22YzNV#`zd-9~aVTNJo8&LC z{bVD~W`T_6aQfpW{O0y4OSE9}B5)0! z6X(W31bTe@?dy}V6KwH!ALa@obEB<%ZV<2;h2f&&008lf(3Ul|xPYT54wx@%iJAC^ zeAe23?KIkWI4SOarkBHSS&K4wG>m#i+j&w9QSCj?J+Q@$Jox ziyX{AYJdWfMA{DM-+(y^^+2mywDangCvGZd_WlKPLyQ|MS4y^9>9Rf_Zb0CFXGGrD zaiz|6#4uGW2)~aF(&PXhT7e6uGmYo3xf#8VOX7@#F4MF9a`3(-Av`3p*{_Y8)Be7L zRz)0iTN0EdTE6gOCE*J#$S{3PabOdbZ5Vn`(uCE*C5nOPSdt^xCQ#8NH{9(TZ345O^F}| zB&v5Va@P8FRCEAf7CB>AN%XZe{aL*_rfB zF8{D7Q?sxIL>MFUL5c(cmONbY;Sb$?CyhiS-ue%pcQImN(?obZLV_@P3_zz+a2Kb2 zpoHrUUGj++-sSG@4CF|0yNU~3%^t1237n(K$st8-t-pam@VA!>9aTr{-&EXhp1gp=`pnV7B3lMl{?oNYU^{dI z?gK+rGnpN&wOODzkB()X^7a_Lx$EnMQz-;&k?o@p5&w>6z$68uP_%q4fDNNwM)i9w zXVFw2lm(jw=_V?*;)EP8E>B`K_f2Dt@G}@S+&)tOsA`M!kUom}EYK-b%82mY5J>w7 zR3}*UZnQ^-!|#^b$j+2B;ofq|;YuS;xK?6?Oj~rtR>o(K28L=Ri4M8SE*PhvNPLn= zOc#`hW$1A$0Na_m1H4dX3fL(;>jGWSTGkYskc@pc?PHhtv&%U&INu#$HHX-{sPg=( zyXoSJNH7gdQGijq4@{qx)Krmu4Z<{Bs0|LS;uY$3!L%*lIc>)NylKf}ut{=nU#MH* zzsQktSw$71(PY)ME_`tU0F?ze^h6;m1dy6hH^-Rh?y>MB{67R$I?RE|>Skk7_YgeQ z0qUy(%Thu)2O9hij~s8nfRfD%oJ4!c)1UxJTGxKL7!CnL`c(v?yo5T&+y1fsziG8@ z9$KH`a8sX56K5uk86dso(v8IsHX(c+hzV(*4NV}n>aMzR7k(9O+UI8s zLN6u_$B_yQXOu)6+}f8GAcKn)5A-z*GPDTs^nzXrEfmEuX5C1Hzzqyn0@HYeWWrzk zo5G&Jl(=FKST8b+Pb5f|9?Fo9-M13i1or$G#`~#eA_t$_b|ar(@c5bG&m`@6CrBlz za%_JEu-E{oI;oPe{-QC$8Hq!{@%>k8zglxsF_koMxMCpI%(8Fe$P%UbZ?phkWjIv{ z!v@9Mt{T7unFxcTi#Sl zc^bR~;K6d6Op3D_;TC#}02ba^vaUqZbl^-hP}M_~5)-9lwcs6x3mmI@N7l(ip-6Z3 zMCGD1WQ3!TuaS>73l&Yc*zUR`@8(LvkNjc&g1E#zp4b2YjB;?x2nQQ7e{GO8MX=a% z)%TU^<6Jlq?I3qHyL}b#VEFuY$lsL?C1rI--oGZlg&IxokziUXt+qCO2se?|;+=x( zXU^wMP^aKUm!l$Dd~8+ni;lP8eV}<(w&dq(pwJUcY4XodtF!LbjUAu`92?oPHb0Q7 zw}Xokg3GJzvJLo$O4c{VtH!Nx>H!HzZud-S%hSvO-IG2!t~$}Ror8-@%(n|p*hkQx zR_4}#h7EY&0009302Q!*!cfrw00;X)o*=EnSNG(6%5wk!0{{SZ9Ua4Sy%xQC^Ka^q z^&P#1`8!0oCZu2AHmZvi=qY<%kU#(c0|2B-3Jd4iEcE02u{?bPa3;^!^%L8+ZQHhO z+qRR9oosAwY#STf#>Teu<@bN9zN)F3s#85R_jdR6Oy9ZpoO2wMyV~}3?l_m1XHR)_ zt|x&3A75t=vtX(|miAg3Jtq;O+$gQ)br!334E94B$m%l5uk&s%G}q+3T#he9P;Tv) z`PCKLq9%+QV*6vxA1i=TC(+QdJMOkmA@+uUv1m!OW+$TmWD& zqv8t-GN%dhV}Rn*uaP^fv|}C*!>5A0zAcC|q@SkG4<(EvDlyo;-!0&3ZqtOXYkU$C z>(Z52fuO^KpfGYZjK_c{N6{jx9sh3VuQU-CsCE3U;tr>bI7#cCkd7;huAnK@zj*4T zad^i{ngApKxuD5QEwSX?mAVr|XdTkznjA34l`0lToN|i|CHG2Lk+>@6i=qwi+-o}= z$LaXb(}CxUmI6=2k;Wx%*+@ zfPM9AOT`Uyxr7`uDN7-k0$q*<^{e$Om(@Z(1=tl1Ul4zfAC0_Sd7T>guSQ8+aD|Dv zL2Qrnsz{4kih+V#1^7wyw@|Dne6wKC`h_jrmyy(svZEX8vKhvpJo?k1-3%}P zjocdXBH+mRMxhh?Aa66cK+e}f=ZG5ChKH|y`U41YtVm~>MjQ>?J;uSEZN?SbLWO|Z z0H!ehmQ3e33ANP4BVd4li%kCRD{S|QN}vUzkw)mw&8t}PHa?|U|2ZwWx9=| zN6XrR?)k?GByF?@FP0xIU#!1wGqM&s$8O4qn*{oRa6w-?UlV2SGqSab532c+_?-HQ z6`W(=hQ;+(h#7ytFH=Hpw4qR>O>3kAtpf-+mo4a&#nJKfk@GxQnGv@CZVogbuZh9H zA+`>ss9LY{PsT*IAtn3(`$be3;=tzsJBc;l%TkQ(HV+;O#+FRx*tMm^#Uu|PD(G8n zYf02!<*VKOpI27G|MM!1w_$Nw=lVal(=7Ev)1sznAj93tGpN2`$4rWNm{zEZ8aHtN z>$gTByjvckod^MJ$4IB&$R$?ti#z_x-`&qOY?lArMj=WLyj24)32t)f=DzKMdG+cA z4_T$OWpV7fi{BK-ySC4<(uU1QX z5Zaj~n{sCx^|TfHuU7}}|9`KN$d$N9m1#Ae_hnc_QHtHqP`R$*UOy~lr^rUAGWU=C zmh)(?$azy=C4MMZF{0j)FDzln`k(co1jjt>f`Tx^_!l;DIWJLRY&WansXMgIENSmQ z_l+-CQ}C(k+n#W+P zK2y>?I-J~m8e=ysh~rY2nkrLp;fyz5073o5C_3i*JwnY^QS_$f(nqhxhz$n;Ri2^; zn}t=E~#pH#;m%^4zjqzP2(9g+S;_@(#>%M zw7mAF$qJ^d@AI%m$(;Rcvc+J+J6CNSbcl9WLEe#PT%NIM>o3&xz-`&OC1nyjjmWg8 z&RRZ!%QTDypW#u`+CEG?Us-1Cx4`fh)1)H$J6z!ct~rJR+Vc#DB%&@7>pM z19h{%+7SSz-asM-sB%}y@kf^l4U8ePm!O{=a%q4FK*p`lkZ)XxtA#!8f;~AhWwf?DP zj9}MhA8FH-v9nxH4s~^)tSNft2mTstS~4xwc(;0{}=M z)%g`sOpB*Lp7%Ljbrt|WH3vYsl(B_8-_Iz8L;zfhKmd>F4FFJ8G_3XW6QkHCoj2-h z?oG6Qr{K}(%};vVNu^vbD`zY2T^=4ES|yS7u-t0q9OrNhb!hyivzPKvKgUsX-wRFn zltXYX%9zxs6`XHOmBunL7PWj17~U4hf(e4Q5TwBsdizF?AB?TcGSqB_scNTXr5wE= zh^@bf7@-MqbXfq9lzic##yp=mO>=W>1AgI4{oAT_Nf?kM>>>t{;{GCmqbyLw4-Li= z;{=(ht1TRiM*L(4Il)bA`3K}VlxmERz6pg0Fu`WKNGbkaJs@aT<7a|=j$IzRDMY@ zl9?chPPZ$UVAn4fLDl2u+k^4L-+uSSsb|QU^i+D|I~(O zA!^jsl<_rJ<;~KX*~!~atG-gY?+|9qI|2cD%P)Cbyw=Oe4%C$qw-Gkt7^*B=9*TLt z)fK$GdNgR8Ba7PyCR{I{>vybFKgFEd>Mg6-^f!Bb&_uz$D4W9(j_FskW~Z_*J2@02 z#nK)z65s1I9bI#tBRMfr{DWgtdCY*xW>eW3GWy&BI#Bc~1M#ow=|8Nb_F;7O6na76o3T}eIU?(KMch@hi5;jd zLpg5sT(V_uY`^ohrFpn4r$3r!S}FsiT|7d}48i(v6>j7Nv&VZWFR7X~*I?TW+$fyk znJL3(Yr(C_P3b=2{H z!T&HH=R^I>cj)J@c>q9wC_G}CkVt7^&{$cQI2^*K=Nk22lardxuaT(&lyP4y^dmlO zin<#*$hr+SSMavfa4#yLF6?T&0ooKwgw;iq8^~0%v~RBB%SSjAAuj5Kc`;X`tuZmh zG=kjY57ipj9bI;=)A@^%;bUGDFJj4nyC`u)Zc2*Y=11$3ay7Y$awJxeC_9$a)@RKl z?`s|_@@UR2b3~-eS?I{FKG&vvgl{(OTjks5$mg)8+~8^gf3QtLh!(-iQM5h(4g8Rn zzmoWZ5uPOxhJ*V-8Z0v4Kg2C7PS8YVjat*cuEYVN-tmjpZ}bfM*0)QTXjXPxrgCAV z90IZ_WQ#kWE!^6lqZmPZeSM#Xz%VKw4Zz=Ce?LQDrnbwCvOkw@lU3;&e)55GB|czh z;V`-KsGk*v#~0Fq)yN3z@?P*`gn|zt0`TMBnF$B*nXv`eDzs54?;?HHeN0IIu0A@U zwXl6&COr0*I}QkkE#Odp%dZv{O@n5ebu%%Lh(pa;42`K@d}~`l)$cQwa)N{#~;L=*k-ju#^YRq zxyi3Dd;*vzW`U9A=?I*;<)lK3k%v;|D8I-Fiux+29~a#iW^*lDIh>&{ff%}AuCbL zuYms$SK(j(hiqgk7T=ZsAf769|A*|<{Ehq{;=Ahkf5<`KUwr5P+62TU{2%gfTtW8g zKP32eJihwA#cOIhAwy+L$q3H{Mq!xXhjQV8byu-b`7VZH8wHWx4lJ6?tj|{7yBto{ z>Bw0ShpJ@QHXne^1OO1!3T0AJH3I{$&oTc7;&^QL*OefR`oDc92mlP!Y&g#7ZJ8d- z$iF4*T4lCV;7ziwOLkqhIaG}`=mT(~5SyFH=>1C-BoYj_MP+*8qMLCE4jaTUH+UG6 zExt>AMrCQ+umF2ipW>*Q72+}yQ`esY2DsBn$wJ3Hmng0*^EV{QOx8B;&314c3I0Vm zqhrfSTsq$biZ!v^>d)R$Lc zcqZacU@CweeZI1+z<)FbJO z$V8*y%fh{p^rT3@uH!℞P~%?`6Iz%|S2|KZanFFBI{JuN!Wf zr|$kcDWTK*{=~OWDWqka*;&P-ro%*L9Bg0QkXis4GlT$m`?cVvb4t6G;TButEKk>4y^U5?_ zPW(5X0S$wV*-^!iHjm}rGC5;7j{E`2{BDYW;>|4#D{!dWoW6QxlzqlEmp8HIADUNP zU^ndgH^Ql@3pw4|!1VD7sdk?CDyD)Y8B`mzG~l3*Dnz6tZGO_JP%KuP+*pfN;^_JL zkvQoS$p}6Tt6Q)EN{J>Ooss&UyDG40kQMGoC=^BJy%EWWZ|1gjs11zj_R`2Lh$=Ee46CC9@M%h7_D z9Z#>L(X8}fw*h%h>=g!oqf`5IhK0U_oQU_0SA%MTG$v2dl_Fs)Tl?aSKvhTN9SG~z zt(T4^dBBzzJNbzyTA!;r*`I?=Yml?c9C zzr3;^-Y$|L2!t9IxhDj0VmS#k$76rF&;|OP7hfxq{EEIgPX7Hzr>F@14Zw`N*`Yb; zEv%khSy7C%d3c3IjoLApxi-la?YX(_*X_fIxkycLcodGftmM{~%X%i7t zzm)Jd7g;MLQCXh9>*B6I<4VrUq!bCSg;;z140;8nG3#btF1;kvnv{WwS^Ch8yb>~}zB zFcFR-E0xM9oJ`DwrV+~1X@(OQ6=$cU4!LJNTypSBuyJ2#0-fEf9xvYdpCkBXv=R*q zJDPd&p9S5FwBo#9_XHD66L6)l+Zw8gd4NOeAuNZiP@xue8b2anzDTTYmVIJPlNVWu zurAWMJ^+}RDt8dVaFbY-t?nbcQ8=@Khu{li)4$r(ov>qX0-hwSc>M=Fjv7KYKyhN- z3L!&-y~%swp@FgS)q+GV1~pvV3>{m15`R7*jNVM}+`8lJy>*_a1(B}ff{J`5zx@ON z$Qe4irA`zNbz)B9DrlF@Ir6?=hVLQv;~qcUPXNOOUg&$qr^RtXO{^?M5Ksy;jz!j= z@ub?+9Jc>{l%f=H?)P{S_))Ov6r?pedJVp#L_k0kuXUgn4s+To%Kj|1e$dsL@zxD< zhJ&P*Nyif~^eNGL6XW_k9$~UH*xUsx8KnXg`#*UgjXGG-hZaF&y3haNQFWV$jv<^& z78C~D_QwH`Dga;-bUZX>-92b|E8j9yM8^Q$`C<{TCeo?*6W*VUT^@rESQh3wWM&EN ztm9=_r49#-(7vb1SOM{dd0}^19RyOTY75aCZuI|N_dcvlr~vl9Nn^RI$;Aeo)=Kn0 zLT_GLfd}@7XZOuwz$8)}i%U8j-w8RTojmZFxDTsPoIDPhulYdwDDz{~Q6E?(Hfepn zz{c~p)%JHLpE5Ly12gPZtOnxiPP`c;V)0h@GG?(w4-Abf<|F$d8&~qAC zC}!wNb~#_uJT6bJXts{K`$iSG|s45e` zwVTXYX4m_vb4o1sbCKE)z|=qv`Cp=A$}XQrYz#1d z_OIkzUNkw`1!)kN3%N!!MT*qr*!+}aJ5hkx+FN7yDEg*CV)mf^ymJS zVPt)(#=7J~<7hO&e}@>o`ar^^wBuao!}0^0kPT-fN}#d4=r5;~W(Pj2>bR&b06?@5>IcLkkH=XV zJ@&p=rb!dmnDrK;9?@A*&o^~uwwi-gny7>9u6Nr31C-Ej6eq8`Y2Ox~)o|RC?BV5n zU2T|+S{y?9D1hXf*H7stS?nLx=N@A#Sw1-UQ*>iJw)JJG+~>vgfrOt=C}+Oca!V_@XnwkDQoGmkcOuJmeE?-6(e z1d92;coBfGL-l%??cSo5)x00&KoT@=E9wQ4&1RvJgHfkQS=>M;mQbeohlcY=>`UE3 z`9K+18}j^aj(^|S*0B2bGIKn3dQYr}qM@qiNr{I$TaCWz8`yfTG&aOmXwYH1+_aMs zWJQcpBNB=nPH7TP!``z{m;f~bIFQA{annYHzcM4=>(z}oO+BBFeO5UxSaetRTLBq! zvKhd(gXfTLNQxP4HPSbTlKG#ElmH;cL|==*&scdm==RZ;$ZLRIuTF~+7q%P=vvfT! zr^?5fyB+rod&|SVE7WVtG{q;-*fEDc$2;1t0X;N?c-gLLng5G2ZF#unT&*B^uSKQ@`Pu^j zp#s(o5_~(|*w(-5+|~DK>5HOx6&J|jm%Va3zIy>y4?ZRtVV>$Xd`2X|kg+ya_yab8 z-i0BjH1JlED&|)%bB*5P<{18mEV_4EjZSM902c^~09XftXF+a`8xMwQ85%=#=o8>k zlcb+y1QmESLPU*++e7TH3eA)Fg4;GxQQEFPssb!z$>EAR<8h5c0Fd*cR6!(Bw)3Ae zYO_yoX{Qk%{HL>lKeQxb+T!9O*Hq31f9TC=cxrdbYVb;$L$DYQ$<(%y${#1RUt#-x{>KFcQilKOlugm%4BhSZt&@}_^;b5A92{@Tg%H- z*Ly5On;TC6NTv{)AXWVYig9wttO&=weud^Bql9$FqM&UtLN(g46%PiP4v1aCutIz! zsis7iW3ly%JF)I_$%o}vDjs}%hGVdl0Q5=VgFrupd&WJ-_!S?}`}{XokhjW0q-Ap} zd0m^1QZ9p6Y9i70$7-v;jK>rkiI~)Q8r!$G2DwCbY++66ra~~bO5YRnb<1;oK*xax zfd-Q4DM@$6v@bRP))oNyJ}0soNo!l+6t`KaX5VCMn7xhjx6#d)+<4nZKwMS<`Z~;CTSU z3+M&82lo!2VEyknf6t5Wy&KW8=$33+ph_AvEIp52G^I(DPh=eV+Ee%@5R1bdel}V* zKXiTLGVl;yO$co4*^%IqtKS+gpcsH!0MTX=vn8_U=yz`!G9Su&?bO=I4H$l5)0{Ky zcC7odKjiA*`1Iamzo2REgH$i3e|mJlt1K7$0UQ|=Fk;y}Xs>m5WnnHKO{F7b!Zy?>wHGET5o-GCmi9m}5}0{5wK}Q{fsp%3 z4CT4mYlW@TOgE3;|8&|;(}l-Y&O@L+xNU?`3I{mtk?4u{BLIbACp9U2eC&tMO4qY0CR+`a;leKZG}&9f6F1J%J99M^o>GZ#e>g zZKvyg`E=b{jHD*v3*EWmx{OGQ;7^U*dTPXl4pO ztYg@S6x6SskN3UaZ27#ASRNdm--Rj;Ch`l{o9HV6TF7O1L9^i?;o0 z?6OYQK8T$iRGDBZISSUTYJcLM>4b}E3hR5SU$?s5z_BsQ9)zBIm%mia+I5_9?h_c9 zs)HWP@+EPC^ww5=wggQlf?-}#Z<0_!EJ98de(cEKppTt|vwj$uf1cFOhHJ(a(AVS; z!NY`SuYOP!6;e0gW!+L4h1|917|bKT%*)}3E!dA6KpM5$wB9p8M@=?~Be%mU7+;I% z6FlyH9Eb*Is(5q~yV;`)2UmEnS^x`D{4?+hUjg*1hDfFV%Wxn8o{viT)iDIblj^O8 zz;85^8w*1wdl-**;f}4A$N@S8iI^hlnYHB~NJl+2ojL6B89Gl$BY_8tka}Q+0M$Rm z5F!XW32}g_DF#+h z-$xg6sK1+%qSc}Y9;x&ibf^M>D=YCq5_P&P?PP(W1UJVyr*g`i&uNX`{Eeo3FPeXX z3h?Ap+EU<~Bsvv-9r?Sx9;!hrAPy6U6@4d7*c zXtFNhc$A*Dxds9100{$mo1!7yU^;yqnk=#g%q|ZVNfh+seU@>lu-6j+ds328fGSk9 z1{~n+=Jv02*VL&EDdW1wIVzAs1&Ei-SH0mVH=8Xby@flZE4t7ToB8M7vNY0==OJrQ z*Npb&Yj#K-t#4JcUuX3RlzV$ibx$+g?*y-J4k^TZ=n#Vbs`k?rAwAhMT3#iHku@YT zqaj2DQzKNZc!nXrqLaO?{XTO29{(oaCH6~#Zs%!l2O-vm3DmRb^6+McAwk%5_OTvA zNFZjv5^?idix2BG_hr;FC8jN!=___wn!fB_a>y7ufCXikg^?f@f9lMKLO!#>9mnTe zuL|*_$_Wk-Sd(rbs&V`V>PfpG5)QOTJ<|DC-b=1(?A}|2SEM0dipeHME`gT^BLK(% z_$~IaxFF+Q#HasHC*!ZC7*e=FJ(+n})-_QS&1H<4y?G$reBn(WK?5Y57pBn3E%9aQ zkegPG>{BDLZb1O{hhDocWJ9o~-&TZFrk__YJ7a%^Z)-;EU1v6#S_s?9hiugliD@$P7*0KZ z{LUmvmt>e>G>qF2j+u5KO-fayjN#-FZbOkpIiew_OSm0V-mlwz9N8**h}fB z;t+@w1#asqRC$>M9^WjFk+BK%PpbXo>sxc&4%hF|{Y#EH9Bdj7NQYk_{snmYZM9qS ztp53^3?e#1rpbgiL{f!jsB-A|QaNgGkDOLrl0i9^{U~($|5ThtmeUis)}mBR12i8H zln)Hx6)`u(kWTNIa{N6`2_}Q8r*|SE)G86N3!sr7D=0(B(H3rZM8(9KtW*yw2*Cqx z%aAm@mWH1A)6D(*_@~Yz40Xn`irBs%N}YhLJ*Ef|NT1(E2uE<@pT2HS+ZS!6F(k62 z9gDE)Xl5>GPXH7t7Q3@S$}rsYTJIH5Y--=7r7{(NFFz{3F@5SyceLEd{l`}VGog8^ zEF4@3PY_Fcj9<~+*avQw_7xh8=ozf??bD2|3IE&EI>r!yt2b;1a7qNn=bU4lV-kXc z^WxBXFYl!S`DF-nc=-|F8tciUBTD1Wh?foA%DYsKXlmA+@xvpl)2yg1x2{iRa2dqo z*E6dD5G=wlsl2$OTgw4nTEU}sdrbR>O3VNxz~;814b}4*7UPRqDW}n;rpImM!pMY# zEc7^e_;?%o&5yPOU}OqnxkxHMXFa)mH{jLxHkzF$LmAA)*vHTW#{5Lwm?OprWoEtg zeC+;$@*4SWJW`R1+F>(^rs&DnQXSMeMG&A)S-+G~oBW7$%ent>=O8H)w*_9kSc*!z zNWjpyE`0Wm_^YS@WyESr$fiR_y`cp$`x|S2A~5x3iK&`Ci{9hx+Y~gJdccmFguXJq zTtv0d`Q~-i0HbEn$oj(wv&y#>r`YET;1(I8QhK`1-t~eaH{F|)^arodCgpS7<~ONJ z^~ut1@xoGn!l#^t*DMB9r*+rO;A|Ce8vxLV<`?MjN@VdHuYs(;kh-#G(qY?{ua2T) zipRyEWy<>`gcCo?Zf~n8Y0b*2L0%xekAV?@^`)oJNXRyF%zfqbLE5gmC7yWTh%*kz zjg?otPt{73J{LK2S1mT^bk-i~is`#^$-` z?29q8Qh#^Qae0{r06KV7ZTjdnz(rK@|4JYkAPK~XuMSq}l9cP?VY(FOo?GDz?@$65 z1p!nM1FhNCPk-XuU=7@Dj~q6m?tT&cX>BCw-{$jC&cdnW4ys;g!+)4}~kJ5LGJ^g*IN0SN>k zC-}1B%nUuRN>@fU5Lz;;MDWaZ_t2;f6G^BP)MB4s3SFsM;tB$d?GVTQ30?F!!Sr%;*15Y=}i(s#)|r}QP~o61*Y1z%a;P3#iW(W9zMUP zR1L&X1M7a47$DUF^aI!qhg{rCghuu(NWqz2o>5ICGbc+;jjZ6rLn9c&*O@YAThATk;{G4`Y7aq(WBjmj4*Or!$qG-J z=o9D=t7eVZZ!+&-E9rAb&1LUd$@VD!x-YT(B7KAuJh06*IkCqgbUUipsHX+_7@}xQ z^$-@cv4(rCQ`CeA1bHuw=4-z_;I)Z}Aej_7uZJo)E!*fL+hNK0h^62x);aTf=L1Yj z+DN7VOJav&j+l6Nq;xpEpdobtYP&Yh5`6dP<5LZaI7jlN@Qsbstwl+Y^v}qMhvGFB z#;y!SswUP&`+r&-rKA3QV;|XBDxesb>q}svIHof26EWNn@Jm$KM1{`9eXqBXO!2@= zNW&Q9gls=k0tYCU3ATae`}3MV{cSKP?YpcRWVF)Gc*m)vzLAm((LD16FWBy~oN7nC zLihf%?_>}09Yyit8^*KH1Zt9hMFTxst6a@lp<)u+qjfJnUB5_3cX_8S>Q5QWt%oqw z?sZn28Vs!PWG#No+zd(kaVLJ0eF4LB{&?-m_Xa_&q{-weMQ5yy!;N0aAlAcg#m}1MoSK-&v9`xoJFbs$1j^^-=PkdpbvzCmXU?lyf*RqFnhHO}v@%fG)p0g{#~K#Sd>rGqKV=mf zL5a;ZbThz93QHUO9&LB^5~@(QIW&G~x-fz#K)?_5?Hx{AVf?s0*up8avr!T{nsV~8uz(J*`kOZqtPrPO zPoFg!V)fm9vZY2_gm0kwjI@@3bk>I8q;z<5<3gHjTDyi+qnaUsuXBLfXYPpg?iwGv zhV=J^)8R7l@-5iTT|6MENi^jA*dIk+N+Ja8c6NZ_I|_T4&fkg!cD`n;wPVj&5+@}w zOdodBa?Z~@xz)RsKE&P2K%>FXRms-IOS0Y5Dx!Iu} zGCns{QKYqwG7B6lj#hlTwr;dx^0dvJ0Fc%_+3l~NA5~3JcayJRO6+B|VGyLI=tH)z8c_+0pJ>V1HWAmTNEp2gPjJGlfCM7k%yR{Snf(oZ?A{7eh=N~Fc(^U}P&o)kLNDj$pg^P-b5Y~gY`JK3 z^t7%Onsk#c7(^r1FQC>Soe$+7@g;2LjdTGUpnE`0sbGSgPZL0WQz~URc-d|z+c+c> zS}@WP4xEe!f<#x!iePxbp#)k4pbqrJGI=d|c&%2bZ)$Xw^Q%vU765)}o@bP8r9Z#J z#nhpt_PSY*OA3_FEKhI5(WqDZpco}ov|gjJwLKAUgFNE4Pz{CS?hwIIKP@JsRNFo) zfrSG9cM5yH3L zpU4GRrL7feD$fJXOn2;Fn4Y(YiNlAx?fG38uJ(zU;1{UG-Qel&sH0 z_wVBterJ(oQ#vFLt|gRPjGC-y|9p(yF)l06AU5t8v7wn5gFgDI@;QsI>VkQ+tz z?J7Qut()^WDaZIb^08melh*WKQ1xrkw$g5- zyR5}qxSBR$tTxbz3!NVGqUp&(8>_hzDJi+mmLU^BOdXNQ9)rkMs8Fb?29A z!zwMI|L*+$EAI_8W@J{}&6Zl#zge5py})i071`}qptfhD@cGO;rxPpG2+i1FVMPr~ z;-Mr}9Us~8>jiQ0ny?s7=$*h#04U&Tf-kIDy5J|r^}#_ioS$hrq*(ghwN{gwm#np{uY-unC=7KtPUWlgOj5?K}g? zZR;}%j_QaXjI)?Rap)@AiUu8*y?=+7*oVQ2Y#`hDXL!F30Hpw_m{JP;s_v`EUeeA~ z{CfflA_-Id)$ouwG#%@?Rg^cEQ=4RS7u0@}N=$e68PbacR}U(G{cbR#sew zmj>8jFR!GofKF`N^IQIPu~iU z%T2nwmo%>l?{vDr0f{O?Ld?$EP35GVUcC0Q&hS3EyGif$cH|<4yIqPi_of4>MGtno%h_#L3}qy!-NCw53Arn&;#h^R(5LsH;LYVPYyTlT2v6r zBG}L9-I^ld6N&Qna}jXFgTKK<4BRDB(n~|YQGw*1kU$N{9N2VoY~!YCf>r77Meaco z&3_esnB_O^;&Ee1j)LThL0{ku9QucNGHDtBY1=4caV*K_SDXI%e%gZaR;B%_eu4Bl zURt@?B=qL6X!;STuoD;Gz#^Kp80kZgpsYu_qiI%z6NAw3shtFzuf`8v0l<^{O~Prd ztjAxYk@sC}V7nZ{sSx_a)Zy1nIlTc1{%7auoyYM=0+{q8O^DshM~dJc?P%ShjvaYaM=g_qGuA%BH_Vx$Ns)G zq1$FgCVK~Bn0P)Awb+2>7j?7aKP)!y5zELqp4p*QS+6s%pCStY(4J84Pue`vH|MSg z?msFsT0sCfV#6bl{_8=x^KB6M$$^H{7p6B#h+ZB(uS0-f$9>V))Iab z;i=;7)&XZ>rNOQ#BFJ3hG|M+Mz~PNww#el9$T^W>B@4VOp+Bp(nRXw1WlOa`w)6i; zlRY6j@*c{vwF(B#=b>NAFaI;VUVeI0f3u;-US<-%@2@Z6TjsbmFyc2N*XxUmWr^H= za$2P9()c5-c*U@F+XJQA!Z18Ec+d%4Ca<7v*WKg@^MNMQwz`$^O8s0_*vQVy*rVHs z*kPDKb1+xtX#*8-PlL#E?H&>fsED;uJ4G>~L^8mH7Rxz5W4hi;CUQ99PsADYX9b_7 zBl^)-1yTdb6_WiM_027SEC898xC&s63I-WyX)g*prPb|<$lI`qIt9WT3w#UTXK^xo zP(?XB)YNO=r*zUym5SiQbriHdcuJP=nLhoCg8--_2Y?R`*G-hG9JEnrsI{RZ_v_rK zN4&jnPp$-~%YH4743ux00dD_XC4hM@WhnyT_Je^hq{`mrYoOcDxty2Snme=FACTG8 zu&On-S9A~p000d?9UF5;^Zj3(_2)pn z0m=zwj6sJ!mw;0)=+GuCyLCySW2y=GdD5`A?^pgt2)41xkpFzw|2V1G*Zj}8mKm(X32Lk%<3@HAw z1jJn^Q}}O=U|_S1jp(=`fB@8)4kVYiCQaL7uzDac7+@v@Vsyy?w6OQkr>nf83Q|60 zTduFvz+i(FU#ffa?gn&|?jY81Fd>ik5ZxAq{dexrhKD{1SUo-_0hDUDipt^%sc~DM zJxL&6{(g;mQONITNt8eU5!He@t!1q8=TUzkXu}l4Z-6H(i=+)B z;4?Mhi8}G6;dV zuR`b$5Q}UHwWur0Jo8avYBvT9*y{u`aztE#Ps7NFEK3NSBgE;fxULUhew0Jk1()-d z?g}^x`4l>3p~03^BC3PRy1XC4Oy8j-=LzdUUB2%TFqGfys1BbV&FHr z85wA#dkWm*Z%%;%Zx!<~@a!@evWE;(v8 z$yGD#kRTA;ClUVnNIjz{SA)DB8VabliyASSCn={@0lk%+KY)qC){$J=R?+B;OIA`D z>$ihsgXCIlo1W!4mIV@z;m{SoX+i~fFX_H6g>~q(l`rIwTp4(E+Uiq)EWt}h82!sW zD#&6+wJim28K)07w08M5m#q0@8H7i@-!Ha{U`@`YuOf8 zwCz!l3bAq$K4!Ih%9C_{Q^+j_Nx8z%w$1`95&n_FMsb{v-g5U?V0>zF&+QFwBvDl? zGi`uz6}#*%dGRuozi(PjR7sdC&nrRn*?Z!?SbwX!9IbIB_+{%tUF%ooKQ7_9G$dc< zfMdoOwG2Ydlz~q}Ov&ajzD~qau|9$^xe~aE$`}DfM&am%5ou##?o*s$Mj$0mMZu6a zM@eDXV#J??_>WMoG_9!AHxlC8kl}Tmd;c{#LJaI0QXpwM;8;%o8qE3<74?a$7^n)w zd`-DiLeCKZ9D$Xd2D7>)+98E615DirE=?E^W`8Ex2vDKSi7PefZ1HQLsUWP~FZBimN-QC@t03i@GxJz)iMiL~rd$0s|2^J)HfZ*;H zoZuE@I{DuB{`bz@S+i!XUfo@Fc0K#4s#CT1k=oUK|B{h_*9_%YtN`7;Y^=KFemOn; z^A}iI`1~lK=lQd2-jUQ7TN00Xz&GsLOlvzlZb?t7d)h@X9k+Xw z%D#)7+zG)*86N`fx7*>GmjKh6T{z?Br|^*`9qjdF*`_Hyiu+f|)=2S8)1))47OQLO zD(9u-s7dtfdYD^;4!^Y{G5jKU-xJB9dM`9^mA?wOy0J7+qT0aZd!+r8ds#j)*w6kf zX7ZageIdfq8}UW^4-U`?`m)kko)I=ee>1ju1L7#99s!Oz#hHEpqbf!3ud97>)$}t> z;l}h4bmTHledKDNM$oz4ES>3LBON*^MZ>1m6+v9nFLT0!uSn3TkcIH`H9+(>p8AaM z7Ql%w!+&yiSiX>!ScpCol;>a%)evudA&tC0R?u!b#7bpNV$qK5jCu#{E(B2S%Moen zP8jog9gIa2fbYj%9`kt@9HnehpZ|0KyWtkZXaZu1#IQ1|NFGDEVhn)&_+afrz%iFMaym z=XCKrH(cR7BaO#20MP(cWc`}=agf~YM-{pXY<6o8<;?2WBKR2aXNuPv7gJUUOZ{a#i3N-gTkd2eSYG&etU;hRmQmI=yL_@g_xIA=0KSOn++@U=b&7 z-vx;6Fo}M)&p)N_PX=`WWFBnR(Ap!J(Dwrr8sJrra<<41e_G?EuH5Q6SQfQz(H-ec zj;T*fPi-3}h3N9YKHZj6QVkDr4+N)$Itt8f*k#TF0m;gXtYeh0QNs2DjfDj_>i__s za*CakjwcDqfSNn5d|-f@@;dE24+4OoW*UeEJZ4(k5}VvLa_Nyy}EIr53#XP#36ti zKz0h`LnXnjf5iWqW$3R}hY0{934o9Q$23rLFxD6*fCF8$27H7vQdN!m*M~qjHrxc* zpl@GO9*fB90`PiVRyYvqkIY9?<#u^cJeY&rJwIrywiyr+0NqdNKUDD~gD`B?|E7=z zjld-Djf{ypIhwEmOFG}iefYQ4S&rWNf^;l(_+RuJOVY28U^*(_5}6P{(mXOjbO0c%wz5mL=Dw=pT_l+VOg_k}x`?HAi2WVOIw_=5=m^yC zPmyi_t_vFE=5JkLvf<@k_yeF|D6e=ZuV^SQkfG?Gqs$tS5HuG6Ws{s~6P;{aSrYgK z)lVNX+6%zz0tQ`wWd6_)S%=+*`d|mG0HL5HJSP&r8I419@et={rl~fM2?QQqJ^X~` z5f3p0y`@Ct=0Ko5IvrXz8Hxo1&`_5k4uV$!0P;5p?GG)a1~yh$Ee!w&hh_muP)-$p zId$X#LJe>s#R+u)Tsi=MkC>U>{gqI|9JU4&4YJ$S05EKgd;ypaXw-~9$kUQ(co%sEB=mYckp#5vjzLNCXNMF;@ne+mPV z^4sfG5Gc|gm~3eCJHhc9!ot3;0e~QAQ-PMGGGFa|m4r0?-ze!3b>CIo#j2o)A&?jk{= z1*Rm2$U(-L$$GP{Iu%}ojYR$Ab|5I0?tM}n!8j~V5e{HgaAe~S9J>F(po8vbo(AJ@ z$MH=t)X_w_TZwQa%mwWo*t91i74{Oo14}+f|3E!Y&4`|nH&|zMHvrWRG2z2wx#BfS zYi?DvUmE^J&wNIj;zCUMaW%Ru`emYj)kCQIn%>nb^AQaks?W5Tr@WY5_vto@-@_>Q z<%C{+&h%`kB<+Fc)&8W$Ud&E$E!9M8IV~5oPsLY9V`)A5U_A%XniKlkXD$TOU(cXC zt+t1-cSSmWI_U=cx4ZOsh@vyjMj?MEb516qJ=LIbpsM3Uhk3zQ@D}7;k0R$aGd7C9S#|(1+g6 z{Um&u5YItl^3xwe!(c9q$HZQ6Q^pFuem@aRLt_T;C7Hlu7 zY-j)l=9_k~f(wPuy*&g%IZYO+C|jOYJJwEN@pNiNZ0Mu~!X=SQBvk2E&_Gs{#Ei+0 zWxHBoU_B)92G$yx~zwGiV zY9mnAl~qS6Wfy7mLz?BC3HnqHNo6t&cI7<#W#ZR~C_=?cJn$qtni&B&H&S7Sx~7qi zwNTX(&1v|c;r-8(lJE~>F8wBSlc8+PQyD2;tc2r0QgLxgRu;h zYj&hb-3iitz>9^(ouG_|uSY{9u6eC=_paTw*c+Fh~2k4xO-I zHQ@ft+F)-0I3O|+=->J~#9)971(#dY8s?M5K%v(eBgB+REM~XHt%#Giptu_i7JNf> zS1i_4SrX@$!OP%P4uA#%hxT`9gYB3hi4YDJN?2N!JOIS>2OAOLh+&q?8KdQdeb|;kg9`HgxPfU5|`2i;sS*vzE8wcB)XI%#KE##k?{FySKAA>IV zzd5Aw|K_K?(16_rjhyjn05H1%0Qf>Vu|hfhd;CA;{@=a{CnWz7B%qK4K<9AgZ_LL+ zcOd|%D7RQfXNVHSzDn}1$UhwZ?^rN3CVwy}IHB6Tq1qh`|6?1$xBr8~J>;JxE#?2n z{|_p@2~a{Ui5Bf!g=C5>1p(kWHS#GV{};jkCkamIk|k59ZXc-b=znzo4=LFHGP_VS zhxV`b>CAu7!KVPBi)8$VjD60}q5#xV;QTJV;ibi<-1wLA|3Le1)u%3nfW81A3aIiZ zsPYP^a*$E7&tF{5`9=tKmn3eZ|EoSkrLOgG!@t=PA0jXT!Yj1V(lQDSF7nG-$z2Pxp%yeDrz|7xr&2#fGe|@&Hze#1;Fw|2RX)OR){|`x6 z3$z;uXbk|6mHuHf@?UH)MnOeX_nZIre93eexS0;$0MR{b+<5bgi~6eyKxiMRqaW&heT04E6ZMO%KXGgRQcvh+M! z)$RDW1l>mOgKHN9o_!nyH-ye+mCI;lBy+UcDR;xVWon-iKsQB>c^w&=saakzHJMQK z{cRi1Yrn|2<+pptY<%s@E+P9WB#1lI{P;nG^^r<0gf+`MAyfIuA|m=d_1-0?sBugKD5i(^eBepY1fphhNg z(@H~E5wAaG8i5Irba%bUPTLv0S2U<}w|gY}Buq57YtUluHA1HwGEf9*CLvRG$hvd9 zfUsC|v8a~jxe7pJYE{8jm~7VpR-ow^Zf8;khgo7fu5T1JJVWqwsV)l2mD^gpN)c4Q zrp694Oli0a7YQinrNCTs<_fb-1<#6N5h_e1Z@ku@t7kPMt^FQ_C9hDha`?u4$4pm- z1UyO*diVyJ#o)Jg;OKEncAztiUz3Y7A`861RkI8`d3!MQd^ncMb#SowV{I~de*z%; zd1Tby3U*`9_lM^I>h>wjh{p~erhX?9CD3@euMr4%s^a9(GA9FcEJ*k~*d`U-T?Ua= z%R(__dD#$71?WJBf%=}n173aaFPbPYm}Z*N)gqn%GO`{!Aad!5ecVlzqPj2F^I*rl zK;i@&_p2phWV1u;R$AK38iFtj>vvk{huGA!ZN%A0$Y;$AGJ;f6gEMd`Fl3LRPjV3f=!ijVECdg|8o^~(E~<%P zLGVnQ4iA^30zsn_{c(WZQO*9?5gJJVwg?ypCCE3`<~W170ob30+njQY&RwLOh>U+~ za$uzm0gV6*l+1k4?k67y5HvnPaBBd7QyL6BIsvYMh_Q(77c>TG&XTHnORhAO}T_2^1(tq`m(k#kT%GlK+LQC<)+l zLN)tAHCO!q(G0r(*K`#Jvoy92=t6gku`Tc*{-Xxt6~S}JK9t0NwF({Oe@pz63(EYP zi3vT6{&)%QBT)4qL#@9E@G`JAtC7%)8bJQ#1{Mx*2ch~a3?nII-Bm;hGsgAe0*VO3 z+Xw-`(f|N;ZS)`jU>Tx`c>1at&MUEF<12u7E3kk9#|rWWz@3khr16To&VRcdl>LZZPvprf(k z=tAlGQxx=uf}90bb@xc63#B0E;$6WlEy?_A;z+t6Q{!x_u0{JhgG5yDh;uU?=d|E$Jlt{h)`5cql|C5w&LkSU2 z#C5&=E#`xw{6be;y|S9gjU-|&s_^Ha*WJ(Eq3N7q@EyZDSjp$P@?ndX8u1Yrqu%`FM0>#O(T)u z86y&=oePi>cZA=T-QW|9-om0k~_)1+Umku|KsdNKa`Km;|EiM@;Ix-RB^uOBfL z7uvM@F_t36M~NkRt3ivi7q||U2q5&pQ?gTxJmNa?qOSBhmiy%Z@SA5FJ{~zgU#Yw9 zSk7MUh(zq_8;4(khlzJ??pMpd+rD|d)^JA2$wgP}_#s$#S30qeCHV?AKO#2CnCN#J z66Z=jgG8{Vh&<7we`%bh-SL3g)oY(=4ix`%me$L|^0ZFF+C^sJ!3=-H8o!<=^!d~; zn^teew1z569eqVl$Hf9F-iyZbgclVtQZNOr%MZuP$bGiaN_Jys};?^Cr%*pib*JiOmt7NIogK7xtZ|t?mVupa_j& z@>-*9>sH;>K_%^t+7DgqZ+F8eKd-m~Ju2Hx^|7TmH9kq|xRn@GDBu3VblO1=5F@dO zzk~#|cMJf93w%xR>cm0RNti@BJg4tujM_E%$Sl$v-5c7UckXu=6OP_RRkhCTer`Z5 zhy4^~n^<}AHAuUXVXNAR)C#8QV$25JGZW7_#f6@J5xOn|yo4|IwmvPnT}h-pr0cdL z!9>B0C?deb6|qoc+J{gw$+2uQH<&1AwMWYASqWFV*vb}G8ew*RyC-T&-cr_6NIkgL zXho~SbIMpWpAT`UX>La3YM3D?_F0DJ2Bd7vo8R))HsF)YHGarX-iGPk2}yu1#< zO*vADFy$oHyO<`Q1c+AAd|x`_Z&D);2ikYLza%futq*FaUv~H7)m!KVbe)yrE{7%e z)6}I~Oq_lY?+&=|_b5;*1*}LO_6y6ORoK+NJrIJG!7x!X{;niv zR5`W&btIaJ*wT`n6s6za$Jf2iozUpC5%^}uSow6qBY{YKiSXiZjkaLlAm7nQI?0H` z*U%^EJ=k5xSg0PRBZX$>6ibl9QNWU|Ng}iTusOaq$ z9l_^_VdKN0D7a$$zEQ7h&FapRG5y{kg%{P~u@=WHNVVCm zFw!;|LY)sVIVks?s(aKkjOF0SmZQB&SN#X=QRqzKKP(NJ`9k-@+Zvr6%Y|C4kQq)m zgk&vz*d2#;P+a3@*{caOJRu|;L%36t!5LVu7XfSu%$MfrFk!C;R}v^zgq$>7yk9SR zA)I_?E5NX|eZ!xB+!~f+@L6v4ESxG}04XH^MQA6-(vn(}IY;C-_QYazT9x-3?{0Ll zGdQ9Uzo?AN=ES;t;Fd%V^R51ZSfbsk=Bp{M^0?TYR8C!|VAt_vJvcwvj}}|IMMBCe z4WT#`5K{;htyx~Dm&?5{k^6t>g?l|$`@tp)e zqd~6!tfPjnSHy~g0V4|fCj6@U*{hAjy!|H4KQ<3MgRJYRsg8(jV*%uAc7DD=ALa#k zJTs6(*s1F(`FdkY2Ef0@>(FVDBEgC8t2$ezQ0StKWysoX75yhAML)jLn(;=wJ*p~; ztrh$+?X?2?_|;kFVk?R2W0XC!^OFoS*x|67S%t1Jtml_=nAnm`%^0I4|F7^sO{sx%a0P58;#Q( z4CMu?Z`0Iqu|b4C*U?ZU_5ARh`y$+v`nJ!zX_YJjbdz8SgFpzIuV;x*^Ca$%(<&=O zZGpZkdl*>A=t zrWo2GRM0TF`Dl;BSL$#*e7G^kN5X*juuY2~g?p>^QVe4iPoU!wHBSd3`wktw8&fbR z-q9siYZ^^yx|=W+8|@=JpS9)zZ^E$8$k|KFBiiJl#+-r=B9=Tbbv0wyA3V>01tyLe zTE}=4PvZzJ&C5jNu7+Vgri32fM8A~Q7O3T{gWzIgoHa;oq=|Bk(QOMkA2ZD z{7)<7%_q}C?eEAc<_0|%@vp2~>pf8$L7{whmWDyYGY6;!JC#9vq>jxbGCy6uBp1If z)mLw@|5$~nWY;w2X~^;BvF_p{SLFNsoE?6J>w^Bz7_P+CnY+?ofh7wZ!pesj!fCM;=&gm2o1Dp zMZTMwriIIme?z3$@(JVT^c>UpqN7l8TfoBfo`4+BLX8VY#>Co?ENPCUlEqWhc$bWJ z$T0j5ek96u+hsGQ$tL*xasjaAR@^HAQY0Fb0>7T*7;&;$^3wM72~Mx3#SxSwH-Q41 zj^w=uDKH{!Bi?!HNn~7wZe{`YyA8BbX(8eeiXXaP^7iV+cetD{)5CAm`T9=n+7DaX zKQ30Qn6Mv#$OnLdHDegV4Lfud`8KCkJI`o3F$^OgDX`RMQQB1y8;!gBkJew=6;0}G zFob2jn9{-9*4*8ujj|(offZxFUnrA)lfJ3NR|r@;eZ126fw0c5K)=+ajXl#NooHe! zm$z(+=Dt(1)-7IJiY*E2T6baa#UC2iEIZP7tC#LM5QSE0!YxgR-2`{+d_cJpeP?rT`@C`Roy^7ytNZ6>v*F0u z7B--s^9lJGV<~TYQbLRzugl^4`lssH4h@ajh2I{0z<2gStkNL3-aCDPw{- zXf8_o;$tK4((5>0Yt~dZ?v}B2gQl7gmj|3O{3%?LoPM~sI1r;8MZ>2O!X z(}S)g|D-^^7dUdc7nr33v5$~bW_WtcAI7zwh(T0|`|T8T9w!cm$q{AYw5i{)p$pO` z^HJOJx+dz_hQnSUvPT$-)NpdXw0uzfL65fe#{z#swwrL{Jg*Evb`(inh&axxu)}vQ zP8d7xj#y#yOK1A&)~p=%248FFLRnC7Jf{UfRIc$+!Pe_5Tg2!Zg9o>T$pxRxuFVX+ zr;=enW98=|iMcNV6ZN^qn5>4HuG&_@D}?Ixs7bz+fq3!+EFCtIAmBOd5kkYrAhBOLnkvO2nCAWQNDv1hqGCAa`kThsh&Fs8mk?PZ!Byz2c1AoEelZQ zGrc~+VE6#%LcH}@rQoc5sOK^MA(jyWr}eNJq>>=WKgOZNR3pzV1q!HYQ^lnIy2iI6 zv%F@p%R}ftn^_-Gmd;ICH>GHWjNY7bb9ny%r7tXdv!UbYjtI`# z=I3L@{kNVr&)*MvJlD1xX~P>c1Sq`)FU$s$nb|j1;b;}kOk6I_;%lT@ zm8)&-jGy5POS8BQ2$n51^ zOYOYmDtL4B1&z;NBEXTcWTWJmFFTcR|Cm*7@o86wb-!}h9*>`{w5`lbg~LaTniKXp z&+V>*wA7=;r_E9k!>4xti)osK^#SZ?s2YXo~;8`?|dwG8$F9!G9eteKBD@G z7%-?H#&7(H9z55-@$eGfD~h+Qh@cR?wNJkt?XvRmhN^n-bAlB1uxF}WZvzIfhounQxi=Gu@*J<`bd#{GFnW7m4ixA zZ?u}DL68-HW_IK|2CE$FM|hVFBlN(SeC;Vg=isz87)cYpsMGJ2E~Zo|hJMY_pC;d9 znPuK|*UFG9#kt^$HqV~nRbqbRlF;E+Bv7+Met35;J~mL(*~KhJA$r~Sm~IzCS!&;{*+-w z7#I|`)afL~1Iw(UcNQfu4B@NL;-bSckitKT2a*y;XmcdlgX}t@A zU?DE5D*x+ceZq8Q!$&O?mYCL}-;G=IuMKoGj(D7TMAQ*{k9m0i5E&KqyNf^ys zu;&4LiBUu7l9KQ50b&06pb+naSEPQMwT{MH{yDrx{Na?!rVHfB<0<%Ht+k$Dd*56< zKryxAAe#6X7D>#6dGrnb4K=&K**J`Y+o}$p^!@mc6*SKd9Gqsg&LXCPWZ$U`xeVDt zwg*OHD`oZx?M@k2f9KabO1LV$Bjmira+fxT0r)zT>Tqz7R7X6V)kVmH)7SL4=3;G| z;ytAAzJ^KPFE)LhO<$J4V3AR~2dhV+&k)aK#-pFjT8O&J!FubzyM+XR$Eipw8Q#o? z=A3`{^?Gys#J*uG1nZZ?VHplj=o8~bLaIlv_&XI=7-+zQI@9n=w-b+|!A@C@TTkJ8 zN-D4ABWC3$omz4>{FrM2`qp=7XhgE0(SSjFAI@Mi+3UVUS3r(f@=*)#`$yHc={v>E z9SXgm3M{%i{jm@JJW+2p_9!soi($Lmmeyg$%^m6c&QpDQmPF!D-7E1;a5?dj4Pop8J|1TW94L`h-`g_N`oCbt~G%CPgSng#Zhl zfi)U1AJKNWQ#5~Br9RY^jA+c5J2tc&TfvC3~jnmFHz@A>a#6`t5EKp1=0*CRXbOOa?qSrQ@H} z!(VpAb{V;z45Li#aQ8&^80YcdQ-g*m^y?hM?CMa zeHNNPE$}HV4#kXCi8Z#{n>tCbmCwuU?6032c^jg^Ay450ja#hll!hP_V)=+5A$6}q z2;Fl!g*KVYel^Tv{`a-5Y$wcn>u2~5*$@og=#)f<26eANO-^`owN5^q8L%TZ$~J1O zWqlDoLj=me`cQy*MUyL|ZKQOIOODGaFpFS)~*v391N2<9da?@sc=OFIR20p z`!)-Vm5yL8+!Y=?5=cp7P{lnJrNVojz*-J=#2r}um%>{MQDD(fyQHUIav`@(!AhEN zld>w{G4#)@eg;J$+MDYe`xfpa!NdBM>cG(B{2Q0_iRn0Brb0{<<7w#?7#lxbsR($1 zDEh~zvJ+CvSRw-S^-4?3Vn+?tskP@FS#;efcHR4TWpj|NlEN={cXQPD8!)DXODx|s zaoc~AH+>%0clw|WM?maG(4D10;rmusg5ek50j!$Mql9j|l+4@F-mFM(jnJhXK6y2@ zs4gp>FgZJSuwedSBROW*px)@qO+-JVDa39%zQi(Yu~#}PI<^{b;fp~lB9J7`Kz!4R zA|dDUkLe#d@Uy8WA7TqK+lJ&v(3P9&IToECIo#;rAhT|@0<|}<>j(ZySjCGwp9inbYSEx36u0x{qSMKo&d9L6 zA5q=AX>BXhz1*;trsUtV)-vOxOKM}DNh9h@Ery~ez3(`~Eat*+G-h;Fu8Jllj`bb^FY2CjU9#AjXiBGqZ{pdJJ>OLKU#iMx`?7Te#7O}av>zmIP_a~?Gm^>hvAUh9xwo_{nCoI>v7&~ zwVW!J9Ey1WZo~UUj=XWqLQMU)dp-sjJ^xBbJ9>YoBLm)W{>IahEJinL0yUD@7*&(! zF6w-$wWNvLCS0|Zhf}Rd2kR`Z0s&fSjQtaJENb=Y_M@FW=WtR7*ja^XpTqCQ+}i!Z zf8m;}@7o%FF0zIrd}+K}2!q|;n0GhQ^H|{rc^bkgvm-xM{H_L@d@IwktaYHG8fWHy z=>`Pj8F@b4U+TP#A)j1}@Y4*eVSGDKSK~`BYS_`4hbc2!)2%AL*^D(Mt@d8-aF={9 zZ-jEoX$FSxgb6lLJ(-pv3zecW-#frP@ycNCN?ycslN)m+#GI8Awwk!1sbHy>s!XNn zm#%?BN8%EV6v!ywbEOErK6*5WeMOLgCRrXO2D`*VPEOTv^dv{gEZYrl0>;+uP2AKG zcCQo6>Us&=Z}jd4<%3+K*`T-GffIooX{IIP2nvJ#v4wnsui)mc(K+4m$Eq}DPre|}9_&CGyFF?lPk;CFH!KRE|7mNKt`vgczoZo$A@u)N-42sVEaO+R)plM23o(7Tz00L zJKCe;B_{#$*mtYvm4l#_Od2(NdvbN`yT!uC(6aj;(b)p-dAgb3njc|e$aIKtlG@e$ z?XPpEX7}5uH2A4F>+aAiOO>vr%8wr|cE-ylt#`Nrf`22AoTs7)r834Wp~Ae*CSZZS z&g*n4BZM>4gdr?R>MX!$yX6fkq=N1xQrd_8Pz(MF4bXS35PMEepP=-9loc1_eP*hq z=35S*d~vJ5%}APc@yU+R)#8>{By8&W^{Ma11h4Ln_7HbIVi#mZtld}P5b#=Y&4$f*S7x+r(CB}`G*hq zZVrox0780Uc8K#m=i59gs-?>f66a5$1om@!m>8cpG-o<6-z{)J&=rgBUm4#m4b}zF z30sLmIM%V0?a>OVo_>Asai(jN%OxBo)l7M)mXvxPMBKN`ZSSas-IT@0qk`Q(oevyH zSnSBv5(XKhe$n5*94fK#e5@+#oJztv@Czd=B#$qyc;Qh&Icvrd=ePN-n7Qc(JKvFx z7y1L`>$u4S15)O+o@6n^o>4uQ-0AOdK?mKQG+jF^ey&Ykc{6Jv!F%QNeHSzv+T$E@ z!U8pD4MWx14oCML%+e?JH#sq5*vBm|-?|(yL68GG%NJgov&Z*sBOM)eQp}`QL!yfo z@t67^h2T--P+!>>4j89SY$m%+wDTaGep4BvgSKVm}qTI%yRtOUB)p-f1czlLkGQj z(2^o%gJeozLPr^w!@@E0-0<+GY2qk)b|&JaAIQZMU9Rc5jk~QeXl(4I&Wxf&5)wbh zfK!Lt;xIO(8*BZ1T&)9lSRo$r=jNMbzDo$fq-w9h#?IE6r~jv_srdmolU^_K7sC!y zm}Ju$vX(eeCNHcfX(E~gVm=+%epeFijf^;K?Bb}SWSR=A?(wseDJKMBa>7Z8*h8E~ zgR~Lk3Scc8Mlz8kFTW$M7;@^MGAd}B-?Zdc5F3A0pe5L)$JQAVfG%QR)IxO2nOSb- zrcJzcSe1ycnP{P0Ty{Ih`6S1wn9fPh&BM#*dG6THd3H$c)GDe}D|C~BShGz=T4sw& zTxmePH)M)EiURBe{Q_O=8sA@#!sHN4>}%ND3C9(rtN%(K+S_6ZH$+?#b)JN7jQLAg z6=dxez+T#s6ujU%N>cUhv9uL~?PY#QGyK*M{5K(~j?N2FAB5lq?ky?eyX$pdoq0;J z#f155IWQ~n-n_SrM`@Y1Bu}~SFkCy>eN~Omd8J$O`=#_^$87-myOiFPPx&kxW{B$w zJEOv)G1M0Cj!7L@@XlX-A7FHV#(Sz(C%XUHs#vkJ{%2y)}hBkIn%<|ytwXHE94~it6#VZoX8lkDUL2_2H(F= zXT!g5{Wds022Om&Da?nXJiJgYkO?>60te}QeJfJeKz%J+{1v*+E>=Orq=&H$s( zbkaLVl+M%L@A;y|Sk5J_j`X5V*4#YA1Yj8XZoaC>gcG!3K2L(S4!9+{OG{I94kp69 z<9as=8slghb06#ZB12WJ<^D!`<*YrphL#mjPd7;S_vvVG#gkM3!sWSVy_4Uci;K%0 zj$Y$X@(D>-y*@%M%Igvk@0yd%ALNOPzg1Y>TxWW+XNlU$A%1eW=GQg=vhjY{neCUd+P$i zTO@nI%i>0Nkn!0|7L`isikd*GlS1)^Gq~T9|*gd7!l2grNqi|3&k&p%q|lUW-T(X`AHzy9D{UiH!EyNlNc>|(zPy?Kc{ z1rpnDsD^xs=w7g*W+ZH-Cm7UZwvG%|sB8$h!b;Hj( ztTgSLsPddz!#flL{G1#_F4E$Lx;2e9x7WEvjH)z{Y-6!A7l)+6ufx_c6=b27_v!&# zw^oXKP0_4znaruSKafE%Ue$_NQc128=b^*>ToR4!xTjtsUCx(A9V57n3zG}JVNP?W z;u`RcLQer8$3A17MR5_CPfk)3T!!lwchSm3kPLK(;t&@e#@-NC+Db>m z*}z{h5RyzMtS&_@@fI9hh7aVh$_48yHTMmFIHG;(_I~`y6;Z}4@o+j_*FX=m_bz() zY=bkJx<2^~L^Wru?Zj_cP5L1ZK-asdGmMZS&nTSzl9G)GXl7`nbkRNfxW`{U`JUT* zG8G~O#y>z(J=dIYp8VI)-fPWjRCFe)om7FZViig9!L~)VNG69vuXh2L+IF(wSH!Dg ziSecshB%T<@2D(bTsB-X?k*daG_VUQ;CRQIh5S~fl_lGqD}usC^t$}Cn?RuE+%%b! zmbg6bW{Li?mq>F=Nh(IiM^?yRBC*bIuHBw1#8ITua}y>%GbB4Ti$(0$I|tgXoOr*w z>cYhW-o*vdU^s2(GMj4tHliB!WsRyQTH_KiWELDXlpMa!xBS>|&aPkmxxhB$6-pzy zeTb27VW(CG2V0ERyGi-umTj&@I!vqf71aO&<1AS1MwDKPhYC~rJJzX!-;U!fcMF#0 zwzQo#n)1EH>T)B+am)hLRRZSAEXJ8lotX+fmR{*%gxlY$x+gj`^IxGHirw9_vInVt zGK-|xU5aNv&eERfCBR?$v~V%L#)O&dtUrW%i=@72L{OY0hPP{cGx0G`uU)-egjQgR zdpnWZDtAmm#1MUh>=Lrs<>S`2VsNbT(uHPgn&rF1w(SdW9oV(WzZQhfuzN0w8{saG zjxMJ%|D3chF-w_u{1Y%)vCeU>6e)AzZ1Z~an(a3`V?p9GCpR)GCs{tliTg6*xo2T~_vgvDiy3$Gc$z?kOc$}w zJ$6+AgYw_PzQpMyJ+0D4w}AHpjcPcJHH%dg;oPud`D>@trh2#f4jmwxn~e57N>j5B z$%pB5uM1nLhpDWmz>|BL2@yh~N!b-DvI*j_F);Q>)^Kq9dqie6aqE*iA#*H@8g~Lg zGZ#$UwCqMAdm5T7hixq$XS?XOUlPtubRa__9U_n?Qu=X|-DNVR@Ayaxp*>ug;L+NX z5U)`z+iTmnksq4XFoej4m>m~klLvYl)f+#ih*^_6$(#A-$7w1lVPgiRy*m{NHknUI zQ}>^n&vSBJGx7{)8}*prO&Z9GPvtE?VdtI+V?}wLmNrv@$!;6#Th$jQozdh@&?7=} zbB3;0%5@t#n8u`e^!rO_24Z03?T{x)Nq=K_552$hb$d4;iDEg}m`S3f%yL=y4JKL1 z9~5u>EeSXEI#4V-h_vF&_JhQ()Ppp9LO`N|p?gkc=jexDWZ_O$;96ip+~CINr(u%K z?)w)nO|`6_o1Ux^%sS_)4utP@TgoDE4dE36VV`ff2xZq+L z3{89AgdhIFjZw^*6`fW+reC8}kk@lY_%Ad$+Sz3;r};}ER-i?GlWUXBDZPZ?f)4j; zichaOUMiPQ5q_gUXz?rI`Tited;PI&Av3uVl67qKXI9Q2K%LJ&srwC z7IBzT874>0Tl**uU|5`r(4hX17x*RnD+N4F55ptU@+%3*KS6os8IY4|B}O~|FQ~! z;qp>R>c>k%o{QD7bI3~tME1&Co=9aQG#GD*Z&|B1Gqqf+0jI~&7jIE9$k-e2s`$EW z#xg+pgz)u~^7}VBDryXe`wZuIoARIv{pT+vqeZa2k-s}c0ywkw85L6OI;fOeH9wK_ z{W?+4==2|l{4a2e9p~LUv`0+ZrrUx`!($sGs|Amf{hP=LL#Dy&lAZy zH&Rt!3h=CHCMg9WMYj1yD4IJl(Y+Aph| zDbQX`z`a?*FKStmq-2|OW2}Nr$0;5C(Z%**s$#pMjodt|?!edhr}=|CC=_*q#zE*D zejg}TuaJyIy3jyKfGy{oYyI{(I6ydv9#(&XA~M-su{_}M_PAOJRhbi15!`REMiD^D z--4}l0;zEkKIc%eE3pljn0AQ&W`T3yUIl=RAH?ui~1@k0m#+Pu{)OW03mlFyo|4wm_V1UZ^ch zhr;!UyJQ*cd3M6_{sT0WytD9p zoQE5xd>Xm?3a_M-qOQU-l;UyzA|S5MPJB}+6vQH)!$uS;T$GS1_9j5Cgy*Nn8Tq-j z;~PYH$(xFVr#+FOuT0@N*70az!fiQhb(@bbM#(#WroV_!%iA81@RKa04`XY(B}e4& z6S>g5)h-V?*EI7McEXCv8XA&+9!^@b#ev^Q%LWx}d9j%vNdT6l zPPR5g=sh8`|%CaYy_UWnFvwA;zL@EZDPRJ@XFGU9hIepZ0HP z(w(+`A9(PL7C2%uZYhwDvpwqw=yObNlvB{Y<2810ZQnTTun^7IlAS*&xCGM0!h(k3~6r6xTh_{In# zy!DfoZqx9d0>3LHIgiC7eo%ekS4+HE9=xYc&6Ro6cNB5r`*EXbZ@<@gE=F6-ds{S9 zOCe@0W@c4AbuTkEA>(SyfR16dQi-he6;D++Tc6H`^3L>U>fukwi|`Zob^ML4X8U8M%H*Gy08)k@q3-VYiBbh;ZO(JmX5?b110HfjYrj2<`z7$ILJtVbd8TBqf5^ac=9(7mh$LGKSQVA;}A$Ix?x6 zT+zIBb89xmEVVwBfE9!IWpR^xaxsn@#qv*i`2EL?)YTk^7Daje5uMD>VDp=yBZ zYMwc!Z>##UK!}I(l|owgdG_e6uyF>gMoTWwV6)lRFl7W)v7l_bnbMEe<0JPd4&N?u zsl-hY&$1YQm#Uqj7K~akWN@rlw)jA$wp`WmRX^3wlV25pwd5G`pZ6$!;x!f)hFspZ zd9~%dLjPwoUIxQD$qN1PqKAq$+=}M(3=hguFk^=Pi`dRGRGhq>dh*qCnKWM(zqmc_ zY?bNyRWpw!jZcjpkX{}RoLs;v)=c(8#=xu!P-DBR*vked)r1Z-iV*l|d1_)Ih!j#O zIntoK1>4qFCy`Y|i|7_AOX~m(-P_x&u6*;+XHlN_pTurt5}k*mHnz@Q1z+Z*?WJV7 zd7=b~1|_}Hf;RR=zf}JY+SOL1eyHB>m(LA|hu?wo0{(PkyNaZbsI442;#!{JkK{yD z-&R`BQvY2nffsxQYeX(K6)N+~3$om_ky9MAxXg0(gRH}rrR1X?Bl@!ou(aPG!e<{b zeU(x!uW#a4mqZ4*E=}|Oz0i8;BMrGhdcp)BRJoq`fA2#N6_Z&t*zxntCT5~e`21ck z&#Ini7XK>_mJe19*iS3s_`qqb6aM+%wprXb5DyrBb3py57&r9+>wE_t$yb*-inT~d@95J!-O`rpU=vZrXXpA$@B!UJ`DLdcKlpi6u^z)= z!`!9f=zL~+6U;9F_$F{JwT<*L?ZT)&F|nZ^QRyZu3--` zp@76+)#vQ}nl*DQ6*l3Ka!wx}r-$nBK2>iy@u$3-K$lL_a~d}PTlMriFCYG~dN zTfWlrC!yTsXK^cOt}Hi9`}g+1TA2d2BCEbtY^^ewbrapLGG)CMo}2?U0AYvdxN#&y z*H7JqmhC&s>Zp!6Y10OCKuXYMjgu=ql)gRjKyDAS7lGK+G`)+nBSN_!&?)@6JO#Ph z3U4Z=@j-k47SnvKRY>kjU400@3T@|xq`i#ZcI(!S1ViO0u(m#FnR6|dJHFm8(&Gs#V3 z5L#p3nfsABiCYXtpzBwj(ZLuZ)p*sA+wh5*(*avIr|l5abPlfDDV7c=-9Kq!>5ZA* z-tTAF0t2wboO8T;g9H;s9tOHw{D6k(c++;U#LOsgU&FTD?s|*A2>WDW7ntmM6phYh zxHZ#$L;)c??s9(#$l~*0L2~us%GEGzqro?T5V%}$JCrm~nP02BWB(H8M}cN_e~t6x zrv^zn{7MEB!Dwls%LY5_%*mbZp$F_BOHI|2`4-Hc94RWp*j|3^?nEdXUT7513X4RCy=QUO)YIjIQ$vbLD>cHT5jzJ z!lQTZIr4FM29Rs%2=xGNhRFyoFo#!u%Z?&+w0UPxjOgD=$G!Mv3?Q6-{|WJ3iEL6p ztDe2J?Q<%N>~i@&vrWAIb1`lP=1Zw0K2_YQL!$u(Cn5%w@l%cV{fQrJuoOn0iVdO3 z3$s>8ojt4*@b<#Bnh|Frsyf3=mXhOMF5CmA~4x8pnX;XXYS$_i% z-MYH)EOf5I)LKcUuXwRQD*&vz07}A*fNECU1WP`mUB6(7h}8`@_zrt@Iw7O@Skj(f z2L19<7!90yq)>}5Df9$XgKEM(xj-bMh>90e&1`RA?~}0ovPda!(@F$R!<$x&RYeV| zw;Tza*kcb%>i9rbYtif3SH;GkeS(Korsn-G|J3>w<7hoq@tx9V?jWM^h1@p&4MAI2 zUpMb)v82i?#0*$ryNkI$zr!C0mdi@gv}8A77v%2dXOiAi?O%9g=J8;^*!O5=dO}@3 zTys#a=BnS0i%rWLNMoi2a&NHOOtRstWs6-L0vchsJqtSUJd^RV`DS_G0{*yTb)#TT z*XKBIlc=L^AZVUEnnpcQ82HWf9;U4acqvo>C|P*(4@+y?myu_t$xa%;DeYI)0ySLY zgEbBMOUKmXr%&l>z;*N?H74R1Pfpa^%V;}w1?>4Kk>m4XW13Oq^d^C@ zI_`Bi%sUU8Sq8xjck48hE#6vRAA~bfzUW8Pm(z%Wo zwPz<&z^$$m6m$91rO9lMMl)K?*ha1v^q7g6kj;1y;E@aMS5&uAaxXLNdFWSj+Tu=z zu1_eEM(#|gjE)aiTQa|&NJ#%fbo~IK%wV)&gV0v+AfTYU)~O628Zf`!hgJzfBO1S-7WKGX~Ly}OO&mH>_`8tx$EF2ckJV&^*SfI^~IQ&~w?ni{6>4<7(qQ$Neq%gWaMN%4OdisqW~ z-psII8C>&snmDwzy9^o)ZTnuGI9owyFK%3~sirhSb1}KvL{jS%;0`70V^-`fgDD*^1pGUAH(vc`T~QkE@3N54!tXjQ6K0HGRQejkpPc7EbyC5J@9sTQG$XFq4@ zr!lqvB34p;Zb)C}5N}Lqg#sSDy1)xlj*1lwb@Ghm6{r2QV5(2_<;uD1le=o?Tgu8c%;nW;)>Z zy~@tWi{$Z^f%i``aCf6d!{-#_%Ahl!fg@A--U0Ipp*}wb^MzcsUC!@+&$I`lTSDu# z=h8F+w>}%*j75hrFhygrqnt=$?oJIdrq1gdka&AFLz!EvRhW6ftbVB- z-1M9fgq6p&8SPV73W2*Yo0&%uqe-6)pI=(_%9H+bkiqHXae`qf00AO#t|XmqaNtT^ z*rp9PlZuEOt#Ql$XTkCaXi?B+*kK$mhV z-6NN4u(IDRRsawCxL==MK5kQ9^}94@rWp`Sb43KYv~qHw5`9=p$-&G?7sgF%L8xqB zJt550Fxq3}D$U0J?~vQ=P=xV)a!VA8JgFF>?hRkP;ILnuu`8VfWbb{s6J&>s?Yd9X z*1nVNo|!#DhGYhXlaNVz3Dm!xYIMgM*TU|LZNpTQciX{U+lNHHR{M1TVv_tV zr@S>YOvMstD}f%%bRbr#3)a?i_3xcEQKod(FpN-_{=68tDEL*URi^puAW1AyfTApk-Y!b>I52!x@9Q+f_~3-1Z)nN+(Wm zw0i2noZ9~RhqhK?S}qDtdtY!~KiU#TtyV*7kLM{dY+}KMfKjaPNQt?kreCxuOW}3L z^OX(6xBz;~?Sr359I?`1oz!neabKS}+;AmIuLEa;6?Y-B>-o5CSL<|pn#iikRNEAz zlBEOj-#%tIUr<3pqHWnKl1}cr2r#_bZrTLpW$<-WiZIgB)=a)H*PX8D7mz9Sdv4miM+jWo0dUX6zhvcL$djx=cIY7U2xsJK}3#?HwFF}_q?FEP= z2^Mlk;wQ6Smx|g<8;;qZw2Uy}6liJ?93i7&YWzlww2wj@bEGue{K=_IRf z>69lF{L(xr-P`sLDa&E7@ySB_f1%(U(7Ut`5bmpYR7L*qFR?`0OC`R=07@Ue>H1ET z$tJf5OC8AJLR_zGTBPqouueBJ3$ZCWvtN5Me@@tHPl`?Iw@A6p@GC`m_@L}b$G@GO zz^C+NVve}4w!Sm}?t!vICRo5Oe|@!Ll1{{j{Ww0>Diw0$>j1E3xr*k%M*e8qv2%HM z6ZOj~8T@tq8DZrtJA0=c>Zbii@or0)@9dGDt9aB|f(2_kFS#4hq&Z#krNYPX=pps+Tv+8mQgE0pf4vCp2u$qVS-0q4Yr*Pz$j82N{DGA{PP9OUn2kT5zeD*Oz1n_ zU>Dsfn;JF0wHc`{X@?IY)!!ZhX9RqhLGj4{tkJOg7LzNyzH(o46eW7W64b%n@6g#x z9ed0?lNjL5dlxQ>L!`%_;Kr;7F5@i^3tOT|^dQ&51$* z>81P6MKrU8|U2KN|_PL3vTr9Bt zdyyW1aS8Aq1q4Jq4@$`C3x)=l6B8TD8ZJWZl}lCMpA?t3?q9gbA~ZK}r2;;XE$I{C z5S!q6^&WM;1mH2B6y(6CaR~(O$ByCZY)Esq+&!pG|Gv$~RPZE_?1B&cQs@xJ*5aGV zv9CS2XL{0C>_;}Y!L)vt5=(rnb2E*@-Q?n=LPawUT`AEB+zT8TDfavk9yQ%}MY1_a zeTzN$~2g$lC?sciXvmE*Yz$G&2Ci;?whWb z6DvCW0KrxZ68Z&)i%1g3*b}tM3vrnTFPmL|>7t3E)VO40hKL+aTb*}8E{#z1b_fp# zPQf&<^}0AwTO@n1%OSmtm{j4#@u-wjwIQ$o03?0~aNQ0^mq9-7=AQqU*!~BI80Au` zVIoxCi=pzdsEJ^YaKa8opxt{w`ybW*I@yXarimkiySB6?h(_|R^bCRzIxgxdC*KIPIv(v%O>UbvT8n5VW)Bx~93{4>wm<|Qcm>87-QBYC zZZQ98;3AU$=NW?gAgiRC*46|DzgSC}%GN9#-*XMSDCC?@J4t{hAfEQGQRVGCdv0oX zD&&?I6)63HTqe)g@+(km)_{#kfw{*2i~+2Qd%T*8#PtZj8KEU2TFA!SPHBR5!}x@G z`=BUVvG6av(dbfh!;p}h!7XT?6H8ZRy%WuSgVM=<#GI0@M2}GN`8eO)G>T()&tT|P z2A4WP$Av}y?O-$1-6@Opy%cbB2c=RGd)R{cM4tE{B}?zm3w6D>n{AN#6r`xbjqThn z-?F`=0rTP+nwy{!r!m?-Z){d0M=!FSE7ngP3*iGJBo2(9Bytm;G~!BocYwdoMiHp@BJRzXTDNFVF%GF%{tK0}#} zB`wZ*-VAAqNLHcpT&)%&IR&@uP!cV;h-ZYkbra4R1i^?4uomtN7|$qxDg@UV7N=a( z<^x4tRHek`>w#eXC3{E*JQr)3YO~=id=~mn=?iWJDRI>GFGzmdwEUVh-Ry-#X7Wvb zEF~M@c_-OhjRhES&PG~wql}?`NgZeHzUrwLfbH6`5ZdOYZwsHWhFFWuQ4y-QK){J- zlPhcAJL9%crB#^Meo>G)r3uTIN%v0>qj*T!K0}&E>oHWP{zHOeaD<-?O><)RBk!>| zd?4sk?==XWuQ3-uNB~1A-UtU%AsISPUcSOH>{K!NSE;ewkXc9oti@W zQ}IJEdzQ`K@->=z4OBwzSJzSxjq{M8L9ckHe>@rDs8{O?g=z>!n?)1Gjjr~%w@}6` zhY&0Vi9Emn0-WCy6B*hXC-x<{txu^dsv85$n+y(Hp?+!XLy_E*es;wTZOZ^4Gg;ku zF8Z~DfFCpXEzr)vDwWdOdVfecoq~>&N)f_sQ{egbl@69$1=bjxVDGD}jpUuB*JlRz z0JlwXPe1z^q+UtuNn5=?W_2I7t&4r7EQ*G8M>K_MyC&5aD7Lr9?Y|~#|2j#EaSE{%SK;z7(4J3 zdCjRdpQmwtK?X~uX}|c4OL^zos51Jeyf(jdhQE%f*#|AGBgE2MKA(@^Doj>Z`W2vt zl^UhB)=O~G^^P{7V!=uR3GUcF31PgI;*&28Kn=c0F00sbW61ukbSVHo$_IWoGKcp@ z2#?%ADZ9Wqt3JS}$K$Vwnt)eIaS~FpT%tshL)~?U4ib=8V#BEZN_5Q)=EHW|F^p~S ziW{My?Wct}i(^?Zr(}waVTmvx)l8Cuq>*F6HQA-#WZSA!e$%z8Y^fdujZ`k1yhHBa z#}zeQL=LdtnY&tNu|~#Tgl4rR@8+1_*}DccUu$r;srdQzpaE{Ah-u$+DaSOrRlkFc zV$?z@iy!FKEX1#Pv+&fi`UP>dIss*Cx}v^l8wy=#t^w}vEulIAk?V+*M9~; z31qO^Z|wIxk<&e>*CY!Z;gV~NYR9&0O_V}KfqmOb;BXR$!FRA+w8qEmQhx`D^m}fs1iW zHy5ng8wWXwhlkB;ad9dAdHs61S*lsbNbRjy(K*r$B8GR*_)Kb1hi}bY_em#|ZBwj5 zhO?q>5{#YQ)8fCciS&bN)5>@vfhc%o)6`EY2&^GlC5P0q z&We0rVely9=k zC&^nn&=K6jI`9Mmx^`vgFbP0a$z>9%;SWb}H>a%-`~JapbqXv%J?Dhvv=w;5$<;{~ z5NR;HHQ)2!3t;#|SX?*ozE-E6oIq%gk8fkL>TA8eLIqe=SH3WlSM|UDuq`+GBh0WNp%hhWQU< zwVEX5lu7rpTZjqCXS?E?+2_!!Fy(#JkBb?(b^Z7W5l1E{z}JZ=^;k_GxQ<@0BkX)d zg{Resv2mwxTHY`>-e$}cysilb-jaVkKc$tLxp$KfIQx^POptXLwBhz zHA&nd?g4-R4+jULLqrm~Nl8fl0Du93w@Po7k9p-K@k)(mn_>CXN`$ynL%w+l<$hco z9bEcXWG2S-;59LbHo{?hb6G;>KKaf`;v&BYu5B9MPLAIviSLh+Svd(&u;mwwm(KMJ^0JJnm&tH8 z3D0!YdFl^VAd@~Pr&@5v|GB7JNcWn6Lx4_n%5GG~yi^c73}l(fe=GI=pc80b#)s6A z^tVWbRLea9#t@%Auh5u*`qPneUnq~0SbGJk0fyI?ch=8w{O|?_(jt}>{~_fuCSE42 zZ7b(9EK)>vk%(js&)Cgt%LMbs!qrWJ zPD~WT&~@F|e`z4rnN(sM5rjy|l<9)_C(1r;Lr*D6HtLPI=I(6#ppcBfpgO)r(Y(Br z4k(hZ=#y)WVdFRl%$#UXoEj$gn8QiHJg71o#D<^OU&-Ui!cztLe3B%4Mxw+5an*q4 z$NQ^bIc*Usg-Z*cDcb)oPeaVKfnxjo#1K+;n>+^=<$HIEdM*|3r{(X!q5=1`Gub)H zl%86FOwpFD8ybRdyUH@3YljCBnB4C6TJsJTF_yj_)hu7u8(w8(9V8NIkc?ptk`pnd zMcw{?5T^NiBV3_jk=!R$PteDiZC7B)DHK*Ys0gmCJOvsL zt`T%uKjeWv1e-P{WsPAWb)svzW+O4d+t|W5C~Q8|fube72QewS(@fEPW)`ELMgkq) zIJchX&Eq4g^ZsrC09f$29Uvx}P?lu)y=~10AW0+Orh9$* zr>hFQm17_TD-}yAJoHFM;8kL4bdx<90Td&CiJo-~lbL|yU%6z1a zv@b&?Kgi|+)jB7g(4ryuIO3-00^{vgNAZ(KfKH1$_DwVqW#1nMV-4o zFh1q|>y^oHNZj$^!H;>DICljBNBLomqm zCenJOfL?I}Z+7~bso{R?hfrh_X#*QziL7_lw|ErfqIiju=ry*(S#e`{s|!e|>8C3% zjg$=yLw74m%xUO71)K}&>Aax_bSvVR04n^cHi(4P##HBA_du=V!5mbun}O8KJC842 z?i#nVx@vgSy)IRrC%K#OetGpd45U{HAmm2bC#c8My$X_hX+HSD?pSD3E8M|@WrVN# z$J;9D@~jWPH$5=`Q+3ApPBsCD|1!3=+m zexN(LQP^Rl4o$vC3WwICtQ?IizVt8NB5X_p{HiHasNnYM6PuLYtopz z)DpR$oiv_{4Ml?3wC~v27E8Z{7&3Dn7RnXCT)`wpQL$Bj1MrS)D5@o2+BSFj&*>Ox zwdXjH8J%8d{>j zz&sL%O8kAt%|jK>Qnm+zoi)onkN^#@gJ&51SamHfnHsP9s}5h5Vr=&EWL|$^051!h zhfaKW3bql@BV?Ys{lzYz#nmkO(y>T+keYM$0cz98ir9i(-GWfeZBpeVB1%gDaGI`bN&`l=EFco9m=-t9e0C}H%=yJ-q`5sNIy;^^m#)2|)PcTQE@J+k;F zVg<+5Fd(G)=Wn$l5gTWxqmanYvkAJnY#$MS2N#|p7$=;cz%3|vU|Jg!Iij0Edf^;` zZ1ebR!^M?D0UqSd(oZwVwx_3>ZL)bdiWP0kV(9ZX@l;vhv6O97z8>_puWEwh#;Y-@|g13WlpxK!TF+ROkru zEPpvi!Vz*SL_qL<=E~eoz6DL1ykUV)KlS5lgNvkqJcX|xD@5YmJ5lpnd}Ib{p+1*E z!u?j&?6fhkAK*z|zSB?*s&}GNR=J5cA?ALVE$`n5y58<1)Mf86+BEw#syOm1l1<=Y zDvd(_2J1J|rxh+1Hjcfob6EKvwabj3VN-{@-2W$Dq@yvxYp9FySw%nJ;>0DiwmB_e zv01VE_<;SHuZGQvkj|Sq)_Ti5w}oYE?Q~%ono%#5EmM+qm^|L@MbG{y?uia# zlckfXRd#LU2AqvRU@aUoXouFxG8m2%@z6W1MnE&1*Rqoy;Be&Fxji;Y zP?Fu-BzX!fLMFGbhz7{#8^cOER&2Gk<_fLcOq`)GaVmC+9x4&-pAjFh{pfH1LZ^3e z%7N0gYh!PlH6{fBea?1q`!a3||Hr|)m+7$QSKvPN?7N4!0rKF0t1U6jk|g?haSVdf ztA|{w9;hggagqARSf+svz`+-Z@X|C)_HD#{r#}S`ohrM3Ry z?sbqf_B_UNXTcw(BXX{LLSQ?eY>U04YMV$Wm3R^kGc*!Vv56D=I$jjZv&g#*JH>08 zm)^MaF=N{X+wG-d$8si+ZB7r_16DQwsVK%^@Tpn}bS4{p*Szp}9X5kH>@+A3S3i;( zYt=NkU@d|e`a~7Gw!L;uOLeyOO`%FmP-vc}fl7xTOG3F=d{l3Lbt}VFD9j2PNI%L=D%d;|YxiWtNW`y494ZRa83po|)zw1PuLzv$Ny_+zmATrT-xqvYC zHOD*^&pVqOaxWV7h({c|ff&5+!v^DzUaNnz*r#?+3sVnX_GEBzvaRp&OXuhnz<$ML z{(zI$eB`F*OlSsfH$<%cvg6E6K(e>I!pkhis2MW zV~ym+Sm?TD!a%;xOqFBDXndWLv3Lt-MEkSS7zEI^9*OA=4^_%_*p4lj?Srs*z4n#m z+yutdLie7md(eQ<9p@#@z6LAg@M~s-nsCB+44Q9Pt{TfeEb9~DQsC->Hihbhb9!Ek#L7fv;jhIK zQDHyTO{gV>p5Hq^@3OztnRQ>FjmWs#8p?|ue4g$8eueHfiW&kDdm6xwEQ@f4!9Uq^ zEKMavvk)@=zV-__6Nh~8(<|t)PWer=n0Q|P(e59>L_-9mLK2arWguz;G)>+0{K7>l z&A>_q4bsXmwQzf0!t#M0WUH^l0=5AZG7?5=oT(-t3?BZZev6z0vXHat*Wa3ft8OM1 za-42>=1nVUWho3d!+O1g@4T&zIQh&g@>`#sSOX_zU4rV=m+F zcM|V}%YbqGnUd;V0kN+K;iPvYZuos;YzHcDB+7n(a1VSmQzWSSu3DeR^VGBCW=F~0 z#md2LHx8uol;KODMAwL|Q#tALCA0CTmsjFM@4&rRlBE6gvwzVr0zs7deQ6vDggZS2 zD)g>kLO3olSp^dN`aO9Mn3?3^EqLSG^_u>+gP1t=OwS#dgIa z5+DEoh8IJ)iJeb+ij0u5y?&!j_zOd9O5-?p=l0720MmX|ej=9?FegzDfVXuMSP>oP zAl;~01%y_#VuVj`z~oH0z1S^}fEBJ6$U?{3|Q9c?m8LWY^srq~8WVTHWullx7c=7A7$v2Z(RH6Nm1ie)p#@b|x;DHqvP za2rV05cW~X2t3oro>HEgOQL%^Kx)ZmuE$WY*u!56f-=q4G5>R)6C02?$>#d*GA7)RDsp+VJ(!q^gM1hkK%H?+#S`0`y$4}0^G!~ zK792ZV$w$RN=CJo;bw0=_~r>hF7jg{#FKnqXj%kggQ5M&xLFkV;d>#EO4<-^2ox7B z1s}W8qD^>M5N0n|{Rv|>Cu5A+{qX_?t#=dh9b;y2r`Okse{OgO?dsr46ttRNdpI#w zrO^}=bv%k2G#c+<)WIrK33zjSM`^RqQ{eA=ln*)??VB^^a4pb>Q3-0mrTLDsirHXz zW!qayPU>ij+IeDOH?#hlZmrq=AH$DE^XFdc!l`662QdgcN)8Si;Cu}YHFB>~JD#Rz z5f0BG{%Nl9-!HN-1oF?gF`LBHBWFDG2&We(A8xBzBhj1VDbduq4RR5Q7B?ZiHbmtQ zy0=vg#7=Z1d+029qa#zo#m~EJhvX{Qj##hrCb;CSw-cmU>a*^GVYs-(y7F>XGS+6( zD#b?CT6^VaJQ;Mn?vW`;G2?7EH~Hxc_MGP2&VM-Ts2aEDj77jM*}(OF@K_XWMi*ZWPl%04!wgse00RIFxS!C;!)gvB4Z!O(VI= z5=#=sFA#4S=0=I5DS!e>46h!*i3u$aUIJvK(rkp5NJO_}xqRk=yk9u+o&UkZs1fKe z1ch9-;!0R6shFPRh8RiTv+n9+&@5$b$N&!IV-W=` zUE%sBCK@TiwzL$@s*W{(qS+6*l(3wuymOsyBZ~_spRebon*-ArE)OS5B*6w=$fMyV zA-^Uu$soWokn&$Aylq0-1~qPNcXkQYTE|^%4HCmKIjT!Iy-jV?j+g}b~;1r2yPPT%q1z*$CK;j}qTKLAx~m#4_pTHeRYN}i=Kn*NZt z4w}LUL1Ng5Z^z;bI)DQ&n(Du?&@YjbjIy9;q?Hs*jEW2Vlyl=(c5ko<#WI6SQ=O3O zKDX7cn$!~qEq(_mxC|@4`-~o`6a)T_MnCc#Z*6G<0gq=)i_NCa0L_%2yUGfAxTqIM z-nQLNGUKjwL6PjZ=p8CkNNGeEyXg|lEjl)dX%pdFr8B;mRL2~jjq2!iDF4u}T&E#$ z?t@)W_(;HeG!9F={C@x_D3{3u!xQ?C8S%pbxjL>*Bn>Lww4J@E(wN)l*FYqHHw#A`=<+d#DoAemS$OZ>{(H5uRP>{X5RNFs-3B2`OB^(mjOr`D?u* zY6#nu@|dtfDFUn#qtn+(w*6MsYw`fh=7{XbLH1?PCqV1bDMUTLm|w9SrSRIejERf< zqLa8kdl!IG2*FWk;B*JmNc67_W(pw8Ke|3~+pMsWClB#>$Po<$c{U8|tqhjOiR44W zH&g%s1>59~p0y^6Q5_zmM}2r$Tb}#v5JSF-uhRuV>T@t&w3ecvW|uT&zj^^ARr-!@ zW`~R*xS?cyi3~X#YEE8$X$Zjxv>ROLhj(FP7n4{aK8${YqktHZJRJYq2JVz6*cb|T zV@`!w>zwGCx*Y4+dmy}6z%l+qCn~SN*quD6#Z|mlrHP0~;%ipBr0-y`(_ivuTn5{7 z|8qHh2iuwPz8r6UKS~s3;9Il7DWC^HS zkKpmit45Oc#3~e4jRf+6%W?0H5ycSKfxT4}URreUpJ?$Q5P^G>D?7vF`5UEOc!a3X z`m6Qahiz+`HV`a{0M=fwfsIr3H@3d=}Gr_QatKdTw;U>8#V#8vX_~Dd2k@b zqs*r4p_HPWo_K-VQ(8z>S_;v@Q=<*Hzcj2cwkz3`A;5ij7QLQ(fBK=j@cb`UyhNZ6 zs<4V-s4j|9kZ`ATu_#`hT=yX40TI+?kbvey^#euhbySNCMs(*nk{k{EL!&>GP9}%5 zft~`ls!so9qbo}bl7>l7I)cf=)7Xo&aB#JnH7$rD1JbcVseu^0Y5H$Uht~Y?sMs_` zhEIt0O>J{!(6%OM;vsZ5W0tmUKC@VWDmq$rc6WT9~ zoRy{PqaLOlA&M{r>^2uXxBLJA2W^bp&8gq!cCj6|WE+TsSZrGzOOmi8hNDy?btO47 zUHf6h=YuIOs=NRZ6`Qej)h(TWonGPTp>R(LKw6k|V7_h4}fVuuM|H`S=$ zgt`$h9jS=sOTtybo_LlKU#p9JJ$(@nArb5}(=>q*c9?W}aS<&IljM zFuE(Ox#5mX4t?~1ZYksQj@3|2`kJ<99PBz8w*cryDZR#sV?Rx=+odRwRByQ9|1U+S zh+mTQm!)?#1*{k}M*U#l;i=%H)iwA1BkL zKb35nEb=l|$ zn8!AFKEi%xuMb-9-F*VjJKdd$FNUfyxU~taLI8@!C1fNKe#d9W^QBqpE`*buNED6} z`k#oJ#5Crup=t4c16cv?Q3bBA)%U`Pmp8# z2-66$_#cu%fE<_s$f5br7FH=U)7X%QISW;j*tF18KLbtasT_j1J3blb>^_~QHvi%V zmM+w$9@gCB&C}}JC&|hSxog;w=*tL50J*(wawQK$000934?yX)s_7bJ1W5h}syE`p z-jI{b?O5nlt5$q(OC-LAakW>l3Asa3R9Fbn{S9-`4yFT9|JRDyrpHmLRIFp(^P*o@P@mv1(H8n66oTT^H!DHN>yMRNb|ou*eMQ)FSGKb^F-RJ@n8q7Dyh!Ij-!K@ zd*ick7GH?_D<19GJt;Xv^aL292Fdk{&&TS{R&15A+M|F1X*YW9Ki=lWt2>9?Q&eElURP2ia(>eP&JRooEM$pcP#0jG# z_Mv_%iWhz8EU$W+xE}-@z6AvvHKu&xv=W@CRes*c&ZS3s34zBz?{l?k8S0CkS7p+Y zXg6!ceF|X)R8;LK+^L^b>#2M%ppS6HCaV)jvsLn1 zm*5IuT_-DS{;g8btwi-0P&r{7M}|FNZ)9M0}5B6=qNOPVukBz!;$(z%^EpoA_>>@|R0D%okf8$VA@lwW|7) zsDlBP^!)Ys*PZA@o&ulr7_1%S^PUE(vG0QCzIQ2RHhLZPyx;V$S}BdwqmAKADxVjb z!&ro1Jv!{UdePy$_ybn)?s~t3=b72$%TNQOH%{j9#uP~7iZhg{-C>s+<{@4w`7f{P zmcdK#)es%A@QGjo2G6+I@@!I|wt^z&p#eG#xMo1u|7+tICq?jTegFYr(f!0D5OgeQ zK`4c2fU(@M{P;57U;tmYE5M&6ovXS5S+9Bmhr+o#D!+u;&^Mj|*{Od3bN++Ss=cyG zmqe9dU`N(x4e4p*f&3%f#zIA2j!N~mJpwdOM5FWL|5+y zQrC0`m%tv`S*e6t;m(B^T1>zSDw4tj zl^e%VOcz5MNMZN2Kng$?gFU~#-~gBECxt!$I2ooc#Zt^v^)zqq*8u_ptS{rUex*U< zA96W=2s@ZU$X9)!$i7RAq^hZf%e@l*k3(ttb|RMJp69UzE1(7=yJ;bl&94PEo$N$$ zWy_CT_Wuc#p7b`b7q91Iiv9R|a6%*Gy6G6_DBVCg%31_DBknH8Ad^<``Q}Vy>_1Bb zK&H9Qt5M{-RU$5SQ}2XdM3d_&nepv?&v8yPb%jaqCWR1WW~opyN)08)@5%g!2pIis ze{(W&iss54w*hM4(Z`05u2E0q+R9a2K5a|f#%hQjtN?V;Nj6qi7C?70uta$w<(~lL z8nDXK%uxra3%-{CN&q)+|w~I%Y)J6Zg~D z0I#Si2MMA_ps`j5&>2GXKi;m~fFuokcSC>9s=OOCSR#|Irt9r{tlk4}cw3@IcHd-8 zIsvKGo_*tdMl1CD9vq3d1V2&w!OUJOPW}MIl_l_t3U`6^V%d)X04{?zbFsQTlP1B6 zg+RCD_F`qtWv3xXTdT5JKL7*NmA5rqr}HYdP_**@h+%o1`yFYUDjv|)cK^E(2B>}z zPv%rmbk1m~^ht2Cv{M6zWAEhxeJM9u@BBnTnQf%Gbqk7=>`TLUHV+5IO6rPB6QHFO z?m?<5j}|&{0`ym2J>Lp57!@+DDB`RKq4m~=ombBlqu%ILV97-c|AnJzy}q2LVrl0I z5uZCIRkXM0mQq>hKzjeUC|jTv)eecKJg2x}Z{1KNDo>8RRV-i$fk~+u@cO2B;{3+BOE^?4IG2#7@>f=nY{Q)&2?=2l62Br8Mr-JTkyK{@rDPD`7zkmxu0-8$L{)v(vD&W-W9) z^!8d3?}8nSyGP9Jk;uDYmX{GpQ46rgqh592qJzk*duT-*D%U}KN*t~Ho~*-vc5#>M zH+426yUXfR!mytif!)zi@)MAfu569=-ewCTGesqk)qDPPEv=tmIOCH=BON&&3AP{< z>5+Z$6sWnH*)aWdDu7}n6|(wnDzjFo4690@MPIc!Ezv#GM&)xbH&rH9t$xlImF&z? z=AOg@uHay`#vq)~|Bg2-C2tDw_(30Uwv6PQ5NedlgB7d&>$JBiPlPF}k-W{jwSY#{ z%XwdS@r;7*Tem}=K$Je7O8hy1x$?k!zvrCY)|*&O13jsw7D$e`c;(u82P32VWH~So zZ9_)TW#Xn8oXPU$LgjkEIdgnGB1ID4)Sg`{i@SzDPh61+-?!hGFeTa~(oZ-4F2k)L zI*C<5(hB!b!AAoYpfI7mDdE}-?F@uGWTpk}$6s&_pGr&4M2JWoK_h&C08W>>AeIWx zSOT#0u>RH(NHNP(z4N#8qr2?PJP2d zmDgL*M$-fg(zon$!M6)|pn4d*jV90vhP;rK1Dre#D)q%cYA(2b!p7(jAP*VW~%lZ^S9v`xmO2;!%sJT zDg9eRpAm%b+vv8py!)Ji#%rR!Gb%^&chB3OYZfqY&$ne)Zj-ag(CH_t$b0!(!Q?Q1 z&3MmQML2p656lKu(6xuhpl<7{EIK-bJ~) zFH60;HK(FuP;vA)%6IEwOP^>|clyPgVG|U$IH8}dMfbx~wh8ef`HyjcU70P3W8*Hs zZYzw$-NDg>j{FV;*!5Y>{UPF#AmztIB=QNYyxhtVmm?=KNE5T=dnO9YIPw%ZuOUmR zZdK*O_!2^{4yjP@L4lg#RPUOv-_AG;-uIwgLb!dHF4;}5#sVAVkD{zQ_+Jiw0`0C- zU|cAg?KGqKY(fnsS0=I+y!!sUGyS*z=Qdxuuug>K*l|3KpBqY7dhza22^z1+Z1+9i zUxUQ-4M8>`qxg7>9j};xVKAZkkaerkXfBi+(A+GaAF)|8*<;~4>P2W+MIPmQ2CIJ- zn>lSwuJa^i6Tpnam z3dK(~gYn$JInJD&V9)<-37h*xC{fXWVa9&v(WN4v>eX==DDlOkEuZ>##PcoeufW`( zUG+gKg?34_N@+TM5Tp0%A2jWzLAB>a-j<>qT+v)A*Pqa7wC#O^|8VG<{6{zatP6tn z&wgZnynsToTXpuC1NzE*P@pPF8EG#J*H!wYj&Mb}8DISaA*$sR@7eN^uD_RQ6jNAu za}pq-4s&|-7#JmW1kSXc&=mgvn_x%#>tINllIwEpL2TN`gnpg5O9CUekm%19QqW%Al+C`wX}_` zZfC_C+xE?!5=sGP{@7H+Dd@>`0h-+5;Fulr!;H|MBf6YR(V8{inBqu{Ho_1APTeXM zgm9z80D5#Vao^x$xKO2-Wu%4}=T=3Gyl3Qf>Fo5+fCZMsBlepejE;{q*8vm*eHU8X z{Xu0Dyrh0u1H@LGbDBW0?Vl4ni{L#z)yADE#w+q#Y#n^2g*hhLsyA7>y?r3A@l-VG z;zJ(m>64|b3utZgI|b)u+@9Somu;O}Kt~9an)0^pRW*U0;cjIG5xV+(m!EKu6##zy z^RA%M!9{Z7{U8vhe?i>~{^gnY-pr}}MtDXdMMns^P%9x5_#b!ki2Ln~K$$|F zQxpI7km3pRC*S|~|G)j~7f7^us!9^O1^p)jsglibc>@JVYg3HuZR`V8o6U0}kgM$F zF(TtG@^MH%_|Sd$+v{>SHt%AK9JA<~b^^JQ{Iz^$eYF=6u5r0xU#UKZ-H591(~W)v zqJ|($k#z!X7?D8^W>MFDpID_FgO~PV6-KUs$pZDPD*eO!utIT*JyPQMF!*FkW=`w7 zUhbL3zsY~#@K~AB8eu#&h7E(Q16MTHn&}N5JJzh2iK`K*c$C@pJYR8T=J=v|`?VI# z@MXQ0lit^n!oy*)FCHh17JMwFO0~8&W|Bb(G9k8b4Sfk79X?SFggu2J1OG7ZTViPO+So zaiRvKD_ci+X#$w5YaA@C_@l_16t-Z$TScR~TDk0{qb-wmUi{UzSW|PK41Y3qMy(kU zHdyX*i4K?tRBf0;l1EyJT<_nc5-S2;2`P>OGkX6Kh&7V>7Sdw-R_sPZ;n&w^0kdR) z2_5oaZ@pHFCYpBqTflOA%-L^U%_=Q3Fs3;SW{IWmk)tY{Q}NjDJ3CcLl=1!GmLFL5 zcd-_ppH;>m1{eEC%NLQ&Te`~(cTtYj(EdtAf=wvD424YV_SGriov=+@+l=#Hx?l9D zQX`(wmV@+J%PS#s4w%-T3MW#YbOjorzeyIt@GuRD<;+kS^)0RcPMt-9`}xr&?54)I z5jR(f;;@{YsnVVF)WJH(%9kXc*ZkQ?0QivfljM$()%tVv1&dxuYz*Mm8 z#$a>J;8fl6D|jyx*86`Jp&PWAS^A87jmG~AFG31MViRI}wEZY|zhEj)K?|*7COF~|gxeze*59f%Gps!(g*O0j3+b9CuHAA#w|Lgrac(|D% zWA@0+j$EL8BMl8Xa!WTayqlk!BZ6RS;@sp&+zf)C0!e z=I~+<^~~#!PFS?NAfiOMq5S$Npl+lNu><`6N8}x<>pQq7#gR27ROJ!}ff{ED0aJOa zr(q39J8~zXOtsnkiyBJ5$+YIUR^x||6$kb1^m52x(%n8RN<35uDViVW9g3a|@1_y141+!ryrG-RKtRPDfjX!+Zh|xwcWkqeI z7B%2C^6+^?nEqBjfI`2UCq@Ftesz1intbc?J(X3FA-5p9F15X8e$9V}TOPT`vN0#sk8VwMe_>SIwJ_~|z`Ghq*R}h- zET4OW2!J(_RA-xDvF)3wfS3cRXT*bDhq;SPCiGa!z|KGb68^CwFQ$x%hv*h`>X`AR z3KW>HB21&Gyz?lQj5ldjA0n=TsN$F`E%B6(@(^YZq1!O~S_Y<91VdR*EZ5QL;M^cE zq!IzmXd00}p>b841X{UkIJMN^ct%UW)VyI(x7bvXg{|h-q{VKV+7=K5WKwu#1=^^$P z5pww9B%)%Y!$_03%Ubh?PR#*;Vdap#HaX*OhTDyC2~fTx;Dz}W`t0PCK`a$B_9`2{ z_2`(0p};;mkQk9k8?w$(69=kbnW}A#BA-IAgdzi5ps0*rvwG+O4pCLD=;MvlLc2wX zDuqA{{zk`#nUf9Wba{r+jND!L>MS!J0Wa4rM}l|Bq;}UzQwCK~IS3NoH7gcvz#H0Y zUNm4y{uq_NWSPB?N<)v0!>b@??+ppRe~PB(crGdp+>LJbQ3v)Jo?^dG?j-N^%SUA1 z&I;EC1uj2D^pv=LUs_>XCy8qT>ym_OUY++g7C@S6YMxp{Edgr7i)~yk!TVvkkBk)Z z9ij)(s8xt^-9Bux{5(dzA7y8*PTQVB&vfB*K*YaH)BpgHq%4S8Us`HIhh%yV>R%54 z7j5v9pd^26EV=?Zq`p$K+tcIkZdZ#vRGCdg7nFbO#ybi|A8>85Y*x57tu&Ac61Q8D zsj2muirSS2GZuS{Y8b=l8Eie%;@J-uKL&^J ziQ1UJ`AV?oR@E#G^AR4ha(*7T4>(%8oPiN`U3i8m*!p-?OaTakxd+}wdXM%#BQRW? z>`a)VdFT@>@x(MA`|GS7yr(50<>xPhk6nf(VE!a~6JK+38^!MU|w>w{cy$ zwp>XB)yr`-G^JS!gHo+;NgZ_faJCl=?69 z;iR{bE=6>Q&6ss$S^g*nA$AXuiF{u*jO8V7iq_qJ#o|=R(B!0VuJHRYjCl;*jgom= zG4dv_`k9rxkWCAeK5mk@=hZo2kAU2d2NBfXJQ9R^16i>mp6`kuGg*QuV`*MTcb~lCO3?ljFZx(0vk%D zAx>>Mm?P59>7txdv5RQ{fZD>A>JU@d_}{oW4X&o+hCIH*Skh5nRZ+&s`;X0~Odxo! z&b}qrEQAnPIQnjh|m#wO(=kZpAMhst8PLU0j6&VCvJ{H;U+C+_{ zva!(6=rTPiyySJJ8t|Ld`pdAw1Ps~M>!RR54TtiqeO(v6UC76JYSTDu%E=0IBnG51 z__N}Xnk4M$-}U1~SN~R?z`2gtb0%Y*ON@SlvAj7Nt*y z0-tbyuIf9*(rRmX469h@eH-EFoyTvYWrX6|2QdtYu5&G^L*D`akVe zfSAc^Do3guPlThE!on&eJZ#*^r|Gerbo1Xe@5G&g$Y!ttSQCI?wp)nLDNNE(GFlyo zj`e5Sp<;o|mc;*9`SJx6+?1;Tfm<;?#Ng#X0O|{~;sN24ZFHZFNcf#EB<#EQ-yJrJ z4#9gX+*63y)~e*4SsW5|P-*c5lTf2-l(xaU{r_9=O>w%6g%Aiaq0s6hTu&hDd2@5a zdWgP|n1fx-|DtR6VKG|?*Z#Z8TRP71lP_)xT9tEVv_EG^RGj5}l3)?`s0oYWgTiRJ z+#IZ&3%Meu#S1 zAOUB1`QY36jF^Wa>>!Ym{Rlp?>d^IZV1V6(6~D6oRz0!K>3*RSnP3}*{wn!vKeG*sy^U%VtCczXh);qT zY;c*JUPfW#qnE;o;jGwNwO2D5`KB|5FsIK7j|0sSo_3z0(zSE0ris{uiub;u(TP#2 zc+y2l*VfFp4H~hA@_x4iI3l|w0qtRQE~y2Bsox3U04%#N$d9B>SMhIfCY5gapUS2f zZO%Pxt^JFrW2r0|HHGd+Y-FmoS-3zWdGsbe-qLq$0E!)WTgu$Rk%FhLghOC>se+5u zO`xP7jwKVKf_pj4!!%-nwdD3|1AnugZQCXnfQ;>r%^$aeb2>^TkxaDMj8pEu^}H}k z^K!Mo!}lw{T{8m#up~V~62Wn4L_{cjC*{5zLtkodXp7LXL|pYTqq|LSv_+( zD9OM8eLJCgEC~?DJL%cxa{=s6!xwa2IBJ=+e(w+}#HYL)DV`^uYBKWnKTxQw?--xdiokaG^FZbXge+ z0q=PorH^7Uj*AVV>%evT&Hm0tpKNmh0oqD6$VB&pu(J(l!>5K#Y;YVeJWJ*fI1QSk zCxxQHGvo&4TI34a1|`3}uY4|-E-O~FF-2@jJ?1nlR&+>GT0I8l`WOwY!#^YQs36&#tLfLw#0z=k<*5JK&sG(uKo#U}=Ng{$5!+z2ja8}=&aBI}z-j*T;t&Mh zkJO8R#Ki=({mpambD_r1zrl33=`}D!A}%_0g>WX-a~v>w;z!1YUBS26?LfR7Exzi^ zSPHN2k3L*8g!yR`#o{zYPAL?-LU%$GC#)_E_p~Df=+0YeAmKUC&K*}6QsQ&5uXHyc z$uCxw91aV{$BBRA2Xka9QH9w z2)QbH1(mxtI{$=c%mgf*UwsJ}(YWduyR=bez zZvCPAKxlXTgVIN76!xgf%Y!GAZ%AzNoRCk{b0DovVz1qw2@^#7V%925vcKt(hzVqVUeJ9di&bo)!> zR4N&c@;)Zl(O2hR{rnPGuDRf<9f4PodA236J7_CT?HQPuG+}T2&u~QD7zi{c#~^(2 z7?6@#O;%Ac>5tPV>w6&HI=+abn^FJJOV#w+Or=~Jcz&3)Q1J=kZ$@Z4OAF9VMNBVG z*vIu9BrkiH&@UdJ@WQ#p=z|JGetOH&z-6i)%=dtu3jz|65J4(}zQ9=p ztgAfWKV*1M+em_2(pctBiB6w*^;rUnc8!Pivcy(;SnPZ6k>^AK&tWmxBkG=gx#egY zDwfhl3=b&vC&t@k|b0)q!gK!05&cAZo{f0dz$Cn}9}l*UxPx1*F?j zYdorx_C3&OFqpV?g4-0kB|$EZ>bnwp(2s9XU;@pWc63!`&X+h;N0$YaF&z?6XPT%j zt1D*;1$U}E_}ooU=81A0%i`e=TasIT3JwfHGb_*0c(l2P{_6?Cpg8r`C$6n^~Go8$7#v~CqUSu{s!)CH)GEUwK@Z z&9DeR>nit?Bt<8z=~S&NEWfxzK7{vgnCZ#kAKAY&1@h zQ1jvIsvl!0^5i>fW`sH8l%F(q2t6agr;byLlRMPywTV>%Sr4jH7(c&w`j@k|MEj~^zbnkj=sZK zpen~1W205|+@SCAqu{VE+ytO8@g^~fR@S7(=e8Rf;%t-MivxB+YUHtn^>&V0O5qO- zO*UrEuEfzhIyW9WKy&Bw0y;7aUTgd` zU_9{v)TP`fhuFi5KB)MkbL14h=6Uo7#iV9ze;Y@cZl4;^E)JR;joobfwkbX@jz9o2PXpp( zCXV?X%_czgyIb5xl#J$XsV!!lW|=B}LDctI8( z8hhh@09xJFM7lueMc9!Y^w6T^>N{T#g6b#02RD6P3cy+>2YC4Brw9sHb|{j&efD1Q z;`*$rW7d|Hr>Tvz-Xdg%yi^}xAcniRIP_1Kw+`;n(kJUmcFKmq*{RQg2+l6$y=(9& zxh45xbZn(a1WQ|mAcZxVg(xym=O^AdSg=j6Rb#e6#*mM9N93()BJozFJTYoGnu)wB zw>8%;A|`pmx`t-EGrqm=r-{t2lG+}}yrP+cV9Q%^uoniSy4xgJTVe-%#sO#&(o4%k zJ!qHtnmuyq<=8T7YI)f!4J49LNt8rp~Ty%VfEUdY@J z7wBXlB|S~6o-m?>DXm%b1T{LXshd8Livh+QDG4vdGaeh_2+Tyue6+L|K?9gR%Cp5} z5adO9&>H;j7aT+@IntlrVsckK;!*sVo1=Bmk#~22<8#bL>b{iA9OCopAGQWI_mSql zFSsg1P^cPLqqSMECvEv&FHN32%2x3ap}4cS}-xaMC$G3G=cziYj5nO z<%kKgia_{*>FoaBen$==1wEHm4xY+fLUk5E)_9*N8}BvqdM=2gf&fQnbyYan)x2bB zuT(4C)0%1rryq6NNcgOS8?EKxH)D{wG^fA-F{wwlB{WA>FATAR z@22C1BHjp?10&8k8qYg!)937orC!wufn%TNo+X7q_cg0=w_zwC{{f}*$ZMlvyKhH- zst^2DVKJ7Emo|3CTfi) zh>Y8=$NiVW_mX=g$-0W!Y}2%_B5zGmz2p2dO^o3K+7M!cK!6oAF5-ZYpi zAlH2&svq6H-Ja&CZ8AYTA-hq#Zl$VC?T6sHdc`iB-0Uu)DK7g?Y#dREZMC>L0i}oj=)GG zml^!ye;w1ft^*YLav_8>`Dsn&f2zVd3KT?(%cQ6&LJ}v(A{Z=2w-wmD^+H&SR}tt! z1#gKW=ZE?GWcPJs;4q5w^h~4NtR&M}VpPxizT##u&eFfZfmAJ3RM$f1wG0M^=T zFgOh#Uk`t7g7pdkT>qkd>Fb3QL*&FvXlPHBj)}@{b@)}+>fwM^H`5&W69a;1!{|cx zo|SvqRBS@7J6%~HoexCM_q-IM(=xr{CNvVfe6d{|%fCtWHI9!YbHf8i>FvGUq+T!P zTv9lf(RladG2BWBQ%%8jo~P}zG6+ay?TlJ$hwQ2KRE}y8dN!Z6mi@tOyYTIL zGu6*f1u$|2VBYTXaMt2SVLbLxM{T!iK3}f1AFC?i($?9yL)~Y_xN{G#h)t&f>v&)F zQeVcoRITJ_s=N8E3XQ~)Q%ZAW+g|oqp9T_V1a_F5I;5_HD#iMxTq)y3gCpQ=?^@I~ z&brKhG8x+n6E4N;6xioINv+4nx%d9~M}IQ>qGKZf5zhp+;c3tS0D1`jLC$j;87cuP zuIHC?UBm_`xnuXBcRf;VGMe09zcZ<@jODkkbWLibHkc`ygbfwg8C>{Lufs#yPZfAV zO!I3W{?58?fpe}t8=&?4j%DAIFk>~5>pCZ05)KXUpR0PDAaG#hieRm|?Wt=IK&P)GrNw#FphPBVwWGP=DEPhqCAfve1d!;m?|1<-RRtd-W5t`;H&qJf;!0VH3HPO z=J!M!woom!zm##O9EEid+(u&_APr9bclhP#&PfML9ssI+(JqC;aH<88`Pe1-CDy=~ zVh~Cl`(M-}bMWm`%XAIz&{(pB>;a41*HKI0_dydE>|-@OF*P3I%jbYMu`RhZrWf53 z$dJafDC071YwX7|-|C6yJ+6o{3Tpw4tRrlUP*{7RNDiXoOwc4%<@{4Qpy|1-3;TQZ zU{4XDjBrm5$OL{nQT*l4x(m0HN~?>94GK?g9aP+MDUga0OQ4{Tr(j;|Vm|K0rSTDG z!Vk{Ski&XdNw$KEP44#6>s7>&{b7ytbH|g)Vs^+S|G1DN*6nFAj@S+=ub{h&eby7G zcG+~MibQibPCw5f-<)$Km3QNA;+KDT5e(#5r3PXwXg$9+{lJZ+H0o6=LBm?g(v22yEjbcA!8jlmR;MA+k$(%8p!{zD|xD?Yn?`HPAEm!FE8gZ z_*^>S(6{`cJC{2i!6#`yv0FT>%?gTk;ck45hUl2!(Sw-1Er10}6FYqB zpvE6H1WPIm?({9-#X|wvpfKynA(rf>n_EpL)U&3{6LCOlT4f1E;I z|CH_Lx0oyd1R&sm*IwP)m`&L+SP~%cYoU%Xr{~1AU1Q_atbJ;^io=6N_+&SGL$#X2 zQ)(R6b90|cGs%5aPD^mwB06umQ3OM_QnMF28BP@n zeNz2BCKcNHU9*|)1lTw)1?T9fuau)SHpBJ3OO({{G>Z)3Y}Q$D-W+LtBy^arxB)Y& zaEi)~K7?$-l#I||MT};Yuv@1SS(Pw8{xETrnF;y@tpcPd9d+28DbF;ir!v>?gB5Fh z*V|)s*$1D4rUug_R4^T4?F+2~~!{pCNwq3e`h7HE�?TJjmhKfR=q(eE&fqEmh`8cx zuifLvop@f_iCHyMoe2PE-xp)n{%eF(wpK6R_nG&wxuPMSC!lLgy{jA-OPbx>qN;>E z?Xf#Om}PtA*kzp-Y3RkA%l4O=X_sA6=ok1+%E?8J$-(s2G4m;v)$Q7wKO+L8Y#=r< zMX_I3@(a{e2{>bNdY%4AhSGUixshj?MJkrq3EG^jyiV!O6I&)wfb~sZ#aB)wF;g

+gvjH>nBS?7uLlv0Q11~8H5T6*+XYd%T(`r?OI^BiGJ+mf} z^Gpz!`}r)4@oXyNuBcl;S(YFPi|au^IIA3#5UpD4u~yd~QbpGq)bo`=!_ITgAl`CN zU<~PGBNpDp8?(dHqMmfLI}gM3uxbFNC3Zz#G{>P?I$;`jt~aMdECxn#nB*<%zCW}G z0cag5Dz}_METQOOIjnMuE7GgLFE9Mbum0lptf5AE$N!$Et(}lHCqm9VM>}BQitRNM zFV+}`I7VY?e6r9%y~JcT4%XzbUi#m)=-DI+BUP<@RY{&RSgWSRHt1E3xL_M(iXU|8 zrk9mCeA%DHO59LIkW7Vc6o`||q!gP6wtU$kKxVEbvy$m3tM4U-eq0ggesydN$_iYWWS+Zy0)paiN{y}Zc3BgDEt&6z#TeafkRhjBy3%;b`3`a>BQLb znsY3dh~vr{MCtmw{Jn}Lz}o2UEjlLD0b@a#dK*V8Pt#)y{QTE^m?-+Fx@OXmZuy?I zDQR~2+;{QIcli_6n1^dF55L6c$R|=qaVUfD33%GQ>WzUyCUs}oLuQgP>{(!;F2@Li za^0~Soek9)&l*Q_{pO@6?x`tu1!cr-*Y{J_1Q8^g(vf|0=0egs*eYar)v1!>+ldN( z*IHNL@_MPzgYlV@h6zrk0B1Rlfza5V;eN}K?9j#+UICj!adXEKTVXexDobB7C6kbp zKglW~`;=5iT}V`yrPDj#+$}l+EUE8{C|nTD#PJ)xHMapli#I_mXA7XDLR;V2*1{VZ z(x-10zz;*v)0N9ru*AAN*JL3;(HOpAADSE#f}yTX95{4qtC(4mKH^l3(3X%CV0$)L zUd)Tf_@W*C=l{?dun=oddR5vm;FoJUQv(0GL~>J8&$>K4(_zxL;eZbC)4)s63t8GU zCTSS2hqf8r=f`3>oXns#AW}am=EAHJ-fyCVOoFQ=R-nz(^@lRRcn~=`a9mF_PziNgLWlZ~GW5a#Fv6aPs4MQVOoC2!awFI=g*ldi&|f^#j^J;X09{A(zKYr~-fwH)0u@RS*CG0{{RH-~b}YCfRF%y0AIVeDq#Fd{Jn^ zU+cbWSe~0Yh9I_OXj2Xj>cR?HNPy*m<#l{kJ`wZBaJ;OQ#35H?&3}T4%vBRm3rP8; zaM&feW2&M2NhNr3^gpp@275L+g?gA^89}%H{(6CI>4$h3vo8{jTY;~qM!9IZ_2EtY z(3L>Ui4U7`-$CQG!Pjy>Gj$hv5gNoX`iW3tz?AzCb?xP+&YT{X-}%B$yvIX@C8@~2 zIO%OCIwt(MbY%F}z{wV?du~3=7hs&b3VlvjtAH{7r%f5Y1Z=YxoqzxU2C=_f02%K& z&xTJoJ;S2IY8Y$;)L^Xo{x$-W7^IzeE|aWdw)4{Tl6zALFP%>FSC^ZLyIA3Aym>*= zhKN_huQXJlxBJY6B)ui)5Bt>|1Fw*W<>;{-C7UPA!5&_Q4>MrzWwJ+5$9?W@PyfJIekj%`ee445j{fb5X#@GV)^k>4 z*#jXP|EiQ%!eNrcoO|s>H`WoyC2%uF+>-X-`EKTwE^ivFA;yCSXJ=p=B?iPSp^J41 zAdF5rRA`2fhUoZRvvs1(hf0x=%0ePKIrU|N{*_lBIaJ9N&Hw-d0E5gJy9t*nTdkN} zM~dXA(-$V)#wVX`1xL|9iJdOmwQJrRL+@E7Gryg^+ioh~v`-;or+bI+z=lJh(HA~)t-eMAXd*ZH_pLq_v2mDZ>Ss&EGu z8FQd4em(w9<|xw=(056o&O!AF#_R$&wO}r|^9alnb=F(V3{8Gfio3$OE!gFTRCJzR zi!^e%p#Var&7-hVS9CR#*1_{fC7?>J$XprjO4HP*g}H~ZIC)%bI2?t7JZ}slI6Bf# zE1V&DkT=TvJdUCE?eF%kCA%JAk&!4`LRYm7i0_16?TK005#BYuEEk%?(v; z2>e#ts=RK@AWAh_CEoN);%Hu1vHD4Y*TGFoOcq7C(m5=dSC`jIuz>!h?D~RFroTR& z5Twqg3UrPs~8dEGyE>Tf3)Y$e2NquYA*1><9p@d zA{tn#9t$Do_voS|kSmH^%5?e_m2bn!VRX&*@lk}w5{5q0luuT8;kyErt+AR4rx=}Tj-DCxoio-g_hNazykJ|;804II1Zc*0wLnm?k5EGJjFS1?iC0j zdUhYFAK1yc78{=KIioUv12~t7cd6xm>>E}GUXwI)0sS8H{@1Cl8YTxX7H(WFE8S?~ zLmq&H|0Qdz1apxHsIIDhso55O54b}aTtqAZam^vwp9={(8j0&5RoyZl^Htsha*}A) za=47-4q;8$YSTBrrm2SQ0#@q9X<2l+n~8=81dyVn;vbtE_u}8`X2+Kf^_Fz34xIwh zvN8vdQyM}H$gbqETN7Q+IK>UYWj6s6exDdsm!t@zd^!3ln{U7Eo$b9u_j<0 zaIn=9#FlCPwFS==d52oyJ#4Plce{|GjX}R(0qa)Tlt5g|bQ8KBU-b`q6EfXgLMC4l zVnblkvcN6ZbQ@&$9OV>Ss(=;f(S8bilIBa>JKeOYB6UGErK#@GOZ$^{6tJ@cpNM!J zlq!Oo8~}%}o0PsFbPvtMl(RFrHA6*CMxHLtt`U=4lmy1kZVG_;30~qCB-(Fhm<+Os zocn&qC-@rgwTHR{vo**bTGXvr#`i))NDWN|lJrB+VlLdOn&&~x>yQ8d0|A~$MkFqc zc64qvVmetuc+YlGhZrOH^l1CSTu1!j<6!dOZ^eDjExDHeC}4Zu(z3_RTr&=mv&|uN z!xy#T@e8z3pj|vP+mF|I!YRxGVMna8Kg=JSTFkb+je5PyoUF#5pu2go{S0sL#4<1M zmR9&k!1b(wU!6%W51fsA9YfMy2(V##*OJH>ej|US^P;$$xO}e2Ttdazi$zZFdSDK7 znZ!gK>8^nsebl&4`eUZNBPO*cX);e{jA{@;m|At9=`tFUt%}b!QiGG!Qd?&6U}L}m ze!xleG)ApbXch}c@Sny>>zZpozaU-JhiIf~9|&8IXy zvExM@B8m60`|kU}JZY6a4?k5bTFD1JJKXdM}+-dG8CF)sVWhW+;HzTj7 zpMVX;b1rLIgp_CBXIplR0_};a0>b$gE#t4jeOJS-;rmOpGD|B=@+1k2_&g78o6aqr~yC-60|#Q*NS+l;-BdsdZsLn1B8S zZrpq)h}Mvko~2rLpQ6&AQvqs#&7{8@?s5q>Rl9Sv+U$eF>-OB%dAZ!~V8-lpm8#CJ zd(#D5TP>4%J?uqND_$67^n1hxgWg}c#i;+0cv|7h$CNV)z#n?ajf>e$wA&yCqmj(C zku;VrTno6CvGdNGLX8Y0G2z(ELNx~98wD{6EDw04>byY~X;ZluW}Tf>N{LzHCpIJw z_dUDr1#)Ut-NSoFOZ`GEO~9nNw*eOEXd=j})*`bZqGH?G{h%vI52yZo`*lMrmUE4} zVL}0m@w_1u-eD!SVSP4BKO2*yKz*(Z`myx*(aF~Y4wy3oEbRt(Uas8gxaC-4D(}gL z;MVXFY;w8@6!Sz|xl7xd@rXVq`w;_SOt^||u+ZkFM|by7zpyZOY{wT>FrWpw*Z}K* zYn_yX07niw)W;BUWKE7%L7h4V^dSUOt?IxK8~=}xGc_}jJ#uGkO;lUgPc=Ak8{peY z)Q+c~oqmu6MH`LK3neB#LeQWn4qGaz|Bzl52b6TU2Sh#`p+7aeM*%Pz#ey+1);X?F zMlX2o%@Z|%18qM_l4wV?X=D@BRbX;Qwlm9OK3v_xCaD$GizH;?oF`?kmPWQh0538N zxzo4oG}2U4r^YuE^|{Z=P}iz9q*|$CjXy^Jw|(>lhADaEZTr!?lAjyOY|V>E{e1g_ z37`CipT9Z6rqe@Ey7!#g;shd4fPDrfyqpEMkRUA@7vhl~_i)s|`g&S$2Xh#}Ke8y2 z7JXhPqXNkqjQ&6yblrY;gQ^PCL>t)EJRC*o^kPDTP%&({IP2nXuy63mFLeSk&b~w- zv%`b_igMD0(sZT7K2M6^2SCW?CM0rD ztBQw&snrlRK*;h0Y1i-XdBxse$PuiVOO!q4&2(Y=;&@Ugp(nF<`x@DK#y8esp6m^abZdT00RI5s{;UDK%u|m8f-~X zx_(54R*6fAHH>j@;Xui?g}!KNXBl$?p-(^{=c;>EuyGTtnV@c=-cOF~-_wUg^~7+x zN~P{So$6J`Pyi<$W+i`)ZP~!p1L+F`TPi-~~{U`V;@IhP>-S)^~$hM(P)&7?l^&6O)A4$D#u1 zvboaqmuydxw8PqP-*e|337WT@y-UEHh`CFX>$GG*DAjMW%3o;v{-J+$(Q9rswN5eJ zxD5Rq!2noV#DF04S=7TuLR_uUh&14t_!Knv6knYO_WUT_h+4ZZC@@N z{RgPd#d1L`G2;(VyY06bDu(z~Zrlu*%1gtM!`|i$R3gff!qlZ5zr7Utb8EwHFB*in zy2H{nfl#%G+Z_>?-Ao4rVBhB7Y_U?y)1L#$88FyoM1~ZwfLb@=7|LbG1XMFvH`AQ? za;)d~mxU*O=Cms{@MvjrIr06sNj&V`mBM4ijab%NHZQ2R3LOo8Ab~CPQcB5hzQE_F z61eM3SwEO$Vp6!*|BV_wX^VEQJ7th7aAwKKDvKH3Pkhn>8~!F*XUIo zuUa)me+U?HfsbA<78?c9(joD=dv~f3@OfVizRL)glQ{a?h2$=KCVIuXo!1aWh8@6!A;tdAipK)_lEs9|y^b({pd;y0b&q|Ko$Tb8to=S_B@|+iF;o z_4_3`2~H7Ntmu%eJy$nq(>!R3Atu(+MvX>8P^=-+ml~WA5D5a_VsVafe5BIq3TjSn z#^ee`S(_gBA06Q!msIowj*=uc-f!+yBGq<_nPeVELDL7F<=4!GCw5v4&4&|UqcgNF zDqv6uFY-0?56cHy48iL`>jydRc)MB-j_D&>e~qW<^5Yn+Xs{>}`aR_-2r z4RS!JaiQucYA&h4eVy)`yE<}eyxxPJJTUm6Fj`DlXZ`F58deqv1y!^~wR%@MFcAT6 zrpVZ^`Vi*UE*0Y%IQD0o677uhLve*sZB1T~$ysLLI`MfXXVn*DwiC`!006$gU@FU0 z9^Z)K6#MyBctM{TPUOMD-yI=A0Lt_7Ji9qZIpkB(8I9WF=wqY@{AVA<9BD_pv)bs zz=z}!o4miex^ijgJH4gm8l;#OH!{yX^+;-}qCTi2V$0MP`e(B#wM_eGvnvV(rXtZ@ zP%=5GHF7Ulkqo=^VUx#6mAmU1-%&KJO$m1=ly1kz+naMb{Q>R?7B1i-rJe4Cf!CX8 zNoVY=w4YGE&fUGpmBs~AXGK_n3)M2GjVxvw(Ye!NE8yj{koS>@KZMAaaE?2yBFI7c zF@2D1vv1UTV_~evi6T@r6Ex#`enWmDDOZ$hm3ux7L+TmxOCDTe>VOC9W+hEcg(u63 zzD5k@0@sF?a94tnHP(YNt(CT;-XG&nda^PN7kLRH2rM72=Bv@ zE#a>T$fZegV2UENd7vf22F%NYjte>~WNNrM@OvuG9j2>P$rt$$_N<|ai=dC}2r;Te zv9e3Xhk!gLU2g$C5TORjEIEmLmfY;tkZ+YbOZYZJ&Uy)fa24zNJEJ>E9DG+zDjt6$o>xiw*V&bjU5xM>}hvzebtq`j1fgN#;=5Qx($ z)=Z()b2-W4^#gEQ+8X#;K#rGU-qA}~(bZvWr%S*V5#f@N&&~b`yEc(P>~xlq-V^L5 zX4QZIY~+^(aFW)ZsKhpy47UPYLum^2${^y+i@%YPw6{zLyEr% zZ$<{?FR_@_O}?tO=I9oJOLcbP#W7BIu|d=-E82w+bj`Y461d zf|G15LV1$lV(*mswO%gboKvYiJLs8FZb6Ag8fg`K_kh&X{)qDGVfwsbeJk_>)_Vn~ zoBEfTE7JV1QilUg^tHJ7LhvO{!oPc8+-^#p4D)5z9n&j7>HdP9&iCNY*E!P}OhNc= zfqo!b^!utpI;HQI=o#_nz`M>|S6*+mL7&4h8rvF{5IHznB+KZ3428|7; z5Jyp*Eo_Z|+A?&$DEBEN`Zzw{5!$S38DBfh|GcSwvHC(+@mM!weKJN z^FMMUWa-OdD9SfhauPKF0x**#kR@SU+_jn{QD}q?F7`9IaScj|@AVU5_guLH!YE)= zg-+2VYK`Nj{!jK!%FtBiOe57f9>ht+E!%Iyx=*sV~jxy*n@E1bu525VwZOhDn4A7sBN8FL1?_eoC%mr< z#+n<(ls~!x8LmerEUcU|a}{Q1r}wRCvN^?*s2R@`$^5u_v`^{d$o_1H|MQ)m#o=k3 zdw2hB+x@njfj%Rq%}2rnZ($Y2g7q$au1Ee0Dft-Fr8zV7dx)pMKT}twx5uA`9f+fn z?ZN7W&wR$RZkRlb0m<`4eX|G8`E_|)GdqXg9zB_Pw{84jcDf=?(7Y9|*!k|c`&*q` ze7+opo-ne&Y&cTy`+i1;>z>zr5Yun4;n~*(yl*%WV{CuMH~adY z(Dw^pTo6VPzxM#d55b=wCq6Bf7TGe6AEG1`cmfg_DZ*bC?X<`iBhkOxJ@4K401yBG0|9q1JB5K_mE|fY zbre9mih%&RpZWUsACn$_*c7pcA+f)DAA2@kG(b#@TO!yEN0o|6hI8ZW5xxcxzZ?fJ zLX*cW^p}SywV_cZcrZV};(dA?*SqQi{~ew1&bacH&La*Vos7Kis{3sqJy8<@b78@S zkcnvCdgCJWwSF-4-AY0Kcgl<0c6-?-AdfXpmY*LEm|%?jtjOX9;j|DaV0 zRFy4G<1n>g1}%}&iN}QYc4hYMt`yw6;1On9$c2-67hU zqUc!6Rg;Qv&F^*E|D;KvT+n34<|_K|P7@x$4X~=#qp>n}izMdU4s0#sUoDp7b=U$u z@pW#?X4GjVOZ5ag_d8UyDy%nPq3 zdtWRe!fz(;navV_6S0s00lE=r5{ouk;*}Ww=Jrx_RvH`a@gmGTBJ#)PL{CH_@`*Kz zJCQzO*0xD_T+c6ZGf?3vXJ{Xps2vrCK_zi6(fSnDbg6`UKq+qI*2!4VfS|+*;QCG! z5ReJysvc~K_(PrTO+E)P>(h4#R>!ZFFX}#Q{*mr!uC9U5j{a9utkY^lP`+-_!%SuM z&>2RFxv>tME%)d^AhL!>!bkKn6ct~gtztT>A03)$&{+?;!jIa4Oeu!m_ic()^L1c~ zvGAKP<7b~Fulhy*Gj;72+d-A?61&D!LhSjy9oWeATJ$il2_%J?1T~9VeNT~*#~g_h zQgs8IU$<-m99(TRvf*ZCOyK)O)Y`(~jK@yDRX?D;Ff8&(X|yz~EuWnz^kt_g;1?x` z2BI9MG-KM74776>v#puu^u4)F9k%8vbnh1zsR-yw5DSRc5S&b^_YUXQh8!z9$^B4P z@X4HYJMWF5BI@c>PsI!qQJl7STPMeSier%P#XTL6wf*%a-tKrZk0<9z%LMX&6mWWY z+_!i~B042U zrj+6U7N`ILAiRTI-+G3c+b0F7McZGHfOt{uI`WI(m(uZf;9Qm?2A&u9_n!2ZX>F5c z^b`TDy|izE(^&q(emG<)G<+J-c2hPS5iwf zffQe7xKyL)9Xl1ETXcpeK&fYS&z1$6_sBD`%pH0>X>2Utgj`9371Kxf+8unAYP77f z=DF=oH+*U)6?9<**g74#;m-js@yup&{WN3t45ME69ocsREmbEl)>*jmj01NsoU7Vo z5%(i_Z=O!sxn{xHhfKi8c;^zDOJ@7C%*b}6Acyg(@P6;%UZ7r?ufr)OOjz8sXuAe9 zxGBr;`%rt3CWNh&!-xK&_s)XZW>^CqMH}Fr29n6 zx%7>`os~9XOp-Wrb9$Y4+@{tk{dot`WRptF>aXQ1Cbp-Y$PIh&6@IYAdPCU7l9)AF z+>@fpy2e9nGL^slD7YvEr0^nlerPvm;ldw~UeSp-oe7qZxU5ih!hbBSEt?;F>>d$5 z;6j5%Cr%6awiVZ4zb`Fe{#cyPlZKb?dO`xl51rSKGk1Zv){ z^5%=O8@C>Vm6WX$j%GLKy`Lk#EHKcS7#}Fof~5{ni|z6nMk!K1Nx{v1J5cO#pa1{{ z^R6>mg2dx48`DwdSr3J-m(yaWpp5umf~!2QHy=WHF{RJGko>|dSRR;(ZL5!%KxG)Q zL!6r9=d`3MoZ!ztqj0(?X3m?5EbsEdXBqz}B1KyD<`Bxdm!ga;nuG+F^gCohhIg;g zVGF->b7)%|OT9ql{@r?f!U!?#940_fF6xfJq|L>FacklDHxQhzSNS&m7J2BkDf0X; zcV1Ue{mcx9;h402(;{Em-W3K}Q+kuVf`LBsjMcl`u_JiACty{IfuF=1i#e`CYX*2h zk)IV}e$XvlfU$m%%>so@#Tflf9r3rR6VMM@=>k=9rF7rNaTJY2*hV2$49|Pnb!|;QzczX$sNQz-th{boVgm}~wDUA>{C>q%aRWjGdc;}taqBTiJl zn7GD1*ptcVDr_Z(=4Kr|k-Xw9R&KWj)>%|N=!PYjC6X86I ze&WdGG+!D300dEmogs8pr>JH`tf^@mE(9>VgRs&n<}m%oJLX4&Oye&R4=8vkCoNJP zir{d|+$+X`kmCt^->ndBlh|%^<@O%5yS-m!PzTh8thP=|?NXdl=MDds3S2VY#Ti*F zl)Vi^*MW5|n4!5g^K>Qwgp>CZl!e49qyz@*1p-=p4mw534H>s-;KL z)**iie~sCVWq4i&?5|q&agU|b!PeoNT${%4W7>tWZoU>mXF8Y>V`V!Fhth4ep{bzDr@Hv4Wmqu z68PtGnnUPf!{@Lrg3LQ&>rebvL*@o!tUshX4QZPkMB45U9s<(}biyu5y+8l}8wrmx zPDy2L^t#G^n$GsSVhj;dzQ=B6P;4(=X-PaKwlf`n0?O<4zYKEV<(oiCtEnw=4^_!$sKm65Jtw`jQ!tmNPz>~v*rTr_e z?l-EkJrg2%%BGlC@#%d|<#55*^jJh?PA9(4{HGiAH9_j@p1 z75GVmq&wKTDtw6(Z$G1WYb*_%qRNnnJ3qOvk**^PR4hHc(91amyvF1>Wr<+8(42b0 z<$!281YG){_<{sw=W>qgH4vEc9skWZWH%<`_RX^!gx7?rlH&7s`i|eSdxckP$(VfG zWRf3QtYlTdQ^sBRzHK! z$==AywQ@?;!ULrA5)dNGcN~BWd>aC5iy#`Zq)%WEKf^M9a|mYH1fAEDl8B|LFOR>u zoqT!;jP0Dxk?}h^jOO$iK7EYXSiAR_olW+KgR`SA!edWf-a7AOHO|Rj&(fz>Sh$T} ze?CL<-2jF7xPuR~_i0@UmW@2rk@x4Sj3t1uso6^Pf^)z)0_zJ`HVSO6aF+nj;;qTO;PzGLcRnoafk1ham^vw!jxlBDT%dTM2}3CfZH- z@X%!|{5LJwv(+4BrE;V;v+*cWXYX$aVF6|(MRex8zP)u%YYN?A1WBXZY-0tY8ny92 zV|d6xfkgk%b8Fgy#`H+1HFnc5!sb$mXBaXReZJ3eYb;>eYS2ygab^iWl+?txXSX^a z?!z3O+5njW=S4@bXNq9oPBQjBW1C%8=4)Pc52xAu21KNw`jc;{Agkcb4yt09E%7i; zvm2)^A@t;bi9LYU6UJW-lpXFg{C_~7SXwbnrL-k|FuNBfvDIAD{XEr#gUn(xGLoR6EfXA>So`5#UjCnDl z9J}TW05P&PH7AjV52*f0cr~4{&qtZ>dr!+=DKpzoc^26CZo-c07+Lnpj!rbEKI&OP zp{U2+cr+Voy)>IT?s*mkg6Z0Lf_W#&{<%1~?~m8<85l8JO^LcQdd`P)E^+FL$zMCg^2HV(&c-aT;D?dYLzq_QMe+N;Hm+AnaF=t&z6KE+ z>$1FTo?HrRD9&gu>o77392thVXR&_8;BIBXmw*0`toSPkc6XD<_nI{N5B804y8>C2 z{w^dUD17^f_J>8$u9E#`+_@!VbBe@I}CAgu5ykzbDzccTBpR@a10Q@vs`14`^%%t$BZ}FyRlWkB9nXM zdUKj_ka%}ildiJ}oNn%Cz+b*eg@ zO&Uzz>+q8?=C_aZdNmOlJE^tq91Y|=@X3B~U9}c2209&V@i?1$n2y#D&ZDkzZjs_J zI3Z0gfs4##r^_mxafUTA(dJJS2neAn7rxM%gNnUrkbe!WHho^c424(vE7r{T14cRf zk=dkjFrPe0OW(KejhDTcGl0+1WB>wq1aZ8O000K_&9s#=V-ex%fW%C#TTn?=GCtsw z$6H!W+?180f+4e6<6>?zx4OV|E4_hVl}sd7`Hm6&RS7qV@ZuWL3h5M8MF(nIcc^?> z!SM#dbmQ=LzKG<{TDs5DT5DSXe+l*@NA{jD6xaKWwzp6WU5P0O;JV_$&o$rO*YI#| zBE&y-&L=w|2W|aAm^{-)CU>|vUDHoc&`-yyfCMjw{Yti6Vq1 zG+x&V$9m7xc4`_PES>uPfOK2yM^YFv8|OJ^ooxssOhrqzK5;wo?pv#;+QR|#(#eE5 zOOE~Z;?g-!A_U%cf;+Id_kM}38$a^evaV$&P;<}XLZkk8+{8L2#B&KVI@IlFi!591 zA5`V^&7P&qo;_9uC~FIINyvawc4yka6c45t(85IyaLj_iG5X+^X0v&9%SYL>sG0YI zTV9nV0PCU%HM3;eo4@JW5@U}6{#30VK+}i8<#0Yy?B+^IHdr2jUI@uI$#`f=6~Q7cbs% zGW>@ShN(rQW90Hh>N%=pcjr_Xc+Q>@x_f_YNF2)eDSwZ6;M}icd+$*eXl$Pd3 zbJJ<2p{%vyWOqpyS45Xp()QPfgqcgTlNK5M%BNDq3+{W_jfQpT9-fF(xJfjI#qLzr zg%jbrBZAxl!AZE3$lg8fM-_N(8j{dE@({GglISrp+aMUt^}218&L1m4sGHR&z`~!t zV5BG=Zl0V05XfY4#4YAovh7jb6W`k#RZ4EXpvme%H~j0@v#^dp_h;6o6O*p>7uE!q zoTg$=@(q>IUe@AcnYma4$Nm@t)-N>_Jj3(kWMIUO-3k7ckrZC-pb>Si2$+u0h>vg( zM*x$}i&9Wvar{Xfva21qomYG#2C{wB+)q-X)!#}%9U&q9Yr#l#@HPtEWhhk1JSHAv zNB$>>bFp5)e7Sl6y0`FC>rs4)Ay13EXe%}BpJnw4!>DMbC8e0p zbt6gE8ZS1Z=&H0Yl`sqZCkV?bC8+B2n>&pS;(1D$P%T=ref3TK^UrOE?fFH|`!YG(>158*FI+Uo7@!NrkUfp}R zcM>bHYHwr?pfdVgp^G)sRx1O%>IAaW#+o^#ZlJT=Gc-e5Mo@M=;2Q#QmLIx80Hgw%u#3|m?mK1vCp2n^yW zUo8O@_} z%=AJAJp4}ppq%E|mz_cP6%$5p0^3guYLrsZN}rPIp(Of{u>K`YE`mME;_knJC~z}7 zwvS141W1(BC(9^+ZNcgIYp4*66w2@`;pwWX^~Um4NYm1xNq4>d43IjG{m&-S7Cq9O z(0?zK2Sh$!-t38DVT)s0Sh2bd#d_JuE!f?Z#3clH(_;)KnsG7ZsE*~0_q!8Sr0$~6?Hx$1Qm4&A2!h^%;%b)Vl0`g;Ktt# zgpWw>>98|y`A>weW~Ep`l8NC|o!OUwPl|U&&^MW7qS_`7uhP~pE5UY8HTHO$qC(cd{QK#K^oJnZk+yH5b;#S&H(ce z61XuoOQQ59M~#e%z5vNHyf6Iqv*WaG@LuBeg?+eoUT)mQh?%>7S}`?xSd^$OIP zL{O2UIU5%tw!JWdmM_=~4Eb6cfw>?q*p>ploTr0b`IkMD*Ysl)Ws<;{5_!c=x^)K; z*VJC$hdY=EWv-ME()*_$qDdOT2WUKJ=J9A`0D#_nGRyCX8_`vk@0ZegOg)Cn zhhK>c&V{6zwAf@}q2_^^na0G`K=@%ycZq|b6$*zIHny&-JcgD3mz7k}dfVCgl;W~@ zrehfFbwA&bay$8Yk8dyUYZW@A@4$EOIEo-QzNws#K1;43F!aUPj==UN@@=!$khvn3 zDMhyIc}&kIce4O)SsjLGSEkX-KjO3 zNHX)<;`N+}^9&T(4sKi(=|Qv$czTiFT`>gmkH~f?AEOb8`9?@d>-K(^W1qE-~bh8I^22a002)7jkkkEXpZ|h){|&_@=;@d z6uK|)^|LI@N_^n}07WZ7nh1@Fe;F&ZHwDpyLhR@Vi+`U$+dpwDf3yMff_5Ql9Opuw zxd5N`ayrA@#-LBik$&_?Sqs)n0!JyqhQquB%dhCw{`U~oXjY7 zBK!w>d}Pfi-2_=#0K(rQU0^R`e?s757bH67RQ@99lwky096GBmRBaS=#1#sOT{$j$5Z_$2w_`c}OB}?hQF_%ance|9DC1QMY}>-jBFjR#1DP=bI~s8x2gMRx z|5!SwXzs`9kql8&|LeRTo}(z8vsrk2nno`9Hjkw~L=eQv+ak1OkKsm5&#He-=P9EcQn%K1pOUSu1r4Rl$E< z+oMjM^T((VDJ4~H@E2Ip{^SXDv54t6(q$7<;9WoP`lSP+iAn>~ZVgsP#4Z7?g7C9} z3Pi|?;iDC|wrf_GnYzoTRM%J~4{3w6+k7GUm{RjR9mZT+}MJ$hp`_!Po#@AKJ~Y8a^QquTMRWs$xa=hc}k*=J?C z+RuRslDAGD(vOO{{&4!-dh`$hVG67QfSTax-4hd)Tdb*$=2kl}(!3Z0yuVz|Rc zTO-1&Q#g2xmR*FQiMfv6kIWpdn zLnz>Q!XIMw94M93Z~nYu${`j1+e1HLj5ARw{}TguI=?Z|f_|2K(HN}7&PI}J0cxz4VEmx;ff%pw#? zg4lx|+AJEE2L^S!vpiQngMSwVW3axFnZVnglZR_yZFOWep$<#c!xr`seI6o~`jb^z zgZ4dPxlIqRC>sFWCZ(D>mTUCt{nwkX;OvYbtfGjNGb_SO^@}iV8s(6`=&cA?-vF6y z5&+Lf%jU5MjQS*YDtouB>F5YVr2ucZ63O{1OogH5qQooe0Pe5l;ou zznQXN8IpIFL_%N;SKsioH-!1!v|2mCNc>IH#2FD3v}_a017jRVt9#|~(VkZ^D(J>6 zzi~w6+qyGw6SySbR$5<)=mj3e-ZvdHuCnTg(NvbsFH;!{O^0 z{WXSf=qi(p=*Kj1r23u%bl-CKIs|~gi_J0uIB)!N#v-&l8MwzPmH@n{;UtP{B0l?8 zQUhYdkBj4$8{CaEE5h7~!Gl~NCzZn%Z&9lQ^NQrkw6B}R%KLO9FyG6AC>L?{eyAaO z)-sU)rtYKflYltl5cSAPIwomVxZG7NyKB9=vGk(npU>fnL#SRbMZd>&6s+&I=RC`1 zdlcu;E-VP8(Bu9~Q4DW2FkrAyyZjcZo~T1p$D)YM+9{Q{llrBLF9Tb_52PtDQwIcN zI8c9;Inpfh9gvC?N0{RUD)l|RjfkO?tt-VU7H4ap1yyROza!ZO39iitHZ3*vQDDV2@Srh8*th7Z18+n`Rpw6MFtqV;EAb^`jog*JD_PV;gQ_72G z)SJ6Oz2*jyK{|Mc7(mkhOBm8KDpcHyB8587-?uCy@E78VsDJ;m014(}j3(Iwa+vH*3!z>r`U8>_)9R zdrGS+^77hi>Y#q>Nj#0-3c^tqo}|vTm#;|5;BQN z1=4iDQHcyI_|z`(4BwJbDw?Gf(0?j6dZC#KYM|vsY3lf>uaX#{PJWvoU6qPU-;DTR zd$}UFQV2oCv(8K3jy&IS8P)P<5T6uKG^m1-FiDl<57DMHDXM=~x5dZ+0A!p5W!`n2 z9!ydy?-{9}Bd~SRgg93*tK7;czV9&e8iQvYN$;}PJ~;Ibe0uftY(jYl5}!`3ZN$?# zuiAdZ*KRZoyn*BDXN`&deAyaSP8wX#taq(h`_+FVWXFGwMVoY6MJYi4A)18I#*+K~ zH~(#b0092~07zHI*&In!a(yUi)u*n00`q(Wo0KM=gfuP2|MUICCPRp)*Aft}6Azza z3n}mqCA`+TCr8sbt5bV?38WcF`OnkVQ8Qc_>$+t^VV_sKQcBy4U5)$W5G;F$LA)Np z;TWD80jg(Nu!9HJU|}7~*$Ttnml78J(Xs|vwZ&kD3O^L?TeBmk z08ut64pYf!hb0I0jWu(WcnT}o{-ggJ@IjD3Bw()fn)2KTXn(=S_92Xf0009303&L( z!I(F@-fVS`jd=aoWL+MdcB7395bDm~@zd!jRzkR`F~3C zI56Ibh%rC_0E_=-oY~s9=00tNo&nzRH-v+ossVYp09gVhs>ikYKXYB!)uy(0$#L~3 z7Tp}-U<~3~)AsoR1k6kEE51)9bp$mcCpW+0AL_TL>BT*#gB-^yJ?ERKP*_R^ zj65&F-F5^y9rHX5eQ2S>SmRx|yqzK{+GLUl;PF2fbj#!a7`p*8U-fzmXSPii?vL;a zH1OfQo;z7qX*>-@`yRb^`)pw741^ueu}e7K;ORm_fyg@8>j!eo#4 zUH|}>eSLf~9zW-=^YR*8*&C&Qa>=B}MHaN|cAM5d;a z%+q1c^jV@kH1zuo_Gn!Yp>~-E4I@O65T*^SsTfDz$G5g9LcI*%XLn@J+N=!y9kzvAwN273xBO+?hR1n0uM>PBcQBB+?*hTyzic0OCb&U_VgKtB1NyLegQD z*s1Y8a%!4ddrX2b@Vh_(fS-n^SX9yq$?Gp87r15v-c+9d3Jb=NjMTMByY)V<;tG|? zh_J1Uw&mW?=BN(&*w1KLA9Zs)GD`rVQIJk-jeTG-Pr_k^e=lsLN$#$2>Tv*ojvN2O?b%2W>SLklRSjAASB zu#A!0kZOF0^FBKFQ@$pa)frbfuYQP{kgv%xdN{um!aq_zW}sIIW#DV;H}4v z;a#fFRNw6#=6!q{y7i>61zlTR;RJev#gum3G8FJK*V7-suBjwQkK1g#WnoJx3#p1G zFkVnrJGhKY1&oK9%0?wZC}q3WYz_Xk8b{|@>)izykCycaQXT?>n)uy;r%p z90gKCpC|`DQ3I5K!#i2m%9zkLQsb;UylD7Xg3o$xo5}Wf?%4+bo=4R_rGe;k4{lf=XxwJ#Iuur*eNbO zC0SPnQ51JEmy^xp>T=rJBnOU=7fkMdm}tBp?GPB@lp6E7;q= zViB7#A3_OflL*V}H0K$Tzl2AE!(f-A!I5kT4@PfY&6X3+76$k54aL0yrY)yQTmgjs z^0^!7L{OE1)7V6~+Vd>5h1QRi@?zp86KIE&?9ZGN-ke^KfXqNql>W^ose4;Lgr-3r zZEn4X1ck)OODJ62t;2UQ1zb9S?7zF=_vq?NPpjrS@fwUSm657%;Au?dfmPOo4Ue44 zh9)FYo*9@d$c~rF$DUj8%B@P@I&Z&Ik4InxF7;SflQ_dnc?-}Fx==K@jpH{5fe^Ir zM<;sGv^rH89S07fwv$3}C2xJLh;WRX#33aNsNVoIMCwf0)ITc0_P(0&J7Y}GQiBS= zN+PGXqj*~6V)F!H<~xojaNVHvH9t(;+_aslbgs+O0Ty8(dY>;Xtq(yR8;7MRNT;7rmuT;m2_Fn-lw4jE!aBeA8BtEn&29wcoIlGx zzf%osBhvWw4zyyU(LIgjhC91~BP>B6RO;vrdm0^9zHj@$PFO_=L*+9#X*7xcLP?`C zmP@G26s~>XT!anyA6W%JOoP{~vnnB&;}?cEs6hcLEb#15p;`VrjFU_;QFc@ASf)B`oV;#>gfY^bTJGpeKgEQ_U z-hg4uwuLE6TEBkNYHY?XcH zy3P4%^9FS6-T1lNB>vtvYUz2#$-^&lIgt?36})xhPDW@`oKy}Jq zqzkXDVwpmW7~yP}>SLT&3EO^FdRly9(oq9m(XB@-ea)9}?n})#J@^3>TXa}xD!McA zkd&+lEB5llLe-M-G7Rg(&@6jTA6#z|QDO)79B5duXhI1~)NDn&N8)Ya6T&#PKdQea z2ov=?ligZ$n)pP1)>aXFyrq?(6JZfU>R>Q%MJ^+IY6F1PL6TKhA6XL@-M7BmEUT8k zsusRNZZ&lEjyR{{E@4wrWPWyB8}+~Z01{BKX%$n{WAVGF3i>feOB#hh8UAzI;k|@% z<%n2wIU*_(jat~K{_DJ&h3&tB)1`)6@~2A$2M(+a1e`@Sy>2Ga<6MwEp)EsF_$1qk z(-slBEp!SC;^JYLyO>!P+yuEK!o|RxG{Y3GSmea9-11IGXEzD!BGSUoG5k6z(*cAq z+isQs-dd^pg*{6yq8&WxI7HHn4g12q&hSb=$26c?;tZ!`1ST}jWFcqxi8uo^soPEJJlO&B|Nk!?(_CW;|{C7bPjU_a$F z!omEd_X=%P4;#vS(D`Spd0=S`^CV@xoB$Z~@00h&3$sq3t`ndR!SFClL}Xls5I50| zK_5UE7CJ!`8;25yRpBiyjMicsu2eO~i2$AXLaZak1KNIZ9X<*of(aHl2z~97-pyTg z0+-a*3JX~@o|2_&ow^^e5S|}ULP`0d^6POcVj=`9_X#5OwJGfl-Y!g3 z&N_cce$fPF7+4x!e{M=|OW>u3Q#nH;1@XCk^g&an>OBfKtMa0Al2&KHkof%kua!$U z$(XYH2UkAjx#NmSd?&|-t}@-L=mWgWa?@(r2>P+O2R|<}KA%@Cs05hKka*%z`cdv_ z8A>jGV&Cxcw2miWa_j;ma&Nb`$NCTYO?fExNy<3axGUljp#6r;mOhy0{H4RXq+LCS(1*UEJVc<=lX-&%{N5i%{)0}TB{9Hym1 zGT_Y>07F@6#9@n?JMT-OxL170vpRk84~EI|Y&35%TBpBS(uo48ukY%|YSotj2wLk@duS6%Cxsv%J8a1}=n;bVXr0-D%Pe#`5^Hi5s7>Qonq zu`1oKBAp)@n;HSxsMHdRHjRoMu73)=*P=u6B6U#8Vfh%V_=0KR%#;>)+UK3M=qB4{_*biNTlFc;|06kp0b?nokP+r+CWkw$) zt1+{Dh=3hUyqM54HkVMZ7}7?nI=x_#9sEawQr=DDS>dUpu|)={TK9hmOvhwy zl-Nkex=?Mj2@krg$dc~ZN(oEA3f@J-sh$A9gMK!NJ*j)V9!+^5pZ&iw2q7sbQ2e`u&v;7Mb(^nP4lEk2_&fNo)Qt?_`Q`EW2 zHsnOTFlyxQ`8bJE^?b`Y`}suypW+h|yjrriE(R<#$@puQ$EYse!1`b`8-+omMOse_-YirbPVM!=5S)qOaT+KZ~GD5 z^eOlSn{lzn?tsXY$43mkM&*6M^-1L-iSpU_8*DKes1ma|`@Q%4bR%g~r1St0#sxD8 zRg5DldnhKrvk(ExsPwn0G!Y+19wRpYN2q4hPgNg3ki^Q&vcjnNXE+KU3#aH@yKO|} zF=dq_%OtCOJRJS!=h1zbEhqxCpo6XnaL$~?6(|2g=8dCUlvr1Ki}5j^W%!_&2S{Rx zI2qd{NxA?B4qe1r+=-~MliYQl#Qy=eMDhv01KJOS_j=$H2R~sgYhkCI0*ss@^Rlz# ztL!9PDK+|n*ljn}nO>Akfcp)|?gwo1%qE-8`JsF|)7hbpE7Ynnk4ryt2zi3=N_cbk z=%GJ1PUScUK&3T)-$6~yhPJX8N5mFlOoP`;g5B=0pyu3#)~OeTKLG-5LJ z8&g%YAca4#IpmVObr6r3L0yv_`zSAPGO=e(#gDegNKb=ibaTOm?oew=TZo!Cj{B}I z=L6xw5geC@M4uIB@G#CHd;-l32^s;z0KKPk4j2^SGQ;V;!*D#s*o(KOzyz{1viuQs z<|Q;6JUQ5E&v-iq#2Zcfo99pWZIunSZIrL`^0D1zfCq!K0i0VVfaNJh&194)+_s~+06E%){vvU#iiGTJ{g4y z$%;iw(RTNfld!DTW;1UCp8RK1cl*Kr(T3n!sTi)DmGhBrRj~K|F;G*>5GY@C&Y$A2 z;MM0G0a1aCSJtj+-w#0vEwr8yar=6)l~x`>9EqkXfKJiJ_yF;VZ8lG$uGjPxbjiW( z1`FS7oV7Wd2_c9llNouxB@lyNi03!PG(<}9QqDUoqqFsIuKFkBmif|Ge;C1>f@@+` z`)W*R%KP3>xUdmjX9u%B)fo#U!Q4gG!8`+_j>rjlgq7j(NyH@4o|aO*}ZJg>4GgD!{(CN2ig%3 zE_X7)0YIe1CJ_ubpuL%afx6&PWp4*;Mo%{r1-rtXHCPdt*1$Sn%T)xP)!&s{2k|64 zMh@2BV9t$ZrBkT6z^sZAa%1Hg68c{Vsilt+TU>uVhtH;cNm-w4_z3K%32R1@I9boZ zZcF@IPC%wh-3NjIls{xeDLZz^jdjDJdGz?$eiclQZ*HrL=@p#laC5OOsrY<+K%MTc zwE%(?l!QCSoDGkkqaoX*aTGqdDdwJqkz_9VlAzsPyni>l!tQfSS{lm&D;!8 z88w@&9O4;X*T62Z(kW8y5-t(1!cXyaOfP~k(A>{@cv=FEFIJVuOV)jYG5%D!VYoL^ zj?ay&eBoore*d|)t(ysEN_1rE#|`_er~Y+6g3$1uP^Vy`+myTg`A7K=fqq03k_Fz^ zSd`3)&rlHcF0qA}MqJCt)cQ3U5=wLOZe#Zph2C*9BZ9JSIxfhAK&-|-sK!NA=P_`r z-zs^k9gz#rZPvph%DK^?Ps#6T>%*qn^k-)qW1O)M(7r3MV#Ub&uPIeWFOB5P+#uBh z!g@fLYb@Wsm{IpkVKl5DaHOas43L;`Cc}jxdMtik%&Jq@W(!|6BXhv&n?)iSEa;Cj zo9))nTe)UatV#x4yP56$Ovdff5MlS(2$^E;K-5evn5-1`!PEIGt5px#G!PnHm~ZO( zw3y0=ZIrO$)C#RKA;R^{v!j9l4S@-%HRo4AXP9`cZkbZhC?CX70_6$Q^b0G2W3-p)4qmsTm5F{RD5i9HP%>eIFil ztBkUy^xhfMJX+K4kYIJg$a=R;Uh*`T`~Lw7S(E2fTpw$1M7u%W&3~<0um%V|3ShdN z1J`TU@-ZXWk*jms$Y)R@Rj?D7Y(u&9UBGv=(ITZJY8GG7jW+#gzK|fbc%5I#pg7^) zawtpzAm0me`fpC@*X?Nx1^c#OVq{irNT`NRpapn!>c$08kJcihbC8$+NeCOybz zIOioSZ1Q|TrOL}=MLwShiGRO>fmc^9j_;1nXi0t{V1gve zEQ3$cx#cZ65W$8$yEr~6>cVpArkYAOkhm7q8!xaGVt;G!FHZIswh1AqPsSqK1Ecc$ zP*d`mZG(U7)eTBUP~~AkO&PHLqi^LkG4CgeVvdO0-cXs>Hq<6f3hdxfZDKzlagm02 z9VWs`6L|=lO!N9Rl%cMb7>^J63;+Nfa~lVyD)z<2IenOIY%N`#)WVWczdtqX1O0;i z-Mnd8otrSM3Xf_tECqJ!g|dy%Wryn+UnQ{%i>aX^$R}kL$sxJQNd_!UfPZq&)4(=Q z_Cvmm`m%*EG&IiqzXfAGv*T05evFGl+!*ZQmjou>cq9QizthOugj#8E-;Vw-xuA;y z?$zp&13(nuLhze|AEP{|D){zgL0kC^Y$PRy);If!ey>n}0?II!G3*$(cp*~`yN$5H`%cci^=gu=&L-oKDZ zMT{WS(@Zl+oM=#HH@SBhHA(x*EEEv!5ExIVkl0FaGW95;&#nfE=-DfKk`fW`Ktmp9 z4<2X}J4vx5md}d?@JxLj8z=gcQo-v>g46 z;cDwX5F)daqYG!T&E?sJ9az~s3pXNAMVxBV7Jr zVY&mD8AkPg(F^KJj;KPuJenMsJdjnc68)Z(%tg`=xcaykiUUm=YEP%+qtEk#J9QLC zm~4CfbuWZMsZhilK~opj`mj$jP!!kmm;jH$Z;>-i`h=?lvG;!%`*4ctiDIHICR@r@ zZL;=kzwLn0?a3P6@$8Z6CAikpCY{p5z_1tbKcr2$iYgwvG>MYnwCSStX<9`!j;Iil z!LYVp1sl`Qem3Sy2$y_&z{E9INx`yKu=oAAUFaG*%%?%nEX0nX7iI4Eqqv*~85wmw zypasY+l5#{sPjGs2Q}m5-rRo~R5<$%oTB=`;d+^IhXh}0Tz256JG7Y-f7Vp&@BdJf zeBXq{8dvZ|UFp2KsCa(Qz<0~)D@QZUGx6E?;sm^&%4k*M$e9fKX_?@+o#a^OHqb_@X;5g{X}$6NA&#b<-^?;hJ@848lW0(@~5(Qiqmt?gr1Ovue` zv?)u~Cv(=)#cqhU=H+gz5dMqSD)(F$+n(b9<2|!+va!@b_Ut6$kHywZR%$LCV|N(` zG82%~gDS|c6~6~8^uA+rU-@@IqH>3o3@ ztpN}nw$}Eucew5Ds`>B1&P;&u=4Zm4IdmdAhW~MQ?ZBuwZ(#{X)SFB}uS*_e9mfjk84 zp!^}hA0DCVJOuWsACzn{X}(P-RQeZ%?8^c2En88V21(o^40FO8RxZK=s=}P+2`+YI zvUi(PlCevb)O>U7rTksva}xSFD+Hrz4w0|xqj*3dR=Pi$H&g|Ta_$?3Jn@`0Go;4c zgsqHN2muI(M+m);(W(4q+3WVXd^tt&mFJHRWWk16ayLOzDff?rq!khC;wT~QrbWqb zTsK(sfx*~<#ml#l|H}vMqjr7p-c?i{Ys6dTjg=W(P8!h%oTpY<5|7i#?)Dl+STEjt zy2G7~m82*&Tbj%#%O&nf^Z6UnhyQWP;!BCZ001TN?L*KaxK3%i!1f*QpqMN_@6Spx zuZmeXpK{KOIRZiU5vq8|#Rz|g9v;QK>?v~&;^8%1!rQ!lF3w3>M{INS#Y&l%OG1^s zNs@5|rbVIwH9We>Wv}%0de-q!&0zrAwd4Ea4Kms*C6NhCVGc~X=Vs;%p{;UC_w%L4 zPq@VAm3*4yxHBmYX2vtSdUsHrptBtxJqK&KBgg@^ZZC7_map|kL53Pwkp@P9ztI~M zsq8$cGMg`|4lrfwT+5R&)Ncu1>dK*3%vg@%$zCryR;pqUm?4&Y@_0O|R^|EdtePs; zB0bsD4%~LN>fzo02UHB@!27=a5He3htLap{kB}xbb2K#&$Sv-EAU_Ub+QFL8f(c1% zT`K$CI=p`szQG#-w&$;d)Or8_258G>F%D;^QVGC(fW4PezCq)^UM8{JFq*S_IIYe3 zWoRNj`jlmWst}31PxXE!*d$2$&&+!yyhm0G zh*P>jI<>Q_!Y1*}#&7%wRA-DgcK_frv@SHg>Es+vZj08E>nbF;1W$D@zkyWGVSizt z0U5x?)aDI9o`FhTM0Sn)f4{Q4KXa~O^CBgUGOLU};)38d+1|M`767VMGYOw;+%R0i zP@7$YgaCclTgUk~q~(~d>4iTXf56}E3|(_HNbXNGqj{HjpQla0t=#Gij=zBpDcMVI z#!(xS$G$Nqgk-GVsCO{lZ*w_tqkRCGfD@=#wHP?OK8+KGXkoq%E{EcEB#k)`u|*UK zUbUl5pDzq?iM?g#a*M6&L{g%{(P6ue3w#O{Ryx4?Ume??a?Y5^EPH=vwf1Nyj`0uLxqCM(n5D0l0M;$b_!BD0^l`B zyC$Tu47L8Dxbm#KgaIA54&RGKWD^`!<(3=T?3`Sc>J{2xs0x~ECG2;Hu6PD4CD1?sB}U>W#Qk(`0d;9BYRZaU`PEz*L^~*B zg;YZ{t#bXrl{u}^!WfRU2QS3PW87Vaz!l(2mnMUNrLXb*el-^40ec1+V7JXa4Wczl zpL_P=c{$8Z$!6GiKu2?ahlU|~v;sK{0gK%Rrm!8JhVzhE000930UCQ@jHi_3v9KQ_ zpUM#cpFDlV_zxj>LtrTQ2TP>QRs%gG`f1)nT7@pQHbdH;Vfwnwmf@B(ADC;`zMNE& z+iQvA2}hBda?{?@T@`6kXxo>08<_-{bX!vk^@J9 z-e7ExDoJ3mZ8u49ttL~(D53dPK~^;&2|1w?{hiGmz0r0z+d2N6l|$<*p8Rp&#%M@4 z@>Ay#!3GcTmsk7;*bA_MJt4>4`se@vB&^6ER7&g&yvt*-1J*pBS6nqN&E5!Uc!%ikCH%wb$X_`0qi;+Uu_M744|U z8Ro0&*=b&uG^w~Jm=b1TcTYaD27Onyt7#h}wcR=<#Q*>U000Xg?w5fp1bqR$1e9;DbVCw+F?gY`Be?#q zcZ0u}wru)>pEpGv@Lpa7Wf*iZ&*DdjJy-_~kCW13y=TMG1mLNM>{|`olsN391qjOr z^lW_ufx;&@%57ROfTZ@Plv&?yr&yUKtq8Czw-(5ul>Xx z^uh7=$|Tr2HRufufqu9|j}NnA)OpgLEu1n_!CvZ~i-Ey0!%ib8@X;o`QalCNQR#1a zxj=>o6hl&w)q$!~l(glnyF!%--0NH4PBchNy&fHNx6%Lr5&=Sxxq~i=tzg?*{pj=I zdFDBT;Hum;xdnMV+n(&s0T-^HBB=)#-~W8P2DO=$pI}z~i0*m@a`6D@W~4zxNpvwR z7xog?#ew-Br3M}~LzPk$lYeiN7wrbAM}0vvXWfNo)PIL%$TKP5%p=JUfd}$W=p6Ma zu&Hl=#W}9jED1=(q27z}6 zkWssl*p!!G`j?~t06YrN0Hx*=H0le(P(lu#6(zTr@@-4~iu7Y_R5I9+Cu{@LTvD2NmDzRClQJ2`u?&UlZVFQzV z?=$~YOmn7h9Q;Sb!xL^bKrM2v3FWcxGHBrO78IpK86~=EJW34ivn55m=DB2X`NIGX zng9jL6k$cx|2A%COW{}jY9ddR2gPBqKR({e6uSaB;xEI0iCQoP|LdrzwJ;v%_9t=~ zwx~xet3}TeHzYWhyh^jz4hxjN{D?oV;aytUCm7&yZwaPyZ-|Kg3Fac@-5Op-vm3>f zj0p7K2p#*V?2bVi>Erm%IF4%j^D>DVfb4uCpsQMLT1Qv!1sLRSRC4-rHB99Pc5QSg zS~RUf)e5fkq9)4djWVG&m!kymg$2M5R}O3E+K9a17Rsl~@paEU6QJuQ`iWfA=MR(4 zv2{#@Lh!S#+A#XH!W#j)z;OO*kOSY=c5a6Dk=WeF4%KX0JXDXL9fo~u?;prwM|w-S zKmY&(002Bk>2=cyiELo6V82Ak5( zx|g~JjOerQ8LWOi_M_-c3(v*6ytdpW@jCw z8FGnfF6djN?7#_PJR}`;reVcoHZ}pjRukk+H8NdJl z8smZz4TUeVe^?9VTu;t)?RjscpT)CoRH58E;m42hn&hnXtC+{aWq+vA=G#Y=`9@vSQ#cHpc0%`4pZBiN z4{JakHLffUx`4a@0e8Dy=tHN_1Wr`??3e|Q=X9v#N#+kUm~4oTu8*f(Zjn?<5g^&4 z^3__b(SRD;fis!zYL(tLOWKJiftcN4p$+O`m-&i%h$}>=eh?slY$2h$>X(ez00093 z08j?a@~H1%(PvkQf#a8wv4<%2tuVM$9g<#=ayEE3i*hQE#d?BlgJX!P15d#i1FnFn zvOYhaz_GrJHbxUKWU3~sDlNXrvNk5St`=O1yZ-FPLt$hER8IgBFi0lgSuS7W56KD z2qkFFW`RXVp>w)0?2psHaG`GFGohYGO}1`IjO>X{!6_TqzJIKN=es-;s@&D^TZ^dx z00RIP$H)3*7Dy}x5Odkq4lM#PKWfJRA;ud!BT(X`t}_#o%Y>;g1lt^sSQkd$wt>u)4m?1@iZ1TPLK2-J)IpYSJ000934s}u= zmELL<9ZZZ0tC5)B_VQRH4|25+8?%#0ng^kNgJaI100095D4I5KE%~d_ zth*uaEG%QvNVB#bH1DW`TGN?rj-s-A=2t&NGrn!P`!X?u zb=%J0FFXMRJALe&Mrx7PsAw|9cS&46Vu*DTAwCG1nM;6C-~a#v00aPdz-h;9Gf@Y6 zq&E_eVAt=!n9ta_Uw*F4us#FD0?JW-Cq4ZIw@NXjN1g=1x(;fdi z-c~Qqm08w}Z=pCoxB|mzd3&w*TQ5W=_Tt3V>YLXH(+LdF47l-0PWUlE=|@{=S0G*Q zI4SQPJM47AL@Hp?8~}t3#}O|$`dr2o(P8{>Xq|^PmUpzR^7Txv>PLduQRt`@rWA)& z&?L-hMGOwmK++7T+7*H}H77ijL7^B|#)QrseJT|2Bw!eHt*|`tpQdYP)~{>%*jT;M zjj9zFd{I{OplIL#00RIO>IXkLM&oNk-ane1OQh?(c@jP{#K}bG18dU*FhxMxzyJV$ zyBI145Fsxd)72|#FOP%-wKGwWpBE&dKY@Io4_xA9nQE+FBM$(%f{o60x7u;j7Aywk zxV>QcEU%dRsRO^=H{H9JE5n})&tO;-9o>5q?Rbn5)?M&m)>}qb*LXNewV$^u6T<_V zODle{zZ_ZZBJpIRRKS_~wLA4dSWCZz44pbYu~w*KO+F@ZYorHS*Xc)$P*@h_B*7Ph z86$d3gUjl87pkRZnA^Rwuk*}(ag_DL5~3E0=_BH<>03l5j3g@3l!F1D5S4mij6YaM zF3%@|Q~&@200tP3RBx=C>gHV=2o3LDe&HdhCD;LK6ar3HBez`a*cLLX0R(m((J8?E@39{3Ny=tKwChR|tT9GJRm>dIS(A^_GYN;Ch>V%sG-`;nr( z8fKO!=f*>jw>Fzjm3kzOVNM|f?1`qK%zD^OBcONvxKcx0N{VSSEH!=m`4=L&_Stp+ zdwNHnb$&+eQ%xF*?_27hu?!QxA04$4<2FE^bcVr*$}z0r#t$20Ba}yXcZb)y&5{jh z)1CgaNtR=-izkwHY~_I*oI?yUUx%YdQfswK1Rf+}%DoplUE`o%y%qo!QlJ11_;1QA z@lQ?P?RYHI=E*tSuBha3w(Ksc-XOO4J*Zl{aq2^R{HITTN3E`Yv8nmQOg0H|^SSQ6YezwqIR1 zyS&Bbv`Sk>#}yaUD9mnm<+JTrXirdJG)hW1f9z&1scY~k(bR10D$Sw#I1!Heecl#7 zZe*sP8nX9ZkDf4cHC6dniZSI`HUpnTdd&OcIV$+>002YkOu_Dodw|ZaGzQe$o0+RD zrDtXE3A}^G!miVvhpNAdZc&=oGW5xdRof3&hrVT74kF4E1D1x0-K3su5Im%(dGorb zmH|wg#ZgBBDQ_TU1!1~1e}O+hFe-eB{5H_y+MZ@L2IIn|9w|LOQShM?Sp-D`$w-*R znT7EY+iJ#{?X?RA!sad)3S~XbjeZbW<&yK&`h}gNJQxGJzNfKcs&SJT|2r1T^gsi3 zkLKpSjsG7Pf^%1FbNT(wW&d%f5VH-|e4kMZU3N;uq}SsIVNW&+vg!}{R6L)?Rv!ly zAE{ltrWhf-3}Un95()u@pIlw9;4M*oUPQHZ1!8W2zB2ThSLPsI1Wr#UD)BRoG3!vI z3a|Iimj=-)kBsE9Y*W`DY$-g!Ni|E|CAFUp2r}%_cm5(x{_jw@KK+?6SQjn@8tEOs zZ9M@qLs_Eeh1U#T^mVL|XvTu~o5JchU!E?zjwOLGd(RGm`6w(M$}4guCPAR&)C0SP zaJ{w|oOBFVOt0)YKrsBz1r$a{@=_7nerop?p3LL!Koo~zZ&vo}<$pa-lb1RG00(qI zo)AwF|4=Dc)<-^JCHMDPthLVGKC7|g<-5spF{dxpxWFe*bF+aRjeGmN00CNK z>(Q>G$+>}wfk$AKHPPYpZPL+Ws+{dte1RtfWVwcgUPmB1et+CGjb(1RWia})SN}Hs zX$pr5n01Wqyv(!XA&b@9A36kkPzz!8PtPx5H3TCbbpos{gfPNH(MEPb_pP+cyL^_Y zRHZm#Bi9_7zKlN|g@(AfjT)i;R9(;o@Rw-OUz!`jC%*T89~{rcL6(8^6Qphy=Po_j zjxR!5u9In=LvMAVbblb!Hf_S<6*S2KfJ z+j5;sXVPsTQA|*uw0{7l?WVcZ{iT!$dS@;~d_eE~s*3}-Mq&nH$<(b~wE#i;KEVNN ziwe8zz%qf3zp*+-J+#EP|A*Y&Yt+Tg@w`S5wDHi9p0houQDgGqA=phF9%8 z6_|aT=63tUahuZiy}rkF$j_BCAZR)Ttv8gun!FRpoZ)bq%ZjTBzqxD+Xl04f1PcLB zgz_u;Oi_Wgysl%%pCUjVf;&t1qNT^Sqm9j0)<;1=#oiaZpzMgNoMp#zbQ8S6sG)s+ z^k!6o+$p4`ozF$a{zH+wn6?aF&}P+HZz+_FnteA_?tR0+o0RPpU$J zTOSXGA{y>@uphW0%wufii)O%D$oOT#Tw8$zQ(D_hB(yl5)*#NGmpy(dv{xFjcSK>r z`A)#1PLc?^dm7_}O6da63as1n&{Ov1DrK?RCn^JV?C~H&$U<~G( z^SEt`BHwDc?ZBRb~FSd~Th-4YPLz&ECljXiEY}d~U6h$|=+6!{pK0k@6vsTw$jRXY^u;TP(98fItWNFn0vgTBZIjE2WGKdgw#|xV4{g!ql}b%A8po` zM(}OWp-jS`f53@2`;eJhK4a%}FkGK2>0&W>Cu{i_1P}F0RI7BL&rhdx=`P?@TW8<~ z`=!9uoD0-*k`EU4AFESMWg-n@3ap-GHVI7EI)t!vl$+53^`Cd3z>$d5f8=)1r+=wx z<2a;}&=Zi)VO`uk=$t|h3#>9h(ic zzv=B2)^7UOv3CKlBr9)p2`;F3;|xMUr1_E%e!E9chzwM853d--J!kGxBIu1Z3)m(+ zo3!fOI8!2rD)|@9)AbB1vSwzy9q*BK)(az}&Dc2y+Q^DZ4Sw? zrtf;v5)OsT`;51`I=e+6F?yA#e=rYbH%FBx62{X^OOb;8!jyJ?uNsSG;z7{w7*vs; z6|DMGv6a2~z^u?1Y6oiU5NM3SdQRiH+_7hORh5%l(AdI=Wt~%p8lWs4&wdJ1G{0&9 zQP_^H{~|x^j1NowCyQYbvk#DZ4M|6`NLxMvt11_y;Rf#JdxVviWFokUHZWW-H;)4G z0L}%O#vkrP%1;WcIW^O_JpA|Qpz#k@KGqR>Y>fze;nRwIi=3KAy@iJRaHOziw>Zss zf3-zx93Wkg&;7dz?j;*0JBoH%4;|fu-K45$9akZ|rP@cXNI-}qaudL<0p!A|)-XR* z^bX3*47zjem2Bo0 zWZFixr3%T_3fbW!zYq9rNqgaY|x$WEyf6D z&PNp2gUuU!MOK}+SHWBY`@*2L-VM3V_m=n$Hr*B2WDtE%umj@cpHakyw>5{O=g#W^ zcvo@&2psQH-ds0D`^>g(CGG0#D$-t9l)7CA&EcAtm}xzohG&924hL81=-Mzr$RKQ1 z111Xj9NtKdE2;>Fi}Mkv<0kZFzFCR1>)WHGur`SR3e_M000TAwo)|8O|4|>#8+SHJ z{yqbtc$hJR0@XLD3wW;z68z%i+KRHvM=IUqMjCUJ;){cwT^QVfDPoFU;uv~GGzN4h z;Y6lx(*ahhmT+t0oN)6w>9z^9GR0|+w0EF2b$@9S5*^yZ*jbuMTnTTaRxNBtHDXCBFHI6le zHmxIi1X9c(%0Zbr-2lfZH;GZ8j(e@r%$p>E(lvdr^^#1kakeU@BFbi%C{YS%l8LG- zA$GP26MJ?3RKveM3P(ie_6_i^+c4YSt_STBU#Ap3R87axRX9l@Y0(*f86{v?-W|^n zNZH7E^?4>@r4txQBxUZcdAgY9Iw46F2lp9kby;B}P z*>Bu*JtZ1$%I40`Iy!mDYQQ*`mxR>I!O-)g=jY40!8624si!uAN=4Zz5EbD$NQGL? zIvgU9Zlne>w@uNsB3>Fv&*l5hlA;2X-o%3xYG6PM@u?j$840z{472FmvjbE}_oLev z-jIyOWlzYcZa)%j!GAOy4y1%k!yn&cJ8!^NV)_|)M?_M6G%&ZpPAI0S0JccOy~eH% zV>AwKYI2zchuG-h@5aE?;?k*^H_d9PS9lyKCnRy1W4zOd{bDVo*sFEXGU_zl8FoX; zTtR;1#r5_dcNo{%V3&Eri0aE+KwJJggq_hfij=NuUJ}mW`IWgUkVlZ5wyo*H`D@KR z^TFOmH&Jv~U$?kU86(Z{H!~5x*ruc0XKm?C>9Y@1t+dg4x>1xzW}qK(9xIw1doc5U zgGr9$7AnjPO<_z>L4!MtCPR#E@B>f~s^0kqN~zY`+O1R$e%*>bFa^ylxhE_bnVBlU zz6P9X;ViT3Cvqt3#^(h=<;vQJpxJfdBvk{sEpCZBPGR$OO^g0C20J%Qbf3 zkT!m0%@}h?w(#n@Ip%ASYZd#+w}T9Sd#E3F#Ey)OjAYI%g()ju<5yLGQ@UpXEUt{u zA2ry1Qh}I%f#-!Eu^LEEE>iVL8xrs**jKzp$wfc|1NLoe zTg zSu%HJuQ-KPV&~+P07{y!MU-)_Q#JWEh`ZqOAj$xDIR-KyN+W-~>@_xnAn%zN@p)H^ zzc}Mkj?{BFPOC8fp^zd9>|mOwTjpRn>?;LnwsRVnT+|;{dD)Csw9&;g*OT8(#Z66M7vrMFHquzy35>)@;_xG5`@Xv6Vi%$PMhU(Z z@;+7ZkHVa(P3BYsThdt6vhEEin?x?e@EHI@?`dV;4_ZrFy*C0Hd?%R{ zwVv~XAQUh2PaAU=o5_zB*N6l3x-wuswzJ(Nd0ugYQ9J-Yx)B$2TnaP|6bHfP zgg*rZZOQ-ibJL}R$mHC+=mF~h07#ZWni#1y0s_%8m=gaIxfLVb3-PmhX)kLMV&ykS zXzU8L)R5PW%G^YZvz@c03Wu4#YZV;fEPO<&Oj4)Aw`;#Zk$d`yuj82TPYBVh0RUvt zyQ(7y1o0w%$m&?giLUWG*Af2m0pC9_-bTe5)r)LW(um{>hvWZLQBwd#XP8wteX{68 zOQ%rvPh)BRY#KUGt6T_Bk7U11>0SrN86|lrl)(??)L*a)SVJy=*kjb?;XW==o{5%m zVgwqpU7($$$TYcwLq55VBTR+&m`22Lfnm_lMzZ(5CjiupgbFYlLO6SWQEvV{aQ-*6&DpPw^aI zNS}v^sbtfL-}1TM0Q{Cnfj24#68|4Q6YhhS^-O11U`@FK(JR2-TKd0f~LF z9EWk|Kg;oC_;IPGbZZ+xN9G^_S8O*P{Cjvgf%o^X%nWCiA~XI*;GCxZVOrBmd&k4c0#6K9MXi!uv;Tg?`& zmDYY1i&xbZ^zTp;dGU~(VX}duN9T7xKOD2g{D>zLn?))jujL#)khh-_kaCpUG`@6_s85tHlmUdupr*jl;>^q)j6z5uG8!)q zA2#-U$FEkl+kT6_G(#})kc>~p{MMlWkt|kYXC9tL9~ddK=-n$xxp=Qj=+`<-p8Kqs~Mv?*!CIO$Xv9N8i;eX zRIgA%6eVrB9u{{Y#TdK#eh2lWDc<^*Hv@KOD0V-IGc((us7QE}w5JDdlp zAmkoU?$rabS|cv~j2z0_`T_u4gT=mNIB~H3;eLK=@EGkC$_g77jSDcqoNxf^sK~YZ zO$k)}kjNfT>Q)ONy>jQ!<-~hCgvMBxQ^pt|Iv3pb%FR4}UzzG>b#C`Ar@ z-izEm|LmZq`Ha-zbV3?`*%!@|mJ|)r7XX+ISK%L+iXWgL*(D&_BD;)R9n5-5X+B|S z_D>NJ6jlUZUljA_5LlQ<9qTLV*cFpO_qUFR=X(?rr@g3E!m26dG!o$3*L7w)S`eJ(Pl-8GTR7-?V9_qzc9Ik3`zxb6V zt@s%MRoJ{&c3HDo$u513*kx(!p}s)`kB$C@2_IHu+m`v9)y49Ha8oZG`BBVfH$*)C zS{)YjC2t?%qgAvvr|(VwsD&~8U?S{=>GKnJ&S!Mvm@qw6|TH#?WLPj z{O>=qDFKbRRg9g-#PiYPA2mHw&X?OwJJ+=0nUpIxNhiH!DqQNH;z$~pE9Kq*)kGxI zu3N{w+KSdx^c1|mNUP0_GDZ!l#LDfEybr$Ny}p6w1t6)$Qa!0{z>lYLAr(582alxY z313=Pw2`t39feaOs$C>-*{d?2o^bGJr2MBa{O1RuRKAP3DG`$rfhpD8W!~lG%kdEw z5P}g@K{Ak+^1Y{xVaR2_l+^5#x1mB9;G_IHB1PEA-LZJPJ;T}3< zp?UGw#|ULxpEuPl|9#5#v&QwC(4+fe%Osa`U6~FK9Bg}_~-_{@f-SRlNe}`%8|RoPhB~@xo`$~SslbR z$@|K@w)pE zWof1;ln#*|2_rc4{-GWK8>zRgyoYt1nc1q9HMRRZM+BgGnZs`;~u66-m5oomPvhl1Q??m0W7oy#>;rAK89A8ZsRM3tYL37fh_-#YEyz(CUCWp63P10n@#aC(#HO@}#5 zWQ?%hPZE$ONyieIE@49E!7gXse{iryd1$ahEQ{SV1hX4dYjz#H%6)?@3aEB^+ekK6 z034dE`F~GP0gYe&TvUQSa@5r5R6|_PJ&F2W9Q}HxIe4iD*$vjr8jlYr3=AY2DFoqm zq85Oe0zxhf7uf3}tYlGk+>S~l(W%r6DR-a06)BuC0kG(3F260tU|7+_kEC(Q2@lzz z8UF{mc>x0OukqWSAXo>$<0$N4DD0cEf|L{#a4X+G^pua(u)75IBDo*~{xn^y{?WMk zhyVhUMn4H_ywFw>w*sI7MNE?DoPes1dq3G^N`-uSZ;;z2sPm1kE^_Y{PJK-np~hlerP*wzvdwwq<{v!}^m z8KO9UY!vpdq%9f~@eETqxHFHMaI{O$;xmU6(fFMJ^QbmBxm9$4576@48z#~?l+7I4 zscL249=Cnbl%MEGtmS9b9>%O+_btA#Q5U7Co|YIPWA2(^cnvDl|pF!5`T zo<6CBt3cw86g+sI1Dg71IlBrbWWYS+23B$Y zNE0UuEvNf_A*Dt}PbKIIMJ=o;PBwFj)V*q~#;D7t%m4VF2A}Ky`%eH^n2`?>+e2ou zO5LO3&3CUNe`l8O^ltwF{tCFe`V%ywnpn6fFH=oD>nqs4QR!Nd`_ zyi#@n^MGxF?z%>>B?UQDOR1Y}muTr6tiNgm zYf0X$M4xyu;1SBZE>sJ;CDEz)0;N#uQ%H7AYvpXKE`ibEL>Ku1VLXGuWRXT!WzdmA zCuGeco~#o^=|$}>cVewDH{cF6F?nVe!oTKRad+h9--PL)Q^jYT`AE)i%J)2C_h+lM zRfYPu7+!kQHJuozKmS@dHxiXFH~65fquAe>x@(`OYhH1F>!lnkLVAL3aZVp1SB=?n z8GV4gM+Rl~Y7QR?^4Q7(*{x#Iuc)p!IGNKZ^zxXKVu3CR_L-Lyf|z5KVRgWS#2>-Y z=5Neu-IY|s9R7I$c+cuhsXnJ<(qs4MrZmXD#%LzU zc_fTcqp!13?oP5%PtMuNvYY*9p(0{(M!jRHtr|k54vYdve`+8M+}IOsC$O_OS*Y6R z_{6Et&j4HM)$3>aL#yPbyUzFX+N_;mT=LS+Z85s%)mTI=7K1QhtT*Ym2f?J_r9<>kc&Z`1pM!YA;lK+nNqsCLFxJ}vvFH%z^-!c zSD8qP>}Smj_aRyZY=)I`vDQS={(qWycase`L&l*|pM^&#>*fya%Pk))5L4DsVT@mB z;(2H*4e+sVgUq5J2f*Pp@N`Jd=g+Pm9K-$=2;DdUeeLJ-Q@dn_A~gV_DVKY~8CvDuca%0ey_Y zNMBw$dGvRu%MO>jJ*rj9CWNu(Qu2_t6!2Qs6ZrOyUeH>onSjSGYWL~}PrUHpq`Is7Z_Qi>uRwRdHvBvkL^ zY0I-)yS6P4`oFN+N?V65-dzQe%>PK2zOjVv#Xx=u`jDR;a6$kUn<@ga1joFz4W4~O zC~5GF`*MeSfv3*t+R)mD57YTvsEWyw;oyu!CTsd$VNoW}9-HiTkUXB%hn%cTF~98j zg(D5F5Dj_3zkAs7Oe)Y(@CPI+5^sQ}j6bI;mI9C4B8(BR0gIm)6LJ>I+ooo4fPWSg z;?LC8*eP42?BAzT7w!-UXH+Mu)a@GIHFnVzc!JqI@QeqNPEbq6T^~Ci+wdvtl}uDo zm)|`L)vv{Oz&%E*eP15yZwrsk3D6Wzm9o6ZIQa1}K_t>PqtVViLP)^LV1*j6U%LW5gbwC&0itXBK}J17k8v?VYn9?TQT!TSxxUmknpr zyIe~=NUVu=s;soaxK+SRa7hN<3n@AO7sVc5lj0Z;1&A<3XuW8GjLur=u#Qgj9i+9H zlA3hqE!B{4Ocwk9(0CN6TBx=cl(rz|9OojF9TZ?M<#c!W|5s!D8i(1>=$~9~l@TcU zICP@HsSBZ+*z65%$xg?(a94CTtitXhuv{0hO=yBMbbCc9VyrSZQ-eS}{D`<0-1P3U z+U(EkEb(DpJ8|7n3MYY#2skvob7ywAA^r;c>FZ{+QT!*(H_Q|=Kz)N9bQNbgND8Um z%k70j6YRoEVpa=e7kWR)RwZ6AO^q?adOln1SeBc~OyCA!0W@Yyxih%QZ$KRGC-}$E z3)@v@(yH?(7;+^y;~KKdZXiorxeIl5mol*$t!s z;o&2OV_``Ad=6(rLB@c{*yl3!Bv!OxdC#(1;HU;)fa%#s_490cI@k*!{#89ZXM|Pd z9QX_Ah~5l28$h3EME;+1W7HzpL0P4)GWO zIL49`*3QPBZ|BBV5}xfS`;RHQ7!PdlUiYU=^`oDQ#&k%=cz~_pB(ajjU_U&x4{aYn z;JKIASDosGQ-w5MoxhpJ;(Ay4g^>Xt$qBhy#vr-gIhBlUlLUhDlF#p!&F}h#wPbbY zKctQRf##W5PbC<`qy05us*RgqepApO$_K)y4lu0>q@MsCd7r84^<(muYBtUA?`=%Q+P46 zD9P1J>uO3QuTV|`@!dJ|t+oOh6cHyp^C>v+3Q1K-b#kC#>dp*KVP(*Xy$;myk26K+ zV=l;54WS;$D5{hN&Rail?p5IE7SWdzR0lP9nIANP+*DZgg#9S;C5zDnAPr9V(a#`b z!3y{}i1G=;IJNywc3s-mmzNg4yBcT0{-B%)0BN?CN__-9VfnQm`BrSfz@0P=;DM!Yu>;v22v*cqUdUJpm-%$wM?ao{Ly3iW2DTYHG_Xd z;{o%pJ@E(bzNIXI-;&I$81*zbZ@-ezga+S-0P!%bSXCCuWysd73aHEXORZ|Vcdf$M zhl2!UX9WBynC6e{ z3~`(E67g5%dhbCp#_Z;Rv82XwKYc*1H?jBtVz(x>HirtR+n@Mnhs^lEfEG%Hr)`aN zaJ@);IM|9}i>`qgO6HvcwS@hnGWS3LiBuz0_${KSm3g;Ctk2ES(sFCxXgO8!WIBZ< zo)~T>d-+Jo^qYhS4d+tJ%LljCHkizb0hsDM-< zr|M>n_>60YiSB|V_+4psh_M6=81Et=zbhQ zbx^Ia%1qQuuEY|103VoSjMy!G$}*LS^KI2%`=mqv_gUahsw{#^v&KUx>9)<+luCYX z;q(Vv?L(%{D~B)CF1O-9jw}MlJYBLkIFB`jq*>`-z`cMG=3k^{NzY zZiwPpi};hQ`8s30p|&rN#7T{SH2$X;Wm=F301PFZ@E-%e2QT466$x(6i|%uOPjAwR zhA_VpBn5#CY;3A2Y*r1a^Ofh;_$CdRDpx{5I9^RI!8!77(pOmK@w8YI8cn2aULX9X z0zs4kqSZ*oKr52mPWvn|;E6p*zJ8Q}iO`-#nJJbLTh@K<;G`Fh;H|H@%Nlznas1C3 z`LopAg_=FZ&-Xy>=^mOrc+eZbtbU5Ii;1e+nIW{PeXkeB55%V73bkTyh&eRuu3?#g z+VigwkwocjiM)rpEE34UE%0wAH4%8)6kGU)2AUeB$u7KdD-H zW7V(MJ9|l@SO4!id-8@AfLyo**UR7etKi7bH()IU^cAQ`vo59$$`AkmE<+7yFr>$4 zMT*Y91NFyx9Lxe5pS)JXX_2R}aDb5fK4J(90dlj5mZ3iew0I0?Q-4Ar&d+jcusN_4 z2hw{Vhm`#x6803lEW(%x3E^^T3lGv+5J0B;0XyXj-Q-NMq&-g!ZUjAf8(^VrB4Le6=GtF*K<8Vpru zs23g8uWp!^R4RaH86V&f7XGD9V~a+<>VMBx@h3*qPff>XcH^y59Ey6WR8E^J6$XPtIE9 zE++zvo=BOmZ%A+rFcAn>p3gX@wfg@vy%r3xL?qZ#Phr=r0D%a>naNm=F<>=gUdH3)keV6>;+fTeP23r0@wBHU;RUy4F~Tud z$h9{ZG;rj5)^jHjI)IgjPQYrf3e3RrD1q_wBT38B4&w%%0JT`KETjKYVAdPAJsWYw zOk1b0W~4#Yr@bLPE^Kwz?T{ZhFtt}|Oky3bi08ntjI=MG5;7<-Dl3r83OoIo8?4+qLJ7L`3EVSlQ?4+ zlSoGrF0_l?(>>D?AV%?h^tfQFFmzjr z;az^IAFr(00M&0G_W&81HTc}IyE)?!^jC6b^mMMTsgj2x6gmbgTZXzHI*_#QFkBm6 z1d3bk(0;h{IbAXKCc;s`3+yFV0*k_}xRK%(zw^*BrAhL|#o9~33mSq(5m~br;I#Rt zv=PscT+L0mG^=GDTqT(c*5qS&lpp>U!rP9OU~*NI;fvt%lbKtz=HXiAA< zS~pEe9Dx6+D%Pcjl64Q{J;T#)ixZFi;hTgIjR5?*m^57?wgQ5`+I>bvA>41tmGefB zcJj9EgaWtY(t*ZtR5yh`6)PrLDR~k+f<&RXTiZ=TC&(U~>wjMr-^A|@;%a%(O9&Uu zGFchD6v;>v^%`svKgmIj>WA->X@$);jABjj{zHSA>vMW_qW2ZPa^x|vr>Fn`g|GKe z4TJ(wgX` z0-L^vr%_<7{r=2nSb<;*JNvi~q-}L~w(+u0is@=(mv~{@u92xz2mlK2rs#i13bVvY zgt27Ux}?|w0010=b~peFwOZ!FlE0$W5#GmFtC10H;GX7>uc|uJhKk8Ov^xn9sAOI2 zvZ&A@i>~`QUI~}JqU8++N9EP{@?uJUiA+FN%n$yzjUry#*8z(L%k$CesiUJuO1DfM zc%9qsADT4AhyT*rzx>=Yxn1uT-~0h1RkykM4NZ6U^~_Nz9o7ud z05+1HfYU=Y*_i-qzcp|J7Cm(&1AK=%^DNqVv$pRS;<-`| zVEraSa$>aC1e0{R$4nwh;YN^i(Uy_1hO=`kg7+PFw#l4fVo2$&tQHa*h}44U7pkB@4(T^QWMU zh8ujC=sl6_*HvBYR6Mb4MbqJG%&FtaKCD>^fi*4l9Wqw-rP3!f?a)(HnzNj5L3(3Qw*n?5rxFtidWIqUV zOT^?v+zQ-he7%@|&&;jJ+zEW78X#EHjH0#&8|F@63qyMIl^wJ&-; zP@!!Bmc(kPtjiZZWohoW)a9S>6+KZLo%bWoQg3imKYMc{Wy+>zgQK^<<8lfY3$-;I z`Xg{xfrd&Czvr6I2*wD z^#gsH`u2~1OAo5^e1~AIY-DdGkJ@P2+2QZn8C058x4i6bPE)J~(o6^lE~V;;2Rawt zu29zi00RJFqyx|e^C5S;H?m77Dq4-uF1OX(Gb}3Q-UnHe5HXR%Q%jb!X0XSUL4mN3 zUi*6-WAM4?YNSus>=WFwteEAc3YN(I8aDQHFhrnnDlb<=wovL&QcWJJ$ zH<>izV4##Me)Qg+VfVZM|8EGYnM=(XQyFTm)`@j>5Ko<` zwp>#a27mw&@krzVk1bWG_bYm&&3ykscOz6-v#;c7dk@$MmTAr^-CmH7#d6jbTfJ_{ zZNa|`>DHB*%3+}B3AYW8%;4l-fDY;P(CkFUfrL~YMJSU`!kqzqm$QLwc>0!BHiL~? z?lve0(vG}0kynUcC4(a+%zIzk>&FKq@}l~p=c^T=Ofrp9h9a$X65H5Du{$O!#Soi( zf(ZUw4wJRF!nwckH#v#LJk{+8Q1lQT(fD~QMuBw{ZPY_LZ?3L5IuNj*=#clg ze_h#Iy>a1*R(yQGx*GyXIpy;p>4uoBjR>azjt;=bo z=UZtfq>)7UV9U=mH$zO`{g%0{8{y*b{W+QPnE_}W000930f(DSz+`rW>bb0?j+xi- zJzs5J!5i^85Jm$E=r+U5BW#U%cx_v{Cg4?(^fXXFU8zj$iq{Oq9boE_WR1_>h$A@K z4a^qalv-a15cA}jc~>k?Y_>z*%9S~4j19kp2<_{!(FB(!*2=eR0q`mhBu8fFR)=eu zH!QkoA%a9~_YIJlmT>nlslcAKxI5j%tPRoAbp3n{V$Ug4&pmW~sE_>@yc;Q-9jx+e zYCNtpRXw}SDzr;w*zYb4>s^7#j!wT7G9r;)P51%8D;NiQElbl6B6IybGOFxFT|!3F zXuh*lG7)+ud6js;evr@&=?K#L-d{`IZ~%Q_ zIVc4mSX}d_O zWbIp;0rOY!W0)PA-?4Ckb-Z}r&fucM^gO*E`wCl>Td6=#Rw>wa^ z3O5}3HsDV{a#Qr5uoG9Q*Va-vhP_t))@b^F%bjkhaaT&9vhTJ2Za;^O0Ur=e5E-x) zbntlhHs1zJwFhM58zn|T*K5_Lr9(2h3}W^yngZ9b4|sEAyMadY*ZWP~y44>yt@AZs z`zf*eRwf}1WJFKhjHJU+(QjgP2{bm-yzYkECjLkdr&j6OK z)GP2ye8h>&F?o`0fSEoU3 zLhpxvYA{R1np?q(>_Nrrqj`J7p1_m13{nP|6j*JTVfbl9`O~>4RRsBJ3D3Qr3Gs6l z%4~wyq9ko5(>r~!jtUX8t+@zW^@e?TP-?C58jULfby8z%!prfksk^myC_(OUs=QOt zFkG~#4#0rE8OlZH7YJ(v1)>NoM`|=?<4+UpYFu1hvi29Vq85fgw3Md6COuW5*1+c& zAyrD{8hnAFjtoe`K7whzi!7Ms-@vQjDTL)8z%c{0aRNU4FpCpyN|oqi!+^CA2ngAGiKxR!Eh(iJ!A^YT5lTDzcRLEZ#5-#OUoSW#$1^=vvP04wZ>-M^B%pmd#6bjn+$Up z5wE6C1W(P$q4=>KO`~d=yRoWNe!eS+@C^TLLcJeZHOlfd9VoGx;=?R>Z0tPLVg|*z zji;G=hGJLPl zbeB$iD+5z55EtwrSQY9P&d#AHGbG9XPWk_~X_a}YJvuWvNG@#iYd|W`50z{^9)B3G z;!~}2;z3S&e?~fnjv`^QOHxNYrJ_Dq1*>oYX`fL(&7@$)>$>8<;m&x)+`e+N`z4b( zZBy1lPv5K6d15O3({9?pZS>j8}-FrOWc}0-wB|L|=#=b2*#I>1=dQcyF zX&~MV@E$ANrH?k2lkR9}&t3)n2@?$$r&9Ypn~E>P23J7ZNG-pAdJeN>raSP86)O8f zIt*tGo)*H^TS<5fTvO-pAg?G--x+Z)2Z*N6 z_c8K%W|ZXp*fxH8jIvaBU#LFfXwBm|>=}2dAo4zm3R4lEeQ_2FA}f2s@-Zl2>e@-9 zEohB-k}BX}S@})CP-Q?O!s)Ih0Di-y_ab3P%dbOP(qymB6SIn(VWf=4%KquZ^{kk5 z{H{;^G$+Q@3b@NTgo~4{#D$H8%pRr#D{FI~ZthG7!Q8X9pt9f6uQi)9)N}fgN*+(l$A5IL0S@*VnDPn4ZJ z#=r_ks0Z9-F<*&%n!_3q)#SL#166V4IOMdS`n-HEVr*Oj@7h<%009d>{ZfS;&%m_7 z!5jUDpJ(NS;VOSnhKBvQ+|KTa%x16OrAb$Vf;_^&x|du{^i1hV{6mY+1rv(~n;>)E z=)(J$sRBr;foh~TerB3L7tfxt-U|rKaJma_Sk$R{zD8Dl!JMZRW((C^e?u`oUh|q^ zFkNJ>s!|M6+|CVo(7l*GK&Ba=h<^~bAUmPb3FI0QY%GRJxbqDQDvE?%41mf!udoXP zspmT{CZtjMMxn5)h1VIIm!`2>q_waWu$F3g-Q0 zMO$+_!f z#~51BOt)M2yeDO{kK4^3dM3{b1^Z+k!`A*>Wz>6)*VzQsGj-Dr14=ey$lNH+#=N%3 zu3^ro+x1Bqq3d+ekg@EE+B){Jg|+En`Ka4ydX9_U;m7G$;`x0jNo&* z{9tKmMt7H@wD8u(eNR4$gI0dUVhHQZoNS?q@%`1r4|}(;?j+^-0C)g!yet$>ZrS$O zGTnBr9;nv-)gwAGizgOhyd-KEiT+8qHcNB$vzQGP`wkb8&mdq~3YqZqF%?89nfZ|7 zXy{l%Pv6yG{~ijH3}7b!+ZhiG1_+Ai8UX*09;llxFynVD)i#6FXw;j|tf}A=W(g~2 zS3-O@R&(8YlXlsCsA~1ollgZ|YbX?t+?Xkv5%6{;2jIAcSX3?&2jLeU3$1MAbyc=y zS-@}_MM^cdHfd;CgYK8U#^?_cgd4HBaV4XBHkm)d&#NJ4a)u0Pa3@Z%_|LO1+~iJ8 zAgqI%V$TP(w6+#KvIIazb9~K-u}1h6F9Bc05m$hs)K7`~vo75ymdQA4ZUy2m-FdCJ zm=)j9ty#*kA=Z5)^^SD{!6JS=;!wmIQ-2$czECSEC`+DOb_x6d092f;H0?~iYPd@F zkq8m$gXoRrBb&I=5gA}YxbxoJnvSvSpE&=IboL``eYKPgvgNF5kHttQs;W8YEQ8Z( z>`!Q09+w)JR|6cVS#9k0fE2vi?jykzgh7;P1E$LhzNX;u){DlFPOb=(9s@v2|G_oc zamUp?2L_jG+bY3~DsI16UD;j$DnWFBs#|=@@ExP$UMMhZ#UV;&AGw=JutGWlNSi^C zt?NgU&&WdrFVa_*Er1Zkr!{V0fn4i4%WSxx_bf^nijFE9liECXRGbL0s?ED6`ujNC zG5`(90RoYlTkDGPn>@KIWIanpEf&+vVl!Fz~HDmr*nO#Q>*2_Fp0c3@d>tW`%+O! zba7j632*{bV!>^s(ndo^0nmUxVgv^{>oO4JE6Ab{rRthsCXfXOE%>*kRI$rXsdG@f z>!ZmEzWE<iVFD9BHzQ^qS}yEy`u(iQjIB_reSdk+=j@ZUTnol{nib z0V}V>Lu6Bo-{{&)O`1bzQGHG?T6H3X$+GslPd))&^1>1gueysVQVeo$>8!~~KhYpc z=BTRZ-U>z-23Ss28Jp;_EqVl8U_d^h@l6>+Ntfa9yLPyy&Kr;b03EIE*qUt?`{*nI zJ0l2Vd&&@RJAFwpwvSEkiB*5o5rYCMX!bIhhusS&tukg8l9bC0X~fSOxKl|cwExYO z{ZNKs)}Hyr0|mgyhWd^#TFE{ve*VhG!2`uBhfegvD-K=cxrKP4EbvaB6-s_do<^0+ zB5cB0A$`kYYeKR9tOBSh&D%X8Ob4=b2e`%t9p)4`G=1x^Q%l43cNPWlRsU0zoU9{< z4^}eWUNtjB{6f^9gPt%HJcaxbV7O!U)6G#Ku*+L~!lD15c3>Td>|86wNfWFHSO=bY z7CPm$b2T#0`8((~s2&K_)4bpoo|2(GJb|Wqe}g0}0G|fB9Pam5C+3uX&u;ojIQ)p! zaGBTVBP!}5vwGs>je&2n5BAV{CKlJ%)SdqY>sl72qP-}Mc#Ps{5V>z&H8x9MyL~NN z^FBA3$LpwY%CsSpAwg*GMkNZQl)K?X$tColpBhFXv z=hS0om2`bX0009300RPMW?m}1!6_o1BlyT`c-#Qg=Wym7=^Q&FK{VnL#~me3w*dNK z)Ipt!aTx9!aOWdD7W=48*lG^oH)q`8U_=W+fv(nTfB+uX4iPoN^Z3|}HS|I93V&?n zEX79>soNnW!5A4Bz#c91?%DoiD-hr0WqzMOC~IY%{$N>(q~Z%P0sMt*Vt!7ImKFNp z5NqZ8`v0@-UY>e)VMM{=`ULljsk`Xd2*GC(6EgO`DP%Tt4_l1|D1UpBgT=; zM?N#;J|VH4&Z#Z{01Ix#YVk{>)C^99oDrQlROwFJk0y2dOCW0?m3u@HF`z08nohjw zPf>OgU`TR%P^`=g!;^f5gi7yF_Z$FBH9B0M1egGGkNUT;t-jCQf(oTXGzo#C&uGszLcm+mlPoW z**J0RTNo#<*5IF>s0J*3JQ&j0$h+jX5i7 z-J{9Z_Zd0DTeQ~tjU{7&f$_*l$_U44 zCVJK^QC94dc{W;QzB*hi8qc9LEgk-4w_1aCBOR4gQedndH|>KtDkaImGRi0vlU1Fn z?w+TTmD{lndYZb|dd%QOCnuR_J~oSj;NzkYY8uh(2tf!##>%r^{^OwSJt&s-dHE^Q z<5>8aH!d{oRBe zhzIT*{fvMzpc)5z94Wo_CWW{F0P4(pgP6u~G6|-k!nE*+(57fTb2rM2V$Q$)ATroE zwN%&P-Taq%9NqBE=NQOBtsogwAF1pwRih#YZtsY->3}LHf*KVsNUBlc+;A)DXl>5p zAEkTFshOZP;Vx5Ak-2b^?BC@uFAD}vj}1o8M==!zIRVQJK}f6te~;d$rb()(#y!MS zC_Xek!S=;$p}|CCizP`$hEYuDpG!eeweEyzm!Z*9GuAU^3;NxB`wb5`V*<*&tjJZO zZ?EG}pMlRSU81T669N^36FRX+aNoD@OU%Ce*x=rVws zc?^{1@knU7jn@qlsv2$U%l6I2O1lK+qg}=Y)O!&uA4~>dkN^M!00g#K5cPlbw5=A2 ze^{B|yr=nPKq2b<;09voL#o(3S;E3*`jF^&M61pJeewN^zyK5Ud!4tO1iu4G85fWy z!fF&gDHj+YX{9hb%I;VJo_bf9Dv|G%RaB7)%AhmC7T*|^m1tlT!|=e8FOC+a11T@b zp(Jp3(5YUtq(muqC}nI?=@x5#$4r=W^47PjE=mwK`oFuUgJL-QVLBt>=CmWAKCMtb z^?dY207}B{d&k9zXdol7%g6)&;3R&=??$mChND?7S%wwwSw@u_PSCB%ZVjGRRNr5G z1Ykq-p#3m}GJiwnKr%Ji@XICBUXC*j6MHk&(hGlEv}l0{vNr~w;yt*KxhyoRfB*mk z19YPrQp&PTr2Qw>6YE|A_WsOxTFC2x4IuGm++8b93B~kX3ER;|(Y3%&VP(N){d(%} z_W%F`01@;zMTM`z&{MXlLE@5WG9#haBV}Ua27L7$S~~z?NF7HhLTn3uidh>czF5I; ztZO&!LYHY?eU0i(jwg~>N++tJhXBI5NxK$$4cwhYaLsyZ>yvO#s{6F5#}FRUx1tCl zC*%&`Ax%g^qu?wKOYMowVN0^91!_AyO9+9@@us9lGl)}I?ifxAODWWwIM#PYBao{f z#9cZNZ2ANOG=n)Tx{VYeAw#yUTa8?l1A{LtEG_^50|2*`)Ctl|8$pjI+zHGJ@SvTvEH_umAuIajQ8QZ)uWHic!fHj)OFx!s{rJuA0&XsiTFh+O0B=S8Tz>K69|r z`4Kk|vILO3oP73kK|kX6!8^fX5n=Rqy1x!2jCxH?Y68rv)K?#UW>{l8#g(^=Fgb}t z-Y8I2C5W{x#?-wHCD90(yW4$re5dLgd5B2F00093CcTmvJNTAW?rJ07og{vE2Jo-5 z_qs$C&}Ps+7L&R*s40K-c4`N~66RwRavb9W^IFB%7Jkma))FBEd=LC3G662<62$5N zJC3%G`_sZ`Uai$K=gqD%mCD_B%5|1^Em^Op@*AJYh7XstYIpNU5LbyW=(Eih@;jW* zcUKvI{E=Vai{;#TzS8l;S+PTddX2MOdXu39*2Y-vawG;0Jq8xi=BRQ)eWY@*_UQS1 zd#RM#vK4stqq0hS&*E_>09_&0I4_i zn|8BygI)_!d1V67;s?p#sjXGwdBp^o43My<9F{6*6Qe7J+&};g1`xa^*%E8P?~^TS z1sC_@M^sEec$ z80&Yv;Jh-6)-z6`amhYC9e+%7_aqpsumAu90EE8zWShQ#(6fpkQYKt&XI?5=V&37r z3|&~U84dCbi01d%+^tZbWBS=GA>Ljm=;ZaHdw1Ug1jpOEG zq%V-B^6oja#gShZ_s0k8*MqT876p{-kpR@?G~i(OqMF}>vVX|LM(2usJOaKxrqr)B zW$6-Ju96C%K=~E@=vHU3sU`MLmvL<9O5U)tA0vQ01=(E-rvvgP&?{ozOaSE^kqhXp zvoK*&g-7ZE?7^4B_FEdTl{8Qr37WAC#No{z7^+m+Z5b}Emo~^)>e!tNJqpti< zyeDk}-|K&E+Mvli!;-VBh2Nodk^T6&29Y0xMg{Ndj6eVad$^a|_*ku3!A@mp)PDy} zXTxTX)PDD~YgbkU@R=R%G?>BvX9$wb5AkCm&FPcfWO>YkA@o~9U)ZIol_hBGPEB)sg2PPyzV}Fjj{>^y_s)f(H7;#_^6$7Irkvl%_wOse!7- zeDpASI)J5_ncNa7>Q|K3<(mVLiuxlx#&p`l3VoD!Hb1Ok$^U($Mf4v z%?`=uTrNFti%=PI!J9~~S>Gp|cTb+X$Bxgsk@)bpeD77lXJ^8H^6RBJ0FRjhf+F3_ z0MJQvx=w-GTcSn5%$}>>ox{({b#dq`Nuj37GdC$=moB6O9IF5W($_fEXfIPN z59Hu_vtCpnZ@-Ed^H@>d!^m>%cNwl=HS@Hf{a}#vS-e1gbF3as#n^l-QLW_2pBL7ZnO~6DvbxmLugSu#*MR^4MiD`p zAnAMv6tqmH0WSy#FtB&$3U^y?WfCf}*a;l5neQIXr2ZE};jviy``CzVf{u7SY1GC?0)6S|g<7he7<#&&rs~sHB?a$z8eba>4G$kr*ft%hJ~UrFircE#k*1rT zU#E@~R^?ara%#p4($o9q0~oy4B8Vo~Uh>r9n`|+~2K>i4PHH!`+GS<|QN*J^9zEA2 z-Pdc0jSea2fP@IzD{Dgb(-)Goy19?iNEuc`J_rk@7cBGI)Kj6g1vIwa5b1Dx9t<(`k5WG$(^Nd`1EaIeMHN+K58>@_=00BnPK9{k z_u>pM+m-QA?R?j!^&Yo(lBpIaDPtzXDjg{51+U}D89Ny#S)gr~OluwJ)Xl9O6C7LYvnzc)~BOWtb1ZS#xpmH_ZdfuRK?1W{- z1BKl3kFR?habE%QGrpOHWT>HzEG2jC`T6JMc~u@XS}$r}c{gXK;?8T7khOn*eJ3kZ+K8V?6UHga>s z74;fk;D1oHEBgOSsR3%d#)P`^S?d+P7ecspb)sM3i}^PY8f^% zOpqSNUmpBDx0A{U_Q0mrd_0pbf&MREBPKSM=>=t-!>fT%Yd;G?8=w64WRiGSH^5m%(=6emBxwh359@Tx#(kWMWG7v zb|HC|gh+=pB1pJ%M1FYi&;yCPW&Wr0B!@$*5J7V+#mOxzViqCGF%SsVDFuJVr;m8z zTvOXL3W<%i{-brBP3-9%K7_o)Pi?Fh4%6;172=CdnoJ{ILiU?)Pr{*)1EEU@Jnv8C zBS(7{o~E^NqzNq2pAhb2s~j>y1U=HyX4{iwPPH%~4o%w`W%~d7jO~V}(F;OWGf@ct zGrQqy-5F|8N=INDTE@Z|bV&XjcaY5K%-qz1*dsl6zw(QH)Gpyo4y)a;9yQ}pL^D=n z4-qJ63`P|ou!cc`<~01pdfI%20>%^$@-A5aGzpP>}X9Pb9A^X zfo&BWfEz$D=h_&1U}h=pN!$1q6oamfZRKWrn2Y2uJ&f%w@^?eRE*V~I5O`a2xp%up zE*R{e(D4=ix9O2+UKu9nq;Dnqj;TU^Le~9hL;AwrCxM`F2`W(&B8|7sA`5#^B$m+i zmjw`Bu>9OAMCuS?(?sjh3ArAypH}T!y-dYM_AdPspc5s0n zYV|$)hWhG}fjwNyHuK_e#(cqB@cUG+!p4-@Ma*&H07{?_tF7_m>c^VQksK&LNJNx+ z*kW;`pTXz1{60`TARS&>MPxD|uk&ilal6*Yr%NWWE)H5(_`H_aU#R%H(9=C!Nz>NU$CbumD)7DkHY_aL?lA3h<+;mVCHkO9pnJ%P=QyGQS8Qx%g9+EmN-aPkf z@SQK8-z;kPs$3R?Y%nvB2by1a#d0mul;s5uXNaq{_vhHevB$35cDy@s`&z z@7cjHQaNLE&1EiJgqcee7d^HnBa{lmw#Sx=Jb$~&zrZw*HO26rpN^VP6Vp+u{zOvi z8NSwn8QJ$*rV}x^l^WVz$al^a(LXqokASc?=a&H4MGZH8$=7R|BMZog(W&6in1MBO zJ>?)M)WP$K>;`A`9fm4jGLcGF$BWg7&vd*rU%As1VBE@&?9I#2Dh5t5(&eLNT9o(c zfcxD9Pv2Q7FUv)2kn2dzX@RKuS0hjD$4|7DA|4P)?PZK2@Le>K{z>`g{BwyLtEFBm zPH^9yBR0ew`0!hzk@}$4qw2a&l}50_nI~gQ?r|Y% z{B~(P(dKp%RXI`sPjbj%nbBthQlj@)4jsCwY8Fzr0(G>=1Ff*id};EWVDEx#t#x=a z`I?WoZ8>UG8ox!kcxfpgYxZ_lO0dDEI(5>6?VQ%(B#dG1O4QI(zZ_aD1-HZjV14kg z59*Sxkh>8Ufi`A8-Yd7H`1J;v|E9`kQw%dWYF$fj7HRu(JO!iE@{@1O4*lw|Z zab@%5s!00GQtK0?l1#CgHbA#Ve(;P}ZM@PFY5YQ1bJ%*Q6>jaHb5_PIBTg%WnW9&B zFsCw>QE#ilOGNuJTT{O_p>j59@Jox}_6z|TwieDS+#x9|VN2*YLwsobd;OV3-e8gJ zo*cD_<^NFk<}v9xt%Nno2n)j^7j&Z3#tU)orR(IrxVTLs4P_Lu+j$@I-X8Ng#U zlbG5FZ}bwE{X*y&?Z`dWiHuKjYS;z#h<=g}U4|YPII8gBLs;ATN5!+8;7Kx8M&;GC zRz`&@9lE9mDz+7Ux?ba=<09zTw@&)8mys0XN5LrS{`kkKOtQ^p)|ol}ojyB^Kp~Rq zMN#nH&un2^9o=k`=*<<`99;TwB6HKxr?5`(@U#+;SU#VRWPH5KnB<)al)OETk7;p> zTVHSRK35E*=r@d>uo{4xOkix5{6#^W@;SHU$kHuOp}`1H*pJ?}J*}&`alGvLwB8cz zF_5dz5Z$h9Y7Yx540Wx6u(9j6(TnPOTqD&@)VZM?VdV9Z%G#LyEZPk0CT5NOSd&xT zTV#i6pD6PeF9bO5OC4Z}3L`#^VEkgZ2jgEB*lCu}j1ULygl2Iz>kXaW^wtX=pc#|CsKi$uZkNa_a+NJSddZx00RJ+v;!rn<1gmOIEVlM5pV3_QnTXl z$uc{~n~}{(O6Oc_(-y-jsJ|!;q!@Y^=f#Q`0<;o71L_LEQ9+i-%YHxm;6xko zbUW)4)dB3iPXLQ=Qayo=i3V;>rO1K_QpH9#(&v}@cE<#v{mbBqWVQxClLG9N^?xm* zes*wt!BoG-VhuEX4QOot@S!*(9Zpugj_UJO$WH~GKm(x`4@viR{rbB}`rslM5EdM4 zn`E&MvX$L!?=PX*5b;N~h7t~Rey*t+Rn*bI000931OSM$q)ZnOs`rRrV~=*hE%4zJ zexV3KXsmF}LV4hJ|XP=m0V0Jf&VF@#8Xu=1jI`d;~Y zaS2nJy9X$*{?f*Trs3kJhL!LS***U0Js#wDT;yhXUk7iT}($^|M5}2@Zxk6rvuZ}=wn6V7v|ie1WR=p z9Rfmypl2VT<+u4|jQByt8{0^MFXj{$bDEDa8q65j)b#zO5ct=p)-c13mCiiA%L1^A zy`L~kD5N3s63R-ONG!;i6GaxH+KNNZwukUAxaq&dhyVZs05#Ia73;ZKfbm8>c$JnT zsLoB#46H>I<489xehO4Hm4Gt_(+eDsJc8wNBHz#pB~QR zQpM&hYme1^^6JeRilt|OZmL?|rNVaJsW~`EaH2Dpk97l&?4EdU33qsRru{VGnvW)( zf*BbL|80-dgzoIKQ_i5xP~p(;i-fq^3Jn*xV8E+0(Yi+04~GgD_fa15MjwxqQP+=-lr{hELj1Re)c`YAXF3Wg}Qh z!2ei!%co4}Ul&0eP%v7NUD^v@y+Omrx%3nbXYEYpX`*A}>q3&E!5E^A277xA2&K|b z`t*&jdmX*sPYXBR&bZq%jz`mcBmGL<;m}RZu zJC53EKOs$a7Ws+3Vw#rPMCrt`t=BbqB*H%GhB1k;B3OHE_Rkn~-Z?N@fmX$)*p2xj zLL}p6PKLI$i3=aINtmAGRa&0lJJumkFx?kz8Ahhzbw8~ByVcxGqKqn@L+};Y=!Rs0 zO$V)Sp^00OI?d|YEl(PIFGo$2peADq*bQ_Ty!=edazVl#H<;2?VEhDId)Ds_&9hJdp?^MUcdk&6vayDo8=b9Jf>Nfw3&VI{AI`Y^vN5RF za~s3EL>k}8v>N*2#&`3s>Ir8rLD>vfD+msud@Xv1Ar#vGI;FYdv!jgQAruUK%()B2qOq7 zEDXVgsY03-a1)a}YKm4UJ*{&DycIG#H^>P?2wd!C3uE=k|*D z87=P~02qC!uhu&;0|fSdjyPA#@fduCS~)NSAn4Xbj(VHKaAzCJ0g+I-MDVJmM$c65KwV6BdWnN&jN0dbO&^LB+5qY!+lhp)e7KhEv(k0Fa_V z8uhEk7ZSZ7nf%WUi^RZIbxLNf+wj~(8N{=-7H@0|0IW(%P~wrvoZM%7#`3=Uh^9*u z3%^oT&S|$$w08otXSzDQ_ozZpniKmUO)HY2|Hmsw)CL(xRhn2FQ=#J_wfA)q6;=B^Z(N~MO<_fwz)_!G8c7Bw*6xa;Ez)$%B^0wF_L zN^k+o8yz4e27(ad>cGq`qR#V3G<4reZR z7k75)R@Q+6U=|u4N3Yc*M}ThCnAx<%`j;XQLcr=nsjFXt`AEt2_y)0ygRx+2TcThf z#g;rB5KpiuWI5f4O1tUrJH`fX^Si3;EdQG}Y&hjFssYBS8P4 znapxbGd|7KBjO$KF8#wM_g+U8X~V?c#pSfk+veb@mOWG1)n|$au5{;I2};tehbqPyA7-oKindUIc=Vt{+d4YP_QspC)5xB%Wja;)@`8V{GVRs*Yc zyk&mZ4G$u!lNuoj2<`#)k4mcmY~WxK#k6E?{--S7x`?a{!;dxC9Q(|OOeIVaoZ6sPo6XnS4cMaV?#XUiDNX2sSoMK9ALm>KUcV zoA$)z%%U2KySI&|8WIEOYyPld=Y1D#9cb-Pd<-DRKgW0bPX^-ryBf})N$06 zkqzK=1MjVq5U#MoK1nudKm2X^G0&jK9~2TL@o+Ufcc(O6=5d~s?Pj?9;{(mLSeu>? z;4E~swMi#SVvR`M?|8G%rtuc_DY8WMYG-_MfB-}?upQi!shxr5#Wqi$D41WOi#QlA zxIx!rcx&G+hAR4XriGj)UD9@B0B-XBvZu^zzA~ARiJ1>S36r-1r)EZ!l;vfrt9p(p z!fr%-1(8mwgg5TYsx!rFRdogYSYdFO|IF@h!Qt9_lQj}-y zA{|QtcEQZ%9}~`yr;-HvXigjSPhVfG<}ut{p!R)uDeZZMUSr^sUGIaNj?iAX)3|zLBt)=Axw`~`;44@ph7Z;z-PUr*i8Xd_5NeG zN)6FIVoG#Xky{4vNm5*+NIg&>ztqC|$;c=3k-%qpc7xrlSRMTJ%MoCy&+dGno2k8J z9#Pj*5tXVTjQj#?9V?g&MW;rVxVrEMbE$}reG+xCUgFAq%i=;v^Nd_GN@2vWJ%aa* z_HH$36Ca2z)Fi)y=GtFgZXg7D5?sh00MxtarbOikWh*fkB(rlLvx?CW)Hm-j*m63| zgAMGvxgI8YiUtYJJ2Y3sB}Gw0_@OXSI@cJ0fs<F;Vr9qnn|fUs32pwdgj^3(*?)Ti2=r)iYN%sJJ@kxU=hy) z0P0wYifXn1EA7*cs4LL=+GfZhvi+J8V0M1&v7K9wXcTdN1vL-Fq52gt*hh8GKh;S? z;z6|t7J~4-E0TW!6d7OMX8efA0S2XxoBX&-{|1MArD6{O5+I7(hf_VlY55JV`}KCeo^6fYjxBoN82r)WX3SmV64C^mQ&JP+M%9*#3jXPuqv)hEw*tY-s!5tvC1)Vh429aUbCuzmefja=k2wWBwF(8RMoO=Q2 z_Z{7u?S(Zy3ygzoSTsf7p%`qOSndB+Aw|*Lu1x~$WQrL`$8Q=T@rOO$-1WlFEv9X! zFaRAbYtI~XAaAco+r-^IwkC1>2!5KB{Z3@~eB`6UO6qK*u>L-yokr@9)o@8bq+GOj z^WZh#^v)DRgX)K!1iE$ zn|o-IBZEKyL}@*1^v7j5gI|Gwx~?X;Q%{Hm199KxHC~x|%yxcB{=g-;C7v6a+t*s-~XbNdRxtGRRGww7Y>y za1umR;YXvN8J%mV1Iz48F19DRV%nP;=@<;8MV5npmQtO-%Y#P(3uTNR+EJc0zrt8; z%N8)i29W>&0{{tH!~*Hol16kb-3LEdoQWhGpd_12vdky+0>4Irt-zOdOuZ~!9CTOA z@4S(?l$)$A=9@p<{HdSSfN$|o;rh$)A}+$+=@nTUGZ}huzu=X8w#0-LF>zLcBZg=f znVpIxo*kltM*EIF>#sAsb?k%82JuyZ|Db;RKt3`JXEA?LJDTYE*ouaZGI}>ZrToFJ zNGC&+EC2ul0E#zywcY%0K{_;l?l2mclw{X=8{=Z{s{dcgsHld9q_|CCb1xP0$-j)* zdP1+^rD~g{$)h@A={}DyOU1}y8)^p-Oz9>>EzaoM;MId6z0ODcCrL}m7=YUX%P=NP zQK>Dsk^&C9=mTDZ>{d&~yveC{Wo%NKc715Av8*td+-^|SDkI$mZ{iWvz&p4bV?B5C&n}7?NeCCdj*h8o6cznHwZ=J z(WlfF53>*jKXmI6MT}ByU1cn+-(sR^&sfPxqtcXw=9^ys>&ii=d34MIMNQ>q7EVd? z5Qxez_~5@+%MvWH1h+O0;PvR%FZ)%|_V4E9-Z#F>MgkY?h%BfOGam7NvFy{S?h`p6 z00E0+7$oAeIu*a$@^qLck8g;9chz0RDenA4l4IGn5vyvGyXJLM015d-QLlzrN9tZs z{XK`dUw2cO;&nb{Y1-WwUgksFoja>^(BlTDad6q2w7_YR70U-o7Eyx(x>9D@NM9DD zNwoXSU2`)RU4+p|CX5Q8n8H_vHbeG&Z=~2UY?he~TLui>ce%N>Ys&w%m^viEF%@m) z#TBPNR8QW5Rd<8R;yHY2VvDvADlMp7*f<&7h-7IsX6=9}){2&_55PD<000N`$%ALL z@6hS@1D29;)5p3pRuqNoV3Qw~g~WXV7>(0??9W*-L?!Z|nZ2QsaJ>0dNgFxfBoN%E zh$~-dFo3>XI#7A_kpg09|NdUy^z~mArPQFWLM;~FL+oHtcr143XTp{v4Qszyh;A3- z`xd?7;rG(1(bM~=YduVaK#9yUbc|SN9fY~)J?0}((`Q|zYbZ3g+5(xV~H^muxSf5=@pS(=wT~9k-D~y zyW-cR-!F*Yr{;*e$E?_~53r_5a}qSV`EHP^0X?o$*Xf}Ez7PCSoa*bQy=TNe6>lLs zNo~-Mm8%QXTG3|*o5sAA;?3P@u)a56FOn8v(r8DY*H*5?bIQE8-`d=L{nbO`4=Adl^5T2Z#d;% zYUrO(?Z04$`<3GgH5H63egj~Z(#+ugIa#tBe>Z7fs1THREO;EJ=ehH_2HZK_x0TN?mT2JGfQlNjy>;9;_J0)^;jS=7Izbt^O zmurfbrsvZBnLpHP6wRxeiO4yvjplccYLa2{h;O{qcFYq)O30gDY*8Amo&<6Fd`ire}4~ex0rfO5A>U=r>$SA^y%pUz72*G zd@vBeLv7Y{Q3H<>%*=QBjE=$^T>Wgipqbv7za}2cg-<&o5>W`n#tvPWi!nk*#UXU< zh>;7+1TAioG}X1Rl-0ve@^iMlp6rdr%v+03E`7hv28_jW$M)CItfJ^Jb{q1{i)2K? zed+s)QWk(T7_?y|nxJA_x&q7y;X50Zul)c^5-G_j5kCS0zyJjixHaLK<;Z@{X?-zH znRKDpkXxS<7>mbtoN^L18D7v&ttK%tG8q*|gyVdaGD+*U@ow}X|wXgsHJkIVSKUumVEkALv2XUae93Q&*qI zlh}QfX{=?Y9F8&)<#a?CQs0^!;4B4DU(AMY++kK%5kor9ii+^{ku@uJY?PuhC2dQ& zrb)N}00wWz1|VA(C|=z(c8DpHa$HmMbf#hQw8LWiz^0P>L=G0}+iY}i*n(iG<$p8q zhiUAkCnAu$cBwi8ne<;^kT|sRTcdCV;`1&W%QW8GvFQd4c3v#wV^>O!`{gK35@_3K z9QPxg2(n~&a10luc~+$aQXYU;p0q5ew?rO7j$^7?j4pCARy^l3779rU7$(s#N~0$X zJn-_t8$rGR<0LV3JL^wtT6#7h%*>TfyAc8V0t={lE*Q#D%z~8xM~GP3h3Ow8}#EQw_KE`=6tE=H9{-5a+At0uv$O?9Tckp z6E^?@v%6kW?vaP9ltcm4=2L8Nd^q*FtlZ7pXfcPwOVq7DC3;Xo6;6xb_Wnccaf2Tl ze*iM;r@-MJ_pRnnYa=p~~l~I$EDDCaGjRzs$Wk+?y zTxq9c%p6g~l(E|_D=@=rC+Vxa!;jRoXdV)qW;0!5tZyl`F;KU#yurdcXpE&)W<&^W z>@oEZoIJb&K=@F9vK8v^leIo28JE8eL-3dY*@%&@Vsav?$DwPb^X^{_imwRuO2puw zNS1-?an!^kS12EJ^Wz49dE1heDPlP{YG^@gn^3L#e>vPKr3XuS5I-&oqYt2wP@Ql9 z^X)Sgq+=-s^#t9c6ucOL*MH7`UkLzyUM5RQXC_!_C`N<1$>u%dctstq={SjcwJg^m zq;2QH1N!5+z~=5AjGEacYNQ{w{$Fz`r;l&mw&|??NK%D9<7EOP5q|Jy$B941SG%F~ zkic91W_P#t*Emrau9}V@f)khkj(hu1zJU`S5%I?J210S8sHi8!;z7h6XVE`-D2=%6S`GzYzbOI`KItfeHm9urdSDO z0L*2!!BwLUgOr=0;wX~u8Z8ku&#X*xXSuC$Vq;w)xy6Ae7ewQvFx;m<{|KCu0HAWz z={u9ss|hq-E~f|1f74h1t`t>J#MVY?YYk(Wn8*imCOHS9fk38=4Dprql2Empbm!4| z)WrVW#A>lQco?}DzG{hGES#?=(v`CO?E&o&4lqePVdkuCx_&8RNtqHD{KX)zwC{B<>C|qTO;o1(QxVh+yQcySCFw>wiGsF*+S;;ypr-;xV9ycH#?^izOft5 z+itkDOLy2h#NgppMOs@9%;9-Dcm83!>B+M)2watpe4HZ^DYs# zc)6nzfb^{id*5cT3p?n+i)zjOa8IzXMhmq)U4n=)wB#O+|M#eYF_1?LWJfFPBEauT z8GB6Y-$j;o+)R20B_lD`O=zR1H{^@JTcV%v(tf~jqcUfLo&S^MQ5*!;FPNG?*BY!i z#&9rpc+?c_EeICKY#Ni#wp)&9(p39>A48AMuYEXKR3{$nCc<*kLD|aw z-v|`>b+F|+G16sZJBj&(d4RaNwF6U@I=%1T)JiQG51o>z z+K&eGa~z@&HN_}0%Bp2AMvHUOxX2QGF#{=MC*~U&j-K*ZN9QQEj{dKOnYFv~ywrx2 ziaYV+)8RLkgpVPromFk`DJ)|c!W_R=MsCJM+#f75pfNLQWyy}tf`~M=+^VYx#Ry2M zuWb~9HF186<`S+zlro_zqppCYUzK~8lavfWDxXuVYA5s1BPpwC?i9l+bTw!(5<5_; z<-i?k+)t+$Qe0H2$KRz^s3&=odL~T5OnFubFIH9RzKu>k+Jw(fB*n7Yzicx-c35`83v2>_-6nz&cAAvobi-UCqA>$1%5w5 z$q<~MY>fT;X%^E>U+Dsy>988Re_M2A#D9_&oD1+ zx$Qwkz7kJCC>W0~&a|b1^P+gCP}527(Dz-Rj4&tk5)7R~Qq-vO7H|6tyn+5MOkZJ? z;c;>@@mAjp33iAKdvwzpEyK=>Npg98KMe6{eu_QyZ#TLnCMf8xtCqDB2q#J-jU84X z3iZ+cO?Aycd?L#$=9EY?U@OQnRP<9{4zptRNO@Vf?3@l|he|&yyyS?m-*srP$Q3aN zVRWmk(T?+r{$BSLTIhlbC~-{*Y^+UudXXm6DfaK@VGOJ%R{^xI?q}w#U2I-j)Q!JE zTl3Dlk~sJg#t95TbYKLN`eK2Sa)u$Sk3Q~8g%!ybzDbT1TA4W>FS#9Uw@|-E2Bnni z9=hnvcTkMp>%Ad7Jc<@*nG^xwi?i7iTj9rcd%bCdrbL+Dk^%3<)#(PUV74LXBR3Ap`m6tto>#P6ac5VbU5=;n#?*{CYB=xQB6DsKuO zs{qM$(yLPlNkIZ;`3oJVVB(CsGR5x0*zmCuts8ibJB~{YM)5u@4MA^kry)4$;bnR2 zK=}|p!yG=NRNLQ4x37Oc$iMt~; zapV8mDlZ%;)X%4=_YgCny1^3eZ6fIDLw?Ov5cTs^St1J?E=#rTFvQ7~FkGn{VG|8l^Por*|Xr;*lQaXPlBjL_$p z2ZdcIt+=ZFM>m5TVEz-^XW}mJbD&Y@bprs$9-bymR#!p%o5^2eHjl#&ycStztP@?c z2?s0t3;vJ)@{Iixi=Uh!0#bW=ew)Q`HgxR7+)NKNjZi5MkAA~h8z|^Y&P_SgrE7rd zlo(q}A1tk)vY`*({5%KDbm7>+?2^LpNE`HJY%RP9{OULJ_4@5003Ha$IGP6h-bE#9jbaM zFHbg0iRJie5`b-iTaIfumD0P}k`l*4k?0hB#1;!`om!x;zB!_G2m@Is%iA);AvRu7ob*Z&?AS^%q6jHN)aGbe-fr4HCD3P>yPc89Z zp!I;NLNK789VLT#^?z*9I%)CCUIOHGWtoOM9#R%EE2ZY_ph35FFU+h9Avhx5PVsIaLoaM4t2l6u z*9+rgaT=eC&?|UggiE=H@wlFY7B9m3NQO^B{F4l~+KO$;7oY?xOKS#A+(>Npq$39|cg5>s%71=U@j2SD>1NrB|z; zCt)ZCk%>{)D*AGZ6W{;`vkdbeqxFJ4EDiJ3~hvJn|6%n`& z&8rv1F8Zbh&&@0qCHePt7^I~9RO|S;Diu}#R!c|t6%?EVWWEeFIjzr%dpBfX3^no$ zoWT%At1olJs#PEL7MAE&2g#ShVzU-OS*>p3(hE!1S`Tfa!8Z!6@``iAY{r0;W3y9V zk2zN$@ZaWg@O#T^NcQ5xwyjwpxeGca)=pA(g+)NPlUwa=9)t@PfaSw8ZQdMUN*q)5 z=u4ZHL5&ecv#&0nm{-YoHfA~u?9{~j(s|0UHCSqowOfS6M+615yVeUMh(WY){P zG<}~Lw`|l800093grjgFP-UJ|^iY}?t>yR?UBjTo3GKiL3b~e)x_zP1iZZ zOnEIIU|ZLx<%Xajmq|fFt!E(1Nm?i?^H3z3>+_ac3hesV5f1ffLR~I0J*Bfu(WI6H z26=u20t)ne5>vbJl2+?+5d6(7e1U!Ea2bk1eQzx^RxnaAXkreUAv3t4cW~J@sCfqn-M#S z>8%>~#Gn6Yk*j$f62PAR3Kaysf&xGt8Ye-PLhy1891mSHnzLpwp+T(F^!+^>!|h>q zrQAdaA6*rPs$NUtY*U|-Q1tj>x^=Fp!4VD0&?f*`1F9%ptc%gM-3Kwz>)aJ|J%|~k z!MBCe{rRgLqvNCC)Gv>w(V*E{|4h7(KIxb&zQ0;5eDyQ(^FtbehycRv`M*`3>^?lA zo!j3=tZb$J7?0<9DOZ0W2bk_etdVSMN)3JsZ22k?vsQfy)JIxj+U|0tDV1!El+tVj zG=20GaJ1eRbL6AEK?x-&PKas_9z7?s%+-aZe6bG7j=pIiQUy(q`RAOc*nj}cFPRBZ z{BT8+o$|na%L0FAY^lXA`wL!fXP{fH0LCTJ59 zfc?c+#*Ijx$BA_gFSQ90P|3-=6z1e$ag#&Z)8dZiC(=!;?uqx|$Wz{p{-~(C^l*L2 zxXSe-vmxPs$gj!xQdv9(o=#&X#XRNKd<;sD^d(ATatq}UKp@AJ8#YtImhr>HDmj&)POjwskr`A~@{A`2ywQu!(p0uftkr#DYmR>q9?04)2J zMRu#WHy<|kb&d;Al@+z%bqjye;r1{Wf;Nw+w0iM4qjE0Qs0t!-b>+-`8ylls2%`b# zm0jKE5+dYm3zgtbLV7JV-~$T_^_jn<*;|8XVTebF;TEKs>F@vm5?y~ZIS!0F5-Kv3 z!xAXSM0iGWd3~^q*&|`%1)lmtu7N5Q+ntfPs8t1kOh`0|ndQ*cEu5z9S65TnQ)D98 zgd3UBZI;+GQ&J}z6lv+PLYzay+X{lY4vz}bK*g9S*(I}~mTSdz*qkg(3UNJ>G$8qp zf-qzkvx@0J%1u^cd@VH03k;S2479rFED0C|Sc>GxPz^BZc`KpVnn_L(K|K3dh9V}o-u3c)}jrHdv0K}GpzSHDH=P$R@9;)<>k zvZ(uryv(mn3x?^h-+ZYXZ`jMdWynPe22 zC0v~!7a+rD=F&0M_jU$KZ@g4Q8bG{I#}By7wHq5K^q)NcAVAU(H%y^G{p!3!Za%mr z7Cm1IW$e1afw67SqDz3z%e%w)mQ>zLxO??=^yq4lr*f{!?I2Ig`&k8H+k5P(U5BuXoe+1VM8I%1NYgZQGaPCMQ%wH9G(R0{{&4D*1Ue zQu~Jq>|MRlLCh?;{N&DrtCG^!24~(39?l1pvjMulG9*eJPf9fUc`6GMSaws)oUQG+ zpsU0%co|>6Y-B9^sud>p@n42AzC`kJmA7vy|LGt5(t<2fyZ`_~Yg?*3uIq0nYNb8S z1lLBJJyej>nyygjsNP(RIJl)dX`aac-A9HIp9`+>xeTp3eeLZJReIp=rBjxIt&;Y{ zNao2JcBYR`HcvVvGVge}`$$0pN+0s(MBQ{0zZ|o+aUba-e-BCK6x}k}_w$X|I9a|e z{8Oc=%a=X{DAXQI;?Ojf^xB1CY#&3-Wo%UzbB(7s{j^n+6MyZ~)hH#XS>j zLH^Doicm_Rlu>xQ<%#ie$NaZ?D>INPttL=4R(Mi$dzletsnrV#(pA6d6z9@tY*_Ug zA-L|9^yH{p^BM0SKa9 z1KmeJGosE6vV)}6gam}J8%PWp%klanGK(`WI!=2}B7__t+H6gGSltc{<4Ma30 zux6$FJPCRf`AYN9p$6V0K;q%Q5+YTq{{HO!rW5QZl+BQEoosGg2nymFg{T505q^Q} zWjm{*SM#4It(=0V(PsSvMKt4XAuX=2cnVK@RNHmzTYM9ab!hLJw<&)2w|y*e%^P9K zz2*$d-GA#_PWXuuPpcT4SO-^WUkVW15)s%oY1myzVQ_1Nh9UpJ`APyYe&Z~e{#+Yg zc|{AM7oIi609fTZ4jTR7QbTm@1GNf4dQ@K67Dd~u)zZ@#@vem}zyJUP01;(&6E~@> zQtBG8Hu1RGssb;4o4@)lfV$VWE>dUq_nc%V#K@JlvmFD~y-`tO9?fo!$gONQVqaNF z&lORAq{=oCeM*)B%0j0G9vc$3YV_K1JsU4UaP}N1>}{|r;+aI4T(CDx?2-U5_1(uGqU^uxroq z*!o5sZ$RIoQVdbDrrJe0_>i1Yh}!ZG2T?7&7jGd2gux-u2JB3Luf%$}Qc7oIJ%^U{ zH56$#`;B{Di+}(C0|22^ZAqy@f*Fp!3krF#Q4D5kNKXmA^K_1Y-$`v+POqvTqoh_s zs@zn$7dMdKuSQ&K)Md&!uhiTh(Ja@YCWX$E78u3Zr7;gz5gPOg8a{kwWwe7JNvO85 zqDDaZ?vugrq{p>60YRL*g#O9(+@4!f=;qU?j7SzG5iuZu000m96_n8-6|iQjHafEH zGgUx0kz%yAT9xuo{EnY_iM#!C%NT|ua5ljExI-8e9~eA-2A}j11=zr8)Kt;J{L;8} zHw(wuxXH|IM|c&H+jNxAq^3TdxBw&(@}2z2+2Wg+Ul?>Up&FVyw#oq; z#&fB?7+eXYQ=RqDmQM>4HKc$50ik-VyQt}qw6_~^svU#EwIZdToe7xEzz{d{|06t4 zyFm>rwDuo5Z;+~-$?X;W6Oix#0O2Gni<1s%mE`XL8($4qsJ}mVyjz#ZM-T;vur|%P ztamN2t8ii2a{EzvZ206f^KS`tjKW~A;;lZgDGXY5kB{`OFHuk*D!U;{(nb0e8QJn;Va8&NE+>9fB*mtMKtq14=wQ@823q; z)mrDta0sQ?u19f?+U}m$VFe`-kAYhI3@@wY`7ULyP;Qu+ph%3rfWwV-n_~ldQ~=jJ zkYE4+AYN55+9HE*9ZxF4mu-iRLd?o9g!P5@avLLe0C=!(j?TENz@)fd8?s&<=`R2Q zDpSv7sBH#r)*?+9R|CY@obYbuE$ueq6c}Wnpid?0vu1xmj&tw?ktHRGly+1Uw8Ocg zs;A;2yi-!O`*ps4{N@iWT#%Nahv@sjIs-##<+)2opv(L{_2NhWWhFs?uCoOK^;J02 z%gR&rfG1`wiUT5-q5H4(-~pS}XL1ydJj9?yDR=+?1T7>K>snB{t(bRuBUfV5IFzda z7UMNv{7dtk6XzRfcl#IIMV3YY!+@KpxWfPLok!(v5m8_t?Vp1yPlT2cGW&oF$R#r-h;j@{B@i&mP-1Zc0DC}$ zzqHa%B)0X@-Oz+X>`G$f%ESXwr5Il=?cI>8L9|rTI`;aY3Yb%)FxxLc`(Pyb#yK)m zd*q&!|Jf+=nA)t`@VfF4A`l#SzT0Mh>jvbq@Esd)FRCZWH-#ZZ2B;9ydjYs^g$OIO z8X>n8cmD@ne*^!r00093r08J^uo3mNSqCs*_=Gz0o6%noie%`*cEWD6w8GFZi=|T1 zI3l!jm`EUL_A8QWl@6o+cooSbP7!p|hI>opwado&CQIQ6HTK<1dS?z}8Qit>PBou_ zebK~~Rs8!kfksQ7S;=10A62Sj#K)%J&|BIJOQ~_`uy^aGqbkQXK`rKYhLyVtT~mta z>amruakR#C*3NmT!_x8fGtj1X=C9XQNmh905+$0HKH z)UAr_{|lUNZFsp#=2S|iHO`IM8TPmjaEv|rQM}-OO&9Ghb4lL|P7aR@5;t3KJ{bwP z*GBi;@DQs+0MLz9^Pjd+`G&SYGUMLv02T#s$Apdkv?nztMRY`vKjnTiPNJS5n~!1k z&NEh@nB=DI8v98sV-&IWfV{3YD{+@hhLZd0Tu2Qa3Ba;$pm<5KtDz^Y2hd;QF(^pW zFd0wsGp=9%6+`GCPHe7s!~)v#lpWq!1^w}6NDwv}(oo_Qt}b+XGCtcq0qoRirny}t z^I)dYPa^MnoE=9^HI9y|BA^|%p0pCXa2)VtOXsIt81G)0314PqxaF&sHC0}&GcTUvj3DBzau~O&HkbhFCK2Rz z4Dk4p<$WM*HD%g!57qC!NkxM4WMru&rbaYhzPMrB`~J;!(k3sb>X&qN|FTn(<{mL+I*ES*Yr7&T934}B7p7mqmFOu$A^gz$GoS5YgFMBdc&b7 z%YYVz{wsQ6ci3700|Yd5W?PPgUx>O=E+HfF_CI-SLUk;-#{3@{6*hk_#KxY2))K&+ zovYrOtXY<)p|tlwMJWZSVaud=B{fKs=Ub2N8}s-{_WwJW$|ByhrO7ije?@5V5am=V=(zT{a{5~%~6aYE_K6kpci|zMarc! zZRQwKD(E4dS`h0lIx2PZKti0tPTdP!1oz)R;lXzhPJZsZ9Bbt~`1R>FX*+P04 zaW$AA@xeT1@PzC`PoSMBQ*fx%EQC)+E{fCPSE$85^n=V0@NwCEnpGwE3q^`k?%D*& zA@$)RP}+CSDGaRacu?r*a@MkE|26u!E0Oa>bjQTfWi%;eS@k6L3H{Sac0DRPSZ7`*Z+4W@x) zBgr{J&AE&ej@i9f(Uo_dqv&?j?JK7-G%5}bqhc6OKr(CKbrw#r!{Ws8yU2?e;~vFq z0L~E^rH4xqvxJj6TiUD=5D(Dh9O`GSj>&gf*F6KS#ul zJePF+=+15JjcSO_1^|BA;OBq#xeQ$!OVdWn>{GYu(U#7+bT56M`shUxB^vGSzTyMk zlLweoDM-#2z%Xomb68MK1Q0|mzcoVuLF&WAF_Xxw!9IX6*~N8I*wS26Sr^j=?SyEn{pwTlKcggGr!vU z)l&*0SeGd_vKgRDHM^=H9uhC%CSNOvn&dB8X^8m6h7reMS~=;E!tMo)WID+5H5b)k zQXfbV_3+=xACUgUTR<%LV9lwck0*FNiH2zs_@i3?1F=5O=!;6;6_1z;x;^;DLew5# zRqpjMVJpq=X<{r)A~e0RW-aEk+|LcG)ULIo)X)RBX;bfmN z7ITp+Of~cBs!j+DzFDYaqS?m-Ir_yfoaBZR zFb>>Wyqnegl*V{y^cZhpmR;{s1?cgU8VDBtDP%#Gtx2iFvBbg<0WspmB?6qnj1TBI z-6VcGt_LC!@jX%4>rY3JV%n8iZA_=7*;jkFp_ye{>JbUgoB{RE?Xw&x<++XRfNaG_ zrnTco+ZiLu2|$4UA?G?eWb|!&d3JY);WTA5%3mxT1QFI*^Yu7V z<6~NKkP0M1Tbds)EXewqAI2c9NfIwYYif4$J9o*~Z$=Dbypze`A7z>MSbt8mX)5 zxB*xsHr7e^{Q@I{nxm=AEvfgu%b8j7N72JBdCwA# zax3Is``?XhPAD>&zP-$NbU_k9ke-Z8vDOv4zvqWKL7g2fwa$v6O6F%Pq6a@JOwvJU zmPl0)jV>rB;eajYEsV-6T=9&0-|0LqE30E>C&H?hEZrSjMxo3;{_mB~R`_!_hQ_nQ zW^YeZC|BtQ_B4@@Nc0z>Q>|g~9V=g?AT7I%Zzu|rstop``V%XrI4NNVpU?o%Yjkx0 zvq*eS;M1Xie9T;?PdW^O@dL$#2FVAVc+U z9I2v~A9%F-F=Yl~?uW&s4S+Ey*@G#I%cuR7TYIFE5@t3b%L73wq#>EYu#D60Agi-LyXC!=gMz&T4nof3LJM?Qn}oQQ^YWcqgM+$32l;hgOy zg;?4k5BtLV*QvyI@z`T1nsDvpt)LB5r$tonY?SRIFDzfxamJJ&2+Kf%PxWIUr$&;R z#BZBHgKuTbZx=lFqP+-Oq;BxeX`A-`o*%)7f4sj3GiyG!Ab@6QCiyG9g(DD)ayFL# zk%xX|(7nbOYFjOX3vOk1acG_J7-u0a&bYepWv&YnC6pxqUN)^c+RnpX_~G|Myn~Vp zNB{vHk{a01;cB-d_l5ma&BP^DR~>8)a?&-u#{47|2-K<&0I@!T30|?k2^0ZLPz<6+ zoN%JKE330a>X;0XQ@FeFYXW%t=v9<*|ORasG@O`xJtb@#SiY) zzO)O=dN=jUm;yLAW@L-2?@&Y8&^s`oCLri+8L5o!?UXBie#l$5U*P=4RLzlmZxUOM z|Hf+8EhpE9ST5qspooX!AS$F$7A;%IWQT4?ZL^MxM~VS8tt8@3HMgqX3PB^arlM70 z6oKbc)8J~lW2FXeU^NE2y&-~bvjWzxYDw|VWMRUK0;4-g1v@F>CTU5Nucka~yRE5p z3O;VSDBE9Uz~z=~Z`}aIh3z{6f5f0JsRWO<-8n(U13Qj*hTvp}(%c?bWI|NISF%NH zUCp$7lfSkRMlua~|GuoDE>PY;i2o8}n#3dg9-l=?8xwP9N*8Wi%&}KzhYbk!WNJR& zEa>JeHQYak^ScK{YWe4$Rm9$RA8;We)pxde&fnYI*_aEa7A!}tHw?h^lD@(iI4yh%w=^hK|llKC4VG{668-iF9vxHmuIm_r3Np^Yzdc*LWs5{v+dI371QM@a& zVW1Jut27GO{!-V%X5Ynz4ikn;BX&ty64}R6?3>Jaa0{Y_J#w<=qZabH90sx#%d@cW z&=lMUisT~|1v&8~RC9@F*_^F2Y7#15cOM!UTgZjA|49!V2cUq!l9ZmoT$7Jn3g1$O zh=dt|O@hZ67c>;gGMGdG2{5Jq9JvI*mXA|H%9TCPHfVEzq@uc9r6r&OZ4Uf!z~)8$ zCJ$@4BwlW0sq90t%1+-&5>SX$DI+e3sc^2DdG;el*kBd*GkoBDmt1Qg4`=_l?- z!055+nXYJEAjvSo105=Y4Q0Nt+GU{$t&=yXQ^g>Ur z(eip}31t@t&gR_jDq2z~7CxnU=?RI6gt8A+MqfTtfCbN8h2Qbj2*wQFL$b$8&Z zt!EAIjHT_jy-k5)oSsLH@Rx!Cto2w@keheH+3R?xm0kG+kz;4~rO0nM3jrHk8-S*( zOV!C+b@7x77+eUx-aRBNFG=$o6_TDSmAt!`NyA;fzx%m1Bn4*F0_P-+#}$dJ@Z0m7YAS74VyI9%8}Ymk}9;;)WGY zWdIz3+$yzSpm@Mo@6E|qGpcZ9EMGVO;Z?6KIeP6@1RYp(ke8uvl>B?Dq#~J@DtMq9 zcN8;=+o9w#t|*pv`P-&P27SV-l=>-%9J$ANn@UxKtz3eoH9YSWCIJq& zc*G>~)2jaF(^@`xEp?F>HNS#_$c1iVA*TrMQcVWTi~CWu-H?E_?j3QgeSRoXA`F6l z>6)%RkLj>>IqEJJ;f`j;FR34-BOrdYh#=DYVpX>cZ2$l)?LnF`Df|c@OGL_G0Y3#tk5Qdw;S3&Rhu0e2 z1vm0K5~v9QGj(C+sCQsm4N*BIg3d@j*WP6zGB;w~2lw?9(gKRDEq?4Ev#pA_*O-y^ zqeI`jc@zq{_gI=?drQ+g7h|l^ay-A_+R`t1;Oja#&pC|YyIq8B+oA5x;B@RaDbs^= zKE9u?b3lw@LF+~USG0hpw<}sMG~KLBk_mpJU87xWtuFR~Bev}SmG=!ijMb<9DI7dv zZjJo|n0BW8N+!$(PTVhZJ6RYateVYYggvO!rq zZ054s0;czGe{JzdyxmZji80q5Df&*Ov&!#^dJT>f1nNIe0D@AcWZrH5an$7US&b9x z{jui(g8cfMz766Jm{icn-C=-(s?k5l1f#smnNOWRJ)rwfa>bm7+oNf{uZ~_Tv4Y$m zgt|N4+$l#++!fRrbjTYbI=~Q!9L@%YUUQxHNAP})T&Cj4T$M+gj??;0oyru!{U5;` zh;I>JZ1G%tLyhPhOjO+n7hOgIe{9UOcrWxKpx@(%&9~B@HM(-k^H_TmTp#`#llg;B z-Sn^0Y;oQGliLMdG+`ymW#Lkasig!ndj;4h{YZKnT}XMq(=qSmoihU! z_Rj?c?}Gm-Ozxd{@+Hu-JDjOY=s;w2sffthVND=zG6#<8BR3W~O*3hZ&oEo3ls_6&ci~O|r6k`enkqJ01AniR*I^=NKLy@j- zYog7IKJ@8nTMpSbQR5m?iD^IHr zN_6z#4F~aMjBVWp?z+o_lTKnZq0=%D@zi(yBPhN}n3k>=Ghq((-Ep1#U<-1X0ze1w zh6+Z7LIoLqehORZ-`zI#l5O96>2rVcx(H||z+YN!v=@{F;%e4u&D*xK{^3=2YXdXZ z;?j1C2Oi2rp=hB;+ELE4OAGS#9@1*(Kwa>-RD^$2d&Z#Tc8Aw^x0GAM7*J!KSpI2~ zzQx@$I56q7In*C12JP03^w|;(&*<_kTBJIf#rlc_K{oaNRrUKMrDz-3JFFchmCr%OUupZD%`1!#5qwuyUkLn1S1RU!(Pmscx-0EegX{^4iM3yuv zzfd`%XEYk+)jiokmu^QgM6L2-N}zID86av#Nd2VFhU6?XeK6}Ol#54+77gQU@o0IHgj+AeIdd02i&CDpKuu$JQzaFDQ~z z%cAl$f)Hi<%)sUQvOn2s8tRyCoh75nFFOoqLT{(==nT14WG)-MweHf|Ko|6`kU@dN zvEh`^#t3-j9hPTZluc%1#e=`NDz$-NDnq_E7c&-JIbl5W;;1y$$Sm$|v9?mIi^zvM z{C-35?s;$oHinv+oe;3k%H;7aZ!VqFGvE`DZqb*Lm)NitV$@Fh3!r9_eXW}ZU|H1g z(p7^f#kY*xnyx6$MPa);q3_B&FQbIFpTFXhw0m^ohF##+&{ieNGW=t|$n`8BN`PjhacPsigff|PPZQ78P+O=dk`_5apdbCfl#gX0iKE>jH`cna#jU3h#7_lzI?VeUABh*x1 z_bpR)#RjJPrxZ*Iv!QW68Sj{Jz`QzVv7v>(0C7N^72_QWl^3h(4iA80E;oXqdhR7D z@(yKD*_-476}rQSaLq{vxEj0?6%;$X%wcL}HK*Ri5={iE_aBsti-6)tS<@QLzXb)0xBiVo9k`nMV0a1qZqLu!2U{>z7eE3udx(BGhMLz>z;( znI!uGBU}jz{Hg{m8Us_Y+_yhaF%NeUXhRE4!h}+1m~3uphjL(OUd(kX(?j)l=h&zt z9+y?C5uo%V3a(xb@tA2e*IXx5a8P#R5^*}8=q@IsVwfqxcqTrC^4XGq)hXjDesXV} zN)Oa6IXt3jv$Ax0I9r-^rL&^CM1RXw_1p7B8oex5KKvI2otL7&t?ib1gI>-xy4|jF zuZ5N|zNP82CcPX0QH$>0?QxBg9gIedn*&*t4*EC%c`d~b(wqy7W)QFSIB}b-RHCvU z>qm^wq$l$xEdJs>&RCB89L`j)@4IH$;(C;M1*0$swlxQMQla{D`R{vlV*K#%{7qWRsX-}!WuG5|N7VM)vFPGN@zh2 z204#8j5muBF_dp2cTv+%zhj7%FQgDtLkoUa?%rswxEKCj({tIfEkb9|5A$_(9NVKN-(X+&7Pwqwt%Xy>~B~1U?*_plC+iaZbyiH#sy)RryN9tDcn8iYSIkwoj1-QJ1NUiUii!}f{ zztjEJg$wa~Rl_$|^mkv(GgY1lC~UFw4o$|_CIw0gm0rbe8fArEnE9Hr_-K2eZNQrK z<{qMoogP%8mI&c+1~Shl21w5G+&?a4U2dnIW41;SC~;8(x+{{9sw^ThjAW(6%;_3( z-D(YkO@b)EW$#$l>(9Jo+N@e^9b2-cFDQoQZYvkaT4j)#Ww4`%CfaFBM8F4;h`jg} zTv)2K%41R2v%RQ<0s=bK)}dtnBoo|Y8kGtmJL}uJb-&X|fJ5h-ek)WR2v?A=5R~ad zrZvaE9RPGk00QFL*2`YImNT`4)#2r@kZjS~w>ibn`}iem5g&r^WZge=16eFXx#xIz zXH-&I_v>=h`Rgk&sYG^VpvVkga_MLIFhiEf-*bO^bHa~wg1n+U4;4Z;n zcLf*#Sj3h+9>yM(g*W8*Oh^wDEwfi1dCm<9tI@+h{KYGsw2%Tq7WBQuOw*RVn!@a=KUGx!-e)Fa}DOUx^zH9%+~Et!5%|bkUkia1Vfj^(;A& z+e8v_&c&ddq@J5+n()(NK{?8h^4#d?VGKhqL1$JY0Oe-oC*r@Xa-YWr-qSLz743tLF#2?|()n-GRs=4bLvQ_r zKqvt&%pI+A41p_E%F`8ZTpIZC^6SS&iK3Vzf*~YBN&T1`yH!6>v$u1 zF+XztI=>{DV&PNV2Q}BXFc@P?=8MYHH;#AvP#CK=fqQX+YRo+#oXIc`A?au6I;#Xz zzs!_Lq$|&9@U&X*zm0gIbRpGJrsX!1NpS|vqLN-Ile#Z|P}kn%RTkQePy|AL@})j+sMv zBy;u>GBFmA>M`K)h3XMr2Dps{ZA3}>oVRCA9KlXzXJ00(XLMq?5Owpa-{vDCBMB;9 zq}TqI;-;G#LQ%T{=vBj|A6*NA2&%!Bfx~O4;PL!HWUQ5gBYU^-WSt)D!vaz~9$4^D zfoZDt#W-)T(*Wn8g#w_z~lIi!YFW?&oA!Y(=Y@olz@zgb_=~67J!l;XV00h>=$~$Vsa+ZdY zuvj)`6?gD4K(r}JpCnDT`Xc$f<=zk4ZnfdDqVS~=2zU#cV`FFN$cE=NC-TxA(i^DS zY4Wu$jMlu=*2``h!?RplJ6mIggS05u)oCW|m&qFab6o%EGH;M8QuSLlKEpf2hfe^6 z4g*yXN&pmZ00OoV)5SVSOv@m=u2&Lq1s0!X52t*}u1pgbRDpx}#&~G?)4#VsF`m&+ zH}c+m)2)Kk|F(sA|AspGW4hjy{q|H5L{w~EfV{7hc+2Q6Bnf_B=-ae~CsTT(w|!Z= z5V#=4E!Z@NCT<^io+kdcT{eO~vd8!s%8qsr08*F$B%v$ri|na2k=H>p3Hw28v_PJgTFo2>qTJQOzw0;UN11}28TbFB<{bVR03z^NbR?!(%m6h`5Gs*u z#;xm+hQQRwdx3F@hOvYJ@?YKQp5DB;LuAUCA7 zgM4W4hiZ10Hb<9W|TUF@|jdhdFBTJ?*XAd2&T46ot9-bx2d$r5bX_72U!0<3=5 z`AvT1fz*1E`o#|7vnkkhRsT&&aGkHUQvA)zp8b=f{vwit95Pe;#*`7Yyjhy1#7N&&Mc76EF zhCa|MI>Nye7-hp<1B0N%iU8OATY^m{=m20F9Do6MAN^c&&ln4lRk61MJH@p_z)44} zb>YS)LFR?z3Mj*i!7$$Q;?CD`BZpBz3oC4N1&K^W1*LoP%m*ag zC^0Pl0C)-uYSC+KtYuoPDUok>X>y<-Eyl>r>#6eQbt_H6+XN=80Q_kFeo3&KS+jV_ z=n`6Pb8W)}5Q8ovpBwEFQ;M=&a(BQiPT_W5Mo8R52$S+yTHIrVg^Hh0EM@XQRqy3f z_d%l)zV{s={qm3tI4ww~8>-p1HR zuFCE&V#PQ#Z4ooK1?+WT>V}0`{nT1{Fx$?qsQVxs+xCs@l@P&0JuF3VfzG8S)y%l( zgrKkwdhH~;cI_+>G5oWxgzhq&IA!5$32Ajo$KYnV_d0!%gs_F@S@2+0b-AmpbJtU$ zGRHqymL?)^-p3qCZH0Us^69SQ_dB{N9y%=c8*8(*xoA9&#lW>W#Eu4myjeOqo$=-Sg7Uv!&%JW2bDXl-ObxRfW3hvXRZ_E5`9*$` z|K)8)z!+?_IHxMwbS{={~s1(4Ae$OvDfZrfBYa z$&}!$)(-n@*|1tP+JJSP!(P5*xl|z}gZ27z?b}%Y?3aR+`zVTQRGOaGSI61eT%;Y|o?)sk3l zibf)EBT3C!pW=)X$ulFU#Lfoc3~p~03|h&= zcBr(w6vJo?MgDzw!~KS=_igw1{6F~rYW3K|L3y6y22xy}eLgNv{77$gi+Bt}7(JE^ z76f6T>No{IC>B-nJsgNYtVoi`X;kFMykIw?vYY}mc*bR@)T0l1 zHIj$2L#<^syD;%nAQvbt;El;`Y%Tt6cFx{7%kh=>zqTY!1HFm=&q(;o)?gWL{h56O z!nY*9x+?;4Cj4X=QL-n(ssmh-Ng@-Gp{O{qDmO(ra9_U>!LXts4+s^2mQqRr%>EmH8Ettn zus;K;UOfuE6ADxN!(j$VbDtS3dl*7;!Vw*R4~ve5t7=t|13Q`Xp=%%#ye$1ftF)wzgMg^wE;KKpAnD z85X%FSxh``3ZmXEZ%z4KFdz$RVdG6(qM352J>KU`>km0qt%$ zB%0u)g(PY93tiF^F$0w38PmT`mtA?!bVo;0VdN^CHR)aqgSCt|9B==%e@r)yhnGu> zQn*AoJwqRVeXTu++bSdT#2sW9&3wwV`5?CYgw09Pfcc$OfR}DF_R*XiQ`XKW!Iq<1 z{DintQLG0&nLv2W6L^q>;@6O+E{V+7aVs>Q$XEtT9$?(0%1a54?+WK1TlE5EpUVT4 zOGdv464+WQLpZp)OOZC+VCq(v5;AXb!Cjn=eh4;d!N^<<}Xc(YfX{? zOkqXkad1|`w29Mi(HBAoQq7;cocCw=U$q2Ja}lLu0nuWbX8GE~XYcior8Wkxl z0geOv7DEq#Cs8smsp?=j?yhnjk6aR+F2h{$Dc=oSG8<_?to6V#O$5(0wmHf*!p^Uf z?f1LiHDZs-!=#H3{u)ap!0BCu@M{8^&7E}UqgX{2WzHy<1CKJaND}h(O|60JlQjb7 zzFlduX0;IM0y&^W#*`rjDrua@Ci!AdzLNbu5z~s`S80q^!b@Ve*W<4Fh{8zEH(X;Q zK?S_&(0_4#jo^Ph>L-2%+>|pm1GYK~v~~g>bsgoUn4JJo!8Dm+Hv4alpWu`A3dB5q z+g#`zfi|urIKGi?#)EBMZh*c#4P0*Hem7oO)j9Zuyq_UOA!m_?dlWc zgRjjHeeT9^Dq!#x3O!Ij3dh-k4pF?XZwAeE$I{`=7Htjk$%RTLm|`|{Ul>Jgv+%9F z2?;Y-*`|l@)H)|F*6ykZVfvm9cSVHz(XCaEuD(ZdgE$ero|@!^_1bn!cUIBqAikIM zEYOez48tr?Cl!eVDkO8gSQ-gR9sO34voiYeUt(FR^CAUMECuP}j17FWPea}JU&^f% zFX>x;44(ZLDv1LlldI3fqA*CJ0bpwWCN*Z}yK(lR-0P-m*88D~oDlhN!KFMoKACc) zItE0D9(l?bmM#fcnKT=2*>n#XWG|N!``+f>MF8o|%D4ak0{}DPfLk1PQ5pm*ryHck z_Z@>V(*3M{h53&R@kbKjB1z*f#Y3g%iPe5PDgt1XZoqDQ zJ1oSR)lKj5^EB`>c(c3F`+2z{6AA#l$>ipx{ISLQ36tnhAxC?9Ry+mI!s{A5ql2b$ zSS7qr?rN>sv6o8K)Z+9fu`GlDHmHcv!sGA&00RT-xDPrNwN<3!gsnJ~|5&=0^y=ms zFKRB9hI(v8RIU)14LUnWBf=U1K9!QNYH=XXlNoO;N-+Txv5O$IUc1D8>@9WC-;YH( zTR*UsLevP+y7&&R)ymcRjqy1=Sv(xnSq;r=WwnI-6#0&9+6bFY~r z<2m0LtH_G#BY?tipw3zVMiUq^2w{5Rqg$LUz7bZE$VObc&*1?PxQ&~~%P^Ulmp4s7 zsZ;bb($WA1!@Drwt*StF3LU(GjKx0KjRTMdt4RA1wOHMDq|<7kTE3BO0-4!Md(XL) zHMoA|BSJ#(9w#E@d%YLlX{<<5S;E`wsUz!gy;BB-kuDOu(Cu)EpWA6`G6aH*NlhfY zke2M{eSr@K)&AUvra`Y|`15#lA>u{UePCEgP&S-t&iMAFMC^jJgn6`LO9d<90iV--JGbOQfO_&$3y znV}7g>2#*~z5kyz&qhXbQgr&xwsgH&6&MC~zB7m=DHyn0eK1FIb<1IWrbsu^dV5=9 z-vJ4N_dT@_29`&9IL=7{`x#+A z{sh-UND)?)vtM478|$Zv@UKK=H;Mp+=9q`E+U>tH(PzXK5lSFwp``7$LSu63Baji`U_Uw2H2)B=6O2D( zyYkYrjtZ8vWdwBKSz&=D6%yg^tB%DnTbAVO#^-lWIs@0Er^ zgBh`#8SN{wy2qXXDA13h z#yD&?DaiWE7}BzqvV*+5*|KKRsA}X&U!%i#Ou-GL_w=xcaFFs9tR%{y!nx} zD=;T!LM3DSgLqyMH(_lg2Ftm z;rL>yu3zX&vZU+?5F=}S}UkfFRFFF3X9*O3`-&sM$%$*aRD&$`RTQC6reoW$?rB2MLu;HC(V=!OhBh`~Z~y=bf!#>;F+nbRnJ;BCw)GL=T;WcC;WI=f zP65_K!68GJIS4oOd$5b=K(8iN!tw1atJSmr{U)u4eGM8FUkZv^gh4BwCp`m)rIW$u z!qQZ2AOHw^S1fU5Q)cT?&_2h>KP_x43Q}edXb`IPkf@fG=xBAmtPWln-*S?*;BM9S z=LDAUK*BZ&4=c>KLo_n7jj=loHM&nb*h4-mDG|8jcyxQmWpKYVD+BYhG@t+ggG(i> zZ<8d78RI#p^gYT`)mpNFq^gOQ@zGR_MRHX|MzLUG=eN#{JFcEL z7i@emwl^ldLeAbRy~X*!I$=m zhZ1;qaoy$|?sYM#X+-!UQe;VMOHa#{Z3A7RfB*y4@=q1Z1Ss4@w}?o#$Qy= zrsBdL0g~4qLaGjc(reYzTpqP@tz;3y75fk7|EPAL`-$`g!fSH?(y)C>wX@0q0Ez@) z@aUGdj#nC~Et6!!q|a9?1sGwTGZcL%wkm1~ud_@NoBs?fWjDY2Md)-4d$JHXBBmt^ z76~8#0ncWE1nz%6xWqb%!mbtXilmC+hml54sIzn_Tx4P5o3emc4GVl2ecH}{3C4f` zAD0|aSGQ;oY&fB*vZ7o~!NcGCpo+864SMs4&ehJ#ghE_@xWx_w35^(t5QLCt zxJoq?Er*6VIo7-2jj?Ya=-B%)y}Qz&002xHdrhdUUe)64B)9}Oc%Er0r;YGhrkp5C z0ui*ov1f)M>MO(<)0gUsh)FgFBc-b;iYV{^0GhJBc8(DQya{>)w5kskB4bnyB$*AY z3B`ZLm{?%T3~;I}T;z1CQrg8+LHm{v-mE_XKW}1QvO_!@KHH#i=GP3&I=+&pq%Y## ztE%tnl1y-5h{>Be;PV1}kH}N3xK#iE2_?gk1sp|`iiFNPQ-F@bYNFUDCgQjAW9=_+}XpBngfgTVk@@BOITeI{HAAOHYa$z!6}W)}5ZvWCt__m;3{FIbF8 z(qg`aVlri8@to90QYR_?hbjK^0|0JXk%!baEq&AcCS1`zD_t34}(Ae0Wdj?WRAfqqN({^ zbph#`S-5{-rtO*{Wr)*weqQ#E5|HADt>mRR#m0TpXrmwY9gIabfmE0Kw zH$BALB4ms(;~HV%m@BQAh{ryd^_6(Hr1#HB<&euS3EgGDnIi+cXKsxqWrLc}IBSQ? zG;wLXnbTr}*t0GG7lLYlO11|7G>Xl@0AN6$zqbJmiPCcphx5=^f`GcYw+IX4GiCiO zn>=~YVgs@U_SNBoe(~QNsdpaP&bka{=SEsf^SP4LdL;WujaTnuk|{Y;QA^u41`wTc zc_`OZcv~eim~9wcfZ*1*^kIGJu`LuMx0!ra#n12`mEp3i-NU!3Du=xb&1CZTpAe94 z4`mg(4$6WS+cV?-T?6&i3Dl0tT%|dQHYwx#A{e*FI9+}dEsiWT&n z%>p%ykF#R9LbI%r&%9u-cK~6hz;6k8Cdp;qwcqo^I*69)pQ4UJ&jV}yhpVTxI7wo@ zg5!5ub^KMnW%^F@G`jOdaP7~Oph?B972DyTelznY*)LLxVW-jn02-e`nmK5X0tfW8 zOr`(?PXlZc5jf1V=sj-{Q`h0HF~m7@Xii`-!N!Dq4+XFvR1&|yOH*^G$=A(U4W^P< z7YVZtnPZ#owQ`{>@e~iDc^Wbve$Jf_cY<^e$)0*&37d^iGST`1-0(xxj~?>mDghOF z(F#0_vWs>#!n8|F`E+__?);{JL4)Gmq`%iq3y1hJS^vN|7c|qhZ0Arj6Stqc*pL*v z9;`Sd)V3-4GJk|G@LmR%4R9Dw)=fAdRRaYgAg5^^cKcj+M#;M2K*4w%{0Zmd7gBtb zQ+FAhT#uJ7G7%f`4U;is5wtR;nl&#a>t!!-++q|Q`#MTp?ojQsUd;15AMp4nIS>v(|00iWmKYwi~#S`-N zidZ!(@=`fLxrZzy1ZsPX!T;LwfuBHqBP_9iwkGZ{uX+BL+Xz4<$OVbe+o1X(JD5&| z78tbI(Y7PaAXv+`uMUyOHs?H~h}j70Klqr~2wqz?k)n5jrhsq*KM#ID!zgotUK*m0 z^d@IUs7odp(St4HWnV9jVW2Es9;!dQ!EkPe!TVFn>5|LnYrp22&RQp+x1{SrKOkPW z7ESqq)hZSO{STixf^UbjKyxy&W}m8D9X236F?|FK8duV8c0sKXK*KKm-AxpZp-=dL zxbJQ(V5FF#buzT~BWM!1L-l0c7d5Cw_^vgC!ZSnWQ4~_Qxm2AsfEMK<{;-L5T@<#f z6Z%bBy+K2sYm6Ws^edO#DXspe79WEQyE7T7srwyBh<<%Z&lrv>i5Mz5M~xnEgd;sI za-BC+6>E{kFG*%TboCKud&wj#Dq`9qZvW9AC(@L%={l?MGV?%Mxpq)zpY17CI zhHE_!IdkMxwM|v$_~jnah{)JufbdL_E|k9m;etL8!Ai8 zjQ>z4LO<4QJ7|J~PUWFc_x3EJZqu3t^}oPGPWK*=e!!i!((8QOI@h;MzACH;Z0KpM@p}Tb4X|j7N-p_oY^{H=4 zG(KFVA1cE_DzGkEwZ<=W5{M}R5`%kJ+G(TDp2dL zTt;xr()>OH??t%g^J|20QDpHucbl80Wi$@XUy^llpZ^@}z5SZDn}N=_jZygXzebTi zgevP({wLk#%!-z7OxpcE?42SCEY;bc!RDz->hHB-Ct$Ea6F_V@F)JBKLTxBVcvNp4 z)-W`&C<*-(s*h;R_9v*|^vh@d29rH-*5q~vDMN^UBQO~?0R*|A1b`{*g|A|Bf?p8C zf^nkOJ0x`?;_nCk?`lB_ektQr4t$or5|>iq=aO(*jvBnqdR$HpV}(PYjNVV>ab;5X zMCZr)ugHvBG=P&(1tq8TkcW||&ZhMQKMkwn@+8^*diwPnG66?DR70)m7~1yp_fz3Z zL9J>8e{irc3a^7PHNwrk<=GqzDBWbZX6#DN?=i%H{&j^HWok(~bn?Ixm;e9|RQA+R zgxajM_Qw82_U9QsJK8GZ3P1pg(8DZJ`<0|GDwj1ZAM32lBd zSg-&sZBNlywgllB!pNdR_mzFg>{;uK{a^_@1l>7O$G@#9oVc;{xw!t>VBcuppDbb< zdonBirt->9a|A4;-~cU$N?EJL9S^uNz<37jlR%(tCz}{cwPzL#zyS%T|J=Al0~C5e zGw;I5m53G~XOo%`Ptj~cf{`;kz&k)(ZROSihy1p{^Gv7L=x$@*pIQZN0`wpNk!4u0 z?C@czz#l3Dn(>+z7FD7&G~8lT&;duD_Kw|MIYmPUF^hhaRmX*6U13gPCOHSuH8b{P zUZn0T@!_*aavUi3&JG%;LCPd3+!PP&;>iwf4Y8 zi~1d4Fc?H9>1xkCLl%M5hC_#wj|2cm1j}XQ(d@+o1H0ilUP@MRW_;Drm)|j2im*=S zN?VXm2-s8S_`J(h_v-N9%YacC{5xGMDTCW1ob-9~9kK^+88*8T$A$#04qnZ7fjVXA z-N{DEgs$r|m4{i}qPuB!dd7;;0YRPyfL@(l0>sCTZ8dIVYkhGp~coM)A z@>a(_=LD%(cJ5@(2maA_!9Rwf$$7TZ7OV2Uux#m^JH8G!eZxoVqq2xe$L|G6nzGJSDr@x*=ifo4cNv0 zg$<|rEK{r~&vF*gR=9A)njRJdE+ynDJBizKgz>c|1+u60xo;U(qHTfDo!9eGYR`;) z>>;B-@lKuCl0gCSyp0hzx}0>0Hnt4Y52+5I0ZL|#*v4KGEsQTDOkY2u;!cCQ*lc^I zU8y08ihTL5eD6t~>UZMTR7yl&co-DTJN&ZV8z zoE?f|Y0*c7lta5AOdPdzD$(VOhYRaMv9&q!SOR&0T_b3)Cn0rtEifbRhHXfy1h_0p z_b%DHK;umb_{cn#-(FQwr@Z)-9((rAxYjZ&Q@9ob z2*b<8Fdz#`^rfNUwg!YTx>vJ#4*xQ*XiHdo%;x7+*gLE4Vx-r#FjS1P0lna{<%Cy} zN%WQKVUhEc>j#Ebnlphr;AI-h?$xFPg^Ux{BgA{j&g`+dgrz7bYVGym_q4Q;EOeZh z%k$$zc$F=q>U##W?Xu$4Qw+ZxCVwAm@b4!qJb>gIxhw{X{N$SU-o!Cj1Y=lHjFf3V zAt6%>_S5X!(u2cFa|mgSUp;NZqSQo^#f=#> z-JLWj!$;Ye*VS6W&Wzm%UZFo_5qu9$N~E|G>+`5v3EHA`cgjmS9+MLe5BTB42*ddX zrGIv|qT3On5tGzlt)O6aB>%~7mVg(G_d{gh^)Po;v43Y10?o1+J(z_el4MVVaVHHu`R^;@A`2p!NqSYY8;?pdIZWu z;2jFz)ELn z+J{7vA^B0tNe)zpbh84XuTw~<#Nke#>~NC9fQ3@jq!2Lht~@#s?E#+0z7b6X7`M#n zYMD6H3RyJM90dJh>4?alCGK6HzwJa4Sm58J?A)q9mSCo=5qpyHPZso4NBBnR;loRo z$L?e${OhV-X-iGkc2~GO>rvh_sL>Vml`eCY?Ubzp|BC{Pc9~sFE>;sVHFHhSkjg<$ zYeJ$Kpc<@9@kYLUrN&CTg{|DoRmIii!eKmtus`!z~{bv+#2&)-xMW48>U}Ch3FlB?Vi1HJ@X1SYkm9(=I;?z6W9l5X0 zC3O;Kg6P0biqN}Ki`W&qz&oSsNB}(OCt2-Ngsam+Y>ym5H>dt4TvKiGu^SHTFnL6 zDt<>h30Ji9brc!(L|Nki7R;5T4{|qnL1IP8`cAizD)Co{2Qd}c9d6;Y z$JL!@XHrE^ozFESam%$6RX}#4g}9j`eAbI(m4c$L?+Kf%h>$0&?I)gjG0gC#K;&-< z$Z31uGp;UIViKkU1bID2hrvvl5mTBAo)WMW(O)l2XCVL(_Vo>YEB;`Cung`^NGS++ z-DZ!oP5ux2A+wwzEkH7BN|{}ji&8bj7;(pcrfM*|9pVVJbZ=qdJ>)E6{l!zM}zsllPfsYlr(Zrhb+V82> z9QIoNWG>fR^p|m1lb|64*xkx}a^baC|(r-a=&}QDwknCIOe`?_&&4{0c+xvr; z3Dg+m!Y&Y*q(!w*64)>#+jc?%6bo5g-tt1jeyd%>y&2FJf$82l6)T}JJ^^?0h3f%i zsEA;7peOdLc#VBS9-Fy%=a9Bna;I&qKH=a1^Y{7}v+GC}OAC4Ao-G$4ei#(0jVV$^ zPb?ec<_GAVDS|n_pKD$hxvsRGn;2TO@wi~XRvf)Ube{y(J_+4IzmmOSX82C2zcK_? z0KZ@SuaApOffnz#mb}Mj;)s4{T#7FT;1fvK4jzgf&W_ND49 z#N)|2J7M=Ua@*3!`h>Zhtw9v5r8cLIWBP~(* zRu64^Bx4*_tpyrOP?L-KycVX$?K7_jCy0=ceKS}Du~rn|D8gj8X=c&Nvp>*>cRF!{ zQE^lx(zG_KSHXN%;c4S?hd){P7WB)#uH_w|JuSWXE$%xC0L!1Lm(liEsT z0+eUKI|MSg|L)vCv7Q3)kKdtfRru9Z8TH>?)AjglqMa`N|cJe3sB$<@mUyQ%WVR_$u@ zzx;jXy&dk-RQHZLz_ld7j@*uQ%5-C!_+)%-{>pq&E`;)H^3L`(_7a!C@M(gL7K;sq zsADSz6H}lh>{~-dYN$^5+WG?iZQ8ucfvkb^AV9HdfaQQ{!MxrW(k1|CiioM^PK(d) z>A1PXb!#oEI8wL!Tyh1C$8iS7J#v1W<}lC?OxUnN(8ji8ycM8$y;-r^`a;<#az6|I z7)mD8ovKdy&A3{65QLD&n%ZZyqlVxdI>15{%cnutK!k9Lz_S*k2HSYk*QZ_-W!DU`-`Rnaa+`P+MT5}CrhUA5!AOg7H+V35NF z^~@pZPE_RvHiA&_SW!DZH!fmQkSin<*lPZv&Gzrx@?_#?JFf!pCXcudo(o_AsDKT? zTAR|NNu_#O^X7?J$M|r$w@d_fN;Y4n>`==|481@+PaN;Pr&`j>kO`J1nVwhTA|BLeWLU29y+5cnZtNPA!a}`Ui?db^VAn>(oxlMT zV$dmM&~{Y4#|GuS7E`+_1@j@>jIDh1X^|M*VNEeGRyQ^sp1`}P2x!A+xz z@So03XQ6xmmQc<3@V(b9}g!P+NF0*VbEF72Cw1?qm0OE}>^ zaH5^hClGB=065j`=zgEkdtDiO#;yfDee`Q%j3Y%rlG5M>_v%TA5NAy)BUJQjsfqoJ zh#~g>-{C}ctbnv){f_I#^H zwu1=p^;4K6Jh-se-H4|{U-65JIe99Lor<|69b%vw1V6UKPR+>6a8pnx&*@I+zKWuN zFXK@34QOTzF{OuVWm>m?>p8&gnf&uVng~EI+4GIn0xrAo6))YSQ6@%t{0>bII5q=} zKTj-M_ufhEKF9Uz4>O2H>p(=_1H?w1<-t1Gy;Ai2O4?Q1q>{$0(vWPBsSsrLK>+|h zc{_EYxp<4oKsy4gRmGYhL`i3s;{=O8ZWm>hFs$F}SR@OyCYFKP$XfesM_Nu34+n!9 z*6#X_u`)xgck>xfF7`_|J;u4|?6#@V?qskLLpN|34Spk^Glqpvo{eu1Cx|8+E1X#( zkpzA-3kV!&0^2hq_-024w034^SKm=n7(`UM_#?D|yiK2826y3%&PMUCiFm3h+9;n8 z1&E9+8y)Ykwv+qh#KHd1MIdZ^GyLBuy3o@4@VD;M%5J;F?FCX*v! znv6npYb`Cagb#9bWfzG2CJHotL`$5R(wGb;S}U2XbCol^_K%u2NXMY6@{f)o4Qo<} z@E;Vt^f!|Hu8{G9>Wu7$ZGLA+%?owL&Nq@N$wZp?6<|m@hway%Tz7pi{L=n;Nw_Sg z9dA0LRJ;iC)QmkW@F*+3h0CBw|5n(-nsWH}Q9|#jO#Ab0L1@g8)=@wjv|`JX7*E>a z)c}IHSEcT-Yx-FzWlaEf)Um;X61;}oklRcn`YUo(M4dFLMXDuvw(*FRWOun*+FaWt z1hEDz?32TeffET+fpeM>gNvOK3t~!EYm_^v#BAoQUhm>d&+4S&=dX3|J4`Yir^<(c zRk`R!Llr&<0IkZi?P@2$5j(6bP%x~if%}!rtqaylMglQ6FP~>zn<{Q`ee0YB?eH-H zAFPsGC1~g^j~p4fi@+p94q`oF;b0YbYkk!*B)x32!L4Kv+ctAfCRy9C5!E` zqlb>$UJ-n&OKbhLqhPH6T>xOGsVdu}bdDoqRk2#t;*RPJF(R-DbkCd+cgCgSZr35v zhwIpRfDA@kBfFo)qC#6r?cz8p^G%oRazf1=jp+ybA9GfdBmPuOQLP+xsoxJtXVz|g zLIq4tme5S$;ZbE^|9M-gVARzVld{5yR7=2>XE44?zpOl3F0@d{>9k%_sMaZbg1AG@ zF2!_w^Gv4@!g(@SD)7$2z+ZPh=-NxK*5u^7I!9v^2O;R~&2{MCA$^6L#wW6lt21}6 z<0=F_b>LYvIB}zKrfXDvE(%XC4=L|)uu=g*Z#j9B`=IkE)a=1do}Y$?OH(QM_=&?C z>DJZvNva(q0gz2)$9B<5LEH^@o&bNYxrk?$*YsM(p!H}zFsTBB@TlnSoFLY)2+4eo zl{w=9kwyY_Wo}eeQx&Q{z+w{vS`8VwCjxyZBkP8YMa1UTx*Y)5{OrxHqMgx6+x}*5 zIg?((9FFdJgXOE8D#6!5bS}K(08sBx3axNT4HoC0Z!=1racadwUP%7Dz*L{`?wSb+cl1ik^D zK}_<$9Zp0v*?VUXA4g{0+H!cfs}p&_y1rQbQha@y|23+krhZ#_g+mydB8Ef68M}k@ z1EM`+2idJ@4g7q7tN;KyO2H?lT^BQDA?1j74$()UN}%c39&`TE{FU;P*-P~GjRG#5 z6|EvKC@Cd^F?6WBIK-@cqMmfG;&z(SFc(qK=?8#%UQ-0$RRE?acRZ!%yp+X1o+PS` zYR*|gy7>jlgtW6wuM_SR9GV6oiy;O&7$gy9g6sMutVT|hPe+hPMDdnr))u@`r)>Wa z>&1dF^>v|0=YpM7@FipaxVuAF;_~d%vmEFd7AY#cj~b|$XoxtpmW76-uE$gAt4I#b z?frPOe`S<*=0gJD))BJEYMp%3bSIU>!rIQZrMa_3VA7?M3`j6spTHJn4yt!svmc;} z_3%and(V~yf3mO~>=(&4)oH~r1S-p&B=~@cZ_uuRU(WvTXO03MJU~}H>LB~jfC?&0 zBzOC_%*1%mtZ#M%=5yMu15OUZiI8Y)G4Gc6^JREQ!iIWO`|@Dy3b}e9U@^}%5f3mH z3;E4u&Z6$YnfG|4haVUQjw{t2b{ac&pfMQTL z{yKdCB?x1jye2(Kp~z-Ai`xMcP%qRu6t@+YG=_BqGzKj|U%W7uD^{N=;h=r4Vy@8+ z4L6-kqq_)ct~asqra`;EXIMqYXBn(N3xfK*0=+d|uZYP!$aC_SSWO}r= z1iZU}MIDmd=R)<~WN+!}U@^jVhV6Ud04q9DMt=YC7b`eFa zwWM7~T%xKfxXJ)WSfk8kqHK8>+nel>t;e5=rga7kKEq47avQ_1EkGoMBA1t!%Gu-y z9cq)QPJZ=C5f^VE;qB>hxG^a&eZu_wAaco5*-;Zc*ypBE{Vc}e@ zbB(I$*4X%Gj@NEMut=t)5L@0O2|R{c7v@}Vs{0CZr5ZyXnDWGDsHT%JQu+?{r19z2h~SfJ)W1v{ijM=4#CF{uoR4 zaqrBIF`>)ow^sbA`bq_KBAIR4Uh0hadZ-e8E0fb zHiI<@^HF5ckQ>-U_OdcY4*n0fF20ku%*}ID0oY2AFC4HgifI(OftLL|0rCY&*v{BO zB3Rr!=OI(8Y|kPz5d$>?6r~U+mCq%})o&4OeRp<%A73yI5s2R@z3XV}3sC7j9Q$R; zwJJP~DWdw25nZ-ZsYUh}o3;B@o#ZWDc!bBJJt?#*1(IHwFtT4Y{K!v&g0A1I2O2z6 z*0rD9ip9NvI=G2Nj#j0q000MsL7G9Rp8^N{EfXn#07U-)NxB_z6fC>eACSML$BK?! zD`QlY-K`o1txhyPl%Ih0g}c-QT+%V2M7yj&*?`TiUEf3wNSq?^&^l57iB<;*IRKX) zYx3I2Csu9T1wme_2sRkqW$Ij~o%6iR&^BIc?dLT`x~o5&t%nlgs%AHDll%GOt%4#P zM?=YaT?orG*}@JCgzSUDX0ZLlbK>US5!}j?ou|ezPkT9$YltQi7dt_SmMOtxW=c!A z;1b%L;pA{!wCjFG(5vDA02#W6taByaNKv?EEz9|Se^a&O`WRNSF>cdThQ5!sVcATd zD|7?7pzcpL2UOAb(kH=nB{L(3T)Y~v$c%5V;oN^(4XEB$M$fgk|@ zv$Ra@Yg{@i;j^#1OB0Joz658lK!S&jRqCIAE@`T^1~>{==o-=BH41z2NLsRGD`ssk`uNb)2EFWj=_-U*Ki zkHiy!t7DvT-RcR3QVV{BHhg|| zG&tx&CONq~2^*({zG>Q@<75r~LnrjB?qgVXX+uj8FVv7rX9lMGXSXj>5dPMS>t5NT zBze)?r)cGEiRmvf{Rj;P&?LR&wYetnaAO1KS@yKwD7bgD=u9dTae`_SlNiD(+m7WO zv_={s`TN`%*;o62e@D4P*r<$==IU8u(5{Gk`%&+$<6K3|)-xi_9+HV?PtVwWP2W$Vs)GGmcQ|DW= zK7d>)bWm?j$- zSLB^y&aw@x+BGC@LNeTMz9=`BUStuFWBz>OubWwQrvg3Aw@{h+io9biy0DwB+(M23(2$npAMqFB} z$pSaHRmlVseEjwodaATw?}3O2|)-ZjXTJ2jfw=LVuZX%%upvFg+dEGE8KIUuY_A>Vf+d zP<=98p&d!dU{L-*inI_>(+D%e8T@NTWvb`v5cpt2^f{d~wRb(>yoXX5FZ*|stwJ<9 z4FCl$GEDVmfVTuHPnHISI|D0a7n|XZybSCXX&i@-=zixv^9l0c^Ci2HKVeu{Kl;xG z<55L5A71Ifm{JRvzdg>mLs3)E`|PZ!L6}hi&nVs-h?tmf2;QXpGGLhesvy+l0Y>M@ zDhu=T$`7GUpg8(juPok&CSWao^}%!zkRSv3x*BGF-y}Afq**{*3sj2H>VIK6;u#FjUSq=y@LK^{K&%HV~?m zKz{?IBf6ceNV&C#95twVK=nRbA|^6~S#^PQ=KJ1L+TdtATFI=XY;VHwQFw0X>F7RCjKC}j zMD40I9|&)CL7wk_A3TR*

yfiEQQZfA)Enh@5kbKq|lj0xj5(AKFQ@TcE1k2k=ST zX(<~-~kv(!i+_3hAE;dRQb1gBDM{=FYG z7VA-c7WM6UoTa2wD7F)n6+ke2vNek7tcUHz=p zvh$lC*Tt1>obZ*8lPV`j00XU#t5gQxJ3ZDji18Ps)t>Fc!S&r;^E_TR?&3cWoj`CL zKKcK1@ix$!vvDN+;Q!uIhLZ3&D!_~Upw!woON8w3XAt=&wq+9<@S%z0Nj;qgu9Trt z!ZW5?TRKSE{OiZJaOHtz_$;k|{YVf5VMjfk8Heeg6ezdbuffdAW2L8jS@FZqlI z&~GP1OyeMRqhgT&8ThOf3WHqx+ew4Qg0pJ)mA#dKf&nA$RE3JVGdJFVJqdrxCk6IC zZ#hd6oZbv97AN260l3v+dFVaZdsU*-8Q2B` z`$ItE{t}`K*!HTAuDDy;Z~Gs%jqtguKH4h?_KlN}ivLoju7m9Y6SZ&O9x0;*o43+P zqB)R~EOXTz|21=*RbpRP2#AHj2i1}lNJz;5V|$%GZ~$tOEw$cEGbVQY@7?;?*}DSz zvS0IS0B=tOFjZ8ZWxVcbB`)No3)j_$VMT6_DQ;+)k*;&E$Sm@k5mKi%@E;$q8GGRo zAVph5Yxq;eMq?cH~mJ1F>R*l$nHWk`g3NI1<5A*BPY_^c70f83$pO*(j6)cSo8sONeF z*ocK9_2M*8%HYy2&fmylm6o!g*&5CKF}H=Ws4__aKal}jU*#lR`qum@1Zl(VNw>e&F zP;v>9E4D^S#jrM~cKBT@e65#~T2O>au3kJnY&zSjD}Q~^mlSfKKPIOwC58qenf-uD zc#as?JcqTY++X3xmn^?gTyCjja-2kbNLl09K#4ktVyo~p!vq^#JF;jsCcH9%Im=XH zjGu}2XcoL!rlIW|R=o$gLV3~_M5aS{#g0_spsHzk4`iQDp7CKzV}InV)Ar?@ufm7L1nRIwLHgW9Lp-f>sM>1Z#FLEBsFjO|+a^{&&G{o0wc`<4PKwuXTa4nl|y zxM!mfS&-P9O4!>{4Kw<1prjPDq#4@n1VRNFqn$lZ9Y4j)G#jy`)LumxAc%~$&t8zm ze+Z4nv7#0|LA;uuh$Js!76R9Tahn6V^^5^S!Zz>TtS01a)%LRHsweYCtwV((60~%DJyWaX-3EMR zvXMeFl3u#v?TkndlP#7HG>mL7^a*a$&3&7G*^oQwhB8Z+nIiFEFqHRs*(!Cce@yK~ zXcG;{kSighghbjD^PjXidmM87(YU$$xMwSlJO;PZ_2Vst%QvEqfKaVEFWdLp65;vb zqGjP4e{t^VD>`#>_@8h+;3BrIE>u2=E_7%`Vx=GI$&OAMJE_I!-(_+#mq+m;E+Slu zE6ADtbBG<_vRICrsQ1T`yGxPcClCUn*&%GW>onRT<)-voJ%Ow%*bA$v6e~kwx;)3o zVu#Dd1RX_e6I_;3`kO~4pyw)@#4=g|?evdFT7wb|LJeJ^SU4!oc1^wtuMO5X>`p3+ z`f6}wt*mTfcbEU#f{G%T!VKJ|5HpGRJaW5I=u`;sM2<${T|sKWel->W6n7~KBo7an zSn1gXyr=uRKWLF8jcN#Zjpbx)+3)$^-&w7K0zig7+wC8@V1ss)!m95!2&@?sv<99& zfxHtGTeO9Ag;0a1yNvu2WItZ}oPgRk(`k}4c1;pvU}ANR62Bt>7Ys>)e&%%vqrcqR7=GUALvi2bZyIEHySq&9Ti=8 z-q1|uJF|SJG(JJ=gXAmml1^K494I>4QPupJdI`DHBZ=IWR=TzSqx4%Ql&yxLN~gSx ze86o7w6v+-=0QotgpHxJC@=LzgmkYmDp-A2?z}YD?2=hK$!mh2MN>GnjrUp!!Wu(QT z4!2WT4a1yZk`D=fGzq(PC_*P`l5rhu`<-TFQ_&oXJnqItpolVoWw(z;OtN6dytC<| zx`Mud-HqU|<+~Uf9W&ESO=2W^TInqg5z*-2qT6)(hI9rE(*0kxcFt9X-K?xIxHyhB zuokQaG!d?xN16{SM>44V*H=3l+R^ZYFmpKbW$VseAkt1$#*Coq7v(icl|>Y8APh%a zix~WU2KTl)b6<#&N+$1+V= zHWr0U#-ikd2B}r5sqw&I7qch%ZFPbq4~nac{$+sjkytqH4{@#;PAR0&;5<>6yl_{z zc2&>#hY=`YuE8w!<0yQ33@#Jo`}um6NYjv(&*JM(eyWC7j3t66Mj<0j1=2F%8LFLM z(!##wxw4jithWNHwLN6`XLpWElkd`ex#j~@y>+$+%3K^pS;ES#(E)r{(_Ix^kIL9Q z&7-yo9Ch)oyX0BHJ80KyVWvS*h#%&g_vG@E5;$$FPzf-81Js4qpr?tVZ*yMc0AyF> zNCN}l?vQBr!fvR()s^3tey%?_U9gpt@L(JZpjh~%Zv?)<;E}xMs3j6VcRPsF8M1Eg z7;1&l_}A^$u?Yj814H)=YG{uOjcHj%{|Dj{7<>Y+u$U$2HR52=W{}_{NS2)Zwnsn~ z3+a4Pym9wY4_|p2<7*1*6hpDHgh3hylaz>zIJoWrLp?Mab5v}{#gr|D0SWzkAB^j?e!35~9*;y1B!Ssx?e7&2Z z<&h#KeZs^31w88v8hpw8Z|hT=NlwnFCo7cl?f1$Bal=?{&po=UX4WfhkWx>)B;fYd z@HDP5NpKQM!+mFy^TKsnkHmA9zu7+w9Yu++faZ5pZ2|7ae`<~5lOZx%;nwN8R26;h zBWJHJKc=ohk*CeJki?bx(8DL1i6j~VH#{nVY@Xv#sBx&`&-soZWHOh;a=4imu2^ql z*aAg}#3TrmM}9O|&lL;1C60Dk>gwRXK2Hf55^IEoB=RI?1+6);%ofpGNpX}?0c0fX z&W#2nDmI}Jb4=l!r!i3~&ZtTUQb_Rmn$mFQ$2cs~I}N^7Ecs;1`fvKvwiqb>FEYjt zU%GlwK!V8MdZ!H=+DR5OAlguKZ;lWI9`x6Fb-I-SS9|{!EwokKE#`oiNNgt1E7*jv z>Yf5f&R4;H$;l@$hc+X7FH_qQiz8TRtebj0>B=~*!BL(NGv^ZZL~kcZJ(x-@Nbl%} z^IJw5tw37V9^5oWOL4wd2}@?CKr)9M$NU!9S<1a(93BuMIWjX=`0FH*u?4&C^fuBp z1eYiB?a85UM|ey7VA-(3S9bJO)&N5io!RZ9KqjyUih z#K4`Dk}4>#%*5@R^y{?`Vb+#LhxcAQ`qLH`VP?Yn`hRI>43y5>-nxKC4b>evJ~6%SC*``D~W&CzJ_2BiW$6`xV};3=%PS1WiH0q%klQ{XPTV-@H>tTB&zvKRRbe*tPabUX59 zhq{Cz@7#Aw3h03DNEUaZcFn#nF62xiyG7^HyGgV=5u-%oe&$y9Dc2yxS=QrrL9Py>}T1#gC0L-mX3l*j_xc9Y-0ZAjTeR z9~P(`A6?M1yI=jaHXWMRnnebLU=J6C_yL*pxS37R@MKzcFP*N`6Y*YkUkuyLoKli5voQr0kFb$avc4H5I%+=4or? zn&Hn&jSQBIcgfsHdo}XjI!flIh1<J$+H3CcTec(6am5 zj#G=gd1&_4fJLpvw&q?5yhv)O%2;!(LYyvk#d>fpa8$(ZBK&$;)JoDU5Zcf9%dt2y zG{gwnD>9L`X|j@_EB!o(`5CWv@g9L~tGFGmM=Yh)i4i>aZ+2rXgP`SuzXO3Aw2sG- z&TL!7gt1JHQ7Q~xJmVKx@o2H#n&*;5^C!YP2}$}4m8frqEel)fC?%czOmdy%`QY!F zI{XX^3_#~!!|IjF#~y(MKToHrSlMN#6ke~^C;f`t46yP+c=a^2#`?Q^jf}62u)~H# z^MLYjipo|Q0n>+1%zPbxZUF4I$dpMFi^*QIXtSe28a+W2t>E>Y{0^Ef?MEW);+~Ek zggu`ZPk+V2!o7Kh0AD>BP8X>#RO4mF(JiV--~&OWv09k)3OMQzt1yia+sEmEU(RWF z(ouW>yq@Oc)4kBu)y=+nl(D}EA>&58@h!FznN&YEV=+(OOm|`tx5h zTGw~pH5cJ8eIj=_y(&)q^z%X>KI(fa&5)>>AY)87r6SQ1QdTKz1Gnw`86XEAZVoU# z*MawUMs8ry>Qw^rhCS-$R#`HVJM?MJZ=-Hh%aRy5dJ@29OT~D_y`pns=P=sH8SD`0 z@rBkA_&COQYA5)@xurSc(+&n&C`m8B0$S<*`^igmm9WTz`w3?h1VwB)Aje(=$J;^&aMrGL(d+Fl$ zsr`eX6+}d$EljEO&J@F(_v8kJY_YaO6+cA@jC9izN#97IKZgfCGHrPs7F`NmTn$KB z+(DPrxcD7VhI^N!WdNM5Y65L>Iy$QAR9!UKq{v4_d)a4g)EA8xGuFPlaaD?ca<;*Y zG}xNvmf_U4?m?d+$LEt%3GX}TM9ZC$dYT6H@Nc&&ixlj7h+NM|!HBK0%oZqktL}s< zj}$GMJR_M&3L8$uv9CoO32xN)6WTD#Vt3%p2^NzZbjC^%QrhpV@O+Gz)V|qYN+9jj zKjuTXrw$`SsPnxp8qg3UIHD4w^)<}~f7q>s-9}n+A!BKsM7CZV&~P-@)#EU!Jn#`q z!QL+AWZZDv06>XKiCvmA(BJEQ1Yz+60ma1lnz^XU} zB7!<(Nh=Z3pUfa#HPkr#NCmcyOUdYqt5nj2Z?^uI4wrub8$W(tJje(Pc};nv5c3Sv z%Q!N8eM7stG!z?$+gu3U?#L7PRshdMb-+8S8SW$6brUf{i(m z496OBpDmy{ewsdPRgjp{2w~*vL3iy}FqL|<0d(S8Mq~AgjdZ_+ODxvDNQ9BmB;dW$ zTYn*!AV(+krBp-{OxCw|D&pvaXVtZSSo6ihJO2GbxNP8`BP>zB>7(|m(7=U!VjU|N zJN1W$tq&K~bnTz4n=nA@(VBKGkF#FlM@mMyGSK~}--Ez3)&Wh0FF^ZgwN}emI^B9s z*FzKhVzG+zEkxjGTwiQT+I#bdxv{u}Yr5%=?Z>dYi>H?YVdr2mt`%&BHLD_u?hjYJ z-1x4-xi6q&O8uGhv%5avx+Tt#=d+YJs0!4Y*OaQT5Tw*L9I#UB*`IWNV1?#5bX_`a zE7=07CV)I60lKMkQ4&gB15Awwz@?kn^US2wP1jKjMrbdZYq~X!%$rX^ZL6UoeCyapJ*LMCu%WQpRSXEuL?%I13o9^yT=`J@7(%sUCNSD%^ zPLXcu1_^2D?nb1g8>K`*kh{O{#69;u=XutT^<%{xW5#&LJI0&?#PS@Jfc6d%H)sXr z8cn?5coL-rz%k#J<_%o&gC%}zRq|9&r&bRRlzNvbkkD=Ocff_*ra#WrX41xbV&vRA zUGJ=0zsRz*a4hS}0XH1g$?C_yZe>VwF}eXr*6h%QRi&&yI!(PNM%I?nD|!BHZjkm@ z7B}gceHY&H?Do$CREN$IGsy_XIM?ntjCU5e1p0>s#&PwK(NF>s{54JXfOj_xgl)Qt z)tqs!Bq-Gs+Xpl6R{C7sf&}zZ+$#3sgH+{*KHc*mlUqom(V$7%u@{C(Mr!-UUNRdU>2gw{PSocl{iG2&f z;YPOspSsHe8$9M=#%FAD+QMfF(u8UjD@#7 zgB|ae@QTLoBt zH%u7!==|03yQZpGhdxd-mxBlxBSk>wh`vKqqBlB4^c?^YDaF%Asym>H2YUMbY(B)3 z7j%Q+sUO&5nS0dmZ@+HezP6h!pH6tI(i{RNWef+U-Y)#bK+k7I`9j>s01(%3RYq6_ zt);1mF51Q;lZ9X8X9)5Xclt z7qJ6&Omy8{k)=NUi1%$>BRO7rN?ZWT*o$^iU>PbOMe>T}8#N3{FJ8C`S!U_N^(gb5 z((Ph8x#7lDn>?phARf+RutAIEJBxN~7A;0$Ab$J}o4Ej`7+AMYtD{))0arn=idaQr zrv}M(eHmt67-JY#6PA-nYociqoc#(m{s6Lc3`A~#RK79AL$9)ch>Jz_3lu+zFE_@6 z^(XaDO_1_A(r@zd2*4o}z?t3L1YAiRHGX`9AY`eOi~8p@C}-zE$I z!W2{%B*yTu@oP;~qEqWh2a8!d<3vgXX`I*#kBp6qCk0tJUm7UXcDXY#rg9~cSA zdN97fn&SX*hkQ4A8)ZhAAt6i}a*(lP@G;Q7Ks~q|r2m@lgLFJ{er>_nUS<_|tMuor z=x6;uGr;&oh)ze$tFJvERmCpnR~2fT{?9vjgy#xA;-%sy^FHI&6ZKk^Bi2(Kh*bNf zU|18G!fMQ#5$t@a@~R|aT$r)4XZLnS+TiJ}Ggc|?EXQC?GFgnQk>2L}RTqD7kc7-8 zYHN|W2)QKeC>)NoqvUufz+j-DJQTO$iKUdjJ4`i&ywK`oS6esxJVPnjB4Fgh&Qy z?s+SXhaU_nj9Pj{ham&$DMhK56g#X805u?n?WuH@@!=#4-t;s#%lFUeZb5*UxQj5b zkVy7Mh^q$wP15Ns#?w!5>76(Jn*~hzvWzpd9` z-kz8w#pciN#bcLtn)LF+j8{C)$L62qNYrAKoanmW)*r0lovt=HuXUbH`ccO*Vk(za zf*OO9COyVQua!v#_&xQ0?u&fuIBdgX?JXwZVs#(CQYl{M(mrWPUs?S~Ae4K3kc!8S z-_|~$1i1rBsVKQ6XHwo0_wPFMZD6zg(3)|V{qx*sr!M+CXd5j$Y`T8ePp=v}NXkxq z+M_k9j|#fU$0hD!^ktikm2-&@4&>J^t+(&v%w!ZpQgBcU98;RU@Nv11R8NlP^14MG z`)-Evrs(TnDy!En`K)Y9SAqA+T*bjxCUv68@`Q8(?J^e17LUuP^rd#@ADO#tdz(U&XX^d)zWjwOiY16=Y(&*lt z*OMSQUo2{zZ9glte@Dqty+u%YM>S&r!61~&;d1-XRiNb&t9Pq#!nGy1A2=xcP;Y%C|>^@a$9uKdlBug3#Jujxk-z0=f|jcIKMJS zOMcV9>i_zpZtD0CI!)&#vk{=1_R`R6TR4s@N|XSQ$H?5(WV z>X_$L%Hj2f;kU15xq&V%11`Ez(^E9XYOgo?Ukb&pW3IT!-UyQlxTGvt-gJs!d8+kJ zD6!<%yC#b9%4y6D^5@9KbxQJ8?`Npy z9jTZS#$Dfw6V2kz9@odZlLqDWjq}^Jqpw|Aw>JPyPZIZenDGVA54$)^N24=*S>_h) zbMWyXSacPUX_Fz#c*Y`U4kRpXt$5ZW$i3of#XsjBP+;r^_w#lGKi*r&OaD+fj6nj^ zqHy|U*L=EnaM#LnaN+wlxQI{%!1KsN~kp}*$9+F7iHLH>S^xP*geI9#<%Lp29+trWUCq7` zrzp`&^7&L3cXT9_-1CBUgb$gt<~9D~)6Jtd^)U@!IkMdfOsp+IML!tf`ef>DPrlke;)boD;FtA_%1g$K_{xFI>crY%V7*hVR8~zN69HEIPbL@%h$^aBG}(b z_KeQextG3=akxxhE2PMMnmp&(`=D(o!-IyN&$C|IiSFPC^4-g!`E%U9{fMfJf0{r^ zIh*u{e)9goxO%u=VnT-6HA$jQZ5RAbp<#yUGq=TwI67F()%2rrApUG`Ap2-8b?J6M zIW0PcPqEVeVxgm$`jrsn?Z8%#R(qAKtSJ9>`LlcL3PU$jrmcyzaH^gVzfi*mo8;vp z>o;~|bz!74^L{%#4(WTIB!wHF`0JmxW8zgvg3sSddV`){@D9OEv;%Qa*uf)|dsb^) zVZP=)!IYrE7(Bd7P16?4w?SWzfA-1s$wh{8*_BXyE_8Y!6oy_nO3lj}pP0Yx`}O^7 zO@yB~*>gMa1;L>?UiQ59;&! zeMfOQpiz7J0~g6dc;()@T_<(Us>adUexcPIL~1XC6guFROR*>7?^}a=;HJO&4YJ!6 z?M*u}b15U(sNVYO9YaW{X}DdcWpM7yWnVo;h;lR%pFB!coPoJi(wsS%Z*NK~J>%>c z>&;y`8a-*{K?3jlTHo8v^Ni%Sao?gwJvLDQ$>)Gq4U@xCTjMZw{oN?DvE{)KB3jM2 z!aqyZShRu_I94mbn#FEQ46dE^$?rrJBCY29LdK z98`PxX2D3Z`9O)Z;4s+Zar*K{0qTm0RvI~uHqtj6p`@f7O9AR|Q^&t2I?m~qtbJDt zxtbB+C9Yd0t!&1h_Hy6Kk1!`)n1!mxgI_=T5w&rd#F>$_cI#*-Di*Rh$mmTzwC&NN z6~tpI0`*m@c^N2Z(x+XLIe?p`)Ky%sBA!RY+I*)xTX^v>rs^Guy!VGUGDPo*UJZu? zar^3vI3SBvyo_-UeU&u-oq{flS$gxWDMsb-?ZqJD_umawG_owD48O;ta(CxdNoUKi zBxc`h7g0rcwlt}Gd@ruVP!zlsA%F9SD^sejQ%XsKtq^rZ=aVIqTFl3-onbmWhzXzJ zu}}H$my6V`C$81q$r_uSnF&h^VZi}es+@PCCH#Uxx33?-kZqmTcnb&^fxt*XxegOH z|H4@WqBSm8=NVtYM4Zy!NvSO1BU&P)C4sCtQn2Uyq!ro)_#1l ziun-M7-idD$p zMpg@eU;y`ms?(ujYgZwJp+p4W&+b9&4(bn`oX}pe5g7l4W%kdU=>Zvi^iAk(nbv?p zJZdFCR);V*#B&fY=`2U+84TY1UpNW^B6tG8R5N?Q8U~s9h$jGa{+{}zWn~&)zg}<1 zbq2Yw0VqrPZw~`@i>*S~76m91!7t4}>Hi8ZQX?@siNDbK`}`L@?`kk9H&Az4O@`&B zV96u&qQwGnWTyg`fVmM9^NfjWhvGqWyE;s#fIh{~4L>xfubwW|1N=Ds`2Hoc z^zD89b#LCzrr)EMrU&XKF^u(>-_rYhww*u$Ro2q)y$r&gZWl?Ak5bsmM6Uyd-K0sqviCj+6-Jvjc(zH;X9%9Bd2A!ti9br9Ey z7j-`>Q~JWYB?cKMt0jps{Piqb-E(4h?wF zq?I+aZ~u^D!a?Yyx&D2|^A>V#O6i*&`scHER3a#P(@faTC>3e#4(cQ9ExPP)m-UrX zNVC~m^2)kHd8N)`r;5LPrGA#LcpYL}&>uaDmwJ8F8|A0>{)uumRleW;*`3NsL)UuW zPYj$hAvBD5Kq7(Y4%_%yYN0tHDG?n}02w&Ycf~pw-_=VnnQAotoIUxgfXB_fc=k)g z;m~W*30&yawRob2hCB!5SdlPH#c0AKD=M`;jPx43ic+t9uLoLH8hfgvq>Qk7TBa2l zvl&#(u*A91dINPzzC3O-LTUG!UTpz3z2837Z{Kvzu=R_df=pKU~f}y-iWiF^O&m!VQB}8977+&6s#z>$fFA-+h z;g(Bck~Ni)a$3Cl!GJkI1H=dP8n)TQ^-fIAzw_75NVpLGjLr17iX7Z_FRm3nbCiAC zH||txBIAJ<`5|N^-J%RGo#DNGd9jJdu1xv)>r(N{=g~Qeo%)>Q2gKHji>@BffO-$b zPZM>WLHRH{gaZgRl+N{VbX0i)Xx=u`fuU==M&Af%$$j_&DL?J&f?Z6JGxokm8-QkA z2w=ztHDc)7LZ3w71)$S?j_Rg2Obv^(i%n@vj#*=F z-F?U0=BFP1E~)|pYdrppzcqq~h5a&__fk;?MH;Kp=*!RLevhtxj<6b3=qR_84%IuoR_ieB#9wYqDu_-`pjCZqPS;!ZJKcCq1wv-yb-0G5TjdAuWy*ae;3Tgs zUal3UH&lWqXxzgS1PjJ!h%X(52A0B5zPLWu{Gfa6xc5A}{*B5;^Uqmxm8WyWp`&Hm zJ!K>(5BRSoph6Z|l9!!g8O=bld&*5%H?K+>mb;mx5T|H$kHFe;7V|q47#2$nw%xvA zb(wPC6Gzlcg;4yN&cGYw$uH5(_mj2E;z}PJ@nH&Un~h~6;JBe27t2690{X0lN2RQi zI&MNg^X;6JK>ugKh*S*R0`}@|t`QO5ov$pKsX|Jcg3 zSd$*_{1vp@Bph2fx=&xb^5(f47Y%!a;<-F=Ca+!tmLpi@N{An1wfIr6%N7GQHejuj&Gj^Ng-D^I>21&~eS zIzc0Gr#xB$p=PW`_x^mjIJ8g%c@3N*bj0}|I{L@RnQWU`mz%%=WKIBxif{D^XN86t z*}!@odFb-(rT3+MCr`#HmnpX2H1^*zu?MDA9@%3`zao}wDn#uN0lA>H+c!`d=EGCq zz}>6yLu@O9J|ufs&(wk-*)1l1#}U?IUpY)uj>Dm z7lM!z^6%vYItJum0P@AiraacK#MXkefGxShzi`BFlZ4!{Bc^{FD5L^vAjf4yQ{ zWZ;gU)|_F|Rd@LcQE)``tphv+fP|g{;Bo-)gYM4c!vLF*qMJ7R6F1R+-a=)1i2x-J z2%ZK4U{5syr9HInZ~$xIPq&sdbMM*LUC)2o*nntboM$b7pYZRW#5V!J8gU0&;m--P zR)8qq1Y?sM6=6-!yxCjCGt>wzuy~6B&t^!rDHc-ZPZS9l&V26hMB`R8#1qJDGb_k9 zOY4n0zfKDPvao+Y_^-g__%9-7ai%!zRK015(&!u+;Yb340>p5n0l=dYAfV6a06<|x zpF{HhZR;cq!0JVO0RnK74{ViFx}tQ|0jRI!ZET}`V&p$;BIX!~7}4zN|J&>kyMLcY zymBBrpyN#QVd2^@t>0vOlej!yF;0mmhm(4Aa&YW-uJsjM{NThb%W-xtWzj=OLS9F8 zpfoO@t!_oDpQIvn^!v~)Wruxm>8Kwop}fID+)?Wy*NDYly^zahB z>?FIh;wC!2PfT{yuHuzj*7yCp9)EJtPKD!^-uF-cfy8KUaE!EBF!j!dJRyPmD%GStnG7# z<7rpOpPFi+^XL!u&AkD9ipFwyu?KC@}y@7ao*=p5+aLX zJBv4@fG_dGu0v4ycI3kIj%d1G(5;d`=u^XGWdTxmFTD)3ANPYehk*9rCw{9x0s5Mnn_$xiJV(Ci_RY`Iv!&*G zauP0{nLe$6CR{##GInH)^%Q=$Me_M~m^}cBU6WmZcY(A7M`5s?Fj{&*R~k-!u;W~2 zIF+FXY0(%HNz+6op74J5B*j8Z2hcxj_33}8=pTA`AJ4o;0K=qRoKzS<9FFsDllUA! z-l8M@deXEfNg)_b^gFF;RgF+pHPfN(MetHrx=YFB_0kDH?C#YsdcBUSu$~hptDgo* zZ{^mVgQckt!!W_S_HC9c$PXIv3CF0BljI>pc{?koq^=4-HwDY;hKs&1^w$Q=0K0G? zCxJ1$hj|K3MGp@^!=v;B04&C#9@eUCg@#!^^&yZtcAF9;P#fz_EcluRULIM6uj)m} zdVD-$l#^=#^6S8HnIembF%UTTzPbJ7l$NjTD%(P@hw7IHgT}fdj0R0qI{^wis$_;} zIYJ2a3z1V0lN(bYZk165R~)70?Nurq;Ok+C`O^C~5Pn-E!@A@_lYvQw7(9;BS^g3E zFcTBwrz87J#9{;ipn3l|Da#E1+yiKx(!#&pWxfcK(8x*wD95Zd4|H`;mJuf&OkMh! z+`j{22-)OZUN1Jdef-<~17)suMpRcp$%M&j5l#6tb{ZS#+(2I$r_P~0e_9>VB&erv1exDwu+AoXY$5L-q71^D; zunRqSOx@9ZT>JYwOyB1831YHvl!bj14mZ8Eqdm&wp&Ti(%MpgX#}BLGyC*g=k+mQ< z9o81IPmwmh>|@e-ek~LC*W;K6o8P>;-wI&yTu{mT>HIUara>$AzSD+6r)p zcj2!`2mEzovg7FDXF~(cRCF^1GD|m<292CG-CyKJ{)~(8Prmkyro<>T+z2boe#nU| z&HVJ%WP#WpCbYUoNmk%7ERu9L8m*R*7F>BH;`qJdoXbJ1?4nsM)-A4+*0nB*Jk92r zu&HFbN4qxkXMOshfMt~xZ~R*1sZ`(?CYmx@WUj;+|wBPk-ZHRH`Vu zEVk>Rf9zZBl4Pc!!#T-u#wq20W^VcR^L3(QEqV2E3x`HnZ!bNHH%7k;j>I{BoO~Wh zobUkm{6@5ZjVYFzgN41uNgPAo5*O|qmp0t4S7kiZ3Dp(s`*79qX)OK^NVO(>QQUpW zj_j9*h8~u{N>AdEYuQTvASZlU#-cJl)BoOOhrnG%`!}3C-{>}XL!ZDyj5b9#Qd;Qd z5vicM6w<kp@5W_Ic}@bQb) zoKnr`sbWZ+%#Bsuq&d8fn@(e!%Q|PP&-9uc+q)nOPdDMc%zS=W7nZsS`s}uh|1aEU ztg&*$Uv+2&9bPB@a?2zoulU_9*}|)>EocRD#Cy-Ig-818&5T4Q>xJatMglCV;YwGe zZG2@gm8^5>M<)5y2tj?e8+F1bYM!d`C=A%$Cnxce@QQ4H_WffD$-3(7XntC>AVd|A zEFL~`ONUTWG!;HX;e@B`cNE>G((Z5Jz^J`~P3J3n0JCX7K8&gaMD&boGo($I9L}HF z*V$FTrd5AOWg|}@%{#BBVI&TGNb$kAp zXelEJK~ryJ3Gd+5zq|}}w&GH>n6}O%*TuKPXYPdYJ6G6w3WfVeo70}tXigt! zP|JmpGEYH1{(Mylb%=H1!BXa1-#MU^uhzy({4jjEnm(B5&o|4Tjt=^s{n3sUpRK-R z;c)A9{k$QTCWPsQV?+`F`h^=;TLXD+ZTCJjLYe2b8sq{(16`x1@N-LzsB9zoS`27UI z61RN-U8Vv5r0w5tvMR5cim58;x4PJ%F3E-l&~47e^ZPO0#!Ao%^6*Q4<-_)w%!yVN ztGsGZjml2nr4I%9ml6Y2JfWYVDmm753;Be385}#4X!!t_b}{4gAk(oG%vZB$LRwt4 zwiDU1188fgC=$#kNuc5mjkeb*Wqw`J#ykLy|LhNYh%AZ`=U)$2_R$(hF*7LeDg!ms zMrTW39`|Pesw>m%7nEI2M7KGK+%I4Xx zpRs{U%D8pQoVqgF9b**eGrgwv{b>gjEb$=X*`L;b{cH9AR-=Ag1`jFFe40L9??dJy zHr4%_rKZc+!ieig+Syl8a2CqT{7h`cWYn}|h_vr(Lm8Fi8xrz3oy>sd=2`Nep%u!O zk5Yr`^?9UMF>SpE&ih)V;K#jFgqVJb9A@%T;@h zbrPQIx&R-!?u%kqHdF>!P=02CPu}Vs%Yh(OQ#EAY1{L)P7DJ_a2~IrR1%*ln5fN!v_L&C9X1gI!r{->yulA84==a5PY=0K{mDgc6nIS8Y|*lqo;NxMQnX#X`~H1jN|` zUI|isTqx8ePQe=JB>DScRxXe)fhD$s7}gLz3>m(~5y^DJagOX;)05^*RnENIo!2&r z75yWBvS3Kbv+*=$&kvT^Elr^5AOmv$j@|Fqi49YDWw#CKsx7|*YO40Vxn6YE`SvYU zFVTbsbDf~FuPS45$qj{g8B5N+I(F?dp)61;2=9<3z?kgp`LZZ__wc8gWvM$pP$kx| zD^Q92+t2SqIBuJhqfa$-exZTuWq)_r3BNRQr)_)@>&4+pZe=pusPFLW$oaE2K)7zrNk^+}_W1 zy748SjY=*h=RtEp_^Y6M>D-hF|NI!5f9>SAzh?&7MQEU(3rJN(Mj4^?-VJ9kEM4o5 z=p8^#h+X~=2**~fzg6ZU+wwkx`v5)sPF=LV+c%21gLh3HH(=k9R9ZIZ6HH>fnuE48 ze2Mihs#ep-nb&+qMciXd)Xu(drni+b#|8Y=Bu~|T*x@}YuvXc|c|p+Ggl%|EzIag5 z%3B4*l-6_USY-tGAFCJ7wc)WTc6oG=JLE-ZCl=6RFS6~GT%r2WJ@$@Q)cjTa9a%{# z+eUFY;rebJUC<2wE;o@J<@Mlr4UXtz5Yj9^+x8q1!>i>5Uw^i&Ta-d$GEX!sIWVUN zs~*}t7TtGg{-T){zkNNi0CUhhBgWqbtK6dId>I%<$OeF2z`UkUj3*^ib)IrFSZpB9 zh5-`C{;>)N%RE`(!pTkHjrd)tOns4WMv3ObSDtAYBL!`zf2?OR#m>O-5ca!9(`}ZD z+bhuUZ?V|Bcct!)WfUtNy47#r<&k;rkqrfCd>s{;IU5y)IXG)RyM1E1d zB>0|oXZQ8llLn_ykWpdZB+o)Pq>=J`aH`-3BJC1Y<)~noMfqDp#w+dhrHeT{ehxtX zpWa6U<>plXC(9Oy1c18g%`HRVfKa*xDk4qj_<=>2LRRwCx@xa&`>an^W97Wk9e04{ zP0C(71`5wDd14gj_7`oj7v1qlPq zp6xSv0w@ktw=1@Mc@Ietr9}#3Y0n4IJCXtbP2)ES_jsf~Pu-djb#XYAtXUC*3!JYY z$0J`X7w7e?${%fxmJhQ-yG%XEZ;ntqetCMZq>CKUzXPwMe=AHKe>44pH~toNformv zJ;qP5N*Fx33Gm1ao-~ouLXOFexX-mo?DKZXhyu!D*Nx|1l?O9vY1```-|~)_(T1ib z0F-qIWgsDx@tiDHZJv<*l_3tN5*_K%uoqpS5OlNX| zEF|-~vb8&8?Jk-c8gDxoGKN_KV0e+KXz19}=B&6yy@@>*2jJnN9!&E?DY*xoaB&Lv z;!IAThMfcpbl0_jH^T#clds1&2@-hnsK^g@BjZ@C(pn(%C#y4>$}! zah<^`4&Jp}Ye5kvlv(E=C;?{qH=y?4zA9{KJeU66nNXc&F7Ay|j1&uvLCxlmEuTiy z%_Z=Om?@@RyuK;bLzXZBw8RR`1E(5RT?s`>qLTBQQl(|31*;K#lrQq-s~j%kA$?@c z6x^AT=zKhlINJRfHo$alT7%{;NkvXK8mnBHqRA0AwnsWE9y^2n6VJnWN|(&NwZ_w= zQ=w#Ahr6TBp%>nej^B4qDAKK{Mtdq=#Y1Y*q>;>Z9VQz+D~F5o49}UQdEuQX;d0HUnqMim$CZH_Y7HGhTbnN30jrS>`TGxG~0gX#STcfPaJm5IK$K~_Ol0Rn~H zO=`jzYH}+kgKwd6$Q>VqbuFiFzaGU(xG4^cGArmZ$l-)Y(x$rmuv|?P6;0{+^)a&` z!xSzg&HRF{Kl~cCGx>A~dL3ekyxHjZDc@MQvu-c6=BXQ<$2U)NF3KvEu>Pw!hvCcc z^Pb^Yw*FOO%}g8Rvd4Z?Dm|=hl54rEfpFxD`#-Z5adWY< z!R2XP=2mWTi?->0Ia^z^jBai`3caf+OCau#D1be9xzIKDr}!6K4m~A! z5z7Zf%?ay>`d;oG^i%I*bccYe>TKM9 zEbQx;v>xB#9sKlcbw}Fh?)SV{F*_zI=jh$13-dC}6Z(P^vBbck^B|ty>IM>8`*3G! zLDA2DO}!{k$y%CL-do0JV}_R4P8#=&wQN1;(3&>RvS%&c^yPam+iRBHx!$BmB$HHk zq??lxR8X}Tso>Y?udw;Kc>cC!vbOe)?wD}9bSJa*=cBJL3bTP_QRkUw3$XYMyR!Nh zY-=eX3D`*umeJ68QXs7dK35g`{n^-yUr`2YA>|ZzPA?~d9`=SN+yYb*so=6df3UZVSO~Y1mQZXZ){nC(ehGgS1O#)ip&0Cd7XV;uL;k8J zIF`PU(d=@vWx3YJv;LExw>q4|IlrRjj;RBCrjN+3z@(>a zx?#vaDFi6gP^cA?KF+1T_fogbb{6j%B&)vd?MYMO)yOm6QdCkv4@rFtV1du*VccLhR8SM;TbPp;)$I?Pt z|LBRlL=LtuF1b*X+$=J3QmF`G(E4avwG+-JI7l$7sB;ebDEiykO>1k)i})3J9~jOo zXKov?40zMUlpdxrFk_?0AUQ82qkx54Bhc>Ur? zcUpo302zBHvgX3Du6(>Jli^K-9=>J_{Pioe%xEl$@j%^_GboIX^ZM+U~bx_D8yA0-sy$JxB|IJhW@OKMbu!za` z5Y>E;1SC1)NG1gxcHm^i|EGk^%+3Oj&qmqJ#VC@t*lb7gRHjbm3(r&5+z&|?Y1QSo ztxNgn9JiEaC8XhN{AZN)wr3X1QHik}(90~C0m?YG4a7}XmqfXk0MJ`TQmU+0HllW z7Fm%(Vb{|Ks!t2qz;49+$Xh6KFdN!J3)WT?Fw^cqQ-QCnp`-xgbiWtSaT#fCBW_!@ zaELizXi;-PnDv|zLOi-sgg-v_@`gj~K??-9o{0&p`Lf#XHne~d;#VL#gj{j|O+P>c zr(pnD6&wJ@Ypfof?~UrdslGRWd@)`6C{S3#gzSV?Wa~+cH51R!{}DLhd1Q>9d~@Q- zo*gUKRR{f6J8}1p=?bEkwdwaJgL$sDcwFqR|B2p-Tl_)5&<6Eezi z8dJ#;1kDQfmPd&_@lE+Bd$VRE;MD|~Y4_%RR70JmjL_l%fWqh|G(mEcXboKAb0uU` zPq&LQtu-6ny|JUH185KnY5zY!2XR460pJ(dNl?TWhDqTNVRn#2VAMgB*Wh#mfE4zz zam-12sbb#f9({^6_WeN$r$376gcVDnYD${%fIa|L_9&GqLkGeZ9qWMX3#mGQua}rC zfkhCe4g*3Fx&TQclvMp6!IJ+io}~9zZi@gn*f1&^@AAI;g4ZG|?4uL(If!vgn~EoK z^q_kg2Qxw6<1JH6i91DfQMTQrtP%71Xl@SayihZP^8H|}-}E=cx^taq^raX{k@ia@ zbVqSz+Im1z2DW8B;TJ*GOL$Kb7X9{3h&-&g{zic%I;x!2SeZz#DwD<(&)xvaG={Wr zBsB&^MK)>~&~Au~vj1psCxfE&xuk)8HLV40HQC@Mo8zQdS4U-lE9H95gqhQI;-a2 zNXkDH&!sKTKYfO%)$%_>DgVM#=hm)Ulw5;bR?YG1KZZDhyqZs9KcyN%UYC*zMl~;0 z<-1Ko!>;9v{HG}mpG)T1vtx16u2~~BUY3v`${r0*F7B~65X)N`+@a@-wa``rUXquIXtf9yJtS{N58Gnz`@Ei8hbxO^sVw62E-#hfM_*U!+b0j| zjhiD`o-6*&73W3>q7%4YbQ61Q{7$Iq&Gx=vP* z7tVf0Qg|9%-PJm){CwQ_`L%p-rmn8Sdsm!W3gX~oCU4f?HqAz*8X*D77u5`PQ!ZvlIDcvP6_Inev>q&UZyDU`QQ>fp$^l1iOOk0R!sKAZWe=0}snBtn8(dY{F`3ceb zEvj}p(>r0mF@x45YzXDfKu$#}D*KHi7>0ym6_f$B+oeCQY1v&)xq%RRR>>=3uNS}gaS z4Pt}+X^t$~@XaAJIieZFiZd&n+syet0OB{Ort;pTuQo^`!P8IQOxy|vw%X+;3jj#Z z0VE~lgZou@of>G^gZ@d}Ig4tme}M5ZbR*A3P{D$`6>ziJxWW*@kQXPuXA$Z1+(c)r zt)?kcodGwWx7F=?tFNlZ9(DYp3DKZz`mUEJA@aMiq$icMjK$5}$eG}G{jZny(dxx1 z=|@pBNy<~91>9v7_dZoA$B)(y|~Btab;w|%NpTl&Y_X6 z&Q?=M*&4u8{8ChuBacsDPD&rEI!KS`P4Z6$U$RiLqzq@~H zY`@bs{Qx{GKy)exZ~z4dsyc@i|>;J0d+I7)}7P3z`OD`qPYv0BViO$oYTj6&gQ zicS%!shKJ_94maZ5wCjFRyw!B6~*9-p5fcgT;G&yk{0X9gG_$h-rQ6D>E+@HUWb+ zBIVO;GI6RZxugL^($C$eUt{*H*WdyLWENgw0v=CR$VLMv;;fLlI#hoPH~`Z=)&ip2 z5Vip88~|8&q9|ZNIj^=}MOv&X`bZ7ROWp#R2s;aW1LbyM{x8WwWKMdx)N`Y{yC?HK~xn6~giI>u`FxbC0{FDsoU$;TwZN+pLfdtd}+|}d2 z(EI32Gcs!Of$o{DR!U&?Id3m2#e!MG%(Xq9 z8)D=mILj`_|CZkL(0J!@#saBW$qYcr2Y@}+ayqC+B7Ngrc#EDW7fMK21M?sxoVI7= zb0kqL;hQ2MCyP7fD!GNxDY!8T(7|UVEV$vkCbZxnPI4PXW$UF@I0;M2lXu^?688l&=z%PJUCtdt;C#!<{}Ju_2MzsiWF4Mbo9H z>^&2%khc1p`)kKxb63D1yru{L+-ndbg#CBAMTzpe+TYhS)YJg(vqAknn_8r=F%b`! z4oA5Mv+pC7E0b|sWyY^jvH*&2nTr!95@(BjF+migg8Ns&3s|bMsvo>KQqVX?v3K8W zjG_O)GoPe)?@Y2O>D2MrIM5B>_wH69IJm|pxiTEon16ivS(rOmp(gopqfo{?LV(Bn z4|R*IL086$$eCh0aiTmaTdCKChsfhOf$m+hdw(}B06=C49FJEM0l0|iS`NSb%!I1` zb)K`hV|El&>6%UcShgNU++9}>d$MUcrR5b(S(Bz+c;iDKX#Pg0_h&z26y09^h;r=v zmVL5d5l*_lw13NXm}IezGbv8#aQ? zXCM8Y!wp|u{9xWUl~pdEdPbfz?wDp_l)L7KBLMrWn@G^**+A>0S`mEcwV9`jiC%MR z7=jwQ=Ptff6hYv_!vCHO^6LR~(-j?HKwsK9wJ?>%rP`%`1bjm(LVBsVy3sisNlHhs z_W~Zrrg&9mZ>~IUTQ01_*R+r+srms}GdD?Vq`rFNsPQ2C@k;o%Na%!H;@7Eiu}fEt9;xcMD5GD!?LPLO4j*Q#a)yT$9M zAvtZV{j~#?@BEh$aO^vOyzs^I>wTXet+V@wLc-k{5a?8##f4HQ2wWcE+O6!DH~@K5 zR&ZVl(-n;4q zaPpGtX~5mMAX1#u7e{-2>VY%-@FzJDPyh^lpofudGEGm}F3U-pZWu-^XDOTqJDIK1 z@SC@XUG9YYb}K!Qo({|O*xE?EZ5uD0b1XHw=17Nhg*^sl)*@cSt+F>uBkGUI{QaS& zq>bh=y-HhVT$Whvv>A#sKS-MiJAl2lToouz<|qc)Jtg) zl|ay+90n6R-n2;obsB?i*vV@PO|cLoQZFQDcRnDB@-0Xv$uynk5DqBOtY>>i)$*2s za=ex5&q(KQ7pRF%~XtqWZAZxL91iT%~LKK2tLNief=9{dee3^nykuaW^&Sj2_ z<5YBANZ5bl{_|la1rKhYw+*U<3O;AxNmdDC8hQ<~pqQYXsmgz66#pr=#vJ-{zlBx` zfR5#$5BU<%xb=y5J+-5TD%haL0vXYS^OMY1qzU^_tC#AflJE$93A24}Gdc6#R;7kV zZonmA{`Tv4x`jmpl}o7Lcj~D9?Adc=o@O)JuMt4;5FBz{I_6= z&L+~)qgv3ha<>3zNoHGH1#F~+?^9?EGz+ufszK!0`O6AqxUCxa-JSqMSL8CL{vYUm zT(ZHn5APAVlsFyghzV}R;LnGua|tF+zHEs@cD&cS!aYW zH{n6LHFoRt4k7d%vE=#BAIF>KazF(m0ce7>cToC`Y$g-a|70Rs#I`!4_(<8Eh2+57 z7>NFZhrK~iooblKd$>!ySHV7DM&2p~u$4mm?7c4*2msAt9WdGaq%E{XoX~9{u>2q^ zA$1dG63tOyCr6CtjqH-u_Yt~~e9{nX^ge!WW+7J;M6X)DL=5HHf_uEf1}U5qT{8Bp zG?(INfnNyJM5r2>4P2t2VE}-}5zG8;^&deto^kw_Yr2p5)NdYl!B1&cB(!L05 z_+Ht^-oW|e$}RszOM*V^?Ov;;FfN#+uY3TN*uxrfbO)ML@Got8?e~~(o(I8nkhWy0 zFlbjgnsRQKnUW=kGH9B~M1K?({(X+j^C8>LyFuu7VjVAAKp8MD&qmfmM6slGeD zua|*MubIH{e~M#jP{84oUNL1`8@}KCGzGe1;cyyfjf!%6TjgGv5)c1|5~?KE>g6*x&&@GtAZ!Ntmeza3-siCCtIpI0;(?Mn$~&W>F$SB- z#Ac*oFL9Euri>rvd5u4jB`hM)$q9^RCocbjoQ>!)&0&PN+x(F% z(R%ySsJ@-$=;C4?FBm_Tyg_h0pm(DAlzo`47Lo0q;ZYuq2vhE+!G&h`;Ku`*cvph@rT^TUD7 zE7ydz&`nseGqg6lc-Ve``Ui5V-IH>=z@)fhPP z{E)Kv`Q7#yJl{bCPNN_6zi` zXZYzi70udHDsE!1&`y=duWUmOZ3yQvbUN_9c~YPrn8fQgc^FyoE_=G;d#zm7%$axN zP7tA`9`Uh@OS4#BQRQ&_lqdKwR~EW5grzy}<^X!+RU}+7FvSm}txJ8h=Slek?sziz zL6NqP`NSf*h}MbtrbMb#OeAb)){3+bq@;e8 z*;}8dc{{@l*KBT{Un$$VEP`>MwezLos~rZrVP)?3MnJ)0338#*GI8hg0;!C4(U5bf z$5Dwq&Fc82b}dxlyWHf!MFpAbG(vJOQiU&~g=Wf$BKap@P|8(=CT*g^Xw@p%N#G81 zx2sT!W+!j8Hm5CX;dae4#WnP54c;ur&?dFSSNPu=x-iQG7=W%)8r7=HVx@uMwLzk$Jd<6_su#c6?YDUB&@9{kF zO;rcN+bu=kGf`e7$i%)+RL5De2c*ywD)4ndto`<>>(l<4QD2MT#?PXpj^o<^D$Yif zOv}j=b1>4_pFDK0tNqatt?l@%rrjE~IUmM8d^YS4=-xAX(V;Qb8tWwo!6wypBR)O= zE`$~UZb3Pl|K4r?_W;)dpj_ypRV$5-!ZY1*`_gup2{=!dp;Ks4!VJ-gAJA6qe73ND z|0xJ@RJj?h%UC+JXmBc{PF;#t`U~DtxeoJX(Vko$_ZNaoVgjSJKwjFned4lBJt!^! zIz;QJ;1hLL1n5EH7ZeD#3#rOh)O7`ZCn!BkK`y~fydHx2pw^KCTYHkz;UNr%$!oe- z_pgsI{Z0ko@Q`y`2PGO_^YF>SABi4_MCs&W3tv>Vr>&LWp=2Q5>WSe&9p(pf4Xo3T z8SQYwIn7{-d@b`^G5i*45sD{j14j}FDE300t0b1W^j}E(zrq_t3G(mo7X1OW{^e?` zA*Winni>>BZ%R`pN7~wR=h*yHWXN3+W6u~9m6x2b@8iD2Y_hgY>cM?Mig8b;6?B0)74fL=8`^h!a^E% z!F>JfC9hh_b0`;l>|%cVAYvN>`_7%>GD?qEx)6q2uj0rCCv7v%gl_Z1fUoUgqv(!c z#^Kx6>j*HE2UVXi=Y{*KriLf;Hux^$HdIEV>w_;Z^9Pz?zTxE;Ra*~tjJc!tCieIT zSg~K|ZG$#Osy~Jsf8(1fd>tEa{yZ!P_f=L?=%nG7&x6g!&S3F|`@EM!Y?LkY4g2mj zh2d)o5bH8bPM|qfmyN9yNK3VIrQ{P?V0dfHbgK=mJ*wQdA5gk!4T|{)InDCqSy7CN zUZu}HXKa1`sVMXual1~XV)++%{APweeu7%_J!}$jEK?e?C4jdK0AzZBQj@*}##6<^ z(io6TqU9Hc{9tQZ0sh>a`o$Kv&0g{wL-`3SYvVqptKI}t&}v-vOE+K3Q-9DYa~vwh z6TOUcc0STKP$lrktPmq3m&qS_!1mSU72gx9;S=I2v&gRN+Y|LH{gmxd4kF&9SM79B zB792`>47r$(Q)U}jYdf;Y2%$n^m>9)>Zl0qoVP@@_272fno(l>kw@#sLf!}qLPzQc zTq24%3f;&*Vip|BmDM}E15bsK%Dd)dtr^JR^eLG?Ic9NT%J*E9>D5gR@(bfgSCfT2P)#y!>3#fX`_$!f(YjM3B^;TrF#zX zdtlEKX%RUF<_KwMXG2AEh+*;E*h3qpS5B}Irljf{j6IxE8P1k=T4ob?@Xw}mpF5lw?-(f6|(prX92-xp#eLZljqVmSvVf5SrBf3KMaSK5mB9-gBR z9_6|BA7dci9rhqjL<-6#%8S>;u4&+2%5eZ~$%2LEU1-xu{I}q~|VMlm9f5@=%A>oZ>;jsd&rQd_0UIBr(P+ILPF!+D~imvh(NxpD0{@~HZ{p};k|{_p_WG&)m+UlQV7^|tj)3e0F4(|Mh@Vfx+f zP4FMcx28< zTE$}V+VZ&9Kf@7(A(&TGPvucX+T8=7-UQT>f}^4A60|~_-Xyz?Adm(kiv^xVqZULQ znthWbcNfH;{7_%qhVi9G)VLR~1gbOC|1E!~8qA?M0{qddaeMP#qVo)lh@&b6P82GsgFII ze}C-9c10Beh(bjVq>D3y%zcKW%$A#v?fO=%I@&J%&13~Tv9nJN<+URF7RD`A(;AO$ z1l#Blmrr2uh@2ykf?>!ObF(7xXQ$lP4PC}3=SAWAq7I>kt+%AS8AWiFCOJDHoz#;w zL$gG9oJJWEgUdb2Y8;{*H{OD3(m2B!AV~s*E}X?*-*Y|@BYJXTNyAE7FdZ7~ zhEEVa<_--|2lq9wlRU!YTRl8-Zrzz*b)LjRSymXslmSRsU2pL`DVtjvg-pq zaoB)e!vH+~P&t5tJYvBniUMX-2t=^TBXpI-s_v~0F7>yw@6eLAUIAb~21bVc`Gb57 zMGg=Ywk;_Ef>-OYT(>4r8A8nMWSSQF54DtdQG;)c^n?+xgUAQBo?_rHY=E zJ~~N^VYT(C`eaC=E{D%I83%&nY7?nG1vrZa>G(709V=XX1}7sB&x6i05K(c8EcB9KE=iH^Y+6*{^Fi99XSdK0tbWiEm={aFXfjw zgAUYn7XDj&fds7!u~D>|8&f3k?LUdZ-A#^hUwZ7IB=uP7CZOKbX+@(%>PHd)*BY9o z`zp16qa1YV;-+Zof%I(;BIi~PbPvD_hl!EHGi^RC|C~)^MfD)hEcVR*l^n48EJ`^b z_iuR)D4!L)U!3gwb>? zUn|H>SxYWFXaX5UjC(gGcuj}`{3^8ngk0mj5>oUdq_^Hbd+!ab^wJ23Qsi&i0sxl( zae){z6adx8Aofm>;zmBzN(v%_3L{}V^F{z!G4!$>;8>0!1EK;hUb4`i#ymu9Bhj^Z z1ld;tG$zoh#N`U{JMk@80zw$kKj=*ag^!jFtIc zV};^@us9S}_?)$X6bm5zZJxEV1lo>2`UfldJ9Fa1m6k9&yK)6JNg{-c?GAPt z^42U99tbB0c+jK!ql&`K!R5g`LX9C`;qXoeV)Ycjpc9BfDNaY7f4cZY>D)r79;8RC zyHd>P>-|0DXROl1>8tKyGbo8s4Rt{UUSJjv++!pyU=lX;Rlcb+YgV5F?xi^9s}G4$ zAawB{PYjb z%_jNkHcd*|Q0fHL**A}JPUhrT>#WNIS4k`LEZnQmBH#7#ez!VchNd88vPDi-Z;NCD z5!*sm9fLn=TIU|1I*cr28K9E=YUPmHSlh3^ZY2B=e%`7!3%ARb^yO+~49K3%#9Nrm zpwFXBt|U13%Kurk6)yf3>v3Q!l>RNC1po@og`vns5Ta=}y^sSP2!y@toU+D3HTVak4gudJ)Z@r^;vOpSIFn(eO!4Y$xse+5orMJ`r z*b!H<>7{j-a1+buR@C((UF#%eCX>JMwx5iWQxtB7U=0-#i7Q^6(!4Hdyaa0mcsWl1 zYko_(Iw)x#7>lbirmg&h-u2c=ejTWRd_k)@Ittv)ywj*=Q7}m9k&DsxLl)^MnWcK! z{vYK`uCS{w2c^@?H4*foc(vaUFP)&(E;TutAQ*)BxJy%-FLZ}ecwG(x+NvBr z#TeZ+eMrJ;l)qYuW~$w8{{xtD-P=Dxree) z!De)moKNZ%YgXwyaYI+LQ!b8o>$XeB1VpbEJ>9aj3G=diQS?KgQ$r`vbju*|RvG(n zll4{)`KM~p?lq2@;P4`%63fNwIv)@mcr9aW6@I_oOp9dc!>z0muf}HFwRG_tm&W$ zRbOQ^LPfFB0R@H@3`uO~8i3d(i%RKM!6&WFK3Yd=f>6g&d1fo?EzFeD?{h54;O5Z~ zEe271(G`mr%ioMvI$GRg-4f{!Rpw+oVlLAM~YdG9Ur&al!m1V)QiZn97qG0gf}R z{>UEL7$KhPPh2`H&)iE8#Kl82M(36P2jErMR&faDSkRKU3#vKvp>Cdl1@~+!0w4<1 zRq8UAR4kSeZ!*4PSi(Avah7w^{T2(#xR_*PrQ*XjP(w-4F&S|gkGXx*7HoAWJH<~f zzw?uF8tpz137N=h-`9>gw0_#-PpgqT@-?3q7^yKXnSV%Q+WHZvx)t|fEX#1=qH3_Pj>`^G|sf(UR9xP%~it=fVo9 z2e1l%JI}ubXS))}kW(aGZ!K6%AWBjkQXlfniF*S>?S64P ziSY<_@J1C4956tV6fHEu9l%ICYxCfQhb2Lo6($n+`ehIU#2Rliz1NDQ&*&H|R*DTB z5K8h4H;;(2gqEuJ%>x;JKk{6v1_~o(Y{8Czt}~F8l7t|EaG*=^^>OvIco=QVKL5V* zC-S+aUtG_zP9B{fIDErGAoh20boBIr%~UDP#RalED7RE3CKVLR0fU9t=S zW`is$Jt*gX;$Im`lJ5R_g*1!}U>69{af8ESXYU7^Ht(a*dpc*ex~-yz3t*;OM9*hj z=$d~u@ReaC#?MGR)W_FF5-%KFNory**zF#d9FlW2lvH`DrZI~=e{q3z&4TM+EI`De z!~A_0n|)DP`!{7wbAATUIX2&w0a_7wdcAx5!7M0j&tZbs^jO@>ma zMw8>MUQ%E0Ai^jy zIvH|YQutBn&&V+v)9zr2dBO(d`*sA5pnCCI!qJHs*qEQzzsy=;%#aD|&ZEzCeNut*FUK3C-j;1912rH={@~U*zTd$+8Oh1!K0LI3bZuL@e_``u`Q#vI#d2b-7rf z!)Uc=XYzOi$j4TFlA-8&^^po6bv*?Q&epDqQosoNH5CFWFqrY1s7;s8PF?|;T^4Yv zthfu+y4Wq+jtbrUNY;$aC_EhREJDoV8}KQ74@2@!B7Nr!sf!3;5szz6tAv;^K8{Lv zu9R7##g`XMU`RY1mDWI=IgV9Y<44FOHp6A9IKd9pf4CYt`4P8bV6`_AO-S)vMuBHB zxft5Ke4cuSSm)Wj7zCa1IIpjhPEqFH;%3)3_t}O}{Zhz&#Tqe#W=YvNs)ok2Zl;{1 zhUM7MCUls%mZ#u^+eH65H`&^yz;gt7G-DOEM&ZnL zoERm~gwF31DK3X9g~v4x$McQXfWfyrSlX2RD?R=r20eITa=ioN4@Fxu`Ji3G<3Q$b z+AHMf^S*ci_rzFqGv|0u;siDT(pMO$j2<8gra%|~$FVQX?>y&u2*Sn1bx}{hp*LNI zd*C=n4m5Ys{MunH*_-TPapao&{_d3z8#X@UnY&nk$Lz~V7AG_YLm9d!?TL%+S*du+ zyb9kVhG$V;{i}JOEOLp8817xK&~G zxsM3!^NBsJ>Da$DXJz0`ANs}(^O%DW-34{48H3_>+uma;woXbhV^zNM42#|%8uTkNdFw0JN7!Gh}=n}O6s zM;-f{dXM4GW`2m0!!T!qP_M?ZUPiyX^xF@e%UYaPpZ&F3(Lk#sDHBmOu5)^dPD+?PN zBYzpvDi_XB)YpG`I7KHYZ^KK2rme#ci1kpw<{(b3j4e6EH|}6*o5s&^X-JK4{Z*e$ zqRg$d79q!DPKFWD6Dhmqo+z!CuiLWwm>WYXDn_JlQWG%Dz$?c=!pfTnWAW>nRCokl9(gI`mCdgGPs*CNyR(3vp$4h7VFs_GgxtM}IW#F%Dvt@}rd{xM-Dk>L`R}!*)NNeE@TL_;O360)vo@Yi zcU_e!Eh>dmLFzxdz~3~uBOc#%E4g|)z$YcSL3FeNJ38>FrUE;xWr6T55L=UjauNQ$ z`TR?2^aX;Lo|y6gs4Ucu??!i5trU@0Ez#2Cg-NjGd)5eWDke=Gjud&{Y5NoSp71T$ z`zab?)KIj4c?jvAl(U@9{ao}yTz2{~VMN9hxOKY8J-$F>^auV?ZIkeOaThi+eEO&T zyo7Nd`JSRVCRRNqP*oHzd>#~8n=$P-4ebavl-5~3bi%$_vpijH!ng@(6dtVy!{)c@ zCOQ%}03kboo&ag7W<)Ovf~el`ZZ}Ys4er^zJQ3-(rg3(rDZ?8_0gAkv9Ec+ZAkbPv za+nWn#gz&`V;^?i;8qIXQfLAYv-s&!6u8k#S^&jisDXp=CXiwb`Q`$DrTC9|iy0Ki z=%73vQA^>xdu9O36@u2rie({`{BM^IVfPVUViSA&RTdrG^8k=Lk*B>ZMWz?x)oyUx zp{L{cMd=Atqa}SWJB##_^U3RtUAMNNHm}pzDSfZqK9&qCN<`@d6CxMCz;xyx{mJV~ zN*6D#%R$bvU`)?#};XvhA*`Okt?!jZyPh20LW{=oyMcoX14+#s2V2t(Wy= z>HQRz{panW!j#!wrh&)-U}qV#O(R4~-~ z+^(t0AR_A;vtVQI`imIgL^;XowxgrTpdei9ReaS5L)CXs$n@IcqsR%B-&x9QY_ap3 zdq@a+7q`c@VckMeEQWPj5T8#0C-8wT(k*7eglS8=n%H^Fz-3mle~)K^3%2I!wGDp! zXpkZw5vyaBChZX^)_s>IGYKXQ7n);7ORdmJ)d-)54uJ#uA}&Hq2Y{uxv2Mj=5mY13FFr~;ycKcNsaRTZL zG46x@(+q)cX*A4KiO<$0A z!)=Gmci1>S4yC3PmpiW4G*fFr`>b)uTg`iOU^HxR9TenR`@0@IIM?3D1c#ns;2ot) znh3u*kCrw3p#^wnJL%&OQ`UW0Wi@Dw&2<6rQ(tAkN)#LK;|8tvT`%ZDRnr?tTJ5hJ z3Uq`JC<lk9L88Q>U{lBZi`= zz?0$C%zTnkn~yF$hi-ea3#7=i*2V@{ijJElo>NskQ(06Mbq-5H^7Xg0XI_2OIZxjC zk+iTU90SN)MSnXzoiOM|g$+eJ5H+?{Z0TL6KOi(>;w@b&Xn+w` zdx69!On2ZQkwHMHgr*Vy-NU%o1a6BaP@48a6d)DFU#gSXAv_aC1<-O~H#HV20P~IR zJ+?jEK2|qT+_VCGmX_J-&jo0VE#L$!;T?Vs93=JuR;Ge5KThF5aV7Yq-o83&5qq(7 zyJ6c={^~(K>7vB_%G-cIK)VNkRCIxI31a`1zy1#=m!v4xhL!lsOr#W>y*e>HiPK~D zNt_P7>iQ1eqxUVn-n(^KyxdbRsl^h8W(SwNyH{VzURh{m7<63ee8q8?x1AaQ3wr_( z9tQ)@*L!OK#L>$@gXRc7*w26cJd7|d*!I@olx*&!c+7Sl(U$tiU%wkT%rJ5_Bpk9G^ESnGyuS`P+VUFUm-WcQA0}xyovDnXBtpVVp)Vk|Jx5i zKogMcOxKj~w1wQR>f7-I2*UYQ<$Jb9T?>P6bjTS|#%wh<b`tWx`|t$xhY{*QWX0p)jx=D0>ltIoU7LuFV0`ttMY%c=Ae^tCrlO|fkAlRxi0+TSy81Ztvd+X&)jn9KMWf-zcU5_| zVBv@9GKsdUqO#?#@M>pJnpZlzqFqo*M-;P&*rQkuUUb;h=37ne&WXNDEUYiW2+K`~ zO_>o_KnrHgVnXIA;dc$0qvUf3YWu`8Sc^&ZlTy3erGC=E;5)cp>ENpHll!C=i8O8A z9)Gv^>4AZF-5+j|j7RXKd)yTD+l|}uRbG+VQ2_6&Rk@?ts*(0E;b$X|zzp{x zoR))6-mG}3C`R#AR>dmM=mC@CIZ{TAp}F=kkH3#I>hIh0<2Jx+^=!0a@4q_!=$3<@ zmf#QYtcSM5imJk;>M;E@|dv&aRJp zpZPLJpxIyXts+rFA|abk``Y4&DUp=g`L(hJ zibc%}@GX%gy?kNWO#dVs7W77*Ln#@tO*uA{nZ4`sqzVstTBP$RqCg5w|?~ zG$PjxB%)&mFomtxWZy_~GV8`v1W1KdcinZ(7n1bc%)45=V*1-5u%{RN3mN;?cA^7ig@(c+W(xTUe= zi(W-UXg=R%I))~`19d$`!b_1IvYLx&KX$o7eX1kwn}Rr0#KSp_`qN+g^Vf2ie;Cs< zP2WjRMlPR!sj$yhO>Xrng_d-o62$&Ps57a8fw1W7S%wZeTR_J70c!a{+aHpVWiR!> z$yucPgPQqFO@^aUiBkMRjS{f?a4+)xrAp4=iqgoTX7kcqltCiuhS5fOz0qcUfeMRz zR`fgcX3n0vMy1C7?q}pFCYPkL_Q{U(Y!~1Vw05!XVX2f+ZuA(mze7@P%5m_ z&VnpOi5Ph6)JPqkV(P@MZf3yNA65=G_{^zEKY~jvhzKdUjom=nJ3ouL!mV0S-Y}lq zW*1#VN7*^N{ryEO+bwKTIJ89&o?|wQ{D7>OLNMawfH#XIw|yu;D-Xz2tacI}Ox5r-BSiupc`a z(4v&6(7i_bj@Y?d4woZ{u*tCIiQF8@1ks$`h|4Yt+n*sWYAYc=qX?bjIGiDt+U5tH zz^}4kvc)tt8IaLCncwj^d=h7qb^;l5TJJ58sadg1n|znCHwtOmQ(AdSZaX1icNj^u zHe$&d*%7Z53`mrx3)hUsorG4-$Ep)4MMv$mGBT=ZVyvDkKPu0JOx=fAGOKPiE97>6 z3&;^}l#G1x1JgqC24YYy!+#Ql;Q!7ui|Yee^f|NS1PQ>qUR5%pP~zF2P`+#jO9wOp zz9V8Su=6IB>G921vLJRWa;&d8?~W?27E-q)=_!jW4fGT)eu}e8Nc4N<1m^oPsiXC@ z+C+Gho5wN0yt!=P(!~@NMNypxQ14Aq9C77hfh1t0QlB4=`iWgU$DHW-W3+1Y#hhPl z5?jfPKa8e_lv)n}YoQiMLH;SM`Wzt-_E%~T%ux4Kom4JBqQh)c@i|mM>BUoxRJWn; zVPx7G3Wet~IStTqXx4)=hOt_Tq!P zz9QTsm`m0ADc3R%h1%g)q>-!pP6Jhc^C}UDeNO&Op#G!l1^`7fQ3$FBO6y@4QfEBI$w;}S9}KH~e;A^cjaY8 zAuaHb@cI-Vk-w^%9!*87HqPjVyL5QXr82>!F9WJKrejEU^}>}EkYAmvtH z5aZ5vpr0(b2LRh_D!d;d6h&~?%mv8W*5OOXq5DWZqsE-->|1{?&O=GW0!H`QT`-^c zYN4?SW^gaEnA9mR&*(dXrO*K=LP)0d3zW-<{BINfi-Z1KYzGyv%rZkTsLJ5nk$mc_ zE87?R959hLbcl`{>@zqt1C*|lGGAzTBySDnH zc_Q3&Nn)D(KJ|&=v7S>>h<<0h7JQ7Jpmz+wXSvP|*8->`AZW@7M0oBp!ZzhisM8rw z?F(Q=JS%E86s;#X#du*t8cVHqB`F4_T8LDDo5^RdZ=^1>bG9%)s%aW?v1uc@L!H@( zH;*iOfx!D&{R2!q#Z}F!=m_n(Rp0Ix>W4Z{Ljk6G;45ETQrAr^nPQd0Ho0t zoa#S65C=?8xV!Mz27=a*M1rAzT|QaH<@!|7I?W~kKIeaLp&$n{BD>@P6pY$xOo3KH z{K&Ox#8@HdSV=O;2^6SLG%I53{hEU(sHs%SMcr{Nr=VO`_TRE^I;C_E1kPJO)gf5M zCO`%8!B8AB?FLbo9McygNx^>ic@ia_7Zlr zE6&ijkHcuwm`=-NH>d!&*NVPL@4dx_h2L(l+>#-NVpDQ*9{(}p_T%Da(La_@Vf^O; z1xmB}wsCKBZh}7jylqTzD^?L;*wZ(kuJ8fa2U{pJTQzpd8wV&&vZtRrb;v4Fr&W zr{-}ddZ$uw7k$HL3*gitE}vd(EW}DH!!*#p6j^xD-$Nln`W=YDf6ozR5S|o*x5O?heRg)>XM32sN8oa5BrSQlCX<+Jaqq8* zTNRpA6~*X{<_|w4k*o z&hOh?DnAD$nsm@+el)9<-^-#AG!P0Dw+LvhTN{V=l}2aC8BG_|;+dS2t;gfOu`lw@ zC|a3|#9pbR=$F=NN-dV~#mUMP1^WJaN?M4CD*t&q{wHw_0AV;~3xJg@dyKgF~qySr_c>F*rXBI$!^j5w4%g;$xy0a243>C_xh33bYviHmkl*#Bs*Jk=8 zN>~Zi2%P85Fi#j4p6A&Wt~Fv9-%2LA^B{@~FeeK+l%I2fA-^OvcmrxGXzMdAm;gf) z)r$^x;dL2Ch4Bk96u#!%dB_e#o&g2*-F+nRb1}>l2&O8xE!#$?0F(OzOjoUZK8Ti- zKt3I@6V4<#qC|OtEcneysiZGp#!(g2RN9Lt?dd73FjzEf{{4x?7#e9ir+T8v=J|KD z_+}W+s7B(XSfJ?x{sKZld;uw`2X#a$2cA^CUDRSJo?w1tK@N@AmSqP(vjrK!saO`% z|3L>pupcKRK}Njn`7PY z)?&i(^KCxKP$(YEYb>l0}N-V~8(flT8HcjYaBSe2(ex%N~-;i7f zpOGHc9DWnkxdS=VK7a~k>Ap)3=Q^1o)KCW?(*L+tLG6)m8sz%^t%Ir)a?nE7b*Vf* zY~HHQ%OP%L_L-L_j+0bst4-Jn9^Cq--cFa2ri#)CftMF18SXtT@lKcN<0h#Daa+fe zEBmX6u+B24@6fS#%+rw5G2=e2YF0)1pgRey-G{1$Qlc`+&6i9`j?hRkv;0~4V!ysW z64U3Ku05=-y8XShAGW@LVkClCu$Z)$ zdiV>kvP2$uU+k)Aia6!rm}LLwAS(B4M}lPLfIRq194Y4ZgsM3~=bycVyd$c$V1-Y~ zI!kN~u-ftu6elZpsCYTg@5xwfQKfJR*`Lh|ag zn5c62hcdEZIcTGDNOJxrYnE++Y~`i3k<)N zXeRpF799o4ALKqYLZQHZ>9$;LE;Ul!)91AnnMrOV2u+Jc_5d?_5WQVEY9bKd*+3j~PCirajy8TJM9A|yOas5e0UItV z4g%hQp~Z5!{vYfGz|a<`LQ@3N1i%xdOoncCJf1dAJj8p@zf424v0K6Z%T{L|)Mv!ZT2cg8EDFz7+&7xX z&Fg{qJO*CpR7#e#Inxh^ICv^zEKK-C>d42rD0bEPqV+Ox1E^Wm;kXesKlTr-Mb?jFHsu3R%aLN&UV`4w8VJ?gRaamHAI65t!`tlF~U2)kZXb<+Ti)~BCSC{HZ~Nm!P${s z=~_M$p|%SP12H}S!v@WkZZMEiu4R4m9hRL}3%$!eu7`ehpO#c!9i)7s67H_2&Wu&h zu9mK+_|OAI_lInfHOVp0FLdU{Gs!UE3SQRE+a|#!{THqLnx2=5A4?>Cr#*NGW9rI0 z>B?;F29dhdT4O4OJ?LCH@DgTO0*DEt zy}sa2xNn^h7Ufe9GGB=-;=9G0k&#b~a%j0ls*QmbfvgSQHe(**?4Rmb3`gfcjgRDd z>`=AH^+g)ilu!l;H3glluA@d)1)mDISrDNL1mzC8ThOT?wn+kdwLO4r~ESgAuUDxi>E3iefY_JM0>Qg zJ#I04Z|*&TfAY!D?5NO-`7!*L?5p9LCJy@_CH)g6DKmRYk3L`03!(3^9<*>KmV~01 zVYJkVp2jQUrCWb$4ySN^s#{8`RJOh^2GJjX;nO>aK)wvQREATjlsk0~o{}Z2OOwR4 z%+j_&mH!*Z0JuQ_1eKrc7*lbPgy};qwT^&CT+&|JLry`&h(pg}DzT?AwL}c?p(mMG z?gF?Mr~(<(JcW z;JE+*Z~@AF!~CyI^?!i7e##OA$8?mt$9VHU8QpBexD~l6OGja z#%fj_no>`~C}l{*_;K26pI?1GNU(PwO%dUBhMgTwT*#q>-9qg~LNI_Vd`bU}d&@uc zn?grWZB$<&=ro<R4KL4jo|0gFNF&EbA@p{~r{rt3j_t7?4n#^>-iuca7q3abwgu z_-e~{65&^zC1XG_gEO9+;PY&=$x-qrmyM#fStRMIYIvwyiZxfYpZWAY2`diozZpB| zp8f7h805dVv0_1fpKX*^&N7Bd_owyt#Ew~zm1f@ELk^F!F37=)+}FHaG%6^Qiim?( z{Ij;pzGSIjJZdlZ^8}|`OC8C1N8=n{uW}6YIckQLcu(ac=%@Lw*W~t>gFBH);8j1r z+U*ECI7WYJc7SJkDvwu2w!jd=igO)N{myk1>k?JwfwGD&V^o9t$qaQ&Li(H%VNx8o z#bcy4K%x9K*cs)xJM`%}zx zW3mQS0_y>?sBq9~@dO$RYN^QU8)BJWBj2@zm*4Pvnf)1()gvNj>Pgz(+}k*J?{cGM zj}*eL?8{KJ%X^Qx6!&6uK{Q=Ka767Sje-qNT2XRBx6@S|q(1|?n%7PDF8z`v6@%9; zE-HVzI0`l)GxQC^`wXxFHpn_KbJb>n06;$gNRaEZDiqzADzY>^XJChXFQ6F;gyY58 z8$`B#YhyVJW7l?BJj2qUz{Q(|cpSa`iwMj40@PuVtUtQ1c%6-F%Maq5sT-Q87}2sb zk7a=pLv7uty)>n|nvPo?(pT^?_Ol4JlMls06W3YtB5OFck<`hlre2*6_z+*NniR7q z)fAP)1nU5k{+Z5;{LkI-%!|}!bziqn?v@KryaymDAbR*{^=1yNp#wfC|8|YqilL11 zu7y%aWE#fQB{_3$EDU3WV8Ic9Wgj195oQgP0d>3m;249!AK)@{8)0kf(p{@pn?8lr z(RrD{r2-40cnckBXq_t>o8`(Lb6w!OhkQ-x+6(9`=?{KTAgEJ1Q+aosMqr%G^Cj`2 z#+^MZUJGWW%|1N#?M7xiuC3Na(ht6Iqz%l6IXXe^K(M@~Wa7czB8#`+o3A`!%r0N! zt+I=zFrLY>uzs>s!4jaXR_?pZ>wh%s2( zoUrj`);S3u?Z)lhX&3zX+a>;yK#w;6t>Jt77EiddiLMCp(kagl*+^VFB-|2_j?c%I zWuk8QSqD#=qSx6{G4U-8LcJCv*_`a_M*FuJ0=*=Wz8vF#iHHjQ4@>;S8pPz`dHUTq zekbQ(-<~%G3Jbp#ejAL=MI`BoyxS6B+I@2*aM19uhmf^m&=X3Yb%-XZ-}y7|!Sv>9|pxVFU#bkA1Vg7NcYl~or(kZY7gqdqEG-kQ2}$#f)UpcCI5jz z(G4_xHn0xjnY7!^VsN~Ky)qDBJ>ZgBIZM(YTNtCEP)Cec+*Lu@DwV##pkZCTp-c8y z0>mTJ7dKA5ft||1f;T~J=iHJ!>f@@a!R3;nNVjh*(W~2rF?miEh!B8fxj+!aA7+$# z*jMKSL4P`rOam4=1iNJX0IW$S!Z@zYl3@)}wJbX?k03@CRb--PV);7fNP5vJ8rD;l zK=3}k6aUV73(PhuQn?+<_7M?03a$n1|3}wbN5%CmTch2$)4034ySqzpcXziyXx!Z$ zf&_ObxJz&g!QCNPAPMmLckVss-tWEdjj{je(LH*PURA62npHJxR@jGiSIGRIparqI z$9g5AdiKb*2R2yunG>BRGZUTZ3uNK4Bi?QljDqE0 zXd9(WML(o4q47zin$?Gbp23$7jlyeMUMvXbt>UO#T&+ek=z#pdksmbk1?dAUEH2?h zX?{-oQ*iX#;XB%C`Uo2hO-W*6+*fC;BO#+f4w+HDcn4{w&YMZ5D@_D5JVK7_;Iyc8C&z)8$s{B zSd^ZZg3vA%g;1{#7fekaPw_BCJR${{PHc+Wm8W!pO!U;kziEDx{5VVnpLj4@k0Nvv{=i%W?1&n1?z?(#@V@#9{y3q z!WHRsph;MIQjG?<#6D-!4K^P9<$tSkD11)-{ul5ost-5rbf3(RzhRrfly6i{3T zS?%~KY-FpZmFiM~D57{5BuIqbnOr7aAQTA?;#vcX=xqm7ZQ+qw*gcj8E;dTkiZ`#mYDa)uL5-@I3@NunLrYYHq&ULCyL;_#` z&S8-S9mgp7OfiQfg47q+6X=4i*;orkDuM1`A*ltw5UU zeBNeHN5-NlM5N7GFP30G)ow-{=q#nCCNaTKQ^g{k{{TlR8)LtN`qXoj5#wPH{3;HR z8GvkLF^N1Cxc?ipHV>`TmPLUS(x3sl0a)j*>l4z35xVeY1D2fhy_sTW_DFCWxC0d> zehcS|s|&&rHwk*;U1A>^YN~ujq{EBGFea(5u4nR~_5eE~KDUY`nn|}Y%%>(i+bI(l zqLznEbI20VQTxms#n+|T#*ByuedJ|to*bccHlU_rWsHcLVm7?QE86a)sgOLk+UVyh zG@JeIQ>n=pq&F&;JXg1V0FI?!RDMRJAo4r*C)rlQzGd2@laVGcbZ|f&drJ5ckDP0A z#dRz@QDe2{j)3N#9{1EW6@y4A3bpn8teHRy`Sd8&Z*~tW<++aoe>)Wch5q&>OHg-1!OufyL0R=7!@9J%>Zd6?fVhqHwNVT zTFPHyZi-O@A6ok8kslM#+4GEViThQp(jACNy23k~09K~%tZ1?Qac3(m& zGv1|8xk=739Oc+ovkDiv6$+C&c5p1CCVzmw-nz+f??-2)ICF8#sqY?KZ>BmP()?=q4w3_p9-` zJMUvfkIAjI6@b2sNQvhvX{a5HyO6gICECQzaC2+>nt_;ot7gW|u2WN8;zSA*3!Ohz zLQVFwK|OPysBrt#J7>~2s++zy>*R(mOzJXPSN@dsw%wz3 zIsY?vSO7;+``zGHxVt^a9A6gc>mfZ`YkN+i;ZUmgg)z)~jdg&xe#3np%;@(UV}j!C z@}cDu)iqVk0B8q?esZ5nAp>tY&*O4v-F4rQ#Y_Q2z4)4l{wD}#1RJ7OCJIFm2WK#_zuS;EAqt=uwxd*o(PEP6y4 z{Qf(~Y!+U{_=T>N(mRn**TWOC{7dr})jxj^XV}N?{l$>HHo3#mds~IgqFLW^*MZ*V zFylpaj$NdH#@Q-$Gq;ax-+ms+i|MXDX4XSB7{!wR!t^CpDl&miqAi16LS4KDIC@ws zz@$5~4tAqN19wN*H6N+YdIH4Cir<3Fzm&flMBI}`v8k~Q2d}tX*{HSyYTd~BPU8b! zvZbrzzf}gfgpG|g{XYHs&vawEfam74fA0dGwmjt^6M8j zF5JYu?qp_T==H(_-wjPvHsXT5A7(__7$LWxO!9FD#UG8b7kQ~D;G&!Mja?H>C4oNtJko@2&4JmH2YRhScYv8ww5iG z?aK!05<#05>by1?U;mZlfrL#(M*oKFkVEG`#dOGPcy7o%BLJpY3=*wb78yJPGd~7- zBDEjL1_WuzfqV`rR*13w^8(R$O-S74$rdKaEeJ;Rlf%ZBGcxC|KJ+!%$SaCz#Xu#f z&zry2CZImqHG}TXU`h$FinWbEjUg_#heq5Tu<2aZ#Yc_in9x$$ELP5+9*0jIWU%>< zKM|5cq`0x^i_~}QwaAZ$(&+emVmg2QD2i>fIQ8>Blk|A~{u7fq_w!c|x!mn4Ni4@J zUge`())C{-d_)uxu?YkiW5B=I0!Fp}L2!^?%ijqntvTZ3anVR09MiOJizD+Jimi6M zgV#w4gJyOYCV@$qb(%ZztZ0f^&{U;%|G>F&%eUuQA&jv^W$kCsNi^V)^{%mu_`J5VXo#e>VLLQxvB@s@vs_6=3`V~Bd%mXdSnk;0 z(bu$+pV-l#+RX8luJf@bf}x;)xxxH4(P)jn<$6m0YHs^U`5C4cvfRHAfBp{^{}*75 zRKEOO(u!FE7@(3%rig_S4JebQUzEi>DqvAuW%j5EL6e{Ci|TlpnWX<+XbSvj~ zhe%u6n#w>*9fR7XE)=Bt@bwlz;7mj-fe^_vY{0-k0st!s1r|to;h>0bC#28qn()5R zq8MNVmNLokvq&E>gO0z6ERRy=H7&|f1)I$)2E9{P^%Dgyd)TX)f7}Mq=%@nNgb73Q zFTf6|8vh5A0-=Nrdo!DrvyFz3 z7U`l}-D$cnghAQ|q0DUXZ8FAJ`y?$pFplE)q%Z1eI6H}d(dLvuI}<5rnY8R55!17j zeu`4Xh`&kZB>Kl4EyqfyO+;Zrqnk66)1W1-{B60(7SspyV=WFjKpExq7qibGr+}GC zfbSZlR@D4SjD#Oc?y+qvi#AKF{M-N>*O>Q2T2O_Ey1cc&Jsa7&z)jiWxLO4ucn+L{ zUef>}77NX6tNE7;H-Y+?jNLMHM@y#`t2TiIbs`T|mf9PNlYnUr@QXTJCw_VP z9M%2O{0Y$G{++Da6l)^XS{#vbXu9uCCy1rJuiwG(De~Mx0lzr3P91sVV?92XL+}oL zC9z`Z!YCo!1bj4ssPA-szS3G0(r`;MER^!cxFddtxrB;8pX4K3KT!=9PPWJ}2!__B zR%F+i;u8@T*s<0+lM9Z)DqTHMDI~YlNJ{7PV=-`0CNK!Q%epFZA637UIcSXR5^$0n zI4z3}p5>~#@HOQi?3gk!-)=OQW6s-L`87qyq_Qh>Jt4vSo@O9pDC08f&3E32OU8v# z$2)Fd+x9{!IHMOgyVGKDYw5w_4#J`3>mh!R^r=h(-pPjVzRuT9H3QSgv%gk#;Tmk4 z^(b2mbv*x$YbZ!!$Lhd59(`DuYyQYb40NU5?v0KRrfb2y|H=`D^08+-=D6ROP-NQ4 z?V_G$4ZHCA8-IZIu)=^$kt54WQK~F_-MDuz@F;tAmX5X=SxMDV` zYv!m>!EV|6_k;r8`_`b-xyM^U9QPV#3$k4|KbPfnuUOx=sK(a$eq_!#?dy%O($!4o zm<4+y%7NwLKhWH?8BH~9J=`8zNB+dI-v+oROnxN+E4^G(xXQ(ryrno%$|xhQTTX(^ z@hrD8R6mtO4o^R<*^Ydmv)_E}Lzj064e7vTsogNoRjisW+ld@_<=e`m+gL~}kCv*P z6x)(qKR61nuA>b130qkD(EQ^QX-Zfp-B%jTmOk{tBx4H(VLX)Y2yKVefWRaX*-kY| zILJUuzq+)uKlZ0BByA-uTJe5&Z5TCoQD(EmGR*xglJ&+<774Rq8ux}>ZR{UQ6((YI z;uZ(uXA9{+4Zd}=V_!jYg-=Oh@3y{$OU-=h8%k!HYeucB)UywV$4tJj=Sp@F_){`3 zEm4*cf-ofl`12F_+)DB31*Yp5WUf!iMh{2B=m=zNUiAK}{#fhLgjb{Q)|78c(H^28 zticS^&Y$>eY8Np+#Cv0L?e&TEV$xJDH}gR83Cl-6>xZCe(*6OG1z&DZJ{3#egOh?^ zESg8f>P}mfVsS^U>p+1wC>X{v|I44!Q%o}X#V0`nC8h_nK)<}@ckRd;h_btQWV-BY zf}|i5TNxtN-hx4U*#LHVhAoeAM3IouKe#qmqR9H+xR%Vfl>!Q3^H4wLlF^x<0_tGT zxpCtopqHO=8+;IpUpXyW*d&4wO`M3+jMqtCI&V*Oss>lBQFyo2uLWIDD87`mTf{!E z?9P&)zP>BQh6S%U$ib|hBw}M*i;hB2tmbRG)lE-%e>uwbWis6648hjdN_avph@iba z1s@1d&-i-O!uL4Lu(LlLm7x>3B04l{fC|5Hy2s73{*&a~^b@OT{S%?#P<+gu%&#+G zv;ADVa7_H+@8ghA5CsauGH^)HPOOebpSPV`|D!&M{rG zdQuEZ*D-O-g}b?nM?11RW@w5;3tY#Vtc95T%5lg+DE&2QfyE> zZw+TAf{}!cv$+qI=dW|XOSIUoCWx@71}%}E)2zcMb24t(hxr< z-KY$+&G9K9exuVKRT(r39y6%0u68CC>UH|oDDtXPotMm3o|}0-G>Wiqr;7`2gSRv8YJj!3y^eICR;6Jb}ku9f+8v z?=^~_V^3YG{SXjt{~=|00gIfO{|j6HZ+b77no_2hX*OiK!Y#?R1Pkwe-&CKvn-}ij z?VL`HDP`e06je3wk@7lPOam~lfhZ~W1@@85td0HiXn&jRoz`P;;H!|N822}0ZFU-O z33DE@Kmfs>!rJf4ZmKM#_lC$N=w|_Xo|oSi0qC7+Q2gq^G7^%IgE_}KX2SvAcwU$3 zRwK)SZ*Wn!L!MN1o&E&YU-INX#YPe)cbxhi+_S*tM(2Cux&c#^bxFSV`r>yCe=~me z;&P2V^dp#N?-RA{7S>C%Z@*EPh)a~cJEEI{UFq;hwBL*9u3#lC+0e-UeDmD#wr7ai zS%#C{8x+iizEf$XgG$L=$w%1opm+H*$mLjps|86x0hTAvHF4BfkdZ1aI%Qy3)vFK2W78tZX+S@k?U)_0|Mw08#HN_f@he_pOFoWr5HAR`Pd>NJs+mWKb^nVH^ zZ?lhD?E{0%IsaHnl0jGE5qQHku_)Nnca;f_@AqdYnOU`V#Pb9>Fb7?Tdfi zCev5RxzspRY$<#P2E(R%e0#V~oSlFssr0+co;RyF4X2C!otm4AxNO;pa*7dI8$?y1 zhHg9h`eIH@q-h3a0_vm*`1Pn{TF;Jb6Bq?)XuUy}pM~E?DFW6KeGMsQQ*ygUBaBv1PEEs^K}?~zu(+&m!}a}F)rO?hh1GJ} zXUDj4q8n6+glEJcr91%yY!#haJIs@1*34?d8ti4%;(IW}rlb&?{;$vnfEwteI1K*k zkz}mLN0-t1K>XqUnc~<>F7Rzb=XI6!PE~RW&%5C(4#RRQKw>>EltWNoOeL6st$UP< zJ5U*3sQZG*%8i|(C8BZZx*4RV6-I8a_H6&zaY0hL(RS(DF_|f=lcWg$T1Y7DBlF1`F+W&itD9Ip{3G8kySfsu}g*M@^atnwxXsFEZ$<@1nI<}>AY6WiUd(A3>E-dwGj%ke6=YekY8Gv3BjPWlwVM!L>Xfj|1b?NLAZ zxZvz)1Ig^r$ex?$D$QqHn9J5!Q>o9TJ@U-v!kflMTc*;FEz1$upepi`=K}E-|2E1% zh2d90ECe`#Sm^(VogiBe1VTyo7f|bzq7GKBD1__Ay>wIG2}_R3{}#@UOZbedo@O>! z&k)99{|lQ7O2x`rul=;m@k9u2O6>Ym8@cqVPTS9$TgdQ^0mv*a$n5|K^hj6_lVH{} zyLMT%q;?QD{%|HTK>i@(||IJ0F1v6B=;|k_5f}R_V0AjH7#?W_^ zheRFvOE0xb@MFrKpvt)L-flIP<#HPP(m;g22;}F&#!0JF#lp?z+X^kO4r*KwW>`zA zf9Yt&qZSVUSi~zoDRoX8&jx7fO%^_Z!Y%aG33m!NZmP(EeEHE}s7&k_DYq9|>H*q0 z;aI6sJlqSF^6Xo_~UuGS=nH#2o zsU@y78i;o=pl8HlYwp0mkpitoEK;V`zvOz*(X`|z)|O)_PJ{8`tV;Zp+loc+rq-FMyl}iIl?+BJstz9- z5}?1-qGv>gvD8m;jeG%DO!Aycibz%S({~5L`W*Mjr4Ze1P&uTLx$5=%oiCB#w;;EY& zAXW%I`=sg#1!Jby=196hdVnj6LTR%c&&?!$@1pIr8bW!+!?IV7Km>p-fLK!wSmc88 z@6yTtQsw$zO~!Djpvr!dxIQ9!oTqKZZjh+Pg2o(u8BV@w#qf|% z2C)uWWOQQE5&3dNBEL?9SY-6i1Zlmb>iAH!gNYuETmmJDW<0?~K5{lGO?}@__D3iD z16>%&0943;<`2a-%?DagPyocsavou|$=GVOEqeUVl`pfxA%R@YU?sXQ(%q`O7vc;9 z108!X2&03I*({Rse$GQ1;3FvpVV&7y+zP(pdDy8(ZUmwCTW;ugyCUlxj|B2I+Oo{~ zNx7>1{mt%-qL9y>VNp{HOjnDsFo~TL^50ak-Ywlo23RW$mu3&+0<5lgbZi;@uD948 z1{y8yhH%^@*V*g-j>YHiw?*4$&~3A@aBUCqQbubvzX(tuCr?y6!vG;P1?XFeJeP|9 zZ!HB%;Z$1k`T~}^5I&l6zYE4*SosRCzlg#JfY2W67$IOXYM`Ww!BT9qyXnrWCVPg$ z(^{>M$oL@+ilSOGWZ$>F zGv!Dg;j>7`Ld&Kt3(Ln)#*VFTJzSB`IO@gEq7+bqZj_dhtGdC?wMDXKl^}n=a`&4? z5AUxTC90i2z35lf?_&aQz@x`CtnS_U{o2{OFdsFpj`+0lFV%A@QlD)i*i!#6#o&|n z9;HdL-+qH}Gx(;zK>de${!p{o#-;^CLT7 z=j3+FCz+`O--BNQT{h>-Y7B`uG0|RC>u6kIiaP4D3kf$^G`}{!5k{QzS6-V6qG^*S z%b}tsgii03_(_noM_SXTxX|@PTrRj4dq%1{8AU3$MmC`6-d3i1Wexs~!lOmzFU%g( zmDk6$V(Z4Z&IXwaFZr0+kb7_*a)oDY)?RF;Q7^9r#@&X>6N!r+6|KuJd}eG>^(eKu z8SSlm)|;6(Jy;tORyncZb&>1F_+a{(X`1&Cy^~iOK-q@NAa5nW-%!A9Cunc@<7B_; z%l=B|*ZynNk6J@*nJt`@cc+xXajc%eUt?`ZJ_-&b$4~JCG+`f2rG7tXpD}ic+WrX$ zg=ccl;N*KM_>qG#cbwxE_8EGXK0%4_{r%DPdFSU5HL40|il3!+dZn9a?8TVxo^E}G zY_ulJ8T*S0+x_IYeBM)y+NaD${bElp8v^_Y)4S~&Gho+I;V8B2Nr^jTq(!5dwf#N= zCJd#iph^2h7bk1m!p&%B7DksSwNrczUGxdApWYZ*U9zGU}x^KqP) zwW~G2sV;tjidGio4rNi}nBzm~TpgP3_1{8KwDi4$!qr5V#bt=mQyzKu`-BMY+6EFD zM-ulmK^~vKC5n8U{!5*J3Nmd4hJamFw}>6@3l`opJlbuHUc?M^uPcXFiP9off0!Ft z?*8HtcIVk$byUB@0ym*X$xfMt6RUWUGt3S%AtroQKqp>XzB0Q+3LKo>&88u3z2}+# z8jqsxy{G9$O>&|^8U<00dlk&M?t?_P%5&z2tFPk5l9^V$PJyaU=oTn71I4I#H^x;K zW;839HE8^19gHQoXHJ+|Fv{Xh+Wh4RJC=2ewekR8HgDrb?~KN4G37lp3{yYuno3yK z?On8OOlx&|qf1U~JX{WbYobRaDmP!tUw8xPG4oTdpy4VedZhZ#N8fAUe(7-wD@#XCJ~G%6>28QRTzg6SY#zU~F|r?)wkJQ)Y6O2kyydknN{5^HZk(KMI1)M^>Zm`0}Ec#<=j&;%yNBC$k>ja4TCm1pU7Jd3p zFyxv%0R0K=;y^r}@vZO*591A*8ECdn)t26MSR-?Ej#g=pa=kM8aHu&?R%mT1c ztf3cw@1IT&!AXc{(RXTr`Jn)1ajd1Qk6xi+WLfC%41GA z_?frq0qA}tYqrGB*?1~$CSrcY_FV@TTu~VWc#Abt!Nm8Qa9%?DL-7{@kWlKF+%ne5 zF=EgHyh4dkU&%H;Ou?-!b&Txc*E-Ob`pQ_Eh87?86WYZ?Mwr_g_2PsJ7pDHNp8k)k zxHEDOzHGU_(u2{q$Ws%4q{Q7FvI@pc-!pfzqcktwI1JvkKDRSadzl#k29(&C%c_Si z)wDOSnXjpQ(;`vmS)FKi4RsbXPKmJHDE@geiLH3m??&T<3L zl@J}!(Bef$!*C-y85DruNt0;oB2#TQQ z!n{5s)mo@7Er&E`EOHBiI3yIkWIG%g|WQiM)q*Im#){O$7K2aeGb*%KEw zWwttMj5@2)haqtvRdm?x7wM ze6+bcO8^iVf+fx+@`7dmuULZP&4T%bh&#& zJsm{;%?~KrI4auakE7uz4Lz$ykA8S&U%HOm{r!{`!eHWyc$;DSEwz~si854tYTLQ+ z%I4GwC;BO9S}RxXq=#8{rf+3LYh~6QY5z$Pe|8&bDmT#ak;6yF*bjwqOGBzrTUgqc z+pb1ou(C@ip?=E&ss|z0scq5+~3u$wrEi!R7iuDKQ-> zSaRxWhCz5&?expu;dD|JJ+7JN&7F8;qh_gBgE0=(97*0q4?SJvz~?kW8I3WTpl~Id z0HBXFoGpC!=q%K?53jrUjRz1}fgd3}*T27ob>|anjd~j8ASuGm$`wW>n1Qa~ zhKraE`{t0f0LU}PcSFK(kr=`P|*!wD_IO4&|-dC{a445|B$q5w&DJ;u0EhVOuYe(uIK-$FH$N9XV?307mP+C*1;mHX&7)wXi{&QN@(l+}e7Jst2NcCgYt7jn;!| zM442}O~a%xSjPTgU!L0qxz9HXY+P+!1p*kS_3Pk2{x~UL=S(H2F^0{!=ln^?8V3Yp z9K(VJ4(=I}jcFmN_6&)l$jg6FL_dJMsTge=rs|Z`^mFl;}>l0^}D8oX* zP*yklxwO+>4~Ek(rq4m_qD^G=v|oN4MRFW#ViM1qGZ#}>H4yhs1D*4Oo06=GGWd9- zIsJ+n>TJmbl8zTw+*UX`3Pi&;)sBd|E$gLTPxW(it#1Y*ug7h5<`m=Hr+4nouxH!MTHH-Wa%GG+(n(xUU z#MzdX<$qvSJ{Ve&(9oGQTIP^goZe;nVD_@11~=N*3nOP*Nf+>o<`qC6krVR!8$MY> zq!Rg}zq3B=Nx@npOALd!1Wt=S#d_PLHF|x2Nlw7X5^yZwt<~bmj=(?Fc=Tf+Csmpo zboudlPr<^R(_KJPAH%QkRYUUu4U0xss9dq+B48X2S|3l0H4}UN&?aH3Oqr!BWD!6m z5Nz7b&8`@muz3zP6CO>?wBoh9^Zw)ZUBN&>9Z&G72%4w|yC58>nvmYvYqGXdyqcma zjC0|dAtCf}xM8&$exUSYl0+qju{2`-cTfARsd^)Wp>%AQUI*K1N~!f=S;WO)XrZ4d z4Ae$?Y5W_=F3fO*fO6u4DzYzM583 zpSUz?kQ(52Q+VbA5#Z|K+PT_XjK}$>{=Dg2<&hxMQjaPGs2g!zrkN$jfe<7H zAONQZSd=*PKU`t`&-?(Wa8wxZIEp#|Dnd4RXA#K&sz#*exSJ}-(vSOU)Mm(4>0^Yd zV17`lDRZRP2Sm#(3Xj#BN3GLX1`Zp&R^-G0i6~H9ENB?7auKZ&{jq`-$0Ri6w8~){ zxHXilF6U&uWQ(_9>OvPR2dscyQO9erzHJ*JM-xIl1s1jor&5jEm)4IJQqz-=6q-cL ztg_$_!tgZuYYh6dJ*TY=(e|Vs?4cdrFhVyqowZ5>fHO`23Dl|94Ju};@lO&4 zxct14bzK+~yor9jcfk@c0Q=Qm{DZakPK^Oyv{hc598sZuUzO0~g2^>lGSX+#e^5rI zge%|}(>T(l?>R+*(R#bm@4Xb=C{wr$OR#wSb9RbLPd;@rFs!Vaws93GCmVz*j={5NDJu}%ON!TIQ0X)j>RTv4ssJ|~>zMU87^dT8 zSht%9Am4+y3(~2c^k2!Ge`PdLy(_?GRT`#z2vtd}8uL95fo@o-o$enH?J_Xel6yt> zvMI9thO#LiQ(U3uifaNUwRHcA2@O4J?~}S(OmbAV%P^|QZ&*y-HoImWdb;&AeAuO7c8GapFXIiKkd`H)i%x^*%Jp1$-+R^lLt}XA>XOdTTnh z?tD^SXk;TT^e0?{CoexjP|yS0k4d@j0=dJ$tuK8M9d-4~cCa7lAeIt`Sc>_7kmWy0 zkWsc|D{>{Gf@SLCOc_c~KY5FA)kttbZFyp7kihY%M5hXKK2kswGN` z0e0eGq~2>AW&bjrN0#cC!W+e5vjgd0$~zhHY}#(JGFmbkt=Texxg+eb>W6Q^qBH}G>h|-=#i)2oEoQa%f^{#4)rxxV8%!x|Hf4$ zYI9Bk?eg+7f^F+VU4XEZxASMMJbM+^=14{ZA~k44u6~vRHB{OJa;A8>)#wsIainS1XZeeeyV3C#fW=YhF6t0s?xNi+UlUB1FYw!7GvOj z3(M;Q;Pykbp`Zabasxg|4q$f&zib&o3wDwH&1PgPrQ$x#R4V7DxHIO@gRa5q(5)qb zQ;4kL6PR}`6_}s0rE+6%Fj;GL`PsboBeF7d*kUR0(?SLe|FCkdc{-oY6sT7JHa6GP zAjM;U0*^Lbw0KrODQ(qYtxZ&1o|O5X9G%U`OkG!&{<+vJ;dXs+AFH8#`jOpo;-{9f zZqc-FAU-)yE5ggJzq!fw%+w$GYs9Wo?ei~5H?!4R^_3H7Q7$&6~A-MKt*W^k0IdP0FAG5D67p`Hr+ zct(m8D6fzV?Teu#0Ax&y`fV)xks$qP3;~y1EXE_a)iRyzL7L-8;Z=AOdsu=z(!p&}ngFsf z4JC@QX8xP&Oy(y+4QPsSdmXl@^Rfat8@KRNs0ma63RxssIuBwxuUGo zgK{jb7P4GKC)0D&-$V-J@M`Uy^HPqb+z8~1JrrZPgJNGEp1r|s95c*6w_->)xHTGU z2U9?>%{@Qp01tXbfqgOgB2FQ2VsmXatR}=k>;^*YdXocmNvm1j?T$hxXN`xqh#OH7{-ZDvswdGj@2$t6Jih#&OdjO&> zH`$-2g+kS2{B{KsX;4dx;q@lenHBP*MMxoD0K|k!zj7ySp;%H!9L2RQ;p?4tOR*3i@aw&;cxrq(;g+{um6&%jpM|p zAk4=d6RreTPWv`H;Nbc&?OBmt%Yu?^jH}c=jOt^w#gDt5w0|qBD&n49XBy4!!o{)i zOJ7OrzrLhvDoFTCmZU1(^lnzso=3K!v+_)XyeFpLDq0rwyTknRy7u(iNdGG&#JbFG6WYQP9tayyhe>%_XE(2{Cb>XaR$|NWMnj-`qK6yO-d}TXS zDjV<0#?<1#n;;#p*eQWW{)Qm?IYEO0_2##zwx{u(yAKQLbpHa>j#^{S(n=A0DV~y` zG_Oe8j7|c{fTpH^j{$}QXUkuo=%Ng}BM2&q2No6mHxU48TU*?E09~D%ioUB5z=^oz zw>SV-2_S9Jl;qt*oP3+MZQ=T0;On2lv$I=JZp>5@I?MNrq#k&?sJdW20<>L|^N^SN znK4>|C`uJooD$NHkI7pk8AcOyY`@ub#jCEPL(q{vCOVjjR6Y;_BJ#FOBOGBDh>3Dy z2+@KsgbPc>ro;>%_OJ=+76TMm4)(_R`73F4@n7shkI6P#cygtfiSRV9t-f;g6}2*; zV|>SIasvjeLV64&R+`3^H9be{+5MnKk41`ye3}3AWCCHyTDQ zGb4q?QV*E>Yxd$Bk&@M^q0shhm#Bn$umC*yN|=b<1nIp!8wUd2X&YZxg#er4=3)}}$O12hL=nVLz}y9=ig>CyJ3BryO{gTX%zWuF7nXZ+;@_F5^i#19PVB~`}e z1Fx?kWkyMKhG#ozlj|@_qVH)}u|ROwszap;^d_Q{+ryv5NrfhP>yvPWLUA9zmHxgs zQ58Sn8N?r7A^wQ}cld)Cjm@ykk^=^~wvuBv0z^M&xorL|%$_XvCrD0e?|*S{NGgnA z7J*8So1r}YHPc@p1Yl>PZ&H3)lzw50aKuGoCx|6h@4L4vvm_9xoy-|R5MDxvcYUlI zVyB8qiB&ay@w>v|Ay2w)PhUBB%-d-|!j6s>5`(>042p!2Z}<@0So(+b8Ihapk3YPu z>hAt6_G;`%3Y3kf5-OQ(Ra<@&Cf|}i_yh$2MGpX?0+`9?(KXWHwZaCxJq$g`QKz@Q zkW6zv$EzRjXK^}fl)CJg3$K+~ITwFslwVq)Br!#iE;bxob<;onV(R2M^N?WVLMuwAHowN{0j|+wt9EDG+r_z)zD`5~CcPB9p zPUHG3EaoG67W@O}bLhn!k?g9MMTosVZ=0{Z$?aJ~YY=|vwwnVP=Wmfm!>s2qMRaZc ziV2~TP{H0K>$x_`vj@%0^pVli%#_S(O`G;-1oXv+v+t!)R3g016dx?kgnc<~3_qWI z&o_8l+Mj2L9lEskl>HUTe$;A#qr54j@_yVX4G@A92!TL||7!p3zkm7!{`?(DXT8scB;!t||08~4eGJviuZYLBRMjp8iOxKkl8(q7G`nN&2WNEuIck(|d^8ho* z7<)_TNK)nz2XJV%Q1V;NDSBG(W8JfyG!w3C6tfG`v@yfWq^<7r72j zBt~Af;PoAbZBOW}>%ho6hZDm1cb#gkjW?1n6+qol(u=MbN#wxh!YOahoF}VWXK8U4 z-ulJXOm{3GQ(RcMq>;{SDj*IF_!kks=<+|I&VOt$Y&;JT(|jj?4XA~!g^M-kq>-%Q zM)djo0G0Du|?0I<6j<^+7aOBSo}MxP2G4xl2RUsiG&?gNDeX9AZpkT`x7-5$f@amTn) z5Q^46nnn~41nDGH5hq!kbMPV&M{0P+Z%1$B+Nlql-C7sObTCiYeI5SAu!G!#h@~1HJgh>1x0qEa69wa3LRP8;ZJPYY|64 zHbEt@DEr?*F=E+tK4LKdDDTBZ4uB=d$R6`(e{~&<9mffCG9imA9mOh2jp!2ohk@fUGoJkeH#$+w=Bj-QlkC86o<2C$ z;IPob@H{w_A*5!4=vf?N-z>7fR6N;gk50meE3nR#5zlEXVF-T-Lbuco&p{dMmBFV= z_R;7+165M38z8n=`k$32@Ctkb8C;JH{GYefr*h zhzoxaMD`W+y}XIMWe9{mJV)Jk0yW$FsY_FhILi5!aX#xbAoV{Tk}M2FVYR#Jsv%TV zpO!3{L3{-%sAd0GSPpfpR}zjf;^Gtu0BjHd=S=XSZ2-s_PURu6B+{Cn!bne9ZR2>j zR7A?aSJ5-ab<^UQF&j)|p*YhSC7%5FH0ZoOe{*oqW#33d53@EiRA;HMQnSE=o#qF& zsb?Z0mOo$^>Iyx3si87ZVg3w;>>%&nfuZ{xa#8&ujpcAfkg2sFY1`veiTo#Dm2~dl z>{94&ht`0*Cfztb$-omR*>Rp(dn6FE7j{9bea(ekcs_{`n2l zLV0Q``J?D1QC##P2dVWp^C|r#gAu=EAph#ULuZMxeF;8E6pO@RDGU$sR+k8(NW)vS z+w>|71M~?L%~c?HRy*ozAeT3esQ|@r5;MvR5a=8$Gae!pS~54gaYxbo3Z!;V*V_@x^sp+CQE^? z<@%ZgUn&3xCPl}Y40jxYGOY*?33zRnfB{5BON2AUA{yquOAAXy`7@PEUJSajxz_v` zrxIx)wWaXUO>R0@BDHtQOvL zrxJK8Il@R6doU6kog+ZyWy)5CBwF?a=PaXOd;igX+S~!KeQbg)lSn45_xXG3wj6_c z8#ahRu6gPxAZ2`-@$}R;@Ylm%-QjG0ycD|7qG*VmJA{nHbpcwsgwAIR~$4Mt`w4}^kTNG zr{eqdYlDkXv&cyxhJ5hIe@&K&zW}>WdZb;J6{pU#-^JmRDA`<%t<({u3rcuI>BIh3 zAT|Bl7MZ0yJPuTnS!$AHB=o_9=QtOG^WDwsKJVriB8VVcLYM$Gy@WZWKLhZA$Lq zBQD$>@NY+h^caD|3|)Wb>w)4X-Dg&6!KzK9{Y8XYVxu$%q57;_V3<&AHxdW7sh3siZ$q|AZCjzi_QH7bdwC4ZF}#sP$p!xgcyyU$o`z2JUyka*>qb?|)0`Nb?$(|e|StB+c7 z;Po7ohycu9M8x-q{WuuHaX>R`$hi;9knBx8Q758Y=8=0$*rq72!4MqxE{olPz$N{8 z2!qK1Sn9`+PK=T;vy{vrIy0-GE>mjS5%vw4nVGD;)6R`TmS_|^%x@+u@Wz$YOms+^ z2Gn&6Qv4k{)-Xed}TQA!_)YUM~y{{*fVG6CFxcaiEbdA8g!EG1b#~h+JXpvo)3RJ-o z$vxOdUSK=~rZRn~Y%TEZRKM9t^UcEPHWFDc%7R%Fwyh$6W=fv?ZbF#~2^>dFt4wuO zsB5{BJ6x>|E!JN1WS`zWVF9q?{~%5VD8J&rX1xDkqyJVaQvfPMh#XVZkDCW_8&n!j#8FwYp#318o=GkRi^J9cNKE=b&?RA3 zs0TuEX~l=#u&H&aD>7D@*^rI9e4v-Fe)_!lPQu*YI&Titu`(9N-?Kk3aj*J?-*Gdy zcXzBANM>QhL#nKYTTaJm=lIbQ+Mo)6DC1EC;jK2ns-WB~(_kM8ibQ&#RMJOk+u>D( zKipD>YtucNp-~dZFi2}|Tlmz6qW3b=6Q`3Zk)1VI>Fzur;h#k0KazebYW^3y)h@^U z7hR{x4Mj`{NVnnx&Mj+PoG4O>zq>|Il_A+jH6`#U({f^`G%U{6ksHyLW2kyH1IJ59 zgyp`E9WpJQkYN;^%91LcIqV*5=5fm=E`g-pwB2O1(;Ny$(JCjur1T@G2}-H~xHJPq zUawMtTmhIM7un>75|1iW9!{%iw@%|qh_Kf2YKjCNr$gqLa?HFT*3Dq!rG8#p3)`p} zZE}(OD7Jh=+xDa_Y-9y&39LXHD~#!{7r1baa;Jn?bzrvq(OuuJRmYO29BU+Ugu*0i z@Twf&<@5`I%Utxb3?DE9mW;ORgk%Ng{%+R7a1j5}6o}i1$^NWZ8sxRc*fbV% z0-*m%`a!IOaw^IHzi6L?k1~;!4Gln=SR;7;*QU~zNGr|>6W`RER*mVZ6>tf=hw`&# zmgHR=zD2|Wo~%xw5>fW!&V)fiWK6hl)p7W+RNy&aXcdldukyTMRqET;_WJtfH110GG z)B3U)r?}qJ{Tib(Ql;*MC;L;GI(LIiiz_;G@@Vvwu?Sp`zQonP9 zScf$b1n5<8B7&_LBz4}Ij5o5eGnuhxqKv%&`nfnr5~!+CyK;y_?6oHb_YZ6fv6-58 z^PPm0EU4?8a{TxGyit_OmAEQol+6!Uau+7GZ#Q-Gy;DKV9Nu$4C#NthY7K@D(Dne( zpD}FX^ElEv3(=``o%+}S@4u@h-!B}<;YYr;qtJSgb{>E=apnMR16Q^ri(Y9^1V!Ao zj?}vG2Ft95kYAEOSbGb>yXLwwU5x+e0F+RE!+&Zx{)-O$iE2g$_rR3G+rPU5AnYFG z5)mi>c^d+Qd%j12^pM&>O&2j{ViPEkY)25r19IrMfbp$t;;N!{cZ+__gPXqv*TCFB zDI=-TX_B&%L5ZSda#XM?8CLxEwkdztj#L>n5UWKdsZT;+jr6=@PP?&4<2xRi>rtMxo3qq5~aTZ&#E9(N-MtM$AQnZs` z<5jj)&_lW7HfvO)5n5-Cqf1yMXPaJft^sDAoh{{@bzw}_L=fx_6JQiX!xso_OhFD+ z(Kthe2ui!V5AfBV5eok^e@_>L%>Bt{v`#WDmE;%7Ph_~N)YSC@;VI;I?#UZIEqE*L zv@VVuZs|2iE*@%)EMf{toEyBIn9|7K4)Q~aBGI7IlE-SgiLycD%r!By#0E|6yt2rmBTGk!RWub@3E z`^D^dSJCle%~leHe6~$$%VIhO8-;op$;6NM(SBN@yLKWcYLf(}j7m#ksNxQ5gkm%Z zeas)o;&Lv1OZKmk>oQvklUaiz`ocd{f(6R&`0qal5WqiF0sw{cl7|9-jywWUKy&Ov z2{+PjHsi@t$hMgQWk50R^Iqgo9ne8HZJZZxYZ%BOUh)+p2x zePwUJ8vs!>u+7hznVP1c1DL4+K+XTOjpPD${h)E20K_z6r@MYygeb3;K#FU0`vxG3 zXn->`0*I!Ppnqf{W(!1)cOb3HIPJIFQkQ8UE(UWS7tmp+G-GqKI4qpRksUqrmHRz8`MeVpx#AC3MX}unrw+z-%m%acuN@>2R+_3UFFe44 zQjM>DiTap|KS(~kcfh=M_Dh4xzxEc+M1Xid004?Al+#i6|3o5Sk&}YASw!IdwI)Y^ zFE?QCi-@iR7vS6M0PE_l}14^KUvmOAjNXQ|zsTi#81UKt&S(%=Gt$27;kdH1gLW zVGC+o)RO)wD_cGFozv(LKx{Dwq2`ddiZs&Z#y%+5&<0yZ(LV;1`a>l~KmntB|M|5{ zBr~+Gb~$*;{d6+1>)Ethef7l=LLeQ=W4UV+IE2zUpsx%AlOeW0H+VX(@5otgoj*A% zm?SNI%G-D!QbLt+CrvOadOYHVD$Ug<)A(uT@N2gT+#p$@K9gpBY4pmh?RV5D-;9DWT0JGqWTGIQE#xklhyopkBgTq1@R1<1F;@XL9pM16xuYc1 zoPjPo?eCg9Ua5OQ`FWF;f2vIncX@Jo^F>0f-?yWJEAGgKl^vnNh@j~)f8T`80EMW) zfdD#lK@ifVZO`Gdh;Y)4l#m8|m(~44T^>-Dl!2=nj0)-emwg~xwnU+@s@?=BAxSml zP9t+h+a2|it0(^cbpAKS_Znu!lWDMxnPYFB=V?lm+minI7{X!njhb*LFLpyLT+Y$^ zZDp)kJatMQ#3uN11%qWW%dF<2tL6nVzfv zMuWbp5QbRH0>e2TXw`gO^R{ILgv`KeayqN1Kn2GKK(z3UOiX#7iNqsp*?=ie9gG}9o=P!BlnF&>ESA*k{DXN~{%w?5fQrHmNyoN@J zBiSb*o&A^GukbSLhf2lpX@;ylMRfr|ROG=t{*@*|iJat;`Pm28s!K<48LQ9(`!n-x zz<{aIyPN(dtkXs7i$K%)xxx@Kf-LLRU|H8}z&QZsuI1=jzA;^$*FMxJI_4CDMMGHu zzWFOSxfJK3GA#)_l?{=eI2TaPy4~>w1`om8aXpW22kq8^<4C3GdYkPfC8Z3Z3Y=&wU3w)C$Z z$aJq6Iu8S8AV!`tI{lyL3s_nxf57&C+9&?^4Bbz$N0$fyYb@y+R3NpU4@nOUO$;T}L8f;4j9#rwCrZsvPc{?pUi8t2l9!5Nn7zA$zqu%z zOA(|)Y_u)kBT^28{AEcJl&P%6w*VdlwNP_RC{Ajwg&0}v=;6@;;cbFT-=EFWi4m1@(nCW zU`30DfFUbTm<&Z}A_waC4vg<@2+=K+N&=2O_~JUV@T^zV&_Wey>@GJ7mfK&-3s#5* zo4rdNR#P6PfHSNr?7fG*hZ1d zDR;RfG}A-GC6mS)Pctr#VWYxZgc1T^{m2EPe@TjI>bJ;iJ{GM6_z;FNnHXB*hCZd_ zivZCS($C8|68*BL1<6V zfk|-NOsa9P){c|OrF{tnaimiKB{JDfe zETR|=^duq>%`Y9{t3pYTs)W*6=S;0TunrQjAKXr5BbL*kSZs_YXb1dGjL<8|X$OZn z1&t>}EJO`R19`Ndf>9QVwQ`xTYd?Bw3bxINL<g7^aj8Y$uFaeR>wOg02H&!Q-k z9tW#9xRqgg9k!E7e&P76S-kM&EYuLaI|b;7;KVtmZOiFRM%uk-ECfnEhq!qM2Knmh z7ffYC%C$EWPBAXm%jzBdn&(GyeTazzIw-0QOi&nX)xr51h%I*uKzTB`cvE!qbq4_Y zF9j6{@!!eD{-0C!fAg8aY@am3L>15)DwQkbHAjdo&0L{rw6j)9PEe=_G0KSo)qTM# zlGbo$2AHUJ(^-|y)1zvxr1hnO$_;btXe?k<1qcH|2FOfAU@cn!dmuQZ2=Kn(G(d39 zIA{+H%OKAdtrC(gKdq)-m+Y2$;2;Fyo74rs00ak}G(MOFHIN(aS5j0TLk>Zf`_YJ9 z7CGDsMVaf&;gFMCSYtM0wp$4vhbd|ag*Pum)2|&|U^h;rfS{ zTH8-w{E9uj2Jd0^Gf7b34GU^q515Ex`XLbw4?K}|9V7`OkkB%f8VpsAZH(99XIJ&O z9~Ke-u!0xLnFRm8ISs=P&~yX!?j#JPTRS2VpK`W;!+TVACVT9elP~t3Qbp>iWG*hfgX)@N|1=!W<-xs z`ipZQkpHT9V_x`)okao=79_|v^(WW^-r8b2y__Ik?js{O^aniLbE}WC-w65DW_o-t z1496Qt)5WAnA0lDm-{_>pai`X4*LD#mnrTe%n)ayXBr3#Zxf`RS)6H^8A(Dw*KA8x zepI(6MQP*Q%_6;~#@QQJ%v8ZI9MjfS7W@`@zuoMnOBd<%)jWNfdwCFaS`py zL#HG3Z>F!&N*~ccKH%mnkxJaAZSa}XF>^PfpCIc;{ z+TO~(!3=6NwXC;m>-gH9ET#lOy3^1*F>TmY)quC~kI5wlwyi z(@l5)0ZD;=jzh~V&EM^4lB4rax>w4Uh*a3?sRY`sNtNRH%g2O0E}+&!hV_wto(C6l z5YPvI4LnDl*ZP6M+9+bgG0*BtK(5pXP+;I>k-_j%JIH!+75Fi5w5b{@<5`(0iYiCE zM}+EbTax%4-sGvdk00boBIKC`!~Jt6r^6O664ysSRUv#FTaD-Kj5!R;AGhdve|z}; z_J$%{iI4g;uH|cUv^*(DGrYg&&G=mFx{O{Z^kHkEZ+QCS5EB}+h-+DQw(M%GTIHcO zf!U*p(_g_m5}TUa+qa&3FMI zLLGnVVdf9yN_ooRdzY$k@3EAkXbLyTTdC3Kvc5jryBXDT(qcmj5d!Nu>sn`aThQ+j z^J`#>QxU>`zlw7msyz%ty1{yNvLz(fuR9F6?$9aQA12`6w2RkjeYT*DDXr0r8l(Uv z(fsxib|>Q74<)7gx54^^ijQQa8AvpV#8gR*vpliqK&OzmEl`HLR&Bj9!bU{nGk(&j zEtfjws1Nyi?^8ebyf8++DE11^`9UrM3OQM+aHnzq>R)NYXp9#)8?(&AB@%pxahA;b zKQ(B^Zk5F}ZP5*^?hxMtZAzXket7MPR=xZf-}v&$2}P^LoYfc7DE-_SyOsA^3eYfI zAb1X?-nvPf?2|El8GY}ZB~Fg(Gny1g)~_+Ra1Zd;{!~TM&DsO|)!62E)DVb%dI#qP zS+$Zppv$*}naEO|2<7G}73)HnU9%+Y z<@XR}`@6+0f&=iLsxrfxD1aVNR9-qOm`+o@07tS}zq3qu)>Y!8VCPOw-APNPeqlCj z*h1DbfU3AE!088uFbh&kG=zB0Q>&#)23klQh3!~sMEzFXYh=-Ypw0Tpp<>T{-rujJ zv#qnzErxQO(vRgkD);KezkYJf%0X~yKF&{@x_y%wld}=vxQ30Xvvq^^T2M6Qyr&RW zKpLd^tuTqtC9UaP+wu~3F_M-so0(+^dcL39CGn)Uvvk^XeD%lxS`TBR9ffp0Vy9y; zoL&%;_Cw}bZ@4@f_w-K2mOSU+5t>6)L;a~=1$#1RlG8Y0HU+)E9owzaXJ>TT8M>@T z^vAsWkEh*NZgcZfl3PD>dW7C`OZlIil zWvl=mE%5-MC4NDM6hGj^tojL;LDw61AJd}%eVufBu>S0%IAkR%0sD6w_oITj(@Ve+eTMaS;OQ8r{e0UQTbCb2zOSX(B@yUG#&?p z;xTTg5)d3}Qn6O*a=K=f-$TA<%At6~(gfTp%?p1-s^`=O z)kI0a#W!*mz8H;^8?uJf;qxkVI?@8Ca69RvQ9*UeL&0HWcSjXSkx3-`;A*F4;>F3t zLS+^erao9+}cb zwpw;m%?V~6XQCk!0no2D6HaCCIWGkjE6$d5F^Nu`=j&0GD|hq^^g_TZr0XdTpk)<^ ztUPc^bp53sTAcpWGK-956zFsei(o#(tG%&A3@IQ7()8jn3RkJvZ4L+vpcP}cm`vzq zPI40a0`xu}E;_gS&-DJvZW}|mtoO~?Sw!gC1F;uYI2qyf&0-fiwM#y9h3jK$NB9l) z3J?@q?=G65DY<9`DbmFDMPXrAAEa$jcgCl`-+EOhy9s$b?h%(3z-N=!6+9|LiS2j~ zwHxZPjBL@#fc+*o(S{KOjsdxrxHJSM%y@?n$g3gtvvD5!nYX06olvYFHyRp&4Oxjr ztD-wuo%zmCdw(ysPdvxZ830Qo2UQ=EMyq3cEu1$lX6L3(c zw6_YA?VvYWRx|H2GEUPtB(sd8mWo?yF#iUnD>fHqFZ(knD!bePAsTG6rm2*}XYTD@ z$T8?H;UefOfpulRZ>iIyO{`Wd77pYU-B9o}jWc_Qz07 zOVp@uxR_1h2jpf=t6CWYHfe{572F21a|f1C31vALEZvGHQ*J-JjR7l zn`B^DmFjYAUu$|nY5mr}QRMfRC-$ZA+tHt){kM#!i}P8?cxu{LMi|&9ydGHvo&aY~ z?M6<68#}Xsb1g!4qt_n9u7!Y}9IP=8Vy`~mwZ<^G2ERnU`G>RR=JCZe(FI43UAoOm zljzKD9TiSg3(T&{rb;-TmQI*R7D~ZenrV8&1m>X8g06>I-B0p0{l*gOE;q;`Bi-#C z2c(=-lM|IUouL#t?U<*ovwsQ0L#c}Qv;Bhw|JonH>d^6ArPe;*3PF0$?ZO-yCd2g> zeP-)ED%{aXWjdj7|ETfuO>C6w7|*tj!APb=nE<6srD}+bqlJ!Lo}R4KAYPP(F7}^r zZ?KGfNI)sw6nHNVo$(^y3BEK?@aSk)$^#L++s-(UA^PDmtH;Uc)uOP|R>+m7<*$5U z_xx==^yT3G;)^Di{F6nj4Ge=z%5O+_r?9+x?t{A}$pQnsIF00tBXw#BTkcGCINKV5 zOJB{-utx@5s2!=hYPmSKim7+2-#v@ycG?H2=X}_|V=Hj6f*~@Qm#vJu3o>NqG{y8y zx%vpc(2;5(p_@Z_=bpc^UP8cvV;O1HTA_1aH&4`+LV)qnStnRlkoAPc3YXpSad-)x-k) zFT|Po@y|2lxYwQgQTMR@^~nL^uRuNrPT6pDGlyPa5sdB269?$GqK1w+85_}BEF>?aO(%!4tM({zx#j4>EWo)^MpjMs0?HcxTj)aGz zNN>eisEPJH&9fLRgR?xSl})CYCED0EJdO+_Tzc0=aV}LA^8tHFf?;1;##P2`X?lhD z!^=5|J_^4LJREgpQ7e?$iA{Va!}CvQ(uad)TRT($qD#UQn<=2rNURNXr$;67CUaVvhF`4=~eB!Q;!FciBH;Z}}rd&cLt5_5{2M~Ff&o?+B zKuc!Gj|s%EHh1eUb|I<}lC3xbMqV(M;6Iy*9 zW0l7gRbb8fQE*uTsaC5gUmg2_tT?-qMJSjqwX0OLFo|3gCk2j)PyXj;R8KjUNU3Ei zsKR*BQ!8q%Sz(Yecq#FVI~zoulh*m2sV6sb0^HgHun=Tu0ojh>l5D_r*($%F|GAP; zKo;MT!BDYL(YPdUlxA-5q!Z6j3{A`v0J%> zidoKv>Khuv0vTx#)PD(&2flMy#r$SZ{wL}P0oPKG5jWSd7p2tkSAYSx9Y#cKa#)qm zAHCCfZ zr|-hIjhxv1FE^IAuHkvVN&ER2Cmm1(KjCfjtV7M>|l)u1AhaXs$_%oPkg{xdyb-4Au3I zF|}&OrHKTU@lT*n!XFIFGQiEKZ{*1f!K-Hje?Qe=!@pBWeXK#MX^b2(QehyVYWybDiyOvOlwLV%+j!P`hq}mihooYg zp&^x6)7_tKIBS2zsFI!HrwD-OK4737ue*C^lMP+rU$P*x{5n4j!0ES!!QF?E@4Sl! zUK2Jrq_+ea3)8erIO;-VEa0p`1|$N5cDBp#5^~tB2`-mh>BH8PK;}eY)hZzb%0m1%D0~s-=4Fq~%1!ALW z&S)E!8e-hWy6{G*bAWmvF4ccANB#MmYJjJAhv2qdhSth0GLYph2B_gAVef}~;WvqS zNdoarW0S{=m;SZI8xV%V9q0g!ir&W0spYUD{;j34L(k&0!GP|?5$!3)YZXTRpw-U$ zdAlkb@ArB}$3oDkfOlwO)evT*GiAH?iiw!c8qI2Mg?59^+bcR~e?|~eEo38VH2#w7 z8k}+2mFn0TT*o6#D`$V`wz1EwC$0yzd32`N9( zI^ELU>pM^sDPB9wZOh@eKGy&JY(HHVxeejyokC_r${_5jP34#J`EQrZ9rogBl6R+|bt(0O`>Oq%+WZo_6X6HLAeO_BvharOH$4uHoDb~b za)bESwEOtdXJjcuH+bgUDLBd&-nXAIcI|o<=TSE?L^qQ9SgIld*0}F)ywJvd8OIlu zS83f`&1H7cW|Hz+U*0$S2V?1(V@sT&+EDH5qwHOCmvr8 zgu=AQhgee)G{Qd>$o}aDTd2qIompS6837Z`N82BWe!TW

2qC(yt^q&kZG_5#}8? zKPQYwPArj5FI~7vv<@~Bl1?dOUv~ztD1TJ?RUFbmv4@MDHL{C+5p*;$>#X!oJG0nl zBXY<4BSe@P5V5W;7UtN6oH8FJa^e^pMv|J${xk3Yl>5D#-6OiIvMo^5zc}qG)tr`-n;#Qih3R{sUp>CX zStUh>r;`b(r&lS`@oTgzgm7R#U2Npr38Ud!8t9snOww1AkhkMgL3Str2T(u05LNk; zBFin&V=#t(Rs$c@N58Ov?lB*4H-zReHJ(?t^dU=r9D%aoJ|Kv{u+jVdt0b*&ZNeArAk;(F zS@h!dSv8G)Rot!YCU|OJeB(^O#Qrh;NJjS_ijdt>XdnEnVZ?3{`^=v`mt~eGbyMDq zIeTSsDm}DTso%THqoE~H*^~JkhjC^>I%7KxrWNyuS)PO7D8nTsXbOU+Al%WrNCo6fRYqA zEr*#lHv4-8Q6iZ_R4pVa#^=)B3kDxZw6$*_%T{}9qaT;&7GKwJh0J8a7CXjvq2=ak zPOKcCL{ca5zg{+o4cnmcSzC;KGT9Ij0I(RT-a%Ac_zkz&6a@Xs#qFe3WSxJpjpwBb*P6fMC14o+BGLFXDZmP03Rh~_D?$K=P%7$2^A1`Nmy<|A=z-96Y z&BTXCw@U)$mjpW~zf;_pKzp*y(P{Qu&6%~spM{4Y>D7EV>*Qda2M)sZ)!Hrp>&<~pyqa1dDEO|B%Qh{ zsD&_CjFFywa;TH%AXM9`9c9`~15m+;Y?M?sQE->fbybQ88m%A}jv=OJ)E9mBF;Fp6z4*v) zA#83yqhJyCC;!Zg6eR>f);8svQ1z{mDE!0L(_~Fa8S495Qh$|i*2URtO!tWQ`>yjK ziK$zUBBNn#OLQv$bLnsq)MDDsV>qn|(IZ^f!RqsKk$M)a-fMeDizXF_Rhk@(FjIn! zhthpyXA}uDwZ;u?OPgoTN~1ks>anGpaKoM?8Qe1I(PoS-`jc_XwI^%MBy5A0^o9ls zN0$lDrvpgz|MY{4Wn-}@hnBn*e%-++0Di(3h^vlOF$3m|WTYqZKgr_|e*fOEjqupB zF#4n3vTeywzX3VJn@IJF2CA*uFnv=pJ~RxTU$-;zvT%(`JU!p3wvK1s$0OusdR0G> zHxdF5i!+CO9<0y#{_9p^cT43O2Q#fap2c68!qq0apo_i%tUXIHnsq?Sd#i8#xpjz& z;@?n%yZ56vP1#He!EmbW-^kSpK@mRrotDm3+Y(9Z?0%%kQMS+a+5YiTW%uO0e=9HV zWJkgFZ(FshZU02}4|xdfLU3^#m@?RkY1iWT6S=xSfd!WmTCbY;QPMBx6lPWh`(JjCR{%?6JD_-`a$|mF^izW;abz)Hr*9 z7d|N1zS3g(+pZibT{BV76t>Y7>XQu=y2nB*!}p4(M%?_2P*dpg4(cE*amD&WE+s9m zF&sw1(Zl4ft%3I=)EC$pkacq0!HbvHW4#hmSXEhbRmxMEOuj0>-YQAjp)(_gQ9M?S zimuaV80RvNq||3)Gbf=k(X6d<_k+VT#qN9*Lki1|`a!(Ci#z8$QqUycdPc#K%x$(* zKvrb=WTyrk2kP@jn`k1&2+a#0m)R!&^@uqdm*oRDg*r&8A-WUwq>y=rn<&#No`ZW{%5x0E+JSB`7QQY6Phjb%>!)cFL* zRXwPCt5kq97KQ&b_pg&RhF1+CJPr zLH<=VX$#v;gmN3_>J~j>1hv_&TiH5H%%|nZ zNWo6+mxVokQ7o{KQ&lB`R40NT>NZSYwKma`@xdA>s}-tAxWdziw`^En?-|{rou7?> z)?C-W*!IDtl0okR&-x~*0YfNvvnC0c%b=wgMQ=9#@+T~qtxucmrCAkGJ@-sC9n?!0 z39DqT&J6*w`ZJ4Y?(NX1#$7y6gn?=5gmF~8lEWI)c^KRGUR1PmTDLN1&$J}OUuRkq zM~x+3F9=EE&qg2C>g{bsGZ?=3Fc}l2!1iIx7j#b8%IT3vf9JO@sU`Vj!CM#DtVPpk zG>Q1;6HlT!C*{hsSc9zpqEEdK`?e=Ae}{;HM>Q5YnxPZ$S8PDSn73bauPOD+=)~-# z(<(dq3~d1xAHA=2Vmgr62e0iu5;rYb+uYH8H^B%!salpBvg^!<=U*yuQkdF$&XbqU zx|;C$A#uhNiz9#Abk&=B8-#ELLtmUM8)4slhD-z)5v5O(S7apKzpnrE${@jh0+L|v z|F-YTZ^3E8A^Ua}zQ-DA2QvRY8B~p;Ki&N$h{K|dod_k)Jht!b6ul4|3VLB;DtLC| z(wBYp$;6`CfM%N}j-vkn*u|{9Oc|gkO#g}Gd7=lUQrpUA%YIP;9-6GiWI+MP9sJuG z^T5mL1q?FzXvn-OSZ;cCl@aZqDd0@VIh*W2584L6&9UC5u> zIbw533D@W^a<03QstB(|_)H=7FJg;cpr*(&jSV5V6eDddq4DzieUnRYf?@KdX}&I~f zd4uQD{uI)=QuaP==Q&34i;wZOL_eYkIq197wY3bU4}%gMgOKEr>gi?!4dN^yZr>3V zsT@U7R;?M)lzzxDJ-!S)z~D*O`1wYZuOpmYK@fLnJSj1{2g(zwBsi&|Abgb0uVvs5 z?H6)J!(SV!^LPuXEFFt+EB`-*x%SA~iC;7r_E0UvKfrKBMb~N!SF^w)^S-Yt>=UmEh@w>15j`T+Z>?I0dJy{$COia1$@so@iGmu&jS}XtoJ?Ho( zdpsF*xBrLi9|Sc8V>g{s_oCs8nk&dO6$hhmhji_J$N)ZGY2-@7#W~V;n3;8er5lyv zwU60Ww|2@K_3C|GLfOy7q=(UGN2|u;4sh}i3s_A_AVJS@yjJvFCH7Rj{)pC8avf(u z6|8m45&1dM_icHAAYfXf&|f0m5AQXHk-M>B31-k%Zd288;nL+v>gplYB3W~dM7!Dp zIIPZRy z9IgO#*nLSUVrO^yakG?w;PoYsPn{pQ1lyY@3 zgcDdYrOaJ7M1o>nKAfyJczbZdChPZXPv*DZR*Z|xJz4F;7Npr_5QS*`k6zE1LbiA$ zHs&JLa_53Q0Nsm3)#$L!jgPE?+qxy>-9LWK_u@j9iu1!s(_*DS>+j}wf<)E`7e-ya z4KZ+8``e}{tWxjddSSF=2s|r>vnl$8KGB!RfKkN7_)hp*=X#QiSXA)l$p@c|`9uN_ z1ysSuJ+|$*aQQOBK$wQeOE`tY=iy2NYHw}{)~JGsmLkDmWZi1g*QIrDz)MK+bdBX) z>|*b$35?sbvwbP^wqe4Tz*XGdRC7JGOVTO+~U%c&>+&-Z6nkQ0tpyD+Iqw00vaH#@xHQkzr{0!EgRV=N>0avgv2 zA+(*mqg68QzGhW=2Y{zYWGJSAMZf2n(Lgx}G zkrjy$Q#kOuU%ZgTIezW5$cWf0l}4nY*x?7!YsVrfp!8v>ts%@?wr710=Z|mGj!#!1q({@@U=cG~k zSCeh+!-QzfKau%>)>}Sevl4bZ&5&7;Pa`tyM{u_miQO{7XpB6dIsw&aQN^5_4m>+@ z#Un!^WD-R$=^e*{4b9j zJg>#=!H4y+D=#4C)&P`&q{rc`(Ij4RNy&va!H)rUR#8vR96>mMOYm4l}>@#5qKES#0*XI=nqqP93$->*fw6sB<_+_)iTko>My^LYX8Ag(f}@pud%UHLNs?kpCmx)tr{=YCjW#ud({^E%-(6+9RQ8E} zAj_nP{}+-&aWPF>dt7q1EEc$^1UJ5XIkOMn9Hehyo&EPQ9z)pek%$4X4EfdS23?_s^fTKT$`V&nic>^z3FS$7c=tI9Er@s&4G~i-_a^DVpJXnYcP2t zdz9UQO*+v39daNdg z_u%6`?S%r#{{cEc#lMDZ(OZMq{zs13U=AM{t~zXo1ICJPr}8O9O1caqwW!E(liu&o z)vMo?Q=t$MkqISi0IPzr!%+PRP#-$-z2wBEIlV@r2h?7)?FBv4)OHHk4oQ{(tEc*% z`40R(SerBc(L#ar6!5oWIMa@s0HVQ@TIg~d@S5q z4utt(jfnE(HWU=<9#=C~y+YGaQ^ib!{Nj*QuEi(9_uKovEA{g1)>@P|O?CZ)L9mw| zlq2?e0*V$P7iV#muy&fL92pJ^C;71aqqxDa-r_Mn+=Qx0sCs{`3zX$S*I<&hr@HefJ+nFB1}7lF6ST4Q z$RQ0S!Isg<|K$3Bmk zYxvvb#j$#NTwCz+cuRn1DLj>>0`baR0!Sv_U_zh#fhCIfd?*%Do(p25fLq5w;7iz;5;Ty%*!Ns@}xRoAyzGU)@B zhI*T55yJV%s@AG>;SnBKrfKV{wl)qASAO*n>ccw{vb@A&HrZG#wb=i`?`Iw%e=wB^!cuO4jlEskD~TKQOnl0cwM*@{{b#M0Ru z-s(~$!O;Qj>GK3bl+FA1mg5LwLe8g zf&;&7_?tC1DfS~u6)Y%AMeh~svdAz--J&GoPZo+mlZCs^DR$F9D%I4Sty$J4I4d^l zau)sEuJN%5+Q>jb>&}H>=)B0rVxPAr1q%5p%)di^rP#a2>y`=Jf9=_AulZD3qRO$F z#d(vGy4_agiR!YYPDkc8Kd^Vc&%zzIad?9C{huOf2$9xO4P4yP$?)0iu@kXcs%hu{ z@@7P?D^QOXahlmB5!z%4u1N;d5_zBW$hz?U)^EwoRtOz!3(2;JQds1&eMng!SUk7? zLq<9H>(ix)L%dg-3~`~SXU_BJd42S*R~xk+W>^q;e|SuG3}i4W{q|D9OYn#yfAozd zJT&NhU+`%q!f>}lMu7l$UJm#~#My68ko~{!Zfh>@2%qLZjV`uF z_O13O)I1`i??lg20J835MTpt$J*DYBmLncYveQ$pkxjxFM+38~f)1<6vOE1h6gy8g zA{uT1(YTGte>MZn8e_L|3TUG<;N3Dj?q>8jX&67@Hi$VisUamEbPOUh>8Hd8wq1{Q z-)VG{CWyDzQBpa%smTd@MpK=(Ag}=c@!czR4W_@j!rCQvtpR)Bml>LfLB*viZV<7@Wjun<|XOSU|WX&rfp$!wN6p!!muDBd{?PLcr_WTWJn#nh0W*xOzsyJ z(hUXcNTQlh)c4vn9f}H8`<*vnG)ZWI%4HDMkbs+umt|byBlwuAg^KujDq-cTN6L@= z`#|7LEFjmRdsylE%Yol!MCq)}_x*Y4>S}d&?AN40mtnPxBzzKf)oLf+%C03~HNt5( zcp|%lM9YG_xpaH|jQ{sRb2^W%!rqLw(EvrFtAK&;Xl=2bcxnbU2t@4b$w*_Gv4?lF z)(SbZq`D*QFqDpF+|-%+UW2pheUv*xGKj;Ehxj@9H!@(|wl)*%S-xO1hXJ$OiPxRr z?x>n)a(u=8_oU7q@bJ5)qeK@7Q0T*+EIRASh!L$1Ng*>DUC|&Xf0u*vG~HL?1>V;2 zb7;l2ksbe@{ja;0hCgxv>4#-fOnkNRHGw^81XvVC8D__whC z#|f;l2R4;nU4^VP4KGs{s=eDBu_&<>GUHkrcRjED=hk|~{@Qe_Q`cY`lx3%J^*m8I zd8heKYPJou)s8nhN;hMi^{{uulLVIYuIr4V~U3NW66_7BH_y)a+vZ&@q z+*|Xlzoo9HC)S9ql^Mo{S$DCb@hh6s=F_0gVW8 zP%wr@nX|#P{xz_o)S7mLZH{U=Sy(XB>x&`-g9YtF4x5HD!8$}i>~sAh+LEy)G) zNzxX93xC1;C0G0OVW7~j4AK+gaDpKtoqG0PAKW7Ko}SLev*g?BVc*8&U|<3dpy__N z&$d0U znGW9czR1x96BV_Q)=3p#U5E(pe zzzrmjjirrhhURkR3YXSv|8*@+?Z^06^+AY50j2}l$lsCr076I$<{Q5N1FER%J6@l{ z6hD$Y9;eP++nM0Pyb?8T!YsbaQDP3e^~2*a?F_HgpEx}2u*fPipmlt}SXU)LK@D3% zo9LR|b*iLpDU%NOYMjyfBL_QTiVd1by^Z*U?H$0w=?pbgMaD! znO@O_i@iXb_J*}cDhw+G@~&x`zjHE=IT^t;mJDbV1h*8|p%0jKjB@-EK2B_w+^a4l zC4_Xjw*4{x^1J`b`dCx1eASR9<(0Y3>FRgPE~c+PtbH z<7<&pWp7CyD?k7IZk8!hcvmN3iWNC6Bk=HozUjM<*Uah3N=e2FWO?8|r5-?AxT!t$ z^1`=@n{_@I#q%HyIdx8UG(b~T7snI6c9buxu`sBUKJ`ooG+4&yI7+s!h!YXVqSls% z)|IOqEG5Ynwa}5i&aVkvMi`Ze^dFJFXi}t>ji64shDxDUWX%jw|5Z@M&8m3`MHF2K z07O!l&YN?f9RiQqv~k*O$9Qqu%jgP0>)KgrUq}nDvFMx-bc%^*2@|e3sZt9l?f8R!K5$tLYF`uf;aSTgQba1Yl3-zZZ)B9-db2+xXRE3sLc?dSB~>8UU9c( z{TvXvtOrCeA_lpPITXwh2A>FYTrE!_IDXR{?V ziE-9hQ@Wi>Fl~it)uWa$an_(|-ILK_C;BLy{Kdv_);E|qM2=gt$wlhn8HafHlI~U3 zN|i#aVjqEOteP3y$4doR3MU|K6a|=6CaIs*pJHVjd&)lXSO6^N-bGoz!{Q^ZWo$of zN}=&wo*@N+TeXpsYrvJcui%c zY8zx-pwK*{C29u5T2o*6t*QznBdyq+{w{tF9fuF^5lsn$lrzY3rVRP?BD5n8gOe|lGeI{a;Y(WMuTA2~?T$E<_k0OBKRXbUlXu9G^YFYl48kB+SVyXNXD4a)tn$5|bsOng z>71ISC}B2)AR2qtUXV@3=)TiX@q1bnx$^&R%U7QnoMsX7Avy;Xf{jY$j4BpDWzc}! z25gEHTrAZSI|G*Y>B(QWW8#WI?+gz&m}@w9%yD5Bw}zFj7=75YVEemz14cKh8A2Zm zI)(IxCBqrZ223j{p~JjdyJ|;-sx194=P+zdIo=2PmVMrqiXlPy!7!v{J*5!ZBTn}{`_c`Gf5o*bydk}Uj=nK$9U^9Nb>SI?J4pF>z#8n*g7)ovfb@W> z!PNNg_PD5ixN6qdg^_Or*SvMJCE3k|s}xm*(LDe^^gj-56){Qku=_HFAJNcP&D{r^ z(Q$kXFfz-`b*%npmBM=$d%KJz%-2Uhm=o6Okc$Yp?1fL(+K%12rII4GA1)CpmcV>4 zG8&-v{x(_QsO}DM|khiiB=gV>wtJ-oQbg5go|I zYP3klg<#SKhm4qYuCMe9M}^_o4FojJkb#Rsc&&OrI~5l#|-i1nSL*ArA=h=RQKl^ zo4G!#IgkTQEOx;kH6n6NGyYYc#UHZIpK>-#ajmb2?jZ>xW49DH8_#moxog8Ng)AcR z={;`cwjf`RUNg4`Fd>kNaOh4Cv&-|j*`5v7ckpva7L`C-YlnknHFdW!)i|hpOn&p~ zEe)2dL2*{xje3ha{nJ@Q_2JHA^u6B3v{&5oy^mln*hC5o4zSN`ldjmPxJsPT&0_tKCZARJrU5tmkY zxINr6edf;c7%{mGz_>(ctpYQ?_61NqLG{Y#CI^Hi0y7{Zl*Rnv`pDE3$K3=l)KiA}IQ8PJQM4$+#qAFi!jc+Fhd<0NRIxD47PH zSAUy4zUz59s?0m$^RhvnDhbeAbymn^jC0!_3(o6y!gO6;EePM+Wd+uBSow3&>WuA9lOQ4 z0w>U>VLgB(r+RmBk2>Egs6f?`HVLiZ_0uZlv4n6L#g6 z>6T-Q?w>SppPIODjWk*HY{LMnxxh3d?^uX7xO7Rg@6*Or+(Wk9L|rH*v6d!$<$tEtsg39&kSW8X|o?*P%jeb?iI4v4H}DyM4Ey2 z;dB3#>ok(g8DE)otElGbm$jP~x=uNw7b(D_Ww;~TaVummt^FSV|Nna7OaizD{^>N| z+#e)O&^kj>}NhsUmMvz+E?+=-{fPYXq@@JpQ z8ENl9Q8o{9Eeoay{c^^(%Gotwn*hsSPeYZ93{ZMGV3W+PjNa5=K(AS%T31_f8l-sO zBB;l70yBvcZ^nMlF)mEtzk@N76-kAh3e`&vAH4Ubx9$cuT}P$mNY}soFhZB6pVBD2 zl6|!JTCx(`uO1yoRr+kKc+TO?82gb5hR3WWyok+oc@qhLBYt)=#&TNdGg8mz4WC`Q>U1sDTkEl%tq>y&@1_?! zEclDMrdFV|vqLzXaT5>t#wTJ>D2m5*W^b-o6b*py=63hpH+Jw)A>8v_4zvy8W1-E# z?EzO_i1g-HVKkpD89tu}lf+dS9v61c{gWAcEg(bK`> zn-NVmpPWKCOMR~Pz}`pGy1pm6|3NS&w@(%v(f$v`-Aex(YN*f1P4&i|NZ*a(U6T>xw^+l);b8HsavPpYmDnU?0}H-H8U}f ztVAK)4t{$G2A4H12aa{Fn>28O5j+}hn=*xodOgYBylk)P3ggKTyFZNXveT=%s| z2LnLJ21$b9D$dPb6tW}73Z5jG+YYX(Si8tJ z(a5U4R82~mItP1??xo&lwDv{|dDNkiL2OMz?dXKdZC`?P=TZJcNd^?TFp<#;w>pD4n)F^4X zpf^4o@Ntj)DyG;x4Pj4u8Y@*)wKpVVa=x}t zhn-%_tsT1e(YLJ&5Yu~>c`kxK{%3HLl~pMjs9!{keGG1a!j@gv@VZGgSs7XY{`-}k zKZB%inu+f$UIdwHdlX|qBAY_KRs?-r*n52YK)nC1X*wqZLJ!oL+(uWBUitBn>c~TI zI}lIe5fx5yXG9&*5?YE8dali!Wd^7ab+dOz03%QhjpygDA|UpUQOA*}DD>vw1v+A9 zJ}YLFeDLlrxLZxTtSG*!`KH*v(N_b)FG<-)dGtFrS0NYD+P-Oss?($J55F8Av8x2? zk82wT`O|+BGW@<0r^jGOV}S}Av|mP`?}31g?}~i4@g$tF91Xj1MrxYBpt8roC*EZM z0O4W@*?!>ZrAnIB#Xv~-jWRL=&!7!j3@4yPpwJho=C2i~dMAuQ#U6L)d53+7yE%3n zaNjtGzz-oKzjFCh`PauI#a~#7-1E-NFao|g>ciPFKqlZw6OswyuKm(Z2bW?spJ`^8 zDn`GxzM~=z`Pa0h54g!7bj;xGd6$fM@@+#NJj|)T_mY0y%6wQSic|?2Uz5u^P4Wc3 zS@Xh^eDM!XOp;QB5gLlka@SaJZ#{rH(PvwC%`aCWw9!e0;Ui9dc&Ro%ZLh~~@_B|< z4l{o-w}N5~mG*P!$Zj1@W56@(KupZ|7OC$9nS&w3sn!N`QyHk~!4fSfeYH8TRhEs6v+w{4@)m&Xs7e80_91}qbPCoAyr_{y&y8g&W(q<9V%efz!N@?7kE;t=T2vz*ELB zn5KIjfHD+hg7@O9#JZI~E2qnTnB6zY!mEj};Egb{oR~3-usm8+T%V64sI$7GY`v&A zjjSZ1?`^G+dB4&^-kVwoyCf@WSe2d`Zwd2 ztgPCBtpJN|<)@f#LYFF<{C-c-9Fem_w*N%u)vUI?wg<`~9su6fPCfi1YxakPIG5G{tB{+F>X};<-+Jwm1606QL2|)BM6MtQA=-7> z?GM329KG*bYmOp(3ZXG4t2Lv68R+4}lb^lAT1j@yrNMbk#`*C31`bdy6+ZeUqdb|* zh91g8rdK)Y-^!ZS&N*_1<=j+^Zbl)>esbOqw|kM2c3xz^Z9;o8t?u6w*uWm^nf zk7%R@?5?K51~&nHPi9N7{q#5r$I{U_^f2lDVA?X&fBOw7EA;cO zi?^gCclx6| z+)viZ_btz*Xs8w_`x29v;(!a4f>GQ+!}q%&N>-D^C25*0{24e$5|f=_1&ctR2FQV4 zt7$p>4@2o)zdlPqFzBl%!4NbgSCMh%pPuv>p)}3MwScXv%&q>`7mIGtuVc+E6WJo$ zf1j-Jhl<;SzhS2WJPULJoWp|lu`vv0LW{6D=3F;!lKj};T%S%#5Ip?@$s193=)@+E z@6Nxo(o97DuZ4J&_1-fhiK9yCA-M1UeE1lSsaNSAl~rHOn?Jp;xnl&dqQ~IQmEl07 zA06*T{@h(7Ri9JUGtpUB`p=Gi$i113=rNZZ|E-m881Am@Np=m^DffrBzTK}@IBoSK zU-XR&`+nGBjBYxiR^9(O7J#Y!gwi4R&9%jVLTx3<)fgz^2iIdQN57|geE5OL6eL~- znlOq)>MBR)aEOjN%)sAz#U$=+sMAEr-=hb5BUL&C8Ecjnk#X@XiEfAyc+Gk|PEqas znL&l0{8-J7yv*Nf!O8hkr*MJd(&$3#nGr^y3bhEja-__4Z=i#cguI7(i3!ZUQZq_* zzg^=|uGSoOfCg15HR3U0>R~TbRsy1UoeZ*zoIlIu4P^#Ab6QP6;S!l@l*edtcZAd` zpHu%4eMCvDVKYT5kq{>4@hoQIg8o@Q)JpENWV8&a9PO+U^8;dDfF&eVTN_ZtUoMK6 zMqTxALw^tCj=}ZMa~V&#WTUAK8Xts$$U%eaR~%M%MFZ6kVIK-Mc`R4p@1mvtRlKX6 zaMe~o?Y>t|pU0XFvcyYoG0=dDIFRR>Ec8s6p)S3Ra2j2gHFL^Qmx0+lSeanF_0fG< zKa@~WcLXK97j@{H8mH&qUh(;eBF}f`5erTQ=w&^NUtVkINxN|*Yl~mx^65J@-nE9U z=%llGr|x$6F1LGLUzApPRaTgowgd}y=KjZ2qZQ0! zj|Ztv1h7=#4CcwccOc~eDKo0&R;{IG6=<{jX-A?ZdgbJ(k8yw48)fpNdoL<*2J5NB z+=L>&7g+~I(d}(`5T8J`bn;|eImwD_PQL9F0W@hh%1onek2X`Em&408P=FKyVFZfu zAG-?L#3CHI^PB)bbPO|J9S>6F7v&h+=n04qcPCLPIP$ztCL3v$ zx31u+*V{nthPF)30RXIQmxI_|bEb1#?w%{x?b;CYH_2*)+n1`|_9@3!5|*qS89 z(S%c6&oog%fqtPw<&V6>e@1owgOk}St*}RW9>kPWX^p7%c%hBmX05PG9|1rRZjj!J zyu^LU5|JjD)TwBeyKoxu`h36Fh27)vPWmY2R0c{Tc7NrP-d7(SOvS zgdkt3GV+$m7PqdeR@JF!pjqvOXZCJj0T=|Ui=%B)x>!S9Ed zLkp-Zlz^Riw@@Bpcq_DDuJ{-m^$(+*(Y~b99AWta+UVXpdo{fANR*76*ix`(-nFDA znNMHJ?LEp2vWBO)flKCrfI3SL4^_ShV^HJuK%-Xuzen$o(piQxOfG1o($zFrFj4>{ zD5pCvC~LFJR9iMC*4T%z$OKK6AdQMUd3F6a7^wbZ!M#OgBgZJ9BzC%*78&b5xU#M^ z-n+KkDm7V^(=NUz+!Xi$p`+idf|}VLR*1wX-J1rNJXW06X!A^1t$IVAfW@9>(zrLg zM9~=CZEK->w%(U5w^@?cQDbVQmdfe`8%+|_bjrqXop`X6z(rBWpr!bi9MGSc?UFQ2L+{%*DR*EnxR#d284U`3<&zo#)cPF zc|l^7?5yWUeO|h@zSDo%Q$*nv3JsXpA11G;+2LK|1H77rkx*E25m)88s_m2h=2Y@2 z^Og)%ZAUa~4Eyv%hUFpmL*Zn^xFbqK3!sWf4|8^b^XjXLpP!g2JIDGp_h_I~60C8X z^>`$)2wV75R~;m~+iXqW59JDYHOzbq^x~@L{CkU&P2MkCVdd@7M8hM@fhU}(m;^ax z!5{PYf(LnvWk#VVrR`ra?_idAh(~>_8~#5>JC1umwbcDP z{O5{c$Thy&r;Ed|Rvw)gy4bAW0`nW3JZ|Rz%aG)T*`cTiM-RkC!~rg&Wg5)_-ChU+ z3mn_T^1=4!!4*l}8k4Uz44l2;Q3}*?Gr=YnTXv}qlp=6hkS82lOUPrJci)8ZQz2+q z4L-9bEX8FT-XOuN6VD~p3<2nhB8)%8dAQ%Wm=xmE0TXzbECp1{f%JN^jxj(^3dW|M zY41q!^pL^oPKrjN6M5(`7$O?o$D#|RJf(rpN#T(>x`;iT{pK+_9iRr5kD$WgvKITa z!L`>OdZQ2V_E@OqL6OH6iLwFCa>}M`yZ~XC$0uwdn%S3mmyH*GKr>tca=)G~R6XI~ z7%gG=eR`!kGsEZ}HEZ;_LGF07 z4ah|i;iVcJE`rx^Yn+8y3~br95H^lE419Sjv%dGU|DXYFgt*h-!Rbu}dbT)^jPiS6 z_)U*QA`=eafIsQ~N~!a?HKi-8Qq3|Qy_csm*wKYJFtg;SS#bsOvXpXISV;t&qEbN+ zZIhzj-XAHvs@SHoA*|w<3YK(j`;Ali7*`NQ3+FxehaNWU-I*gwCEcZ{Sh$KCdg`X@S|wB7YzQ@7s$GBn)iCX+4B>Qv)JkH7>k|Oqg#u6yK8J(F^54U zp9fP$Dk9Q{OZzTln=@5u3f24yE43FRhhZF;P{P1t%wFHTUbnT2FHx)+_@&XI&ELPl zq5-?lytGrIC32u?fz0?dI5;ADx-E=;0Z?c#IRJfX5Sc&Ena-l=Yxy)j)B$#Law`-~ zk3)}wPpNPiwN6|%6{8{_z!Vk=VicNud=SS_$D|{ngOmqvfP?sWzYIP619`x0Aq>bj zqHxe~XU$UQk2Zj2u^PNMws*~%ndW@i)`fPj?~`OQ2f|gPYrFXs&);59RfnJ`-ax6F zzTDtmifwdm%VRNQ{`sUI_dvD!5entBNq{;YhbsN{nw-S&R|Wii?x}Iv4#k*g?x`e& z?7+k}>w~8xwqlUDwYeyS-FA7ENc@LqCXj$$){r}}%XU18PRX(?@x|BLv^Ww0*rsY; z1fTKgt}eB2>Ws&a+M7v2e$1D0E@!V=!HA>{DayWz$j_ze2|SOj+2mC_mWbmW!d8AI zrS$`(C5KJC9x*ms|AUGssRV5pNclFeYU1);UCo`W)*QK50XLpNN~d{25niJs-elr@ zMHHGJFIQ)^C4u#wN4*Df-$u&ohWSREeYKDUNk#3KOp+>+CGv;4AHg*E#D1;a@%i|SK1W@EWHOmO|pW{nOIJp@pG zDj;>J?>}GBVYKk}uD}WP$8a(Q!+7^LiPe;h9R8(E#R@=NT(dVm(JHRHIe>T=Z6Fzt zimL!4NNgy%Qv>E*55)3L_0*URO+0yH{&#NYO!ghJ6UFgS_84>7=knaPl#4YZz+AM3 zjK8hI7`ZMY;AzR@C05>K_mlohx75AI(nX zUhPpf$8$WpV$#xw4NmC}0I7>l`0#3@N&^OcX=Y0d`}{}|DEH!*FxZeYtv8{kJfC%h z!}MDK|AaFR77%InVE=Z8|Bpf06agsjc2X(AD zDR6me_3=0a!@NK?x`~w?Ire8MKf(^`;;aJBS6ShY)N|gceR~g;A&q2o1_}-vF8QwR zGgRE*q50?#^lc2gJz#NOy>F^ZbsSJQFC&8i6I-b}8D~w!ahP(t>oge0Qul~H%yn59 zd6y30a$@}byI)m)hos>kCe?%8iS=p(#k21TRN^GlH|ZTDXZXVJ!yW?MnsF}*8N_)L zPHYhsgpU9t)2}!B-_Yw^o~QNO>*hMp@Pfn7t7LlM5fDnnV>>Il!8OYgB0QdVNwqO! zq=M~UvckzBBdjSaSM4H=l`&OEh7#SCh^k;M<9b%BR!Zm6qe#QESQjT+ylrY43<;^H z**mIva7HO@{gC+fv926^2v)(^K%elEM@1DS`xAS$0bH@hzY0LTAM z>o3afezpjpX=a{MJF%-M<&eQoId0cSZ0-6?hI7Ru|g#W z8v}FIn$bdS@BI^fbSgM)7uBidt9H)?J;0mILJt~6m5gtKTzAx0ImE^$SZrB^`C3jY zutmc8h0aFN{+9TC2P(?uwHb%E&#BLYsc?b>zdFAURxfNCT?G$4qr_$t{ydg`vOkEe zcqw{S57+wvezoi`Yt`d*t9B+Ix0m4C1>NytwD)C)U?~4~cmPq`TqyE1W8YFi>ju!B zW-E%0c_E}D2X!x2ugIwq1pdh5$wlj@%ai8OokZ6Hr@%ELC8He!a>Cpb#cgqBNb=I} z=BBL#N30O(pr#MB1QN3MdtnB1hCmf^bfX|qh+rbIhY@Y@!##@&x_WAEC5hIJfr(IJ z;y<=1@RWI2SxrY~z4Ia>f-P z*}c1`2jeW!j0+rV*y1Xx5&|_A2v1*?nI1Qn?V`S#(TSt(P=RWWRKjCx-;8GT0&!>G z?KeLkq~cHRt&NOWUb2FXX@(2dHvPqC96iGwPw{*|gpciX&awY0i}3g{CWi>$#E=g3 z(p^{G_XDU?2rsp6M0Aco=EdO8cGe|~GViaIV8W@1aM*^NGTLr$&IA!CE@hM4r{6|F z1R}uz#AQ%$YW^QMwa3Ih*QB3cq&2rT0B9S9q`D;0LMpP^th7p?%2Q$5#Hp;2*CP|` zadcubzp(o2}+~l0w8UAW4T_)Jje9K?Af;G`?Nx%U~Z>Jf(mr+mN`cPAr>V>-*NSfVo)gF~rCL(SoRkWAfSJ zDPXBA^Jh$HWCNLu-1=@bbsPdHa?vwC;f%OnsUoF7|L>6!N>p4&PFC3nB5w606#B7D z#4ze!BuAblmYPlB$K}y7Ts5}M&E21P;#%uOo^?GjUQjNDxPYIHvh1j~;9v~JzR)-K zQD+}FGhow3#%aBSRi8)H=sqlx$}2W+kXRb*q}GML5aFJEl$|u%(*zPiHHM*WPjyXu zhKs?6|7L3?i>h<)$V+USOF`^60pg14+cx2A*3MoS{ZvgbdUh>42BFHeXig>4Uoq?rW$nmULB3bgUPPbvi(3&bRLNRYI zGbq{`Fr4M z>1<9+_hRCb=K^wnsug{s@miVZTlUuYPohc|J)3#gmdvt}iR2vW5ob_VlpfV2f$d(+ zG6ngP1Cx}H5IaqVu8KqoCdji8opa#MV#Fxp+b_~8UAmIU1abfi!u;P?lEhw2vCZHOYbV1nYETT;a5-mHps}4v0=jK$8%~jpC#81V}L? zNdWb!;dOlzg1x*!r12oXHqua_M}^L9aMLZkL}smT%PtrNBn z&4zaz6x7iAk%qD;tR=N-gnzuiZfk8ll}D{LEjA%Ph>VBBkGGQ8{}VXVC0F2pitPZf zqYdAB0{Xta+5P0_Rd&8Fva@ld#3)^(_aDV*XEK-;C)<0`- zY(Jt=tit+r7U7m>Wu#CKas5aMv#(f|aK_ZeUzTu{Sh@Ej0%t1N@RxDep?zLu;Z z9=4r}E9?$-F9YYGB2h)3M8m4;xtb79_v`R({q;^;u_(Y$@Gh|@jX@g=+Xk3x(UrxB zeGvYDn+B$YkQ{jxz3`7;A&bKya2LH1!YR)dC#OlJ>~$knM9fxgVylw}$ph83MgT{Q zN8T9Y5cXJoNsb`QM z)PLV4?#ce9^%y-4Cc9EWZ#>q?9ZMKh6DIw;@w>Q;Rl;nUclxqQ{>$S`dDKx|mTOHt z-VU%2jgiGkUYAFB1^zb53)~_3?odi>gUZv#++zO0m;Pp zR`TJ;gI&7FXcET%jVhU&J#G+pxywd@#PpzCpbkMkmr`Z?n8)PJab=tYLeHr1$+*W0 zLDbp&q}*nOmzh`uKheR6G*qffcVNOtd|XXIUfA>-k4r^>)bVr-HK$J(AJGPfPpV$9=bij{#k$oWf{Q5zi>3pJIp6M? zoZ5;)n)f~LQ$eN5jNeH^ZqHfiFm%`}m07uqUuG2ffBdFB@3$G?+KDw-dB(@N!42+o zov*iNg>f~*-N&YjPF-*>Y@9&9LE*o3i#j6R1T*c}Y%bxA3;l6Y9SKPZY|h5kq_zlz zF7%trbfYua+WEI3C#|*DIX+QumRbqCIPcO1j~myf1h=uY;;aJLUrKY>iqsT7e-uUj+@q;a^b3DdV(Wz*}Yu{h!e#2 z&l)sO^MlD#r6i=qj1F__NQgwK=INntAZMEFU81iUC0s{ll-b+<(L)q#VCL?bwBW! zC9+zN#pg#W7X)`43kMkr?xvA;WH_)vWRzu3uCqsK96`*#sf#)nEkkXP^7A0Sl;|>6 zdPlRmtGnZK?(t1~_^dtj*U<*A6eebTGF%?T_#gidIgpcU{~(z8f0?)K^F2m+_{uR_ z#m0A@WAs$`DV}s5ZnO)Cp4t!eNC``pay`D8#}=Th-4T2c!mFFYbo8wUi~F8`qE^i6 zBs@2}ZYj8j%SRsB_xhJUUu`dw-(Gs6nEu{dJQFgrI9H74mHH-q>HyTFAaXXieBU{K zyo0Kdrw?(aRAKndk5Ee5laa}@sAo;wBX$nw199+TU{#}0#y?6=K5OYXpJzTKoIu+w zi{7lHz)&nOKB;RmqP^^iRoS=-Jq~{!ZY(!=ERzBgM|b>IDkHzYY@0d$rD%_1-~Ups zqT72p;rb{Rv-c#t`UnuBF=gHwxkC4t1v!!k*_u~<9%(=o8W9r(_gUHJn zxaF8zjV5YMS6W{5QJ2pCPnNBLZ7#jzVkoS%!&_eX z?&9mVjO-RsscDxdxB0N-)}!?(5izvFy&7NOm0DxN`h4Jj?;Y+#yGX->ZE=}cB1&xd zclvnmL-IG|8-*@Bbnkw!f@|l!`IY+kKj3jSfaqmsGUKUAhFaTCd!h-sW`y3ML-s|4~+ zRppo^j3zP%Q%B~h#N<23GraDPSEf?7niAb^WwQ%uYDd;5DkWJ{)Q+fTC~1pN!bs!7 z=x~ASX7|ztE1e${V;1dQJS~=5ir+qM3;Z#82K=Y^z(uIS4cP<$OL%PD5yhpvPXlB4 z4pWnyQBg^4Yu>j9V@{BECWzu?ETCMQf1%4NxE?Ud`^xntc_QhGm9$CbcAhCa7^*wq zZ%|$J{damT+Ywm+;vbbTzqlme1kcEAeoNThDc(8oz!6k?RaQ=-og&rabR%yxbK$lm ztX|jG_Ee%^lNZC(HNs3$9>3;zXhPy6UAg(+(THV!Mg?i zU8(rlX7R3C;(g>_Dqd6N=2%D|$Q=ljCBAWW{px)M_Dkx3l~U#sj&bNCo`9GEv*#p5 z+1z!PCUQ7!2ltk_!pLoHcsFT5^{sUcBM_P^%EQJ-Qg?|Ka_aMcUjYYiVE+`J&|E5{ z0smF?@#Is3#>M|zLLL8>4*s-I*E2{(X6Q52TC7Y=kVU1uALzGd#@BBO@f4jn++m42 zD;~Kf>05nm=`P!YJ>v3r+J6weAKE>z)W3o^G6^hISmsuX6FIzk;&e-&g(M$FSV48+OfeqO2@$F6@tT^{Zv zN$Tev^?XuN$~t=l5VLkRv7C~Gq>tn!2XKO?gJ$Cdgy!9rpGa2Nm-QSb{zQ8azP5=I z8`Yj-KpkEQTZz5fx&>ov>ZAJ=MG-R{YTOo@2ONvBh^>*R^1 zTk^N4)^4NA6>?8fi4ds^(%T0)BA-0wiEzCzTy)S%My;ht09oMZT+PW+uTIOD`_Pt| zv_X#lY9ZMa)AlkK2@uk8R`*mXPuN=Rw$5*(Vi~w>00jU!Sj1E-{SE!gcm(LD6v3}> zKsjU*MS1c$TM2vO4YDx#cZk8XKObG?q6`$&Ao}43(v4dX(@Y?*|V}0*v=S z4LBqBoeDLG5-13c`LUF7kPwi?80?5{;z4e~XTz}bYYsA1)P3Eu8kNFcv}e!Z`lYa1 zec#!AgoN7JuN_ksGgOS2#Dr4lfTXDB$cjrMkt8)$S&|0n0Ec@ zT_aqAvu}g+4G2GsEx|f72Q8&fKsu}ge*3DFZWOOzZAs$^KkxL|B+8JpettG&l_ z{f+J_VSaq!aI4efK#AO{0_NI3EAo~yV%a_a-5KZ8WWxjiXT}B6yVz*+EFO6|grjQ~8kD?S%3eltBI?2dmbkd8Q~Xc*hO+JZ@m}U_Bgj(`}KQ6DKei8Uv&U z9KOBt39kLiT+-Zv3S9fBYG^~i07d+jpgq>1Wmg6m3%2S+qe(_er89s02*^=>dZh7# zD~bSi>daf8aEO@`0h@U`;OAeWvxpOmDqT@vn8ECAG2pAl%hkc8G8(#kM2xN?RiCF9%^ z^nwRJS4#K`?!U7=gPIi0{hndaNtO1$biHL%TwBvMy1UWF-Q7ZP_u%dlT!Onp0t5n$ zySuw5IKhLvYaqCLun-(B=RD6l-f!Id-7&gH??1hI*Ia9_u9{VAR^pwR>70UCaGQlh z^RT?nA4MJI>Tv*TZ;sVojTxBNmqX?Id8-* zs@$=ylo`z?I{8)(t=h3+l_*+m#jR{U)HPGMOQglbCnL=ub9mstqt^T}e=P?|9Y-7{ zdmM@~BPDUeUU3n~_%&7-(9>J@2_#|Z_Ku;6udPt6&( zv;Gnt_T*Lq=c%xNeD}AW1$y`j!90Z9*B)typxmXCe|n?|MWTt2+90ypCMIyUI}P3 z365;4X`D(HoZ2#!7HaFF0DK2Y1fIum3d|1g`--yMV%X4jzKyc&ssLg*rExEJxSWUE zn0fUTiQ?bu6Mt$O&YWJ4`|FB|rlrcbVz|?Mr->5#%B(iJ1NKSb;7+TMO-#K-v5!cq z0N1gG~nku%4GxC9(%pM;~4g*c9VNQn)sOZ#>_FAP{(4-g(zUq zO+GN)g7Fczv@NM+7fJxsi@A?u>{HlUF#25xd;at0^qh!zDoW<&w~xBDi&gU&HIuU+ zHH*+i^Dq3th6-$&&1N=Vy7#oL+p2LBUi8|iM7oRZdJ|~68`4{O5OBwbU?TYiNfiO; zz-gujF03NdvpjN`LH@IjagDx*OeeeU35k>!Hyxsl`RUJMSHe;yd{`73?Y1f+mXjsP z+(giVs`6;KwN_6y!kL?h&#N}sZ0Y*)`dD7N{hufwMG~p*WLIbIMdQ)#Il*6eZO-3K zK#R)KcDXaEO9hJh)rL^;$rkh@?g7;lhA>N*Gj+i7$thh!E^1>zeZY$#1Yn~C0C-rj z%w@X&ck{P5F966ks-RAh@IvUuW4Ne~3L+1wcDhvljO}>iva+xUFbem!2xdvpM%nOD zc)ugJ3}a#=Ct}|ExF4FDWUL#6*${LdFD(+z=$S$2Qs(Syc>|>5c7N?UT#;R- zUoP(Dd=^{i5VE;NG;qEvhuYS$w6PoZ3<$O?nptUlyw6Qcv}fi_WjR5A`{RI46^)tp zdESbP=;22ZQ`%_5cxkK`?_a5Crw%mtL5mHOx|LOghDLh$d2d5E`U&0`0X}_-Uw43jrAa;EoSzHnN%gA|5dPzf4?+qBGIx{KxT?M*>gfL z(TlRs>zL`<>#)%1{b~u1h=;zT3vasK=h;RR_rFUYu$NQ(wuC zoL{i~+C@R$$n;}2X9NB5gUrT~+l%<_+6h!bc6>>hMg-$P!UE=<7)CqTADKfwc;ePT zaGCtN@0>)8o$2U!ly3qO@AkQmEOU0)C1Dl0#l}o2f86sNzrl|2cCGcFBFFu3gN3le zI+E!Dt6hFO!C4kd59%3LIv|}Syz$N_e~)wA^HfWx^3=G{-NwKArfcs`M754^@&`xdeSgm|P_D(y0*n4anX*Ct0!?ry@?(g{2KQPOrd59eH1n(Ha|q z&wt?sIeIsRn}S=!;CNPm7P)BFe=(Gmjbjdlu7G&B{lVlW!1EY!ty_8_3nss} zw*`(`H2X=8hXwBLFRTAd&j?)@w4Ikcz|v8M=O8ccZaeIn!O82%(|Mq(M8sK$oLQ&6 z*Yafc>=nyip;97If1%hEY&q39)ejB8997mmQ~K6B^z$r zHz%=f3H@$|cyB-M47@@8&Fo%I2eNtd+9$t{9^a(?!jipG!0;#YTyc6l0`D`W_X#f? z(&T7oaMh9)q5#ySMZ^p>;^N04MwDaTl`N%rO3ybwJ)ZJcluWRRs-6AO4Z$)|aviR| z@pvJzGH2*|pS%E?N9G*XrBX|wL+{m1t;)9G$B3y*F5Ack%)eA5rO2yvX65KMZmu*m zT%`1*7ZU{WnBsLG+Y?Lei9QFdSA0@vmO;;By~(``k>rAWD?Bx@ORs+Z<59ULqe!zX z(n5HNGL!uNVFx?c?K@NI2~?UY(u3%2(nOd16qv)2s1O25I?-6ZjXWDcPtElWP`fwZ zSVLuy&FvL`>=wa>`N79?ohyE?9vu-jfbGXxW5cTUiy>zB8-Demfu|8ZKd-a(qfJNg zvFJqrgQsSe^5K5#rgO0^{EO+Q#k|+X=4fKMTT%bGys0k$xu+Nn(kUl4pno2D^-M{3 zlGSKl@ny#vtir*K2oMvU$lv*1yE}XfnxRrl2um~h@|==7B#wbg+e}LNAwd0&6W?IN zI*#YtuT+RSCy0$bs`d|8yeo$jb}E0?+*Z>)3cM_u%lDM$LU#0ieXWIwGJ9>cxuUMt zJu+enf)k1Hga_K~sT=Fbd`Hex&9#Oq?-mXcu6D;V9HrV}J4sEu*Sj^1bmmjtF3E>* zuUew#%_2a7uLT=iI%X6gSo+C61LZ$gT1JwCSc9-1^zvTl8W{3Oi&g4H+D}vh3}qa2 z?yh%TWfC~_YV;Wy;_6w>C#0t?hz#!%lloHBpWTk+ema*Yl4!M+y1`*OM6DHv@4#hI zX4f_xromg6$}z<*f1Y<*5ue+%(>1 z#)YALQf+6iIKKAY-_ad=s%9D`#^8861 zq+wNTP3^-bQsP2d&06!AH@i(&h(p|cV)O{cC6&G$`gQ^vVK@>7Zk{T^%RQ`RCV4wN zHnNWSDWA5jjGlSP0u{2HR=0P`ygAmCcpwYUStrfoB*B-^EsUHU2LFrydPEL7_Gx{7tA3-41%P2eAe@ z*DUv!p3h`PY_iA6f3eJV)j3eUMEZY09HauM_F7aQ(uli?J(H6osasIA6b~2e;qPTH zNs^RK1lG2~Vu6zcMgts~_K;>_mS=e_P=m%=|5OO57QFs9LBK9!F59WrxIhH*e6MRb z8XIbQdyMm)a!TZQ=d_oUGJYIOigo}T)2GmD-bZqJmrhO9>iIF>l<%EEA;|wlDM)HN zyJ4zsZ~GHRdd#8AjjJB=pq1}%y*A__3$KTo-!x!AMIIs^G}?K^=%?u%D z8=i+y<7Y~Nd=afUe~%v?DYyol*7IMJ6wdkr6b(vN?6pJ>FLtu+f{qttMow>aa2}&@ z$tMl*>!xQv_j%Kpul-r|ay42lBlwNKa;+@!q2?Pi#5D~!9q*~VcDJUN}}a{)L;6!rGev;hnBsbC#+`+m!`8A zC@A9Z^1N-`3@>21HLx?_Z3GrYKPVVm~0B%G?^oJ!Wn8weD# z+*f=p$6_+8_Z3mrcEnU0lUeTjS@GNfR!M!-(E^&80b4x4-~W~7;C!9o|FjwZcZTh$ zdbBiEVs;~C0sK79a~?}BXQ-$;fH*$+)(PmL#YGHngLv|AQLOlk{eJlvD)6xaeg@IA zMuJsyf~FRTWnULr^bLF~zLT_pwDAQK6}8M}^6-+j{0SkV(*F!4_bz&wLh_Sl5P!Sa zUA8PAGG6K!X$^0oa~Ms;3gVFV+&M&);@U&cqp!$MzB&JbTusic2hYd!eOs=rn0(-f zI!d0^GC|3?Bw8>^NbFq3STql|)~Pt><{^3zu8N4b8%Ygt1OP#ina&|(hRn(-G7pChhHCUYf=t$ zr@wkt73o5=+LLrwbm1oIcO{&0fuos{iSP$6XbM_`uW zYUxF!l%^L{@~9HXoT21BD4(W1Z1$i$ULfrsgQNAze~b!|a##Ou2aUmxI&mO2QK*RD}AZPraqLwNF2ePqXf+80wEgpaG5wH4Kj#FUS+Uj5_* znsxdOCKo6d901_l0XU|tF$+TYvl!3q%n*sCC;C*9%+14sZ%+D6ZqF+ELQIq`uI6!+ zpIckX$P+ztP<}18${WY9>cPl?!xFegPv|-<*@)S*2kJ&!ESF3QiozplhSjeA4-A~g#w ztSH4rB^x?+YCWKe6F7W|DB!BIQ(+zl1AN@X*o_*9%5&Q!@?KWtzA#MeilBpG$QC*M z22>K+dnGmvkN8PyxsD1FQ*3XbE~c8JHg!+$>e*BV>pG>I*yO%1ll^AXOeTpcsP2PA zo_i1(>)VmuhApUPZ0{ia>D&D;)u*x&!K@n1WbCe=L?QgI)64KWyOn=n(`jY*oXkI1(7+x@$1I3T zK)3$Ut`pXtRa}!D;NM86M3o5OVmxBIXhr}CD6ehjukJ1|bp9C`BTsJ3+zpBX_3^DQ zQkEV+96-{SbF6{w#;_`Xx*B82gC&je+y0H!g`n#j)j2 zq*u1Tv|u5IZ6y>$W73xJ^7wt>`5{FgGNxO_DIS*FaVNf|8V@NCO{}41jYOhW+(AVPU=YSzI7iO z3*5zEq2O3X6S3r#%O_ECtoQ+2xnORev;ZHu9~LaeVpHnO7W{G1ftZ5o*vgBZLp#0s zC(A^CTqFFrA$`Ie&s@%uYx58Y4#3n!l?MZtyUe82^19){vmw^psMHwCe(;wO`uPJM z!L|VNAPYTSokOIKj~7$TzK`^8N4jlT4<80txJU~DUS|UYsbXemIKM37?TsP^9aZ#3 z#S1db()^eb7Qf9$Jh18ZII=d!lGr?Fa_dve8GKjy?0iP$fH}wGt$)x`N(7$MHCZrK zrMQjk*{e9+vSc|au)rKPEVQnCI~Wmw05h{P<>0zF5I6s8>!D%e+>A(=lmgN$TYW9o zZ~2f{T!+)m5)2}G7f&j8%gpxoDCJ`lA@*oyud0K;A~GIvC>ybbEbxxv72DHSZ2u)9 zVE`tUDkyWjw)+FJ?-tZDWdn?5%gZ{s)y80&vld0~6&P-ocwOBRu~Z|^1;-Lufj#0I zBJ&YW{&aH-&FGnBazgxz`-3G+xT!uvC`e#Qp>UkjFs1YHZ7f0ZA(VDAmI7hEzX-oY zg+B2Ru08Dy%67XJ3TlbE)#@K)StDea_fOHsNGYjTsTkFHB|VorhER3HS%uv~O_1$s z`Nt4O!P^u;M?5sWRa${ zm6#x?;?9;#3;`I45hBnx9N#S3eO1G)!+i9@cy0pTOo{|QdCtHf)w9_m*zD|bGNV>Z z`xSiZPr{g03vjnYT-d2so*{3}B#zRr>$LmC`&y{BmxshE+3+`OKl}DcoO{k1D=9r~ zl7Qkt9)RCe_3P#m6IpR-u`DwJc|A@RJm6mVvB@6~KliBm_#r0ewZuph9|*b4qTuz3 z=ME=d5D`dtqw?N3WRQueHRm|3XWvO;7QBSZGf>38VgA(JChr4HRz4w*{3>o(+fs$o zPRp_j&mFNy58zA7nloi=ogEsQ>qecN+xLWJl;sw+(>Z*X)!pF9q)%jEAh1mB6Bm4g zU}gUnN^w|5h*!|;{d^93-Dg0)pxk4We;+3Bo?);V1_D}&OVaF^a@Y{e@o^R)u2z+X zx`8y<6sno#L4>9m^8k$qOB;XA138%XH>Ua+~Vc z^W`UxW2}pp#Bd+7mJ*J`Iq+#{Cd7J~v9akngS;oYNR!g* zu}h-}pStDZFDcy)_VGZH~>eq!Qa8`$B5&AD;)^3mW^A z<-dZynvB}&SLiCPJ?gn{bR0;wTwdNB9oCJL2f~wZ4m*N%S1_kG%yGi?*k-B{%mVd5 z!rDEF0@VKDgC-K&&HLi_bth>HNBIm{fk)JV{NZioloMIa>OZa#GOVUMzIy_ghZJy` zy8D1A-LHUN!YP7{Mw&Ksr59QIih7*%V(?14L&T91Zk@CjGq(0PmcLE(x3W~@Ug-py z-?nO%FKMGBPo48smz5elLs}QAVID0h;r~rA1u&&VD-joEOG+2 z;hXm1YLCbd6oLx2CULlU4SOSGm;W#ferx@4IbSnOm$waD7bSMEuaK}B_;bVI;H}wSA&N zS#ibD?aO0)Pr-SPx=#U%jvd-0NK}oaw8laNX|uAX!>HEt+}x7WM5Z;1rUi+*#?_2ii@=<#_Yfo`=}oGLn3 zhleyY#?{WCBK4lwO?Sqfp{T6utf`7vrGCiAl`&#$zyF_sGt z2^A#&QZ&XTvhdcF`0V=LuRjOSDlM{xo(=f^va(z793-e|w^z`w?(}KZlFQ@wlsgY~ zd-hd*?a7JpY*dX%xsnoBYufs3;pRTrI3%=4fy=rq_9Cw;hST^ybd#-MI%D~sn>ujg+@rv@rne9lcgQ#SVBr1i~`3z{HKTJq7>-s>$>k<`cNnluK#wH}NM#2@XH za7igd+onw|qwGVPKau4gU}w5nH@?^U^H8r!j3f5h>~}`5Mmt*f^PJ6G|sPn_$ZqLjFQhGef3WTK~8Z*=~(njsE8;SJGeM^838_FoF4B?<2v zL4vUlUwMegJ`hNKj(3Ng%&xPYU8)-5_P_SW5E#Qb>=J$nN)^E5C$P-ks)vpYPYxpCECAG3tU}Qy7#c z3P}Jc>t@|Mq~ldc|67FNfnB#D_KzF^9~duh;{qbZw;WEEt99(z{G&}bB?8wvR13r4 z{z0$ZmJ9t40RPGu13m!*&1qzUcNeouayOQ|-J}lr9tt6INuN3PO^5BLhK$vw&YkrD zUq-V*4XC{C4JML!vWS)-)R0x1|0CBxQ9O;9nb=&@FV&Ril6odxl4Sj0h|$WU=!WEY zQ9xB%JWHoW#aVG5o=9Puz%-8;qA*<;-=lRSv%msAQZEfk<}{vjLkCVJCTp;p@<8Ac zy;$C!JdPY;2)X`PS%&bYk}7uSmu}r(NPX|W?R}LS69nLzr%MR}*X>P_y|1I9aA{WZ z+ONY=wQ_3}yR#P`;kRc|wWtm5{Jks`G!l11Dr-qSu>06_we3H8z?HMj^P(BtXruFd zG*}P*ZG%ol$nNU?EZz!7Bm82=q$Mw}HiGPmVl0uIh$1BgeU`pR zdh;EjDJ)xKD<{0=6u%5J5>cuNf^J`wXS7%=;`h_b<}T4wPd?a(xRI)&CrmPY!5Mk`|)3s9-Y5JG}9eae(R zq`)B^5Y(BU&`o4r$tDfMykW+TLl^LaZ-^vh&Y#$bmJ*r&;pV#Dgl6+g1Xn0DuXq6U z;h-c&Kt6scN>5+b0hL@&uRP9>q`R~5Z_5i(1vmM)dUQ!kih-6Bk<)p)Z^l!>nf<#C zn?7aq$u?0Pc;;8IWnaOL`cGuUL<>#T5rf!dQTjnoh=6(kz$6P{j{Dg%dur;`EF{qy zcIWx#w{E1GS z&@+gfiQWmhvScU|)KB&5gq0R@@mxZo{{&w*%~f5XuYXyI)fiyPC%(Rqh2jTKa0fMC z2j>STMfCqBf|GU{G{UCe_pnI2l-vJ!brYyL%q#5-GeyCw|28mI)aZh7$r{<{LgslU zY@Z~43pqz{NCr+=e9_Z5dP>mNA(HRyywEFQTNihH!f2K>SoUeR;nD*EZaEd^hpZYp z{MaphvlUxHTiq@RaWmPHZvzcjHCQ8Mn#TF*i|=`nPnVoNnRL$T0{z%5C-7SL=;fQT zSR&pL5geHRF_7F=-xR4!2?%rSB~uPn|u=XOTx6lqDuSC zn@!QW_!DCk8aDLPpwhP1_3RTIR0!&QD3zF&d>B$-!W{J*`Y3AVKB@#G{XDKFu&Lnn z8dy?XAhg`R9;pT^lU)Iy$iv1;^a^v?96zpN!1EBG0S1+C56T}~%{4yzOTENOBWy5X zNu(>b!9x^Lr*@-|90C?Ly#=PfRdHTpklTC$TM)PyQb2z_t1R4mIJFGVT(fFsS(8xf zTS<1yh+Bv)7{1x|ie81>6*EXcqN<(Xi$-kzAS>y&i>-;p=JYrz_#3bca5fu(D0R>i`duy0#kt!p=1jA^hUI?zBl zNiOTU<%EpBX%(_9&!2 z-m}5x@QQ8P0+K%e`=@2x`QaFzGVaMONy0eyl)C$dUUuhVYto;%3{!Rgd&uduX0OrjTqD=CZaRKya; zbz~KFgucb!dwob;iCH~DHD-j?H<2rcFg;qk!P(mdoNhH^+TdZ%(5^f;-rX_s`c0$> zU>LDt?)7K|>1oivW0J2uMfX>fD2I&5x8Y!~d~+&W`#xgq1wUkXNKXHbZror)7E2pk z{R4-ejW4i)Wt-3(x!4U>!$t01<@^r8z-6)Bk#?U;f=SMD;{M>h!p{IyfiGC$53yyj z@ncFqHMi<|BbcS3E4AX}KNH`Q$oQeJd;VPi?0?eL9klani?8Q2q{u>DAl+SvjXy&{ zo*rRq=;&=R4HPfq5Cvf<=?CU{Gk*8${sq<$%YjAt$5rYCC~EW2RzoV{p2Apg-0ys5 zm~lXa09^nQc!0#Z0GArTYA2D=A`dY2e!ic=Tn+EMIp<|Ll5HrMD#k`2tQvL#g9U2F z>N-P=XUm`g%S12mD??rjnbChLCl7;uz5}0w56o>)((2>lUG^17ACoCOcUWR09g!&BiDDyG*^u-fbh+Z?ZvZ z^2&bY%di>;vOb!kn4J~l99CqmV=_4fkXCR@cJqhYVB|<3T1nZctKwZ$M(VrLW|t6! z(TM8r&Wf+Gn;&Rm{tP=YeJ9c-7^-cY>^f1hGOs^vMYiQO1)SR4A-;yTV+Q6jbcC< zJ$}lpOy==(trhF^P=iXZ%r^rcwp7YJ$STJbuBum!XPKEYG9O{LD}Daf56TUgDgXc; zK{?1{|1$Tl{!bq8JiwrQ3*rXArdv?mT4Zo5QC^>ThbU^Z0;i{OhIVRml7n1`S@FEw5#Yhl}Q+!77>^djP zkRXR*YBvNhv%(~B5q$r1_asJ%up9mxve|+RlF-{JSAiYegJVT9&6q*3=mLBJ_ym(5 z^@5uqEPiqEMU?>^W*FK08?qqMv?1A#9}DJ^f~a|Kz{+1F&rt z82{yIK`Ei<#G87sB?^4TER2ELe=}?Xa6Z4-t0az%qf&IZO;Zq+Rbtf1b8XJ)fCp`5 z*vZgh|A6OU*pA&pBGz0}yq{y!&qe<`7=YXbfUy81Zd4XEaC~<5Ju?Mw#-n`)29R67 z0U*8pCVUhtr6@|DEz+O=egz&80RO~5ub`b#z#u&rhJu_wLjmCa_5JdC*K4306sG?; zQvapm|0U!b@i?ZTRz8gvX7n)j*95;@MI~=H8+{kCCdY!CeijX?9*h%zXx)o!=IR|l z#Io#)Nt^ngJA?u7+0dhm@&HRI{+N#mxY}AnyhUkPDImy)IV_1aGX5C6H)KH}0gD0q zd~tcTa+hV*wiDxG=zr9GWL45K)nT{TqW##KV`>JOF=}?C0b33JuaacHZ?LFiR}_$R z?|b{*4p^#jv^c1fw%@KUdvS-j&YZLE&`7|QU~>k&0Pe2)-PDs3e-QG3hgTy(O|KRz z{;#X3pPfShw6=mU)d3;^etHW7!=?<=v?g3nHKDXQl#T5+CI7M~t+aPqj7M_?kH){k z7|%E-*m*Yhk^FrgKWmxHhb)BN`Oa2jv5C#sq|&I!Xp#CdefMgMY~p?aRWZI-oG$VY zY&L_YI3F8KleJnkE=EMVbJ+nqQ|TAyrgoz-Qffpy)HQtbPxq&>Zz3AO#N)nT8za)y zxt^41jD@M~M;zJ!0`cKD)@3&)N^_{dCl)S`4ljsHs0}kgrXBjiRd>Y>=Yy6x>x>i-N`+>f$n5X zgddT9e+20q^c+G`)8#5G1ktA8W=6}@C-3EAAyCUc&@lZ$&sSe1TzuMUh^zw!lht1Q zRY(k|QHga#@|L1In+Stvm9Wu7Gf-!_lGAfi+09kXSos-y>k`ibD8liYqc zN}%R!O`OKinDyw+>6#u&7jM9o?q@6Mof*w$MJjfEgL@*10>9dB%C5=w?#N1kt|n$f zZl6GVyXH$|0P!_jgs?A`f%<>(O#i#mLfv^}yZ*TbB`zXG>FehPR3E<8wFG0 zaDFiCvU=~L!0;+ZW;H*{zha|n9H<8R9mxZg$foo6Bs0b`Ae|lV59@P!j_Z{A)Dg?- zoBWX!^_gCC3@x`_XlF=ceBHH>R2W@ma%>JpLOZKVw6;f}x5zLJ_{$x)yukI?r9_P) zUhT%slQ?caGgGi_pNXvOA*Tjc5qkr74!+YJceP%lOA_b9;Z%T#Nh|@Y{&KIhu~L{Y zpO3|7wyBt(5nPVX8ua7%yrT3e9-*}42S$hu%;{23BP6@iNO&wy>~-|)uDaQ$*bBMB zgKz4cCHMNXN($DrLqFU-Z1RcLmYo~kv$4o)OQa1Zb}ZB^DLOg4j1qb4<@UI{ec5S5 z`@-znm1;>Rw+T{ZEGLm^pT!DQupouWvcoJ};xDBy6lpQDo<)4NbSL$vPV07a=p0$! z&;$!gR`w+m6rR3eW^N~>3?=V-L-?_cuv}dFHfwl~Eo`L}!L+6z zerjKXAvQ!0$3k~q{-W?I5{TdSJ$ z#KJ2b8#Wwd@=vdBj$U{U4(>wR4I?9RW&O>UdlKwSvYHI!_`|y*E3{yavqTqmYD9&} zGqEE*i!UB(|4hcq96~Y|4YpLC=aY)?Z)g2Fb*ogw;obTaJ2NX_1MI^0&C=;jK(l^- zXOGO&wJ|>pAq^y%I^m3;V`L4#{j*^pqw!@7`8)qptV{x zQh}pXms3^0>ykkz%QV^==7mh2EVrGk(VKNvBq!a{>jJ2z`&trC>W()J&Q9 zNuaN*bCBo^9JQ{pN=yPPO>oEA))?=dB3r69mNmVD{)M7UI#Q2jhzs^0g4H*pKG10C5 z*~QJj2X+I~oG`evqt(H_Zs-^xI{-kOcHyN^-i4U`^OE}JkcoSV~ z8O!_eO((TVxwWNECms^hIV~Dnx1J&3p_ymnR+#Y}l0mB|A-WP@MNiY6lP^FC+SM zKf;31`w6bnTsk)T(|`gJ5#~$0hoR+K3Fz8rOa9AmBUGL;mMVr}RRiw%y1z6j#9Ci- z_1+3Nlh3}25D5oMs2#SikPMmRddeB+eqvUrPv4?933jY#PNQgz;1FM=F#psc6DO+z z47I5`Rd%FmkOk(ib*LNpDMYv7UUeX0TQ2iS7 zcT{!$=qbHQnIQ4f6`->{Uf(z{7 z(oL{-!e#FfX7JewBMa++UJxNnu|%CQD}6$wc15_I|Yw;kERJ#4hV0+FZEy#YcBR z!W@wyT)G#cSG%Wh;yx{M4kYnb)o0eiW*^f|5?>6ts&;-=h+CMLQCfm&Os~;3fJqBjmz+ zeo$vbkH`qkfzAxjVtU10p^53I8s5X4cR7CbgtOzvCrFF(x&R)WvYd^2A4QcnieP4U zy=+afw=9-zN@M1C`YLeuy?>)cbFfG0G`gW+=oI~;sxlIxh6#d-F41YN7H{q4i>Z$~ zXOqFfgZ9NW=vw)s@ zGpkDU_1_iwwv7=uAvu5Oc_l31?(&>9v6 z^iJj+v8TlG5fIlLXrQ@cJ|yC;WUpC@XG#MAoL|~q6+w`l@s`Ol9KR~K$$XK2(;J+2 zp>*k+=RH@XCsDDR;L+7-&@eolXZ7ka&_!Ta*!-l{@!f4$cEzuk?;-Ru_)cCW zXn1DZs9OsB=4YP^TqU%N?Vf@xCfaxgnV=|B5QZL6nW;(J8a(l$xmi;olKWc!^Xl2w zD{GJvs-?iIQNBhpW}qCBsQ*Nm;5CS>Hh}E&!W{=Q2fQ65Z$9<^g!CK4y+a{8q}G>W zXYw9i4q}LT6PPx@uQunUzmr6ap-)wf*x--uLXjbaw0|CEeNRyJ&>)4fD(T?^&d%Y> zmQ*)d7vmCpJfkLiX0cJbRTv(o7}fm&=!gPf<}b!JFxEKc7vj)Df;ZgpKO&Ru)9ms; zx3rj^ezA^1ZXVXJhn%&abjoXxhpE>IZs3cZu1wEUl*7)f&O?roDg(MzF5!VP4C zh-z*I%Fi92i7R~iKj4?kcfWTW6c)BR6buuk8ccqbK#bcU4GR4uJeh%&2k1YsoMRR7Pz)E@-<}I| zMnK?wW1xLTRRxUp1Q{iWH$T~?GdA0$hI;asH39x*~wvUM%zFo!dkT=4lVm5cx=z_ zQDZH~TAWP|M@W21CQebr5%Bpjh}vuhlVJqI0gp5v{cB_;5ymPUHHxzG`9QNXW}5@? zyc#TP+<_(~1W{_y*g9$6`TmQN#y0ETZ^pbQ#&@B|vfqlEw8)9YP;CNKwb`sm$Jnbb zcE~-hGe6y)b%jACaa33$90E5ZE#K4EP=p7YAm$qX9!=0<`L4iXocH6?2*+0OZ}`)V zjPFGHOLhwdRX8h9*p*i>kzc|5A6Dr9BpASJr@)oGkz|+6QgnHWR5e;z1m^fw1aY1A zoa9ISV=C&iu*7)Pj2gWdhNA^qx>ZbxFM+k^T-)-}cU=?$iAev(fOJ0zUO!>}0N8QJ zb?O9jyRuE%E9NwKsa(W)Y+A)z!+Sz(KwNf{nu096BrwFVj3yKZz@u*nh5K|f->Nt& zMaOjwIs_1@3ixR?;hIpE@jnYLp%L>w#+i8G^K}2!%bZhBf3lz*P71NC1;mXaQ=ZS- zjPw?_RWFdKRH>gAi6}ez$LtBfb6$OTk{}6FG*$%I&pa+wBlvKa>SxIOe7bk{G>AzktKoFqSW%-N?KnT3Of-)cWkIeVV$VlP*s80#U_0@sqhLS*O-i8jVzv%*|HYv-8 zj27TRt>1COZQur}R%1#!8n% z(TJty=yOd+#J1FY@%YS$Dybay(t+`ibqeEAMx!*{1HZgqHlwxH=F(F}(~J)rBmocO z@3`{f>KoCKO)%J!$#sI4rOd(k&Z@=@y<5ChhbYJ45df17&2w~1TEAi@`HIq~st4je1MGS0H-of`IkDd*z zl04Per8-gCg806|#{faD$!jH~)R>|4wD^ZiY1p8l`jakOnUixH^1A$a#C|&is|u#Z zcM3V<*ou5e`q`T0^a}dnU9kBqC2Hzcsj{mvkyHQ`h-_$DP_?zj{lqon8d&0 zX#9%f{}N#Vq5wdm$HCS)%*PXDZS3!X924X+6OBhdgUV<_8P3(8jsbc;YKo3>iYh6VeGgu~RKGwoi*tFrjS z05H-n5NND zIDmojdDa)Qyu;)&jmec2{(vi9+7-MC5q>sB;BU~Sm`al>d%)U@u>uOFR-gfRYoJVy zDZG*c_CCyQNb?Qkg|%wKfyVTxcAJAmo$e5+VWQ~oX+&6SOdgwjhKmgfk^%ZlTVSNd zZ?CeNxWJ%2*e7xA-moVf2kCwsdLfX2%|d}MqilOo$i||Y%BUMk5i*ezD`xV%PA_N= zEh4|~A^h)WuD@Nb4Qu0-L6?o6iR58WcnWMX+t`$iuf8>GHxAlX>n*cPI#@$_mySuvwx1hn@T@u_08l2$n?(Pr*gy0fj`ggu_=iIq7-&*fl z{a5dPd)MCelsr|H>4a-}BQ2j((+BCeE_Mue@|xy+cr%3cfxfF?KiFLx{yQ4|bD0cIinUY#1;tA{N& zhih#o&Bbb>=c`IFYa;KVCmO?0W3>+K{?zNICL}v+i~(#|iRO$#$dT3imPA%|0sHH< zBO#nlZu;%sGH1bX*Ndz;zEmrjy+9doo-fCr49=LewBxAQc%%oOZ?XdFZoh+#Q6dCvA1_ZvraDuk`f2qemZVUTrk~n$i|p zc-ikR*K}4OE5#ovV9lBs=1|!;zf(*NUFJ>b0Fi99uynEBf5Tm$^~BVzabX~puWHirg41yDLNqi@klLu24A#kcDz4`?S<^d46! zq6K~(%EA-#{$wd*hmD;!$)Qu^J!9S=|6G^U3FuVSP%u+PE|-flb~tdE#3!a*nsP`s zjvf;rKuJ|@>$LvLniXd&MA?gD7P#_d``m=~v4FEEfbRMPg1gr}x@kU;636~)!SSya z(0ouwI0*C7VUr*z|7BR;liQNP)MQ3Dqc&&;3=N4%;kZ_6L_d(A$DS_lt`4MeO%||$ zuo45CvfltFDM4~PErfwblfU;oo+?sp`w_)C$sMS(Fhoah{B+cxryhQ)?C+djH@Lwb z8j^1N_%zSg#LmPngNXw#n{F_1?}_s{k3~CT5z(Ud5x-t|+!zB`x@{WZ!hL z6937o*|8J}DIqO*!SvTvg?$g5!O#Ay>^Q_YQv0|RIN5*+QTT0?$}yu~`w6}h7jr@d z9VKK8;u%6e@$J4jXsI_asKTrsC$$z}z`8u1_#!kWQr^{~<(o{4gste&2*E$cx zRJdF|CYY6^eUXT^w zxh9v*Y@Q1&y+hE}P)pqyQL>=n*T0jzJ&O9l&UtJ+J9G?}DnDlIRQ>b=p#pE>!jO9H zZJ)De`{9JV-l08ii;@R_UlaszGdsECwX{rc#IboL6@~Q&004);Jm%{EohTP=`CS2*%eWtWJ9CqN&$dhGb3kw~tG#w{aqK-s7_0{uS}~7XkqdAg{3? zmct_b|HP?(sMrwB59CcD54<-k-=HFcygk_>#aA=vy?YxJiSo+LHw1w*i8LSi5Z4vH zgE`KCUfJM173Jb#$5DwRv?hn-qjM4Ibuni|Rk~bEQC-gy1Tn>RASo@GpRq#O1=cER zK(w+8ju-4cn}&`MXukIew!h+z5tVuh6!3Gdhl0KKgtE8~4jnZU=k_4C{YLbMt*K*Z zUR&7h8yryr6N5cm`$xEmnqO(13egqp*ro}7>e~=1oD)t_XbET zvqsi9(i*-U$i-7$iU_680%N5}i2iBhCt_<@6{NjDWGK*xo-7gt3yQTVYKL$yrwt{fJ00GoCNG^Antyi zInsdPpWYFrC}|{0WvUO_r$MT_&Jm4JOtrrkobe;{Xe73}#n(EiIZ(+!L>k>ZV2d`1jj0$ZabpEOd8x))2Sz zi4)*l0UFhc--0bfl;V6e0^)Ig*WR9RkBQ`%sX$Ul>)jtJEnlcV_UZ0uSCe>Y2*UnT z`^gqr6pOD;;);%dtg9|}+&$UX;N~8^fIcsR@{1>K1+x@<<*&#M*pF}va$N0U<$CYt z=ax%$fnceQGs3>3T~(ql4CakeZlzF#+1a@ryWoqr;IehO)$8nt^_gaN1@5G71KvkCLw0NDS|VB4bape~XJ~%Uk9hTe{~&v! z%>1{ZjVpEZRZ z2H1am5X00L*-*WDDpFs44~Jnd!`g1L^WAr)dvLv7M=Ar)v-zMi_n(UWLx_p5dA<pTWKKFgJZ3{deT_?VQAl+xNJf441dmyR(f3cwdgLDoqvrgGSsQ%jk zA)h3bt=n_|T!2%54pLOh46lkGlmnCbT=!vtzEKF9Bs1a~RZy~lH_Syg`eSdc2Bor2 zU*&yDJW$4Cjxkm!sXA04)`Tn=OKVhj?R_Lga8X*&Qhwtvt?KcP;gmKuBJF}}&O~N! z*`2j5Nf-%P!_s{!{?)PV=D0fmbxuv$Zrtn3Fa7%op}B>~X4d16-zH0>YlQgDe~&HF zt^%YtEE+*cFdt4O1^~7K6=L_xz#}S`0A1$^Avcb^IoJ1fx8ad`?0RT0ly_F-F@GVV zR38-1TkgYZTOxiCe;!I_Xh-sPSAv&aQ3(2mn zyIds7ZumVBbtXOp5MR2e-iFqP&p;vPLy|r(13ie*i=&=ysJ!i)%R>{q>G|}V{#VVw z8%XYfxviFZ^aH5{9r}{4Jx$|tQm7MSA^SIPn8oC^to2gRAT4tpMs?RY{lUq3S}VSP zg(^N3O5O1|RLz@N6jL2=QwFtknC~^=da|xIy{9h~>2n*;R7{NTNfz7S} z0OvBQW1BmX(e2QQ*-Ia9g^{;BJEqo+@aE#bJH@Iea9==071r5ba5z0vOSZWHOK-hM^C`ZC;Yc`F1QyTe&xqv zR6=FT6jEizIcJymc9#HRDkURNp%x*Om;-wOO;KVT{l4X@&qbg4z9gFPh@qUqFk=Ww zWu9(olNmF3^HhnX1%U+?RnIUn{@flUBZA4;Ac7SJ=862bC=5if2x_aIvR z;JXM|^!A`S%4DdpcbSF=DhAla9X)GdES{g5Vd*W_X}gAy6)GTct(O$d0T1~kll?I&Gp z496LMQElx~mb>As1d*HU{jkF+BPS4)jV%xp=}RUAGBqP)hU7+w`2{tXiI}p}@PJ2f z>*W4Cmt~Ieiga`rg!MI(Cd@^yVLQf+-q#$eI1EP4HHw&Op1Ur1J(E2<&ypt*YSV3~ z2nN?q3gSjz{`IyM4*V<5F@Fpbvz!@Qt+N|a3vbjp{pCH@PCwn<$1FgiK?VVbl%KKh z!$jJUiY^uS>3;kvnbhpVF=JqV0{bH~qsnBZ0*2a>%5SL72GR3)Lkpsl z1|}E4nNH1GLD1y5fUDI+D%Kjwva{GwvzXeUNJIKF0Q<@-{)|9`^ngejDlHUo0Q63t zytdWX!E3(NOn+GHw|YHYc$-KjiiS)_u~d9jkK<&!ZNv&}A7Ogaq`^bd3F z6&$K_;rhfWPyM~6om{OW4rWQ29+<}Sc+Af?EGpE{Vy?E@vTF^Z0af0JMJ^RV_;4D! zK+b(Ceuhh@Xa8(s$rOi_yfJgtL+o3nK)KgSbrLPLF!^`@D!ga_KYE)DnwKT}H>G^2 z-n1Y#pKd&l?#;f>vcyh{I+D5U2fgMmQI0yo(#rBA&|;|i`VRtPVs3dT9pVISPtn!% zBSFSP=_zn*@EI&;=bsN>WHLz_>0L$s7PP6VBKSKI*Fez@EOwL%Wq4W!G9Ae_+`IsS zc*<&Zp`}`%Q?K5AJ}lodcYMD#27`J5xY|4sEo5hT#XF2UvIv>WudKa*k>Vpsnz^-QuA z`@9Oqmb~3YBA28!GNPk6uLhaq$w8lAOm?Bz;?w#D5o9h@)8E8Oc%EQ+C-*^Sf~WHu z+3amD7qR7zW4esdaMC^Ej3Tp&(WK~}Kgj$jlkp`^2xL}IJ1mLn2A%9r@a8%@okVIV z4pIV;b#%+;oruOn6ivl1jw62u=9Mp>)O!Sv+9NDxD@Qc1aW&UNzk=Ya& zf(NEWKz#+%lN-CL?z@?AIf?MbxMMcRUl8cwTs3cZ?fYZy$W|{0PsS@g8|5Eg=qK6m zY0-1)LtndvVR7egVnPd*Z%&J2lM&q>hRUD?@k^ajeSA-{mQ}3UL^Ib^CD_<(-5pR` zkSB0LkUJ34tvgSkQ8Z(Sn!m)jC$B=r>yaXIm9pNGy5t)d`OUqsWVJ*DMfDB7cYG&* zdNz>GW1a^am_lfF=8~^yG0z#+zCHH!l_EM^l`>(t=pWI zP5tpSii%!^q3rq>g4nS>-| zCQ#{xMvj&@p?SBe?7`LvXpjrn*O z;zO^P4{ar3$Ni}+qyXN~F=0PJR`o5!y8F+X{Ux0f>v70Tr^Mes-jv>(xqRTZf;1b| zeAh4F!Ji(p;e-Jl!r3s~jV4G!BG^}9ieg|nm;2H5V#%%iyGWSE@Jc&57n#}k5@Z@HV_!E^yj7t{}EXRnb) zw7hm&u0g;U#Yo&Ik2-_+6t058YFnO%)nE)IPsW}>%6NJyAP#XWa@*4kaI}38_p?<- zx5hXK1{T2J5G9Nzp_6umx#{uaq&}i!=eQX>&x}aCD7>1E+C{K4qebZ@E6w?0mm-sq z$+a3!X1|X+7=qW*>bZaf2BNr!A4kcZ>&%7QA5xeD+tUez%R7%OpN#rD(K8&aAMvR8 zMShCtzRngwf6x4asj#Pet#4T~TbFZ{)Z-E~T82rrxu9gojk>1wue zPt{)rF1S>iHePiJ{})_596_uv8jll|lPc8LC%D7YK#`lK%zG$kYFY=gPk<>+B^J`2 z1+YVFK1!HV&pU}Pvf$PVV?5{lcD35N?MNHef$Llag-iR3oRNw5>s;IS8l8x*=Sp;Eg0?HW24s{Yl6_#Pt-QrUhfO<^ zqrM#|zrtZ@`Zy^StX*$K7R2)}!st-W5Gx`8n5XRUf26QKS3vm8_ycvVRzZQODi@p- zk>k|WXF-0%0NjZFU2j-~=b5@%fex*dnf9{je9eVG+K)1Eb znL-Ed9%I&aTuW~IPsuN@CeOoR_u#%2bQKDoX<*;|EfgL5zORImVA=*AUr0whb z9>V~1Zt0bwPaAuvFW<=YxYZ?$MCA=@PQbq5T_gNa81*0$h>Agk2q5l1$!!2?0RT#< z!e9&E%0VOgcMu7|-Yf#8Mz`y??tL6L-Nb}4oIhr>8krZA+s%;-;z87GQ3K|iqTvB2 zcxieQ%1N7k(2SYsE7(5^jjz)}IvJb|q9?mcsl%gDq6%ORxiGLuLqTyh?aewt>Z+GlnkjFB5JfK>c|zdkCL$v1YON zlU5OCaz;9KJKWyX%QwvyBk<9{GH>BWuI?nX6Y-dph`wlc=dc%B0IL#Ghh1oa^&96< zu@?El-h5WtU!8f+X@Xt7iRr72?HAdATal~S_cmtoM&2g-_Rp@x=1)$spl+W%o*8iF z({0_|Jqt&bUiC)+a@bVcGG(ldxvC4SMpjD0h}hpF4}&RtF)E?G2NtH-!H|jj)=;z_ zrwZe1`{Kk`cN=wvwr3CuTtUEuLlmqD#`aeccJ*xgR=ANwfOaG-@k#Vu)8kg$?BOHhqtuzVW0vj6;h+t|J`eG*tilH2mYL{nyh8 z7}XO6QneNVShM@~_ot4&!qJ}&+lAcqQ^yTn$=!wkdDp4SnM0?ZQ{_eZMBv_1^u^jE+bRhlK|W64+oSpoklUr|2)zY8I{^%Fkn1DL>IfTU>cp69b# zKT+q33j#ZXSSg&EbeM8q%T?YAdi_<*SOENJ>k@2>v2e1JFySr`!fS%;ra`|0a1k;R z3K0@}U22F|2*^bDHx)A8D)FR$1DG-BNH!o1*=r&)1|jVNfZDn!1*)pKDmXh8ogaJI zm(Q~+=gatY2VHHRIwXg!e$H>qg#qfz$kZ)G ze|6&i?QU8BA&1(}w>}HvY0ll7tQHR{`5Pv$58I0kuhTi>=jhN`?Au%E+!wgBlr@;V zvmtYtG*@etRO-BQ`0NI#pJ0(WTH{f6=YtS(_H_T~E+W&ZNHOg(=>Qu%L&z;$vM5^l z`b&xhG_tn>x_>>`0H;Jmes6K>+OK{h{rJ~FrDPq3t_b}#P`5W6nVNSTEed#xZdStN zWqwG|(!M%2HYZQWh)}>=e0)v+k{w`nrF>e?@${7ar#qp6rCA>DJ@sdJs zv*@;g@{{0q!Jow4_-f2Gh`;YoL#7<83%}C{bt3>?UR~?eOgbLdxaxeT==>;U>2R{b zjnD@ikTWnA56Udhib}(?s2twnCRvMrxPS0Sa;2At?LZ9c`BG-I8V{@1D6k3)X5M;E z;Gje9{d>WMpqkGln5>E@G+1;n-;rdPf>r>Wf{0HCBEJ8)=NVouu=uJZu|*{~swk#b zMZpS%@Dg}x2e2DTyalYvF+GL-0H37 zgg##-3r&3i9{Untd~Eod=%Zf1C+^tMfS$^OTXW|~v3{o~A!G}Ho#-SjQ^fg9rKM~i3ay+YK+nQ`hA--67Vxc(nW&6$UPJ$o)Ob7fOR7<~ zEkN8c_Vd)VC_S&I86YdRxCP%7ut+!f%VKBiD!YLKDK>{cahlh5|F6dlsnBjvIJX0C zw8L2vDlWb%yYVd6*2xLO4P*lqPXRag=nxaDFPtZS?9K=}5QPhgu zhNjUDEqw*gNr5pXRHn@S9UVzk{umvF+DmJH4^=ZZTa#;zgSfM6LLV{U=%CYjp5?iY zn+I+#?Nc+vx0*ojdalU5+lk0q9=*|rVZI9Wq`DBD) zJBQ+~kSylXaTba}!}z?{lVG;W36=q_W?DWEqNc?D=;5^DLukY{d;jv8Bq@>(Pypl2eX7^K$>9Ja&($3tha@#wth;O zY&F*bHM7jBtH*C>SGJOR%f@V3%)6i5DwO!EFhaGbqslDl7z@h!`o!Dy`;(6)B5eQ_ zT+MD_k9?@oS^{A~(CPqbU>;}tei4os{Pn3UNLT~Nr_^|~s7kA(2mhPcu2LIkaE>gA z(cgb1;=M)+egdaUj_^=ZnEwRW7Sg;7z1d?xJ)^Lw5z%30ex*R4G`qCPqTKc^#u5+l zt{AR+?5>SZyyf(vci^QjpXcMsZA}@bg$(&sbBG^JfO=Of@@U0X-P(P15-{EIw<1u( z6hH=FO>O-Nst=+?)Wq_19R5e99PYy|+(%VVHKLfldk8YQ^;1 zQ#X|$qTAkE!4#K;^sYt)n5?5+NM4r^OJp`E%4htE?warOhIxj9!Y4EQ9nB1lOXs}M z%x6U|nRV)m2`Rb^6wtTk(d49~71e&`7pWEXxgF54(Tp|rx1?90%ZV3yX>U-e2;JVz zZ&?FCjey*F^Uz7fHpZa`-K~X^rK-@MmB!P2Sg|l0P`!`B`_{D47iyDln(Ju9?NC@& zGZ=nP7%OqY8v*G)$ND$$tThcF0;kKguM!cujge=Ey|92{h~aBWtjZ6Q-FWNDH7hE- zM|1-2aKJtWwwjD9Yj;QM}U(0IDp& z7^qdPL_yIAJ08S`=;t`-o386bd8R>>>u;ph%xfiv%416x3>)&fhUb+z&@An z%#XhDFXre}xhTM;0j5`T+a}VzZ=O=Ri&OwM(MJX}e02`=F|~_OD1_U(F>~_j0tRwIRoj;^ z5~Qm|_CF5tvmy9s6w-)y+zLa#?-7wg`Yh8_P1%F;y25&?KP+VwHdx3yP)~wj=35!{ z_Y7!^?s>3vIg~^*c48WV^c^vhssuNutgu`Ab6;Zblk@4-h{(y)x8Xe8?Ebd^2uUADuu!u3x@8qc^wr1+QYOk_*VIhFijPGX8`j zsg6S;#LJVWwxgm;&6e4XEoSmDb#mJPmSkDK_gEIJi+YXqPh@tgy4zX|kCg4u%rIp)B&p5)*!h+g73jJgox4^Ix79@c z{n#o>>z^Mj3li}>u1V3ETJtmI^x)zN#b~E7xak86Do30Ab;wC}M7@vUp(U=qOHd}T z)2k^O1*0iT4BJFxK0<}5FU!%-dc>xre2?z!Y5k&cWXb2O3W3GkWx6a6i zC%@0Ss+;nb0Fd&C^eZPP*fh%ce!mz9jE;>nk#Uk?_e&=l4Z+JNsiPiS_gA4=dlsNV3X_Pa)QVd}NhKydh)lZ#E2cchvS#vx?JI2;QpZ zzRv+4gbxU^gPfC{an$?kJg8aUJ5Y`kG(S8$9n3Oy(BN%dm~VG$y(KOD@K2~NX4ffN z33Z7?ug{kMD?tC^M*@xoN&Kw?KM?FQGU~(y;G{km+9E`0GEtG5hX-t;M_5G5*X*yu zwxl4Qyu}5S=!B<+pji7zbGw?v;0*OU_M+}C+yzpzOG#o1rrj3RE{(F@9aE;g%tkX3 z#rXfme-CHUFmy-aA2tq`+u)AS0+|ubeLJ^Dc@}+iUQ(UYeAM3V0acbPzzybR&qO?y z*A3(cj$JzxNxII;dd5m!PH8;DuPQ73_+#f^dU{~OqG~lC$Z1}WE~2?Lv#nT91{u$+ z8Ii?<>T8w6rl?mD7^AfALCxK~$^d_h`MBQqy(fxju00b2PyWk;Y37QMF_&Mt!^%r` zng6%R!q{%9JtT$`2}c3%-O2QVmG5F-&s_sCX>O%avf=)2qAaP`UvcVIkSj{N5CS&GzmB>!SE`v<>SIIy4n5i* z+UikUYuQk+$<$42Yonn%$|q-nv1uTV0W{Yql)mNQF-*Q4y#B#LF&j!GF?VW0XZCZG zhml)GNjXcSAxMYYR6Oqncc}N{7Y#LM)Jc4F#+pV*NC_U9Pbz&uYABK-<8PCk^nO0z zi!Di+bRm_-@9_kCdwD+xx<%M}-bg;joMxzUsL{ttSBjHah@GY+mS^*?=qV)m4U)XL zE_JQ`R}lqiLCRl2qnJ;8*P#iVn%rPz=H)l4kM5^b25_6-M(Gvns}(y$>;tWTS$?up zpM`X#_19fsGcotl8dB(_h_t#8xIl?`DT53^8bzX{n?6w(vnYT;i|fTH+`(yB3F=~( zJ0bN#PZmy~PKn`p>^&c-jvVHlkp=_{Z#5*gC?e93YRWhuVUy;PHtTN6Ty*+%XuJ4- zWa)^Wbk8JLTBpi{S3>8N_PTv@OG)~kpT}ZLdiZ-UD)!!9fE~XOHv~&Ux3#9kzwauJ z9v>m#RVqp(2l}aKALs6!HK{$WGqEEPcOez^J=$iOoFqu`xPXPBd0mQH4jVoi-H4ev zNIO_Ct$ZWsR%1c}Rwot=#zBpq`5%h$6;09ul!5HSE zZB3-c&*XDOB0t>pK8II=C4-XLW)_#+B_XsMAyis5{>b$?vb0~=?r(L>7Z&2MN|^zy zF10%7UKu853yip!J;_zdjvbR3k~dIQ@y`JpVgqjZ;X9)@)aU3THT8C?1fyaz(&Jd4 z!#zOIYV3p_UyfL=sY?{8!s=pfROfHQmbt}q?W{cmCl`3{#OEX$u%?5fl|>yEydh%Z zg=Ln#>WSlmtM7CiEyz2 zBBl`FW(MXt|2rh`5Ahsg>LbBR^}>vMyx$DcsRxpDDeyh)2Zn6NV)9g~mbNBH2+N>h=~NPDA0$b$j%wV^t|{WC!n-QwN;Z{% zeLqH%z{!8573z@~e7)K_$1wUC!95pbZG(Vw^2EjRh?i_F%2^hd9C|ajz53JL@#{W} zEcBUg%s(tfpg6z+!ur>oggtqE2tL;c%|PZ!z+kOzlV5mowaFb8;y8Dw!lt0e@HPUS z;cv3NU)1Dj5`C)gy~P!erQBP5K~b?fE$kHi5 zC8-Uw(t)Mb%kU;93lp$WnWJ`P2Mr8kmd-66OfZe#4_u3A?oEMPkQ>M@mSb!E|AX14 zulE9Ly8!r49kCJ(fubna>t8xORso=7fBl;FkQAy#teY!UE{ZtMOcdMBf|Z6PyPS%3X?f7*z9 zlmdtbl7QLfF7n6bZY0N!d?F?hzl!shYH*6@)0L(ZfBfm%qv(Ofr);LREJxK8Pmwhi?sBx?6x%z1qsbp zS{)uXH41A@1tc$A&-`s3yk8Eul{laLg%)kax;!T@k?V3=#w1(+$ZN=V-WG_5)t3N> z_)u)&I5piDjDCrn;*$qs-xbVy?VH-Ia@wHL$((j3GJPN%)Gppw`cfk3nt}@33d4eg zrhn?=ss*rLz1XU$=echDM3Kl zi|D?og6y7q3b$8z)Ul7u)Wb-tSw5M8A=X8+o6ruCz>J!A*qsT&T8MRoR3)8=S4iMG-aj9!3L~SEwx613q*>e~zVgg;T+pl+m zvODEx-m-*CHb+8RC{l`@_K;x>L^(2Iusv8l&=7h8NcM%d=5}Hh02nolTtw0_TBgY} zFKObwY*{w(d)y6=XHF!+iMIM~u%tNr4luZfIfF%5^A!m;?Yee>2UN1hBJ<=_T(<{Fz!X*8y6uoE?gHSOmI{>GJ%eK`0Bv9zKn5a{!T6 z0YU}?Uq6Tfz1jOj>1X8bV)w6K(M_TKcZGk5!j!NAfTd~&w#tb-!Dpt-U;qFBq1JdS z{>P61#v6j6d`TvjKznu@1^fnm^~4=BJ_pw#?X|^(y%)P$fS_5ERyuxfHwRNJD>T*W zN6`nzI1~$tSy81Q)iw{OZkD=Q`D{hCqg5{>LT0}OZ}pSZ&qu#LdHsa^8ZZ* zO%N4?V5DmbKrlS?28L5gi()Gj)dK*CWtMHt2L0suj=Xn`V`xp z5j2OtK%e1_qkM=h^D@^+(&Z!?PSPs;ka4i>s&d?dTv8~)g?MJ5gw^SKtn_yT?#~!Q z;;gENbqy6ZDEg_2#jTfFE;?{a zi-42Db*DoG9ev9{Vjr#EgQ=}Z<@BELRurf=!K={U|4FXw5=$lbUN8MZmcndfLygCO z$B7gzPl3z#S54|r&5s3L%lcnlXEs5q&6cXhN#e@H`CRnN#8Ve9(CrMFU7i z^=4}^uQR(hOfrX?k@!)pgy5qMa9AXNwCYWM>7@3|mT}*rpHXz%NcgB96#CWl5iz0l z^XMdw$R?WtMdcs$SEiaJQ|7r>sS$MY{;`IzuXUXrwpZtu9q`eh`X4c$w0f}+C7G$i z&3;c0y|>yTNxJKjW8wt~44=)=PZ9`zu}x&kG~6+Z6Y$KE&Efj8G6#^@84}k)5~!yW zv<24?Gd<{RAp&Fm+Ws&^$AX4_vbAdoySTZY=QI2;RyKqPJyyar613=dYug;)b;Mq} z^=Vb-hDMuxb1BHywb%A@PmXXT#|wA1Fblj_*JUh&s{b$7U*8ZD4SCahu-_D3;MCZhF@^ZWE_;#_%_)Q;=*SV(L>6ACg}Z^IC}epdfh2^DdQ z;n;UHlc`X!5oF8Q8z8V@D85KEQNdiqT~!7AUUX_Zm0umRETdbvOUvMGH&@B?!hQoI z$~Z5`CnEmws0>z7fneV>h?_=D-x+W`zq!_;KOPhnEbuK`4&x!p5Ru{-X39U` zn}0|n{me_AX!e6!yb&aEZtMo#Mq4&KZc??8f00P3ylu?X=TydC^LleDbd5{S zVmxc-L~F`}$Emr{F6dq5 zq*=w0afHtQn&YTzgHM1o> z)zg`v3eBxH?R1Tu5dcT1N$Y->@&P3P9p9UajE+<~RQgkiaj}`MMEbXSayrxB^yksF z{?EUA&L5C}>LpDe2CK7R&6+C(-4Za)F)fwOkzCyTEKXKD|KfJxi1ZFur2ROLC}dOL ztyHy9V~^j$OI{Gl1SkF>jnSnVhoBI4_V_YkCW8z7}kr2 ztrWnt2QfAXfO%2X|AnF9B^2o-QUyo>hybpra$SH>VwyaeWb49kzn)4gJn|JD1qe0_ zUo5kt@b(XGcB#;)G(PkqJdIo4>Nre-A z&4Gp`WaqgLd?bmVf`-XM5KIlX>75mJ8swLyT}yLi(u85X#hVGH^fOKO=_EzZHrBk< z2n~6j2jl71{hW)|15-pIdy=8Uw?lB4Pb??;_W1_ z_wGN4KcO9qV=ifut5dM{=$HC8mV!IRC^kqM_x!mbu<8RpImW6N$d-WpanpmdcL6$X7{~gtjLx3bb4KkM!}Nw zx*E1C=rm)<+Pxlsj4w!)mY^`oES?6Z`0f)=;#|KZ;d5l9COPXg^egHL*ttbvkc149 z|M?q(RYAhufvE3AALHOiIgC`xHVeH#mTu2?iJ$T%k8jJ-+>yWVl*ZV30>&VdkDu=d zEhfbwf()O)Zh-S=vf`~-weT4G!q30P0nl90z{{PfKX&A&#$p#@%gcd>%dV(w8hepK zPE&Ku_&q>;2p2r{Pg5 zyZ`H$UZY@J>+(VXN#Tv5-ZC0H@@yn?{&^Oyx>;}4Ug!?yiKVZ5$XH6?hBkCJ_@dzC zaDnu8A*%;75@+exLi12`JjrYDO^;Kct(`Wm)vvQ?(E*Ci1qqhG&n&@r?U^jiw1gjZ8-InCNq7)s%@eQ zARByBNJ)8-DN!^VrM#_)(BYPZaFj-3_C@R4ICYfPh5uvIAhtZvqZ zBK1I1=TbZ377be|;=0#Sm}pK`2&d#G8&Nv)(!wWaD5 z=>Wl7mgCWOE?a4QcwHGeb@Gs$UEKP&Ta$oof0P^7i}A7V*VyIZNI8N|{WcM2a= z$!Pr~r01NP1hDyFY1gO`}L=5bVmvZZ>-{G2k0RB z4JekEtoYxki_lv=Bh;GoF^d)G3DU$4A-kf;J%+DNFkD>Od|k~;}IyoLSd3lmtK|{?`;eR4(+VeZ!+_+g(DlU;;)G&@PQ5zcw+NkBmGbcyN;;6iB)?MA*Gnj z99Xcr`|WVbPsfD?o-v!DImte}vTG-RCYyH|=deh-$}?~GtFK2E1c#rZucPt~@ zcX>r@g{MJDmQ)YbD8C1nRb-X|f~u>0m*4Fqa7ucAfoCNam;CB%PPcppXWcUVHX7Ft ztjY9`lNcD>Aij!&p%N&p8v~9f3%NVHQm^tTKU&xi^>6iKlYYrZ{bp#~*e1{v7rz^J za0{ctjwte@d#`|8{Dq|Zf;q;hOr-Rv8Vh^2oqvX{rvD1&(3ni?Z~b-jG{15g<-r*1 zJ34rfQZfqJBLbB#4 zz-o;Gt_iOtf}y5ti4ckd0oru6J)wq;A_npDa@I7c&cVxjr5N0!#=J^Qf#++cQc`^u zu&>lM(cl-ivr+D9MY#%g;^);BCej?uHmg%)sB1}UlvQ=CZ<<_)+VrX0W6WUG=UxEq z$llT!{QuJFUU_1{OLb0K?PsrS+|-@92@F zAP!-^VQAX=GhV&*t=Qjm=L^5|fc_uCu^RZreb`L4(zfw*$T?b2FFq`L!(3KN<)Nmr z4?3{!h~F+(7|U4S(O-6hQA_pn!%%lOPsgfFaLBFAxQy z1qh+fpbY`g7foxEE&1rFSMug=wE%a1-8=dqm|hQ-F5H5h)0%sP2_Yg*%Z{QjBrJC! zP~OxcQE0GaFbatgZ%Huy6l<`6>ZB5Wkz)?#BlfWg1vAqCa-Tn3%zpFnW}B z>iK>A{NVL2YG%TByVV6kW0$Btd*>*hQ_7`qdyfzOLK1YD$D}Hc6eb&EKX;PbYZlYI ziilAW4^(z?-&>z~#YTiNigj$LK2YuI5V*vV_P%0>Cb)2wl*qv)BdGoHvbo<-4ONe` za^Ex+3KXT~u`#az*N4o65K0ggCC~m~jmY$RNpXNnuAtHD{ijDVkOCqon0GZTC`9q{%C0^&X>n;idE9zs=@D!&U!VqZp_Q6p{4U+q0;U){Wgi}@!gJ-! zH_${3Ra-6dVWW{FnhSOhRH{>`YT&A9Doi6k#w~cE>tlRbW_GG)`V;`Ru0YY5EMJoA zdw|b4nK~mhMos4m3mI2oyC>_`2VeKkP6;MB9bK+JY&Bqx?OM$>INVQt&v2djA!T`{&OHf5-+oV!B_+pBDh2yU#m?M)wX%gZLb3 zl%nOnPVgu}BYg&1j5lv8{x7=zGAhocix!2u8+Z5M?he6%ySux)h2ZWIAh^4`JHegc z4hb6E-MPK@yU+dc-S3RizpI~`RjbxqzTy4H-%x5*sqBFsca!e#wNmEv{}#b!@r(Z# zX(1s194D8Ast6Rv(a-utMOWa<7CF(+%m4sF;F*NrSOh>3m`M3`G`{K`$GKA$zob!2 zJb@+O?jpQK*H1h5eY+-LbQiGBSwy}_450*@#4-o*5F5@Ca{FgkQb^8hF29I*9{cH7 z{7Qu|;vH$92r-$aJU++1$R*}wIkvqZ=^cJptaH2h38s5K#|;`A;oxfknG_4$D}IQ6 z0Ob}KgM2UsG5;BAG;v$o<|@5%B&-kuUH||+0N~koVgewXMg@J%Y6!cuA&a!Ydo+TH)NY z&QkE@@;i|;of}I-_74mDk^RPXd9cF4<>F*#q2XYpX0yjK1>L4|jS;v;nrM^j8O}&X z1>QA;La2U?`()g21=mu$zu4nF7>+%3u4&HM4K|1%Kqu1ZWpLh1iICC74)R4$rr-op z5G`hzOa!(I6Acy*6R~()H|kBhJ`mn93EfP)iI{)kq6?orK(O?6H&n<{C_<^GZ6@sT zDGxyuR>+4R>$C@bmtg5h0b-3!b!m<$Q%@C99Hkq@*8kW%=KB_m!zVg?CE~AJmI6mg zlg2N#b_u`a%aOlfi0N}59Q>i+EylKTH}}-5Lh%Y+OXYNbh2~Z=9y5z(@`3!xkXc(^>Qbd6jqGg( zXb3(eX7C~XA8Q(XNJ{}25@6qqz&t>a))V8A!|Jx%ZyKNwK-9ksVf0cB{kP6tlOD40 z99^~cK}W3{Bg#D4llZOm>n|E}cTLR}`d_F}zkQuKQ32bI@PjZ9m^L{yrlzCx;h5w=9u?rjrjwKBiB(^UOvt? z6P+qDX@?q5Bp5{+fd;$PCp#db#tY23L32bxd=;vVzZI198{=Xdd^#91PB3JX|K4lx z6vB|`u}qqHz^M@c(wLNj2Bd}M>8(tGW;FP~0;yr^p?<8dEQaP4_Wo=`8)Q|8=Ah&adqszo&(s`df*{yOv2vP>O|aC_=A) zq2Kr5uf&up6LOW>^%3S-K&n{V7I~l#8gn^`f7nIzV)2Smk_GtEXtYn8*|AgGZ}A8J zfjt<4IHeKN>zS@eZG=iD_nXsykleo@5<#;nl!7&xJCC^+Qt~_D)t%VaugXpA@BGA2 z`s`?eCWU=jKt(H{TPBLUFSh!aDWJ>fdIwU004BX)=LE8FM#ld&wg_z_ z$ORxMY;a$9xyyx|RJqa$_~)5}svs#*d5Q)2b8rD%i-K)An?qcn2y!&xyX8|+EJ>ID zZul_X0I;!;M}2at$!6+UO?!Xxwd}Y$K2(Yu?6Jo-6U z)i&vF_>kl6L@I$~gwv;q;t{J%9SJ`^xag=_P#@s>?OXJJHq=5*zd7;-wvNA9Q}xCm zE2GqC&~7u6?3UXp{c6gSe!UNDpc52;A2X4+a|PY8M-@1^p5tjX2d~>y!9Z z`au9aD6`htp#)aMPcez~bx+d%UVQulxeQ7wt$uA&HRVqoQFhiAmVW##6}-KRLcJ^) z{)BDcl?N$iFoqGw(6$vz(UkKQN^p^SCnQyhzFxY5(r@l+AB zNNCr=w9B1H^%*Nwl4RxI$5i{)w)Ae7T@CO6bQ+>ooM~*wAlke$HoFiup#%chAtI)_ zqAp*xl~((*b%H%Q@AfDbEd(pJ&p*D=U)1D8Rk%*+8^$N41Rc1_DR?47=vaxW7GrvI zX^%*KT*7uDU)Iu^2Vab(;SoPeLCciF*UQSTpI`pj>cul&KE!lfli?*|Z(S_=!A;nW zkTZ9=J~C36{;{(u{NhsEQ76^Xx3!Ngj04yA!!G~2q`}+$^_@x#)utS|aJMZiMck-v z^e-X%Fp>s3;OTct|A(c&wiyxbu#zr#YNS=1ZmpLkZ;6G*ijGTp_Zqe4Vy3Uh*g^V)f)!tZBokUJJ~C+C9r? zlagO=heA0hEi4p&;$jL>W=B;Q%1n&a2LH6>)7r8~d!0NYRyLLHL^?K<#Dww>9ErPd z0O(Vo&`s;5szk^uAp-bTSl_Zx<<;DQ#VsBQXD%WH%DAVEs*PJQ$K4(q)4JX3zYosY-3Z@`|kOf=Sv#@`#DrLtIzw` zwqi~G4Wi)46(VtEYPL+UCz$7WJR6B|L_9xn3QgWG8vkgeBvh zzor;}LWILw(&{BXT{l}v7tKnDFhd+yyXT2?Cu5l$+}rvHa~p8dI{4ZS<=EYTyaLZ} z!t{oT-sy24zt{UJT7A(ROe!-+;}4(n*{)2r4_3{*$r_V?#cZlG{o_JTYbcVD?19c) zrkG6PTYZN%YT6NM(>F;s0aichdnReh`I0AAw*khbC(tv9oO*yczzy$K)s%x&?P`nE zOJ72J%^uT8*fO8wMbwtX0eu|Yfj*Z8cBRP#M*UPBIeV>kfs2lXY9wL9wEC&Xn%glA zn_{<@8@6J4L10$4{^=JBK?$E2RPJ!>0aA66hPeu>Zu2C3(MvFCrJ1%MgSdGKHVMuX z>Jz0l2zVe0=+N7b*hL-JeXEl6LfGu*;@}~7fX_OWUKnQ?78J+B3o6J zQ=r-mW0Jfp35|yio zitnZJ1`CZ>evz$t#@U97xaKR75}frTLK=r+`ENE?WIED@$VIf zfDm@-Q{uV@>3Im(pkoK(@66J~7N9cF@|KhZL`2Zp|M4t}m(`v>^tf!neuDL+*1}y% zGDMeeICY*JUm9w2?uI-SYch~L%|?sRLl#2GLM?eC_-Brcy2#iSmq91j=gy!evr=4W zVo&^%?_bE(f)Loc3V*TP1u<3;>S$UmSrdL@Up8kN{reznOK$!5GxQhPO_=JQGWk?! zcX#p--b5{gKI%gSXXC;=svX*>7$M!pV6OP$;J;2?MZU33mwEUd3y_!Eo7V(2o8Z&UlTe7<4^+pI~$dLLKWxPUizV2GT))X_+JX0#`=b=IjQzz6sNS&=2te)FUI0-3iV`TGJZwEG|>{{MnL>V9Rb1Y>ZFISTXLvEDYH5lSb`Q!lO;y*|+ zKi~R}DR`82oB$vdM58a0t~wM^T7nrj@}BX5X7|W;;j|BW8~FJU`}X!dN;`HloK)9agJRLtiYuN}>h z|E_RYJk!i)^|x>-qF1vsK$2x+S+tl?efRGx0;%sb-61`0?x*2qZaL{a>U0h*)1a3f z9m8G?m_BDWB7J>`6D}jVgPb@U9_Jv}4Az*B)We6(TnT)DA2DAGQvA#rswXRppS!T$ zhf~BJVTZfSw|g3_D;Xrbp)Sy%M1u*pvfmxN)Z|RFmA-+8AXIHN)Xp;8-?WN2Zh(p9 zOw*@}I_fa%=92{{Z?pV6%rU<#5ohH0I*jx&M+fnQdQfT+W0u#=m)qg*y(x=2Y#m1l zS^V=lg*oV+SE9p~-nc*JaNdUZco!cC(!XHDfaZ;)bx?ip^B`YKlIWpLEtK*pd6;x= zmBV+SepDrYLW4mwleW$naU#^Szuz4B!`H#4CqGhx7-3mK*H^#qjvg69BNl>qparu4m}L{VZP_Vyf|#3cKJZdVi9 zc(Bx+f44PXqN=>Y{|J0!^z-3ID#m8P)C!35`Bj!5@^RW+3&0&ZZ0MU;DfEC*Map9r zLWuKd^Tw_?XWu0%Fk61j`}D21uA=8F#nF=HX(sd@16Lqh59b1I9ZFMkV?|(3yV z))s6$JHsh2Zia3)C-Im-&jlhSwV17jkf-*mD}BTsCUuHYh(=^Ye&>oDto|kp={x5$ z;5~|Jef0cGs)lq7_s>JOUlV<3Q+6t>-_7CL)s(UO%Mh=V7KD+H+Q}{?08z;STg@(m zmp@<^CJS7gPsV-f)Mtx4EwcJ>{EZoa!pW%ErEvs_-x!45n>#soMDwqnzc4F9Y-RHG zEnGaq@P#TMCUn3e4ul#yn#nd|=mie@GZm3~on;QG;07?H#Lyj@OTxluYW^(8)l>fy z&4j~+L`5P!>U3qc++xI0bTLIAE=)%Ar7%pu5ZQyZw-lfeu!iC4vTO>) zYJxMf3m|6rU=>G^|B4Vc{*aG0=uDV_q<%K^iGaJv`P>PIQgos9uNC6cH|;j8{4-y- zFX#z-423_R6sGpISrHl#Bcr`3P>i393ZO>Ne`9RZ_j5YFd~i8 zxb=^;LgLJbxL2*qB&kx~#d9sDKfAJp#!E$lTMQkiun1J9k<3NJ@QJIESJ3wvdb2+} zHXJ!5QzVHy5`D!sJ1x0V7_n4!ZY7NU@?{uOW z3nj{-p(K6%!S``Jx#>Za!dJSa27_E|1Y4F@bJ!&$!E_G_{GQoAQJH}l+<86a5L9hb z!KJ%^--w%e?=GN!QgwE)c{9fz^yn?nTZSHt0TEu--^(e$`%L+p`bGI0J0#}J8*?5$ zdrw`eL@<3wWIPt~msntbdt#JHqW-kim#lG)k>khPO|UNt61-=KO3oIj3mQYfUMh*h zKwH_mZ6I?%UH~2h3)eCgKKE@=a9+if&kM#_tX_9qp=bj00M}NGLoPd?{2BhP_h7A2 z9L@K+w(gUiCNDxkB}e08p35_u2Rt$#rTFwE<>%jC$?lfIG9=hv%J_$!AUT~$1SV%K zKZdCvj0JWr>#_EY;*GKhwvarSGYVPD@y9H5@X7Pe>)a(VQ9d@zcT|IDXQ~bSOI&PN z2hS5W2jtdu!cYR6_=cYyO25X7%gjC)b6KF4JAKEs1r(DYos0&Tnb1G;vy&+c?pWdx z(^TPSV-nd=nxlx@6*u(N=wnJ=S`w)J^0!|n>;&ljNMLz%Q7&CH?x7T*P0`B}fCwIn zJT#M3)iRIe$bp%>5|fRp`P8iCfU?SrVm6tzDh^|IV2}NIZUITspP;0zrMpr#*3&qt zT86EQ@p>YLhV!6@LDVs2^~AtR;(dwq0f1;=1!Hu{^x`WJQ4KM(c`+xi- z9WnoTiW!V?eZT$BZ~2dt7zBG9Ag>P~`yLSV#Ysvv3oQ*r1Yc^AhBULxr-AV&Fp8z5 zi^FqwcYBFsZO|O~RIhX*Xb^)*$S104pMbWa?3AG!vWW$N=mDa=DiJInH=du#1$qFe zN$6*EeNjuIbzLpKgqT9DKU)0Y_-)LR1f05)K(HgQD8GIb=LM?aAkzoG07pC&hhSbs zqr4u&?!tV#@!e2NC3@3%2V?6fDk6SO0nQF^ic71Gsufx3gOzU z1JsiY7B1KA0M@JU`lTPsG}`mHa;C!J2RX@v)pFm~CDu1%sgb&vi;GG$@o_^b6aQk` za^i}gR&22R@hZVa)*&aXl8p&7*_ymo$jGECXwxe-^sl-Mk4OFt1`ZnxT-E;z9GRS+ zH1k)b|7ltP#1vqeWu+MU5FXwfNOla`51XTDqE8+Li zemYo?D@|-EzWT_9jv0dYwYoALG3DQdurICuTMz&rp0W8jBM|uqgIQ5$n!q}M;6seW zYS_NGSZX!kge;HpOQcmek)%^p*)Ql3k=UL?l~n4VdAH6;khQ7QJ$T)QqW-f#gl?!z ztAh&nb35g1G7>bp?5;q51UbM3u@bpgWCdbVnL%2X!6N>2#ag5_Gw8$llR^jsaOZ%N zTU-AzW4pk*way1RC^(^L1=(<@Qo@`Sb*%~xn(qjo*@Z$$ejK| z^`K9QtvIAU{hvKR0D|zdj`Gk7PR;Uy07-#7Clv^G3=aXCP1E{sjTR}^@7dQb@3B<_ zp$ORrl%`p-8-)?=9+yb&?m2L}0nI(X83@hZnyf!&KJov>_RK8Ad}1<@_MgiNc$o z#Blzpq)Ej;%yU-kuSzIH>L7HkX^1AsWNJX$-bD!54F-W4nA3^)F9_!ai$&>(|AD~g z1Yqe#88tx83LZ}*mPXQZ$w7lyCvkI4G7fJh6qJUKMCnyfX2exjv6iUo3(7GoW_XjJ zm1xS*(hVB*y_bOSZ$}vPN=H+hx+Qx`7}^BT8vVQSdf0pi5H2f-24ISAIV?XzYS5Z@ zU-4zlAw2x^2?$*42&X=awEF@Y#G68s(u?)R`y13+pRCm13XQut7uh5;jk0?}?P#2au2)eY@-%)cWAQ zHI|4kt5+9&x7SLAbmdC9r^hy{^nQ3yP(O%>M_n`mN>S$_hnEZ9D>vKAAtmvx?6n32 zwOIfG6W87gwcS60{qy2`y244^)Yav=A%Yy++^uZ;)9I${T~atU5@uvJBek8+s+dE_ zS1D2A0>Xnf2*M=N73%940CztE8O9t;1ekNvXZe%bzs zfrs>DlA+C(F)+nPitCzKS7{ddkIzQD0u4=xPw;- zcD}wGUQ~=_CCJ*If0q(uk_<;P|K|H7{ndq>v(?X-!kip*;D7~9I zO)|4&q-a|F+fKjLE3}()D9NJzguSs^Yysk$D7#W%q6fd#AOYc=0lWWF zh@sCjaiyCzRZz3OIsGfX@Z(}9y`~u;%LelvJngWhsIQK5LREZX^A6}2|E zMwQ|E#~w}!CV1X6#ZxBtEd=vmcW@Ymg@6TL1g(D$XV!TyxC81Mr{4H?-)|20!~t%+ z3tdAYi4$g>1?pRRTrCq$!wRg}{_j3OG$v`yW<8O_mHp-gQxp_?W&XI!6k$q(u7xHw zF1P-16E>AMp*oX+YX@;_+w{WmE{>L@#Zu*)`~|%21IE97(Zcp2Zl$)92?N^eTl={J z)QAtm_*R`hnh*TXcvOt_lfO;G^i5n?jBsAg6lPKkpya8_&P>z;8`MY>_7afuy}$0h z(s+%u9I;YTIj{dEDDAF#Raqq!77!~z@U9Nof%vE5K8yP(9Eph_jnOl2!4S9i{9-Vk zF7EiF=6(L}HNzk+^`zAilR34#-XC{EXNHh^FR_i?xHmeSKSH1I*TN-_nvVr^$hgXZ z;KJ5Ef1=R0Nk>lc-y^sT!Pw@NBd}X#z5=jGH(HTGU1d$3j7J&YwZXcS3Yaq?_b=6g zL9re|XoMvB@9`&e0szauOxe}NP%Q+M#JdiwKbWaTJ9MR^`yvBLz5&*!o+feMM620BY`Ya|V z!Dywpmr*!?8--zLfx05CtW{}67W66+Hh2gcaz zE9H;XjV>Y4tThS`FxmW^ETIciiWRcPn=)Zug@R#IPFMQ+t4fufPOb=H1c&oy(%7hs z$lUL6%C7(gA#lH`0A!<}nnhw3C@-oNoDd2U-7StEQK4Pmew;=0011K$4G+QNgQT`K zh@W6^#ngFZRDtuZ$jWcHh(d&^oWL@-XAUXo2_hKO%uN zhSOd*W4WNu3sBH=%K4IUPZ5& z4YnoI8`6=Rqo76mdj8sGP79l7lg*&znSyz7`66=LJ-PEsn4=6)ubwq*@Ts3$a&&b5 zdEM9q`f~7l$sEsz3xUM1SgcPtv&6xt4@})Zlz5trw{00WZhxl$CC;07?8SlpoEG9VO?uxT902%v z*H2+z#_t38wdaO1{LY^%Ok?+ggE#S6q&U!&rZ?EdEiuZ1lPM#=?5iJ52gq7!ZSK_S z4gN*L;C?ZV|63ooM=5qHtF#(qbQ;G6$2~#~+?N{VF60xr-98}k(P(w+(@e%8&|6N> zJXV%PNxt9>`I=p}_5pGBoA_7dEf_@U8vUO)hehr)XDX8DLc>36KmxVj!}@;@w2wur zdR@T@G0c(=TA#{ZqB^qaMQ88Oe`+1@W!^RmF0?t?C{IT1Q~x#nn|y&35(-Cctl@f; z@*8dLw~D`(1f<&}5wpT@OK~alnxrVxjG0hMzOjossigGN=sOUJZcP!&*uJW3xzjc| z31($Nj!PR>1cY707g1Fp8O|njExEc@?nav@Du1z(-W841P^_>gKU_RcBKVUK`xNDh z5{&Q$m`MKCar!3}^_M8qj-b15ta6eQ!xt_ z+qi{_MP&n$Ro~5_ajM$BTghE8(}?L`O`r~h-#(RnBMR|>eM^bCchJPWRkvD0A$k;R z<$D;Wb*u=d5(Xxm7!*1qR%$aHMbDs?g9KFGHOIgb0~{C5nLqtcr^66D0f1SfqEX^R z1gio6h!f1~tB5^eS${)Vs(2+-(&w1ViX3<{&PX6DoL-_*Xi1)RW=KkubFcB;GgF`G z0j{J@;h_zk&F)E+@o6KX=|jk;x!-5oF72p1`V@VHRu!x4!zhrqy|w~%k_?f2FR0MX zLy|7quq+mykFCoqu=ihYP|0yk2!Ak||$YwycjbIwM{IF*gZt_`897Ctzy^k@I}B`!-Tc zz2I`;oF}YBbiSVp z%bjqq!$WDnkWEsZLu|{=zC7XL%}03`-=Gc6LZ$RJ`+7n$2N^npc|w0Mu@xj2JaNG+CeWMWSn<-&9sb)#h28cUb65U#Va{Ap2e*!oUU2*+@0~j=}RGAV5QD& z$Q30*f1a_&pv?lz1tWnB%-Q(YY=_}p7AemA9}vK&Gyql*8WJF1?5pLYQJ^fyPz7r* zMkFfxw|&uG$vxo}-f>ynOXDO&+33hhD^=7S^9<1ykElMG$da(!X1nC06&_ISKTv_t zQdHbP3`jBbczFL}VWnL8GSwXO&>0%(qOi1H9!{}ziWpb`R2Ra^HFUf5qXXV~#SHbP zrUx?|PcUpxZ@QbVMmqpAo{)>9h)hr3lHN#k{J>30y^_Lee)nm7#JV1}M%g&v%8f_G ztkDKFqUv5711Uv%07{u1J-AKJsmbdvl6>?tPaf&=%#IJpt5qo}Z>03@8=T#6UhL-A zF3wmMm4zWCUCiJt4u}r$H~$vS*!aI$=fj!(0L8VuF`ngTMfU6iyl+l+qD4^?_!#=C ztE_XPsmkEX1y-(ZIbr|^{mDs1E22SC_&%U6dt&I8Gz=)_VY>h=)5eijAZbe(#1fp$ z^DFF%2w(0`dDJC6k^D89E`Ob?P{v|*2Ftt~+|2_DP=pj|^T#PPx}y6jk{9u49WTYN z1>}&&Q&Rf7yH;D#5_b-4UP)yGF_ibX%P`0(VVgedZju-5G59G3q^EW3lUE(;9?!<7 zOM{I((lYnzm)OXsd#W8gp?9cU%nVldQ*&q`2ayN8FTZr0Ck2m;JAiQ}-?q_`0z8>1 zZ+)I;Aoc%bu>mTSiRB&m9tt1dQxxJ_+L#$Wee)UCWZKN66o(|X0b4@NXX1#{r_9s9 z2iOpwJ|8u0g1nF#FRrL(EFV1V zL)UH;P~DT=5qJJtcuzl(n&9!VdwT(Bh0k)t?+Ir1y>>WI4yk@;J<2cV@Pi^7e1MyG zYLC@3U!wvoc`E2_>HSxl5l^t*ZpLsS23{3`6&!jVK8TWU5!u!#J65kL z!Zm*nhu$!6UwRrug48q0ggze=9$%16iN}#u=?}M=@Dfzu*k}U2=PrCnY0Tq;ay6Q= zk_&M2YRj*nShdLOT6Dmr=cHO8wrDsN#`tM-U)hN@y|ot?P0>^xB$*W0IOi`{6E};3 zwY+=5T`9q~Cwv9vWS>3Ex*pnLo^s7;ri!t%kCAElOYoIf1`k@y>!Svg(|iV9+-x#U zBhywv{@FS&O0EB+`wv%DhvHW_VDnrVWh-a?`%9GYwO+@!_%J4JAO&%`0vcKQQ%LX{L6Q}j1U za>`Q|sJ4S3bHW5$Tx?33vb%ntuc~P3^0SpW_5E%#yGC;e(1H8Z2Pz6x$e&`FW%#}^ z>>ltzNdF+rgWGU2N{*&_vn$#_L+mN1hWp8*XQiwsDkvi?_N9Gr--YK%<+K6himW+k zUO9X-n;ICrtlNTn+@2*fy zlXSv*%W>(-y7f8VroUb&G?xig$%?C#?B}TV;GcGVSi9EWv)YwkgkvB|xGtFj>uTYZ zol#<64aDl=Cl`Bgg5I^r5`KABaDjvbc?EySuv#~_D73l6G739iubH>QT=5woLg*^5 zUydR4Y!Xrs_rZ+T=T_8W670@UjycB%-q?XFSWT_gv+ElhZ z)2G77DQPL=!7Tn7=(Qo=-{Z^ZBFutKsn1yO_A}XCj_0`PWgoHFG7-^1RLM#WH?U*_ z4W8>1?R!0cQ$V}j7gc2NoL7v=s%h5w{fFmX6g=>$gToi6|Ju~R);vafPZuGj|MU|B z2>=iu$4SkftF$!J1%_)P4a+C(b7NJTw$7ULc0=k^@kr zO7|rA%!10W32A(Q_Gm$+dzu@2t}z5ONrR;LXI)&Qy{nSsutQoOxRBS`ir6h33pCogZ^6O}b z+AMEOA_+aPGtXkG5u2``lLeyeUvL9LFU#bE;2q%de?lC>?rguWpJ26DwU#qJbfz2` z3y}msmX*0dqSh6@1lG49gp5G~N3CXRY5u;dA+ihH1g7%~!P&jgkPI(NGV8YG%6 zy=8g^;DWkKF|vQiyHu2eFyX1bPZP*i2^MKc$M%(QF=+BKQ#;y%t57Po1CWco;KgaL z4uUMBa0{CdcLC9XV1h>~oN@O5v6lbW6l4?D=62H_2t(R1nR!Zab46==ei!#QJrh7% zCJDYSA%6#TCtwp-tDp?q3JvUr?WM|i$IGCI0))(EMKiqX+^*GvPvk@zIb=Wi`UMuY zZ`GcW-;>v6a8$g~(Rk%4kT9P__5Zq@dTgWD{bjCT7vk1cIBl_7_gJA*j4&%sh2|8) z|C(Z`y1$DGa|0xyz!7P)LbqmV2{2V_wE8ad9ob!jV_rv9>ZNEu}O%Qp~1T-P%V@>oV63`?n z>;Y;NX*yLm@fO4txYH}WnW#JFeq+|GltWe)Fo3eaH16mV0Bt7`0@(UR!?EMwft z5kgVe_ZjOxj%voWvkhlBsC)JIAOCM$$^+Up>}uTRCNxepTL2b=2txqc)Wt*$s*nfv z#&4t2)f_Wp=hSIDSGzkY5T(aPE5P-Q{?M6Nbn>-Hyh#v~xxvL` zzxULSR+S@|k5X=7ozE1q{VT_f^-5R*YPw_F(&C?&u893@^DN2+**>Ku zXCyaWxEJ&atF~?_>D&!cO0s2+R%w>sGm(YxgJ5 zUzymH2JlR*hem$6qB}%_(?WRWyDj@WLz2qs&7Ef<6Qj8cUy)pNSp#_K3#dyP4D)li zg(uwsC!NfDCIhx*H~WK8GN;6K7MX#u5!7AZhUy?1Ki9R7q(o87W`PtD`a$$0G{9c; zNn&}weaiWI!I!L62p*x+i>V?Cm;{fvi`Gv`@uR%L%_ffy3bK-QQK%WU^21^Zx8Nya zm_F(?F_F322&P7vrasg#sLSe|6RyU~tDF1{q0dq47du|`cte)?8> zqzK}b_LcpN6xkwVVg-1grPqW zjDg@*;@#2n+g~jX11eFqzldcmT_4G;P9dR$o#>h<7$K|V_S7Win~!&;;QJ`ogq~&3 z{5Dk(9!P{Mn%|3nk8dGNZ3HK}wlU+nK}@A6R+EfK-AAPgF0B!;jnMLBMFCKDUsIJ!yYum)-^|EHbO;)-6hvJSmw0$cQtb|Kotqg~1)!WCa)O3AMey zv@P$O?&1)$z~Ea_5Jyaj$G(==C8LC=doNUPpw3G$rZWl^9q;1^O$T0Nd!0GHF_zx9 zecJ~NNH^jUK+XNs!uAUVaZ7(i1h8ZLVZ< z=4Z?i;h*XLsS_zfUavHU1$ZX}>|{{Pea!XAiRN)XwX%!DtwQ7M!dFe@eb14%u`=-YF=YjhM?~_i`YCmM?k_cEoJE{DyH)B z*eOtu=XsES-rKIIk8S4nR9}Ys9gd@XkywBk4j>;0W%s)-fSUMn0h|lAxrLiG*i*>o zxssK~+Jc}S=)DO}+@%F-#$(Tb$pb7f=k-5-0i}u}9t${?^&dMA0^G;T2w-t)9)nbT z9sscW*JZ;!9}p_J;>&Pmk;;|_!xHdRUrGQ!;{uCj__p@47>nb`Y#upGEybX|qs zu{6LB%vXH;_(G8CC@Bx1#P5e>UoVO4e~qK9C@4%I?#V? z)v|+#s|X=Z+QxyDBUtK~LQGF!&1*l!L2>jb_X*gNq#O>pp0}PcA(s*%dx_iB0U%8f zYA{^4(e!!#5q(L!Gih<4UxB^@(}hc5&f7m817KUz^d`@LIDmHmlaak}R~P{33Xi)? z;Jq&M1ljYj;Yv$^i2a86py7+0#Zy`e%pRplc~X(uQ{kB&A}m|&zR-Y6SS6$XT_qMu zwF9W%ik!@H8*W8H5)>B9N?UEsi+BlK(NYkJ<`AVHO_AFOP>!ZFx^MKNuGFMdJ?Ju7 zQaMQ0K=iWJ_@x(`1UBY>37{_}4OmcOy(dtJZePeyO9sKzC)s(cUfe>`N4G z4nei5>dQ?ST2B-p07Y0!jV>XFw~b;-(U9@JpO(jzKh{@(Q!kmVTb%-s4#BeZDxC2y z@&6mKX9m9wpMKNTBbjYEpw+0pv)RBt*b%KK^`mxWn8N=nh^T8cnPW#GC62@Z>+xAioj!Q8oKK- zM3o<1dy3W2G7-u8_v|(19Br4cXm>EB~^CtWb159qz)? zbA12XQTManesRXJY2}SG*d=9CxTh|yf3pJbc&L}_bDIUy&-%Yoa#V-uGL_W(+co#5 zouC=FJY||(B6V^-quO#7Rh-z68;FR%|i+*6}IqI!T)(D z(lW%Pu{17A*G41O`1Gd}B`>5{D3AW zjfGc>t=u}v$FV**M?y!Pb7T3i?(yUP7Z(Ds`2jtpJw$!M;?9492{=`QO38K4+!R1tpkxjgLNbB;tk^fsAgo zaz-7f_Q}WdD&tc>6>z64FmQ$9mjMJ5KbR@6FiDH-t~0d#G7bGycj5?R8a|mYra$Zq z9bNHB3Jog&McW|mVMQtV{vBD42;lNu~yJUNozjdJViK;;N7sMqJLr7828SA8cT>YwqV~L7=(j zsDrbBetdVM1rbHO<$?S?7Bqs_?8lFF4~B3>;@9!6`j#A+8F#R*SYwa8xeg$1(WAHJ zTibi`)OsfS&-C6h$Bo98r& zdN9GWcX2ci--rzg7D>@ln`d#^?RTQxE&6{uIlXK6Y)ZCn^wf6Priy4JYOFz*!FXOt z0PTGoHcvkTs7<@|85k5#Mit=`XAsRs?ZD8k$nIzGkq&#&ir{x@YTFRqk1=g#y=o{Y z&-|ek%6NL%;f&V%A=?gnd2q1O3lkO{Hi`CVRbQStO}>TPd}`EfMLCQHYs<|jU?U@L z8qf!S_I&MvpEd5T)DCcTaesx2}t3I;M4uVx90p6GjVsrQRq1y}OU zX8*9)n&{cXWvJh#(J8|*X>BAu#^IajzD;t}xdlqz!XXCQIM-Ga#{#*axr!J((LU85~ZZ!6mfAG45^YbAJoY$E_=*BjRxJ zdVTqv5h87eo{Yy+NDz*-9QEO&@4My1rsyGr-FjrvUe|`R#c~?ZCFV|P(%!9}1dBZR zB&tsZTS-4VS=iC3Dd-U_ezu8CvejlvNj)dXdNoDdTJz*9GcS`hzH>-?WpS5 zsqx)z1nFe9JfLDAvYkVI5cRHZf6A!bkx(9}4?~TTytIFp=t5??!d*9I5)v;xE{YEw z5tW*^Q7rJAcSO_jRq^9)#Hjnu*dt5F{1GIYAEZtOYFV|2Ykvi+o5B&LsJ+(zI3udF#6BM4VY* z47t=oybPB+eEx4>GU%S-y)e z8Oyg6tiaSE%D3QCID&zOPqAk97EamWZ@Vb^kY33Bkof{8=io|x`t0suTUVF*6(vT&wm(tXb5{yvby1)Q;yybJzz(qw21C#X{}t zgnb#n#_s2@JqwuI#R~H)x-c9d-NgOOKLd2*%Sv24A74!W;%T;DuY4BW{qw%{ZwKBm zFqU@zgxUV#ihnNu0bn(%Z3UrL|;r}ep=_zz!c7m(Q$maJ?0k7{!&a5 zB?aFB(+)#FGDOLVl*jMRrmt*bXBg))sM>iHv`Dq?VQu`L)mdwYFz7M19-|h$1R#Pd zcT*nU5+&)lGsm3_C=<46M+z(L^+rel%KzL^YgI6OpVF_$Y0z~0 z#YNI}=W9+qP}nwrx!8WODL-|M}OsI5*E_KdW~4s;=6-t7?>xm#hm2g?5mL zWnqv<2hMSD1K3mCk91VR4j2jljv7u;fahxZv+Uz0s{a#P1W4r-Mr00`1AvUSm<}&z zm+c;|R$aqFXu+lxMO7A0B`9f$?@b*%_ATpHnBtJAvQQu6M@pAafQ4T;V0bp6SRN*>_pUmccOzwnE(F;?EoB!9L8wi6I>wNt&RxKIyhfH z?lIKvu*LZbNiPecT`Kn?Lj`57!+Whrt0D~xXfY4$WPRIkXn_J_Pi_8Gn9@ zlK;EnkMLN33<^il9kTFt6`7)N%ZH~~sX9>&^3D<(HHeIGvx`f_Iye@2|qSX(76*RX+_NYL;ZD2|^5exWmklD2}lIXkog&0RNJ})k+mgVk|H=V$v zdipVka@Q^X5`tY=g}1*8<_S6bu!FafS)g@r-+eQ%QtGat?DkQXK?14t60E5>_MaAn zfRi5prv4)o`XBAf|9-~;fZ1&zN3^OpfkZ(rK>ZNFP7T^jx(4;qc(95yy(RvZhr8e| z5HzQ#a-D@zisrr6JeOf4;kFR{Lv`UdfBt{V&09X|3_u9F{!vrNQ8G#axCfy9x^L@` z1_4C^Ck8O}JEeVxd6uka2^=xJCajo8HK1`M=KYdECxtmd8~3J3N-6jp>yHF<-`7zE zAoAc3qtFCQMjH0YH2Lv-eX9DQjFGpDTYL}8Pryu>(CrdJqzYpV@Y1`}KCWbP8|d9H zPsWO*0ay%v9GKXTrC0xB>HpHXKi0xe8vB!ML1`Y4{1L}eMHxg!DB{7u{q>0i$Gzu@ zvqGA6-f_h1S&4-3&SuwKR>>0FC+ppsK>D1v3SRPk*X8hEOJNv*px_WhXkC&(r69rB zPRgD`CF3Bgj7g{Q(*aL*h?bRm7{n$Mc?OXc!CBn){`(dvHV9_K3b_l6vf32;Pyo-r zp3m~wu``?hrsv)w=0=|Tp}U*ZHU*^SLvyGg#B9_6+`v7zt8NE|6Uo|A2ISgxIl$+< ztFyKAZt#+RDOwc_<9mE-9R*Mh40$rB+oX2nR$#+>JvG8*6iWWkYZ}c1on(Z341>^++RfRX;sh%7MX^IEFhoAHraKEIadsvb3@)91j>c~Po@h1$6h&L_%8zBq_+SmXJv+!hGkMbS)qWAl5z^# zOa4D|9Se1|<=oMWkgX*1q!7JDDrqT6yVE0yzT#*9P#AQIr39dD6f0nd_tIs;0~{j; zXTrT<6!6Pp+u#wEqN>`8kLD>g{Q3%`ew1w9G(fa_x}9brdk{&jV4&3^+qg|y63b?f zv5Ck$*wR>+t0@pAQri8shvapX8VxUd3hjMmA&@f`SF2yf0F&Q*H1g7lj>viFm`Z zAsAo0RuNo=(;s4$+Gr~l;`1d@ir=TW%0~dTYmYrt=m+M=vuBzd?8kHIP*VU2W~XJ6 z-vp=tD#9Po*nU8x`7dZVLcD}hKP4h>QvetS5GDZl0T1rezhyiji73832{>Ph2r{mo z<7d~^m;&@<@uvtNvNe)B+ls`Rf4 zY50%WE)%w~7NQW{*sUPoU7i1y8U1I!2sM6s$AADWc%nK5?Sd&hfr?|wfG@{^InjaW zY#mb(b1>L;9|^+zJ7<1x{qb0=&Ooip2kruCuZ1CX4N{p%>_z{;Z{7qYj_G!fFY{k< zi20InA$s~QL5If5#K#UW+7|Qq45Hb*S^9VxZcz^_k_I%=6^+q>YodKLk^Od!`E)bCuV3&dn37lT9)RfcPrfR+nz^9%d{cu;TUCtEg57|R zK75=flz@E{+UM-8A(KE@+h2(BQgCl!do00cXHfCud|^z_w1b6NF<99M?^NIiSP-=# z^HlK~EdMFp-#K43>MR#fXadpex+hr%Z+V=3(O?mZ`~b+J;BVH#Zfoh`McOdSFWVv$ z-5x>bT zX3HB4F4@k$iF4|RjFT%8f|_Dugex4j1P({B(pYdj!3hdD1XVikWDfmJ$+w&Y4S=mO znwDV4mJY|4J~a%Aa8#`5Z4F@m)F2%NF?099eBAUB_jnDwkG2r8O8X#P@>?O9FmSNL z7m)UcgHWWlTTadRJ>bLT(Y~6>E{cts=+x!Y&Bj8oW$;JBgcj?u&NfeAhA%okV`t^# zRNF~5k8LTlB*;5=dCw3-)cu+!x0JTNEzVIls5%?*OGl02J@!}@0MoLaN5jx>es|c9 zeBQ@&TAEEA#8$?OU!IVRtG-1zM&M8nOL1JN&s|bh<%X3Uekgr-dH|j9cT_Ca^DxH)44nC_)^YY1D zW(+iM;ANLrc(1oD(~Y~idSM7?JRaQ)!TEzWsYR7wTH5^=3mPNZ(*E(WD5ONw~t0t z!fBBwwm-~%DkJ?1kw)>cGn)Muhdy$a&#H&glzs0#QWYq9KzP~hYYE8va2uXnvo{OX z8n^gb`B=_eN-A_ZE_q4t2TIamN(eFcxnV7DY+ktDGe>ynfCj{twf0maeCIvT4dZ(T za0%>^3z3NS5{VGX-|bMszOu8@)o=$s4)Frb8%;XLFeoP69GfLxdWb=>_W3y3Fkd4l z1x!*~CUKUcSRQV#Bs10xY5sYZpOSeE|0o-5RbNP=VeKXhiT+Q6VB zXz&9uB!t;rozmq$1E2n$1^tKP%xWQzwAHc*E_!{Bc5ms;qCJ&WA;#=vHpiuuVgc(l z+E!dnA`n5Qp>%{NIvFau28$0>Bmt>63un(eVa@=A``>)04nSvr?N?LO;+(g?Pi@(wfFq833As78+to;A~!INF1+T zkr)U7_h5Wc_72mB4TfimC+m-R&{H%;SHYG?Ii}d#Ag8Xmf36z)F zK{n}XGy2GvRj4cT@1VN!QA`(GQL`@|Ew!2(oP%eYp=+Z7vSFVmT%C^|lv|tSk+qDM ze?$0UB;Jnb;bJPHlz9u;_gFP%g2~JiY0yw;Pdd#vR6uwV+XQVz($WIbP78;MSq2y` z^9F3?Nt1nwx@0ZPdZlXAbHkVk&9Q})z&ZWNS$}K_w-+B<_B_fgmOffZSZuIF)e2kj znr&WGK@I5Q+SK7%>+F%HO^vs*+&EMm?OVynnd=y5WgLQL!56v{pU) z2i{Hl_Uanpz%BZ9&>b&k^m58YAp2an%`>AWNEbQL-1OLOLwh{e#n17RSa4zKAy7y$ zNFhMm%-I72)yU;n=CNW4piM5mkywF13MwCAh&Sh;to~s%Jr#I?Jc580LZ5O5X*y7k zBBQ@9FzIFcsl4JY#usu9+;VHad}FAo9UQm`zPj6!tW@3fIXZ~DdW5aj5momd56z=| ztw62t=u%|5FK(hD(PX?p+f4^#sTR2Q8xgo0_EcWH|2I1;ww{}qw}j&db23*$3nqU zMp57M_y}k*r{W9-9SP-@jp#7nrT68~f&3Md>98Rd)-vi8Vzr0V?=$8#$`ANy>q_=J zdI&=0FAP@h>ou+oy5dJ!UYPib2(j{p3Ggg1=_fRec95N0A24OU=9Q?xvkCn2O)p#^ ziHK=20JUF3K%Jf|nUBChmN5G6W_iV}1;T^x^q0gP6KLK{ul+u4(Zbj5KhZN4id!GN zU@O~wJX&!L9x^#Stypv=!#|}(-`co2<1jNPiI6Rp1pLi5o zps)p{3*Wv9KKKeibRtTZL5v5U{y^vL5{A%e>>4{Ij(9Zj9IeLP(+53y9TLHV-~S%A zSyV#P%0TfrA~GfD$h?`9isB#b|cf$kb#lM7rXw_MmN;F4w5J< z#XpVE@*wow+p@nU%tgU_B`iYjuX!thAbpWg@#Coxf6xNiz(`}P#-5U$dI#1dDHq^m zo4(az^i9OnT;MzoSrC&)?2E_jZi**U>e8y3G?=V^!m{^LC(!zc!U-|%mPbh`M!75_ z4{05JNpcMyzE2ID&>7=kDojl-AZwe?Z46xe7O1xZR9If_3sO*vqLqkZs7Lfvs}z|; zL~YsHkK1beu_0=D1ppwiCX`9_!o{bBSU3c%WKV9v+6FqRi!X;c*0(cxW=rsK8SGxk zsF$LO_bY8bLB&nBBOJ(g6)b_#B9HQ>Rj~YC3;;eNEn|>z4+ztcWyM>kx~hRj=Q#IO z_XW8d-~z+@WnIN4_+xZP0Y|UJ{Lk2g)JoMLUDpm+39;sbZj41^dmE98u`tBYhy#2c%7x99@SuwJk73k!jx+pCJr1{UUuu2 zsk5-@3qKO1fofJNrdEFn0t$5HHAS@w-OJk377*xntA$|)ZI^I5eXSbaLv(Rrn~%$y zLWt`EFC)s~a7w+qfd7_PRa>ISCJ^K}mYBlr4v#z?Ye1->!(-x@^vsuMW6t!*zEaE( z5zxvaF;4vh*!2Az3-zC4@gIi5t}`5!GB1cQ7^oW`HlbgVTf7%Y(I!y^WA;&5a#vU< z*MUpy3U$+3YH?j@4UyA9ko9!(s1tB5$%i zalBeziDF($Q?SC1jU0X((@hP_t`7AGfm;2P)-eR+M3B@+trNU66 z0elvW0-KFonx6z%Sfg1l+O^NgRBHU&8{gW28>U0_uEhi4(@vx~`DgViA;Bg5#!IT< z>DcWPgSzES^#Cp%Cg!TEYv`RjcUq99+JO#C>^;z>5;Ek^lukG#yLd9%9>N4wss&)en6mqqGCx7yd70_8c0E3 zWRS;x?rW3=#|@thM~@XKAxy9dmUJbRo-DFSaJw4EBV$pw4#yaQTnGja#HtM_YRGWg zn$)r`+Z>GS_x%G?NcS(t5X-TMP&`crcd}JSWxQtVye7+rIbum=@_vyP=qq_V$)z*m zE24qYez+0X+U0sd6}cNkcRT}xJ1x91MpKuxG(q|_%@;3&<$ZRnj{q1+YjNyR>1HSS zat~8cidD3ab^4`10Yq_*rVqa<3|gfzn)@c$(->{9FCmJ)VFu8jE(E~-K)D3}p=^L= zrl*%QCtnlq^snYXsRX9(LM8BHh!z z>=tjdNqfEH1^G6!~4v&9-=-~|6zQL6Fj<5Suh&r|Ds{3 zT~8~qx%%Cd7YudEQ<);sM?fL80J23ICA)_G$Vj=u?&fYFm z0SKztD+3%W=we$47|H#k1o~8}Lb!ZV-l>lTbEPk8Dpd0y}ihV@7 z<@iX{pTFg$al0Uc{S2dYcR-Wv-Ot#Nn)Z^I2)M#;Y}%#(K0o#%z=MZRRP9}Z;O%N@( zqJZZ)lZhvdD-C+wbJ5&e)qjAdAZHQZ@0E-uWPyZkwj>A02>|HdylI#}0O9*Ha0{9ah}BocAgF14t@+3EfqvBQ0dFzZytrb*YPy^xN&d@F9Rmkc7iS=Ih=ieU9 z9Q*kv+w4N*gzPuZfoO`&3b+537Ir2kj45$zyMpg$-17luH+00k%U;!TP& zhD#BrGs?WpSI=HN97=CIrRQ*7V@OS8ORx|~R16)IIc^aauXTy`9MaBC2nf(=PzacO z4BS9g;xG(23-TnhuP%jw^j*D|z-iSdN8#z_K z&O$c%?g?7ccn2i62EH@va)t<*0c8*=$W9%&%56|ie?=1ImoNk$gRa@FT{2jDh1dHG z4DfNLhv}1hBp{*uGXAb=XE%A z1LsbbaXc!85*2${i>=&eXlIV{5SG8E58EpL9er;`k-4sEF&emVl`RptmFMo-uzjkY zR&81YFC%j(X+9@WY7>scnumM%dNjCsylD?65^{f#bD~^?BCzKp*E41#ltSrWr2LGF z5i0_VRo!-jwUqea#fxYPvuc_j!t7o7g13IcY4l_|@V;wWsCFYE-#Suk!-mZvjcE0A z{($m^`4BU}G3ulK;38@hbn5y;>GMSod#F`4$9U2I>d%)Avj3bnM(-N)^;@Hdgorr} z?*(Gk=g1vaKwR+SN`RtZzSu$|BQS|RpVPSrRWMO+nVG?vNsqeUg)MDc=7S}xHTwll zzGhV+m)HJu>wK|lPH}==o+dNnVc!isNQ#MthECc9y!52pRO4WxS6K~-3)YtA%2O~N zUjT*}S$#x3Rw(?MY|w7X2G;gj+;a0gSVd?!EB-kGTpK{3n9q!CslXA(u)<)|)pT67^YI zC%5U!tVeHF*U+nt2!wpt$s=7}_NH}+-2A91;Yl~ttszy_=0V*$>;223bo zpDzcrM6a{n##0GhVLMnf0=#I6T$t>FS1tzYtymGdNc$j={YXt! z@?XkPsZbe+GsA|il_2J+e^iX*e?~UwnB7*dk@hhN`qjC!tdO|ph!5&Xf4ALCtl| z?_m@+%t;@SFxcXK?T^sq7dceOFb+oL9=kNOdm%=#1+U z8I<|kIsl1fR=D&sH=mkfjKTDIkoe^dBIIhgqU3er60(=8d=+Ih?AX6R9W7UP!1Qgv za|%eWC3dc%^Pzwus1!o*D?*lG%5{p@p0J_k&gQA{_|kTe6XzMSvgP3gyV~c)6u2n1 z)eX%VYDINb>}EHR`i`r9?=O{xB1BZYLy;BXAj>_Nd-nWc_;VbO$Me?s0ceul`Cv`> zeN{420ZF?-MlXG1h_;c@w-elW}5;a);R`!K;^ zaaOYd5(mNGmv%#fqpf7!`8UInH#sBm(CGH_Oddv=vi^3XLHb~*9mH@;^m(Hcn6z7AO?OpGuV+@)*5+ zEv!edocf!D?RD~%y!2upMH?X5BTT1Cz{K*UuQQ7q|9Ig59*$l2#iuQpZtppY~ ziqPV{1jmpySX{Xx8`T>-6Y3Wg5ihn?dsx=@F4bpq$bS={CvJ(9Em0I=tc%Qb8pT7W z%MMI34zpMl#R3gc)+jPuc9@AVvPpJF$c0IVcm?H&C0Su!qCI7)QOxMKOi_u&j>;&{Q2CJHZsu9!go?B|1*LL{j$S-Qyzlpea(=Z+4H6q_^sW#q ze`C!M%3ipvT6Q?JH1ZS6N15*#)!*6 z!xKyrz*Zk^_-dO8h1l(A8%o#Pxatzrnmj}*xu4&Kkh`ta<=M9Hh0+mF!#k`%)6LG1 z=fqqFP~(|li_IhKF_-;8M}BbVffFD9le_WdYT(sOV}1zaQ=kw#D%tGh z{Lu_7FcOMC<1T{A{f!4|JVVm4yrRG){g~l6@TEJ7eVHD-O}sYsTFLV4lL^heGNN~N zYSEv?LX4We4`W_f9$!D>Z^J|)b2%!KE7Y&0j;$e;cCRL#tX{_8ePMXwJ6j!cy~hGh35K4u zOwIf+Pl2BgSwU^0PLqiI%^_PIA6|>*Fy`AWOoaN^4yM((aoI}h2jf=UQY1Kxe|3YN zLK5j{Y-qi}Z?x)}E;=zbS~@sz%Wf~T-)o#rv=gy#a-4SOZp^TP&tuOd4isPbwWMOg zr{(Yd+S^~HWgtS{`^9q!A=9LMR~A&FG&zJ{{#Q$}?PT~k=tFs)4dV#EDQLAaar;%V zl<(lG?Uvt=(R%aB$xgso?=U60%m|^O=tWEOXA)s(IPq1{e<|B%FI|2y7s{}?1%9hz zT;SAcLc*1h%=w_raYPqQJt^RmXAf5GTINB4LT|onO#3$A=^@!01n-cO48M(%z%_;z z;xCAo%CAC(XnTM-N1CPe7iLDhnvE;tPP*Btpsj@-!@3;984Cif#`@ddA=Q2G$?q|o zf@bPgSKk1cM;fFTQBurL!_r7;4I&u=XeQos$2SO~Zkz*0o>D3W@?G;IS<5$rgqQ`E zPP8oTiakY<1v#H|;+ZWAhTy}4oItcOr7_JfQ2fZ?kc6p^WM^RhgtJjbemjqfFo;yu zWWP6RHiTpIrOF)3d0MW+jLsE0@TOCuXT%SVfY2X~K?rsJqGhWlQzCz6Z9cbm;U$Ss zS#w*NhY4Cm7Boh`x^X#&)yX%~ZSfQV{5=6TrpoQIRuz6BV->*O?j3TZy!eT0Kw}s= z0y=)Z*nCeBO{`%{bdJojay?U-;C^HPS<3mui~IEWcX^9IZprr(Qx!3>D*TxxzV$Sk zfu`Ht>bAI#`qRF5de^CEg3gSqyfF2q#{cTUuNWI_+smc%vP=0HBex=|52LZ7Wgv$i zg`Lct$IIPk8*0o_&e>Wiu>HXNsdMHBGn_>!)5HTnWRvV96UD$NAVqV z6dB z(!~=wg#fz;Ddn$v^#H=G7OgeNZ_6=p$Wc#Qbkkg6r%9Xi+q+m!^Ur1y|S;MAaTYRjw(! z37Je4OZai-|A4gTKL6EJ5zLp5^kN_36I~~Kor)s%6cpvv#YQfJ(hgZ0zcV72A-z)> zq478)U%ZEfJ(N>2g8CUym;43`yo~`xcfxPDVWfawgQ>CJ+TDsY^4NYmSyaAHArcx? zWss1q!eUbaL)D%M-phfe%qTLFi?x+B7)HB4)@mUW<1J1BWD>2hz6J@l zjc(;#wo%MWiBczP@e^^5-J-+K;)rrDYdR>Yz6fuu6@5xJ{7jt&(5hfT56prXm{XL(;q z^mIOpYkbMaVBH^_G4?(>F?`zx!8@WmU*U~-SR=%npU@Pz*&iL;1+?&l3FQfs7_kzG zK(Ho;LvshqY&#UhSd^JsC1YvFi)gNyK%|MH<9ZBd+1kSoasK6}V;{c1tk23uaZ(`U3 zU4vPgsyaVKZe>8Kwbm4`vs67oVMNznctYm$BLJg&?EY`qcvFPq30&6$3Py}AJfPW^|w%GV7@i>VkHq-0&W5bVtP(UG9H?R1^PesF2z zK0jWHiM|#LfKd}c`5Ywf?cWp3=XivF9&?WERW)7Csp7T#gkn8BGXWsiGvf!!`_HN_ zlW=*&WqMr*l7FgZLFjsINJFjY&rq$Za9xxDB)3H&AqkbjuC^Yofm=0!dnA^`G}2o> zI>^iS#T8NL(Ah4?n^@GZWDd_vQ<%sO3CqTEhqLn95?8NVdxU*Tg(NW4cB}_qy8_VcEvAn25eIfR@y3&PfG=Mcnlx9)` z$F`16tMF9oUi;H7Q|7&Z>_2%9QwVrL%Q3jqV9{YM{bTlbb~O{fxI&9l5WTMTRxmS{3MAUs%FZaR=i&@rZ5Ub5A?%|ZQNE_# zV-tkfR@KDWknRN`<0lI53=|Hh^fktTmV1`3b~)BH_C4fH*mUd5{aV2FfQ0hik5q`+ zPrgoTVQlu81Z)KVfL&;BfUlZuWH*pLMHY2i7xYE=84a~_5MJyH1cY6DgS3cL<)K8E zslf_%Wu0lja<7jm3kO&vH`vM?w4m|%M$K@VkN=CJ_BYNO7+QRk!B7i~U$~loSFa7* z|J)n}$n5n@s>h{_K>oVpU0H7R5wl#6Q0X6m5^X+l8r1PteP3Mpnw>es#E17$q^c-0f(9g)opnt?4`a77{ias{^SX#u4! zSQeRqbHohCU&{a58cAozAeb(j((3cpaK$E7MRNKvGdbnKRuudfG=7K9EUaBbf$Jqf z!1;H={7Zaf1v_>POwjSyd|RBvNN69NaIgjQMxk zrnPF-e*tZ?s(~uyl2&qmq(8b3hpZ_8G3bnhJ1}0MX3*!p~9EL}@uZ2D(7sg$)!ua+e9Vo0(b73Vwn5%b=aeQlF;gxVk1d$odZNa@tNqhasM4%M^UIjMS)<@_ z4(GM*JWbPT5c!N%SzUu!EU36gD&N2guqtJUnq^bfm2H@)uWmE^-l1~j>+w^_Dl**b zkv%}yGxTnv0=Ws_#4&GXpeMp%N?H+~R%+!7CEIYxMZh=Fw@0|E@7$Hyq3wQ@8tHJh zWM3v;@+eIbzQexfz!WZ8>H9lpK>u{00@s9S<1L@Sg@QNboIwl5bgGs~QyQ%p973N` z28Y}Fd+9glw2Q#tEYNpJ{1NcOJS1fENl&Kzac=uVERO@ZAU{;A#8=@NsvbDfO;hn2 z{O(So+QmxJRNHg5pPz>IV=~p$2G41C&{J3hFO!0}%<(#40}Z3AkCkOZt;lK`*I5D# zcNcliGY5|DPfECSrfbqsGK`l3<3pJYLz67&KBjDh)h>voz&VSTK0{%I0d|l99f{m7 zkK)L-KZrmz7bt+KhGMP@(*thb97JR~#?#r-%hBK8o(6znY7gmC2^wZuBBr|}CX5xh z&EN_?K**kOgr6XN1PVrhn_N+D}nD`(e*QIY+AL+O^Hs$EGcvIbem3Aq8 zv)`LHzkti}JL0`_2?#hfUr^Q+THS@qw4MkD4n1G=80!xtlHOviQmWKGT|?M(K2cDT^H$L1&cM(A(9=<-ILi=c)2{`P#(<~(^>nlW; z`?RDK2+%{`yZ1UGrbyR4l>d!_oPLS&&z+r{yf&qu4$&U`Whfk>_eKkuAiGNiwwLSI z1T8SWxb~n2vAzj}zWX^D#ZXhm*wMi-zOjgay1kK5b8B$#4$ed>t>@ggl7X07%x{U4 zCytERGLke7ZAzyHq`42xpw`uNaZDarE5xLXc8NQjV%}?*pHPG7+Uq|}AaDSv|CJA~ zfY@f6nOJzUBA9Pd?9#ucz7(~p9#e}gVznob#%xN)Z>KiRB)mktFG0a93au<0j{O)< zBn+{dk`CJ_V3mqp0)F!kJm;D*9@hy4a~>9mFxc&qAO4`nk-48y=oAHMXS?1xsRx5p zB}Nk_8gJQZ1v1ng)&VqPJa=D+^ABPJ4zovn7pVA@!Uo8R#UTs-8c~PwdIzOcPB@p& zpSY}h4?2zNB#C5ly(s;-4UL;Q=R2~IPmClcVw?-?<{|nG@5>A2S|t+XB?!5`8*FhMT?qG|%XERHJ26&)7pN~Fi zBf45Q;a#3u8dwN?uZcc&$N~hgpj`e*BDD7TjSc0*B2}hHQh6iflRWy z3yiy_^s@m8|E_@wB3iR}&Bq|raslx-e|<|NVjeplZ5lD82U_%-7XU^uQbFm`d>*mA zxYAUMXJso?9IPb8-h#^CBGY&QP-z(tR^)Qk3S0x+4E-G1{EA>|D1RVhoahU^5mBGB z%0%KNk(HrM)nh`m(wxeU2u3C{3G;wwAfJcmfQVF!?M-nEZ_g*zMimS<*|4yy-ws+? z$H%t7>3#LlDjR$TRlnQ@431UB-8T5`EUGND@~fnH_3lK+-u} zoX%d1%E(@Mj&B&fY3N*{F*Qsa{o{&B=^fxhA(%~a=$d4hNR!kAClTHDY9|v5@MM7O z0v#~m=({4`&H5*e6+73N!F-a=nHh7#!y5lAmZH`Y5q%?a`!y`br~|lK0B;O~cxiCp ze5_Gv5+58diub`dEMqW>NfSp?1N3L7^sCmy$Hvuooc z@eQeg#`8uf44dEwAh&DaX-4&5Pmtb4lUwuc^EXb^5`w>Vu^^3)Qb>+4hx(E?o5{I$({%Tm_IwEN1s#yJvA>$woyh@r|;mLDvGN8n3+lnW!X>Yss zy&qN$U$GxG*S7Qni6>Xf1vx*|9Nnn2c2h5*S!XUhpZ5L@W3nAW@Fmegolz(W_Spoe zv@`tLf@+>(3s3&sDHqxW!OC2Nq9xb-J3%54fu{Q+`-kwjbP&|Y{=WF{$+Oe zwQntw-@Dt#jMYnT6|v@&I>s=}CEEZ*g)bfG zKNmnws83ThNBCIs5q+Ym+}~5Dpc@|ddj%a%D``zF#fnJ)YSqzUYTCuVgS=0)gB}Lv zSMIi%?Gd{Ry~miKfSO!Agm+yf50*0FFa;dU2Sj1;8|ro!+9N7Oeqje0nwuMP6kIZK zh{Y%9dy+bB65Hu11goq1rVQswuqXWhxTk`}4(!fYLt=C{ApTCnBs)9;Z?q$fid)YQ*`ZkwUf zK}o&+A;aTzmuT?bH#)GYoAhS)Pse(FSkHT;r<0^8Xf6S{QLDbT0KDq^Pu!Y_=1EX3#2d42AI;!P2O*XuMU4+JM1!Yw3(}8X#6Le*j1q?3QLeC(M<&qAZ zOBDZ#TIvzmM%Py~ldQ2kH|M~kMGnk7US#+Z{V9>UR)gOK>(duAS}J)_wYT<3aNx6K z5peydfGOO#KlA)-WpP*{bTZ$Fyv zvu*LRAbCZd14b~`Mj*Jctl4rrnhau8ZEKSvd{;PhgZr9%_wr2i-Hg%;EX5%(&R7gz zZ;pQ*lZ8(E0CQi2C&O{`7!mSxLQIM{rj86#*7)7^i8Z~!%|T~JJU$Q)jY?T3Wy~Es z$+9o~J*$p~Auv3OsEcJ-YNPtVA{{$al_l{ZSvJ=zb&ml#WRd1Jyk6u}8t%oE=gldi z{8L$qQ+*#)g?M{Gd-QBlvp{M%x!*`~zyl;@+ zu$q8012wypXY+N}jYTHu%xI2V0~J4d6DXE6lnZTK#CKjoF_vHoZP(iJcQ3PL$N*+~ zd5fPD6Y;lIc(doTOcBwg#v=+%{6F8*3?{cdS|a0VY)QYsSsRCgL(o!GBAW?($$M%E zu0=pSrYviq4ns^VVGvpDgs7&_anW~P>jzbVlbFG@$s*bQ<$K|;km81dlPZa}GSIPK zE3r$=bh`e(_5u?(?hrDa3oK^dCDQpy*VkB?0MESS^V4rkYL&lm#NHryC!pNPIV&&p zPG@Y4fYd;9Xi*A`_nFo@2Q9Z=c9}bq+%VQgUw~%zK04C6u#~sb>QU_;(4b0DD_I&4 zbu?DD_^rZ6&(tX7bjX{Y#p9WqH2Z`$b&>B-XQ6L1azTYiWH2Da5>JmcV{~)|f*anE z&h^RDO`xmS5PjURoi`2`LqT2bSW1JX*iRHTsCnP(@bka^zJyhifXH~XE*08J5Uru9 z?CBn8!utaUSLv+7W;fOJA}F@}=CctTo|*;$+sy83`ZlT-^ehn^))kEhKXN~v(xD9= zfW2+m8;&N2qSsXI)yH$kH;dflZqs5%k>RpYhan2ix%9TaMoc=Wo{blkMMc z9CAn1pD6qjiMRC6p50(my7)^7XI;?yDF{V4km)&hG|+Jqyb0_KXPT9GVjmU?-3_f; zS0IwhMGjpB4`hgZ!T9~dVFdS3r5p-vEaaa})QD`bZd8xa? zv~+K-(Dcc}28z2^H``&LyXgg!&LGvpbVpGNmPJ)AM=Nv6<#~$NycV+>@e>>54A^9q zEw~LZ^>B2&6Qc&Rrm&r%&}ZLtFScp|`q$$jHO7tQS@|*La#=*P_+}8dU+FvQgZViY zEe57k(T>W!AN^)s8rD4cNtDlpoc|6!LUNwC#l*td9I9QM2{3k}lV-Zg1=5;vBv42EBHfC^ zl}RI%$i9Y`VaEl|?axW-0tT5~3NZ=*np0H9St0t=bNk3D;v_NqtJDP@9Xy)C9H9b0 zrRA`506xuTKcK;Bi4TlNP5dor)<~L8qELFRD-rV0Qws;Nm->GIQ9!Q0q~N>uLeN)w zBGq}(GY9`ho{#6tzb&(B#TFV(lN{q)lNx*?CspyD%Re{Ana0j09y2lDA1gn2!-Kxj zomgd>FeASW`~z>Q_?2hB*Z>^5OEHdg= z<)@_Z?_5Iag&V+=U1EJU+400OFpn-XHv0&JT%E(TKu$4bOFlACfiNBDt(RV`@@JXL zJY|+Mv7^jrJH|oizzk!faWAceOcPHYos27STuT5?f7{}!!Fc3b!qYqJ*EJ>xhTo^m zxRf|$^}XS5D!h_Of}B@@bK7tk?0y_>)Psa4Wu|OaJJ)!TLFR zAm>CJ@pM$TMM4Ga)0-LHM=<4R5;qG{Tq{775!I_M9#3^R$kL7#J*TMU7#io>^zXL! z<^~olA2x3Fk5&W#Nj*~dAKXpXX~-9Maa-IMmkgHiShRxo zSpfgc5UGcvWexS}6dAdo@P#|Ewe>CjseNbC2L8r7R>nui?+gI}Zj4)vFyjXL9XQ5I z_h|-~=O9b7#PL!f`&yKfvXY2kbyrFIFX?orQ4Q%hQ3Bs1oN?~xp$dam8m5+jV>(N_ zi1EaQUnrX9@q-L!V*ARoQ?&eT@bu*aw;2wnvhXDj!R*tUX(5Xzq%UkE%FB!2D2grE zhxs8?E@gp#eJ0vp*S49lJO^*(&G1k0@VdHJoOEz-`$URkcTHqQ6cg^e2W61mWX1s^ z@vOOc5#x(GK1qFf?2z%$R`}Pk^A`do@>WwWtjc35YsO3$iG%OQ<1Wfk?2gmA^p`nD zL=Q~$+;19OuZaSDbTt3l zK};Qq$iu*m%I!)V#y+0hIrVmp5|KQDlRq*~t7SGSV8ZwSK;y4%1yEIM=Uz9af6LYmJ3-Z|(z@L4du$dIlBU{Hn-r2c#;f zjW?3M0-`tbhEGQo%%3BrK#7t31g@M67zvFg#b5Ea_Umu4VVf_8gy|ji*(GYvF`x=g zkRAw`F2~lkSwR%*M18(HX=jm$kBIX(=~B+R{l%O-bXB@Lb=G4ykljNz2g_t$Oa0vJ zDAM6PWzgz_Ns6V*D(E@6SuTeSzQ@w3{+-W>7k~@Fb{kjev4B4F}Lnn>@vzSuRlC))i@c<{^VjQL(!U#x!t3nb;OH$2Iyj zczQ#o*EkEh&7M))*2%3Lb1@g^FDBZZGtX$%lzO*nG1N2)XTXLPOHPj?gpxCdO$WT%m61uWg>B`uM&LrEH`e z)m|Y^oUrUBCsUwkxW;pE^4pgGko`3X_TS%^r9yZn6mOOT!wj1H*^O!d(Ul;K5T&iI z(@CG5!65SfwPLX2=TXp>F0VV_L(?sVwLl?DzGMv>`)`}%A6I4#z_lVW)FLZ6@JC85 zt2Nx${%V~c+)OnkFMySi{nks$%o!!~FpfR&uS%n8c71`~4>}ON5XM#vYV2gIR-ZRQ z;9xj`>g6)5e1=}yj{YVEI=5qhB~(^OLgRuVPwh8IT8vdyDUsjZ4lo~?n4{YPGuCe%hV!K-kUAc6r12O zXTcpK+5U3Qn576nzN7ddfBw+ToF#am2VJmB8-K^|hx%5aG$44$7fT4_(cVRzSL->O zQTreNIeU1LxX9KF_u?`gmQ0k2zmdUsUV<_~Hpg>L07^oK>uw=e13ajJ zXMh9SsyB#5h=~enDL?=K2@tG*MqU5&*vXcJRINRp#T@9f%-E8F3edE)ZHC9@nVpT@ z8Rs26=`VNfUNZyWIP7k`H<>#tNHMUG;9>E-2RW&V$>yI`Y8RShnXmj60~1oz9}zP5C~T2Kk#VN2d76XbnA%oOim;CU8P==orgxU z0|U`2=#iQM;PlmQ?li4AtpJvt%+cf^WkQ^EmC`V7Nr#@7wBFA>s2&f7?r?L*5Jk1l+#pO79>ik)u+6sWn#a=Nd3Eu;)L zK!T)|cF99V*0B=7lyqntmI?gX7cpuL_Y4se&0i~uEK+kAGJzVm8alfc8Xb#4oSg@u zcPsz^HcIZ)1K*O00Mj|t>#*f_LGt17tPzoiTWvl2V+xc&86C)P+3K7=%z(o)QV$gH zn86uyZl;7dbQ4)PJXAYP}Olx*1F<-I-jhxc^%I4YU{;AW9v(5iZe{{B|ZOX8GD zPS)(fg)G9dJW5qZ(ZF6utU=a5TxV#|ESH5r)6^2p6IIBoR%hQNB3CrW5;AdDB#iVf zyD7oP)!Vr6EI%C0M+01>i)c<%wPp)6TEKrwZ<<%`;X=O68k#IdzZKC)5u~NU?ufn( zCU8xy;b_2$2~K?O1-jB=HSUdQ?vAqYbV}-%lw{mF1pC%&L5lk>CYz~USWip3mxf?} zYzitc1kYQx+NEUIry)6}bOcN^#nt$j(P9ekj2+d~3h*j=g4}C|dQ;(h+U#6)S}hQO z8S`r;aO?V;Wd*m*Lv#|~_w_k=uGEIKKV1c#Eeza(u?{+)CbA{-+l}DiK)xAr;al@8 zQHbS=!85NG1BW$p#WuCu{OAZeqBkv4wkxl+Kz$>C%I zv6tc??j^C3YiVA#S=4Q zyNr$bGH7g!%X0}vbW)bLu4V%qmYA}J0AdQB_fgg%sd(-fSI5*{jRZ#;c)cwH-Cn<@ zns6Z&vv6j++eK}m;YpsvC+wF_Csiwi}n#-HO zu~@@HFZy)L${fQ4aGNA&rJ7Y;c@c}yVLg=P=xuqS51Rp`<|8>Iv49trxXd_g(4wex z7Tk(o9XBb1mrVmKNzG$-8F?4TDpcYH>yZloEfEdxli@uU5t|b_lvon$o`*)15_PP& z&chCd7))o`Fy5x25_YEE6oHL}<~VtERaZgT;$A_Q2WPpnlUbvR>Eg9V@4<=V3u8AP zxZ)Bo751er+Sf~oNeO||W~lX!imjHeydJ2}y_wy)>P~_rnXA3duLS9l+NCBTC4r4> zAaFi*X05u@*jNxP0(msj1hK=|#e>AELs>e~-;05Bo8&ve)uk|T(Wq&7z$nBxDG#Ot&;+Bi2@*6s{+^m4b|@*++( zRL#46#5nyG_$;-YIoyP!+hVPuT6#7QcV_7-(yRwNNAGZM#+$^;g5+lm0Ryhk01zQi z^E%o%1P~1l*kMH6%Q;}wk3Pb^BIo^v6|K5Q9{DWGTiWL>{1~FQ7r%TkY-xwd8OEte z(F%+wAzr-HZwDDAL1YTdt9f-M?Rd`Sa*hOvY6_b$V8?v2@k6S zn1vaj# ziLctD2zxXRyo zGUoGkN8i~fXsS7Rx#durG#B6OHZqId>vH=ONq4t{<7J~B6NbzyaS!$FM_8G0wGPTs zTu%)2ks**bj^A-AFaA(wJ;^qjCv#q*bU#&c=QI%)yg-9Sb?v!63jGEY6GN%J0)>YW z88X|I@!}6J+;pyR>-I0X!zFFg1E|&NYluw;ew171WptXL<-5^C`US5 zTIi#Gg&$0q1;1Ytq%;36pg+58aS3|h(c8&7+GDR4RpEy!lNVY@%3!#5VU)pR)?)a9hle^~hb}%TDEopxo zwZJG*{SmLrI4I_|sTz`%V7LiaePOWjg^^w~O)CAJUVQ;(f9Whj5{}KR-(OmMa_qXS zp=2@uEik`|fguM^B#*6`rt$TtlpTyDh_&v2wWLXsRwv2l2-2`;ozA8kn93X{8u<UnUz)N)tp{+7-^8%Srh0C?Vhc`xxHZi$pmARIm*D4fJFrOA@!$?__;8G5tEPbFaFDb(1#<0mUfFLhr z(dRgirG>hvn+2&`huCLb&@|14{b0F*RWBB1@~d>sdYIHIF z9}Pmg&GR-9&v+xI3&Bt?Ww>;5yECtXw@j!}r1e_|+W*NJCd@W(35(>PXkRikX>t7l z2c>s=xTJ&nqjor-^0m>crLc``5Fxq&!)D+}N+)QfYA4Uqe2Xim_?DKpD|=>J4Cx@h zwGKW)$d7Pct2&C|ZN?9LES;wHMah~SnaNS=uUq}tss5kBwG)iMUh-AlNs=Y@?=f(^ z%|oT*r-KcQ!a{-`$KpNz_l*_O=W1*kfd1(S3+m0p@Q?B~_?uUO22dxEbj~#z*Ro;S zy17-=J0q6LwX2K2C+jN|g6gg=X=ERuC*|(Fa#9XQ?_p21e{Cxwg;IAT6mhb&FuEzi zL7H1s-p=;FwUF}sfw2(G@2fuXZrzm7y|sT_iGZnfV*3YDW}LjRP_$oh`e{ojdd?Ki`IW%-VXze_ZbGbIX<< zT~kWZc>)HmURH3cj;9Y4T8mJ$8KWxi$*hjTHGQ;=KLIoinbH18{J<#DdT>#(-k#L( zQ1`%n!m`nca7@1l9uInz#Ocf<@|_2dTqpxxLT1_rE-$GauDD9 zV(XZT3`-f(JtNwg@c1^p?%$asuaY*7?;Z;~9E8RX9zndwi;R9~?XIwkJQBQw7Yap5 zQkA%vh{mAFqo1knH&M#wu1unkBDf%=H(N_>~`od8%S@ zcXx>xb9JXhP%iCX5Xe8NwCi7XXJZ4qS<}C)oN$`dX?GugEUhk^6~ggL6(>+V!U;<= zkU@tEh{$7GWqY-Oc!JO_d#9;s7ey`$nr8q9y9vg_!uX+ng!dEW={VF+`({y6HzKTe z6ACx8DZB$Hl>lLr_EFAh3TDZFj&=h4n8KVe3VBvwp&PoKNMrSSgh{D%eQEk4Gh zX}l;5HV+|fHy@!%9JOro>Q+PUlJI2BxO*_#BCoKZiJ{DcLkq^O)tR4)ImYk@Qzxg8 zp9Mv6Ao0bIo%A&xZgWXCQ5= z+E{g+->8!AYl2{=2Y}^8^gbs?3Zhgx^7FNBKReVO7@c$lCURCbXq?*h6?Vvk@#mQt za}5HBfF{zc(jbKG@&m}tU-DtQ|dYmuo(fH(|(`_ zh+f|9A@Z~1obh5FfNV!6fB4=%{Lf1Rxm~NNcMxX$kux=k9C5VRF?raylo~KBc+OTm z?HAy>4{6!2&Zu=f7NQsDwX*)NY!pm8dXul|&+#ZQ4_F5HH0y`rjJHw1HJ8xVegK1g zZ05Q4to=H~5xqu?;$~2iG8iGz|AC+YY$`XecB6cT4XVG-zk~IHe=K#V(?=|DYP(wb zI1sl*dza^FeQ)9Z)V=8_X>@f1;UVJk$ba+4J~rwYd@NYm(gwmaBa(ec+0Rdkj7uyJ zVji9RipAMMkQuv6E(eFE-a`SDWg!9fAlh7Y=?M50F~;SI%X5+Q7~}Qw6<*UIp>0zz zisCPs6YN76oJ^4c8Q|3r+zuKR`kK1-sC#(wK-_|}&Tu~P+Ib)+n(MoHr-(GS0Usv= z(ch}qVKECxPDG*8=qHXq>q7vDa8Yx6GuUFTgrjc-qq9)%lUUQrmga+nCTX|M9c{7^ zm`j@ZPjG2NTm_B3sxfLBIN$PMm{4RtfR+D9Ny3Jy;vR;vv*diK&*cczhkq~$aoGIF zo&%S6NP)gxMh1ozF?{xZk!bo)=rmFyM~n4MSV_<$V-A#SV>9YpPpJnBO38~I{aC9J z(N4;>v2R2yR@}EcYOj_O%7P2GU8LjX)L8Efn8kO5YrF34VBdS0*Noa(HZ<7rsygj9 zTb5aZlC@yM7%He)6U#63ecN2tFSo#LD9t|Vp6~ln{+)sPB*x7g_ib!rS1c@DWaD#F zUH>nF`w~`8!^J?s@}>p820UI{DK8&=*LmX;=|RLZGAz}&Q6{4u)3ZJnNSt=aI-)Z9 zH;Frs%$Oi#kkn{zLTiHi?11Iubh3tyFGEo-fKUt`vq@Bsb?BM-tz%5l}S`ygMEMhe18@APQ9{gz(FbvwNv%De*w7 zJN;+wEGyyE!*h6+0QHs0$o+O~J@edrq%N+H95-56&lT=o-iZLJL>`yFQs38MxNOv_ z+j6E7^Sd4WA?ysacM(NLu-_4cewJ{lTFumH2e2p?jH(FLRE^t+GcHAgqF|IVA`@J- zW(zw~$TXp9O^Ws=q7YoFLel6!0=}I$_A3MioebRpOg7)S*Oqpez*YvtHiUC`D7FjW zbt7}(WpzGtWAJW zJW_;+oRkSeHl~t^O_*U0IV2cM&IXD#7}#tJ;C=)gMZP4Lz4A*8LxnmWcst~fMwsR*7@Ta`(oJ0hq*ftA~iG~a@Wiq*tkYZEG_GV2trN~YE#2@`X zukO^6Tuq2RAG23JS&M$TwB=bbQ2ApDw3hjVb~&+1x8bYeWbULB7q;$0l|N)O)kI1_ ztKrXYm?JPeNU*(h~Fa+PkPstPLZj<~l+LwTDJTcfA86aN_={NeaJ~(f*R7iBw5&+E&mOw4*?@_(y>eTM;t~LUiCxu%sH?2vK{*t zi*#O&W?)mc`xTSa{*UCkind(thBg`(@Aq~ZJScyboF zD?X*nc9OUi&2A`M5}$>p^VSM+6HdL`Jp4bJ95qh#s)lvJoMRm9ZbJU}98JxyKq>ZG zIl%g@y^y}3AFZT+PK@!C7;v0D$ZBW!*nizTgCa-)+?`YqQgh|lw1UoWqG~?vwZu6l z5GhYC^e4|}Vn*=@6EeaMrX5tBz%+gja7I&bcoucPBYY0Yu2h`%dE`Odr@)MF*p546 zGDShpi(mX7F5u_Rz)^&(pUv#0A}t9>w>7!!lh#@nYYe@?FPg(9!pe%bW8XaG9m z_J=WF%22d?NNsmYe%cm|eVoob{DZ zURLuSXLl_i@-HBM!f}h$_;nY{VC@!cDB7cu0;3Z4EK(vCm<(g$%x zIw_4sv0W`gC3NkmNQdX!a(UQTB(p6A+vY9bpiK4=nKz==SK zHZkSPeJLE>ii=6dzefO-`jH@%oafBDLLU7Mf$s`bAK?LcUMNxEg=CCL(W;j5ro|MC z=-+)j%I>i#Fz)vr^wsmD*c5ZH_*lRRRF~s5WLvg;u+_Vq!pEO;tK-1S4cxV#?V>8D zqs+&Tf9{=6Y&l9ujdv_;QjnDRiqoEEe8Dp2Yhu3^XD3l$7GjGi#9Lskoag;RBh@4F z@)1IqGS`QAx%~zlk>&e=7K2|!++wuie}@xpo#&n5z|0H$3%wlBH*`8d`J+$xCB^DI zG<~;2SJhE;2T02{OG>ZFCcWXVfjs~6Hw75`93F^ly0o4yFs&5RVjMABtuL>y7}_L0 znC)na9)wlrJ6%4P>)-HnqH-xH4b$($w}TCS{5+Cm@uZrc1Ftf&P*fJ@_%t4oHm`1^FfkhH2<1QnENHG>9gCmQflKR>uJV6D0_Aw*%T^(&|+}+UR6ZA)nCoSGW&!f zE26*ZMgpPilgk^*;q$TPUwf(FOA-&u_D*J?1^FgdF`S%Zr2WVCj6Bimg3tv-FCeD+j$dVMWArlWZ z{BS2RKnkdKik5dHhfqmSo$1IW%{ivqqOomwtrcy{@=p}v5JYLyyh07hI1ai6Lqf}j zegFUi0;t6P3VsRdA5`x42^)iNu~6L!{>i_-Od;?LZV&f_Q-2-+0ZEIh^~9%;FT zHcJenN=sc18oQO!3{$fqu-wmYbmNiVdW-P z%36pfa4d0T$}d1`?_lCXkE|4O%JAMOhD<{AZHXbDrjR-ujl(6e7#Z?UsBNrt{A!r% zbqJ;%`e6gm{Xhu?cpweYHj;Qw9WRvfxpDs-VWfUg=*u;IkH5K^+|Hcdb@`dsIjQ$m zPI+vA$aKJ3iw!EC|8~Aq--=ZHNw#5*zNoK=?A|Nckl|*HL``x>$V9h`$Wi>^qaBA;fEJNeeEK+E+^kU-IhO=#XRGErrS~q~9%RgJ;Y<4p0rXN9=Kl%w`lvlWg zQ&W@Wg<)G6PIuPv*ghh3KdcZ&!No=DoU$y|(k9eb1ev4Vuj1Qs)mBfSKm=UR9_6?( zm6DTdq8topXPkSWE&6za$bW?Jv?J7dw>yinPG$FG)FtqPd2o3nfY!kDDOIG>G@BYF zx$%JSaBnwHJO9ua-diTY0`#D*Qr@H?C8}yI;6m@xk}JfkLW5U$O`G1$#WnWxV9O@% z2X97%Vi)2QBXrKN5nB1W@p8~ffTxv&6{n|jk760^EgMZDu;yfUdQO8GA)rFoW1phTu}#9-{~B=}%Rz6ECX4!4DwF zLyXHJax)WEbS3sH!hzVqr4y4ZuBk;ucwOfnbS+z-@pYVsJx@k%Ey5y%F>^k@P-5gzX6{PUX%`tOG z0taIlhWw=Coo~?~0{(>EPrfQbD!E;6bt#|pWn*~E$=P5_cXtiZ8?`R6#a%=g&)b!I zW%ViNqYVf;P6JkS$seL)hAUavMsg%Ob;KTV188Oe{det?U^Ror^m83<4q1?7*1RR( z({@H+DHKT0zI|(N;_bNykTp!O3)DM{B-P+9z1MxuMbR(jvXHFS;{D_H!`kn7MtdqG z`n!@W$;)1hRwmg}SB>ae$m^56@^4nawxf#nE`WChMdAGG^wxZY79|KTv&Dt^)%6 zIRb7!O)%_ zh+N#>HM7EO^*_>L`vC#Q%;y{Vgg?%tu)u^~&PSQOo&Qpy^q`bP^5#u^c_nbLci{F0 zdcVh(#+eL(5M`H#r_#Qj7?{vn=gqrp)sS|D&bmNNoSv1b)s2`;8P6Xap_3YCopF^y znSPyS`^k%Tygi-VEJ#SB0TefFl!$318mAmYhr5#7rYFD^<_c>)Ees^ozW>#M!cy^! zCjYz~r#vFG{M%^2f^Y)j=Bsj+N;2||EMGPZR!JEkN}1w+Rg7vfpW)1L&~DxV_pO0J zivcr`O#B5RX`KfwZ)AK?<=9oMlOw)!X($2<>Jm%avVorZ=vg2c&j8q^o5O@;e;{va z(|pmCN(4-4wdXH~rS=gf*2w$@pkz*Zc1q`;HYm~t5NHIM3Ocn%VUv+6yX=20UOZF; z6$*N}xRk4FTUI#dML!w;Io}7u6!x))4wWo4hMYlfDj(mX^GFI^9-Yar?9JW}O1I>kc9%XK zbgO+PyYaJq%|g5PF)#!BCI?@zkGC1TLaF3mg7SWcG04G40cQVwh~#LB9|-2K#XesV z?VQw?oqW!m*;oS_$=6DweM{AQh2ya4T4lr2L&t5tMU-rrpvemOW8s~6OZ2dalKq~I z$e;!sUz*Or%IkpS{hpQ}X!k1oV*n|9hW3*C9s6Fs2y##1jsl?oi~eCZVe#B?LRuWE zZJH!~@vE@Ym=AvdL$z3LlMx5KQS~XaM=o7Xns)4Bnqo56zhtpM^tBLgI^ep$Y6UE& z*ddCb?jp9|<5`X`L8xrD5J}zOZ-9_sggntsk0G8YR-iVw!aLV1@rB4?%`V=>#8-lL zIC5XyLv_QiHMCN*l&gu_L)D}aGSS73w@`h++KC{ z;{H3e-cwu!PiN}uL`tMLr0&DJ zT+!{V2nhsO{r=t99yrQF+$`<29(s|^l3A)jC&z{8mC5RaHwzsPX3{J5~mA&&xvM4e%-(fsLgBT^9LvcL}ER4e4qcoxi# zs^=#%rsd;{r-;=m1B28AeDYXY$|<&aUHNVlRPjJNc@YJ~jr_J?tYg8(l~gL@vt($@ z45izXANk$v;NuE!J~)6_)sGG{lLj6%8qqM&)s%4srW+jN*|{=2P2()G_zXJsM1V;{ z!O(YMN`}d35SAF@w57uvAHrYG@i6*OJhQ-Izc1uT_`3|Vogf%G!qOI?-^@4Lp!zq) z?=@TnEInUS*k?GN2qi9C^q|F;RdHgL4ZNsbP5>PaojjhSM}~iSq9C^88*|X8fBRiP z4o-8Bp7vsPmtz?J1=AR zY?I?%@o(zwZq$#z7$d1Ee^1RHrtPl?6vdVO;k!Z0v5ZN|;MUlMYQ|r&)w@YeZhk<(ii!KiF{S)k68IP)?^P>hptWEe`6_Dx|V>)d50#gDH z>jXDZ#f9a*0(C2KC9%DLvz?#9Y3m!rLhqHx)jzuLu-_FNXx}}`Hxg`p96~x3_QRgL z%1lvbijvhyZdCS|dUyJgV~zk1A1md#STeU=ftGDx9|j>ETl~BBfhQ6N{yoI0(s++? zm*l8=R={@QAOI}DJk3SNN1+4X`a&Y7rMctz$ya;VsLkM80cw{o3(KGTe}}0%^r8RkRgSl(!~h+!Tkp6CzI}^Ub}^QC@d0dgcjuJzycZwzJ^0|dKuiTI zCp&bZnlE@vodBEI3%bq&?}gMyv7Z>KY%1OgIa@RHXRZ`n>6r0OPs_E2Szff^)i8@9 zZ%tEkBr2N^vE25wT&#wGrTm^C7|D&wv;qG1N`C>PDwP45;yShJMhuvX&5@DabUJ}g z#AB*D!qU@$+R{t{Rat`s?4QNAXyfl-b%#;%Le*s?Fe~Ouq&0V60gmFKN(_+4!P=Av zgEC>FmxybfRbnavC7bnI*-hj?DtGRBQifI<+bAY+s>Ok!>#z#B7H)fg)kC4feDh7D zaY2j{+^Xj+M{fi{?}Op7VwPa?greeY7j2TlXuAA+g(=Ogg_Pxzrgt#9=S{0>I2suCp<#4RE$31 zI7LatZjW;A0KeK0rQ}rbf@IVXi?)|c(3bP@w=(t)rfTBcpu{;G~Kob z`J%WUK@3sKqmM#}X(WL8)v(~VeLmgG>~Bcn=|of+o8E-M z-z1ZjW$NoFBw4(U6i~@`7h^}V<=pP>z7t5S|7s^ypK~cf$Lq{B-kiZ9cH`_iP#u;Zw(IRRWz-_%Fe2w%$hAQcq)4w`Lu z`gqfNceu$~{X|`Gd6n(e*iT+0XO92&1z9()X~TQnKPP|AW1WZlmpPx8=t)yoNg z`6zn_YDE)Fn2Y8py2tVtAjk~TO8B;-s^@R)<@iA3uO4s;GZDB2sp$|?D-V|&6}e-> z6BrLCLwbP1_Y8LEmwU4M+TfyJR>zbc6P~^(6Mo1h%+8k3=fZH(DX(L54+KWx@ATyF zvr?Recaj*oObnz8xd9h4QS8>gi=}2yRv{)Fp6{Mf{-Yp?$&aN_kTL-jx*859NF5H#lt^YDdyY^Z;eiGh zc$s)Lcq&p0pG(?;mmRH&F~ENNX$vw8Gl$Fi28IQ=#d}7WINnJVCpzMxR}OpCgEIr z$k@HII7rC=p}7FaoWp8O+;qKXKpT^EN0bQa3iG)<2rw&>KjLqfDdogiM@@2ZGEvjf z&Tm;0=#5|J_o4vh#uM|Grjhc%VGL)W{haHLn*UO3ZA0o&r|A ztxoeYk+g;Kt}2+yrmIYePyo=z$;Vb0e&+WABS`RR35TBlLD9KB5|+wVAsgIVId> zyT#$!?ZNQ{9zeFdZwACD>wUk-Vu+%!n(E^V|E1I#&Wql_TU}a2);rn!Th8-N`o)qp zj=fX=+CZf->xBcz_!`N2g82VHb=PnqdQ6D0?G?W0tyDA{fY%+ytqiwOw8d;~({7MC z>C%$`Sq50VaDr6aDdb2eLL#Hk+@YtSPR!~~Br!>gkR-$AuGvDf`=L;+kdyhxeHVEG zl)8$9UU~+7yO4MT%UdU+_K!QcS@+`Av?&rqQt;@bgbd4ndZ7D3yLx==jTl_XbmTyw zDA;b@2LFtp00856tX+XJ&v0{)gEYw%7xwCGKj*AdVcGh)cyY@dhQWyuR)HJHWM0I1 zF&9NB1UUlT{j7KXL-wBY^jH}|g3Mqly&P3@Tw#(_j356Ob*DsNUMh@K7_Ah0%LeL>)hn{K}d|ztd)~2Y!G64Sl(1o=1PTpRx8Kv2H08-aWwI zN6}Ac*i^s%01Koxv%CN^Iy2zG<5y7HI>tA-JJKrTX8wcQb)}sc?wkpwpG`TJ(LX%T1V}CV|-SkEpMrQ%7MLh2wk(3fFsj>B)_^@=(OUYhOqA z2Rq5ZKIaM^l)1ZnyikmVVa~{sq{#yDMkWF~PR2VgCqK{bBbi%Gtj}fcfjHrRQ zWJllH;LWn5@&QLZdm4Q~vOuynr?>(z`Vj_4JILfaK}g-St~c(HR3NFNdRebc`)m^R z>g{qkOIFqmANBoM*Mnp*ie&FGyeD0v?BdBy)tC@(3=U!Mtdz`|aOBpV30^2RtL*3+ zp(+eFsMkJ^aVy?nObWsfSEeLKS2Sw2@X~i$?x(ML=%mP?_i@n1mepQ9bp}0%5N+E1 zj5DVbRkmfPA0i5Ft%N&i!|}>RP!6bY9iF%xmJfWHIlxH2+Fg5EV}jq$?I^9>0=aHj zB65K*jVM7GCqduW_*<)5NwBqYy&yCi8k^0Hc@ScJdh9lTE_X=r|3Tud+?Fri#I&Zi zpqGuZJf|?-5Ndl?!MvssGV(I?sJ#s{%4iFe`zSOB!-cWf=?Dl9L#nlw;maOJHaOmW zf#&561-F13u4Us5aI{tHKLp8igJ4b{1R|ItK_q%RR+yMV^ZT^C50+cxMCgC*y=37m_G(aul;by9_dFL^^=r*0AQxj zMP(&Zt@y6<%```Xsm*1xb5FM%f1psstvR#P3?79~q@m&NrTDLD)xJDnpnwJ_)JC+l z!q2B6IeOQGjzRgQKDCQY6pk;xlS1S;OkKmC2B@c_Yx=uM zTX$?oh$@Q{(p}-C?QMzR5yGDV`Jl%)tXZz3glhUn5H2tSLRDa&`b&f+vxlf+REVv0u;; zn9%x@{t8~NK4zGv&P!}c>kM(Q9s#Qv%|UYR;+hzd@FYPoX@xF|L$fh8kTqJ@Hqo6Y0vhz1fCbnQ;+gP2G$NF$sq5 z@0Di|aKK>`QA1(qNIU2|M#ntn`pqkLj_$9i{4hH9My8I9y1p;i6{?ky39?W(JeZ%) z{|0?;&X&&%`?Z2S>J&$IBBkBU$(#L>1dP`>8_$c-@+9mWqndE^*AfGl$=6v7T`T*Z zg_6ZD*dk)%r^QW`7NCwlsvush7#H++g#bxFw!ejCmG`kIniIaO1_n-VI<%igDu~d# zqT1tHU;s65S_IG{QCH2+sPYidz4Gq7V7$H0RHT19iSTABz03b?@s}{7 zb$#pfk$M4P-E>p_DxWauc4vNtBtUP=BZk*-zkOaQ3I&i=lO~a- zgZWYOh71wyNCD>n#v@~}`Wer-K*JSVy~5FP$0OH3r0Tg(fHac^Uiem;MnI5ZGC2A$ zZ0P|j{pHSPAWbcyIR0Li{9><^>402>t1E1(L*ZW&b;hb4)V!0&+EA~Mwq8G`?dE-X zm;-KVWY}7K3%4>c-|EFDDs5Kh5x+r3j*1R?QpuA*tKog0m%dH0$cK!i;dQ-tC)4~M zefkYqoIxaXF&9yUTh~OZVO}GDY$tUD&jIFNW_3BYMd^SglmxGR{QuNYuhN5cV6;>i z^6JPrPLNqADsIu1iHRij4JTq~`2EAR3E7C*$#Ip(vaL`WWh&aO-)7&Z-4F!?q*Phe ze(aK;ix{?UI4QF4kcto=FhN<_=P- zV|%41@5gOQTthM&cL1w*l+NRsi$w1GHeZd(0U=4Kl60cfPM+~1yD*K3k8e!`_>br? zXd3{$g>z>Ri-9Vy&+x&Jo)n-)Uk<(x(tc3cz^}tL$|3$Y`zLXnzUG0q&X9^nHKM`mV;j%xkCZ(QU50;WMb;x%l={LkH?Fu)}Dh=N#7UhQ5f&pvOUpmKYnWENggLeon znkU$(&wh#;ov}c=pNI1~sX)n!hMCW0EnGmEId$CQWzvm&H-MT)AMA!UbugYR3RG*o zsvoqx5sy-pWV3XX$MM$XV9-Be>(DEG-%0DR;zY%F5nOK=@9w#6H-k-^jH_Q*jo4b; zhlBA22e}kB+of&IQZD((G$8~FEv-YVR|rtL0Aic2D0AJ8=V)p$iATRcYD5EnnsU2- z_I;MN@h=30N~T)o*^MPmb4iV#6AYI?aTLyLqGfg;3|S9Dg*#9K=+2^5@(+nDqr9tK zIQmd7ZERn;-05?!-(Ja5L=So!Y5A#|Dr?JAIGFell}mp{7nu_>%oU3NA3dES4!{q< zGsMW|3BH<&F5G#Srw(Yf6wn0pzjv+&WKfN4l_XMi*MGl*HK5ZfQhHRgChj0){b{jH zgy7sF;Q|ZrBQ2Xx-=Cqj6Oiu7)*g@#AUI>Q)q*|Aj)8NnbyZ=5x6iMEGLVOxuXx3V zeYuH6(=n8=%e*YE+T5;bWR$DP*q2nL=FtgkAP@Wa!f-|8H4k|JsC(CjE+SaCh*iVM zLNvubzva)wfh5)Nwfd_D!@b9*`8-b0)s>u}*2HJio=pe@+XX!72tfUp`i!_-?tZBb z3_Ke$$i&{CEG|6eff7L?pJ+RN1rWNdQ>4OrW;*Ff%&W4Z2#bd)4UzcdP^*CY_Gk#Y zpe&`r53l|MlZK2Ba>S4jeV-+i(S z{dAIQQd#h2N2~`4|Et62B^Hh&-RK!I#?TaED;k&3zdZWk96L7zQ?>6FI4%xDvl1=X zSsyg0H~fY92Y7{0N^&5og1nuJYbDG9hFBbgW&qBa7f;q+(o_%uu9FAd=w~AlSWok8 z>0cxp8;IzXjubSbz261ja4-QO-6AnWpes~90oQp zQN6JrCgYQm#vOuwUkzMohh1`j;*v}L<5tgdm?|@>%gX5_a{#mYixKz}>0@-{46y<< zXTdVhkhQjE2d2BNQ15Od>w#aKzApVwAUe0WG+>7lcg!A-tS}ei7^m*E&}(4PC$@7Q z5{#D@cVA%b%W{8XBLwbmpg+ps60rH)1pnq?cAZiJQOU{@YHrgJ*I~<$AwjU1FhfKYT?G-TQJ)PJd&O^?3 zwjZ2I?{JQXEL=`rf~tlQMyXCmXrhWoTv75xR987(@CU%3Y<>}KkNQW-{PkXxVcf(r zF2x^rxMN&b2Dd-1aVB=p-IR6C|ZzR7@x3eL zZ6M+^3%wZ1M~6PrC^5Ko_ELq~wAlr-c~PssXbVl#$MbFk z)E{!Enwz1XF~Yqa2@*Ff7T*hmXIS+l0)@W8{J^;cP@4j4QAb&~N z6hQ>^W;f4j`rd~}f06oiHhx5C-3~I$;1QMV{rh|z+^oOL^{U)t5`tm6m|k)(dqKHF zaQLV&#o=HBin#v2U%MSXIrKCT^vM4AdRTF6Ai%X4uLdK7xrj-X#V_OUbx;>NnPSs4 z@~}Ok2iX_BG%@aYpfZo|&A7>7tTdb|-KF!xK#_dCbMEACqGsk6P$)DLMBun9n53Qd zOT)l@dVpxlskz1a-K;d21J+u1iR1Uq?($t?*b`VQ&`~%1V2_y)G@g@w>cK{g!Y z_b7-hr4R9Q0fX?v&nyi@3=7_DqMcnvWp>5?JW>v7KjJn25*X>MwRtB}Y$`K>}@33b89R(}Zz-~ftw zT3SDx`#l4@drNr5l)%7}xy=*%dzH#4PHDcKOP+_6yy2Hn|KY^(5|}=g~klj~Pl<0!-{b5%m%#S_xHmCa(Z0a(5>lP4nc$^4Ef#g7T#))cAajnxCb zfj8O+RKzTjyNJg41l*EaqhJZq#_5>G@4-Yv4v@Gy5blc3YPO4UBwuEYuj1~TQ)crM zX)0CcmezZ-9`m{^%d=OVZ#%fP>l{1VQDI{P((#&H55LyUGUVQcOY<>{n&zm9OG-mb zx>!S1SNfdsD4n3DzA^M4j?Z;mTo(_2*T2F4~9cSrkx4|Ze#({4kr;mo7DT(J>;x*1cN zII3Yjrd#P}EqBtv(*l})Q3i+m?ms2(kxj@~-g5I)885*^du3yW)Ev=M`S@WuARe0l zSqCMZjS=u~dQL77e)m^(_e#Y7^IwL4r0-~>zN)JabU%SzGmrB5G4FLg0-$M4w>iU~ zX;TEG{F4ktH3rc)+;)_KW9b*}@8YAkKxC)+&sKHqCkO4LQc1qB^+WDnTH)hY;+Esj zNqc+I7xFTH#0+**-GIA?n!vh}g)ocreblK8v-6y3<jlIG;~&oJhl+$E}E6E<)=SG^)(2o*nN z`vZ1UAt2w6s&`^Kve%JRvZ;tg=v1P(fK7V$aF@U1Y0PU}jei6irB#KRdAGI>SJlB? ziqiQ-G?e2Tg8*4SwBBAsW(Fn+7$uMDC4FbWi(t((?9n)^PmwW0oU|}Z;-ee3GihUD zV4lOSBR9x%9~i=C7BjpuwC*-p3XLRXGKR1-o9c9Y0(v(QDs7K;8H2m;V;|JlBl=JA z#6G^9L}_CfdxEPTqyI+xr5z8m39>4wT%rdSr-?FW8SuCfYrwh*w(fe)Y)02CLPjIK z+T)|NQbSss5cxd~RnAsjY*Km-i0~;i1@!0Ld}vYH#`1Jwp)Z6qM-6XaMD-pCrFT>k zx>`q!-f{~rck><@jMDUa@=vWypVDcv7G*1a%V`Ld~w!U}2~ot6XpYbspp zp;c1fv2tKyH(@%`SjP~>kQrj4V_MK?!ZtIyK^HO8^%R^;`BV8~k>~sgGI3krLVg?> zN(XfyBoJHNW-S&4Ka~x85b3*`thL}kbP6DD0TwoI0|8&;?j&N!9Xiv>K+|+C3Msml8hx^&y6VOI_n(E8YMB9}JTn6D@3o^`^S?$ijJjA4; zad#X7oc&)pA2T}!vMi072bYu9h4hxeT~#RzIqZNjzkEuwNd3}g%q#9-23@Zwnk$eS zLY0FkeOE^Md|cTI2XjkSOeSq(9zsNC92buw<6+gXuF`I+*!rSEgy#^i=mv@%fnt!S zj{rVez5vh?9_%Wdtu5ZnV7}7Nqmno41neiPe`C1=B@NtP6y_iMQH8!|yj)o7PqhVx z8{@^&jXNS#)lG$P-A}*#;PHK(M?MAR*y%cHsooq{Zhtx0Va7Ex(+QnA8CMHrIEs#u zV@IyR59`CPY$=-{-EqK+z3 z79hecQsUBE%iQ(m)j{<;%f{FV8Z&pS*9+DT;42mf*E~wU8A&q%TvYtpQ)5v&idD%M zlsto-IKMlr=N2JR=3~cDB<)n`v2H2J$(E5A#r$p)OA{`S94+yq6jQzq@aD^6-rYqB z+?+o>qL3ZK<1_`Jc%++^CL0&bM(U)D31@dFzleG(aEy<3IfK~XX{kd`;VVXo&R`W&vr9fj%D97$|h@`Z& zVtod>vSWn;_{g9V7!}jRgm2F{FL{mgyU(*5eyjA-YO+i%8bP6Crt zkTT=4@)wDvKjjU99MBQ`no$!Ftg!G298hsK3aDwU5^L|%-Xi3StpVempEUS>aC`Lb z-C7~07<|{yZqNmJb|6@iPSl1t_VEy`6`)N}I=i89*wHZ4O)PCSH1w+iLXrhJ#4^sNH?I`z?vZm66HS3N+8ufLo`rAuhjhPxV3{ z1+G2-N(L}Eds9FF00RI5jqm?X5kAl`!&;!?-fI%9>AHuerqN1FMAQ}(>8XSp>Jph$ zKk4%xxC`6`GT^;<3-vKAtx56>d2|cy?fTvn_~m&fh%@6z9h%+sW@MMzFTQT^rB}3m zjft3bh%U>VB1o#+_(nTfjoqrAjyiuSjFs#Ak4FRB*A-idc+dhsctA9vv}cvG5AQ96 zPi;+9K@2Vgle}hH%{kpcvShFl)HNM#rh9W$2nCRXTb5$solEy!7%jw&VtR0kC!Q0y z-nS9{%j#ZjM;OVk-=OVtOb86k)w8z^tBD4*_3A)##o6{2rL244w9(PlU=9j33h;I4 zh|5|)CJL7$Mi+Z+)lOaO8;XTxe9Ky<%FDmbOD<^U@r6o-V@uO}T|HHM#?U%KXf{?< z;(0``2gMUNQx>5ibo*kt#~8)qe7Pr$3I*2?l8dj>8j8q zh!f}%*l~5N(5~%Ps?CUvi%jocb*C+C$D@_f!ZN_fbY^15A*8z5+R#mW7}?W#AQB*| zU`$7E>#-csCV|J@3=u53fw7hyfUclug+<)GiG{6$o$>T%rATq4zi#)%8ef|vYtn#f zmMTeaty*jXn+(ha>m~bYRjFS4Pn0AAYP^GOphDd=TN*cm9{ByCV5MU+JkZIQbJF6j z?|!r(ixf~kOJ#y7m$Y>t7WZ=*2Z4}<)~e*b!fUQDq#}LwCfpoUL?z?s!u$h0(Zc+B z!DwjTm@8^;KY(6sFvuwfv9qH`Ui)e ze@Q$N9guz-Sg*pzYE5HOGZCZ9z|a6R$vJp7D=?un%y+Cc=baMPNXcn6CB%{;H3oX< zBUn*%9b@gxq^ejmr3Wk(bYmwG)p7W+nQFFoupQ%*9sAG3BtaoIC10N615e~qk+lVN z(9}S#vq(I@UQf`-q*z%Tq{{pN{zt>dUeQ0W-Mj_O zvjdeKmIoV92g$y2TS<_5O1{x2wjEH;UOyXSK^)UrI0s4BxR&qhY&lZRClPj}+fI|7 z3d}SObS$sW6S~dNcT&HcJzq`)MGr~@jyT?ZCr^nmwwz}S;MlH08z_hU0g zdvx#shiCmORoQ81FQ*#PB}2d60t!dk{Kl9M6S6*BYy>p=*&b<7TpwL`+kmh3h10MZ zOvCd{(5k-3?mSeV{)h>7wJ`o5+XMtZjVEcld6aq#XfjbZKf)97rn-CE97ot_>?PzL zrkykY&7&Kl3b~?p@204;ND)HeS|9Szdm1uFS8fTjwVL~bF7S*5&RYdDuWL&076S|k zHQfjXyf)#fh(Lb(gx=ft(7(8ZTxkTVc8P(D+QJINT5)iU*@|Ls(%ZQccM3GJ)o_*e zZJuda;J_#l0xC=Dd-Zrm)xS~gdR=CWifge9M6-6>q-vFaP&FG<*FyL<_H_zsz{e3< zRb`B-ZHHC2HRPUZYdabU`S$9GQHYC7;Kg+5m39Lk;v z)M17S3d?iYRYs0mD-Zct(psx3Kg(3_6gM`uuoa;3Jm5r9(O@6@^ylR~5tp_)CjV)> zzwgCy4h1QhB}ahsO9-S?zlJZiyaBkVYebEzJrvz1Q>eT~VLm=m@fTt2+WjOX;3Z_J zE1OT+ae&c(>j-0M6DIH?yE+HeGp%v6DLh#L^$EjYy1bF1AA-~5!Pvl+zsbv8c^$)- zon0T@DJ$I6P^7ft@pH2`Z-haMkZ2}RdBKM9+Hb$H$yDiMqb23$fas3pJ@9Jx$8%XE z?kVq`G!D{u&XIwA(9z!^kBDw3Jr%BIqbJkrTz3~iSU>v}LKhh8ATMIOgOcrpSbe(% zLXTGfA?j`2)T{iU(|HX*o`|_ivyb0vr6!xoX0MuK=T`eFGm`1-`}8*|5HK6!&~c@x_#0=F=QyM287&U5N`dAq)i$u$SL z6Ct(Z6qL3b#TaxjX{tK-@1c(;9M4-}b<7>3KfLBVNCyA^$x=H3ZiR#Q|M2J3$D(@< zKfip+?Jf5g_Trq`xR?UT&}!UQg4oJ|r}V$)iNz9tj_Da=u|(#L1H35-qe`n8ViW0+ z^BW=^&Q9mq*e2w#05mT~F=@p50FAh@Y6QEiG>zBwm;(Qmqa0^oN9o2Nma69IoZ#&| zGa`KYG#*)YaIaaA3Ik76Q&H0qX<`CO(3JVylWD<_Yjv?*RA%97G_Y!RelfY>0cAPI z*ECq!oGZM&DeezUJo5JtPIMVrmb(^)3EF?wy|J58Ts3|C8zMt9QNm0o@MV0v!93YP ztYBdLLyc5|#nhi)`qfbf$gXVjm*0{-$OQVi|8RIr9>J|&gSpePiYABw*hc_X9Uexy}Dx9x473YKutoN^EJguA=>kZuAmm}nuRcw*q}Jh(av4V0_A z^?Y>zn2O~50Hj%dKYF35grMl_+Z*+s|GU*6OXJP8;6a=+*brX7jB8(HY_y-k$^OD2 zoX_{CyQO{1O^3*vhxSS_hs1`hd`Eqvyma>o{SUfy%V@msy^GE81|6YB;-X%GajSz> z+!#35BTH5>Ya~#S=NOsiJJj?Kq~y3(YR_x&r<%S)*SFcLSx?Y`B;rJ98|7bt!M7c4vDA)G9h_oq2SNnMT6)k-m!SK}c4;t}Wmm@T-@@2_!%qWi19Y zu2Tf&n)=^_d>Q#(F7{z$yEF$m9#Y&Ln*2MuYPMp*YhTKMC1>TW)g1K3AWx zdyR5E49dDotcW7Lsp7$n8{W8z(A-~M&vd860t zwEFOxu?6+)YKP|>{yI!w^p{G4)kkySm*(&zNJ;XJy0w{qj~-jFE=*>W93<9JXH114 zxXb^q5T9_(78-jKgKON2mC}bbrFGc+R2^?UbzLn_hS8X#e=3w3cM~UJ*lEqJ zX2>bm5_g0mQ{NVnRLLo_wi}1hmt_#5HbbdbLc(yv!`224(SJDd-(=6*lvP%0HL2)& zbS24hD~{eD;Q}!gLm)wt78&FNb3B zNh-l;(U{L3X(4W(C)NEFaS-bmT;@-^daNERMMfQOG!T%`%i`OFgZWPocS+m0JroXO zgc{T~ay1kka(OBq~vODs^YAr|Rb{T$bl_s-a1o%K*{6m2gO4X=HSQ_2*6>;|S9 z$)s<1q!kVIS(Ub+Q+sGbmrUoicM&-gWHB&F`3X$T#)O0(CkN#}(L`2T`l8k*ZdKR- zAcJZZ`MU=xp7cFmPa!^c2E0KSIK_l1SJ~m=3%z~D>cQD~VLm*9)u9&y4$@6O6RPxN zZM7Ntg%Q6lFaQ7p06Rw$Uxj*M-v_~>#uoX)7PBj)qv1GYgGI=64^5*r*EB)mNhHy}>wANjhqEktoSfgU$!-`2IRbn}XY>Uhu97!*LG6zl)X+{O&^dN! z3ssXO8$l_pue~}er#dGp-w7HG;ul|0-+fnroal>Kf~8WnRJl2OM8YzCKT>)XqmOM) z6?v9aQ`&G8+XrR=7JzjuOxX16!FbY>+n-#Yt(tv^vDrwTP_-mn(%ze|@{Duu5*|YDj;x#Vp!E*?CU)13!2LBAmn;!8|8iQWcI(2wgQd&cW7)2mA)iZqSQrH z?}^_}n>8JlXxL)O>Hs-p_Oy6V+IQ`t<_nzGP@Ojzs4j5(F z2D#|gS(K`;-)_4+F7;^HsVBPC{47TrbR0m8`fIg^p6KgB{HL)cGm#ojfZ_V3@2#BN z9dJt=C8P&T@Ox9B^?{Q>-3t^@eeF~OI^?cV+DzC`U3$q% z=euZwMY}3crwF{-CX>Rmq1LXUksf<~Zsb8Dj@)CI$kGG?v!$U@z!1FpDZvxT>8*d( zd{#A5O;&Q_q_Zd9I_QUnMHjHtcaop<6a|Z_VrsZ)*2ys@Cg@W~TUA4^>xZ2Zk-F;q z4r>^xlU(L*7Wi{y&Z0OIt=tn@KDQO3O{LZYN3g@cxOEpM?yyKUFjF80w{+>8m=!LW z=CRzqQ-(zVkAY<1|JvzAi!3Eb&Du5Rd|7ooHZd8!dR)PUEVgFg6d%KX>yayq|vD1^m&fpqbx3e-T0He%@0WX-b2+7#2@nb zcFwGh;Nk&!PACj-dyg%rt=qebemueacZ;=b{zsr}9|dHN@{fqgmj*nDo^P>3L~^Sm z{QX&>m#TB}-x)8}w4qnc0SBH;pDSe0LW?N||cOOL`itNqp!S?R@xOrtMaIVn;zAjmOec=W085F9eem2 z3e;;pre?aZii%TeK}}pE0NsM>ish7F3=kn@|NcqM6FSd=)zzrC?)~6mE7ak^F$T1S z;B>r~^_Gdzg008~d^JemmJuCFD&u|=@#9Ymwve44RskS^I_RI@nrBZC9c3AC{Q3c# z;2BZ2cGEEr7QL5UNTPD7$5mhx{l`sgqUwWMkf9lfQxr*pUzd8eiJ2@+F=YOyR^1b0 zLVbzJen?Tco>-d?Nhk7Y*dUWev}>Rzka}iMS4!oci>T3ZA+oTgLmU5^z0k3QtKy+J zPH1(pCcT@GD6MIdw}6BBFKTaP3%)%>_tB^zx6uxtQrJ0=2nRahEsL3y@)OWju8N$4 zU7bJFYD-xvi*ZZ@AZ*;WQS$uV1teTbZeJ&k4+8gHt6R1iWHt*61onoNS_s?cM#ab1 zGw`NpU>EZzRn(oe0z>iGd^|}uu!<-q5-h@Iy5WglJazO1W{IVc{-3^AFcsqiWy{{X zhqMLq3xD!ocrv!L;i1BmO$zyY0i%V#C6_Ob>;OY#5cK8g9QVv{-jT3Ei_%{VdHKa*MYLSUN zrqkzwV^scA9Ts&u`<_r2Xp!WT#c|$C-w@2W1X8AlCm274wR^lr`wcLuXwJNMiQgu1 zb*jnYmN(9)*zDcz+jp(6r)&O&Ho~LNWVQgBOfNE^G{5y_ASU0#UhvlbE z#Zl$MVB%fng{d5JlN3D%eLA6a+?-6y6W{gJgwlpbbx~Qq0*x6eC=?sNhdC~kNdC~} zUOu)U2mqmzR;8#Z|IH(uA*E6M1jrMcz)*yh zIx(QO{e8{QFMIYi^iM$3oV!E@I$?3|v@s}{YJx#eVXucTNEg{JiPm|W=} z*$*$P$pqCV66JrIbm7FlOCc26Jk@x;r{Ds$3~DYnXS#hgL_(xAm?u)uWOm>Tv@o=aM>(SRN?i^}T^*F{{EG3Q|6g+dKDIU}B3QE+=O+!!NeGFwP?UB5Pd zlI{q@kMzQ-iyLM=TWx>#u#zkD_0CE%j%itE&H8!fIGwyT_k<|Ub?13#C4aM6gMgV} zqgw@z(lahYsq@RM)k)Z~lrP4<4j?gHsr^`r5nFwpnu^7Ykt}2006ePjQfEjukCT9@ zD$Y@bmCwLv|I9PLep>wEMzsyCbqR5kVH)Me1JS;>I7#F8$t^l{I*!~=N*i6kb5+Y{ zYv7~!L)-0E(LLHS5Wfghoz!x=uM;6I#!1;Dp0>P*nnMK+=P113u-zL~`qP4vQ2mb* zbOL))9&DT*))fc`k_E7q-`<=QQ|U>@_xs~gX3Xra+7uCiNY6N ztrS$E$9q_@jO3xl71WAw^k39OX3#-DVhuQ!2YDh27fJI1EjnkZVQQ!|qSLqi)8Oy< z*|0aJKUgLmWXx|LhIzD-$ZT&A)9Fq&Bb5D16%{}mcZ4o%yPYF2jB%Qf0DMQ&(1TtG z?<8=#cb4~%3>(fvmF-LaR%5IFeySz(ie$?7odcksgrecC@1WuGr93Ws;A{QV`>(#x>IXrLd3_$v_1)81C=IW|-Uac%z<&IxA5 zTEe5Yb@|BojiI5U^xiwHPfJ{InbUJb&aPZS9=~K&0=uJtHi8X2Y7x2$jyiL2brk7u)Nu^XR-E=oAP_X?kwwABc{Cf zp~a5m+_eoE76oSr24DKh2zCo?sdRxv*>yce{Df+sc@H>2x!#_XSSl{MI_XRz1es26 zd^}4_%p9LhU&ZE!9I0sk2$X$GU;=E+;~JuuyM$AUOwaZy)RO7xL2URaMtX#SDljJm z9vE9q545F1q`%Zt{VAQ^*oo>xsu_HZwPt!ad_y2Pk)cUoq*pOh&}j_=F=RaTKg>}6 zihK-nn8CK`kVS5TeYwnxmzStoq&$*S46GXJmLSxBR^C!^cjKA0fX>t4NR&&s6Mz+| zh1X7wb~rz4-Y!h%z@0W)&v@FK{rIG-BC|127TPTFRPZNN`1jet-5V9K-8xQ=G_+lH zLqG^cQs~B~?E-{s86;+1=vDw*rH_TLM+K#}ap(XHpdbJMEY_6R%n@@*h)tixzF8gr zIYS$M2sZfKr4lUx1=G2hts4XfFQCjmmBEmc2Be%$BWGJj*Ja$y7@MagT+LMw5~ywz z-3U0Lyr7j#E1@g-`3|q`Z2BW_$u#2}s`{SMmT-6PAxFu28v4p|x&%$8tFTu({b0vM ze1Rq!e?E8GC0{VCbl->7v(NC@bP^lh#Q=NG(C82j1lruZ`%fnff505fuHzRpSjtZI z>I9@USOXf!uV%)^e1 z&icNX`eFVtc#?G5+5M(ePXPb65U_l)%6e1=_6j&g{9A>G(D7NE>H~b7EuZBU-~4N- z&!H)6{XfW~ltj|%sx`{sk*`y}FEs)wuqc4p((>r$?|*WwYD8bR&0EyVy3soJ(}q8! z$X@KF)2;S`{7zQ)Nv8@lzSDnO4^0E~Ku2+YvTZCDP!+rDCvr!14*qOgxaqhO5@1AdWLx*-g zL%DRCzO`&d)ZcXkNJ}DH+{$4g*y!puxl*1DGWDtuSKt$XVd3=WrO}bV7sumfJjYYU z$V}Lbb}@>%+JUaoS`frMAtovSsz=J%kwQ0T_6{onO%s7>^S^*Pd-G=!b|rTHkZ@_{%3}fjUNE1>Dqo8lRoM zAh2F^h$w#{c^tZMTCX>~AJU@4_^~tp9+YQPJE=n5q3PWeR3ZK}D`|!Ym%FQ{#C9E% zFjt~%K6Y=>NSlL4_T+kSjH>C1K1%!^mn8@25WR)k;m2=_64{AFicCho7h->!6FRqq zYwI#e+ij^6E3~xj`p1ufX(h#gZSfqjdXZ4Uh0I=-P4^KvF-bFn&~^hkUX}7g3EW2u zLc!(jWA4$@_8Am59-auN9o;R7oFNpf3X(& zzQC)xq4c3@rlW_phDjpM#_QQNxtxO#S()^QdcVVXkr=R2FrM*y=tJDE+$!*2YcsQS zbW-Om0KHwsFzXz}j`h(k=q2&p6?t)2-pqerfyN)5sbFPM;9HEx{6U*vok5UaE>TRm zJ~VYl)k%3Jb$w_UGfc!Baj{(n`V_KNBH zk?JqFI9r9W;}*~i?vd$iOcLculm6CDQIQt{5g_l9)4{&fOEB5&4PBy#>z3}6FAHPw zT%Dns1~Z{{d8Gcyhjpvc;&m}83fty|&m>0jz!6Dxp@JxO?Zc2iX;U+P{BvCAam<`l zZ%XY;zo_teV&?<0Cwpc}_R#fEu9OTkelXE=vA6%~FaG{qufUD8`X2i~mz(q>ki9t^ z3nnyx9yhNLtZ1A{<K_ox#>=5L%$0KK0VGX0kjmZx*^;^o&k*NSS;?tA+w@}^C(w%T55e4(&SK*J zUA>w5Qn#rudcRRGe{nIm8q2&)z_;a5)5klMdRYa`7*zyfLGhiaCclJR3lDnM7t7*n zbE~2?U{dxC!&#PAPI7p#^W!{xPGJ;<$om268n~8g+K*j^eJ$x?^?r}jazGH<5|5{Y z+(b`{CJE7}Rit{!CGCBPBQos3Y7t&WA8J{vp%^lB-+#b5KgpQw=^RWr3ydYNhAR+G zZ;)05*Z;`W)$g&c*&FFtd8x6(-5}oYZYQBo5f$HEFyxy}%ny~tBg_~j+9cY04c^?j zrT~%j6KB1QWHv2*XuXIPS$X7|NU?5avzPWm62wD{D* zl9&Jh0|1W@Caf&i^6^yWhx4w^N<s_-lvd%PAki+0-DNul8eD~FC&I} z+ZfYR807$)7gT;+9Pc zhUf3|GlJu&Z|F&eodT87oHY&2td>XFZr>6DryP>VFFr3`Wd~Vesgkt=d6F_LrZ~7@ zL_}tyYA9fz+JDP6FlZvbJ+)Z*pX9@nYo7t#3i}c-+|T^U?}kBS2W`TJHF5kls`;)7 z&yDSOOT9UXu&RB_Nr(8#ef%21N17A8WLF$B35Q!_QsMLOW{GuC zl^ZJbe)n?9yeY}E=89wHKBsh2(9A~Db@&M%s~{jL`QtK4uu=2pndX*U4iH{wsT0PS z!DJYPq{J-==5g&CnZO{>X6oKe>PDe*Jkc}p7l4pNfKCD6eMGJfO;akM7pCugcZyBA zC`^B_vKK>V-#niM*`=q$)3{oB6MpJ&36oVX$XU=0Uhz%8kV3H`L_pNal>P3MC~Fin=r_jBqfU@ey_# z?g-jJZF{sn1*IibE#4deIV=!Za934#MMj>LGl^kuWu{uEx~kTdS-SEVDh+|7co z1WPROk4OEMUS9(a4DW(5DU)gRP9VL5TiB>%Ed-eTvqA7`%z3qA1t)NrV~hg_WDUY< zuEHlbkbUX!t5U`mE|mB0fe0dvosuz3>D!XTF0jE_Bvm8X5l$#UyeZMp$CR1{Z%Zvv z5qcp0f1_S=8mL6X)aZj`k8#MFbJDjmpIik#s!bgpfnrEs+_LF&`5UTM4$2zc_w_Wq z23II3JD*Lj30+lD;t%u|3UF2PGmS6+00RIH(_~n9+CTsj!~H#;A#UvLY|1GBfnqJc z>MMhlgcAFVoA3;UH0QLL!3OM_ez46{YBo%+mp zbiM=jJRrsJ`|e%%u#1;xQ026mR3=)9&Vph^P7KGOJo{^J|LNNBbw~@atBX$9qeJ=q zyYe#u$)b9epq4@y-h-*0N} z^IMlIf9cZv5FsP3VY74!(wPg3$KB!0%85Tx$dDl-WN~9UxY@Ae1I4VGYdCAGyH@@; z6RGNAN&1TUE?%cwRHer&OClgsv*UTyY#JsXuxP11I1-iD^>JvX;J?tEiaw-|<_)`X zVgZ!m^AF%$hEe^YHTd^fg+bqNc+HtNQw9vfS!$7(=m1Ekw5u?j5Y`ZXm7v)ibE(k9 zJ~QX?TYK#K7P|*nwVF;f9`>Cmw~?4_8Mf;lN=}hlQzff7Xag2N{D~|dWmB-=nof#+FnbSZGOI>`zsIXIIT6@DqArKUFk(^0t zk#!Mk$^1Ets4O*c%VeJH6?19a`Lj0nJOS5EIAne#I-OO{@7{)BJd^DEv27~;1!7XopXl~UjF_73s_1PQQg8)*Es0cuIH^@7#DxjaSJ4C zmL&43(3O5oE6{14R-grYO+6>;caH9xC9UHQ@dFmq8?UY+6a%>n2x(BxH)@#i1Jz?VhebyJ=PM z;#EWthgASw7w{Z`ax=K;z$inF@_*x*==YbyXJ8Beai8G~|1iC zXBY$jFPi?3rvRuvjb|zQGvQSGa~GM-(}+}($jODGzAdmFx=SB|I8qn@ViPNr@bwg|$GMCx+AJkB= zNgEenb>#kY>-p0gT>2DAJLc-G%{_w_J<$(Lm<(y`R&qmo$MZ*f4x#v1Y)sCGgsr@| zC+?RxwC|lPCm*V)gq=#^&bGy<@ZjW($$~&?5_iJ8?9llU#>IS&*m45Qu^3A%kYXU^ zg@-7Tm16bo`a&$sH4B6Y7Ez=6sq z6o1i8S~Dbimg_-gfe7%blHJ|>=tUZS`klFq)s0OHya1W25S9};%=YR0(Q~Zi;KTQ2 zt#}0c42Wyp$fzQkzl&3J|NU*gHRU%@u6AIf`F8(0!}O;Y?Pk!R^@TC4Al#&t3cen< zJB5=4RRe@A1b`KRKK;HT;1!}uLZ}sV{FxO z&>^G)<=C_Eblhm=N^pDy3fd$MfFHMGUnC6NLn0g7ZIWyfcj#*HAzU&K-DX*{Hf`uU zUw$(HQb4W0$`)n*0cG+gT>%spHwN+;PZ4IQyA%U;Ck5ezV3?5KGYu1}5=1Hk#9F3~ zG_2ePX`4lsh8XoPSGO-`2+K630oi(}Rn68@-qb8`33>|ih6}^8n{1}A&iy5-4af!l zvt}-^{?yQiw?8dP#iYQDvLnq+yD;(}1H^(bY(ZvEBeXMy+EZ9VR5VjT$RCJZ)?EBu z8O?D$_t;|e z3e*ZgGJ{?7ih4$f8fnu|>CPLL-A?3o2xcjLGu|Wr-eZRD4$0mZ{{#k`{ya3VGs@N; z#(!hv%_0;w&3u7``SRp6nvrc3amIx_{WV5qE2!(G_(pScyb zU`(WSbnRzkRa*BK9S7N`ltM_x#JsK?ZU@0f5oMSoCY*Ph*P#mKmmUI$x2IXT-r)v+ zWj@B)57jD)xy4{!Plb0PKugEPa7xRva?J;4a2!zJw?91N-#|%#<+$fpJ`a{umf6Ff zdq!o&b)PD8!$r}8JE-MR<1grpMTUQ91lwk!f&Lv%gKOVn`t^5MlFdoqJN+AQCGWWE zES)~|L@R}%;UdFgR!G&m#T-=iP5lHO>Q&=Qykt6G`!t8o;<@mnh`Q+i!t@pIukwkq zug%$*U>X~iLTn_IbER3?ffnEf_Rs-lIn@UWo{)wPCl9D9X(!}Q?QP~vH4ml}Vo`Sey$cQ^+-cpT- zb^2=5w^P%K09}(F{N5IibZ_GNPMmzv_BP*gntUiIp5CE zvd28GlYz#uneYu+$PYG7?U~o>UF2H1ynfHwkeFPB!`f1OCZdDe7 z_xW|L^qrS4ud=|ea(rEI^07-^zoL)bZq$Y{J1<~C@6JvdA}4o{H9yY-e@s_;6zrbM zMaGVfXjV{Eulj;K67&&t$V#QUj3d&qmR!Jxj&}W#D@48z~3cC6t zkZaoU-;*$P^K7)P+zQ)jK^YrgN;>u~;=P%`_LJ@}WV4`B=UNS_<2_^LxkQCOL#<43 z??!|eSjZEJ^aW#t5u~PHVAVLF=){n2`s7R|yEPzrfzd1xFk7tCkDnPWcjhu0NhHY9 zCFBJJM;OQ{ggTwwhhW`&<|~(9^`LW40VU#YIZmE_NVfgt8VNsG#xyw7rOr!Tr2@iS z_(oa%TX$uOioo!x0Aj2p((sCvIJFs?Fv_(iBx%9ZrUf833x2uBc4mpu9=SuAohIV^ zio*&Vl$+-5D3v^nvdF#Iz9dU4-)$n0V>Glk>Y%}Jq)2_FE&J>1kxB8d-S4ptpvr5Z zDQx1tQ?jubTgW3Z77ICcGGdl4Y^{iwzQ31gq+mg{hx|o_MnM@RS_bG5aF?P>Gu<5Y zlXkPDhyuwJEor?~pgeNqzDAhS)$1S%RBMS%b!%KIF#d--=e-Gwq`^i)QAXO z=ieErv+M&{AI@X?S^WLir944=T+IILePhm~x+lt0+&;|jy%xg$j$jb$h>I;Ss;(3c zV75l!Q?otJaUNy-OV(S(RdZ?gmz#TNT0-ol08%#m-f$WwQ7?kv=4!~!o_v5X8Vg-$ zIO4e*ZZqAY0PExF+rqYBXV{0u;hK?Z<}w}NqUskh1$8sJPPSXMHQ<3flyDIvWNxJ&D0^k$`?yVl<4*T^B=NR0KGVx)~l^JsK_93GeZG<2l+%IiZ^Hf zd2_b(@@OLWUgz2$vp4cxjJrW;BOGS}TOZoct~|3e%F`n)9X)HeWZWVpkUGO)$eD*e zwaw*P91x<|;}b!*Kp&3Z&X7gb;>n%C86NFXWC$Oa6)ZLNXc04FvvOqc~${gO)^Pnq;%gkC5VpU$H%x2$u%bp4Q; zXx}DuKFb7lkm+>y9auzN$r=&mn1lD(8Q}Ay%o%L=fk)4oA=I6( zYVXpWKE0X#%flC6k54)ev!Q4Y{qQW7e5;lO8dQgK8+7>>h!4b~O|8hXI#gOo z;(^}2l#j72WPb!zl=<3xVQd-}B<|}svhINm=Nq5B`RWW2f6USNK$96wRVp@~yLeY4 zj|LQbqtOH0fgjWvd~krgjK~~T(fooK{)pr7)u_^jnBO>6wiWp#AJ9b;Zs4rg`+Axl z(sz-MJphX{*h8tSJA2g;XQZR1!;v}N5BqMc7Pgf8L^7nPw7WX!#NwP_)y?<0M&Epk zmXP)dckHO2O|y~JpInf7^1O4@+oSzfo61=NMa~vSMg&uGKN=0O>73rjOjx3a`IlPt zt4pOoWSHG}TVxxk4ifHMpq+0hieO^wI)}b`%4GgPnk(mE11DewYhXhYT41NM;#0Xg zKVDO2fd61DuVKD}w%r^ji5ODDinBA$9^Mkt(-&;`JD?do^1BN@*v9O4L~DK%Cap@< z&2-%Y0SDjl=&x4BrkT8`_gNASKZMpc{g5z7k0uXE-rkj4TQLu51e1$WjZ*{veiBhk zqtLu|KBmKH`u05%QZ}EWb;?q~6@Rugk9=Y)WnOA81#D{&DUwEr*A z|E8Wdwf3M$jj>H-^>%<{Y0FX3AY^xU^&l3X*Lh?B`4?^fN0>67VLKQL$?(hF&`m|; zcs0H)$UZ7oaMQJajrTGXOYkj`8MS`JItt*9W2~Rk(62oF=XF4Xuw0Dm={Dm(IZ2pa z4HCTL#*`k*#__AX5`^kk@rr)|&Q#-d@(L-HhI$=BWiD8XdnA+X=1G8&T1zU*xcebs zwpA51FK{fQ?~%`X4Qr3e-{B^|KARV$@Pd_-XXT9oh&3Tu!@C>}X?gum4S!pD$zkM_!R^&^+pXG3}-R(=#2S-BU^HY zt5`py${G5k-r!V7Jw{;B8xVnIVvPlvO=@`=jd9!o{}*ls!)c6iGis#C3Z#n+6nGgK zuo?)0BLagiU2jceuA*;VtJdo6rayi-x`?`qzm5zS=2vNte>r$$ zIwv|?Zj*4cV(!Q(WTj@SY9icT>ud87q#w-|v2}GUfR%bAHYUe_)QF_PLCvgJptN4; zGW;c}RSn>(p&mSPiw{;zQ)_IcRbN{DGZ=pb^m`;~Wcq+##=S08^ay~G<}t;hRMp@g zt}x3H1jP*;EaCxYXdwG{&hw#tr-okvBgV$j@w4{ou4)HUBb>m^R$#dHsPuPt_}9T9 zyoo@gt*++UDse^Y-^$^$-EMY!Uh>nxq26N4EL1jWwskV*;n3Gp4O~pWSoxw2>W0V< zbgDtHljmq^gmL`ViL2oS{*n?X?$Fr!aWg4~b5H&x=-ce&9+ zG1SS@?FG14U%yZRufVKmeuw`6id?o;x)M31with4Y9DY|6dj-_URXPm30fa5WyS_o zfh~POdsdF9e0J@%zk-n^TfIhdq!fu2nM&!rdvAJAw7LRUYw`jp``>_=0Mj$e$Zg|v z5_V7+<#sf4;8Rjwz6VJQ=#1hai39@uDV@(3*k3N~dDXLSGvW{hB(2Yn(T11JEa3@f zwzjx+RToc*`*t2XFmHgcnv8?!dbzfHn;D?RXT}gisc%fRUpCxkjJi;rVZ0!;nv{3+ z!5&UEOOX=)gmli1dT~FGiiiVF%QoYUE76J=>{M;elV)IJQ1)JHOX-Y46WXynq&Em_ z$|An4!S73jB06WRjEIF~$cr)9Bq;kkhDM(WQuKzZ3P<~S%|};BH4- z#2(nGBl*XjIFISSob?#?-%>O8fVl%@P*q9WkLi)jj6E+c{ikV;<5zqYeQuK5w8N>i zdR~S~hFdNMF2MTCZ=~h&_P>;f=IVzw2Y>esu}*R@cX^}ImqkEC8#}J*5e(#|XT%hP zQvw#w8Kv9pTk!H_$mgM+ihb&C7Bc{k+z{rYS0N#E0w9>CqxYSvhhJ}r%m9ytW_Sa( zHTuM_4^(k$qiku3qFDd|Cnh*mldM~h00^@B%U5P+9cZzZxsd;+Ch_Dj#`0wctI=p! z(aQT_+fK;3SC;@43=4H+0-Cp9G~5?Xc(=v=Z5^LsO~Q;qI=S*<1|ChB%B~=TkW7|R z(=&@atbEddF_P^upL(nR@WoDLTBtY&-wFZVtBNW8&MXS3!!Rk+4E!&8RKi^4j8bO9UW`W(Iu z?0fTnr>P_Zs6D=pvRns{7>Vj$5ouC(M#;F=k8KyLL1ZM@TCk|%aGh3=7;RndL)uLx zef^(p^v!7WDMqejM@vMgORQH8%G;|L5irV?-CSrmsm?-zy}`R1E8icOT&_gE!g{Es z&h}(a6hl=J-3=!4BGa=pVPt@_AFRXp+H7UG^u; z3F=f8n)6Blw9k$(r}+c|d3V!iiQai5!!55=MkkSs0VaDSYx&Z*7VuoIerSErb?*@SN?%Co3QYq8ilqCo;Nmp0Ug!02n%%fN`uPh=K<0C%-? z#^j6uwSZ2{+J83A`Z;o3!I>PL2bicr$*Oqi8`oJC=-ig%D_gQ8rPuSSyOscoNH)N+ z?V|#Wh1^TkZG&Nt1wKk#r2f@eKWcKQeg=~wVlfRB!$NUJYg`5kCIOSN0b~SeOX^Mu z{#y>|oWqzN2`}|`?LRRw$Z^RU0b9#wZARGy#cOiIs)GQd2x#>A+qpyk=-kJ=ykB?4 z9etr_7J)GaC%TDW;(Zrnk8)jQy^`K0U>Jl)b?>L_4XX zpcO5iTnW0b4&89bwCAEp4(EO*efEk06z` zA7%S&zV3Op>cGg=Iq?`yNxXFZhN0q41~(&=bIY~J#EdPFvf;nd3YjVPKtgx#i@OCH zOwV8N9g}?(aR(9TZpeK!LP=H%D_SuI>)ZXEOKpXNM@f*yDFzKgtc+#AwHGXhb$EK6g}8UDzyb zDf*HX`A-8I?=txhrClxR8*7C zMTy?B8lpD7>ps{?6A-c7i+h9YPYCWHiDz;QwVDape>Bpx`F&|5fB*mk0O1Q83Q=== zLGEU5Sa5AO5uQJCJibw5>!jr#v0<#~F_jq=A0MFSvv@FrU6SJV?+=p;2gE0yW+kTK z^<>otwAMj+^CxX@hC+VZf+WZ})_h(b6%mXE+yqaGa$ya;;Lwy=%6gc1n~} zhm6}o7izf;3Wf5WQnF@-4x1BGq2}0zRz{W57?z7R(;eDD(b$8IpNLHV(T>!FZcRVL zlnF7NBz(&YUIP@{b>RA4&>mfI!CNx8@l@Y(=m$1j9c`fRC9ycPj*+D#EJ#8+3lY0O+YS zWKv-J3?$&#`fe>(TT6~@2*#?jf>ar@sb6{9N?Q9%kELm&%|i4F^fW#hIt^)VZI}UJ zX%W>FpOH!Ng(FJw#f~^8Y!tJsWZy6tPT+Q+(8PKXCOLmaOyc-)wXk0sxu4Smd?a42pJ{e>kwKQjZ9#bweYRWZG6JfKA++owgPgPC{bG~opcO@R8KC)GvpYs@})2S@eB#krC((q+Wf-# z)e#O0QM)_QDoYcF^Ek&#D_%u5q^(wki2;VRnyZo#(8kbV=VpBEFT48m$S#lU>l4W@ z0;j)7k@r4^h7+Z$5|vxJhX!N_fX=`tm6>; zS9R7ohxsf|ty`UKQHgSlbz4vr(nUw_32P-Fu&F6kSSxp=Q%y88h>I<><*X1jltg*x zGaC&30jwbb$Q0`06zHt|IsY)9d*YDGtwCeOkVh(sn+g;Ci`KduV7uVT#nC6Q+bHf@ z#HF_E4uqJCXcxI|$DIG6>e5HRg5fFOom$bQPA5yiyqdKeWRL?_WR=C~P4jO5fU}CY zv8B1T9*9-XWh(>w#_J?~Zl9>VvnCF?TSw@aPjf}K|C%2H`z?PtmK$I49J#pwihxru z#S=nd*jn)1&%5V#l_J%qAM83F#LS3|E)jnNlyjRwQt=dlDE4AAwH`98KSBD$1TtRc zLG1B&Sp4#=R(z8_3cp|<`j-?Ny)s!SMLN6c_p!l~yafSzdZ&RKyYVKfzxs6Z*{Zo# zPz((tlIzl4PK9S~Sdji?+Do7DB1v~mwBW=LKh@{RpHkSkVq_Myu_wa@B1y5K@-Ek< z8AoPOTur)W1I;)?%kNtdkTmWxB)7tHR5ELcQy^0Q#Ya5aj>&H<*V&O=Gthpx1iv)6 zh{y>*o0xW^xBLG3jLTB0#e@o@qQW_R#xQ|R{i(;6I-Q#KDz!_Xu3Xt;HN7xQ+;aT? z_s<}mN^;96eWts5O%G2^SC@ra@=kZw{%B#QoaW1trH9GlKT_fDCya2KMan%gt%O z_T5DQ4ht5_%(xATE$2TiBrVzTcZ*hPQ2wPcZ})*>KwWL-W5qS<-o8M=?6w*!v!;(9 z)*VOBppT3lul{R6in^#0hNb%-3lhu%QAXxSR0$lf%=f3PJ1jvMi8Vbt>;$eanLZlh zuZH4fe#FlHWixQJr{mfP<<4&}rEbdP={+*xuSgD9ign>%+MAaXaPMurmh@37EL8*w z4Z9%6GUbRRM|EdFJ8&XTBW1dF^nC_b7I_#xG=oiY=J6ni>fZm(6-`VAF2ztoEjtYP ztTC*y_^N#3b#9Y_7u)ueE=23AVa(e0$p;R!1C60yryxIt!CyYGoxKmY%1nEjW|cYv?{3NuNFL9TJ^ zaN$nLp<^QTh?y&tCzr}he@ai&T!TL6tMY$!nt?D?20kXldhZ{jVLkV@bE12H?D6VM_F^D92-=7 z&X_lYN}-3+EIv+F*XH+pj$uEamZ?Xiq#NJ^0KX%9^hQMvfy1#zH?jyDu^Kgnj4WAA zH6wkvp#>yvR_aK?iR)lQdB;SwRT|0~YUH;Lk$S-X&cQ%Wg-YO}8mNmJRpMaW->^tk za&`b`|94Gn&vWt2yl>Nn0Y6A+&{)y%J-s(H&h8S0NhulvyFI3Sj4$4m@em9WuY)Je|g z5NqmX+Qw#{Jd&SZD0I$Q(P2;y_0VUWI?(!OrD7HlfqyE*M#?pnH_{XtA8Ni_TK<{C zaui$JCZ} zvO2KVf3?@hhOqGvBKCh;(+tUtG@~LK!OL1qfPNVEdS{6!EtG`x$jlQ+v|o{V2`ztn zRNJ!t18AGx8niyFpE3nq$_#qYiV+WR7_JRzh#bkgcycBzVZWvo>G-$iWWncp+aM}j zedO`N+Nr{|bafnB#hy?|KC7If#6WmRt;u2Cn~Bgi{syB<+*1W($rZ2FE`H6odVa^H z8+WPp?7F%YBsCR-$+jH9F&up>yOY32O8P!KeiuxE^m1?V8l1|+k=T}sx3A<^ zHxC5B1a?h7{D)-1LxDUy-N14dRVeDkblVq~7TFzRnMgVl>$6|12LD*Q7fyplJA{0IOIK&L96|uyG|PG5f55Tw24DBe=vx(IUy1S*{o`7piK1qUQU7vRh!|IKvCV?U|{C_j!3bknBgOPOLe?Re{w#3Vm(a2g&u<=WDz zt62ZRvg7p0e*$9+edi$KrN_$z*BfmLaa+6hOSTfGKZ&`ZdiJamR7}yK4y_XPLo@UAIZ9Ov8h`f5w0d5xETN#8>q zu;EmX$B)c43XfZmq_-K=5nxPAmoCC&k%T@ai71a!kJ`s)f7nY8S==<#2RPpsT}5{( zPxYOC95~k0-Z4hu&vCC13SdkXjA};KvI=J!W?*{?Z5>i% zYe7uNt(>F+*rukjjfp_xmh+CNgtBp9&_Qz#VAXN^eaxWw{l}lV-#hF?gA`S2@6U@N zqIwH~4dWNbPbJu-V3NJNW^mFGIIFE^H&qvzbPcgW)|vLS;-J(?a9V%ARgpZ&<&u`g zIxj@8bcXwjw)}cfGXS1*tCM}64bZ2GkXE;M^-(#Ru><%?4Ee9`wR;`F6C<;f!3WO( z+8cAMdrcshy|J<`v;RJYx0U8l=_F)Bm*dojR)}$qk!+ug>vXHK9w}2K=^QZ?($8-9 z(+i6pq1AQ`kOd$Gx~IRKDtL^umY3i>=nj?W5R>S_AfEEjJbb9`!)K($Ld4=1 zpkJ-BQ&}Wv0010^H7`I8Ng5JUH4(*=4zh!i9?E1Ro17KIrGH$h-jyY>N6H2xB2B^%Xr}_S(E9)MG2QD%*iN zBMbI9bECc*IBWHMTa?6g{Ek8~22pI^X06%UjyW?xH<(oB9tui6jrY+WhrB}ZL(K3R zE`&KS91M>OyT;5CHkuSZ(Ke}kfY_>FKqdqETQGHz!uM8dM`+*KBEtH zK`V&O=EL#y4WZb`s(6|eMiGf`ZysbaX0g1P+`_=29WB3;Us7OK%gWK7JdRldJ8;+P zsJ==d9~t!|<72k@hon~=HR&VBoJ?^*2k*9ie=9lr>*dhhzP8)nOtfJp*kf=v>wze7 zTUiqX-=w9OMuF&54;;alJ*93>vq1Y8-fK4JzbzaqJXJ}9G9B^4x%F*SCg{OOS{%g~ zQZ~o*3R9`7Op0aH`g}`FO^H>KlWtfcx1G1q>(92|Axz9x4sEzajbhU+HRY2*vZ8DG z9W($JbNVSr0P5LGBs%ka(i7lhtmTuv1N6y~N|nzOV2brAxp$T1@Qp^xc@z@i_z8VL z+o^aN5bC*0G03J&54Yf9#HD_2_K4_e{L{W+I6E313mnrEuMkTnV$tAC6L#rqwkUQ{ zBM0am8< zwW1O&_A7imwSfT0TH8ADF_^DqC-R;hJMXE#x~h)D^TPc9r`O?{9WU9w@Ba?&rkR@M za+6+Z&Xs)5;J{ZuQ(87X1^^}l_XKCAwFVVvlk9YS;cle8#>F(PKPo`!fW2iow}s&K zeAX!~*-BInY3Ay&8e8~(%kl}*roPVZqH=vF^$RKsg{3YeFaR4z{_CNB{&5b}&V$c* z#F{xs7I8uFe(Kf5&U{*h+O#Z=pK+uf4rFKgYKyUco*oB2#NC(xz02 zTu`lWI5fMGiHKOsw1iH)ntI*U=T<--obUA3HbR1>gEj58+MpI*2;SUZK62aWPgHon zV#F1d(=wD;!*aigKn;-_)_nvmnPLTnA0sEciZF+_xjoK$!LAFk(wHM+mi@2w%ISUstw7RE8tL_mBJ^ zaE1h0l4g+kBON~VoKNwm^ZWwtzMEeGA0~E2_Se(9LXc2a`xvgMsY{G?MRdse5Am08 zTvw`-p7mN|gEDFE%Ji^~Y2VrNg9^8bQcmcy!1ubkOrTN(pW3CYu1^}(npCh_x8gIg zEsQ=C+8~>lqN@k#Js3BQfD4KbEVzJubku>bJ&^jyCwhM%%b@~jU7Ztkh#VN0&~m4S z*J&E{`O79qOdx6C@>2tYJjn_`;(~aT)1G~b4)bHlRN9ZUs?i~b$hvwY5PrDto{wKo zzUg_j<8RpvIiIPe?l{z5*r%A| z%8wZr|2p7Su&ahrJ+Ag5xq7%d zQ|R5Wx@5+z|E8%&1_r;5(kfT8uLB01hiIeUF|@dPJ6cXjQv*b+|5fRatszI)xY6H; zZzJzmDb`2#=FRaDWG^U-#lho7pr~&sLKWrJgUG^-8q+j$5*nr?0GSE3FT=A@Bcnya{vs@Dp)6$)x>b^5R-tv75fQg8 zd;qnDx+fX^v=Uek%{y^c>*roHyiGLI3w2E8NV(yeCh+zGf_%3K-2Gn%#ivp>*iM$G z`9R%4&MZ)z?UeS>;p*b6U^3>DFG2@nH$oVpkSmHSgFaP(WwcerpE~+jBW)PmYr1fO)2xEr?yo zGFK58m6>r@H<<3755eb$OiPjmrQICq3CQiFxl@XK<)~hcGy0uAkqY)Icy&-eS_TPh zNf{(7!iN@`#{Jh4pdjPr6yuY<+03wy1`RY1ocL|W8gTIr#xI6ZNO}x|Ad@^Qg)qK zs9PPl@6V=R1{?x?1V@&ziO9SFOC`FbZezP81TOYHInKddG?KXmt?Wts*hfSwWGP zVTznh71&f}WM<=+O^;ADQ#EUp?Vi5NKy>z$SPWqK@oR#)e6YpnQr~ese?xeieRAru z;qBx|!ehZWtuZX>jI8|-Qb zh2taC{_V;msTm_B-sN$OU?t%U>AjeGTm5ht=g#tjY>T)D@@*E8jS5q=3`Gb>r*d=c z+-xngf?nm)V6k*M%SbFG5p;R;6s7z-AQ@6YUQL(Ok7N2$b}AEYq-58|w-1wB@yS0& zWk})(HF_p;p@Q=e14ZAen+sBm3rx5DiCemqzTNWpeH2pQ$Y0MVXHUXDfHN@(w}N%q zKl(GKzhsd~$>+n393fBKdxxY@+7@HaWSwCT+02&HwKt&b7rO8PF{0)CZupFdBT#o5mI2}LM^Sf~x=?thIg$z&x z49_Q|Gakmv4~bDhLxsZxVwzJ63RdL(AZ`;mJvNIkyGXgBs(vnmA*6h`NG!e4n5dAM zN{Sw5{U&=8ZZi?M2bquqq?J6E32r_j_AeM2b+3TAK3j>%skqxu>%CauC=#7=Ty_f) zV{9~;os`-4s6$(%L^vFvY6hAtY(@s&%T8`&SxVCH9JB0mGGDYpLuYo64R0Dme^sIo ziGulDlCj;+)YW`j>D+3_U=*1-2{AGxggm(&4Nb=Yz-|oLVOv6I<0j@20$J58ugP zT@gTw^4{lENxw$8RSbJ64E2|`yK2#CZZxkEpk5e!?i4DXzd=1qe}TR>yyo-5oc7%( zY$=_CH#t*nJX9SF{nwD~a879rF)!nDS27YIchug2$ZDXAwBP9BY>N6NU#EmIgab|Y z`aCy4 zpu6x%i%uM^+mxVOk7_Y2vJ)+AR4Gn0Sv|b7%>i$?h!>8g()g-^>^hp?r!V5nE6lqw zlNYAX`49eh2Elb+ui$M2(@PsJygu7beW)wf_fkCSa?PU-nzqR6u2#0@+lb=NIN zwPDF~O+0YTj>x~8Htt3)!j zD_cFK=N3sfcu#UqE!W6L5oY2284KdBIMu4W3NZKUq@6x}KVA3VJQd--FhSU5*-d^5 zi-kvQ%hOpZsa&DSoh6i=(LCkGpI2W~nj^NWso%l?mH|((41=b1XLJvhYDCX=YsT3vzZkj!wd6qFiVm);FImXsViK*+e!A|k~M^9-W=5yFk`^zHjN> zrkwx)0|D&mcCzpU=btuiqpghlkHt2=6XLXuAcxJipM$Igg8$NoYilN!dVJ<&&x}PX zAA?shkMAH^eLEwnkk=AqCzv!L-*)sg;hLvl;V zbLcy(UhwL)_8BAaDLFz%WR*3t#W60@g4Etx>R9X{W%;!gYg;Hm`|pE!G-QnV)Yxct zBldVY!V&WUtR4RrOqAZXVgf5jF&i&S;)5w^PO4IEBW+3f(B%KC_CK+`n^hBY+2j(2h1gkL!O2XjvMobHf}-9Y1^-Hy{z@?Fu;~T;dtg#nt7U7Jj5Slf385!0|tRJl( z6DuL(l}fENSI9ZlCkhL)@L~;ht*XRal=>At1yLF4gFBg`o7v5M#Cc&H8u3OmXMygtuFl zVCLc1BJa8XQf1oz8`~Z4nnFIYqp5G(DONnr;f0(+)smz!xxA$y=$;Ry+$Wz=Kuz{W zAjM|wgEJOrN(ts~Y$3aEjtonjvs@{6o1bJPutKQA%-B00jVmu~;1g#)V6uTQwU23GEU6a8o~ zICw6zz@X73XSvBPaItlODB&2^XA2!vRGEKrv;je2njei^XNe@;PxiqW-7tY{jK51@ zi~S+spupvR)QKe7J2~AAB}#_WQu~9WTmaP{yFTW(8~ZfC006u&Ccpp;7~}C8_wr;? z0tFnSCI{d~C@q((dOJd)PCRYsM?10tmEN@6`3TUSC$4i!v#v~J_2N2k_z2A1Z}OKW z?oWA3f6t{SpgqpI)$*jJ>?zF5FxVZsct!ni?H>_UnE)-$RC_F&7CjAo;U}BxZV$NX z*GhyS^MOP|V4N|aLnR)bx9YN+4Db@MSyxRae}E5KyY1$l5pEK(jr;f7B_nn|+dHAD z6MXq54kOi)qj|<3UX>VSHg0wJ7;ffx?~ddwHrWZCe{Y}-u)FuM@xx0(UVk+kI~>Tu zgSz!xp>smHslEG&v4Fl*s!MXiWkZ1ymlKd#>9dMQ_2!==Kp9yMNj^y!LYkzN9RiZr zCxfQQtMz z#=Dex946e?=s`}^lwtzf*gS(+t+gphgBE=%I;r(uzX3tIY4UFi#NYJWpE^ zC?=*)f|KIqMrZtPXMwu?rI9~YQe=y@x%hUj^YxqMjA z-G1rZw0FQh#6s8O@D!tO*nmo&1+bQrDno3@g-m{5?;vNd;3+i%WArMR<}HK4j%S+> z@V63g7!(4!^uyff1sI?j#Y0-Rv3H_8p9(mUUq61aN9Kshc`SB^L*JKEDjaA$OW8NT zZ#ufWHr!TLLUKjTxSw(;>IIG@%Uv7X=JDMeYXCi_eDN-CeU$7jcfHoE6OC!)(gw<$ z7qJ%J-1~wKjMI&*o+rP%JE19w`7W`F4aO}>C(?xHz(0x6cjgJlb+!-a2{)2qnETHR zYT>&o*CuVa=Y}>QyfRD62hhZF4Wn(>L%huse#ScPN9PRs3aHD2weD&ggM{(QrnAU4 zHkbOU;zx)SQ9x*iO-Qq!q^*eUDe|U1`_)9{!{HX%$BURz|(jYHfi6UMI zBXg+5WT|WJu^`tezob;7qzjtWu_kCxy-WnAVH;|O8H0s@f`_}iy@GPd6WFvaa;N&6 z1H1h6$*lBrbc7b$YcY5ed~8OEe_OC2vBT!C~CYW zB*#d(aaDC1u761sZNX!Q{3JNb=_BdZMv(?1Y@3F?r3F;(l95k<>_q~(iCf*}dfA6R zho|!p5u#ROuk|bc2D>FhkVkp>_3a^M8TwkF4ppBgg-&YQDAfjY`%y`K8u555TQ7o8T z?zFL7P8F;VsSGdk7Tx4Ag)VbyjkiCViA7?={%FmiCof|O!qSDJ$6JVCPD|CyNxt@# z5R`9;yCB&SMovs@UwcI+t9BhGFYLRPOwu_P7IMy&uI2)^v~O58rd|S zEV&|9-Xt=_w>pdxR2{B}wF-Qcc|7@^E!e{!;fd@(^$h@lU-EkRkeN6I1g4mUv)Lz~ z6cdJ6;^-e(7;BYR_IF*-iS1;Is6v-V-_IUZ!x`;H;cyBN_+zO?lMo^Eml*@K=y;S|2F^b^U0dE z%RJkAHyfr)ea#u$xw{nD3(Z6ByY+n5nB&7d4(|8`Xp*dJ+MCBEuDH!{jrGmoIv2tIfVP``z86A)5_X4a8r&se2tKYvo1` z7BvvXdv&DK1#Kh?Nm!Ndz+fl^Ie1jHrt4|`H%dsdap(rZP@RnvTjn@gZ{m;e@A(pE zkO2Jlh;YiY754x*EMLEJo(*^u2jdY2AYIC)yr&>XB*@{?V?||Rb_sM$d~`V*5S#TQ z`NxuOWx0eFLkC1UjIC}1K0}|OyAw_`f$^|W$s3@h=^EAu(^G4^x=bNo4?os&)xewz zk4q1C$|>%b&xZ=g-C~POTGJE%-&c5^rkvcZXl4e#jhNUu@+{>H_ z;$|YgemMWBb?3&GGK)`WMgRZ@QsWU@OkmQ(sPhfQnuKKsc2^`^RWGx~l2DUGox3ee zY01(tRf2r^GukLPC3fxY&NO-judJNI8SNmE4ajf=l)uVawRn{vLt?Y$wv?|{du2kR z#7NIiZ)6HqU?K7)C{T>8t(rZ)aM5e|`R1#+hZ~Qw$x_Yb9EB{q*|Wx&m#jqelsQM| zfY^o`b$YyhCoQj_0y|Q7=@tJQnxvUl1QARu?@X|({-QCYjlAr+C8;K(BzTqwSb@j!esFMsxMM0zJ@~VHBluii<;ZK zZV5khs)?(b3k^A(i4#6H*%$o*yhK8ya=n!)^OCHC{<@IcY35owpo;-5+hV2j{nzIqzU{w1Tteb+}`s7TNjLWQq3 zuJx^GnC98SW{6s@L)@n#E!(Vc_Y$(S*dpDLYvht;0O#@N?wBm%XCn|>=2jW6bFp0) z=)LOQ=Dl(5DE*rvFhgL^;x5oM=APWQ+H1*V-rd&3TN+2O5N)$4%E9Nk?=5Np{K--p z%luWZ$0lf>Hod5(8Rgh6@g-MT+8`HGFYTf05eGMNc{CUo)0G3GZ~~*R6WYg06kG$x z2|JQ4wQ_68!m9JWU`0z=dfmwA!63XWU5DS28Mg)Q3LYj$Pasw7R85?2ow*unI7z(9 z$m((Fv7PH!g z<$41M1IZRd#ZF{6M8Zlo99-y4!4F4X=Nom(USVd8!{+ma-DS$tzl_m>N<<{$+5e=z zEb+)iAh`O~_!?9dTpbr)336&%HByCu>;^6Cruu46jnA89df_3Mj7-EV%*aWQAX~q}<+AyD`p8 zDM5tvw$vVqs@V$L^x)9WZNefUQledVi^uGsJUDoWxzwGebRXm|*_;=`r9p*j2Hzv0AAB2!L`a4+YC<-f4dk}T0=o}fG5!V25K#sp`Mm+NC zR8^pi#1D_Z9bDU5G@gipe=j^Rf7JXeVk0vG!&B8A7rojpQx=wmQtZwhhDY_%Ht94X zk(ScE*kS}TH&wo}hZFJ5TRr_7fM}8>as2O2WiW-Y1|CXz)V;I`rkI7zKlQpmqc#7l zDhLd9XMT*ABk1JW*SzqA5_l`^nmw*KZ({NGBOwZFbdv8!$D*L+RfN#|V|wr&_MUd8 zSN1E{;_>&m@R}>yDBUZ*wnf|3Yg;{D|K(&J&e)>pba%e~r3*hW*9PntaoH1aIBiq( zp4Q{jOzlpK$BzKs^gz$xk;zDf16a6*k=B!%i`Hm~W!ua(V(snKc6&D3hEEVQ4m}I| zur12=f|Y-+2+>eG2bBXx*=JY9kv|~qm17VlNkkc8buPuC#=ve;qL$PG^H?Rst2kZh zB=_<0yT}uOr81;cin+>A{Xfk#S>vz>`kUna3ZjrA>tO%(QjXa%Y|f}4+}Oe3$QnxK z!17e)Zpo=4MzYDK{T>@u)L$0^vx;uhVF$mAM!203Q*kM0vZ#HzJqAVJoFLjT-kfgx<&mS!qUvKtr9d9vlGmv#G@3yy0_Og9jg{KV ztPyURSoS1;-hPXJGat-DTHdr=Q~w7}qHdIpDq1H@=;+Oj$Nk44P;)7obSJY*V0RoR zV+$scf-41;ucQ&qo302l0LFZpqzzhEBR+&Xw?0z{%z{t1j zXS%M2+&9m&SLs%Vab_WNKCZBX2N84 zHg9h=?mfM0St@~n%fYwfCgVSEKce(d5;RSAppK`tOzyk|@P>w5S=^;aBb(VeQQ3Z1 zdH450-+&t(kj@yNH&cY;?mjU8#3G7`c-U>o^WWmXBU?b+xHgIDipd0s6Zj$;SGvea zUBWIjtSl?tQc#wgcw>+OH>o)-&x_gmPr`F~Cv9Crt4^87ke!{6HdZLbstKhEWmvro zAEh>rcP zffeF|?fSFXW+k{E?G`fW*!5!R9HFm=32`FdJfx@+13EQcWtT=4IIngv- zwkI1XZ5oH&Ay`ibrYm(yJ`Nh`83W|yPFf$mth&9-GybD7ZJ$2*h*^D7fUvkhsQ*qP zexY)|FBvnqH}@GuZ+X(|T2|}nvZZ60^Es)M?A(kiZthUdP};tB^m_ zd@ta1TBEqR2Q(F3!6ns&L`gL;X7XDX$%V_!xlpedDmWI0@*CXprq9^@m}RcKFlhqz&wo zOuBu%cgM+QLR)--xVOK;2DboiYKBR-%2ILf>~CD=QxKpO8Wn+Kj#Rco&d)+zBz=ut zJJOsV+luw43|L!z?>a7Cu z0_VbVJ8PvpYA?OVH1+Ssyri+kdvn~eT4;QsP=Rvy&@l1TWrtHO2fA6Byk!B8@VgtO zFsP9Vp1Z_XF`;wmO6{f{%eXTrt7FIz`T6lyvn)CgD&S3i^c0iuKJ@)|_8rf_*ELV4 z@7pB0D&8b))TNFWcqkN*U7_s5tfeLP0r1KpX+tG718eyP-+%SpWHWX=pAmay4pn`m zd(yLZ@LExI|1yv7KgvxOPTXtGpg<;Xy~JsqL{ISjc5~0>7u_ZS4*Gs>L#H8p5EFvt z%^T9>TA~iociq6u^kZ2O*GTf^lR4%V#@mg;-KpG^41pShQYS(X+)$xnw*c!Hk8m*2 zWmv}@OAKot@%{9eh_)R?$ktsN`E0#X0#iL#5Cba7j1Mb;p^vDE!oj8MHpK`Zzl358 z0*%C`lURq#`gL9c(j=*VYCF7+{d0?LrSOy8yh{{dB-@stRhZm@g1!wP;=0D6_#Yj= zVd*6LNU^2@iWH4NvBHc~?7OyLj>tkTE}Bs|Q1>RY{))}Z!YVB4 z=v9@JS^j2JD>knVSBM}*w6~EB-6B6cj7{(IM}fc2E?TZEmsusKuA6y!AnT<)B-^4a z?}bpHN%Mncp~l3h^Q}xVwR+0+Bbs{H!HW%&e63=P`=D$0i=3L}gwHlv<=80(y_qO{ z^9}@9o?~B7|9ny(d0&)#oBZk*V@E_G*%i;PV|x=fk~;0kJ~PE!C{R3%^S(fZ{k?5n z3W9vUIgQvoWVvtTk{4{0Lj`N12I%brLj<0U(wh?bzsZA_oUV_}&kn<^GeeNfIoF{cH zL}EOdnUPyp;pRvY%Sd`Z7UP^Mz**d)aifCDk8h-d^&(U&g~lUAvsJ^ps*A?qphp6) z@}{F1aza5+F~9~Cc(qCf$HR8eA|@PYnsn{7e9-0hSrO-II^SDJG1*9~Kp_2q$pBs6 zNAdTOjwLuB6#KQt=%L+xw-Dz=1oab95(aM@<6}sOqdrc91;bC$_ADwkB$WJGK5a6y zZ-yrCz0QVRUBF$rz+hpo`k`4SJGZ$d%|eieG}^^%UGSoQ zl#+ygRn)Z%JiE3XYnNm9^tV0$U-UP;so_Ledj65LmMk{5UuH8%Uem0%(+v+brdTs6 zje0IBfx!MP5Zm`0TzRdfAVD~xdXgyAHLtk->9 zlFoqOu_vFA2O$V|(W< z-~{r0A*ENyR+my>_5M%jCkg90`}_yVUJq-b@*w5h}3XO!RK} z;f%E*vB?jt!>nOBeU*MlG@7lg;vsKZ^Gb(dwWU_T+#mWxwlODU1iCOL84~8in>8t*lZ~6bTMEP?Q=xX$g&~?XN>D;$8e_flUpP zL4+PR;P&8tS;0}e)o2@3a+)ytABsVWP@V!0bev;%X)8x0D@B?W7hQN`p7_wb&+)vW zK>!J5&4mwV^qk#{PcA_AzhlGW>rU!^Pw0eaZlwl*UEszDwD&3E!|3z}LFgMqK$O?$ zf=P~vQW@ySit=Kf;HO4b6`Se7^G08*?}i37rre+6H?{yC?~{j?Qs!!3C8=I75tZB@ zJ!XXjSI}91pG3R`Xa%csa1aYBxt7s(wJd`#HvjLEjgu&=*nA_29$R=7bhG*cr(SgF z4V55sb^wKZQ!U=$hU7Xi@D!E$vQSX6g3}-FxkOU=Vv<%cZvQF7Z4ThZh|hXcZII99 zWoa#2*#Ul~`Z6%=R5Uh`c>a%oL-xIsNb3gtYh&_3?|g>&7`$*(ilD;i@VA=y<3!wu zKh(Ir1jyQ@YsKl6z~;q%9&s`VRi!Kj5j}_ru#}-JcIoQ=U%Db9W+xE^u5F{$+8GOw z((B9^bSjN-4+D>Z#4e(Vba?y)0Uq7~mtRs`cZ+TFUy-{{cUb9%xfN9}#~XqJ*u1Qb zAHi~i#Mmzth+uA7v_b&RsqIKI4U=_*{&E3^7=NF{lDvGW(e)yc4JB<1O z!89BlPIa|?>9f^qfw&d6Br6uOVc!q>tw~Cl@`imNq1MnoN?hFii`9FSGF(4Bttv3X zl-K>ABS_U9@@dNxHX#{Y6To?+V(G?rcXYWXqe8?7+X)UWC5Rt^&^=+Wi4jD4h)n_u zX-~(i(Hapn>-Z+nRo5qFZoieuv(zI4-W~RofhKNRaiFuD-R+Ajc#4bQ00AaI?0<-A zQ)G4;Gtw>EHn6zlfC7NJXdt-YofAM#18R2BFhaug)+dL&KvxY$^0+o6-a~%Z|jYnA)R9W86P9MEEaP8zj->Aeqxg^bnX%$`}ztIF64E}5t+KotZ z5{NfbzBOvavkI|W7136pdis$fGIlIN33Cj9w!Nji#7D@;$f%=W;?o}-=WYq`Y{AE_ z{%1r;lBoNlL4iVj64Wol6=3z1q<}40m$G=WO~adxwK5KJ@vm19+qcP$F4vrof<_0B zFVbA|%hX4bXBCQD-S;+On>$d(tTApUnd=ONvG=C9;W< zNbP&QH9y(CYO9N?6-jnsAnfSiIjj5JLSRUTisdH1EEa}NOtj7{I?TxIfw-MxpqIuQP%ZQSP8ksv*cy)tV$Zv_=a#Q;D(W>OD4=(PJ}82N^R1C0!# zY?2fIc$gy5jqiz+yyOTMOMf=r<%xX?v`tCSIQF5G8+u)BEy|D>r*Xn1VrEQeNW_7` zNDC%RuKRzF(9DwTYKXa`%cZ53>maJF3i-pxAMy=J{NC+YH6IOG^2z7l_CB3cVr^*& zm`?q2hZv1o5uAPS5<6h8Gi^TOeCd@2&_FC&HWP{;qL2pCs6U8h0FDVob+R)k??FWC z`I0eV7$Dm5Hk=GNU9@t%J`=~A9D4VvAZF@{#DCl@hDBJraD}YEcvid40Wa?*UR!Uc zA}8s>gmQ1pA8w4In&gK+=(mUeW292inUBa+_Y4PjA%{$gViQmAe*O4r7)v1`FHQ@p zXq6_v6@u>UKUj&W=hVn^m8A`qSx4xlh8gmyza6!9AEVDEgAU=}Bjq$fUGbWnv{&$Q z`*y$is>e>BfE959kr|k#!hx&=nh-VeP09qhv1lhLRU7uDgg7L0g9ca-c{C=-&7nQg z+?fbhortfUvDfMheFr&|`@5X`y@Dfxh|S|hn>^V`ql>neCDh<}Mi}9o%sh)AbyaRM zv!B+Kj0+#~W;254YUh_JXd1Z%Ch5j2ArcfL5&bCBatUWYNf&)ymrr&YIR7}!I}?9B`n%M{i03nt0( zUq3j;Wy4|G$I%h#pdyvDKXRkOK-~rCg61nz>hm zYSh+%LSE2;^}`hogTfoMaH>)c{~&)EBfrc$hpWk2avOkK;qm*l7JNOC)_yWjlRUCX znbPySl2!?c40aUKkZ)p}jq?qp5VFl7Pb^NtfBDZzxLd%^;vaj63`g6#`ZhHR_ZJ0n z2|oVjg$jd6KQy~l>MwjkR5AM%4P9-L2xsU7>!UgV31LDp2xjXPYAk_xje|8Fs0>eK z)%`8r1#kr330zYOX5VW_++U^Z2EnXi`Cn~C9F1l@F@4q#O7xB&(9Ft28ovc0xljp- zIPIYwM8Wwd3vC!J7M2mX<|0%X+)6j0^)Nc5DPO(`5p@qH#VQD9;Jb& zeOjb<2bv5iV6Hd_F~enSTSHY*Z0Xu?OH3xW)_xy(`sDRnTXdI6YxfdelEc1{p5R%T z82PCQ-j7k@YdLdB_sQEMM_=gMMy=H&ny$O}xPdWMWVc4)q+v+Bwp~^ZP%9dGzp+^; zi)J)s!b$UYY!&`0+sCP@?OoFL%#qD&(f(O3k;Lifu>(_gs-UE*{7Je2ybIiT@#P<} z1^brtJ5Xy{FUgB;xVG3K;KpbbBR61Z_yXUAM$Yu#TWHX`4ABW%r?Ub)t6%^2E${#U z1*%3zDAFI4g%_|zgJT_xk1sV8WGaFw zt^ya&#BcnG{Y$6?DH)Lz+r4g%$W6CI_j#%($tr9zWViP;m&SCjHQ z^B(!PkGfNfl;`58^_gns66QW)0RZG7yS@Ekj*J(*KV#aq(l$E2fq_*Q5t}-tt^vx5 zY1zUM0p_>k@Os+D&34)pv*jim6S+e~flIB6`!5RT+o%stQ}00M!Plm_{{@U(V5__a z7G;z!6s;kXCAgpaboRzYP-n@ZLFqCCeE<++uKUM`Ggp4S?8Q5y!OjoArI^hpmtS$8 z;BlJl&IHm6}TvN!;=^&k3jCsrKTviDTASPD!>2KeUOvH9?@bkJ|_{Yp-RKyD3~JwhQ5F( ztxi{p@jYg7sIbLxjAMTK`AZMYs#R^Iih1&XW~IHsVNl*`X6(IIxN6ns_#+)`Y-O9| zgjqNiV&pY|S@j8weTHK~j14~yo($*U+o2H_k*&T9DmZWE9<0O!#FuL7F%1ScuhCvr?SPq>Bsje~Gc?rrD#*^kGWrnjID=(&h6qJ%o3~2f)LJ z%*t7cTp@2m+lt&E1Y~9cZ+-$hA8+Zs^xV~!bg6t3Y!?Ky5YR#0Ok=LuNH6lgEvB zFYY+UpBWV0hDM6e`~;>syQ9g`_-Z3Fqe3H*hDr#TUW_YMP~7EeL*d|1gFa{e$6sC2 z|KQ0kDoI|);nR`^V`k>BNw2r1OyFZ8uZUX_=qkgyUGR})l~h-5+=)G#9doLh0(K8# zJB6z-Y?M|KZbnd5T&KcCX|N_?DAGTTZd$j}wmFT5_m-Bwt{^hOhGz(Bu2>K?9n%Vt{B=2Y z7KLv0(gLXPcka%%#hYOhp)_+f(kLA)ewyg0qF2rVKLtePi+_b6y~aO}c^ta%w{_=o z$M_DzA?ZUkD;Z)lCXm9LotKUO>9qp=)*-Lyp&pk%ay|6&DwqZVCYahjYshprPX{Dw z^JY`UrAe5ZLxvVDwbHRJ!CG}c(c*OOnpo9*@?%CZ4oY*jA|9mcEFyMY^SoO^v|xRH zw|#|zd~>+qitM+8^qPImLyDEg;{^pv^%@Cw&2s^_dH`1=Gx@F17FD>fDG*nqURl7e zYtqA6Y8x2=(5AwQ6A|cY5FRSa*|Vk>4wAmy1z-RUPJt<(KA^bWIKiIeoF26$-C;6) zfCw;zk9H;)zouV82_=m{XQlg~_#=Y6%Eo`UtsTU_#;%dol>bUD!>Of|2&2df=seEv zmJGI#X-J9U2bz@yP*-|hqPv#D-EKH-%pGu?GRF#d_lG5>m?wWeIphp@Y@n43{NrRM>jn8frY zQ@~(3YSKe@8KAz_;f{6xc#XqS^hBOI#X>iwEif)K;f&cwAp>6SfC)(CP zpn{gWYQtk<;-X@drF{7cW{AyJFQD$C9i?8!r2?DFru>$!D}B(I?4dyz0%_fH^(7r& zp}gS)#^>8qPo`}Q-%;={OCH-L?$?O^%lJL1!GMqijPCOaQII|1)HTpHfif^Mn}sS` zH#U|(0*4yVxC0?eG|yr*nLle-`}AAaAx^&c$M-s(+2RbQao}hg@3EYhi3P zqm`_Tei&Zfs*P`vuNaGWUe`PTPGxOPN>Q%=*`r(h znZErF?56me`gnD(K(xJUBNXIm6pCpks7$_(#cV@j2RC9G=|P(utmYje>yzg`Xl zB3AcLP6X8nd##PJ+{nX%AG6y!6kNI+l~g(KWhKmDHd%QUBr>6_L;dhly!~v@crvB! zK?*j=96q3GR$qiX6`n77U5jlpp(*zu$`Ha=OD+Gr|M*6lDZceKq>uy&Nlsru$-%cz z6}Yii_Ug;y@wt4lQETZ``O!`_LiZ9sx%R!e5e=ebgB&S~Wf1A{OnwP>FsCy&LGdkL z_|gVTf6#aeZ~q*@{sC*P!R?N|l-;fE5OG?h*D_Q>=&jaqD+G-XovTeF#{KT_Jb?=M zhfkV5`GsSbb#4cQPH~f7ye2??8@TYd328J5k%Lu1L??$K!D*lQSE?EIt(0>mExm|C zG?CNYuF1Swg&b&hn&{?K90lo{A<{z2X6c~Mg2Y)mS-&9<)2#=Mn+YZ@t$phe+2hg^ zNhp3o8TRppdbEq%O>dd`&R-Qk)u?zUSRdgU0XRxf^zv@Uw#3Z@P6TiajC}-DM_2?p z)Fghr*fx+Oz>K60%gMu1^Ab-mAKY4h)zJ7%sPv>GHzEXYnC7bR1D5KU{FHcl=B^IU zA!Y3{UUE59{RXyfbM|h{vu&#Hyb|XCj%I(#oKscf+tNSZ4~x7)#W@0kHGxi>l8V%0 zo7Q|b1%6%%&_ulSn?{`qbwU>%4|Gan&wRAo51Q&7CBa~DK6voxBz<{)T71UeKino? zXF&s45*&YTjD2keuUJw(k&R`kzZw-UM~eK?wN@X5Yqm-XE0M@Zoct=$di&QK&Y>TA1wHj<%%5Z*&!lumXxX>M1Pz(&{gs z&qYrM*LvE?!mL*Guf2>ODmLV~kDKSPs!DQa37gRN^ zFEgJV=Z5n+Mg zMuu(bue+|CNVdt9^X9mGm!7EYcdDXizzv5s9#6Frr-(i80zNUQ?Go~n4NOtOuariO z918}+v%YVRiJ!1Dp2UY2yAlwSS71M53-FhJ_pK-)opxz`7N=Z2#B0zWkvBiEqB~KzXEUv*7 z`u=a(BOe990432y@!viuhzqQMjvel{IKSm9UwlhT0p&6l(o?E)?+b*kP^HiJtysPT zc^(!dHRC&{X11${GPGTDj`~w<*~N{d+LIP|y{nPXP`W8dIvi@<;-0%tso|0paAp+t z9i5OROfKd1#e(1(A=RC&A%a&K)I@JtbGe?6u&3_xg1{C(k{8{&7eQ0>m=A9DKW3h> z4oF%Ho}>LP$i17b&eHtQ>h7FoFGfdcisKEQ=F`XNG~Ua5K%~OM-6~-2YI(O{(02Wg zMmk5Sl)GLAzc`^bh?E9D5Ojrwckwr+#h&o2l0fB5jr!2h;TM)%dc;h7CA63oH1qES zQh5q#?m`et+{Z!J%H9pr8!EgBJbQjDV;5|`Ng&3-Azer71Ys7gLkxmi4r~{*tPN*W z(=N}X^Y`_-SNoR%Ay`Spgwd8`)Ncb;^T1swhKXn9ud=rhY4q9;o;tN9n^4n|9z!>O z!dq~Pq<5rI%JwHTs0fm$inYF#gm;so@5!D+{@_?ke zCc5Wkg~{hxzQyHZz(EE2RO7*o{#T+L`9f@CfoZM9y^~M_XiaU;`w~Hz9bViH&WaXT z;HuMVND3DoPlnF+^1Ejgmz0cnTm8r8G$P?&&yYP$nH3<-?>rS?S15~Fz=lMd_KjI z>kOt|LS1^s&6|9_e22uB{cx#*p-#(vShX#}Y#qmPnmCZ}%b~@f?P@ZDX_y5FG&}2! z5I`=p!crF*aF47K_bz6B5bM&K@}=2ad*@y~0KW_kfzpX%Hi{Qydc^%b(sEP76=ii< zmJCOvY=WJatl8$LUK<2Z9fe$mh)zfIT{1Q#^t5nbBaIm!JvG?+%mc-|@1J?_kl@Q7 zb!WypD4=acw+Qt&fc;!K!w|v1KQioXn(< zEcv7{#~C!vJQ4`!PTrc3n+NU=0iRj&lo%x)*wc(x>-M!$RX8np!gkygzqzMLx$?!o zE$N}|xn}q{^4-{O3;Q*>H-6KuVd|o3fFU#lqvlme$e`lFGzmBA&_Pch++g z^#XQ!d+9C`K^mS9P|g&c>fTnCVdc^CJw9Q~$$d+cjrq_hbUGs>A9cMxAMRxpLHRUZ zkIil078i7;^(<;u<^b>>A#UaL;~qLPw9Cs-wrA+w+v7kE@>2f05*ZMjFk~)Hp`BdG}m2Vg8_#cssMS^J^IO6 z22u*y=oC;$RNw!xO3Ti~nIi)+V2kcE)Y3Tk*&*Qu#P#s`i*be(R9Cxe>1r_){&_g6 z_il?FCO}j?2M}9ytxQVm8{l#+^n6fJQq!=sa4v zTe45DnR;lz0P+hWDL*=euUT}r*>^FoNx`GsAh=dXUXiW<+t$DVOVhYyExuXE}HQuvRZf+QB?vNVEL8b%tEUxj5PN;p(45{0x<+?f^d2oIS( zR8QC0a9OB4a+OTq#&D^32#Gd4>MrA;*rY)KhS!|_1wLCv)jWzX1I0;XmYM&);_0ho zXbyli(~Vt#bQG{wyJWjNZRkRX(Sn?5PiNO|0!`3<$l1{VR?eVXJ0*zHl%Yn303W;Y zsD!v;$l{P20y{jmP}y*z&>c?S{G&b)|5KPXlXDm37Rt9Tn8NU-(@An@c&!792gylq zLud6C(^9<9f=dEz^zPlYaJdCLE9id5tm#U$vfTi1zaFK#gRK4)z%u*a)l)nBXw?zC z{(uP+obk(3MF68Q2y4Y%knOieJImf*A$P2;tMw;MD;WnLc6Mr2J~)FR|5vl3Jeh;L z(Yl|YLwNH~aG@XV=b4B4bzZCasj&dsk*3H`?9QqR`(?hHCMmrZId$S~WPg;!Qn_X5 zLc7SqV4r>2IK_ktp_-t7%9E{WT!jpbL=sekAFw5`3>Ifbsb$8lai4{x{x##UTuVBr zSRx=FFgfJ6*|mXi7(G4ZIP?TVfYum#Gp~l}S}&wcwGwKruo(D>hs)Tjw^CIWmKMZA z7uNHgiIx&J`7OJmY`DY;$e%K){eMKz6=J|2V*gp9i^{RL8H$F{Mn5nYzjPF9N(SZH zI}H;q^-rt?%B#U<5~>8{MY6duisaep!|e^tQ#$V85z}!Ny&q_jft+Ef=;0~c%KCZ` z;>}?5z%oWibXU5>tkM;hKb^WMNq(Tv+i%0pVLwA>&aXF$8cOnOlMFRIQ0tJ5|%UeIs zIw0(1()`$wKhisT$BM7Z>&=aw3C@T6rXE_)xNY6KrHZ9z`5f6}%oLn1Amb*xZb=`z zl?LcF%8UkMc-lOhzkFn`}V{%467Nz&|1zi z#ObV=3{9ZMzD7$z%8xDS@d9AfM~S8kUH*X`$xb2Zz4c;3Ve4p&^=Uo@|D|J&Dlnt`G$a&hR)=$UnI#McbbgZ zP(=@AKpf6}Swo}fb!=Mga6ukHE>tC%YKKH#uM2%~A$_>^e14yE6Lv4RJ1{{s7JcvO2ePcxoH3j^i4*^$D;QV5@4)&0%MpgDt_Hhz{@SG zUp_$vQh7m;B*0@~dp8p&cp_aphxJz}mNs&D>%V;_*5{6lkqlyDCer{fv5wgiazIUu zC84Q$aldJCNRn)9kvZx%A)2yapL^D(^(wxf;qVXXhZ7}qX<%2h*7-zwhgsFWYVo8+ zc^5(kD!`pc-+4zV+SD}U5y^_Y(FvX!cofJTAZg{doJK~)e5ehL8IlpMT2KG}4g~Cv z{KIJ!VR?zQzL8pHPLCg33N?A0Myw`8PD+aTx9)B%6f00RB&V&0xYf20(C6nusHZ_9oml;j3#O z_s~}#nh+)3m@=25+z`P+V8<=*Y=|k~EPtRwz5oCN00093KR;XmYl=3&vD}HNXn1tn zp8x;@02PyO=khB*&HX*6uNA6nx!&)rBW<}mg}mK%&}CqJEB2ndLcQ|YP4W<@iCslf zVh)0QXk_!kBxt9VMsC5rUf(_-<#*-E;^Kl2zzv4_^j)`FO|(H-WsJWmD{uYrOO6$f zx(E;g9}Q%~tb8J?`0U3nWqT2ZtuOLzQEl=4njWg}D5PXq`*?-cP!4}T`gdtqhw3$A zwD^8=Z;ZTkv2%vA7uLfb*Y{+6NtbQd8o&Os*YStigB!KQ--G?0MY87weJ&)RBtFCd z0kLqCF%oeddh#j#UemTYWHl`o|9rUCujN2q$HuIz5JqV|KC5<$svKjm2_e?98K4cq zN3F%TV5>`#*7$0aev(RPKR2UZ2UqSss2=UDbX+5tCYLQ+s-kX=DK2DdWu20!*Z_1^k6cxe^1r=r|g=TKX!e>n9lf3iMsF3=rQiq}^E^KDGDFB!vwWXvuW_ z&&T8%xQqqkGFvexM`LB|;j~B0t3<;htAK8)CTfDVp6~g|R;nox^*!r)jAxODUBTR5 z{y^lmVOxO>97J8x533`ybxIrOZBBtge9QFeSs@yM5m+3$7mx$T<03Q&^j6`r1C zD$yGr+YtEmc>C>Atlbu`T1H@Jjnd(85)N+`sq{xpSOZJ!-&CtGZkO=EDUb43=z-v( zO=)nP0fGyOB~Z364kRwOrPoPw0+nyVIp?w(&XQJ5 zPoKr9`n$6#r+$+WT>EF*rBwilq4JiLTvu?8&wSYjzggzUP!^Do7SWgPx}XoCO)++1 zA;V{;0g;??Bq0x-74`jlNJujPMbc$>lb)5IM|kUQ_;o~I z3wN|lQ^-6?6<_L?TWt>{273&4d>MUXzvY)X$1QJ8)e;u`aB*wyFe=V>bvk4;R7*)qh4P$)c_lVwIju?<8#B?qU5c;EtO-r4e z&Op*slPA7LLeG<;gIRjj@RuX8W;ri2d8Vwo|5_PHM$W@d?OlPD=@z8MzKW(VM|LKluQ_S^3LrP#r zo~I(~_e|YKMM`lZ3!VVn)VDr2fzcSQLE3Ddq$(-3OC@SVkMq58;!rErt_utXUV7^# zF*@#FMUdoOsejAuTyF`*3Y5W%M`6qayw6#5cbTe}vlGG<2_LgH-RM$43>*IxvH!D` zgg6rKhU%UWEg+!R9%i8e`EC8QMl@DFpjDc8SNG0Rx$J_hdm?s;(0@T0Lz+i8Kc$MS zeltQ>f-a4A?6_oOYMyf36LHEk$~kpB^t%~Hj1r&Z%4vEr>sYOk5!0t4&R`XTkYNbk z##p1hImBRFvSfF04PDD#|J*4IJz-MnWfso*xqJT0JF03j@BEokurN_uACfc8{X=qI2Fxj_I2sKWhD z-nt0#_&5{=^-7Y}nphc1D|30`RuhsEja7peio<`2{pkqK*Mr9KSMv&=6Dpl`f z)p*b-_jjpXHY>Tapx{yyF9~w0LLXd(`677GPun$`5{tQ%&3lU+@G@>Zt5tq-DATw} z$(KTczE#wWQCTfVZ6TjZPNRt}N=sL_Hzm~17&nn^bgDLT}Fh1GQ?$_B|Gf!)zZ_`6X0i%WAUy;ji6UWj^6S@Yh}_y_i3;AX_&d z>JmBkzjt!)m>N@&@E~X}E_-@l26yVH;4MfeoKe8I>EH`Y6 zb*b$Y3^CX}Ok0|Kh}xzjKqFw@4M{n*Km)Ks8ExQY``{>U%b9|rtpBVG89~MRZU-^^ z@`?0o5XN5fjp~t+pi94egp2GJoDE6V|4%T&jm17&8Dl1oz$17k^smw{+`CSG|(yYncXe@r5bkyy6pbU&70H9Y>+Ig}m z$=Ko~^>U=ntZ%j;m1P6YX0xPpw{STCnEkhbZ~?!|qKR~DnFpNY?J&316`%~0PyI%F zPd;jlO|taycm`Ba;z^Bnpo|xu_8GE1$|J`lY+oIYht1@0WJgwyk|}$#p09@zQy25t8`&)5hkocdspuf2%oKUt@~n)L*hfcQQ^#Gvy&Eb2_kyrm zuPoN-n6m2LFXCui-hD?2;RaJrenK}epXd({FjGO9 z$QkUYG2~1ac?7ebqui3I2Ep?R7Au-}eN<`7KPHE-t~pUM@upj`FRuU&WT#tNg(^V6 zme3Bd>;bYpv^7luyv`YU(5d&xy9o)~(NEsEmBps#^$;bs3%?dBK3$`CSiOH6 z|NN-Xk7!tP)mLsdxNuA~+swbEJi95+!H0h%bFI>V#gk5(O&~V+Z~HXCtk}a+ z@!^wFMMv7PyisFpDd{a#Ld#s#^dcxSfm$L(@91smvu_%HBT>51`-;}`0#`u)N^I0N za<6%Ss^pObqq4I^7V>=j* zYTyQWlE8BGe$b@MXUA|Gd%b=X3B}#%?|R!zmT{bSWIwpAbO^{V+ob-?OnfAxHfB%nP5G1%z93k|Qxt zlGb{_2~=(=UD;q)m5PZkcngzrao9vI5-bG~?&xFN-{GPRz)EjX7>|CFpZ77!AEm)# zqHT7@4j^cAciW=$P)|Y;%$$}4HvIygUz!1o)Mzb*{`Qh0m9H#lky5@u`Dh2=Ke2|6 zNTn@o9T3a3rmn;B!}7t~%aJRL*$}e~9@Py;jc2Z~vTif_5i~10RZ{RL>dl`u3%Ds_ z@LMu@b48#xrqXFbsQPPtL}+>%<4M6F31acyp$9VG$>eVFusBOV_Aoz3?sj@E0+pt& z%HwK&&x-BW?uPYh=2xrl#VU_smeZUHI?FPjj5mdo@MWfG6?h1u9hGjn6t3WPJy`F4 z@>wJxO;PN4($Kd^50(9borsd^IPS7DW9yq}7s9%WkX_6857cd}5R>bZyh4+Z_4Xle zQ?IP9e;DR&iKG|5RgEXB@uEF87xhD``7{Q)eMpe2ikZV<&?q1rI=@||UK($B_dn;( zm-zUMvyKLC;R$RPRx;+AZBh5AlLju#jH2ZgRq^q#3}rU49n46%IyXg+GGs0_=Ez5y zt0et;kewgYGi-zXSG%&5e{r0`2z>YG8;09+Nlt4;EocI9qjy1)f)Ot2I80v;ZF4J& z>C3fur^&3|iEnp}eZ4Hul+&k@)gj#!kvm_OqZh2RA32@#OG-(L9&N;q&5>X+-b59Xv;n{TPt6b!Xq#d4p+Yc%w+Jcs zsSVIl;_0t8DQdH3+?G)l_9{9nN@#?s_M!tGGd0mNm}T$`AfKPX)omO|yxx~-YuXzZ}Foa##NkIL5vbd3A=-Z5lSkvvcBJf?aObzO{>6* z$2Q+=K3h-h2v1sSNuTL37#~udYqfN79Vpf3$?{p8-&#I0^6F&9^Ha6BD57A#9&u#e zMF7%lT!N1+Je(CV%2u(#6<9OL~;X{9OaWMriX2)_TO zNp(V|SZf27h{PzOWOE;gYA+_Wp?a zu+?)f=Ap*Gnypa($bl#2rqx}q*cwl=n=o&Oa97J~Mf~1vA)ab0h1DZ^m&hvm`6fxF z_$t}OuoP5?06jp$zx?7bL;BDF-_!=Qn2L#sC*;l!^k1KX)of9r0$#HtvkQ(muNJlt zvA*Q47S_3{(1cr|lBOFe=VVH*f#z1+fx-{IW^VW9llkouhG_g;Qp~~?pvO}KIA_)1 zk((x7sAo*UdOf%hs2mW%x@NgNDP8A;>R5Y+cfI&nH^|#==?JTY+W_<_eHL5U8$Y!6 z@qiDekii=oo33Krq9|yELV6CFDMbuS=>V|i6|j`bJZRE6pTl#Y zs`2v~{}7^WB4%Rzc4ZUKp3tZSIMKs28hh&6{PK0;bLHLUP63?D4#}0I?k3k~95;x0 zrdpmF0YBbz@-{qKaPx67jI+Wc231OloM*LGT$-Cb4j(E0(SFn7_2c~bmXI)NSXr}d zVTt<#2rR`#OIEKbPs~H zk|-Zx=ox^Lhfcj``m=^HRXI^a4Yg0yOu`fXEE0{yChEz21Ryfr;H^-(Ncfx5VKv{s zC}J_$SFLYkhIHvTAu{IpkuYzcI2y-pLH)*I5kbo?ZuEq3!lv3hk6xhnF${gkJ^CKe zb>}vxY1I1X7JW4@3H?pgOv`jp$PiYN*0OrL3(%D14Gau<5||{8My`$5cfDw~PE~WW zr;1g}l!k4XsKE9Ve_5551f+MzOc^ar+|H*p`Cs?VyB3fNU$=@V7b(ovGOkf$F`Kt% zeJT_xTyLzzt_tSD+BmAoPS6!L1oNH?3W%MYkvrwYf&#QyOr2Cg%~4N+apvWP92yih zPBz!Mw(ut7(B0)Rh8RmSX5RoTgFlO>RE3Z6SJ-nxZgv*VT3OqwU6Zj?4-Vj zo9cPo5YUvWGjvE`LuW61W=Pm`{RGo^q(ZK?cggMScnOQ${}Rq+O2dH9Re~-ayvU^l z$kB4V=ICDo)n0eO;30|XzCizW&^rtnv_w+`MNS8X`>;X6HMLbt0+msf<~8?{XVj4; zvp;Sea(}PY+)DCWcuGq|&NV1$)UqSSjd;J<#M|f&bDEngIvtPeZvjn`TFW%aq?N*d zE7Mmdmo}mx$|Ta$Hd*!b0wfO z8>M(9K03sTBmc+U32cM1+p^ajH;sgrc~OJ_00RI3wP8WfD9f9dFMvaa;(EXhmjodx zJT*u69J*n6q-vL7tFXGHxJO2;w4u(0YTmq4VQuYy@92;l(xy9Eu3ly~fBR0s^(pny zA->WphH)mvpyT}>yT<`78P`bNL|AoqdgE`de|h_h$^O_qbS2U@`vr)R-ND#Zyf=sC zZ*YfUc6F`bsJw$;aij+vXf@Jw%TnMuP+sv2?mipTUH!o_P3+?NeJMKg&?8%TNv zd)|Hq5^xrq9wO_!Jf2H?A95w=gOjZo-x47|lqEC>yM-b@rwy@R9w0f)+1dlXL!=uG z_pt(*xpA_~9(kDYuB}&~Xh}tJxQT9$0Z|O(=*Bh0OZ~+1X`y-SqLn6KKd}>P&{$S~ z$2VVmWI2%naw~S!Q}4z3D%ylH*bcdq{V)Rw-q87VB9N!^T{*wcosV^dhiSKL*yz9c zN7Qi}()89QhWKdZSI?7yh-`*#$*LR2T?1X(`vmQYM-w!0?a1Z7)<7_?y7S@0$`C%y zx>yvRxTLJxGo9r32#5zlla0bUAD)b09E+CV2jk4qf1dfH`X%dBXm^WdzYW`vy7 z#ZAE$ZOyB+xJj_7y-QHBFN5D_N0grMlrY3w&(sLLp}ntbstUZMd$)v_QZv3*?aOs~ z7h&3Ya@h6+354cLGa-|B^UEGspRh~yW09g+Ylj)Jv0Mayc^g=y) zQ43J7$O{MEfCQR>(4U%?#f!OXkt#%C$M5rirXTZ_>vY)`CcszoeKP|EM@euEKUE`+ zdSj8X3#_V+CKj)6s{+4bT*E<yZqL zw7(~4#*`|+IjA1z(R;rcg#5m~jiM&6XgH;9j&A+6z*^BYbP3oVgT&YYt~u zrn$5J6`e7c?ATatM%ghe@pjVi>GAbuy5iHuGG4ewJ8_*>cH-UkyPMOQlg1>4QyQIt zwwsJ<>jo_Fv?e)DRz6(Fb-(adwfk1V&ux~Eg2HY+>xo+G zlrz8lji??GsyR4A4;#FlPn&}&d{f{2Ryocapxa_Ek(gwDDKU4|#A>8agtxU{ga=>o zk!otR$}KK>%VS%Z)zb9z*8e|O=TLo`C<2|Rh%1nEu-fG+bp`)I`*TVXT zM0o}^H@&3sD`7%q2V?>}$1-4Z!-rE6^80VWPGawjs<^Pm|JGOvO!oCadJIQ4h4Ym# zA9^JdZ0oFohSBUU1v$-VJS0`6EI*7cwJII@nEj zk4I8shKsxbeSIWtoV6WV&@?VAeo=mprHOd_p8yizxKN4D3s`rBr>1Rz3j#;4oru{9 zSo2wN+~<1pyux#KN%LSt&5cV!mM^gOzMQm$Btp!k*+*KyQEE-;!^L4$6jZSf67y)^cf<^sTKlowL% zBYA+N^Y}Bg3io%0d}uEZ4ZFP|gYzlrWToc4!VlZKkKX-@m54EGmXBa6a1~v(%Rt%AXkz~|{CUj(zs?78Y+RF=Wa9WpmnfQ%|7hN9=k*TZWJPtpX*;M$ zJ#f&PnfzaRKP>F6F;kt4QiZ?(0K|iTnbvY}kEE+Vsj>{4&w(;$TDf}HH`~Ylu2j#v z{g4C`^bucYFD-1Sz}el>CmAAd-hwvA|Nq5da2v3jsd_)fQui`!?i%I&KC0{pHLePh zQx8p%-cFg=69m!0fM!x!&5m615m*XZzdrYO&&Ub9)$+nERih}@%O-rP;fF^sUU zmF1YX*BtS-cPZ$Vv4JV+LEz9*gAc*h-vzyXce@~G6>exqud#SWE;ky3W{((8UCpt= zaxm9q8B(tSL-OiHROc(g|o){Res!N1fz%NDQW2;w}oWUv8%!|ByU zcUMA)|Grj@j|^U|#;+`jfCuhz%O?CPjz^d&g~`zl0My!l2m!qmdxUq6;PLl-t5Tl_ zifc^4gL0#tTQRR`v70BU;*CJtorQ1rubL^Wxo8 znV-DQXNoXCmVQy3VGPTuciAc0PdR#tm?W&9vl0}tm8u|9TdWHJM4)M>-wXjd`0{ogyu)e&ERbkO;hf-e?b4quQIIW!ehZ>dATNw#tx=d|aWtZx_MH z-`O9hSrc)6l_78ms^M{W2`-F`;0MYYx-EZvX*->}CgS$5waYtR$I;|->JPIn&xQLy zZ}nb0#8dQv`Z;Iqp*-%a7OW`^zZzK~3>Duh%@-Rhq(K~amozrd;wuyi(m3IoqAopZDVG+NKJv;uR=H*oK@?C!DmxsM1b5{VS_&imcWdfkTzJI9hV&wk930V} zU9T-oF1LC+4}J>H#gSTl4JNTJ#0dJLn|Kz=?^ya7B!aZsGF>(S;#%0rTRnN*CzZN= z*V{At8msQzq!^!ApkQ6uypzkppoU#t;2!<^yfRKQbimgB^?5+W^cF=qhTL?Ksz|4Z zAXR`jMf5~0p;4qdA-EX_n*>gkVBU*gS;MPR!|%j&gD_J9MmQ$_GN+d5sYOE)u=*S~ z?TK&U1A;bDN+47Ob?KLy0~?Z`7OKEL2VU6E^O4KzY_OPfm(AzZ>cH=TrXV>U<@6ma z_M`7q8;g(T=S2Z+&Urnsim*KFt$o9Gy1}w1xIOarng09j4hj{K3s_I1P?tLXOb++Z zMxDTPC8p}bHJ`ie_H6ovr{S^I!am~}a9_lA?+-4-BCluU36hmF5AIeo6|-x%L;N_$ zRm4GK12+ZCA@^;><4$Jy*vI_q4@f+Su^Mz+ACWxZ`}sK(g-Rp=x?I8Q`mQoh8<8Nx zop{vTqmsS+Ni!dsZcKR5N=YL`>OW$J=R=s|Bh{p0%(&t<%m%>Vf^1&~x=bmS4edXY zC*2+3!ATu*>Tli#(ZcX`O$VN+fP2_0kd@39Y*H>*tP~MR$0VYAIZrv5k}*k%bCW-* zrfL{rw1dYai4PLa@`7sHua!rV_U==|Q0pNM;Jy+S3e7htak?zts(rv5ad2y>Bc*i6 zHxz}_4HJn{z9%n7EJe))Xo={!)K-EWQTyjT-0`W4@(erba5c$9|KHiRb|=x!mhux! zq&^4vs!81fF7&Q_(d*$+)g6G-s~Y?*H4-&suzvh@-mPQsgW&7PHjJ$b_?xj|C`Y+QM9y@*tzN zU1RFW2wwYzef(XbNpMEPp4a1Jps0Oo!NUX73!*Y7VV8&ReVXY_-`OQucU6PTjv=an zm7`^%#Q|wN=}pKAK^TSO71(~yr%O)3X_>`=jN2qm`u^`LIsniMcz)q zC-t0_!^p>aL~56DNFHjrD~$^7hZgGfD$KhMzCK$O&$kD@zl1)kUZ_M}(YTgj*~gfit)|JhTW5`@ZyV_~ zcJ-|Tx-o~~K?ZPKCfE!YYQ!l-@nt$r<>;tk^qKl32`Y6(Z_&5E8Sb~n#aE{m2hNYpl zPBA09b5B^)@yvrYYoCt%y;C+w6IN*e>&b@I0iP(y!f=r>K3+(khE*x$Sp-v>gAVxAGj-amvpfcV6IONzl)GFK~{Sh?INDe|HwP_D{O1zp6K4G2o zC_9jP7hSBqVn!*T__sUy*_g=7N~$v-C59O##-U{>uUV$=qX^K6QfTRA=iiyI#=ocx zf)=FByHjRV&R@M^sy*A>g_ugEr>j=akMBtuJ7z_uKRvi;yBNS7mvW~EP^}7~yvS-% zMsJ*y+@+ZrE&qwjemcUs>ux8;)5k{Qwkp+3TLjXfE%j~iVfQF2T}~quPJ*|06U;|$ z%lT>m!z*uQ4D=lBs`-Fe-Y@~a$~hSUb*3rV4Dv-GlAe$j9>RZ#Szhf*^FIL4lLZjv z3(}gO3fB7qRYx_kAkozB>4h3b%Z(Vgf=`?YN)PLPXYRRESQ=oMS~@x~Qy+CkuHGVL z-Au?$SP<~J^h(;}npX$UI(t{qk#IaOVK9{t1O?Fz)yrxk4*{^ktVdxtBNV`HnM|@4)D(cGzPqK7gV9NDf>aX>7gS<=@XBN#{rC!<&ycH9{{ok_B#dTtFylP`p#ri0q3?X~#SJpKc+b^T>b&L87H;h{e+NE_nPO_kboOl>lkz-}2)!7GN zDk>6=Z-_`77emzbxOG@mW~=`|aDn~)G3#l(1-?5R3uYy+W^v%UR_85kTc|iqY&9NFcWL4GHj&Aw9^%eA#l%8$%w0Q_= zIoo+1Bh-eq^7P>a~~gWlI%jCTIxcZ%(YhPH+hPv_(;z49$qLH&sJX+y5j zk#TDC8*s}|TejLh4DF-@zKy^CG>h_MnMk=pib=17XP{*66>`dB{xNd50M zq5zqF484ys$cx@`hv#d&>s^wyJRNpXd4KhH4iC${JChYAzkNk|EumA!Ewo>Cq1QdgyU*zE1Np%h;wEbr| zI}F{NEA;g@d@b#fgo0A@ysRj_t>%6NMRq!{Lhxf}8XZvspjF73!ZF{?$ z-%Wuf9BRk(fPt|M13#Pkef6cs^*$>LUVLp5mBMdl9`}BT`3i6SAzv^$qvA3h!&CQD z`k8bDTucDSQt%?Dn^wvn?HIJlvMw2W|3J^vWu6 ziUAv8ANtTBO`u$1rp$Ak4L=<&6)QNr-}`mZu&$S^GD0RU<2MGbCVA`10ur}JI&wz; z4I$e&o}7R#(t%QubfNh!q0)P+Zh&sh{X5Rm1P8HMf;aFDRw*Z{NOTapf_n<}Y48j! zVf4hx*fInJ&aAz!d8d~ZPTVbXhRj`KFv&e`}57@?!v=@A` z-Bl>rM4F}0E9hURL@4{|;cC`}RC3M%*W3T--he|)R7QIZ!eU=p$lgv8=Lmn}0?`K` zO78yX(qpAQ^6i*L#HjV?a=LSXzl zWsaW~$C7`x0DmI_z+zd6qy8YuF}X%}xE=UP^IfltQh8R|yv$Jq#l*5oDiP6e4%#DE z#SXF9Rp)1aqcj#`k&2B>%h0PsNb*kYpjAg8xx=tIVc8RN6Ad+xwcPhIM%?;2rTG+- zFvq*-8?ai$b6xK-eYn-u&W4ZE@xuG=?EyZ(?q$@H`?%3P`{6io#EItph#GYY&676D z6ov_jf1wQLLce(BNSTG%Erd_6c+ctsgM?QnG%x=Nx$g|L=yF&Le`VuOq^$?kTSh_tKeid1_s zkFvyd^cX%WDG^puFGwtqc!Dv~cswI3$6sbX?$zEpUNzC&JG)tyMWm@S;N-tfH{Qx; z_{N*XB-`mu=q@-mfe{KgdS#13Ruig@4Zs>W^17Qg2r~G5XxGbrJY@FcysSWy^Qsl! z&VVry;akX9><IGx=J=?(K1i6D&^LCvABxB_zw6hKD~aa9 z2A@=TXe5|Ls(rd8*%({DZ62dR%IW$y=QkgE)Z{rsq}rF68SG-)z>=XKBJY_T>#sOg z@nAN(e4j0B7kSY0XiSM>O9s?bdHL;`wm??J+4h-QYGif{*#+ia(sY2{wK#}@i0$+9 zBd(g5CS3KU4@VxHyplbLZgY)tQfa6!F8Z7ppEfrHl7av3ufi`j59WF(YE31hL{_2j zcLlCxl4ja?%|UD)5L*C0S1C9H!7&+Tc*Xt25M=_L&ev`^r}&nXl9waM@@abh%+Nxh%xy1R7<^ZuS#s<))r*T5G&GrvV2?U?? zdr$~4{462pk-P|y?yI7wV){KlIO-57MA<(#aq(|%YQ%?CM=3-UiwK?27nr1ANiDmI zJSnF7`!P`6qvyE~Z*T15yVdNJ`%fyoM^h6KH5{a?N?G{h*?-l=3%I-J zE@NUS(CPa4=2%#wxOX5_5X&xgx{vU7M0+#+2Nw70Iy986tDV5{xS91iTP3mcVKC6m;_NQO!>V(%Y2f(XK{6j20pMS%&r9E_b{ z8u_diib6EUGC05(zoRSa~BOSL<2uwr;@Z82M`NDL?e0EoiyC|J0^hmy+j->|)O_uLr>`5~B>Jwu=y~ zz$KAZP_(glhjCj~)T7*&GEOr=v39|wEV<}%4v6_KQB`E@s7Of|JrNO~s}dt_&~Tw& z(bvBEInCs$AS_N&b6Xx8k&o1&bXH!Z``^G{N%m_tK>^^(2aPR`*#5>m%@UrzSxNar z%HCORg}+yiy-1{QMz>f@{V>u%^*(B>Zyss!3sDislVIF!J@JL!`sr;0eQh$eZDhV5 zjUv|4-6799pHse#=_}E)5+v1PJt^@S0H;R&*Bam&yEfW>d{e5|1Z%ip;Zo*HoJ|(J z)hScJ@zUck!hKM@-?@QH{Qd$R|L?B)j&B66}}BJY`Vr)=5JDghip^%5b(|KiPoqRy`;01 z*KGc0idFnY*f{Q4se+95HCt@-0R*jkgPhaL{9fBsm~F!q#6Gdzv4#jz520a)vMQUe z*Uebwy9m@DIl1MG+@^w2`=qV!>KN?JHqTrl((4Q0;fQdrsS`8uo(_}W4Tkx|A@9%n z>~rlC$@v4{wlmr2AdcoOj*FXI4KfqS_N=jhrI6cR-~}<)aU-xqR)=s=Qj{L(S?40c z=mcG=cCisL)`^IeqfNf_l(}RsYe7tqJY`A72eMtQ4#4u^)b?^t#n}2#-uR{mM6B_G z3`qMg`DQe2_m+Z4S_2am4!p;HoGXMO{VCPBzL#xADTSu?yVN9Hy>+Q^t5-5Q8-lht zD9U$Iax41g^DKa95?gW8Vasg;l@D5@MBgZ6FT zNm=P~0!5}$-R*|SwHI8Kfo<^^tk*LGXiP1w&c+g6E}fqvuKmU7U}T1Bk($MaQ+w;S z(Y>NdA1ZBMDld>M)Pd=})swD1FMw-|)l-~k(}U9l8la4lHICFc>&K3gG<5o_8k;Fi zXNu^7Iczv}y8EMcf$a`b{p=Kk&jr?U2ah%-w3mqv`9Ez-XTk&UzJn;6;s@Pbi}tJL zY5GgvlT|W}e$+aMxcG`&*ZoRRCGNg^!6W8+zWR8L7*;xDYW)iAYpp}%pNTi znN)#7Mz97vCi6#f91S_zcUaE>cGC7eM;#W}3*~2cG>-%yusSruqLAcCRVLnlx}V6p(QS={2#U-D z>7zZ0>QFg6DAPiPD_|AR6XF@o^AYs6(!0pPUgUe{B)OG`ras34W`DYD|Z>P*<#ty^WpG~6S?WfP3LC{sY&NL>*r469s|Mm^Q^Aou^o7Zf2m z&;(%mHSrLye$l3(UyRr7Sh`7`_S@?Gf1E$r^kYuzWqXi^^Fri3mm^QwsBEwPF$8_Q zwxCql8lXK#{Obs%ha+E&!lGH6a6z!{$3F%WcL~p}=v5iT2Y4dR;=L4@1!P|Aytf9T zR}VFm4rb;&2%Y+1&oUVkp$xG~+7}dCOyMa{K6fawH(ej@!9QLNh$|f;1c^+=o7AZ` zY`6n0DzS49)L&Bfl5jJ5PC`J4v%lm65XR#Ebq3s6iz~K)6A}Ap>ZH6;xsi0)$JKI6 z1|hcMsslqrg!b&7WEqzt{assJ#L%N3>x0PLwMMi=-Go%eXrDd^J>tfG;pRJrEZxlE z-lqeJ{Ydj%bxi$Ujmx8P()2M=-XA-Y;J;`Vb~d+X#FPMZC5+1{=$NLR{Y!usT#y6( zG~-oE2sy;BkfGdx_YSZVRCiNAulKI|Xq?y{_IJIFeIbFXGz~MziNE7{Y|!mL4?z$m zcsPTr$i%5_*6;RX7tH4S5A4*}usHJft6TVewFV{FiCoIEZiU+i9MV}YVm$sb8f!bW zTd6TS`*IPOxmPh$DWYp3%1qa@p)Z6S2!^J_&Q9er_Ck3mkswhp4IJFUBFyV8X%XXl z@P}CiPjX4U_Hv8rz2B`Wu&6`8nas#Y2A*G(;66(ekiO3Q@FP$jnj30q=_Jvfy?E!* z7R-B|lOejbvt9Lc=Zt8-!O+Gzw8R1wRUzXm5aL#G9}F9%zHkr{>XDhvJ?=>^R zLr`O`@_ZTE*Q$s3@@4IP){)yjqc4`R(6OCk-YVQEmVS&5E3h#=fNkg_*T4{_h>cQ6 zK|V20bDDS4*9r{);xbpGjzm*M_zVd*T40$XY##a7%YRGx69MR^CVLnekh?sD*p)pqF2?~ST#2P_o z!zr3#4(p#22cy@gAnb-}Bv7${oSaH@qiG`$KH}6dipSi+GpyL52`CcEIMUw2nG0Xe ztU<13yutPyTUj8Qa&sTDt-+RDMY*X>=GR!$j_7_KyvoUW(w~O#H-b`%eyNk9yU*Lm zU_>lL9+OCe-S8WSI?jA;PKOa=VNDK$$rRX!o}tmt0#(iv;De2XsT>yGc~*j~ShyIj zW0zXiAh+5StvZr_XL<0CUj_2*Gz8uu*rK6@d%BuO3gKKq^Uiyh!Qv$ZeB=@0lvRRs z`c(V^GQ8*gPUYc)2F^q82}Th1Q(1Pljov(7K@$HC{WBhl`87&HR&a_`btT%>G&u7K z@QpoVMIGTCTzkg$KkubV6WibI%UYH#_BZVV)RjueNjW?7!Sly?oiyc1{O>Du1`Q1Ta zT9ol)r1778gR;Wo_p5wkX{n04!o*bxQ)Ei3ZZ1CS)1_33 z2L^N(i;>H(= z8C0a=^3ku-6l!Hdf*OO=%=4ARaIGwHVG4hb)f=|X@$fJwTz3oAgY zDZBBEv!3i-NQ_9|yV7yZ;6qCsbyu@#y8#gXKaQ58;WY&zh{ANSqp{Ec z-o3#$4kgByX`Kn=3t-STI|{i4;I1-B@FB&$(9o)Dpgb!T8qC9T;~=KsmHg)>PwgyZ zhM9m2{9%l69mou*{?mlt;(i}#z)Rq}GT*basd5P@nJeb{D9WFfL>y>WwWjoZYA7ROBSbHh0 zz~rg!|1Fum1?P>^PY1hZ`d1i{*Te~tpkDruJHgzK5t%n-wIG_spRZLNx5@4e91z?K zzJxoFalh0lsAV_JF}%eTKOxvh9{lUjmfSWQBi5bC+MVM30ehd6giEuOdtpl0$FoC&VvRUQ*3FOm;Ca)Ly zlZf`3DCfdZ$AJoK55_3_+tR1_(GD77FTVabD6pS zXm4*o00o208OSODm(mMZyYrI{0#ZswvvXsVVf@A6uak?Z{!6r~z+ij#`KqWRK%ZaE(f!|A<5V+Sy+tkp%9( z`H90&1w0p=D}%;`C%kE#bSJTbmHoVw>syV>iDBi#5L~&SVtLF@UgHUDn)d{e&1A<| z#(*uR?b;K23P%X546@m%syT_HaFO%$+0L^NATO{r57sJ~!h>~3e^y#F!(U##O%@|m z{m4bqYj`I+5$;#_{WkI!y0rT^?65sQdDmWA_+rZ5`PJFXucy!QGz zziuL%BuHBc(^a-vp2|19DKLt(oI3Z_4M-D&GE^L0v`M}|KgLS53#^$kCYf*eyVO(= z7aI!gKuH;*u1liQ8$F|$i+OK~m7yfiJ})NxtS3;C_*_GmuVdI)BdU?H{fP)08mdhzCzTOI=x*+?RipIfO= zSzww!K00JWnF={U2va^cuEWEIVJ*YHDq;Ws6$dI9`s&3;ofw~xgc;OPV+Xl(I}#hb zU5QO}hgKf%LkR-G_E~k$%PC8+V1cA{dlm*01SWv0*zE-8UkbYg3BX5o7i;GRTE?UE z%~+(xW(+PU`NNw4*eFmbf{>!;YLkX_YaOG9XcTM-^;z@(FADvd*n~9S<|ZI@Y=*R^ ztL}ZzhX7DN44(mp{bq3x>_Gz~S=_yKtk-0VJNE(@l4l`y8|u7DI6?VPI(c2_7`mj+Cng<{B@vWdP+Q_Qwu9RF zAWo^QYH(-4?XyP2CQ4+70h}<|aGD$gq!zLxs}Y^-`;+i&Hy{Qplv}pg`KXt zijh!XODs_JM5ZAyd{P7w(MC6DWCM!00R&vAvtOoI&DN7Wc4dYo{7?n zedb4HhMM18?@D1Um6AP*8ghPEZ22VtmicyyL&&qGqTCJDKsDNcseZWaJ=(1# z(Q41pf>7a0V9vY)$NaX;u?4Bh#*>*Wr%LHnNex}>bVf$Hi92gR4bcY4*5~xl1Q2b&SIX7!)ev4Qqw`` zAFd^{%ABG{@2j;a{OaV&(8KM$zFhD_lmD$UGBh;nx3c5~Xd=9FD2dz4!N$P9cDHOa zeFHYrOSBpjuaj)?($Pnc==Ts~@&d{k?GlGR_wH{Aobdv3Ed_6>)Ke$>R(L+4SE?U4 z6LWppGAn!HQlWC z$~v13ZzIAF{>+~`Pj{3)c2RnuFmb1hiXn{OfvF37h*{w$$Kj$KZL(zez9_|6ui)XT z|9eaQ`o;b`SzM5b6Dy!#FC5Y;&3VXAmhQoy<2=|s;(4&Pfz>sO)b%E)^cjWA7%hWR z0L`bGN@M=I>2(vCns)gzGfIEOzDP>iBJb9;jHeyISrEm=$qOcRtj6^tjV&@$ceoGz zlG=hH{M@L*og1)L0s_uf!T(kg9FwAgQ$1b@j!3O=0Lxe!4`Z2 z>wnTHL{3RTjo*OCloSF;LHpxqCBPW}+D|UMdU0Aa8Ov*}e-0Pe9G3pL_qIrv?$!_; zng#!m`dfqS+xjh~O4*%;5wlqXIeX_eHx}9fEAR)&!kR4eq{%ZCPUa{pVQ(8^uk-~% z=gYyW4~lmbNDd?%nl#8Fe>9V1W}QbwN-6_y@I}wmWPF-kozryn;SG? zca?`_Uow%i1~Ea`)9k!tPrEBovw=l|JHc#S3xwO*y|Ax25kDVeJ>0U~VTs$^SnwNF1^Pm6D;@QX2+ zgM1TFA8U3><^}7_zZ9qYZm6oM`a1JZAHaa)i`de3k~hfbxS1m#(a zH)~GVZ=i27tp1T)Jr0Ww`*?a#vPhgrdD_(cE4W9F?yp|Xy_h}#O+mK^9F*QS=~TOu zyowaG=Wqn&{>9met1FLoPg82BNn=>HUgu^3ZKQ4g)5jUDZu$?o(P9$VVwE@JlnJsL zPg)Vz@VlHS9^`QA7y7JyY?$h(sK^ubbH)cLst=?+#KM3qI0^2e&4u#Cf_w8qieLcT zW?PC2@a{KULtt`!aC+;f=C&e}v%9Ad<*MOu_^(-s=F^|v<$^rtMb4P@U=L~b(rKnh zW{N`G)r?s%s&4HL!Pm?-)?iRELLITMz0RqV7-TNHNYe9$VXh_*fvV?(*+VoOa}isU z>%IXc4Vl%d1{4-im#Y2q=0VAuM(PbC#wDjbZgoY~^mAH0xJ$QosMHNb!ejWi`F<~I z`&Qa)@gMf5JZ4z+rNixWNM9?Icn88oJ`=UImi{G%x1k{{xag8tO}_jribYeOnoMQU zwT6L5845>1@1tw)#>=r;PIa85g4aTFZuuK#%)`0-0uy1LV^C3YqB2OLE0%FwL6(@6 z9Ih!oj4M0K5WoND^sySKGUNo&K&Fi*OhdJksO4HNGoN$wO=MBbtrN%7SJL|i0yf)E zl;3tN)#H6pJ0%iA&9q^XA-nXil0pFJ(?8Na1MhPV%MiWMb{vR752ehZR4Ux46gcb) z#=91>@TQ#TOwk&M2P0!%lAmdP>T*b|?h=`EAuzCR!n&n}V~>L4VN*KT{kEXNb7bPR ztljG59X{mZ@mBh?yzbpL@!$Ff{?+81Wy1!9e|f}_a=S5@R!z6ez}UOYBY_y?X3hdA zgXeM#RIe`nKP8N7{hM@yt%VqkXP+ zBo&@X2yYKbxIK#uVIumf$(9^1`NZyxx|;ThR6P?3kuu-32Qb{F!Z9>@j@b&>;fyPR z9IatxvYpspyAh!OUQYKFfw1@;g7`pE{J{=-hQe7yns; zKPrKr*X9sg{h z_pl+IG#(H%2Asptf6+DAckmRe@3!%tv-%=M1Am$fpHA;3L>lv^s-U@m zD>4E)2;#{mZ@FqC&Q5|JDaimYk6#^VqT@u6s3o-(*ndP9sMewuSK%gm_VcV{eh!+M z#kyQ78tq|4wR{y%b#G9TUxQsaeD_C)hR~Gjm7OrX*~?zd*Q2teXYd(=^vDPGdMTP< zCDQTP2>gh$EC0-Yqis75k3891rq$_gW^e;%ik6XFdN{gsHD0cA>a8o%9Yx65=a!h^ z#0=_nboev&*lO@EjnKGYRm`fJZZkUu5a=A<-THhMiPg$9IVNG7r28o(y;mTii3eqc zFuHRdUlSuK4dHnZv-tic&bk2q@&#BiRLhF zYgyj220E>VW-KH92(V1<6CSy)txr?6GW>#f86=Z@@@E(FBC#3FmO51CujxwyDq9NU@4ZFsGoi znSDHEugeP;OcD;xbu6bwXg(NxPA4X}cA!XCp)(CQ4EoAK?*>X4(mhqdGiCp zyqc3Ia7-g1xSfb`+n3di24lJ9b0U_y2ZyY@ORym{+@V>!$(hvF#28rWtrZ)MFs;>| zizsTWoM$TO&hQVT!|&;+_M)+!w}j7tWFUXu>ur*q@>hPgmwOqjRw2ZALJ74j`g{F^ zOvQ6xb?9-ilm<3Jw`ZHMRh3||Gv_EUyZy=yZHwK*gXdlUfnYxFfI8KcHS-p|z5OKK zPooR$Q@L1@6D3RKTK`j1)zAmHbo7YMl zb`C|_?f-Ow+HRHY#6LM4@&9Sj=QaBeT=VU6vL#*pzxeOwmO__q((8+pE@XP=_6&?- zUFeievX-aA1f+BsK*Do9Ggp{t_L~q1^MGt{MlJrn(56V$*s>e)?+fy%7;7Lx>~dlV zKn?(%Pg$1v542CXH^Tekw|-bm54cH)s19rvaLr-oMA43P>dIw4(&Bx211%vw-Nq@> z{ao6n45O8?5Z3$Ir!#U{_o%+`LiH4Tyk-9kZIK8d%~N(@2PSqz&En&kFHKt0*mSseaCiPyY|GNXKIpf}F?r3~3)v^Jr_9?k`1?{13S~bCr-r<1^<2lUW}SBYdAUaMnec z104Pa!xBLF_N$AtbvF{Ga6cDD$|djJcu~32QZ~%&sRvW{kYWPbnNQ6*-1))bvGchh z@NYC21qO;@d<$w%t4tDNhH;eFracHbA)@SvaeS>*I1o+Q6%|@C(!d5B0p}HK9afgE zpm@&p-{zXu8-c9e$@=cfuX#gCNg0vD9ZyuMNe3$bWl+PWpodn zc(oXr*{}`-o3ONdOvHbr%o3(6LfHsYpIM8I-LKxdoZ_lUY zBSb&rb%$)SddZoQ#uI-%Lp3T>(0xppEPMHo#l-W>*3izDC>9KO`jWQ-Cp;I9EUG(E z;lEqqeSkR22G?JIraP?&Vt7Y%U55V3qv!VxNxB5Qoizj%-|K(2|FKN3Y&S??K!Bhs zwlfvi&g9e!OGX-P$t6V|dSc6S%NE)x9>iel%{_y>Z9p*k3vu`=PoM?-mo)a6wNFHv zI-w30)8Veb+c&xoZ~8@u%P}5|#zna&u030oT_(pURRSty`Qjww71=RXn=`s{<<#cX z_;A%s@CStA&Ow75w2LG3Fni)8pdVxNRsWfmsF|MFI(@@M#hZ}f^C+Bhvb0m{?R(3k zw!YJK!A6}iYU$KZw0+w!CFtx%c(`bKw-?8IC4~qCW|G3Fn5AD60>;dfokG5GQL-)V z^#sb*4XrKC%tZ*+yMg^b$=p+7Ps4n6+}M!PcEYx5VvDTFVz2D#LK*eDta7}wdVTwJ zaS*KHq09yiDrfv<(D1Mm1R33pr5}wl1E;ulU!UF@`=5DmS`fNsKU;-=*k#ue9(n{^ z2<{n|_ju1+{}ykbPx1YLVojW`$wMw8g`JK(Ixw?5-zAEjL9zv^jtLW z$zh$8RhN>oT-cNK@8Xxylj<1Do~@9sjwJ@fese{G-0?2r53>QPVeCEROndbbg5EyI zUg9H9@8Z;UXEMvkNKGyzKa5s&)ZoKQFx`yd(O{=Ha?L~zDZoK zL=XD*PtjVF6$oaAvLXPh;)3Ol{_tt;Rm*Ne)unGU%LC85uUt@5eYD1n9BWAZ+!nN{ z%57H5@9vtLBS7=h{8LlRJ}8M5c95(-I4D6VEV2%{TBsCob%JDP$EF7D@CL{B`wp8NP(^9$DnK9l5AD zvVvDqCQ8vv~QNFtO&)o zm@uZH_F;YU###c>xs9;^=E4Y-%arG3Wjb6D7F}@?D@&I=Huij{+sgledH9B^x)V6p zVftdh4J%^I3MARug}_dHrw2_ss+{sp%25WclizLX<#PKqH7cen-MR_h&kLmo{<%Au zyKP!5rM7R*pYQdez2u&wL5&BpCDp(13a*1IArg)JR;dG|L&T(2%n5kQDMPFfHh5Vn8?RT&*UM&X|-!96{tUnm~Oft zKw@J9ZPK)BsJoM_lxpu0{wflfPR`Ym{Kk%*q~JLL7ZT<*y;8rSrgO(X@Yg8Mn`W;@ z$j&B2K+Y|JTj_YcoK2c;l}c4{I)1=p5v}rsSvk4&1H*XoE3jc)1i)o?=gWJKy*bhmP1 zChw3m{MFHxJaU+oJish&o}m3J&A^Y9X0LMn^;r{qXcM@e6yh->f9m4rJ9xz+7KeVg z{T<#sSK=N&*Rg|VbH7&&6RW7*eLi{P@uFCE81`=mDzB^^T+vG1PQCJj#o(W}=A^UP zXqQ?~In!hri|OL8AS>XC*U?@SC)r~070TXz*kio*exx_nwm8%yO=3p=FV$ZGy+Jk!vz1>xg|4yI;jeyqLyM>fg~#IJMGm--*v$Tm5qF&Qtq;nicS zRw;t>-c*)l+EU^_(lg9H9-%P`TzL_8=B?T$ymdKF!oBJ06wn*|NI6TDP3j`g!3R>m z&B}L!*xX5Y0Izb=yYN-acWwN-m_#u)iGQI9&}JU*4ln9j=>JJ)CN)!S z+ql%vrMVvEuDD4u(TZW+1{%bblBqu!=G#xdFn8+k5>cp~t}~(3kNw{};<@9jUPo}; zXWbg#A<;Oz7Aj2E!gSPh+>Xao)&^rg97M0o$U8m(4Rt-);~8)#IT@a@7KHVZ+RLj| ziuqCG6{UE5tok(e4Noi`Uw8x3BWfY886Ww111ek_;+c1xk|q?0Soux1dgtf}LqRQl^kKDUZuF7{G1W8@Y#`|(Ay$oKs& zlm{WY)G`1i%iFrFn7Rbq7@M!j>m}rM) zTTz!(6lB6#BlV7{`5))Rpn|NLRT43?>2#SW1&4wS%N3HYT#e}>e02P)q)8uHd4COM~j-Sh74aJch@D`CJ)>H92 z{aVN;A9SHrYSLx15B&!;lh2!`Azf$rOX)v#rc>x43=J~ZA)Hlk1Z}IF zx+=1q!*lQnk`!XxVm;^9?!s7BN1c7m6M>zZg(xl&&Hir)X6;|M-3V$bmXx}Bhio6g zcs4^N$ahBaoZ)!&lUb_Ui|98X{;o@r$C9rEwO-qw=3BdEK9l?#}HFJD#HW!q; z?jlS)Y-0cW)*E&QlqK8GuZnr-AtBPTw?ayD&l5ZH8a+m_vke+f2|f3IUewdiE>O`H zuZy$>!Q(7`=AazLf1|id}|G)zAP0xte<+ua|l2z2u>> zsW-YhDU;987KO*{Ch~-WF&}<_hvBkjLGaeBck7eH4?!2D^%A0TQF1Ui&!Vzp&A$Ku zA2XB8Nw+JVf4nes857jPc+?q6^;dQ%b>$0YW=DqigMdg6!OKLY!BtO3ws+_ypc$s>sJZeq_Dr|(Ai36;sS~-ksd|Kg z@4tAzw1|=<>P|De6x^jfqk~mRJmn2`#0Li@W_}Hpc*XcaM}2~T%s4>fD9#RojDKpL zH`x9rtCUP2f#zT{fT*b{RRyJU2I1ums+N0vE0UgV>owy|t^4U{iKy}*&UU)5>p@P? zW0{|~*8=%JOYKZQ+mWwc$Nr{aP~(>j*BOk8Z_bOm>0B%qzb^3&7b|M1J_ri)2{uwpE7vyu+^;`s%dNS0*<9K}(c~EU)96Rz%NSm7q5IfdVCe2_Yr@ z#J5{uEDf?mtPeLZF2m6a9h9gkW>?HiQ|bdQ;<|;q+`#p`+DNoF>prT0_w;e_B0m~5 zR$Qcu@^M2CxG`@(6twmiWs%+W4fkws;bL||vC$pO!JO7r*RR^MYK<$zEvLUkoiI)j zGbBjUx`u{_vYNQE0C3kQ^vv>UNtOGQo>C-z!6jFg^R?C+ohK$mzAN6OgoFf1<`tct zLY-o({ewGlc>0`IcpaL3u7fR(D4F(r_G<1|_w_3n<&3S8n}0Yf1?D*n6zNh~~UH%M2?mHx5)*1c@L4;fS8 zmP3L1rn~kAz_F{&<0{vwtN&apT~?-ct-^?^p^)%RL+1w&5|1^!RA#|1M|@V7*h$=Z{Fly@htUDTbfbQNKV<@Yp^Q(c!Z|rUGOsv0Ch;qAE185E?9ose>W$DEl%J2?Ca*Mv_mJ ze`RhQx~6TsP|S?)gR3g0A2QeDUtOE8v^$l!QZZ5WE&`aM(E)cKaw{5)_LIU)yNGWe zE5N*vhjjzQjQ}whtf$9+&eDQnBkXrD$&mDipjbc{qVen=URV9-#fJ#tte{3N>ro!iA6HiqjJGT2C9j!H@Ida)g2eGXukizE*goua}5|5HBouO2}iu3B3 z)FfEpTajC>EiC#EYR{xQP4ur&?1=o2Lm6@(RS&B@`LlT-MGaCC4^HKv3W;RbTs3@j96sM4`VyCOa$6?@D4bst+eeO8{s~ zn?-VeDR)Sk``fZjmXU#Eih~E%{-dW`)B<(VYXp7I_MVJNVSHxzjB#+{ScgUSOEI+hpLt)E<0>FYTrrq{FTcqsn3? zD`hoH$QLs1*Enf1m=g7xv!QpIn9ftz14lW%=*zZji<_)B@UI!BsK&gnxPky_-mV4- z(bOVldK%DzPPoE5An039&+!HBn@uqxRCJ#LS`wV}KkO4GJCqufM^?oW)AC_Oad@oi zd#+f5?2QZp9>!YA>`Yi}$XLlcS_ABgGnXSVl(4t;(~4-jY<}D-XU0>3&^lE4#;eV+ zIPm?S?e*GIxKtLg!>s7-CIvRb4!i-VA*;*kWF*GkkP!V43!*Nf_U=^oPEX$a>q(Z# zcr;07P~R$UJKnNBh%{sJtKSQ#&%!cjYXWn9kKnGr&*w+B&g8O{rWoOL#vQO2OKotS z&6o^>Ei_T`A#s|(Ek^O*!_b)ovMLLN7#|Z*Q{~=ZKo;fRQd~ZW-$CMR7~JA_(kUi> zXRqGwx4Y9=!~5+8rUu=;GxJF!{R5xhM-N*7$a>N?ZL&s2Jp~MDrV$BvOO92z!14XK z#aQpbtI;Z%k9)xKmfY0i`x%%p5F-K96D~uEPM@WTT`RV< zEXpnMZ_D(DSOYm(ZVn3BP0q0~H?kXvuVW6`oNP-H2|W>yTgvO`IZoZ?Kz=Zy21a6| zzg8Lde#yVvx|@_K7+w6FnUzfp6AB;U4?Wlb00RQq&;NK?;|m+&XtJ2|%rd{vj}QalF&bbB#%doCYR@ z#l^l*2zG*uqVu|7CC88)Q?5qWU+We9#F@rJk#NI#f*DM+BKeY|zxur{->sE*|6d3ZO^xz8+=bLgT7N|F@sZ4T01DVI*AkO9lL1nUq zi`_S|JG;>hmRpW@7cz}lx{gL*7`}2)f!y>Nx%Ts0p!2OuQf&+u{*86#O_>sc|IJZV z0g4j0XgoK_gyqKm&pl^|;XK6U%qT&yR%JU$TA*J^utLrkV1 zoB$d5>K8*h#oZt$!xS}EoH#^i-dL{-M!HKL974H)E3ttNT5-XNyEUvuflaq&8~@-_ zc_!b_2I4;irF5qdqQ(SEals2@WS*p+A{dgTK*3~pfNd$jNooB@lQY=Edk6jgX30~1 zDkb()@YjQHo{350vIaR^VejD}aOf|>*=sxo9wb9zu63XV%Xe$JGbTNA&~l@q!5YD| zpGB2-HS7(d*ObXPjlvU;G+x7WkON`LaqhfaZ{JlbYU=RlP=n`AT-{jc%zddePO#vm zk9({XW1}x9)PR1YwtS>MQn~1wA#Gdx&|uGRi8&9IEner>Ywld7GmzTQ$*TDe{xSj^ z(KL7fbzDj&y^<&<>Y6rcWf@E+LvI^qjH(~Z>pE(A=md>W|HK{hd=V@E3YJiz$<^Ay zrzP*vD`pz&#=dn^LiM&}Vt^g2UI)Ce7A-Zi!b-h!#m_-kDvZ`}?N~ zJ`6dMl5a|5VNMOE%rFxmDyvkydx-U8Q-FkW=5hT`klaeh1kun zgSCL~2Jq+=yoy?|8m*Z49nFRa<@<0XBr-yAEph~rP(4e`51}^55yw5Wm$uombcl-4 z&~b(!HEe7%bAkZ(2IA%loF4u=W`->RuT-6P`nshAzIDj1lWf;`Vb2)?D*FM~l@SEO z-mUeh1+{)BQAA5UWElz|wRYGXBN7G=?4xeWDmJ}=!>8G>Jl^nPR8;ATNc7C8w;dzf z0)9%6UWZHeQ5l8e-1Y4wA;52fm-+w@Q2K*uiE8(oZGm!2yL6oyoS<6s(Vzk$?UK>Z zabuB#bnLmhn-o%^RdLgjKRu`wn29MNk)Mf*{pwGF0ugM{Re*iMSnRd7;@IwvtGmAc z&}>XnC`1;gKKcr61_(d0kWHv>VXHd)Wq!x+d&-;69hF9*((Lr&5ko61ifOZvGF3k4 z1YwpHY!WPrx&Jo-qVZtnC=ebd#ZEbZFj@j9*-Db6WBfddROsinD?fhE&M~UqZNQQ6 z5K*703h`2m`_Jp^0Pf^hSzq#VO*`e(b`MCGma`&FrFfvRj;i%ypmmZH9ePPgpr2)K zJ-I&Un#DjwlIAN%tY|eRf6Hasm}aayT(|+*;-(f?Xf$>>flC#My##E_7v!$$pLP85 zElwPJTDaB;nEwUT<)RNDFi{nnpGC#W0AOQH=J+q}UE?@9T96l`FqieJAe4Xr0C`bx z&QH@EGau&bucfhr*00J4B9=EhY7i@Q|`CwWXRW)IPW=bP&wjXoPeU4S_h-^RqOk}3QX z%wLdAK!Dl1xnq=6?EPXiGvsS>P~;Y|M`mc{=1bfAcVkh5VK7+dFn3zgJp)Vn~<24ap5^;!Jx=X2L+LFZO6NR_5hmCN$c-z8C6o>Mdm z_Ha3-1!)$N1slH#pt$PEw7nnYIU~C$4H%%qb`7IHw*oMK6`B49)0G&5_Vq}UZu5i= zJ32N;)vgz6f2U(|=)*ORUZtsAZQ)wKvDdrNQc3MKuR>qi`u#5w|AGbv6KGgS9hL9g z(ekI|S5*69WHMR;zKuzcoYn-{-*C$9lx)U@%L15%TU4PO)w~&= zEEgG?U|(7Z*TiGbZYYccTk@JE$>P8jv`w3aWNr>hiPrkfm4^r)$axMcaCK*DM?*Et zz*n|^0ywlttXJ?&3A=Evj9dR2+-p1N#FJ6tweNr^RtWEwI=}+HiM3&w`84F+Q(8Uf zM*9*#a>yqBZJPzw#qMPnwCLSnnw$+4$7G4m6l~K&Yu|Lvj(Z4YOoPww={=p!>(?K{ zDq{@Ui4-2WOntY|Y9RJ_ov@QZoP& zbeU4rP*anCJHRO_n4OW;eBVMFsTOoa#l`c#@BmRsl`)wA*R4>n4D1@y?Ivz@1w!#V z6R0vSz3zUPj%Lt_lFSgTb+51C1NX67QZ%y+$`)Lx^ zfutlG)=E4MibVRKxiy8Bhr@hpX{t+@Fh{ZmzCZGo{HP4Y3g2onb4fCAD3Qs;i_}MR z9jK;D-s^CF!Mv~=$#*KE6fqDu62hFtTV;*pv$T1>j;m3DLN?MgW5CF8I?NgOU&FC= zCjbcFua9cY=9;Jsjt;W}(%s{NXwwLEr!ZZ%|*hRBCMM zea3XJ=IZ!W=IU%92!ee-bi3cc`j*t?U5$&%>+6iPKSNslC`P9x6_w61CMCvtbC#-& zA2_@>j(=k#xFcrF0p{zEU*d(^h>2KBSa3e@$&=3^i#5?e94}F;rr-^Boq+IVdT&UQ z-P^Hn7&O1)L;K=vv5tM7##S4WphICA=sOa`YQteFsTqbz!8LLd?Sb&Af@pMpaPF40}Psf-$BVEl>Yoch1P&c&E6g^Sw zdxI`iPRg#@T<2dSmK2q0P4sH0II~Z{NKrn*am8aBK$%XN}r>A}u#nT5haD)9c$%Gy*2*2c}Svtxy$j!+VMCFNAgIYq{BVdo_7R5jmqH zoD<2Z$n)DU>-30z%)Ny>*ig9h-^+Lj94lb$CPMrk0Y=+J%fWNW9J6ISp#OcBA=uvT zj&2Y5%PQD1hbZX;kRfO`ZW?+d)eR-HC^N>jAARmd{h1*kbsXteM`~~Az6$YdeVU%C zeMp+@mC+n^jV$%NDjBF{gMDVAl40k1cmp=ti6%Lv;@#nTJydjG{HZSpJcLx?_wD`y zzi#A3rDv4&SpxCfWV>p`4?pX28QjoxtS;06!U~INz}zZ~Vei5)|B*;142kpOD#9}L zjlxgXoNISWr#;sx6|EwCNj6EDObM|sl5>b-yh2-^m&Uay-{nl#;VIbk$YA-muFy2d zkGN1DL$ugbr^+-%yGvYV4v>olXWpsUrEJ{7tVJ<^>)$C)5V@|mhGplRklMMr6e#9z za5L|GAv?~XS(>XC_QS-z5)#I9YDNONGePC9wEMRi7~sD|g@vJ6^d78f0ProgH= ztq;o$fU8Jif&7PYTKgbMBX{Bv&s16^g>rkkbH8kp52q#tc=8_Rm}s%Y1s0v9(%{Lf zY};$^RlGB}8}6YTPi^GpmmtZM+L_bh;R;ZsI{dmPJmTqN$ORmI@;>Is&+tdAMv5Br z#^`P^esh2T08G1)N?vjz?GASzaS)Gi{aD-F)*ng$vhVP_D4DLspJRLL=!b8CClM)i zQq95D*&>u{Ai@pn#Ld0&DR4et3W@&8TiQ|_BGFgNVK`R@E0fHkDQPZp8$QC`c8Kv! z-E6xR!~yjQQzPsCn;7{AZ~g?z`8U*2*tqNU%=w_O3DMOH$(_KzTMkSXEBmns+Ze^X zmGmEn=p(PpM7rN{g$xFB3gmF{-x`HS2O%RbXrq%qzCM!fSl^oDOgI(v&GIzjN-avK z%~wY9ypIR=WBk&>SBoi$xx+&yS`TAI_JlMf#+^q&UH%AT_Qoe2N*SQG6fPlgOF=d| z|M5`?g7)ZTdr&Xk8i*mkVJLZOPyzd4bZ_n!$Ew$(V@_P~z@z$q`=yBOUZ}NDxttt0 zc&P>Jyu)&MEveH1>ETj~&i#Z9>lL0IF6PFQ zV;oe1v4vCs5-p{T(?8&#Et9}u=Q5qu*&7-PxjhbNO-#z-c@4yUra(fTnUY*AR29V} zBir{cZi8E#Ff0eiv#opm#M;vi@TGI{5vRru3a?BT%%69TpIN9zA9}bASFD}0G)$9y zzFhEuBE%VQ1_Qf;Y?X7=2`jv)n*!@vm%;V)Y9LHa*(l5!5kON%vhBLqGPY_-rTn>7 zbh_~-?S)?pP`~U{Oe~1d`{#cGkvT%>ZXX)8h`P_Z{mg}zCi``pY9lq1`K5@@&_ajG z^>_{TuS-gydylZM?NV_9X?pj4mERzRV};eFAwHfK>m-+#H_@!o8lu)dm$Qga3`hc$ zu=|v;or?J7s$mJ4NwZ|=$0K2Qu8CRRW+AY&lXpoVS!G>A918lMB=AV}&M{~VA0mrf z%Od& zGUFiSHv|6&u%pjzeQL%s6PGmU{)zCah(2)fXd}mLN3fjk%PkXAh%p^5e|q-&tHwSt zl1<^gU17Fw3}uGR;68SuksOn+~s>z^?8|z{s#vq3{8R zpZ_5=iL!>R#QN44O}5QtusYJo#dk#1z!@`Gi$H-pvEO+n)f%grPWYex4%SEyKyC@C$92qvPC z$@;2hyc)aAh}5~`PFS+l2bUE&uD-p+*DJBNNZfhfvdw8#C2MuCXSE>4w9dyq9JEUw zj5eOR4L6b>NrKO&TbH^bzJ``Oq{hVvL|2e%nM+CxFa?j4p{{wNj-NLzdGp2D6$oZV zvqCAy(=wyZjni&a+pQb!04hM;Ug~Y3l97tooTbSqR8{|pSevn`(OUiYgPi3K(hhEF z6vOo$=0{n>;biP)_G+B9eZy^RCH)rme|6U=zDCt{%5x0T7(zbcm)^uThTO9{n>5+b z{V5nI+tTH|0HoXW3rRK?ct6;C5f2ry6k&#?LzWh{yTtnI)@=7R7fF0o26>2U3{NqP z`C5RT>(W*(?>76oZkO`{!>X1_Yb8~v-7RdP+aQH!~HJ0}fmBFYDPEwi~r^g;>W}jw?A$+Z z*zn)GZD4Oh?Fw;8UjP6D0yg2M{Wt%Q6TIB2&JQDHwyxJ^GEQnZBlsZEO6kadPeo9bW_Z0|RU z5%9ePQp7cHmTxl#MzJQ$I5(M&kVL6OcGzG0gF6u3geU`N!623rum(`IS_ZH4D%I-O zrkhr9Iib4`OpKsU$F={`pVZuZ%+?yHk>K~^(7r_(BHbR=k&(!YKx#ij!E!E13yMx5 zV@5kWV?&m_)0RAIh%D&`36|B2vn!88tjKB&-7jabZL7U4O59lJP1l@wM!>CrSCUTm z{s;SaPK4@h+Uc(tPhMS~i6^cUU)vwGakdxa1;{wo|63K5{OadC`RDP}BU>Lhcfb^K znm#^e%kQiE%WhsAjYI-;kpjTez3BC6b0^(fWc?0^WtGLxb({tnQ?n= zE+p3HL^$@Tdm9A&HcT36Ux_G!!Rp6&Bo-xHcRv5jJtf!RUM(!>@X3~qxOn2lF$Zw3 zxZd{Bs&lV}B1DNoRb_d6bjsNLLnT%7Dna~%5-Me~!eG=3;KK-R8W1buxgNab9k8 zAEfBRQiUh;)1l=SR*P6Z+A-tu9ve~DZ`|kfnlt?47VnE;3zBcJCD+UTn-MsGX)o+| z`D%(e7vGQym=%wjVBnbc|B)XA%_*7Bjz7ZC)fMPV=Ni}2su{Xc=+YV-o>iTcZRuFY zm5SQtqoqlGC40|J1b9j)T_xX{dsgu<}$(a;S&XxXyzFiijpD6>t9Q= z9dQ^B8_f%xW;#!mqSV%@N+phr9%G8SL(<9B9|z2QaysZZk!VFB+h;s6BHKM7Z4PPc zK~-+NNc?!&>pD}WkSrXH;mK(Qp1+8;{U?c)VL6XN(}r$+HGF`f%U z&Y%vaqj}ir5%i?W2J%n>rI2#Z2XF^ev=mR?MV)|gu%HWytlHWf%xa6QtuY=sF{6}c zhF4}ebg*|pRc*MfPi`=Oc6+WdU1hAk1>#Slh$DKjI_6zMihBy8^Iq<1XWR-tkz|4D zQb9bjr*b{HQN}rh!k;Cn^Vn?WT(OH4H`Ip!frU(f%o()YdLXQ?UlR=FN5uS=ohyyt ze%K|O8gE)1Y$v$tOvaKpNk-S(N5MsH<7hkVn8(KD)8sBUX`bn8@dY<7t3liV~4j?`7Ank&or6%<6zipgnDXA zB0XIm@6Q3MbJXK{g0QDH3%@xae*e+u)5T7^wlo-x8^5|4MqqQ4(&l&(hS+(*%*qE& zaw5GOHJ5WJpukxAyI&Sz2CAhZ4T&b1Z_b^$NXUn1iCB*oJ*H5^_=uB7h3P3S6o`^QoDgQa6s72}6CTD0mxvIRv{4 z@#e)UOwldIBghb)sDEfbjOXTAi@8UaI?C%la}1=)ZR{Zu>*?&yCBP_%`Pag!fc*EY zT5HnX=E=eqr+NYA%GQ^Cb8u7lM`B&VmO+LFi*hq=vyTwrB&6i-sFWp}y=Mxw$(f{YpxiBaQRMq{5n6fNCeqHQK4;K?b!5%*EyNQj3L$_)4M&= zq5?viY0QbdCP~FjhHhFR2=3GrEIPgbStpnj?gJ}^DT_lc>)e1|D5o4n;HI`QZA|T4 zhON8llB_}M)JNvL83tM!Mrr6(7$2M#{~t3o>WYFXdoq_(K!(?YFJ(!WJY|KdV+jz5 zv)t5xSV{^Xq}#O+ld`@ZL>R@J39)B&bT}UWrnKNPyZf&>diR4x#5U8I^W*P)KtJHu z-*%DQ96B7qurJA@0Kku5pMI}BdGDMnG5$)K4WjUoiJCkwoij+ZsfQv}m+LY&xMN!o zbh}Pue;+om!JAr01izppy*G3mXMh3{rOI4&AOjt92xk!Gw+XHZ3Hj3|3cU4s7liLVH?xj>*nJs)ES*G-%?d>f}bJ*_JsVi*GK2#Dpp>q6CLKLy8F~+>*KSaVY z_$#MDPJaIRV8UG2g0Hv*mJ#p5&sgz4obYnZa8q4_02ae3kcZ9|f{_si2w@VgrZo&N zq+%Y~P%on56hPUJY#wzV(~&864M$fQsN#{1t+|FV_vH|k%|usse;o+5NCKIkez>&; z^0$c7LOH-vvInRJCiPSOdo^lxlS`@kX%SR;GtF_V0u~@M(6HEOU4MZp{ePrkNjkat zF5-2zLE>>vkpNNzF+44iSqcu%N3y@igP`&&QN;je(Gm-0UY|INc9oe$gT!S2%!>Bq zE+jai@7mb1{eCVn?KSoW*OrV|^rZw#-+rEx4w5UnJRRjITP17eSIBy;;A1Me-RR@L zoV&yB;67IaD4n^>zUjbtsDZ<>Rxi(hLpB5`!YcihS5$Z4%3exho7-}E0DIJQN+EK% z>G%oG3k1#SUNglqFdbHP_>Ym05dpdVACukfdc`C%d=-N~Hjy}8(^xTfDR(ZlmR%Kz z<+-Nk{(YAlF9bcmYG^VZH}fJVu}VW_Lplc;({G>aOCuua{Hz9y0yWT~%KuZeqJy?B z0fc@2nwe!5!&~Ta8!O zj6>d3P9&=2O0QczWU1VM?A+Im&8FNP+c!X}h`#lAbW<;Nhz|BYx~p6m3CgJGA^c@+ zkSh68vAGnz41a^0D(E+94}Hc+HSe044}UHHc(bWEpcQ*7df0u8iVwZnA4c6jdh)d~ zcniWR!2_Rwl)!LJ*==%63UmUjCu9)-Ze{O#Hg)6wxPay9Hm78$7YCIC13S>&VaV3e zoFq;rO8jaTP&$>hazqoXGtKMSn);JVL*GrF07Yfc*t21psEW2#;F$g)h`C+_Y7+Y1 z7YhB7!V(U%Xg#c|+4P9sW8D2WjYdk=&MJ@IBBk!cOrSjF3!EfqkVOqoRmPIiHHt>i zTqDf*i#}yraEOU8Q1L?WJ+sU)teF#JoD=7TsS(Htc-yaFo%p z000oJcCQ6e;^LOMH7c2Hz7zuU#MsGd0y$~nHtotf&&Ly#WJK=>P(tWHj!W1(75sha zc69&%LfmYc6JryU5*CK^FN=+$L6-ikD1(%>(d)oH+69AT6_)9?t#bx~wn(Kwij~n) zSR+`^xiC?OSy28#JwJl_zLIWnsvu3U9;rlRc1;7b9HO>dz@xWTOYpWt)o(7dbjp@brpSpChBJr+Qf*d#OWi|zUr9KkH~{oE?)41cI2$j z^p+|-_x`5-e*?R#rzwcZZ%MR&W*FkHX6+MW%;U#1tbtU_#(An4yP>Wv9W%tumI<@%|WXl@>n-Vw>8V7p>;Huo%N%{T-@WA z!4-{x=**mqI!SIcjPG0jPxE|RAOWJX|J1$bB^N%I%=h#eqa_2~MCpabeaE_V9c*CT zRtdnY6cILnA_RR!%9)f$fE2WTH}wFO=o9$sADjRHI3_~DAgBPv00EGE9Ft^g4+atZ z16g9VvMNoHuoDBag9c+?H6MnWCI=^G}G~aJnRX*DOz-!}#ZwY!9e~95| zP|Mo7HI>)aE2!$@nnJ#Bx3($KFF-?~ePmI8rSE()mKM2o$P!BSWSt~cCETa%`Txx= zz~i^z5TrL-+ad#9DS6cAV_EhvBtN23LNN~L&PE@%BAvOApcbQC^zA#~p8YG!hTMfZ zE3nap%^I2>CP~n=J9ASc#MdzTN`T^9z}9~{0;$Ir`BnQUM;qIyn_a{M6M&6H7owe` z7dVdPE*0z5|LC@`L zFgraeZ*e%QIyX&pzA+%gA2TRBY#pmulg+G|C%Rzh$t1s&cEwn$-E;6LCY$PKB){2T zs~KSxFk2-ev{NaAQ3mMr<)`y>saR%4o?!w#ZvNtR7uP&zsXVxPO@iZ<^ z8j&Pn?oTP(O!P|P`vMQ3cT%JhagFCSno;rCjFcgnWSeT+J3=w^H&F+V(snyoeK14- z2spF+7Ht%scBzD&eUvm@{j2*Bzl~g{6^n&Ci-1>Il#K%oC=tf3P zRE&7tG{Gqb={Mb)8Lfw~h<8@eZ7;W1&QV$mOhJ}uLuD+%&Nn3|FuA6B=GJIcT&r-u z2i4yjhRK2bvZW-{d#WjPK&A;6F1TCA5}9CB`d<_lvZPV{(CfWQn-<0=7w;M|k!HEv z4{mpaA7_(3ATW$}0nKcMw3Mp zLps@t^9kc{dTF>6w-WKpK!}e5U)o*Ab|@D>#ZU&oHOLdnDYg8a|F6);DBbid_5|kC zj|LRJ%pLH#ea-!6;oZ#I{9Uytx-O9|IP)eqTyW3iYVs~<=_hR?R7Ec;-<7vBmFOwQ zZCgf7_Xvv}(x0#Zt=XZ5k(3AVy^K0LG-S#T{$2{ZHvm+iVa6qPfh`6WO6BTSRRNPd zXq4-x9vrd8CIP7`B_z;-Mg$x%#D)Ef6-#9DHUH`5dAVls=Hu5Z<`BF?*!}ITnNq`D zxM5=a>rMQo)dT?uuH4h*BfAfZG2IpC%PjC+6bynG!p2NSM%(vnXBRJ+QP%ygA?4oT zyx7=JDgO;8DnlK&#Prd(TAJ8$g!1G-hlb?<@tvJA-&>zJBT0N3tES)UvVB#J4sVl5bt!L0Bf@%RX;1}xn)wVcRent8Z zI?W9xNI5Du;oUSzLZyXOv}!vN!(8-J4nrGYkGm1^`MB${2e$C8w%0uLXfWY(u{yG>cc`=LNHSGKJUf*gP(|hURCHw;cSwj9 z1tMCAVWYQ)q5JFe4c(ZL&Uy0ZIkWE=4IVq8X8~>l^X4h9(yAH#3>jYghjB7^1p~G1 ziLnQgl|5#2;Iy}}{y6aXImWh37T^l~xh8eixBg0!cL0wU(MhqLT}WRMJ8c8E`^*!gT)(+VLN zR@J0)GnPgcB^`F{GR^PKY>o`qOE<8L?Gv4Qd$N*gT~|Y2xb+(o{LeWuA<%IWS3Wa! zw4?K~`T$%&qrXW%J_LJ-mYz>UBs~H#;$e9EdX%3V0CEKkE@Rk|6^@P?r<(afIpiU( z3<6gd))Uq%4FPEi^J2o{$cc3whTkQ)J!DV3;IGHCf$kam7V0nb+1 zK+=8O#RH*Ww~1HHfZNXB4+5xL=RGIb>~Rp#000M5^lL9)Gp&;ZDJ0H?>1e>tx<_B- zHVF`W!SZDz=>&+a1xQ4K32~^|gghmDw110%ZeXH634$BOi+2g9^#pxD-^Jk7z6YHV zy-rkD7l4T(^rD^EW}1Zq>k~4kulqbd+q4X)Qq#IUu6eGpTBxNe;Sp25`uBfkE0NY5 zoLfCQkI#Ae|NTq&NX!V>EH{g*{p{S?5|;CUIdJm(0=L@l4EQtbPzE<5u4w~>8lj++ z8j|XIdy);cl)-VYB|LBtlm&D-|Jr3ro#o>V^-ypHJ*T8}vLY6X@GqBNMt7|7CimgZ z(`__@apvHuuz6;N-tLu|GI{@|*6=wg-hMz|l;A9ZZN$9wi~n1CQP*z-tc&<#wZZ0; zm?c+R!`-jMYS&D{6&Y%JkR>}m_j$HcJi@281p3hHx0#*o$NIm`;)0w6EAWSDx(S!>-k{{ZHRL{#^b}!CaxnYu@bV2 zq+iFf>`wCyvw8P)#Mpj3qAAM>fH!v7XiHr`Dw^{+?6sBEm>6a1mvgQ+a* z#KDoX;J4u{6Mp?8{X`N|nPTXyjyA9HhP~;q!9n%Ve{HI_1Vs418ePICg*{AEzu#SfyFT2V3L8I3GvLzyJV7!gAK2 zDDgEhd6C`nS(-jQ^XP7wcPMtaO5kaLED0t5x%N@5kdi%**}nSBw?<;R>C60+h1nN1 z%ExT6kV}8nv(|aMq~q0EYLl#?N%@5vg}pgaw&j^%=raLp>p2bBCHkbQfTc|QBoH~% z=0#=oOkr-i4)okZf31&tNE*KvoI0%RV0aL5(ui3~Mm9ces7NPuo`Ur|krXu3ju8u@ z4rcw3r27Tc)$$1|=U_;6`jc%og9gyTW5y?IqsvDUWz_kD2y*pZFp=NlvGl-A zLcad*1+6k&{Y_OgTJ|p~z-v6|eKpx-_o=jz{MeTO}rdaf^K>VE@DyN=iwtCiY-T>FJkW@V>iyy zVul|_rwP^}p~?DIZRh8<|KE0vkDX^HpCQ0P{4cp%xd)>&MZs_i{gy&Zb9T76ZU%NH3>&AAl7#n z+oHp{H6(NH);)Dj$y)ywsim7yDZM;XB0wcpmZa;pn)Np<#$V4yzwXOKRUxgh)Cmk1 zL+U8^b7VsUdmJWM2KLJHHnrB5MsKf66^yVXZ63^^E49f!?Ujr7rP%m#Mv{==-`u8y zz9x*)LYV#3vfqW0yk$BfH zIcpyRwxOjRt&e$ex8Lz+LSf8*EA}IX(|KEse|BNX-8?Uj$z+8)@)npQ*x8opoK`Xw zh3FGgMbE1?+k!-BCq_`d;6+zNcSUn#H5z_A>_Eo;SHeG@0nSj`y1BLbwjy#6Ima&0FKtas<(!*3^SvREzOOge z8zaGHS_oM9b?=|rb%M1DNso=nq9!ut3{%ef@n=1Igzgk)11*7&KUmjvOtJnr6`^1z zc`QzOS`rAM0NtADL%5UNKTIY;jL2GBtGBQ99Hy6Y;2rpnpxezqFD5@s#Fxa8N2-&rSiD@ON zUn=VKJsQPdff*_BStzY7f>~Av$w@~>*q{RBzjU_pfB*nim`o&D5LvmL(h~eWhVSp; zLr|8o6v$cem}9{J0?0$a8V|VzifKiPh+t_frK`n!Ec|pO3qD(uBBZStUCgR5FQ%{; zr#kWT6-Q)+QB~;@X<$ijoWLPl$3c{nX{VJ^Oo7;Z;&&MKo5jyi+)Tw@ayv#L0VPvP z3HKA-@|h%~r|*nzj&;LC#VT(9mizwVj%_(kUK1!kG->Sz>1ZzY^6@Jkw;>lRGx=nXMWNliC054py}Yajxi8&M5dK zoK)`bixw#K^u08LIgYDGTTJ4H4j!t%$AOY*v%*h`+Mzi|Iganq%~fSs{;lbS&gu*5 z1q;@%qY7GXO41Pi1*-nf12HMy`yVlmgYYB$BBy|1*^;fDdYDliS0I@nlCZf5APy^7 z@Zu-tru_@MCv}EA!4_<`jT+!xJ&R%dBZL&zaE($11tkA9DgZH_!z1CH*e|KE1OA`5 zTQhR0l@!HsyD&5eCho47Ue%5~f5>i?IAdiRsE$aBw_wWKgs45Hd{f!=>Y#q*x;89xj1o2h z!juv>(gFg5c*+XXMpeV|B7!kWbbxYA0G#TcfKi-<>2~!LoW3&kA<53kzjm8v@G!gU znZIx3Oe_V?1CH%O5nUl5+Jg$f>ZbFwwhyAh;P%LRJkzY^^T5Q_r?lpF_ca^!*7D(A zI_*B^WxNYt4sN=XcNzZI+YEWjRwWX-bo;M8eWb<6DoM3A3gw^*I>c2i*QJ}&U47MB zpto&0oQb?8b+CDmsuIIa($IK6L4MPC8zb}fbxRA0%g{cLvw0PiiuBz*DuQiI`^1zy zE)DBr*uiQ}P3jj4Sq_PQ&gK^rQqt*f2EkTFH2J$(p!~n@LKG(x%91pjtX+O4aicbm zxEO0`;BK&I@um3d*ldCF+6V3HA6=g{`0N>LQC1o6{xaTNJ2-RKgymXu(?&rH_}4aD zR@To;Z%tFaO<@@mm$X}Fu~`x3;^RC1QcPJA0HkE;L%;Ufg>)T_il7Ukynhaq%Y1R)wcGlw z*Xh+Y6>GV86l1jRvjIjWvpu%_JcC7W2_ZTOA7n@Vu^7-jg08xH(S6F!sT)(FSvn+h zEan)BUOLFV!3ia@_ScNF>!SS-#Kw~uU;7#> zr`LuOz3-o077r@Lc zwLaV6ytmXN8-}PRY{U3+%H)2;clO z=;_nwL>RbOP-53R8lCWnlQ{f>@$^+s}>d_D<7E zL?lIUsc9x<_-B@t%C=oBVb?HKP!a8u0dUSzk4!7+a{SxubV`c<8aUk;Nag%?SlkOc zw}+R_P-@1M#0Og?@?RICFd{f0tWvvDdq%%_*4@#^2em9O|3Y=99NAw+(<$ud7 z0y8oe%a8B9F*_()ySc@eW|i-7en)%I zVI?Tid(-ffEYbsy2n&fjt&GW8c64U(iQ-Pv16J=jABUB1@fy!GMfn7?v218B`%hKZ zDn3+Gn!%Q^lKGV3y^i7KkS^@?GpD8?|7#`4EBDf`*T9)*y5F2;L7pXfvc@LBi__u< zF^+Y!RxNo7y^Tgr9->7i>0J26l)K3-;Mc{S|HX#>FCzoq`K{jaS8^prwPvQ}q7=Th z7I{a7Y79!PD8goVU7Y+FVu+&-AFJ#A;lG?<^qMNrKMmvfHg0f$AVaXqV62WqM>!GC zOOvaxaT=D4$wmn9;gq0BomrE!_Dnn<)YIW{`8uwDuyo8YT^W?TH$Buj@|QKSm|qFT z1b?jy0QTmu+5-gR?_xhuAFt~-GQei%l5Y&n;l?TcoGIfcF< zajaR^QYVUvDn|avf5!5TlF6a8`hE$v7}HLzZh&#@Kr;bi0c>bWAS+vf2E7a3XY$*z z#U#8&H%zvy>J#x&(fmTt=`j>&npIKfQ!Z1HRsmV@E2JQ7G6OS!6&9G3R5o#jAaT#( z6ltxl;xS$wwE^X*>`iB6NA=Ufi_ffA=~#NcSIEnGt)`WhD8->*000934FHxelgukDV1Q!l$;iF#=fSei`sG*BMBmU+W|08-OF&R@Y&7Gthvn$b*&j6bo{ zJs4FC!DdWAY+F1#cI~1qPJ|ifN3!bIrFE5fqu4wcn)U=~+K+7zU?Q`--d^umTlIYtlze&=!E`3FKmL>!qBp=crq~oD>td_I=;Hiw);TeX`tD* zHmzgZIB>iTapi(vwb<)xki~oetbjezKy-- zC&%r~MG_PumsQTJf8>?IMB^Hm0koMI0dT@(agbG^>byzglcXi;s)_pJFOJR?>3t04 zCMpismD0i+xh(4tOttI{hjyNa60p>2KvnAm%;hL(D@HWUS=0X1;_ZoJNKT0z8X%oZ7 z>4^)UU-qmdEbN36lF6c!`u*2|k%A%H9C;Xh%H&`hN_5L?CIPG7ctK%j3*6r_806S^ zV`*-ZDjx5c9)7nhn;*fUrM6!n6r%HZUgIjuCCaP#83be>OSWrNZkRa$E@6$zeqoY$A(No6jeM1)<|Eb-)1TgbO5qZSdR7)E}Dpu;#! z+C23^Ih%>T^HqNT?_OKYHI0VN!(6_onQTDp!lwr+1`~~vzRH?%n}J(V*#+vcYLU-w z>bjf);PUGp>1VxK^=h?hpS_@F{ahajM5IrX63t}0`bjd~DPp=J$iuIbej_b0`DE|m zA#%bc7q}<@xU={8Al0Fqfb#te9{d-sTlB|#pb?AWr}YMeLWOu1#_hprxR8M5Gwj`1 zEYZrHbBw+Df40Ik=MUZ3#M~C=v|_NU_%8{_>n>gznL>Yo&+C9!;MH>=ENTR`I%H74 zq)s#@a!(Q}Mdw7sCB`}!HYP~~iQbZ3DHr_`@dM9)lEr1|fO&>gyZ9ZK5`9#oOjsC! zXh~w}Hqj~Ml&oNT5gWTEvc+pHSMJ|Pqg=hqKo769U?Ri(`qGXUv_s{-cyIU|QdUfX zS4}Lu)iAjd5woJCA;wK*+$ugLBzdb9Z#l5cbF>mG!bztPtufQukZuju<-+FWC7h6n zqhTWr2rMpn4B_EXLs6SBteKEM87`_l{?5fJj-2)X)5wRG>*Vc+=M=^Lww`(Rlv78- z)^ncFwMoeY+6JRH9FaJ$_veJ`QWKDd<@e`gGt&Z9LSVisz~S`D!}2t@6$Gnu=780b zO$rS@yiQ5rD?gDNXpZL9CU~o^^L^{`{yPlF`BN`n z%fgP%Bnx5C!^(ecskVshkF{Q>viRz#s z7^M02;1ECn2D?CoV|?DZih_bM>M+

bP2~8N(6IWQIsS3PBSn?qxE4v6QgLI6wr+ zJS$c0I^AAqQm3l;F5e=^EHP<_%})RNoB!F+LJz0L%U=n(E?vJy(jtI>6?C^n@W)z@ zW%+|FkQHM7z^e|uusj3>k5JxVdEhjRebYGs`m?%gy^3QT!`YrG!0{Oh95`KDUAxIswFC|Oa zR6DK!dNhsxfzblzkI#d@yD9Z=^HK}_y|aQt>1FtvUp(yblIjJ+k07P{qFSB&G9dn+xS+jR$VsvM0`Km%+4BoGXaJiu~S zQ^z-P#@L9h@Qn79C5APYO{49vR|?YP>=PWaoDe`;dz+hcHIdaDD*9lbt$?`S)q^WK zTC29?g>SN`)rPP)tF5XFUFvQ!TVy9yF_46@G$c^T`4L!3(6_S79Rc(%T;vYfc?y!T zWMUvxb>?`+f&L5Vy=p2*t=t#m7Q&z)|J~5I3sN=j&rDILGo~qbYb3ba9=(N;#`p6$j2`tk)N~6=OD5}ULP2cX<;i;0EVrhB7fXNz3Bb=4vivE3RcEgIyBM(;5l1r!u$)on16 zh?-|`C61oU2?qT4Jx21)yF{j7@A;QY_R}vE{S#zjpsIylD@z&+yf+w&zeiX&bpQ!S z!O7MC4IooL9_D;by$Tc^ z%+c{@PkN8r;5nK-<)=u5#t5xbUW}bK!)&;hZ@Y1~3$*+I31^hb&Z+0uC_x9N@Uh&! zJ(0zA^5)&XbqS?TQhB{@hB$&-uBni|ST@g~;fSudT=pQ+F7)(pm2Ezvg;G!Ca!+p4 zVye0x^RyJu+-zjiLW@>t%9b_H5~$g!vlC^vJ^%;m*?sY|U$j!Di=FaN&Ivg!kjB#6 zK}!cE@^)}-!IM+|KFlS_4`cPl&>vu~B3@B1vLJSf$*qcRYo2RiLy&8)e<(JU{ zaPE2ZJl~lRoEG-mKGQ4U&X;nm1;g@-$e5afXLUT7ZAZ*Cw`Fn zmwl;JqrvC8AKl@9KPw7Zf^hVP&?=_gRq8}o$lfe+Kg0LCroM>-SflMTIRYS!_7q65;*Z%)^YR%c# z7X+X&zuO8AHuTB}wduPNx_vBD6{9G^Z2)9&bbIJ?-q{|7gH+{$Uc9~yb@tBTP@j!- zI}%nl8gpEP8gISP_{^-iwUg9})uq)EFaEnUCFcdS^J$i*Vr?Xy-GJ5)bpGI#J9B$v zVvS~{jxE)c{Wxb{B20jXv7z4LZSogMVC%PZcph^xI;hhxxt!z6!tIM;%W}S%V_St2 znZlV~EOViG@>s&viQ;xry(n^pdCz1pBf#YL1fdVqeAn!r{Lg@?paR>RIx4?xker@yfc-o%G@PpY4>v06Od`PAJQpK9F8eGNH3qF)Tw;RVc7o+ z$x%)D!mE>&h9E$<pFy)o0rm(^( z`7z|Tg{mU~)DDeeU#hpS*hM{&O+SG*0{o)+^y~t~qmg*+2Tjg3v6Pf|j2JSJWErmX zZ?cC$Q~1J|zZ&4fdvi*mV?f4_WukjSpAW2sBfrI56LIyq!V?*93&CySAN+x4+ub{u z!PfK*Hkuago{+ zHCgWwgUELPdE~6cVovx$w^*9D6!eh&E+^IE7o{0EgWO~RImiWm^3NlDIG51Co}F#4 z2z~H$pNWb_^L21Pq}nFnq{l)#_7MuNg8Uje)F~ zvxK5=oNB^46kE|R>yNi_ zlhjDIZxP#a06_e3X)B)Vz&~oxN*-k@FGef{ITDo=9as3&hJw1kf@c%BOsD0sPRpV- zBhYA`!2mz|IE2=bpJhzq0GeK^s%nFNnqpHbPr1&&ElJ2uqS)mD;`Gi-WroK;^6CWK zv2mSMUd!FhZ_Qg3Yb~iSuLDItAd%-xz?c#*|DPFA%4({W#%K^W9&lm8u;EvLhPxNt(-SA3l+feWD5=M4o*b9iFY`|befUIqt z@5zVG1BEFZFYva~Vt1jpk_O!XGS6hi0V7W%-s@O(8^EP$@B`k3&@tg~@x7D#V5TgB z+%|{OW=|aLaz?FoEWDi$1!Tg6o5U2PSIIVjIT`>l2>B6ljf7jqS=k~LE zSYQ#q(>zk8A(v-do@ns*v&0rMKi#gf-|ML%zHg!|+I_uiKL{D_5+GuESo*4V-f?`Hc(Vi27;aJ z`zBdolR5_MQa2Oyy-@-bs&YD@`Ef!_5s<;0K1$lEAiSR}wG1f))eS|J+o0#3q3`hB z-n0P#0Mjf0H)#HE$$r}6(Efu*$(U~NbegE51U!X1Q@g1pzjdoKU_#py6yL9mz#?f^ z;ymBX`maL|oB)4?oJ#C{0I(T9(~p$ij@(^VM%j}4mpg9db?p}nI)}eSD$8TqD4&WH z@U~4muBtr+0%!9-Bc*lVP-fO^6;dScL`xV3KN(Rp8&AZei$!ffIYQT$PpX3&p5Hah zz2mB)LA;6QDIN~q5(Q2@WotG2+9p{POvI}R*@g4EOY^w$DK+|-dtJNLcs^uW@x%zD zSBZyp^tXK%6lb6&aO!BiBu#V;;^|5o<$s-Q7;<}uu4p}v@D6By>fB5i5``UYi}^4S z5`-RBTdNhKb^UdW2fD<2mhd)vIROzbgE9yhBUl8MUVMMP zv|4Z76&KW+j59WS6Z2pq^Ytj%enw!mcQ^hFlwHeO`N4Ri*VI0zK+#`2Hhr!-IBlG1 z+(f&daa~9x&KdxU{P%5z2$iKKoCUv&PG%R#mwcKE-A_=XY>!wrUzd|m0#GIz$_7L5 z?g!Qi;wT(clVAVMKS_ zq3nh8b2nG({<-Z1!E|pdz!(_!Nd#)5PD$?JYaB2q`O<>}BF*LEtx+D6Z;4n5qui32 zMwX_DEGrPc@p(qBoIH*4!3+E6Ff&y*)N5`JLGd7p|1zjRFnyhYSlWD)`CCs!5ll5F zdPx&PN>yA#G2o&YeWZaBiLKCUihTi%9u~L{Ug$1AQ>t$P*WL%@Q6WR>IeH!QhVhWt1!%UMw%8?I~%R|b)cqWQynzEdpV&OG7bW zUIBDQb?g)GN;}XYU1p_du!`Q>m5-X zhrYS5wBcFbv?8m8u9tVq!O6_k!wA{ zF*16iSf4Tx6IXL*hWuwcmduRN445Na<9;|=7W&P-OYi(;skYU_n(1Ip!mHWm^GR_< znaxiOwClrsfsF*z8~xT6J!vC7;ujd9L!!WI1;je_=wvb^HR?hcb46_XV`eiap?78Z zuUTo2oFZ@b!qWJxIMSs|In6*?_WLC>bN8I*TDAPbm7wJbX;UMfAinNo-vj9>qUz%T z5+&GfA>muRNVBDB5)hv)sFIr_jWVb{nK-fd(*3mz5|%eRvk+B8I`Ws3Lh$JePfKQP z8;9WPgjr%NllvuFj5J7Gv3DTLqv6l-Q*r9-yiR7U5D+>&g-KqH`8mAJ1HkKh{=`tk z4w8IhD^=Dp#Y?y$Rr~T%H-|xtR4LEf#mTO^5nh;Zv{;jvo48qQu=o|~lp$gjR?m!% zpWM0cm%7*0J5FFGjq&*#3-@D6fu(#!9P(+1q`15=uS z+x#?W0Zl5bt&C)M|CFja{P3`L;SiG2>HQDbX=u`s%u%}@d$SrOqP-Iz2ultQM7~W; zFtHPNpym9;&>_xy67l#nE3r;P-`L;majRYLgWFyr%7fp6X%aWH6XHFU)pGGy(Go&I z4&S+@29nBTH~lZQ%?`eoS7krOZ~%S0jCYlD+boQZuzM^G9WvXRKewDVdF6KrGO z*ON{r^oCGE{HtRUjWoM0jBul+Sp7`NzMW%1_+(atq_6R6%7OQDB&`kC!MVti?%L5I zRHl*)z96fC9Hck4t)-TjPl^+HX2vtB?>9IZ;s*;1%;SC!>(}KvFv@Rh{ zhoqejT#sRAiwvzM(Zf@F{?2`RiEU@@?52FzVb*;6=lg(6&PLF9zi zLiQ^C5`o;?E)fS;v0GN_erjgUMe41cDb!IGH8pm*BswBW$;J)j1q+)SEw+FaME|fhpLti_zzMnjc91qF z0M~R*%!I}kKYlS2){zX|2DsH-(j3U^^9f1+)|vnB5P}_r&qFql-Q0bHAU(N{?xH-8 z@A-vM#^M#@ePI<>!6r>=<~^PLSL2mw9}iJPQuOS%vw0OtB+J2xtDkWu`vk>x5MrtT z$no;37%@^6Z|2m`BSr|QN+I-oEzqh5w~S6BvPp6X<&rcdo=6;n9-&q}N>#jus_?-Y zFoA7j(#{j_o`Z!>tD5t9lMpXQw+j&Pv={xCq!nuPQw@DdsmZo)5=yS}oTpgd$VV3i z!}#02=)(wU()1Ny4z4(k!Nynlj-6Y4hWIbHYe*HQbO#geNQ2Z@&{VJjAK(V%fvuVNO7o5Y5!p!5Y>? zv|GTkE`qKjR+P?gE66Q>g z=F5NsktW@M01J#9GV#T2Zu0L3s8HndNOf0PA5X>8YJ<-9k_nJue5bo#6uSk4pD5u# zlM>+Zz~u@76-RbKj!Kx6tpccx%xEb4Tc^$$6wAvrBxBPkSy<|6=D(0&gyK;ccC!iO zc{S!O00G{BvPTcTwV2i21von7E?(DmPqxm`3l+&42B1xPQkBM=ww-p`NZDMI#69hExv7|S>&o@eie0a- zIDwM?zJdr(_eJfm{wKm6DjB0`eBG-Z8YX@~#4tF_AxACMIB$y`cEejC zT-nlUdT(CeHoR}61n!ohV$u75F+WlnFB|1KSQ%KkpDP|=J6+jqiv!s%E&ysp0U*!6 zOm&u0&{nq9IXUtcmVmj@^&ds{6eKI7s1&aQMrRts!NW-&uQ_Izd&zq7Lq7~k_G{YD zr~%_osUNrwT~r_`v=LgIX9B8>HAnDG+h&0CvTR)(o9eJ8UM~Q==EYGc2j0ND+PZ`8 zHWnEzWHMU!`yCHLr>*Np>b~LN&Wy_e?IQj0(nG{o%hzIR9isc>iWr=u5F=%=EtTkYbb>9o1r6%Z#gH!S6-W| z`#)%Fb!7}UJ0M9)xev@LmmUOx&{vw6i+_0ngJPmVf_$~2@E>tK+3E^tl`06_IAh%O z7+rQUWkl-3@bkw|B)DFs6x_@U49T;kF8$n}JRBlI{&SsenKirf<#CU`M}*R|izYs^RzU{M)@acE?LZXxGNfJTXk~X=;DQ_YK4P&qua}F0BmsRh#3MOco183}1&+Ko+Ke;LS;-5l$n0 zGbb_eNEg9i=gRA$4kJ*I+zRszXvDY5D@f0>d}g_0?^Y|ZMk)rz|1|>p*!`u5eZJ$= z-L-##qT_E|3zt&9$=D5aTsQZ7$@L}w=3aKkNfq;xY}BT$9nWiTh(eU>XuquR z8c+SJ`5he9{vBQdj!h#3amF=EAMG~rTH>6qj1- zwVNG=(w5}4G3p&_#U-h0ijGPv578g2&#pX)SV6g8G9qdgY|4 ztOGgbx1tFDGwgBN4UI<1;q=O-DAO=P?9kohITX{;YW$NCu#xQ2f)en6Pqs<;7lyW$ zX7ag0%sW*&<*kA{Gkr@&8CjK6H9K+2+bjbTMu^M&dbi`1@9qize{G5p%;jb-7Z1gBYe1 z;QYAwn(N)x&@48;kK(dW#!uTrPJx;>ws4@nmh17UQ5N2u1kWO|ZP}EOX<+os}+A#6OI6Mthm+o1g{DZ|it_iXCC@`#lO#&|- zx-RVhr19V?ft^hh7m;`AIaPoWvafAgpz? z+33Ql$nE@4KW{oP!I#5LiDgAl2d=<8Y%4*lES$!L5BLKeWJoPePsSfVbg0~BnwJx7 z;_g8|ok->}5)(v6%HapB!kHkH$jQ$u{8&yVwZ=!``D6sNB5Fm|hPTz>#B!1){yVrl zW1H;McLPcrB}X4xUYgRKvxxSyxWVoT_cY`%xR;5SuUY6cJS-GUsbVWA-9<|$~5;+k!W}#7~VI*3sCgcykZxR;pW;?$>e>x##4^G`0D}p^p>SCQulptER1;f%AGTTK50!h^a zlmV&qt5`#@9g`=Pdn`puF9J^Et2As>$)}pJtd)*W64Fbrl3^>nPum>%Kd@w21%+`v z1jzOSXN5*-xW#;fWMD?;h89d5usN=mr}9QZq`hfgk^Q zgSh=A_~UI|)}wp8;NkR4?DA`h*xERFSpp-p*{KfiZ-^@O zgS+Gh1KFGrrWz=&+sIFK>(Y4sQ1YQ1itH@<<0#ZDMgBX)u6HC0)C-KbZDUAJr8#MQ z(#s`JTNV+om;eb$wx{@YX)001$*Sxs@JYO-jlBCOm$MMMMNV^hsc5j+yiBvrfI3Yf zvD2~Y6}2=qP2S~yDMH(mJFtES^RP_GwCkgny%C|-W_$8;JpBd3ZR4kYN0wPe=N!a+YYibaukPRn!J8Zh1WWw3a@rY|K zuObzbr7t5^LrP;f4WF-MlMkf*NoL-W$18kOldvs*1HP%iyp$w@wC`L*flinx`5{F3 zxCyq)gw!b$mLISV$d)aDUJG&3XEJ3-@iBweYi=nYdq9iqI+csTbAcBp5|;QrL*TZ1 z2M*ekhS^T0`wQhGX5jc-1f$u(=6*C8isNbt)TLaYa^~?0ev`>GsM|6r!)}VVRvqwH zyQB|Yn(D31v8Be87FCKWAmw;B%EzQJ*X~%i6bx8~7joIXKH6L8{k^f|EHI_{hyFyF zx*62b>i;jvZ@G$!q|6)Ar1y^I-V{JCvSU6 zA~jF_+d**ex2^@^V?kOczxLHrI70dV5ec&%etFjnLH*vw6DqP&C2-)H<4?T)V`8Wn`kwy@b_MLbYVwLj>66zYw1`D*!ozk?_!xO z?YIedaqldQaYH@6xX+xZ@B9|>5NR|os%S%nB(+qthAAlNyCYjQ)5zwP7B1oowunB_ zJcz_C1qV%F)RJcMdm0zOa(eqLa-GMsWvuG&VA?2i>}F*V-wlaoW3XJB5A)S4L=e{D zhVsf2Zo}DDBZs^&84Yal;Ch%Dnq=><@DK6%&KIv6jSh$p{CW0O)m;99CU>+ml)1`C z@AWsqWVvdj{{Dh61M5mjY646sXkV3BL-k&9K_}er)q$VHMav$%a*b0pzjI{jji$=$YN#C@26_M^>xi18M+O9( zP^|DLXCj+%gwJ%8A2^D*oIY-}z5?IfZ2z}zD4r%y^qvE9B!rQ*Mw!90`^MK*vgH<* zEyeZGfOYpI2q+{2@S6eIC6Y#Fp;*mS*2G~k?&sjx!O1o;yF-23Gi~{%4JjyRraKRy zBbUxDh`BitlGOe);Y@xh%*7XkMY%nq@+;K_1eQ8W^MIUKk|^xe zPzCW3YCyI2c>~r#WC~nPqljY^e2BjN0nwme_)w3~LvXL0)51USEE}6Of-5c~klRnD z;LT7v)y!`qPEV`&Vj^#yVW3l}j8FYx;i6>?>he1JMT}o}yYh1b7Q_H8?;icv@=>qUYB6A;6lf0OwrDiVMM!A znW|z7)PlT9Gx)o&As7Obwx8vMvV$#5osH)d4Ei=%Ex({cKAJp?4nsQI_9ki45;k4W zs+$x7CkLO*CHKvzt%9%eqE>iQ}R_6 zZa7YK&UYc>K&~pbNd@&jN9V&1_UF{Hx-#1@XzSVXPO7wYcPBoEhGI@%>rJtgbhoI; zZu~)>-r>rk{Xz6@b=7Gb)O!Ezz30i~3Bt8Sa;8Nvxm{Ca0?$>SDv(rCGw_T!3=udCL#-o^Z)KY1g`&!Us+86g1+kb& zWoSsx?Po9!ZuTK=E9!3L`~2p9K20VQLr_*%9+c6jBmV(kzo0}?S~g}drH2C(!`}Da zx1`c+U^yEsXo#S|ed`Nv5%<`*CE&$W_EBVNaOSs&OO=*=dfWdw)k`V@70{+~G<3K< zy5ur6kzEvfuqQTNZYti0n&vJN_iFh|kUVPYzLx3@ zSF30m7YcP|QT;Qnp?4Snl1;mjwQ0aVxub|lhLgDEIT+pQOn5GisuVg&l}=lPxU#BD zbIa4fn0(-oPC4lp*JwxUy1he?=qn_Yk){RgTPE8JAQ z%2s#1vw%Xkr4_5ldgBN2v9W#>{@x{h1s_fry%lw+f$9CpNYKTF zkD&71m>2VWt*pCLoW`hSaoryC?^Ip4t5+PXzE1j4A56$ArUKw1H+`7o14JhlH0tW@ ziT!N7Wmp|cvj)0wcXubayJbOeC%8L7g1fuB1b25QIKf?mYjAgmAa^Buf9JdBp8IF$ zRXseB>on1V38oE<5Ji$1$@xU{p2n z8$=oJN;lrq2Xh=Fiz;33C?6o=wOBw6b50|(la9a60}Wq9`~5_EqyLlgV}UZ2%nC=F z-xw(s#maZfSB35>_lVXmN0n12{xmjnHEV&|kL_PS*+Rz)ZCthOo@BDan)81Y6CK%@ z;+@rKj_CO|;nO!@mXW1h-r}P-%By$=b;D{6Aj0qN4G!v@H~JcDUrOwHkck|b=-6Nh z&&IjS-~7{7ae;uW_^X*kEo~~;el-OFjV>40^B_yDH?=S9lvCyul2}_^v36Im3ErsC zGxtMTBQJcMP9r}YD_;55Dd};Opy8U%6lnEJ3G{QWL7PL2be6wxkV8vXq zq)l~W^}i#QRd$&K^u~Wljd^!F1c+leGSjHSU>!SxABM z$_hjlhgopC!cSQ%2~_1(ru|-mo8-@v5aD5!3hqZDA_r@FJ zO11)hIdM2%o@oKAXH5JXH;8Mt5x%XJE2D4!g7cvJQ6q=_h!8$WV91_bylR^23^ z%Nj^rQyKv8t<-!#3Dg`ISi=@Iue)%Zx`I9P_WjrJxhEN}$hedBp;P67^Mp=GLZZ<> zrWcNBdBuN=>#`hL-C~lX7=z8HUdKNL@lh+EEcJ)@wVSQmpVh1#>!fxRPM)8CdBLxV zkyx})+9{5ZTzGE-ugwC_hJut&^5c+uwXGfC4HGq|09BNaYC7MkO;Di{HY5(9A48s0 zj)0@|=Qs&#2RVun`h^6va@7Uq80sKaYwH zl6rjX;Xm}{mT_5k!_rkk*v|dgT&0Qkfq%#5M~G~(1vgS_j#f;8+XMk%-`-DsL72NWcClQI&Qm@dhld>`vx3DcKk|_|&%xH#^OH5bE z*XASG7Ow~mf_Di>i`Nzfz3RCz4wYhZD3eU{Y3;H5(HQ@V*-J<#YqYH8aIr+{z zBGcwIJxi9>$N{r2-oLTL1CPHaR2#{4_xV+9xEJ#nT7JSl(`G{dnyOgwQ9_w6-1IwJ z%PWKR_MCogmZ~;PsxtANuKC9dTPu=g(rH-5lL^oKui-zNj8=zVF%yv!F1 zCj7XP5LuP2;ORAr80y8x@`BL8 zL>!#)UzB=6#Q|G%`~p|sVl3oN^d7;C0WCakN2_NMKu`t^cY5*#Ca{yJdlf$Hif`$q zXVA{`3yT)C)7lY7J7QAG3NAYeb%w~#&m_X6g`&GSyZIgCiEh@um_I?=+Vu>v5vxa) z)0T#DnTx|n?37Q>tg^ztTXpp$lNuK|>1Q=RRfL(^yzg2FgHu@y^ajs}Ti-=5+Npd< z5@-K4rVc$}Se_U~gbKA)TK(a73$s+bD=_6-47T{YdtdXSsJ<+g`we*E_OB+J9o!?| zU)NLLZr@WA6_xf5NaAt~N~WUR!@t!Uju6ChqkXztk+XMT{8W1hl~dH=;~X*(KKU5t zOZh9SQ@7^G4~s@_k^Dd(5m-wwy`~r2TD2TH>7Om?nm6;g_T*d2PmKG-jgphHYuCMl zMfIK!YBmA}t=D)CnCl}F$}(=<)dDVD2ibnsS!fTzBPJP5yt1^lMfIIxD~T(oWcA-W zgJ4Vgw$6(j*Os*^+F%6+9YQwk?J0rCsYWx(Hk)dlnIBN(kk{|OJgJl^I1E*$O*^ ztE%%6H5RL@p}Ep-uoA)aIQ9M0&w5DWfhf1$SrJy_ub+>|yZ427BcV{>HzYT1pzp0H z4{y$N49k>Gv5D`GHB^n5YK<66VQ!-Iah))HvB_;CIXEt8P+ zJDjDqD(j~8O}EFF5KPhl;l8>WxT5dJFbgGG=i?uM=V(cOA38e>W?zu?z9x)zRy0U} zdlF5TZ0I71v`%yQN$V5jv_D(dSj{U#kTf^2;(1z)-xi zi2J5vlQ9sVL4e$+Y~KF9%7}aD+26&-+6a?O%q!E=>%Pu{rsb53}*2J zYy(bX6ppmmK`LxEtQ*%Cq=W&^*2#B2lzB-zyr}`&b}B7S_Gv;_+8ZO)>(stZBiN=1 zsydy;`ILpey2#*<3tkL;s_Ym16UepwWJ!K7(`iuMyC=Q0N&T^GjDEPphcB_RG$tNb zMnZ4>zM_T=Z}D1O?;ZxzFzXqW`#!;sjHwH(P%D(~u6ra|CJwrjs0Un35wIad{kPk# zy);yfHJDbsuYNo;86ypyB2Yh&GL^@=pirM?1*HbEtS-oo^j-OWt-2*$$Fa+Nid*`; z%X=iuFLMMVHbuNMK_jd29^pqJAnW*x99w(bI{Ubm_sLYi8Wn}7@MrZK8@yrGehy$T z^a%ePy6g~P;_B#L-ogu&`zxXqj&iY?tB@dS^1YZoBNX|IrM=`)vSpwLmHcmIq}xE< z&eU6LbOUxir_XQpQWz+V*g)N0Z>0%{TD+!-)Dij8D@0AzhXDPoFqoS{GdTTse9q#^ zPud-jeM6?LrmAj|xH62GKr(uMcZU2!Q^5Eed?s>jJjp0OK^vhWY73i;M~nBO)f zeVV%`L^V-!oBz?2f&Oi4{9}I27R|)FAELchDh0c8$bRBN15S;bU|~7<;THdXy)5{! zKT<=WwoHh5I}ytM)Ip}sh8P_o;oE|g&{f2Ao$4uR^UKHM+Ho=8dwkTxK_ z1hY#wW!W8+LCFPyVU*HDlSL^%tx`KKU92_)8F^3qD@i9!Q=ZQ*FW140Da9kEka}HB zEjK&*ELBV4eNadBfj*h?uqxYHj(lS!BHey!gIAXPSpG~6OmKC5x#97fuJ%{@7Z)lv zT&S@d&xvU{uH-g}9!P{z&(Ga>=Tj|EptWKHbRR7`2*Rv6OT-)4UF>xs4NgU7hlXQC zAmG=71Z{r?7v%gi{`IV=Tdu1v@5KjARr3&rFtZp*H{nnpq@HzFHA%w_{#(VqmZ5V_ zhzIq$f=pKaF9@|+u1wy65k$vFByLd7DQF+OelHAtY^BcR`O}@2hFA;SHIR|Vjh_({EQEQ-8Fl$<`{-Qo@f%=2)G72ST|7RRG~%Q)Ji(>ODD7d{+C zxC2G@g~*NRQcLIx8bKYYtq42|QOY<4)a0^ua)Cy>^HuYC{a>I%7Forj2fmeC-p1?@ zs6{GL+upj`c){s1QQo7_yy}Y3FesVgf0aJMYz-HzSlpX4*{5?WZ}dn)P9Jii^B5h+ zhyCg&Zs{>7fLNZ^0lRyktccqGmHL{K9#U|S%wSC8fZQJ3m(^p-k5sMNa!d0#o?C76 z1kY^_m|-pyD)^0tr9wJ_o(JX3M_OJh7~j|7M5i2)dWD20otX#)@N6-6JcgIrAG(30 zvPSZ1=lMYCruzY1(5)ePo4be&CqW5?d-Gz&@$~BlW(fd3Hj3y6^Q>C9fLBls1-YJ~ zq>g5%EAgyEm8^Xn_zM$yW`yjDj#SU;1Az-QHx$c!R%etC(f2iq4!GzdyHv3rJa!I! zZ+z?dtfed9mq2~RVo6XmrE|8&=v-nkvTDqj8f$Zo`<@wGPgEzS=aKn>I)*g(%V(F*g24R-@p z`eO`i!sO*=&kN4S;NCpET8K0n#l+=G~vQ*c$O*D zt65LPZ9t;pjVP)ohSquNi8S;oum-9mLY^5zhX9dd#Xp*xNtkh#!*ki+pA`pX&ZhC` zQ4r!Ff8fxQ8cyr#Q|o2hIeApi;5@2^c!jDzEXBzB4=Cl2u7q!q?k73lja7Kcy?%BX zi_7NBZ#X)k&qUb3rY#0~d%`Z~Elz{kvU0k1t+=jzNGHsrx=LHiC!yA*I+*w#xgWPs z`!VGDIt-qhcZU(_^8^iR$*k{%M|_NDmv3z`@VL>thUndXxFDXSpM++$AV82qvucyW zhd*z%z`!~rLGYpfsyYU3M>TniGuY8awCr^8%YaWJK`YcRX3zfg<9Vp@ z!2rpZ_}U^(@-{iOcGl(aaYnb>FZBfH@ENzghgNwcOK&)q_&ePKXSWm%$Teq7 z(TQhS@JT-eQtlD9VQFOn5M;tYK@|c%`-7MLJvF~r?paQq^}^frgHv+?=ZsaA?->{p z3|s49Vzs}*(ex~JycPv19;N!VcJ#}nsu_g8?4FZc%t26$J_6fzwP8K_^NXC%0L-Rg zrVxIb{F>8~PbJMp>Sa$mmlVgL5HeG=zchDjLoYV9`$_aZh4VPFei+8Kp(kQqMTFC7 zK$OX@hMS@k-1m)9HtXHxwT$Nx1ape(+uf!tE?^WJVV{AkQius!@KI)5gZ2zrPd8a6 z2F%ARk*aUZfJ)Ln3y#33)>~)*<-zAKaOGQ$vvNoR{&SgV^z;0NYcFg zawS66O);UfESZ0v7BNV3eVpTdcJ<=Bu%uwc8{(H`?Hsv^YAukiN%2vnK9VJiC-FV{ zuuoIGbt7iiYcyDsCSqhsf#)%;FNm_c0c+p zK|QME{k87~luqct$5wb;@1#PLv$#$JW+**>?bvv@n8SGSdbXB>+EC|)YI4ty(8^?NWioCi zv=Eb8q}Gg&!b$m_MR^`n2{wzKzM-Xh73y&^Jp5*hd1n$!!?T0_U8A%bekBl$DC9sU zGgudW++Zj`9Lr184U77H!;eI5rcAH7Zrkg7XFZiQliTG;(o&6?Vh$AH)>_#xvS zk@^VDopHm!b&DG7nSA7`jVltG4}a%K-7K!LCrhS;Mb3}NtcKLiDqmMrI`EK$zsK*a z_fWfX&4qNA_-Kj z`JG<&R-(^~Rlh)W9k7T9Ov5jQA!ThwAa9W#KQoVmA!xCYkPC;~k9r>WMV<|LZ`rnO zsqK4J2NJrLn<iFAXu3b2zeDY`z6ZX!vyXu@p6NA*E>FdA>WJJ0nOO+rha1M)8u{tH7f$w2SERnBy#W7&#z#9=fwfkmyb&+rix>)(B)P ztYxt~W&i4{!4eJ}{`W-88Vq_s5egBJ+MwbfTwtrzJoe3D>idb6ZN{>USmw34Wf-9DRyEA57@{U{Gv-qp>_Q;41KTKgEz z=4~VWBe)vI7AdjzHG5XWqCs{_OzAWt07x8Sq=EIfy3I)XreoumOwo*a~eb znz~g@qd6WKAE|sj4qG!u;JdkK)roh$!CUZiZ0HqfYmcYK#HiNe3{GjN%YU_gNI#T) zCz%O%>afqy<94|ZB%a*{Yw(BoHa>tcdF4?QU@Q}92GJpV&@9Ef2Dc-`Zg#`1>TW}9 z{|z2;@+)Kp<-_wy9iLzz)eCO%hyH4%n(${;gbvKSgf@+40T@@A za6;kTy|s!+p^DnW*d>Tt=!nYV1k^DJZ&gcJuT~8b@$j1g$Qh2THi~4bv6jg6+6U6o za;+puq#nbUUrBD}ff+TY3|zaIRZbBCSY3n`+>U7TUy{hlsJ$9kbjmKOdFHC`U{h3Q zQz!SMQG_tRq>^brLI1q2)?G$O5m@RoDlgZG+rAIC-+ie*jH}4E{yNU+PR-$4j1cTj zVvN$(Pxon;4MWoLqqB(3x$TsI?{oyZPNSf}W2k!UJ;JJ{?)Xpgq#d6F4Hj9q!Si|Adw zsXVx%B2?s@{MSH1IEpfEVEC0zr@{z+ej8yK@)nSP3 zRjSHIFp}UDXqG9`ebjrxw+PCff_poK5{h^g8U~wPR0>-HzGpM`#!;u`UL+3o782NG zRWax!?BSDH#a2ahu^Xlt>LU1(BvG`5SuVmj#z%3PpDc_PR!rXd{i$&1Di97Rv4cHq z8SrPKiCq~qRp>6jEY4$7=lBuJzNr`P(V2^Yr`Qs8HK=W+B>_TtByUctC@8dW*SZ$_ zjjNM+X)D}>FO3eZZZGefD-a)Gd`2e*2ONV6Mjk}&ELxP#QHLUX6VkLS`yrT7&(WvM z5`h|aYi8lcQI?JgIM(gUM)&JvKL~@Exqs#hiD=C=eA;A~ZWybSa_lZ03FKC&?@W2H ze#HV)+W)jf%1^34SMxy;^&@Y4(2P^(m3#X(OSG5$v~ynx(o9~v)y7=LtXvF%5(OcS zPQC^~FQzOFfLxYuSt+a_f+Vx%jr4BO<`-m^8cGS&?EY*)ftB8#5xa=7T)=!W6q>|9 zp=_7O`ZDjQrZPLFE*Gmh%k9jh(6O;ve}~EiAIQ~oDPwK~$mn_Gt8L-EVmS>N%NHk0 zZo{@{ck##&Qoir;dXeoRR~5R(L!3Wc_Ew?W+U}N=^>k;Sebjm#q3+250B}d)Y*Ymj zbpU{SeFwL77)19FDngeEedXxny}lJ`zwNH%=r(#P;`1dD;c}-##E8S!aHCjU2IL_N z=XPSxW_zDbOO2N!kghYP3Rxn)5=F{Ru~^ z1ZCpKMMq5?U|=iq#36%XN1;FaAxgl#WS*vahkVvj%zpt!$nMp}`jM~StbCJ+6{K&0 zNcQu`yAr5Bv5OE`|1J-eS(BtyHRQXm;e%cMDMg3qbm?j+y{2lC;;bvT(I06})m~L6 zE~ikQw5MI4zkU^Etama%Dh}G=`(#(n)9IHC8Pb{b=T|^D3eJoZgH@r-JBSRm@^6*&A*N+qmJ`5H3}xv z?8C>k_aeI|F(EfntWetv5-tDqY1$=)TZCy}U=%5Z|DiF8Fi`PU5EaD4@o%j{uL#)${8a3}tB;W(s(g5bAX? zQgn2MVtDZpERCt<`>Yzk6=%w=~I+(8(H#F@> z$^8>U6A zqXEmtWr}#$5(gmVBAYhIkOBZmIGaKUA_WLoU=sFEww~MIAxv)4e)uVKV(4SCBOHbJ z<1v2F$rNebP#6Cq3t;@GcRl=Ch!&dkeWRD1?k2oU{qa9VSGvp5hfD*r0*S zNs_KVT~sLU2LR)Y&H=?4HriLdn-b!D?YYyuEq*pRIjFp37HGF2hXfh0?(m^2;lujf z)n%&Kq*C-fKykobNUp;eB&TN$T_;L4EDJ2PIWL_fc%B_R9n_rsUiPNG>CZM@H5Asj z+D*GpIP z20*#D!}%)qy(R#R6>?g@bH!L+vQv`F`Cv`%8AB@%PW4cfj)tr;GIwk2c-+8~hmhl< z`wSUy(#M%LY(V93be(|@>zWzG*;~(3^~RuNSXiL|&-T@Xu5KEf9Kg_wUj)M*|4xHD znpguTXCiX7!ouLQ(|svk(uav}3fy(w#fJHr8 zbCkE<2b&>7_HHuMnML_#|9DiJ{rB}dGC|6(mFWh_C2?eMi_@Os8Ps+OwPe2|xL|#x z{#g7mMMpjD$}-F#?pma?uXQ^N@L>ulpPjM+PmR1C^*{vFplJ*;u7E%dHxSB6$#GKP z!3q~11OiN9z(Sq@kjlN5^`OJ_PFRKZB(MZbfLPK6dCWB<%ou%(ICo&<9{SzC#i%mblecfg*A-&U1nF(pM^3GYO zbQ<%IVLbLC5vv-%AEOBUgd#uF?f8x7f*q>f>4W5Q&B4}O3%O(Mgp^Pz1i=d3ee}c! zTW8a2v+wj{B1}&2S=Wg{$!a``biOoH*wipez7x=a7e)USPf=>#2T;FSDXsj9X4)+< z^ktVgvSE|pN6~-|t~4X~F@ZDXa!u|!)n+4pE#6~v%q{PdLz7Q@%%`J^#e=woie$cp6Cem%u$fSjQW&YUKno_x4 zW@(N@?7OR#0xB?aC2#abVX7He#wP96i>Pcw>)a<}OR5=C1(o0iC9PTNwp}D;qp$;q*x)cMD=dlsaCY=}nc^(J=0X_f# zNofsvunB;T>aK0Vz69)ooN76MEZ`Cne;EMQ9^I%H!6}#ZOQv~R_XEh&g6f_^0H72p z_(%bO6=?5#gZ^tI;wyX>_$(0`?+`MF5m*C$%GNtS4*(kGAnpgFzHt^=7?W92^k}RtjbGg6ipB+ngp5XU%h7@%SP2Q z(iAKNw_S(<7eTkiHaz=j*znnl7oMB>yJX&_mQ-M2tVqq*wb)6~_8-OvYQgO==Cgr1%(*;;_d=9xC_7FW_5aWa?~FSOeN)msv6Zqd;FHO^WeD&+z*gbxO1 z@Hm8$SNAw>hL=V4EH|H-1$J9z`RB|X87Q;W4q!)rYipj$k%_A z@JE)p>i%OyTsA`J*1s)i762Ig=^q&il{%_`5xC*t`sKf-hG1Lz(}L*2Ue5)ig*1Vk z0)QDW-DgR-fl2-(4_>yvifz@!;bAmOI`}ajW1>JiO+I^)9wP3^T}O=#P=#d32)+Y z;mR|1TXjX!9SHr=*gyf9lxx@eYM%>k1Jb7vq|a#rNT0u>0U#+(XcrFvIDRYgEAjhR zi2BEKLln@iT988iCAfd@1?f#%GTkS`f7@hr!|~waMomp@zc4F?~s91#GSloW;rUBP=SWq$|=x#hC@=u z*=Dw*_xsb6beX;ui&2;-{f?3L@=XcCCnruZgdiaJHVAh$ST-%1{ z`~}S8^!E=)pD=i{|1|&64g!El$=dfv9RQ#?033?zAQ!h=44Ell`okj)umd6iF*xt{ zL4IzKSyF^%jkud|HGDEZ--N7b9igHG;)$d93!Cb83yel?TzPG1rg9dk)s+k1GCRc; ziu`$ReEym@^m<~&U`}LPLy!#|D%kqLH}r{~vljq6Xd(~6ESyeT)&vf|0wO;!jQ2n6 zr&BpL^$ zKCHc_;N~cRUaKX!a&C7>KNzg()AJi(iU|NfjLQLl>6^G#B4hgv>EHs`vnTG2gqN3G zGwH2t=CPiIjVYP;UFTf2>OFb}dBB%=E?nzR4s~bQgpRF5l@qPwk*`@sxfALjV9-b% z7dOJMTOp*A&PR7_GIXKvh@MK5TKP}lmTEIUPpF+=Uu$OEP*R;{PF&FepQ9uU-iM6{ z+OGsu%udWZP?d8FJ3ru7Cxq5a?gBOm(@sBkSk7e@(IhWF!a4VE13J~g#BFJ5e1ja* z>;}dH2%fgC@WG|Tu1qOWExb1U`Gb~>FFqaAR8%4mA;IMJiyy&fuGuWN3OxF@WDYuE z&OmrxN$0(L{i4H0qc8jME%mXn+L7gx-w9sUFd<}Oa&xj#?ob~Q3AUpTJML)gXEu3F z>Pv*D+$g*YAmb4!UU6N;pADm5XMRulpHG-t>$M#?jsR0iAW6U`YEq-?CR zp6v)-M{6u#NlN||xk^2{)?ykEw(y6>#Rz)o8yg-WdJA-k&>I0Oyw-EfSU!CHX}`BC zK`hhY!L)`^ix~$-M@*{eYNAjT{upHpEP2NW?2k9yvIQ3B`>)TYETmG;=)oer^kTDSSltF4 zh0ppuATr|fH$stMYX6V6DVjv8_uk{MS8T>Jrx*UyTgdkIBLkc;cz9a@k4RBe>MVY% z&Z8)PDWVrOD{{c4Bvm-Mf#o^dO9Bx?4*zC<`DJ%VTGgebg^@KZJ5Skp`QuR%8*hQ# zCxFMquYRyF_aSjL;sIs6wuX_Fa>!19H_0z6D4o=rs}T~i9-vix-RFj7C^{hIk^N=m zFlQ1PC9T$RY+@Zt9qPOtV`>P9-b{tFS-;l31Ex*wK;g%XQ7LMitUSC1n5eZMWP;2l zirOXUy#jOl&r1&7R3sj2NoBZgzm;2m{ zi2TesK7Y2?30f>_!Vt-s*5`v93Kij#_W&8CAD}w6VM6CWGG?6#8A?}#4A=ykNJN?k zF)GT~##ojV@QTC%2JB0$8H6s@e@qTo#<_ALU;WH00Ul9L|*bK*fVGYd{K(uo#Sb)tTARs#a414=@1Ty}Zw{z7>yf{8l;LxO8? zBf|E}TxteUbaIQB(>H)_8r#Yo@KJ4ex!CXun9Ku@Pg%yuw2@`S1pADULp)4X<^n}1 zkl1eVo-H6~#!N=D2?+ed&LCFcjr#eQ&4@tIG2;G3hxZ@gFb;|U%sWume^mV20Jlf| zM*_Z@;i`tGkVvF;}DL9y6%M4i4LA=M=j+hwhHqj zTzE#um`yq9CbX!{eOdJfC|HTvUkxF~qPB(}Xt89MY3Pwh**&FWvT!$^0dxw9B3&4W zeR>B!U*>`ffo5z9!s&eG(LlfN-y3C%K|lWuicCX8P4j^LSh$n35*wP#lAl*kZVoww z$FtAj*FA^VWVXObRO`$^$CG5>(|5+5wb&uzWM-l<+E(hiD^n!4y>mvDzY<{U(v5GagN;{DBrDA zshBP=tDSo%dkjQyXMXmy*h6?C+^k96S{bG;_sJ)$S^oHW>I(ZxTF+j~EH{BHuE|Bu zC{_Xu2bF3eEn4>kwyAZ`LKKciC?whG>Ev7u{NnfxxL7)Ou~%V;f=eTv3n)-v3Y103 zjhXk$FAO|51Q48Ws!Sb~)bv9N@%sS)@hJON3jH5;hDywf>y=4yU5Twt<>R0@;$R8@ zgSl*cfD#ta0|RFtyycorV|nXz15CT_ThRR+X&HMeW4(9pAg4upXQ`Na_qVmFSkGF8 zd@GruJKeU%eDaEK0vBX-nHc2ng@P$D2a;bS){8<`3)MP~pXFn~`R~Jc4!5;t z&xm#<0)YnA?NO;!N+JwhAosZyypwzrpK8em zE6o&K?PU^LH~wWJ;hc0Tj5)aq*l8?=tu* zY2Pc~h7B}^6r-~jZ&w_$a=J{-J*zMQT2|MBVdv<1wm|T{OV8&t_5Q>+ zUg%SW_Kr)t-}&UY_5*sWo$|V~(#qL|DiI!2&?tyI4+T;lK+OF0Sbf_8SvV3>{U=EQ zKN#|vT>u7_-wi8;4J#Tk6%5OA)LS#n6Txo$c?rB?%B!VssHXdG4LJei5M;LbH4~O_ z7hKZo#1pcbjmF(>6}T;Qu^M3zYkCN0iy&V4fSqvJte7|35Af zqKgmoqCo)W0WdvAK^>Q3Zw3GWG3g%>2LQnA4+9{LScg;3bg7~vt}gGw)tNh{_hg-ZoKa1qRF*ZmL ziZAU3-=Z<%Xnko^$^D=#LK8_;zsUmd00IDjpJ3Ti z*_~EZz|cLBqY*Wh(_mIN?L_fSV|qba+qg&@<>sFT4w4e zARsi_si6$8bLG%Xnf@AXEfiMzx^gr&9>I}FX%!ZB7I~4w$Ix$a0r^{&A{X<6QH+xD zLjv;dd^KlVM8!%h`JQ-^)(k6sbSbShv(iWCoft4~kV>s!+0qQ6f9E_zppX~zRJxYI zEq4F5p#F^^!I;|oq>lfOBLAH{fb)Q!<0uDYyDgyi{*yRvI1gh0?4{O#+16PXE3pkU zYijQ`VQyH-^l7*CD$7wIftU$bUFTJ$t^^>P7UDf0ij=uj8wXmsIUGmIIKYuu(U zdSWF{)mRoNp> z{1@8awr)t@|B>O6{t-bi0Ptl?3M?>&{6H}@Kqz;DhDI#}x4i)K<&u* z&8ue>kPCqj3bz2;^NWMg+_J#;ja6SO{s#-R+S^+Zx-inWUJtX%j$?YXx5*Y+(|E8I zH+?&V7$VHw2}+8my7$~x@XD_y(_n9)wX7cDbQ##HKa-umvmJow-zZqu^%APr{4m9k zuDyA~6|vf;BC95-J!DV)R$Lu^BHIs;H?Q9X$}s#v8UQX$HH->2&HViYixjDLZvX%n z74}CP@Mvf(vot*MgW3l_3Jwfc^ZzJ~^d(A4hl_bScY|~PuDdfQuc9XfyPthgs-wOA z9#b$V19eEnt}ukK39gKdpqb7yDy9etX@Y?uK~e#H2PEGV$&zjb5GDvziBoj?NKZ8Mt1+hHS@-w19@IfY z^Y@FfR0Pc^AQF-Oa5?m(`k+-s?WZ1k!byKLqhaz%__hU3HbXpFd|;DsP=y;ON&&61 zCEw?>qS1i7P$v@X;t9SPRhw}6vJkJKZjWjyHS0@RG^Q zNr1f8#0;#-ZK$N*qp)Cldi*Zb)CZF~@)t6%eC>DF^ zMm_4ROEO?Mji)U$rY_NNKEwgO`fP4M6>^Ke#wW@A)RdtHn$K8Mr?hP*q=D#FQ8@c^ zrL6v+5k@2n%>)3$tCmkg+5~unmi{~HKn{ZfG%5*me2Em5!H|Lf8H|75O{hx%VelrX z_w(Hr94Q8ak6cDb?Qu5jWZZEs*0j>vC(&Fwumn!5i@I>Y8sf1=V5+7x`qB?go+RJf z{HK&#{HyDLq;m9+K}^lKvgw@ZE}t!pD2%xzs}(=zWf`9Gmj~+B4ii8V$V9@-mtTyk z<7wRb&eT{iq~J5r#AW_+w>aQP(IX+1s6Z4Q4BzVTGjgoXqUV9o@Vp@~b$?by+pq+f z;Lbc0jCvug1YCQR;~*QK|02Fi`+hJh7;_mMOEX)PMAtXFppPoe2{s5^2;z09r zeDx%$6VQ4vN2$!(^oY60M2}&)3pDEcpp2R99Gp|;u~dWqHnrSrM`eL~Na~(Et7bzf zpqtVNpa$9EPu!*zB~AbSUrWKpwiXj&R=T%g*TX^?ZZj-mT>JS58EM0OG2y;cjw65aKEj;&GL~>;d}l zE)V?w!4-1u_rIl3|3QBT{uy$V;aO=@P|1CUN|9RD4}eH&P+=`%L3$DM%H7*^LKnVV zJn-1S0g>8mz>AUaO*n*SR1%-zhc5Oje%or4Mr}#eP$&3Ufv+-b-#I#w-}_}p>2J2y zuVFK(E<05e24A4xcR4W?K5_27s`~L6{0sQ>AHe_E3^xAi_J89u2CP+I|8Eh9Co(So zh`77K?DRQ$3pjzGRfazT#IL~5-3uN*rX?C3GdKsz7Wt1j=ZMW3yz{m=b>}4R7+JP1 zY$o@ylY-Kufh|}lt~TrjDm{T$s?W9`w+8yvn(?)2?)*E3-2x2MWN%CBL_FiC-?*nfS}a5CLP3Z zJT_Ovg2$$b0%*HYm?dmRUc1I!MAt=z#IQT9fI ztzlrHcQY!a#2`OYOJ)Q(=tQ^r>?z}@maaE zs+u>7gO$#xK^n~tPj1(H$}N6K z2}YvYLFBYcTk$5wEjj(IMKAq=S*Zf5X3}V$5t55=I1ab*MVD!hB;_bvp6pr!{rqNJ zm_FbEKAqR~C&~D&EWN=-i>nonV-Cz5+DzOsP9?+#F`U&}L(wxSi8vxz_}Q5DigbkY z3OnOx3lu$?fc_gYntkU6aBS;LhSD`=pMcb6DhV`YmMqNUDVAnd#ItYT5zq*Ib+4kY zPq`IQ84~FgmS?C19i}kvrjn>;EoT=y8$LzRc<(Zk=n(POKZx~KfDTf!E;nRQ>3v|6 zm$`YiYNIi+$FwP9&aW^kLD}m5emNfDTh)c~lvOcw_U-aO33;zRChDqSF}c=vRzNwj z&!z=}*(kv^!{ORoivL3qS+`g!KQJPC71wXLZWcK%KV7L=EFlZTEStB$2V>hsdb z#@jRw0dw#!T`p~M^gS2Ps#%cb;Bh`FZm2!X(~ntt@OIbJ1tqxfMVF!t>d%N}^f$&l zY2IQ>#?e!P7;~cf2^53(5>95%YWAx3UZhXmp32Nve2RpPzt~#^?$%+q5HUWTG>NRk z8?ahjaQdOO_}Uj8D)TN`Dns32Mogy=bsx6SkFMK;(+|`VpU~LxgLpq6n5ZG1sT@9&oyvxjdzlF+l4yUlw>u$OTLf*gel_bJeYR@ z(%RRvI8b7`5RUUf@!c+6gkdIl$wAu@9Y2=t3ITT-lw?x0D$b^9`cJPHd{`dMz-|g7 zI3}$ojJ4M}qbu)LA&sipq)a4wnn20!+#<#Lic89}Jf*n7BPKY%PqhkMpv<^1xo4*i zS}Yj|4}8^Q@%MIYaeCiOY>Aa7ZYB|K$-O zOkxJoAP-MLxh_uB0wVu}G@z9{D+aB9I0r8?NCOC!Df-8dbAkdl~n}5Ow=Xb(c(Zq;20jGF|eeKKEs)AnS3iF z3Zt#Sb9(9chBIZ57q5MD(IJZRy}_?}J5k3i8IL5NA`e{m@A}doMzZ>9@|ThD%ya(> z@qe&_zJEh~tStP0b%C+|uiGGJ{`O&Ku8_)MSalOV_?uogZ_oe%4Pc|D?)i#7w2@j{>Q=G$Rov%@e0U)kDcJXP{1`VBu zC!V|nm!8PGNuV|&u0Voj5(eCW4gZ%tgFD#om)iu4_K|0JjzzKV%5Wqu)92xa3LIO- zDJEO^3@zl=425!41Bf_gkv6KVD~q^}>Ffo4$kA5tbYei^_5xyUI6zFXDw#; zq2=%t~2k6L}t_`$1wrx9^*b_`_W8zF~+cqYe*iI(4ZQHgpv2W)6z8~Lz*Il>Q zS>5Z@DLi{upW07p*OEObWDI=O%Uc$TlQtw;_p~Plk?I=k4<=4&ockSFfnCl+pcf(k zS#!;IZL%fKcO!%t?Anl4VTWmFSP%xq8KZTL${(I*(D%=0>#e`5VAx35_+u0Q=m4Yx zEoH5+ma|u%_0z;0{40X0aO-z}u!l~sC+$^b1EkC%WgQ2Kp=dXhhwr1lt~Nd=GwF;z zJpFL%&qmnkjfJ=Q!&=R(rZ-nek*fSU^@r#A9_&M3gOrKYoYS3j>npu^dNVTMBaneA zjXdv46N$f+pnBtR4+z@83Epxpn()xGo?Wa$jHUWkYWR^`mrU_ApUw|U8*3AeWfb?- zAjY;tY!1s$#RHvu&3THyr#Gehg?$Y*vzwbogwmj3o{R-~sKOd>ANC3>u2q*uG2!BD;~x0D^Vhk6gMRaiIAO_0p{w{?RS-At)QCqs04fZvBdLiY)g9U#$+!?;MK3A&D!qeBnu452p$6HtEyRNS{{+@S}iR-I?oZ|p7 zUN1LEDG#|tk~p3O&N`3HP2u#4^tCiy#OAh){mUdk8jF{>T{2ecB$m6x^@=6ZPaan1 z3y%;kp#*l1cz=G16_sywuGE!c>KUMB=&4^w@9cv9CW(u}VCid&$SBQ#xVx&sFFL{( zsiFd2J#*;x0~2vdnnb+rl1m=66WZax)rc%u>-|&+1rY3%*Hiatj{qY-9C6d{S?es2 z`8J+ka^ye4F~koF8^&SU--}kJ$~|8$sM8{CjKLT3Iqcs|C$Z-f%8B(eX2ut|yxCg- zg@3JIBQVpW-2DIaxIF(>0#axGKXvi79{@=5?-@Qo`ae|z;`;cR!#@_#^m8>!6#y^< zin@=g2gJ7pqnMTzfTpa_n79rG_wlx_aFF+IhbB$j+ z_kBVy{e(XDAJG2=29(9C>)*IQBwhaxXn>D6p!RPV3lRW->r3(Z{mGn`VnJE}I0TH% z*@U`OnZ*|^zt{XaUr_{pW`bUH9&F%cOGouPIN8f|%A2#R`9@W@f-7*WOyvC53$Ia1 zMU=vpjO_+6zs(k|2k#0APeie>-_sCAih)6y4DYI?9sM(MIt|S9gme7IEdLAUzxrJe zaHK*+erRP`EBEyRHnF0)1DyEuQ|WjiWFR5pey_DspS!;{CdE8Y*{WWou{S)I-wgxB zuAx7b{g2|Is3-(7gUzZC9=*PScEItq7n5C^kgy{ut{KC8jzc&-qR1gL+s49P6R5=| zDK@~X>+s`|y4EiZxkbH_jc01pOH}TJG+`ksnKHW2gW(ToVcwn$=#@=e!Ypd?yW`(~ zG;kaADQn-#-r5}AwEiUXRm!$^MibxY1t@oaR>A0}P;~!WsDGjA){Dc)olTLhf)W%{ z=3$yduJYoQXIA8F5RR?S{3gXlQtU6FhGVw|MI=*=PZY=pC1B`*yXuF>_8h1MF46#(*EncElG3-=Yl;{;S}X=?5Y>y?1P(l=y*K057_ zW4S`?qlo+=?&m$(!i0|}NKDzzEh z#D_-|wZn2D7f{lrUI_Z}f}dtfaR}vB$ObGg4F>%Hed71IqR#PkhzJeZk3o92##~ zsRer?jxn?GH2dFIP5FZqMte3}DV42ajk0(mbH~?jQ^$-LS5y94U!V@r-kjgv8l%Kl4XmB;3nKZ1U5rAO5Z1;r7kdsSS<0dRy0 zg&3f!rSW0rtB63Malq%hr$ErOp*ZWJ-Z6(6cB9Q;Oiuwyym<7ga0_sd3DWDvZ!8j< z05tYc8Jfj|l`3K)?ISUOg;%}dPOf`ESdQtmFEZ?t<%F3njtLgzHK0D-0=Uu{!mzO0 zf{ZLK%Fb+LslTp8GXBxb=R8B=jfUnJzOosyiOBIg+dk;3zX`KmeDEihW0mbb=WBBg<;dvBEz10)hg25db!e9|x%<@;wXOFLOL1!Z`k>lS=T{Gswy==rxAH zv`Ggs??b_KfY*w51Vc>svtos!2S*D8>wQ$|UTK5>;+M%!?;Ok*GQhz7Z8{X6RV~^1 zE=BC*1BRyJ?Vy)PQxTSl(O9m@64~{Y$Hh=Pn|OD%j@MpST^0Xr)CJn<#~_I@^c0#_ z0gNZe4uWwtY1_bTQJ~MUkPbSfM!>ipk~-ePN2B^4f`_;D=yKMa_k~w!&m3p0CU0*E z{CB5_taUn8sU({>&*!Lmk+2E$qBHi04+1VTM)%9qQQA!zl8h}De+OL*bSoGis#!DY zLRq3i*2x_7Z~lR}$T-=>c*vfjk3(2Lso&VJ4X0!&yi+4kb}O&ZL49@LWD?A{=nkQV z0!0E4?N-XXG!u2H3+9BPru#=`4U4AX-{F$D~$ zZ3|eH`<*VYwB+#qQ}-|l{4lBHVTDo~rqUME6Eo&Q`qs{1yUxty2k{Zsd`Uu=l_p86 zURaP#Y35+sG~rONKYMz+C<=pi)=p+gQoC2x3S~cvcw$DbZZC#4tMqIdicB7fr(bTGFA>?Zu2qLn(0z!WYwVrGcnsy~Uyb(>A+k?odb|dxqk+dUI4i$b& zD^b>2^qKy`Bb83m(=ZgZT2w%DK)SeKBj|=vDWS&IH$D)|v-iyyp&Y))GD$ zNCr*4_uF-{`98E-mv+lU)^Ra;$VhDh6Fuyz;D8+D7flLU!^wF#-G=P`gfY(o30cyV`gqi(GE)SAH zLU7~&vTLWX9Npc~kMK=M{H?$MjI)V?mj{ot*sNqANl zFzC~yo(X0Kj(KMLaL>#+F>gqF+mXHQ7pZ`y!aFUC$snxlMEg<1%S;iAOlE#It4d}`dobp z&UXjLmG=Y_MoR?1xlYgLdemgih55%hM|`B#$|r}+ysEG-%>_R57?=)@HWyE_(uRx z0P;8A-6=5Jzjr_`06?jG6Naw;RS1O$@a1n9{1xDHeg?W206-*0cSY>_8wOG$3d9GX z3ncqOlWYMRd_Up+`h*wxf8Zfq&*VZ)IR253l_1KgfhXjGKZH06ZX*!W_uvm$Dz?X9Di#2o?H>HZ^uHsa&wT;` z1#p`aQG8Nyh%NyDK;$p^3i^chFX|3is-*7!H%|1c4k8+%dAegH0Ar?0-KX*82qF z@CoGXFAIch6M+8wyZ+z@Jfy0jdHl`u|L5Wx_5FKmCqyAU1B;pRfZlI0s(RjqMQ{i+FlS|nEu-Lx|pvV51#z!;-xK)V# zE$=@rl2+#M?0oZC#M*yE`*$k#|4NUA4ES7G{t4k9{`=pOW7b%w zHe{h6!U1%4^2BnX+l+Jt0Ei-hgDC*m0WcY`@;T#|0R=dVl0*8R>_L?QNCHSmKvV?7 z|H|H3crl-R3uF!iz9SL<>;PbXJ~;fJ6o1hW2mr_6{>g<(?{gR}O)xe3zsalSzsc)o zcUm=}ajtWwwKGE-T`H^-hmL9M=kXyZcm4-bjwsF6V}p*evI=MiyOzsHUq!3FcSrOF zKD5#+qz0?3(<*M0L)J`OJVd>mXCfcrOB-CT(2}kil_lcBb7P$^j(d>If+;xnEA8E@ zBgEvvw2!~heIl-0@v z8zjL4rAYc%Lbrd2p57rn+5x&aP|auI8*Ow-gLqA|ovMzPVIpSX)?IMy%+9=}a`eem z75VotDJLOwxIwPd^~JX49}vS1bS&Q@Y*${&Zb9A5?Kmm+k$Ad zg9lwxhu{2QidUbp*qr15nJ<2xS~vtVRmg0TX~=W3<);<&IjPy1F~rS$X|pEG;c0 zwMesAMW={1jy4XC4viMiyU+Rb3n!>w(fDMYMfEN+E}P4PzX_%}1=+NLFi$Dz6EEr& z*|uHS`=#|0F42_vjsnVNSGwxvP>n)-=^V3AJ*X$U_coyzj`=^{EF_ZOtMbrHaur%0dN%+i z${iHz#Fd5jcI9x-lbTS_y774k#2B0wxUG&2Am=Xr5}kh5HU}OXB7N)JtJ2J6;A&rh}*e5A4Qj&|hIGkA9>`_0oV^cvCD zja7X_f_dUES>NJ%XB!tRd~mwzCm7Ijq{N1T8^~bT+qltXS+d3 zeiz?Ab1$sOZpcttQD+Y#%7I$FlFnT*>N${fI>6GiHq9hba#eolHBIRl-wE+_C8Bzp zmVzoFMj|pH2|)e>a_nUEIgRTin3?#=Yr_BX8en!J5BPq?b}|5XE@PVR6EGC^PN7?S z#IXIHoJ>M*cE;21qMUgsqQw3cF`5WMcjLl6K}@DcO+&;?E&^cC^sQ}-l5fXg7aTgO zas_5q=m5#jZi+DIOG;Siz|%ELSwQIByM_t;RjU&FsJNkoA5Qlo^TphKGRVZ@fFgOpE?7<*e zm1BcW_e}|Of5LJQhcrScp?NzL;({1ChmAKkt|0pD5UW!>jd^caF~`S1KgtYVZCAvJ zTJ1yGeH40H;tIXxOB6)>ju&w5a?PiEe9XHE2arVB49Z6IMGlU()3$(JeQfJ2B2(|r z?ZuwE7kciC9Sb*+i_mCSX?@d$h`@>2K`R0sz}?SZbA?JuLPfXMtca4d{Yh}*V7M!2 zAQGpP=yknEYOnWR@FT=#z@%!o3{>|Ht&8o(tF01#vc0~!u3)?JIptFMq+yvT@R0?i zp}d!G=UhEWlq|HuBEJWmHuhP=hUk7(X=-N?(KJq$Of-Gjp%9TvW+;c7G9(b&PF)Pe z2sb3^VBRhFi(~0SuSKO^N1E=gYHw%lihaz2F{H&nHXptf`LRBofznT&?}>3Hg{Gk^ zQyoPv;L>L^sodxlS_=L!?jWS0WNw0=^pM@ZvCPG1&fa5WS!SH#5HtKD2$2iW5ynjRf?Ds0C&Zt z_U;!&T*V$j{1Rr?!bGvKM48i%CBtqZAgh13jLwu;2?&AxhF<v0(oJ?a*J+f-4MIvEFxqv)P{SW2K>H6soXgi|SbjmO1v!2%mY;wNRfouS^u21!leX8dl zg8P5e6LV<2WGU(kgf}`eMP)5HbzQ8Kmzi-UnTFanNYzx{e3R6U1i%xE9;q{yMr#zp zX_FcQd`FfYzoOOM6Ju6hW@G#kBkhjySCoc-IT0h*^!1|@_(xUP5WSRMo>;ztw;lN0 z(By#)QAYU(BWMpoh@WoAV?{aycDI(bF2KPmhQdNO#j@zE=!jN-tn5Qq^f9^w^wXme zc^h|Ho$FF)0jq-Mv%!9&3u$*TT_CXa9b_BG9~rPNnpF4CyX$kt^b+p|>R#QW@$<`k z-?bB4y!*3N8z-7a5s&YeDAo!KBE@>jYN*gz!@|eIAdsW!F+Gbb9Cv0=$ z@LqvDrE#l(3PAkaTn;4t)YCs~`#c z!}zx~0svqbwr|=6m(=6HBv@Ux-V3!pheA$6Rj0n8g4R4jbvhR7=e#mB?`Q;ogoUDh zw$_Infyg-QqPvcMHn1_c&?5$cxB{9=eyarFA;L(wZ%~lbBPyL$2)E%(d)a)~S*$UB zI-1Ii3v6i~lJSx{d?hgESC%5FvvJ{j`pu8JqK`b*@I#@2BsP>iHv$p!O^a$W*Rpyd z4Zk@_vg_^1M^(b#>9e48st|Vi`lBaa;=R00pa7sffX}nYKh^Y4U*KOP8)H}tOoH#9 zijT940^mk9(-c4gI)FVn4$gkiNShshr3KZYwfcvs|CJmRK&=PRIOu}9fR36fIReuZ z$7l~2D5Ky9qk>NNlpBN5Sy-=YOhPROAa%3DUTdI2SMcW5gMu`JmPiDF2yTm7m#bFR z@!wdg_bOKHpU)G#k&}K%)WJPbDy6@$OE~W6Z^Rg;YL??gi`$f~#NG}1+JASpQTLD6nZK8kC*Irz;PB z3kWgsy{q&aA$1g#eK$4RD;01$Qa&cde8m?)3-Yh%|Nh2{1rjR*poTil$1nlS=F-bx z+0=P-GA(ti%p_2Mcrzp+;J8P^bNGw#2oDKokgWM8OTnVpynln5yW&@-z{UD~Y?;D( zLIKggbQ3DdEq1wibsEccbx}a+{1K{N3y>TwnsFDZc!O6aG9R1OG|GUcs z4#xZenAqb0m0854;7?usU11$(8J<}Il*keWfy0>^4`*Ks+7dWN4Z)`KdzPPhoc;~m zhN&=mRq()K?V2j2a&X0QH0G~QayHH{EsgQRYv(YT1c048Z{xD}ob;@!IzyT> z@8Hy4)Z6l_X%XUkcByTar8$Isc+4h^XSMmPM~w(>;*I{*BQ#YVa2s%g5V~zY{7~@+ zlyLik6se>yFcrxvM2y(di?=@tfckLslcpnfwYef5EK937)qJbCvkD~Ex3qQM{J>J{ zrOL}&AVzlIi4Pf70Co+c50ZeEJ1|rmd+O12z3wYM!WdEq>Yp>*?t}e@zsfCj|SwX%U;d_g4sp;VC3u1r3bGLyE4P? zKu*8g&n_y45@R$3TZxu_MQ=#6rbU|!+Q${@>gSZ6As&yC;|$nweC=EM{1@*%`b zaJj{X!n{HH!b9iF(;B^uKM-U0y|ey!g}Z@?aRlXa9}6qp7{*XEF#y14LkLG~XPT&; zzY3c{Rq{?1Entf}TVg+&5yDCpGl2N9iIuiy?%Uc}-%9?z$^v7!NE|p>^WJf4+1RKN~CKIc@kr4=NhE$x&QeacG;`Nkh?9&m3vj({8;RCCQ~l+9-uB9)6!(UYQj zK&k9I<=NFr8x2s~0uWyv+Zh|Q>MejXcd#m)%jp3$pHOHtI5Os;U5rzakW1pFI2Aps z?od+wYRb$4Ady-9BI}7Ks92h)9yWt3ZD875Nnp2wM5K@LI^m$4P?AP_w<`ED-q>8w zh|Z}-Y>>-c;`GV+a&0Zybt3ShmXrqP)wqEU+T_sIw2Pc}#11*KP42k2rw8cV9`7@` zxeY(*a|OT(v`^)3jY&#{dTJHq4>}Iqp_gX|e*ds=%d3(p0T?>#7SlZ2;8r4O^kbf2 zY6IHe_K|+b%{a;~T99BF#45k`hwa$VcNmm`<1-1RO9!| zP6>nLKq8S$AfEH1x;R3AEcd0vB61 zGkPaj1qp)m0(G)uS}u6mys2P*Ac}6N1(HlYWan8^B@}|TbQpAF!v&a`9T#(*k~ScV zYJOqXf7@H&$;h9o8so*^1?0KLSbtdQhQ--@8uO&mIwUi&-zbDJ6@Igch75cZoyc7+ zKayg?Ri1n&IzPPLAF=qNY+G|0DjsZ#dX7a*f&*uX@t}MPmOr~39m3K3A@xgoH4mX{ zk*vCpxmy~cjZHb_0zd=gaj^!gN1#A@LdWd>5O1zeN9-_Q1uzd#qaG%W^?EV_n+?+K51oHEIrlE}MTQ$~q zOQg;Cp(nQEyj6sjNQ+xO@yWqRcu*~L-HIX2-V8SYK)Y)8yBAzqF)}g~5`KI|zgii7 zcc}EdZ{)QDu_jyH0_InkomXS z&I5rd$b*zov)YpMG3v(h`HEczTXdKN>kV5=ZDbqeysu9eJ`6=*lQ=3GaSC=bs@zUg z-L+Kpp{{}cryS2s_CSj`u#l&QoT^sGI;@7RH~~87kOX*u z7_o}wgi6y+R>Rzvs}>YcBt^s7FznQXW&Ux=#hNTf75*P-^b}YyEhiJPnP^M`EHUqi zewKS_-3>B~*%z-#O>sS)@2U&?oX(5pNVHZc6`H zWA~M5W;@MMP|^#F1TXw*&1@u#!7opo?@I^q^-?_Di_tAk(p1S7L-w;E=UCq)Ke1)j z_|Dbl!{+%hBD)B(`%!mW^lEm@He8LUF5S!_fUVopk>0KjfIN&NiCT7rYAC~7)H%ew z-;MZmzcfHk2y5-MD{%Fu_w@(%89lApPc0q=;=C;MQX{CjgmtP9Hk~sL^i~GTI$S6= z>7PmZ*&-(Jl(4U`Z=%9q85pXNZ(l{(!0Z#(LsSahK_F~$LX9Vk?w<}b1Ke-D@vK%P zKH_f}+>OOZ;`ybka+B_8#dMZriyg3Le4kpLx?7O+8L`p&dpo^{zb=%;_PSr#JQg*7 zOgg6oDm*M5=&#nw#b)-i&N-4uE4-m)ux8R(6VtNy+|F ze!yfUIlVtA=rn~tm@JUj(7|oQCd@dJPFskA3!`MDZpAc!94b& zI)3*}^6Vy5xsTs5B2|3Z003QEQ{N}; zHuAb3o-vO!+600?Jl!PDEk}gQ#PvGy~w!% zJ}t&l<+kJ^{x^5*cUX;P1FT3EEhoP;ey+@{Kv~FvW1qKK7t$O6T&7FhqV3(}8*&dj z$~-KR+qxf)tv1y>Q%tqCLY;*V0w+lKPM&NZ33g11*91<+wvZOk_A61Y3hP-#-P4IT zNXYFx8ZmR{sL?t-b2H8bY2(q^VuWyfq}ig}YU)7pw^HxVs$K^lpkI`pylP8JGAB~!lR!j$)=kEd~g%P$5X*^(Y-zX(3n1ZMH(g7z;E)Xr+cRxUZW^_J9HmlQ|g zXA|PXlwG!ehcYeK3M>u=x|V2XPwCs zex-dQu#2I8$2`MzMpT(#y^FThQaBQY?|Dy!XiXHWWy~q}_UaT^bw{jLrf!J>N%q=G zWJDAARRQwN7){_(U+1SscX*L4P;a44M?!L}huuM_2JLdc@nt%3pd&AqeysL4H9_rn zm~bwow-$YCTpZFi=K0^VLu^8PM$VUW0q7VO@J^`wO*LIYk`ZB!Bf_IC=+75l#~H0IT1=o3ZJN=W1A>XYnS^I!fg$BF$gHOv=3qw|Ie4 zo4Yu5Q!DM+_&gN@IIy&5U6IVz>yKTZ)^Dv(%^O~RKs;v|fONq`u@Py;u@B zr4$!c{jmf7KzbOgustl|`2gv+ggh3#t5ScVuMEj6rSz?fQEacfB>VBrURtv6!yUt+ z9yO`W1G;vwii?A^@S;fog}uVHqyV^`+kekUgH#GAcEI)E`w9yNK-4)b0eQ%MP3B$9tkj zgDM$03Qh)MZ$MZDDPuhy7x{U7?vLqtU2_v!s`#SR8i_BnOrfs;hLitv9WP{u&3Wxma_?-ZY^IhO4?OVVg2lmj1_^O2S8$9XB|Si~7=N z8r?L*1xJY1=Z?D65cr2XhuS?(4|r)VihV~4*_JkO9*rQXpLv1XfrX8@W)=38&ggFr zmEvD&2s(p=3#Q|(c$o}apz-JqwjpMD`$FOgK#UqzE?)$*!O4_;!S$;e7y!wLNBobv z;DGk=n8EddOjPx#?AL1;Ocx@*h{k(Yke4=g^!omimr!3XyZB4PTqpqaIy*g!-Zx(m zH9sD^FPj!lY#M=W4N3R!RQ4L$u2*C$LDzUEsN1$B&;v1%Cv89Kp)``L33nDgccL#%XH%NFcf{&d)U$@N^Na64a@ch?u)b;f zy^Zolqp52uf)eB-gAVp~B~)u+2O`akIKN=-BjPeJqDBJZ2nvVtO#~79I!G6nq$^L$ zuH#WHaoBI|$c#tL!&zAq+iCz6ju^g2AFHi>!BbG#qaz2~tSvayqhnYe)%R}oO$Aok zMt-H(#L<&J$J}ZlrT(j**5bL576eLbIm6z(Ec_kmGM|r?SnA|HY(?4c)#``(&u#Td zTGwC3)`ygq>v|e$klm##Kmq)bDRK*nr5hEcNGtKC`U5cpb(+kerMF)6jUj+w1d>FV zr(n$j+4IYtm?5oso?R&6C*&(}Wi_d&wo)?8>*)f)Wsy|yR+^F1_2W(!SN4acDK2H%?@ zpmumHpzSgJ>~0>N__=pq#=yS#_|9+9650SjtnDBL27mBGf6LZpLfhJ>@NYroEl@F3 zpv)^Sz4d^YJEs~p)7je0>5t4<3AESUEZ?g!znn@@L9|M)kzP)EL58SQbi#t*Sb$^Du*kqcF6OJGqCuJ5 zkJ@WKz~?;j+c;@^jFH91)2<^~s2$-b0o||5MIBX0Meo;9bI!TUU4sdniDdUDm0SP$ z`YdubARcD3h~05!^?Z#G6X5ue?qHHk@Y~~y%r7Wg&Ty{#uWsM$?PjJDl~Fr=D$u7= z%LCJ@+OKRiyYSbQnm!tTR+N;?Ts-FJ@P9buPoy+BEz|SV*yVixZDKQS2y&PS_*vAE z!shu#PtIr-)`h%``eik9t&6gv&Zsna_`bKzhDaVzeO8ECP1Z|NjK5YBrL=U$`{pGJ zfWPIN%uh_*ZLZ)wn?Qmma%!ay4-e89QFF({nAo&mIj@#a)-}jNb>HR zZM*0b0)tx|<=7b&rTZ-L1^iFQFE4LSu1g2bh~cqkY1a1&tGT8<@=n7g^^bGrye2C$ zc34`nY)V0AJ^o))&h66Vc<7=_ucT^6@HSAzl=&xZ`F4rL>6GUKz?1^X;a{QOE}tZk ze##nadkh7H+mo@XuEaw3)Zs(O!FBu;uVSJOKn8QzWOxa_$&H0U7tobSeIu6X(iI z(x+b?A|xbKBHDM}n=_pA=TJ;C)zbBBw1XX*U3H>wvuTYkm6783cES~gPd-|t6S!q} z)!_Hq4L?L9KO#59_#YKbg9&??V8XZHklS#qGe7|BH$+?K6(&JSa+u0S*W-EFWNC2y z@(R)c+Rc2|F%~$3vk<{4vc^^!u#ds~pWB|hX`?#r^~>#i$eAGQU^ExV$n zQ>>VW?WoswHwMmAS>#;={P+!>V$Oos04;p|)1q>gBG7`tBR}S-b`=duii2Kg;ZKb& z%i0&_R=bDc$3*F;bFUQE?|Uf~0?d^Ol22gfu5k3ydLd7FT&8BRbuJsFbk-1sQV$$;!GFVJz&kvGaV3~`wQ62l4!#{xH+ZJubbr)|WVL!uCp zuHLn>h%2$VfRrnyrUI6@-pPSD5LiO|*(#>1Gu1Ax-x;g8l9oe|QheznND(z)m@LfS z62>Jr+tL7vz&(>OYT}o~2M}R{PEfIC+4kO)TD@n6WR~_G2WzdR&cVLRF#eC`43<|) zsEZ*Cr^ZK+SJ8A12F)8IstNI$2m9`^HUid(CAsefn;JJMgfGaHhq9*f<zxL z2o1gNJd{+K?OsHP!iPO!=DLIHY;m0<<^)%CtFIaspFf?2;v{DgV3_TxPH`D|`ouwb z%J@jW7zdoJR~A;@b=?m?wZ;ok)*{$Fi}zR<{W?7Z_f@gIQ-?9<1bU)GB)761da4 z^VCF^bEe9F%?_|T1!{55w`l}d&N6n8Phdd8xiPGy}R z${6nfYMa31LS=v^8dF0~9BW^6PhI(5ntHKA*pHDz&Gc$K3qQdr!E{`rUN%ncH%ElX z@;0fXX;PWhBM%f1m%%Eg6JJTJ5Lpr4QtuX+fZcUv88@DeYx?_W%{N%JR-uEuTdhVf zRC5}p^O}N62G+C&{5c>}10?*jyv3F#6+j?dSd}4zv2CXQ|Vyn4ITPU5E)fmRNmb_$9T3n(}DlDMvVN4#n_k9 zhg$`|U&QBH&(>jmp+~cwdje#R1YX}OC-PaS*9zB_ZqsRW#lGzZD~qvR@Cv$ZMC_9J zTax&wNY{Y$E9q~zLS&|U$M9#MnJZ8yT~zPyYAE4=C-^{sh{t?C;m1JyQ9 zBEmJtDi9a~X6mF(ay8l^<}s{n-4M&WM9;pq#Z_ygy;rB!%4u90M;lg|v`zl1L{*^A zRsN__Fx+C+!!kXXR9ZWZ%@ZYhB@Qh#$B@+I?vGC5Z$-NxeAY-kHqXym0w|)(dnb4= z;eg0XQ@fCWx{vR^Zxy-1&&Gip`L@UYqz3h!5r^utW`>${m?ut+ns#Nsw?q48!IfTt zk+-MJaE!vt5POw~ZxFb=h)u;68p$IcHdi;#tH6@H^vntF;tayGjz!4}=CeY)35)O) zARF1Go`^g%@U^`H|ya1{V?L6@{E?JQVH;HOQ zK&Wagu_84iE$PZnM;<*MN=2mwMdG4&wx9dJOX5Ln+7t?laXO)JPo(DzBWo0M?HVRz z0WcHK(X4AAfA{uXTmXRNA=x-c-Z2qd^i#)+J%d-{$K1#Ash)LGmIumcZ2+Xs+K00V z+2y4@5*7j#(wi}as(<(wJKc8CK}l?vo(4|oh=_})9kQua8Pgq#0@ER6Y#4N+Dv0J1 zWf7wEL;!%^hO2(wvBx#&6plOoN7(Nt6U#pXLCtDS*slXWr%lC-S?>SmZN0D@gF zp$B=?9|3|n%X5_beo(Yuc&h-ei*_2uHg0_Vl_kQ&5uc$jv!(@m&BME!z0Blh+|Y}3 ztKCvBuxyP}VvA?du~J?Ymr{Xj z&!&`r@)>_1RbDEaGpgWkkdW8D5UN8Y?33-(#`!LQzn^3#YF`TcHrdJAOUh{}ys@0~a zzOqx`j7dJhgjsACPx&UOsgfdQWbyM<;v$dsXHmRBXpdLgZ1{_% zM;8V%^)n|9etJ_rEC~^OEBKi8K{uu5*%cpitZfzd1t4F!+>XJ0PS?l)GYc&pD{-GQ z9g6_W4cVNUR!%#mYvje2jl!_Jy1hsM0RDjYyO1*@69ULNlPOb&Aohk6OYGUAl5~iz zW`F>|yr8d+9}xh}WZERW@5zHCNdkY)&Sk95lWN!f^La4v@@go<;NJYvChpB)Er!7D1F&91qq(;f zdYbsM1YVw1?!(SIcJIxGQrTEE6tf9W#%$j`=ORH&#;`*%S?8KxgDQ^A zZeD14^3clWOPbZdK;8Qzph`n}n=mx5C>%i3=HlxafC6L6gf+0}qC=5F*0D zI0d8)KA2Ep0dLsyQ#Zq>sL=D`@v@#76_@s zX9QpTEjw{tr5^Ua@Qa2-yO6br-YbzI*GQ8IX!OEpfV8I(@t}*(cMb6ko;#ro)jvza zqV_tw>bfjLr>-+OSO=D2HGC#oV=`cwS0i15Y?~}D)dGTyy-hQ`_26)SBxy4XRlJeI z=u@aPZ7Lz}Ac9RWQ-Xptr5ntwft1$|ja;iuSym`)ip9)miK74n$9%AD%=M=U?{#C9 zIf(JkMSciHf~kc?ejrH;e?N06(*G=-_yE(aeKmXOC)$fec!be$+ooX7u2Uaq9%2;9 zHs~&l2XpD5K8{ZxQWl01PLV*ipQZUFRyE@*s0X?+gIRhby^h`0X^${iFofY2Fg)ym zXeC?=!9M~Z96cPe@j8XZ5yq^jhlciC*Q3QO8yhF(YGHO-#E6-A6MXQw@E@NJ z&uFaJYFF@g=Bde4e0wy=PY~Jf+YF8WVVt6S$5@1fZ_!E97{TS+QCWC{76?uzli;(M zkRqoUo$QKSOGi|$B$V*|>le~;p9q~WS3}!lZn&h!Cv@sniY798l+s=hR-QbXV1_RTn`#}8ku~TVY^sLjLC}@wKV|*< zDBEk6?uMEAomp2DT&_1(sNgHU{W)KbBYQ5V2Ea=VOSx^py>6(w`Y^X6uS;KkCzCfs z#hZT4C9NPf`(m06z+pF#u?6W&C7W%1G2J$#OPTWw#Fs%I zmak9QbPD1CVA{loARh>n)&E1(Ifv)*yy1S|H&$acw$s?QoyNA+hK+4BP8v71ZQG66 z*lv9C{axo=XaC>5W_EYxd1mH*K6i;Na^3}~lYFTdrT(Oc=j zVq6kpmUlkdY?>B&E*>7mC29uIH*T-#wxh5|j)X%bS-TCE>h>QGTeZq?c^DNjbJn)wjM9sGtNWio6!uUZ*qM#8}zfYcQT+wZTttb95>t_Z5A~ zu~i?cM+jhMltgN~P34wOHek5ZAbUcTiY4g=#Ge@g z5GD)vf9fZ9ZXyCE^Dcs`$~T>Aazk$h$m9cB9r7Zut|*-b8KZ7OUw-2<+_>Y$7y zxNjQFL~))=rHn2QjpDHYVTcno0L1!l#b>r}PG&#uc~TK5i+BkkIj9c$agPdnzbMb< zCp1Pp6oq|aSO6baQL%NsH$6{3*D-zc5hSJ;&cY5K%wbCyRUehcuMXPnEHe)MgS@nK z2O9Fv3n^&-5MZQ@julZUey|xFrVcpOTi=Oa=F@j66El+SWk&^m(M8CImKA1YBF8wF zNR~Fya4xBa)ly+RstqsC+gs22NN-K%3Uw&@u70SGAOQA+_ZL<$7vrR|POa0AhU=BHnIcbcmN6vE z$o?@x^*;pZ^$IPVj-n;y7+Zr$GP3WbONlGk-n4wR)kUgTq0>4Anw508x1G}f@QqS! zda`W-Zmorb+^L=~S=QPcB6~Pqqo{jEZaN7atKGB<_{Hh@S?{*n6XNS#D)#aundmij z5vQ4*2o{&9hjJ~3jakrty@nzuX79CZ%QTL`?U*LjzbhC?AKyggc2D2p3{}0m>jYyQ zd=8U~TWw>lk$0c9;=Vhz6o>y`h5#r>XgscZukwJVC*#J~n`wGsMpIDcnoUQ4G`sn_2~`)f3Ld$WFIqD9ifrJ5P4Lo@m5+EQs_ z&sO~3D+~ zl9hDQs&0ped=z@*ipRfNGO%}BLh^B-X;%YaQa7!jHtFAa1sJSz%ZfNRHqrYB70~WQ zCk8FQrNozMy8&FbT|usHho?0wqM#+#YS2cogGtKcPCmLwRy{q*F4MB5Z|ue#DKDt( zc?*D7Y-o7-6|g8{rN1(62toX*{7i#EpI!+5db9Q=bz@P`C$AQytBsOu0ta}bl^l#1oOnY91U*-7I`_* z1?PRShN$uJ|LPudYT2*_U!{&LszO(t$l(?YXBIN%J&Dhi62msn+lrX!mjHldd5q(@ zol*(3xj?LyRJ&j#1V$gi(qjTpFT8B~twPkpdtUspK%^Daoi?l*N)8x1GB+fex7`4Q zv4ExDo)qHLgT5!_`V^_R!qyD(;74Q;{AY}BtB+TWioVC6J+s|8Q(oyj#AhtI z$NUiIzktpQQjI$A2H-6=O^CdkDnc!Ob7?;2QfbzryX_w1Ve++=s&HBzp_imW+CsK4 zwVws8$CYw97sF^XZGx%Qg85$`M~#N;IHPG#%eYCfxEnyW->FJO9p^$E?V=)X#?bPK z3QkLE59I%`g~*~72%a$$j{FO3lK|ICrWR*we9UQ3ab({+@i!oe9VGWxblR%(h`EK4 zsYF#AjPDg`+olb!!edmOAP2$Z`z~U5)$!$!N%u}JuNL9+&@SdzoN;t72AZUS)Yc_} znSLZBzl?J;N=nP|FUBlrjg6b+B>kWio>1e`hoS_JY4YY^Qq{eh#M!yBZ-19DmQpdb zATM@5YWff@+0Fd&)^(lw(#t36gQon_GnuULFq*bGrl2v&AzU+#VukdVndR!C%)KiW z;0=u7T+4TUAB|RDe66 z@gy5Iinfshq9EmTfBZD$>FoG5-bF&k+M0PY=)n3-J;z08$sT+=ysR3z+U!L<_tMme zVVsepZS2kc;p|yiY7~(vP;*56i!u8bBQ9xU#C8HT!J6$xqFS%Cf0vq1#y8w5R9o!_ zVWeN6(Hc8H4W5H&5-L?6EAvHPON0c|n==`9dZ zq2$*ggb%EXz!$2uvAyClu@1DZlnR!;YW(>)o zI!mvVoE=I@?rckVe*Tto6PO5$dO=vQ4FhD_2EzBRzoNZy-1AW5f4nwO!ak!y7*1df zh_9^d3F5N9)j6Y8PkZ@Rl}}@5vhw4r&i3aP>C(@ z`?AEuGCPb~>TV6)c++}!<(Ss_bF^jS zyHe4htOSU5kXyQ(ZF7<48*_#m^mfK>^wg)sPv^@7@3V{?6DaTNHG{0KBP&9$&8;@? zQ!`zBvotI4=tQsz)(2D4>m5_aUiFs}$btIwE%D5au;aL57I7)f6aSuX0FjEXF%JAf9iSVu!({HTW>NeQ+q*y=r zvjZN@+TK|Zu(!(p3u)iWX0#i?5pM5gS!!0`E7P9gR`EUOkv4+CtV(qc1HDc^IH|&L zCgO(Iz`xA9pHp~VNjm5{i(&TU@N7AbWYIn(>Etnj1JB;neHV?*l4Wm!g2_2x*KgQ< zAaip)5!$``#t({|jE&@(YF@GiS1};8?Q=V?)VC*aThmVrho8}P*|qPsQN>){!-k(B z<_Fw&(=j_t37bT`==95wJV%mRDmIEt1GI*SFRgY`{1o`)72g6U>2F)H%~wz2xe9&& zT!t8wgXUC7elJ27fe4DE_eUL=aR4L?u-2~8VjbSumfV{X%SN6BX*P3(Fk~;ieH;G4 zvEA+(7omb*?&_AbgQvIzyYf0g-}}lhk|p=66y{>O6Kqo z36EbVMXYXQ^o3kHcD)#-c_yBQLhb23CN15?QxgM(Agv?l-_FmyS*}Qg3*x1>?rJ~4 zv`#{HchY)cW#w;A0}&dFQb9KLSAyl3rJFqOOu7G*3ge=D_;osM0FAz20gPw8n|^T; zF+%7#>6y7a_=&I$C0w04Rqvk!Q4ZatApdUj^L-vcyR}ba#(zLRc3#ydI8V51L zgc6<5_NACQ-K3`SPOhV41KT(e<&djJDVn){LHV@_OxyJ&>pWddllyGP#$ejhy{L?V zs~q56b*5oGLvDy`OXNDoXr2#*#zgw(EvVBLsnR>m^5E| zRMjOCI^dE?b{}tMctb|NeZ$_b7=0j|YPBeH9WI2bsu-?SOSmwISG_<=;>I}4Ibe74 z(B0Vl{r^;q%gYiGpq`e11ssE=_FZUcU|V zt$;@=ANAmqO7o6KnR8okVRXpIdsTN=`?V@sxQI`t}n^>>)b*}TY@1DHRmzf1%yQ7e184W5(7cxbK(O)!-TCB^8XM5-KYtZEt zo}R5vmAlczDOyvtN%JGAE6SRsW#f>?1+7bse6U)@R<)joqfv>+7PtDJfSvpPH>YS> zST4r{7%3wDNqX!!4zJ;Ku)eRp=Aju%i)#fY_2Rn)3dol{3c)*%u^TZ|9ePnU-)-nR z+glKdMuAY)^h4UM;s;*q{ycp{Ejh!6Tp-1@s;|l7d}zJFoa<Cte=LReeX=!)U{>?@ti` zw70+p3a6Wrh)W3i%-|PG=^ah8`@r*_)Y%a?*uiDL`8{N1dMxYZ0Hg{9U)&N{0958E zV$yYO0}larO`FrE@pY8ZrJ~+%?nXPY+U#h3-8XSA=Yi4b+$U@WfN=9e#t@h2A3y7@ z8(06P*w8QNNzS~vgZ%i^&6@Zsga3Gu>0qD^>{A3sMm9|J>OBa&26U~qgGx~^$a>w3 zt6KBc#a&1e{}H7BbucP9#45a4a_ON3jcCx+^1k{}LG%3lckAD6;2RO~+3+PL*Us;m z!tKmTE2?}3f*t}P4nmY=huRLsP&aT;30i_jAM(&c>>!o-a1)#qb9EW(k##F%Lc~dR z0zg2vB6KoRRW|PH+6e&wu9Z6X?H6r`&rNPiKLcRXeBH&=R^o@!w^uUG^*nt<42TT5yR>WnWq%+laP0w`;lL0z@{P+vY!heBLXjrbn}Xh0&qj-HiM1@V zakv9!vkO&rU&8f|Aa6fZx9zo$3jd9JX8F9vv|lG|Wl_Ht^cRNNoH<0vx;tnAAhTsV zpFi+xP*3Y9Gff<#o1zCXUan%eH0d%Aj3+ z*xyhj`#mrMi)|VJMZIf(o#LKJ_n%m1{9SbzF?;}HDC5yjp85+fQB37%c^Gws34lNr zP{-M`zi3~U0g4K4v?@8%SEXO;OR8Eur}c$qEs7``xLi&tD}D47v|I6R zBG`=iZE`RU>|#Bg|0+4UW!I(W{sf_M9lELufbzOwDfcV7nB#S}qCGLf9AbyTc4?H{ zO1A?v(oy7Dt6?txM%w{cp(eJXAOyD;2GHWIJJ}J>0n{Cl@54VcgLyI>KbXXQ#@crR z3`e8RK14YUpHl#KjB4*)R#oiFni%}I#`>2D#gE2-DfpT8m)D!z=bZ*~Rd){@QDO4J z{1*XeNkPGAW|$1Z(*Ohg+cg&hP$2e(@;oH~C|-NXGk+GV9#cp=)`eCS+5;{4bz2KJ zKr`?;}G ze)!q+eoFPQmi∨tbRV0GbkZT>&bxtO}Dt+tyk;jHSe1bG4-)(F{JKDqn9*U&e7D zzMQ;YV+1$&pVdrCPW)keSqLCC{BT4Mlf9OHpI&2=XUr$iw8_LVzO7?^$Mn}fyyrwv zpEau>Q~iFNiA}WEASxJ5Z0kKwKT6L7Z(LZ7B`cR6hEhr$4Z;O1QQXVPG z-c+F)L60_QT81mh038{1{o}b+rHM>s;)$q-Cy1Y^VAH$|_v)-HSi;=}~nkU%E`xk?LCP+4fow`qO|LC~B#uudXsvEIW#&xR&Ym zV~#E9%Zp+lHF2&c`Sl?ys6mCV$Zu7mEHYuzhattEb|_eWQ`>P#s+ixh z3;WsaK58L}WnpA7b}EW#^|I@XZtwnTV@rb0fO8bxgMI(jmX6&@tOk+jaeH|bP-OMm zjjY={()~C4H}C$tiJlt)KjCMI8Vei;(r8`yD9yA8bDSK#H8)3Ly-o)O`~z!P1U$IY z`@nK3GrclLW`cNnYSPN?w}0$Z%R*9%k-?n z@iG$ObFO7Sec%AR+AdD?2~d#)orlbVUoqsv<~j5RB#xBJ1T!l|Z;%Ep0*kc6(@jdNs5+(k*J^)p!4GPm$B!NhC3j1|{SYKnEVmZXyPvlBNkOwCTpOmNl>xMZ}4_ z0l5BjOLh-yTfOezH6m_%LQwXR+GDRZ%YG0qox9TXIfnzAj(j^hNiNNQ>av@*8|E;} zZa6Zg8XwUXB3Ww+eqV2ViRjP#kva_E`LCfT?XMk8Rp|*W&mlWkFIHi|%nB-SVkXhi zqZ>SPsIO`6xQ<z0d<%jO9D>FG#u1aJ1Ik575vE|4v5CtI2KhvU?G86>fc=0N!P!ECrg;{VwKliG|6 z*A#nR59G}K=?2kI{61|;b{?;14gjj%uDqvZviS=Tk+A$==@$F&Fdj>NN*knx;GR7} zoRiYUlgv(l`OP|FIFtMuQt!n{%rC4b{*<*wfpiFgA2bKJXdBSu3-w}G`%0} z%W?N8I(F?O4@5_XVKT=>d51;C*PubRJ3D9CV zzL2Zw?cW9hbSS}ExnsgHA4n^X96~!SKkRUATl99D9|m*<8io-=_F_HUzgQgwp=2-% zqq-43Mmj>tdN)=3nY&y8ohojptZT`D3)OK1CUN8Gd?)RHWUW^E6dwZ%>ek+X?(b+ zI@L;#7yxwYOX8zDBLC1-)<5HYl!ZdO-z6R|D3oT87oJxY#{ocs_)o_nNxET>o7=a* z`F&B$`~+fv_tg^{O&(tI5`z3{m5-sh1P?iTkjCCEFVFlw=4#Xq1^}nu{~XWB;)Dx2 z5rJN@u}_(?a{J$^8t{p&q(bFDlpxAs&{QR%{Hi!~hA|-z$9?@(W=|*aj^OQUrT`;u zcc9S}>8C8&JucQ|kS}IJ(eEqgH=_o|oS?Dy!KqFOB6I{l$ zx^|a8t;4ZG+$cQ5mo*QJO+te27>_1{>vm2fgPeWR6;FqbFtDAXAsT;m$!KIViAS3G zwvuC!@PE9cmPt>3XMI8QeaRiDqx~eF1}`K>YUiTtYN#*hLDU_dw3#KjV9EIUT|L#^ zT(o96t$l)6UcCd_~Nf{k!id~^ExvC#JD(8{X2aUg zeeonPe}#acwB<+7!D#aJur0TG8>w{oY*;F(;Qi0V@C_c+opV&_>a8Zhkfq#&wHZx! zfx`uS*XoO?=xvVDB~0o+#zw4VyTWAfX(1M7gKlFzTyq?374$fgYLlRD_J? zm04oX+bad%uxqrRViUcmmWd|vD%H|M!0Hl>(BP<=v?GD@ucpCq%1mCN!fv}-DD6$b ze5lcUcK?(lgxJqH^fNI|K#Ay}Ch&ZLf84)6Tg&-~LzZSR>z@y`lG zlk~YzGc=CWZF@Rnk)_jyWOlguF?wnomT7b|kBM*H#p5{l<6IckwlWlx`O`PI?#T-k z_IK|d8RYd5x)Sc6A^s%kFzfnGPOS@6uPg5Ke}7=rH{mfGjsKC!49VZ@y?0iB^e4zG z8m5>vAclJEi-V^?7c&_vWm}Fz<|+L9?33bBE_c#Tz3Lw$=}Tf*VO(s1uz6qooHwu} zVNDfXDn%X{|D+qs=t(T@RFJVXe)D81@LiH7^&Ib&->crBC4oKP{bFReU&Yg5{N6|} zz=J^yFf^kMsQZd`iKN3d`2a3CM<<3w&w54X zsp(UC-jdy@Cw_K2j)d+Y*X|Khya~JG3Z?5HgJicwn}jhxqpthk2eQ!nGUU=9UCfiS z-@htn{HURgQFVlpW~Eh@3)b_P(XMBDs$u$U@%FX;_h8YN0)oOvu36=dM7hnt3t7xmy+I)AVH95>SBS)ml zq5AGJSq6Mezipq*D-w3F$Q8FaiQCs@uO@L>)c!Y`;6ir$sj5oTNIYCmNnUP6ciMaN z*Gy#4Yv0M6AK)ZyAtAi=&~A?3Y@{wzMM{2Pk_ELSknE=Hq)GJRWsx=c`&j0c(m@2c zUxa}y1O?Ginj`mM_M<&AGzvV~>Ekz7!XAa05D4mw@iQeF8?(L|Z$rD+i%}`dbD2Fk zip=XYu=vh9Fi5H^-mzi(JZoH<7|J}{tXmQP-T#VpBA7un@!($S&t z!;eW=i)uW#76r@V4`Gj$8hBkWs0>Q7COYwpcf$w<2M=3Z?P*Ul$wEcZj2Y?v z%7h_X(#VAVbY&&)V^sq#0%di6uuCwSA>q}0wwfMkn0x@h5@6{LW?|dA8DSZ}$rAIC z0_Zr|QZoDi1h$uk@K^0PYn0|pkBj`&X)&(D&t6gsNV;o&fj$C8_7O2XYPA{6*OU&! zkPfKd@gtLS+S4rZH7M>$;P#Mnt6a(K)97Gr(-C=h((3QyYCtDNvZIbc3W-@+@)D}K zhfP9Vix0AByvM}s{%!|zsY+)$j@xt9hHyM$lQofLC+(c7xGi*uioXVXP32Asf9-x@ zIuk|CAL^i(cRAt?*h7tJx@Ywdc72Y685AkL)U#&)?wa(YWLGi~{Ym&3*>+8^WN3gn zgv{1KXJ6J1e>$W^3wb@(OZtc8>)+ti+jO@*Hon*mbg+yRLi_NFi$LYZY@zh38WWq1 zCqj;A-IbgTv&T${85dVkFNFZ&V(DBm0`%_GXEBV?%yE4laO2dvEP^{^Y|^-l=aTqw zT@+cts1mv0m3?+&{4-NA(#%F3yjbxX$4jg_zK#lD7L=Hne$sLHVom?tdU*? zO)35*FA_huznEFu-{11U?Qy=lVZ#`N<8~h+E7sLb%cS8gu-z0y1Qzu~DY*4(KyGbm z6Rl|LK&3gnCXrQeh~l)>`DONsg-b6i5;;;-cvj{=BH|ZB1QAR>V7Sfa2FfeXgu-2y zW^f&MgHOQ?st8kG{M(K{y?=k{F3SSfMqsUuP!WX2h~M&Gd8NKfj?j`~ymr4PjxUSK za+^24#Rt$R_*1st_s($J#8n==G)L7pc^F1UEql^8O4_Tc^)KFi!B=_85}Gz(ud;F$ zgn2S=?FP$Vt%ZL8yD|6>uc(H>Km9Z&9qUKg&&SEB0AgrcE7~Qu z;?K$n1{M`8@o5?rjoT684gU`aXqs?(mwAqm_L1GkW&3~iF1}E(&mu2pl{&Q+z7=e) za@;2mSISJcB0!rS-Or@*2*R~T%9H_Lubj&_&2mIBUqu0FlDesuX$BBv)Z?`rYi<-+R715;L}Abfpc1k|u%QK2KLO3Ah{|DhH> z&%yon`(K7PI{HcR(~Yjlu^%tEVb5q3l+#SGFCokw)8$)8S$YOj3Ad%0P@d^qXI?k0 zj8s`ZD_1;}{>^kfIWL?cV=LizIYhKOlrj|2a)5C{*gqcI;8nu{T~1$Do%A0k46g3O z_HNcizLT!+=OzJ|j|wbM4#)dHkBsogc0`>t^$2W0{==A|UCn$Lq!LT^W{NP%0eQZ; zR8Ba$c#wl=Zx2xQTH$0p$_UC8v*xIa;+ax$AeLtpKRP-2ZHEZt!h+X^Tx5J7$;FP}L705M9rj zcFLeB_FPU}19{YJR{Qb^F1&PdVM;S2iTjeI!51mZ(!CuJiQq9~yuXrh-)G&WGj_f( z4f#GOCElq=|DZfNNkUY02V0;Z84Ku3@Xl{%XZ$VH)1W0fp3(iVODAFzd{WLx?5k*F zufL)G0F;7!wa0lqC4Q+BsKkErsZf)M&0Y)gHV>I0F&@G{Xc0I3a+)3Y;O`N=ltTsS zaMtL2OAT>TExSvTiaNBI!yg`JkmQaI!;k4ip#Yu~`+EOV#m~ZgihSwJwLE%<0nU>u z!2TApU+}kx-Iyly**cAuj|b6Ps0x)&gEpUzSvVIHvh1LF``o=8DM*uM)9BBNId)Us z4c{s!D(spWvQ=4Z*88<&D=J0-aWLx-u!brYFCeDEmx@NhbXp27&u^6z8k<2?#M zg8xLg-%Ez@Lz*(hH9-t_h^)ZQzwZHBYp?Ne*c8<6KEGcwG11$R`n60ne)V+pS-j44 z;I-;fMlzo{Y|zfg2Xd1&K+ZCu-Eykn>(tV*1{T$Ha;uTsJL(b=8Slj~>dW#!Hxm(;SExeRwcWBGZ|0z8J&qe#wm92R zLa21-ek3PtByyigm`_VLVIBpKd`kqQXSU|wgx3bbG{yPFO-Io`#0Hi|T=B35cl53V zQUIY&5do1F6~qmE+OKQ)x1xT~UrQJR;&8bf=#|z5;isQ5e}4b$#7Jur*B!8y9ZUCW zj^2EM^E`SoGL>-nq&-FFEJCA*%)3hZdUl&466b9oao&6I{R-7@ggYoNHm zE52OY(7L4D|Bg7EuuD9okb;2ipU_~Pl7GlE@*HJCA(lF7i4_?G(vqh_y6y`!@m+#& zBF0Jt;TbO`?E{QCB6>eO%EmY{hu@wXF^+GNd5w9I`ztQH5VfjS4fN|cX*_vEQ_Ed@ z5wtD|&x7g?{iwO&@sL_#*HCKcuf0q^Tmk{Ci7&&m~bNRQc(2yOP@ zX2T&!DGqk&C0kHwk%Dw%KG_R&@*`#ais!dJLV$w$yF1hnfiEn;dwwbB`=S3s8F=~O z(>IrOYnxd+B}#PkIL5KTwqG=Wi*i)$#vhcJsp)_D}1A7if^P?wvnX+aRF`H<;7 z$-U7a>IW#str3xi;?D$JedQF=>TwQ{{1$fOi0eJA{%nNja8dL9| zs+e-{2Gonlc%o(rf`q#6gBZSL{H|K%BO==vsDac1hp@EmB-;d+PLbw1ke=cA;9Gpm zC=xoa$AbbXgzz0tKYFz?-mQA53-OcIn>xrGb-& zkI0ci6t;-yFjy{61sQbq#Cnsak=`6bxVaUzk4l20Alymvrb7H`=6>lp-H2n>4!rmg z>+I}g{G!!H$|WCFhZNW2FA{fZSS&3JKK^(aw8N;5&{O)$_#P-(9zT~2vsKykab>w? z*#5{1Dj1Oc_i0GjCZ5XO%n@q^DHTS8P_!B=1 z_la@lWbd&1kF+nIj07eB8G*}@h!qG9J~znxUvqcH1@ZWJ$B|vy`zS_|I!SzsA#6+X zw|K7DknZF|`~-rx*>iGv+^2rmh`5NVu4VL+8rH3?sbLnb<8#mCrdiIb<6f}y?&q(Y z9Yp4cmD>|?s%;JfjK*cpAY?G~Fv`WUWhwe1QA4pd)sYlCReBV6$eGYfd<9vO8r#ZH zv*`h;=#W{D&Z-DIbWK~)*w1LDR8V$eJzYp-+fM>)4J5l4P+;W4N(>Vf&!u!jM9^{h zp{LDd51rSq6X}fHHUyZ9?ta^5q2DPX4w|%nvHZ)y+Q$pk3%1PThngmItXsJI4g-ej zEg2sK$!k#7l-#!}sPRthMoB*arJFTKxs5n&_&M5=*VdOI|P67EDn7~!-^K`~a0EfOX7P9ql|FsFCXNttktc>ws z0J{wc7O|MCFh53hqFjx$5sj^|rmTKHrd9Krf#HN!`~ntwgOJa`J$>mFwM)MKyparp zN2(W5+B?5LNuO4X2o-k%@4)AriD+r6I@2$|mOqvXd%b>{7va?Q3%Z}yas!fU|EJ4? zYC0v4-Q9qcn3b(RL*wSJ&7A+f{ zrcVFtBhs`^?Koi|xN`b~J~+yW&^Q48h&l-gdi^p!Ysc9a#bX}DGh_z zYh}W;WS=95-F=`&XmcEgXKaup(@|D05&Knkl_>KX5>Eu!vKcDiJ4sT8ZXq#U%IQho zc;I>U4R9pK?2?{Wa?N$M+zQ&@5J8AIB;6Tf7ERit|Y4$=p$lH=G_udpAZJ5)Q|rv5K3+z$QrbKY%gX<2;6Vn5Q8i)TyDo&6zN zsaR951k%qL>1@yO&U{Zojdo2nuf(0Kgyb&(;1U|Mp*<`_; z=K>y}lB~^$+ZZ4Rw!ex1wEBD<9kAnY!)*eRLNK;RX+R>tKF48<_ZRnGzX z>{QnTHtUA=UGqu=vLRs%H(NGomj!0FDT5#89QF;cIG<;bT7MIq`(qEipa2M^UmYO` zbyG5;#j7hzt$5->yh)uBruP$Ow*WZhFoKIi2=2~NO9EZY-FO26tuA^v=Sy5BVMYnp zgk2YxUON&=_wOfstl23nL?5bUsJ!^kfENHn^1ax<;xkG|Wr1)KmtPlY`o`Z=?|K*f z9*9*iq2I8bKyP9?XD7eO_|O{bsy+-17?JlGt8>7+mZjVyqwn0ZRo&TJf|xkts%dPy z>7T`Q131&-k9})3o~TS=ib2nvLP*PD3BN5-^vZil+ubrGA{>}z?ab&Zt0?L~9~&?5 z)jxp-(F?xeqiM5ma(YI&plj>!RX3#&YvP7-(!Y2Cd#f}Rv)zk2et6%I{PG5m7!I}! zi)!!GM!HZw>Ilkz3n5_4fD^VK)W`QmJ2wAXM4W`gB3WgZwgQ-={p@fv z77P5hAii7vAiQHdpKr6Zo1~K7tSG0aKK9?zq&Nj@-UQl_*(`oM z7y=0VHeYia{h%b=^S9${U?>Cqxy^UPsMo8_V1|p_9m!CpWx6ecFs;mP^64(Z>)jhU z2Gh?c`wT&K>%)A*Ao8^1z8yFUgI-2Li=LgdU_(vSF!lfIl6te-mQwW0t|(qJEq5?D zQ5}XXFg$g-zjm_t+q>C^KCTkXH%+Z)f!Mm>2ReWOL*Xo5a#M+Q!H(4CPk!LD{~Qz@ zq;#?uKGhQ^T6tZO)=~u@LhR~(oU(sdrX*0k*l^Cd*hhX|H=xf)v(*@3-PV#%NoW8a z1n!pnjqg~v=Ck%cKbuvC9sjriBr|3! zgyLfie)%0;C&?vc4nP3@=VkZfRI4Q2J(PJtv{DKH+O1eNX?$L>*t@(8PZ$?Z^L{77 zH^rXWX^V4wm?(m?Onw@8a2Aq+p8TMBV!sTMmUkoGMnGBu=KO9s6p3EmKi~#J`}%r` zV^D|GodE^)q49D6CgaRaZyqM7iX@bf(}E-cD9p$D<99?A2TH`n3y9H$WyVgX5lolr z6HsrZ-{u_<>q5rzd8@Jb@RAn{Dv+;kxkp*$VR-x5e$@T(b)V;m`8`g#m;6{~@loJ5 zaz1M)sDv^W0FXG3lC*3W{3_hdbbFf1#tz%jmgLvxWI(oZ1E3D8ljJtLgM_b zp(BUd&@09i6AA7>fyJei_bcBCdsjC(8KIcODoKGMky|baMR>}Lvfd_A9?pFKX#%Iy&Z)uRjw$#6wU zxJE$5Xik5MD1~2SWRA0)kZ>Q&Yia(p|J}VrM28@Ym4w72-NGLkbHi_a-kZLh`zGc5 zknN8I`>izb^YoN-FJrH7iTxkTl&tuSc4&yXBytn~86F#jc}wInBeLA*WgYXHpW@%9 zzt426?)P8A*4TkfQ$B>u!ZtG>l4N+&!fG_r zH^UkmVqI)v^3oiPO#~&M8+)ueQ5V1Ed@bV=>oUUl$TT8+EragP2&5Y8Y2fNT8s znVa-tnys15UawP1-Hk8+;t8Y>428a5SfSJSTB#31 zx2XMQ9?%j_;`d*|rHVUrL^Iz|$o&8`M@an#Lo3n)0v-_!K@Br-OOV(R8!{6Bvk4Y) zdP4q0O!YS^IdbnBHfU+QEqz5Zychm~L%>>wppblZ=|gdJqQGd)VY)%3S#@RSp0V094LQ z!!}9&`jK&3Nz`wMMm#QsfLe{~a0vjvbFd0q&BdZoL|KV`XSdc8+*a)0avdoB-EOLw z9)h4oZjI9hKuvzaDYDU34IFlMHkGAaYj33tP3SO1tl_Y>bqF8Fv%^3+0UgBg0!%Ti&GNVmd(RMD z$z^f2_%Y>TpH8J7BLYu8JVQm*HETruM{Ko3{S-xo{9_!2_caBH`JMJji6tCo<0!0w zP7X5acmv(Sp+QT_4Xtuq_Wst@0rHqq^_w4{G!!m^3V}eHPnt^lFSRV1TIJ;HEY_)fG z;t#haJ`$&8EC*)#Bb-P<@rjuxc6wv+#Bt#IiR@39CJEggHM~f${QqKL)q1JB@^!i( zPxD6@4irxR^S@Hm)(;y|mH(&jg?!FehN{=Snl`@ZvP?U32pPCiz6`M!<;52iVo={3 zNpf_;XiBU*F&>GSre}h?^mw(uf{&sMBsvxTp7+zoA1`1D>P|2 zj%!%EC`~mMkH(lHw*dcQaN2A)8hY||e=ZupPGq*GroqYJm7Cj$;e-GBJdWvP)ca^5 zw&6u_zG%N@2Mt~vLmqgk#68isW>_#MM9v!{duT|9z1Y%MoCfN38CDZs zP3NGC9gJD}FNrYat4PdY%r1F}!lQR?htJA{Vd^xMtV-(N^FkMsp$*l-7-{YJ*jLLQ zjP~xAUg~)BK}TGg6yiD$H^Nf;QUNM)Q2>UDt;j~n>-Xu4cr`efq`7$ucZ{B-g-0zq`1$+J44s6h3Gyqyeiu~4W3hU8R zLsMVPJhg`RZmgK#Talnx3?1aCZThV*Xk><+I?gR~z%*vBx-t8hYpubC@lhz(Hsu%- z;Um^^p7>kn{$u_f(m7H~z*jAVt1C)oI94oO)R2T>N@j*m&&}??9r|AD z&FZ*PrQXL8Md8Njll=^*4qIuRolI%qcPQ`7O_y$tIQ$E~(I)W*+t$k>+S1P2byePL zVZs#Fwxb*PB%;=+O?a=a|G<{&_uK84<#+7OzrI%lXm6MPlnd$n>SnuH6cRoMm5akl zqCdV@U@AE86|DUI++iU*%5XcCL8^hy%%x?&SyOM>DprUlw&FdRqCVAr>G%+2YoYeQ zjyu+H_^OS>FcX=1@sGdwX>a8ubHdTn-cJGU98NPyvJ2>BhLA=&u*9`*~g5325C)b$E;cVEX>7Vw~bYV$i5n?BEHm*!gz*+(F2dEu)*L z*J9m2U_f5kr6F!e9Uc#U`(8UeY88^Xe_nrtMldC-i1BEuo9TfjU|fd8;!iu=6|7Ds zW(%7P$^u7+wtQG(-g+5S)}?D|^yYhB)8))q@*3b&nlb?S68u70G*&az)0UR2rF;EC zE(j0aiH-Q!!afZz|L|9^`qQKT>4Do%Jou7tU;^^W_w7;J*RoMtbPtZarpg9eL$)gC zkxbmWPH3*|P^ZrA&2UF0lL|#t^JkQSHhpB>iK*_!F~KCsM8zrgT%V~-Rk_T&?fV5x zo-m7*QPo{s4Hh(a6crc566AJ`e^G~N+|0V;{V^Ftewc*}qK@S_q<@!J{vUG2noIF` zQ(KH2M9;59T<1cMx{&1_U*>3)DoV8RP9F!7h0lg6Qi}Kl{n9kYxHwN)V|_xkk3}~v z;?FugzmO}fy}wvFN<3gET89L)(XBV6#-#Ha$mV5Xtfy04C-E>IcperrH@ts`r&WNR0e+00k;J;@8%okuDBL$G7+7!e<&+A6l%bVBOhlZ{r0y_+5^jg>ai@+acIp>7!wH18 z)v_5Eqoh#k*};7XrS~FzS8^Mncf~?sa9z`Cj^3MPBPLWy-}_YtZ|#g70ucm^R-}#$ z379HdW;AB>@1#P)*_U8f2isY`nTmAyf${jaK%>bD){JUh&+o9n!E*kDt9F>AJJA~> zUVE&;$Z%!Yg{_0R2Tt=McA*M?iYMzHaAh1L^Wo`|ZP5DFV0#jSV|9oku)l8Dbfucf zNlyIX2lCcO%83(H;mz_^-#AACH9G)*#p}AcEQ`&Ufk|w&5b)1STnT+g=yTTG+MnUI zk3u_R=)W?X$`2^SNa9D%3ISyQM}&A)am}wTLd*XhtS!~;uw+KebM$q-xbAxjA{(`!2uTRxeiU^Jgagb#1B{$sNZMj0THMp4704%zSM_Fzz5T46<| zxHZ*4w6j=CWn121gB0u>-;3?La@nRF@9 z*~}qFZI4hCv1=U(eG{MITtvZgm*g1o9;RT5lz{KeMAyJdw^m7eyalEZ0Xk^j(2Lqq zjz!Np5IYDHVx^k_Q9*iLi#f;O<)okTLT*cM_pLDlW^?wCxh(27B(KVBgZ#-$O|IC- z1IE_Ym3I-3D&H3f`{tQZy2xkbkAhJVMW}1wsP35xQkR4yYxg#MQ5vqu@n&Kh{Cg(# zDl>CtUtd+R5EA@Xj9wFhsxO_1N5&Fkk7Ch&3GSM+6cy?~0YWT{>lAp=AVyqCQFj_f zt@Bu{1=K+N;~z%5R;UTq!Vsdj-#}y~@%^d12}P4Mmdu{sn&-d)p6^X@t0~Y_mhOiu zeO2X`9p{)(pyl3?s;wp#4~)tO4n{GqILW$kC=E`)}oKQQmK1J)8hi z`JX-2Z~*k-ctC>-p`dwdATD{yH zzPmdWD$gU5G>0Wg+lqZ4qOAa@P%3$>56l1rDc$RZMNB5nTesUMj!wnrw5CM92Z`qF zK7{}p84MKxIuHPA`)ZU-Zsp$mg)Pn|lyqUo%3VG=ARQNhmE9c)1;_E|i>;4iRXU>p z01FLZ3T9j=ntm}Bzx3$mDQ2e>o@|6EPKj#Aq>!=jCME!CK|u9H$zdpA&eMPZ02^C@ zrw+%600~HU9_|ah#a*Fa*r!qSZ=0~96$ud$5$GJi?)=`` zcIw*pkQd2%3L+$DYs>25zztrbiU4SLNL>(&inz37!lRFYv%-NWa+S&b3U{T^To$}< zV%G~?P}7u!T>4DzK6jOX008y^5+@)MP6TBQC55Vha^1%p$|xxQ0QjM}J>abX0EPa< z%E@@x%YX;*41loS2LnsrHGlw!^oO|~kWA z02iS^9)U^FeYq=nq;f%Q04Dafaztz}l;C;1;{y*>|4aq^RfqTqPjYO1PtG(OoFjZ^ zg5N}6B19lM`N2$WE6=141pxbSlv4l?nUiN~<nmB0Yt>0n2|NAA4u zPSx*WE8&{J4Xm-^L$VwY>Bt4w=mq;;j;}c|M}lSH(Q^JXMt}iI#&4o_S;}{@G9pqG z7r+HuwfRS{=hg7mvM zKmZa%9?RK9KBc4WJ*Iz`tGFj=%lACaj0sk6g3d4iE#jWF*-)7it2>RhQf4N%=*){z z3bDCQh@w}&HH6WwFVdv~f@3MWLbXpkKFI9<@;dj3#zr0}yf8VPa(qX@5 zBQ`9yRe)i2y8}Q#eb7R{Cg;tI-#>NB-X5!0i*al}X?gjVVu&WdPc;=5wm{!hOgQy``X65Pge2J`eyJ@6*(|`st9{AY#eUw3sLoXRW zfmU%xxESQ#$M3RvEu_@nIL4 z&Yq#HF@U1 zgqrby<2#YRT1Y+mRKNx0O2bx4KixzL!Nkk7dTO7o?sHj=g}3W+egRS4e=QPAm)n00RIgd~&G| zK^f=OgLtHgJvG}1kO3}Paw34s`e*ho49@Ge_&{fJqObfnqukB|MHK5^i+(uJDJJ3n zYI6nm^E$9H#n0U~0FY$iWE2(9$b>&UE3NEy9SA85+2p!+h^m`8Gf+@u=aLRs00Man z$);wB=aN}I?ci8eRx~Efhc=AXcmNCRr@PM+q9%Kx?i!j`^W;w~01+(s())FpVtJb{ zrfie5iJAp$BA)JIh6=Wnuee`B1KTRe`jt7coS+5*;-O8rek9^==N+lRnpy2yP1Z+f z0@x9%Drr-aE{7D{W?6aSU6=p@sw5LuIat>h)`Fq;9%jCOPAS17qcxaSOyL-pM0 zJuDnIPG6yMSj6+bN`L?t?GLk>1*aE~CQ`|Vdfjj>iIbnG0FMeLUhk&{pTPhe5C{~r z<3(*gj`->KpTmQ96WtODXgC0Ozz-jXI<$H*rKxTz$h6lel726pKVUvMs*nH>cmyGC z-fufJh^b-rNHi0<7n)DKy@Ow=)7gI~sw_0C zsaa^h{j1|;SUXvH?^!+qQ)=6$Z$~cb#`2BW(=Ve=SWgTuGcPhOR&}yQ<=P+_waus} zsPW)g{N?y*bac_QOABur^WT}Uj~^9f<)_EmyXwq@$IPy@yi`dPAp+3Cb8tid@pmTT z|Dj%5g;uh4A)jmlgD^YCj?jf}tzjWw0K0JR65wixa)}Eli#F;vfYZX5#a3z2a}hG! zOtssQLPitT8mwIahBo26;8QG*X-KKFKnnHUs%^nNsw*%I{{R3DDM6axCxHX$ZEK~q zwI)*l00RI5e*{o#hQs%J_IBymn>+_|?rj63u(HNLkru4}402Y^u&-Chd{ra=y{jve znJ{}nmO3>74%-EVoq@D&+`c;qVSq$7KRo!epxWQ#Vu!2>qPhK0Qam6bLg_hbeh>gmB{>*b+6<}~ zh_SsfLn=~D?GvE=-BN{+rtfL1lI9vmIpTWNQ~SH&cBrMQF05}~S4tOvVy98QbTC%$t= z;ic+50)NOQ8b%=z-f07NDnoM$9DWVNuxirD<);@@)yRcGfmcAcM+t_v#uY6GC*6xT z*U@cMX!@dk6ak$x%60DNqu)zH*}XfT7fO6%eus788@{8|Pn3f@+Yo}I$x^GD9?0e! zENjc&3;k3TQ|9HTbo^+#d7bwhQS3|f;wpSaRX(h7A_v?La-+i?RXMMSyn=utF3@=R ze{fM~+D@Er)E~3|91<}+zH8)R(rD4qN`LQ1?3aC!zrt_|3h)dQSscMHwOIKpCGg5H zE^}E7!r7k$FFS+&&VvedcdTeizKN|)SmMCWsZl;fY!hw1!?LP*v8Rm<)t0!8qQhNo zpKT1dYAd{Xem{DKrE0Lw5PtO(Mk%;VHuX6&2VZn12Q*rU9;rJp%@Zp7W(1Ue0S{Bx z7^|YBQbGi<&8)Jpq*caH7tYMN#%~6cOt#d5m$dpj6c(pbqi~3 zHpU-yuBB+Mo*hl{_f^dvp%FW5a$_2h?2UFZdjX2uQPM0l@Ii&(Nez=BQp;_)2yq|c zmE%}5h)M-hew1duYSisSngWu9mJ36S11u5E2^omelRnF#9pldBhe+Bw^J8N%5-s*A z4AQRv0tSa@-XO*SxC-;h4r58CIy~7oYXMg3SL0jAvU*f|I%JgK>atx?J{Y#F( zH_Avd70&D{UOi*PMWhj1JC|JW^}YagvPbOK$N-j{Qr9BE)HSlbTj)4F_ORVbR2g0| zsm;I4WHJwQCX(q}A;>D8u|#v?fB+sc5X&5fgTz$cR#jA>{O1IaHepJNb_kyOwp7se2eLW7jis z=S7uJb(~)2*pS$Xt7nrj?f?J{SpbMnyGiJhV_8Cp>-HP>lF{bn({PZs{!**YeR7U= zVP72m5C9VDf;nT@x8oEVbc)hnRWLU!(^gC{dq<2!tIK3RSYrgPF9scYXbSrL9j6)O zsG>acPyhg`NxpaymZ)v=T8APTIIAh2mHJ+mu1ke3&Inp^aQZE)Q(WCW96uhLmucB4 zhTCiu;26xhu?|ClVkFAW2;<*>V&7begLBcz>!o}$IvFRodZ*k|hS@wSMum4fJiKFU zr?~n5AJcKrCEubGfgs=g?BaGzfaU}iG?TSBwQ*D!bP_WHepKClKqD%|C_^)yFWM-aO~nY2Jm=C{ z%mHy!6*5qS?*JQ+*h3~gU}O+_6XmWfHcoG_TMyE;&6eKd&h1|JiO!6xta4js)> z7{jWJxqJpYj3r{HNwPGccKo9G+9G`D-?Y3`MVx6vmSqT(!?ijM{y>Z|+`qSXcjwx9 znUZREKF5pnV2b2}J1eXKiP0Q@Vtd3}lt6W}LvJ|#dz9q}6M=X>kr$igC;=&V#o?h2 zRonL|=Bwm(Vu%gYF)KK+0+8bw2>;1tfO;1 zDek^HtmOowX^)wzVS$DfK8#7k9a)*uPF+kJr z`GXRhQPcXpS|v^p!-&q+*ypAh_Jnc+$Xplj2KG2&y=_zC4l`rI^@XAF-J!i>U^|Qm z_%K941&?p|xM_lKkPF*W(eGo8RUGV>Np+{nHUb}V+Y!C7xcC%U205NUo?=&FfgRGm z0Yu>dFu zOJHa6?>bwO9|TGrHl%w$gVr^QX~VD~`=|o`1?KDQU;RK=X2-U00jJBn(gi^cfCad7 zxQ{mVzvB)%x|{Yaa4tckFsLyo`B@eHPC%zyZ~#lL3IhmwB;q@mSJ?njH^u{C#|9^@ zIxcv7t25G|QA3uD?Rr1}0%YL6dT`7y4f7T7H)%k=)c{44QYhM73dGoZqM^96-*^KE zF$3`jzM>8wcM{WLIbWvsSo~MI&23^}E(_6*k8J}jXRZlH$zeA7#lu(6<}*NbTb`cD zwgb0NbmHHvk2I5E?_l=SL43E^l^aR`07>oa>=%+vr<)KIWbm*R$o6={)@OE2G5>CW z{6+U-AOHXcH~pLjhwh!|?Y{yU`y5-B=nex%iqn7)4zO;h-jYI>z5Den84zazgXiN>@P8efRLyJ!r3Ttr`9ZD61>O zv{Gv72f$91))?OT5s@=Mo8SL4Fgg(jMvqi6Hzw5=G1NrNCX$W6IImMQ&i<6epRNS^ z(SXqd#bl^%Nk!Oq7t|>hhLI6oSb9*=TM6O^a7D)L&p!)Wzqa)Etx-dx+|4-_qm^n2$sU*e|-KSOVD-7WR))=ku25KNP5A2+P zB?xlx_-#a+G}JwC5hki7Gfy)nCK8dgHE_ty?wIg!COaV(y7|B$D=%H7+SZ&EzBmZ7 z>1iD=Op6?TI<{4k2W0hjP3#W*N_?sv*=>eJ5lJ=YB0ZC@i&=?xJ!iI?LOP3`}~XXELGpxzg)=9=n;q5MgC zx%f@p9cDx6@0fWFG`UWdgCKB0n_zcEK!+;79j5vJISt>6mF|92Ood=lSQT?-RwlsA z<9R#tp9bdtMv&&*8$b0RCj5)_U7G%Occ*CSn6Qi-mE`(5SkW=2CS@a5|CsoOGvQ~+ zcPBIHl9CgRLf85XAqHrNb4jJK%o1aN$W9XJ+jyc|WJNiBaAc3_fZ>Ho(^kju-0+Ai zXiG0E000dGppnWF8oAar7qrhKOQdEtEoz8IqPnt%WR1ZqK^@9cb`=pp|VM^LT$57-5W zH~O!;ddfO_e|%YqZwFYTg-QU5TPnOss@KDck6b4-!J3p@R(1*b#hRH77P(XH9GKup z5u9E7h5#;@G3ZlSRma%EXZJaKcY^U{>>rfWO5egNxPo|aU<|jJS`4jIf6ic*U~H(Z zA^Az0NSW=_D!H?WBZo<0Q!|_LJPPAWpN8-c-t$a_PIM2WBidtn8(|Ah`S(u%5{f@X zIg@ZOR>-PhGUh>t<9}AyL@?=zId8*jvHwV#TFRnSOxFZgD_k7h>qoO_5M(hSLPp!dch$O z3W$}V(uS=ZgKJUaC0Vm7`P70p3p_*K9_hF|6=M?MW~mgh)uBE(BZ1xK89TT9mR2 zZT;EU2YAc>w<0D6ia%AQO_wyXM~9fE9B1xJ*!D910qWP_H-y2oyfeN-i?bkBmmk-m zjJTOKj4p1Hn7jtHsZFsC_Q<@?HqD*hv#lx4nygVQoXhPlIA*mUxe>nFWtWjg#K{jh z!MSb?g7 z%*^SrKFCBX^Xu6H%zW4#N^1Lg8o~VBXiK&DTZjhT7`e?vb8G6BAvOOOy;TtMhLwY*4lD^Q?VnoocA9dR|0d1*}dJLp1!uIQ4h$fg=zG{7lU{OI`A$Rz#)kRZS`X`YYYHKyvil?FwJ ze0qu4cC3&$3>y%f6|z|t_g-Z;$7TjY zWC#zfUr->Yj1WGydq5W$c@t(-Uko3n(2J3)4XkoGd5E^sS?A#9dOMpHpZNFcSW<0` zOeGkItqQnBJmUh@TWNw7HE@Wq0006@0iN&-bgvX*&)y64RS*CkLx6!P0Uh~Rk5Vnh z>7hjVvz-D{{5VW^qpA{y)jhZa%&h0SzdJ)>zUfCD31W`^5R)bms^Snfw^8O3;OM^yyvd?U5F%6-Nfc%1e%5Po5uxfpf;|@Nr1am| zGf5Pj{&j1QFpfm5%q$ZLD_o*mkp{1F<14_V>P8MGfq@mA-B5NUz)-VaAh`;!AI!_4 zP+_w?CFIHQo8TQuvNKx3l0W{{U{YEf#k--ySlEnm>}p;TsmJu7vG(FrI+ zDSxcrLi-09H;M8~%5zY(kFi4l^7SS}Xv22F+Z1na>#S>DR!lk_R(kvO!UZ8e-&79< z+<@Its&;88hQ#FdxR446sy&49I@Q&v(^V=%prdX{xp>2+(^mzDo$mJ8g^D_&vErsT$D_j3Nbu(>8KIv{5gyP7J{LJc2CtNT3|+F zo)|x0#fFsJjsWLDW=RuZme7I$vZ}s+<@6Z>)tZgIe&r#Yv2I}i01Yldn(&68KwA1+ zTIp>`l)wN00|1}@1Y5H}9r;2*$sis8+-8pZ))^o^U)rTrUMM)*kG0h&nl7&7Q)(X? z(KlN)&Q#Yl`PgIXX+K)8ZdP39D@pQpU3!+&uM*1f(S^MBCoS$wOjciW{~a z2IX=ny`Jy2RNhSEk3`g8mAT~}g$ls1lxp0w;Fpz)>Oka9~sIVpoY~mm^XsF5}AiE#XUI ztIY}OiM>wlU>!_OBle(l-=;2^SbtO;6!Ab#<;%W0nnju=QFC1#M zJ(x&SGlybgKfrbD8X$~QGc1LB&Pa;F?JnHAFBE-VIJnqTl{24q?5;?3vJ5#; zWqkB~-@VKKikR?@*-|HU*wyHb7WFcICT1UcfZy(EDCVb3Z^K9nd@GiBP{Lvs3Z|E|9UYN9< zs%S6(3Y1|!s#S+nH;Ah{%OlG$RT%+`X7+Q@;AjD?r1Z5xk7C+B!)gnQlX{iELU^Di zB)l)PQ;!>62efxq&wonNgyRqCQw44{9B1x5jtavH{^0DO@;pbMZxp}^&bF#q;8Uri zK@-q-k$A7hr%}{P>Ketvi^q7pYf0Ew#^HGY0K^P%{gn(12LV?G0T$VnNg<+h}m zjfDJL?F%O={f}mxmT&+BvW~m~U364-ug@e@kM7MhUSu(-7aChP$&a7s(QK7;Zu1kR zAbE+3Ivx~VoD(zv07y*-U`p%2w+o@jgVa(|5&Yw4!tU3)r8$$o@9S(ogJLn(JV5EL zm4YXpr;iU9018`5EHb;ldjyYIWC5K>m>4Vjj_a(l?!M-AX*XF4@szm;&Jb|-05|q| zBicn}J4Ap7!I|E@gBb>}Jnxh@4QW@)>GgatL4kneCEuZj00r8)#$O%6 zCpft*2(G@1d5$D=lSwcjPlz1d&icf#uCuei0R%T{X2ap=ZT3o!DGL7s zSl7ha&ZoF{%72IrBB=YgS)nkd;9&sWxg)&xI$3bp*erhnbK4Z7xy)iTVlbj7ZU6uh zhZhnA@H*|DIxA`b$TDpG=AzN=OLt+(f}gC%6bp_?=IKmbK) zFGMsW*v~=tjPDnGh7z6-UD^yLfZSjJ0Tk7eOib2RFYlU61aAnyxWE7dGac#j?DE{+ z!tHNxOBjy$hv^A*6G<}A00&)bXdOGNRe(m%R}1R*zPd4(BWZX!q?iC2)OzGbv=j|b zVOLYt0J}f|Hf-~YcIk7$w-fqBty=~m9{pS9ZU9N+J$n8Cd=sKCM`lj|yJG_YJZprv zs?sn8ry9!II0AiZ6%}%z23=W*H!uJl8FhtPp$wXoXKPY&4w`^4vis?NPkc!YLa-Rs zRho+St_o)N3LmvzxfeHLT(t!$00J*WORVO1`^kkPfON>A)GDRfqt?0 zX8-^>hs$_WH{@s&uu;LNdQ(sU&_BS9u_I2n6N$EKFU0_evc?^#vEdipH|ZZk*#0l3zx(3$1-7X4L=>k5{rTVMCuLOrC|7PjXV z5C8{f>z#?5VwcM5 zj{k)~NvlNBmFkH2suclfAoxWA9qS}u005xmKn*^@Ub$WQ4y`d>kYLgP5}iR|)z$%@ ztxO>V;#kfhR}D2Rl5#5X|L%);4DhgNhJhvg%cS8L`lr2!+@MM1J)qEiD0I71vfLfh zHtERP2B3-EUHpowT#VWQzpESq-)nw20yA$vl=#6KNT>mF}$C#cE$&FP4&EaE3)D@WkZVfNKI+=*&K9aN@ZHV0kb! zT<2Efm_dsP(eRS9Yciy5jCZ)Y9Ry_Dd2CdU`*asFoU^`wWFT1mr?}gtda6)a#e=!a z?OBQWXAr%ERQ>z%X^jV64}8Fg92H{!P&ILr71T0K>+6r@u}x}6;C+p9ss731^v8qa zd#5qzxsgnv<>ruQQi!p_|0eL@$;^EYKQ)Y(LZs3^NMi$SU3rVXHV@grxzxnOM&}<| zFa73V`Vhe_Qa-318n*f$`_`)OouWdQUp8;MH)H>h03ye%f!Ful*ohF?v$d3{a{D_E zAATT+>6F-StL8c%sUp_I2Gny&uA>JU;`7MmKBjh6i$cE3RLNBKVdQ9(aQ|sQ2d8xd z1$-g$-)UcROb}F%4e*(~*KLlEMfw06Jgir}PC%Q9lJ;?}ZF8izx;AcxBD^B>eDX_* zQt9z^Q$PUab{au-oRou^mWctHgwQ?!%vwot_CwBU`aAxYZ5%s8<*(d7T>It;escW$S0jZ4D z=)O9{tyMY^O^jl%aRk5&(z>Ko7k?|NyzfB;yqv?=CHmOz00pILUN-l&nyuZWym(AV=^69@1y~yqAEFbiUNrt$y-q>lEsBYArC2J{@>4l_n( ze~;)Gv}~xrDb;;=)@wc5fKLaSXub8sWy#|J00RI3-0DS^FBJWOHrL5h)GXi)L!6Sx zXaEB!00Y~a<F%GNY1FUzs`Ay}$tAKuxDWMIs1h&(I#!(E)XBhv*JH{9oY( zk8#$4%;Mz$0<8f8{V#v4i;H`zqGV`n59MUXC1q0S5qEN+ohhVdgNRx!1f^Qd!APVw)^X zRjPyl3A_ZmS4qv$k*)d&?IeV4ib8=9G;xBvq70LZT{W16m{&f>SWG!R-DhGf(400Hs7JBb001W72uG{qBTtXRHNufu@1CTsU@MJOlwe!?g}>RMYrl=m0AiB$ zKmm4C_cxnOf_6?=#dWWh4QPk-Y!prcbMbjSsM!3o4UF5s)pHPmF75E{Zh%tVKVW_| z?t0$JSYM32oU4Sy!SXTpoZx{d#M4!TeO!GhrXoM?jsgmt#(7X$FALT@68a$IAh_GIx5TX9ZL%q8G!v+l>msjo= z87qRt_k@$Di4z-WeW1$)&aEJ*iZUrcltCndx-Pv zDr->OIA23u>&s(c8zFfc&0;0I2rSXhYHV4UH1hOA3W*dZx(i+=`0z8MtuEB;r*O{w zur__nz|`0Rw%E{?ORJ=>S9x=4c6KN}Y9C!FJGd^SMv@pu&nu6Q5?g&VQG}vD&nIR}aWg)tR)Ct~N1I?Sa zmc!3XA4YedT6X_&B4h@)c%q^CD?s6oW@sS^e&9qs^v9>Mz5S%VV*u$L$OMKR%2Z`_ zA6i=C=lpqNmM2J2UWBrFtXlAXjdZ*r>nIjC$58&+fZzexWmgpqR)Kbpiq*)Dnr~t~ z6Ap`c9DzMM}bWI*qx?^U>M3=q{=_4$JQNG0WO8+`IjPsrDS;-B@ON3r^qn4|~Fj~*Kg9L{QKfgR3`AGbBcd04O z>mfdFiZHtuUuUDUv}o8zsef)W^Tizg&#>MD(Y|L-I{cOa!Vu&b!guSnSgw!Xy%u1H^P%~|K|4T^WT8m1tV6HlbmcV4I z2h-mP;RXH15L5;W;s<1B&^nKxWN)=6u*kifY;w{Xsu(O64s#?yn~MOzWYZ|r;xNA6 zVL#lvX7&>oTsVulYzsBBoBZHWuGFO(2C34HxxX?2KfCpgEIET%*(>Kns<(Qa=i<@} ziUS<*crM9GVnpZ_BAB~u=O$Qn%R^StWi|s%;QF2RHcT%x)E$z(No)!oL#^q+v^;yLpA`~u6Pf&SJA;fJ!7wWLu45#yE% znT+%v{`$1Ujy^Vfy0?`+(t7O4872$zGV3F?;0E6k;PGF0X<7o;0MA~&(sL%xIk^B} zlFbhnu%b8x_E)v|F(7^ka82F883{#%c?)xzSE7$2{>ea(nv5V5fP^IVRGpeOA{(}@ zlE*(3#@q4$01Ea&n*ipZKwDb+TUzN!l)wN00|1}@1W((zosl$tD@)+3I?+-I{T!1*f@b!w0-S%>4ah?a5)c2qo{#D7}ujZ4UgK zs@fEpu04^au%fzZhdM1W?w-z%EsKFS#hHTQ+c;L8$E&H3@j!dWEZV z-Zj7$(YdaUb}49pX(zb~wAo?WPEiSjdYw>cvZ6tRUA z=yU<(sN(qu@t!KA!kqDe1MZMa3)&8V-H{or4v$PBTovoaivX;mRj2 zqG0o3B8>N2EM_|^x9^P89r!E!8F`DgVQMG5iUpS~chq@bP?+VP$06`zQ**i?9OpG` zy+^$g$dob*?iaSSsVlB&xcX?kD9{s_vl>3hj{IfGo{S;8{{n?BKz<}{WqSskh%JxwH{N=xT^?VhyrK(QC@hVREBVJ*%A z=i>wP;adKCqHehX#(X9^nADz+dK!AYz%qr9cQPV0 zDD3qBvG#dP2jgc;ZfaFzJW^NsqSeyfZbv>tx7#b#KVZgimp^GO_(lSbnTS0F$tH}w zC6Yv|pqr!D5{#gfEyhf8HC|~!Ztqv!;c~q7$llwj(1EH}*Xz5g2lHEx`)dElbM!KA z6$315sgif&!pJ?YF~ObgYGy#W(U!51FeAdh+Y_gx;m}Uow-UYmqGv>72Y+|j*iY#0 z`?8b)5{l+P?8tFiC3GFOhhP}j*;*p{g&(@MGbg)~z?%y;w4=hq8LQE&d?F+MAGDwy zSf>A~Rtc@g;MtM~K~k7~ynQjU_DJNX%Z+7^7W8TnRn8H_SH}u!+Oj+l&h-)-SHAqP z?Y;=108iE~vz_62cpRaK2`f`rMZTZoBJMe}F7~x-iOFe?|t-rh-=g z_e~<~LWX%q3nXz!nWjCSbff~OH;)tTWDZi2Od&@H*r&bYULp=Jz~#5@TZoN?Fae3|r5|-FK^-MPeGWgb(m)jt-2Qx@s zgT%4eJ{q;2!yRQ0YT)kc9+)qP)d(`jV)bL#;3q;i;XVoI}LL*;%ESI0=9IYweX^I6L<$ zI9?Y4KS&?J{QB6DAz%`p*Dji6wY}SOzM*^krhD~F+B_iiqcSzOe$FPW`HJ4)nU){a zpUjW=kPN$lgA?ylCobURZU+zr2ryp<(<87T?_Mbb!7;jxFYKSf21yj(u?xy!=);;~90^E-gOgJ$XGp-XR%B zbX1=^t~@6q<8J}9eb%cj@89-MRp67&@6ATnWD04p>A~?~_N_X)Hy%IefQn{9gplRv z$OwGo?`ur!|u)=Tz>z%lV`;i1jo5CmSFK{YQt~*EcSBHv8le1dAWv_Vs#LC8JBpJ`Eu z?Q0zOsXYU(4E=mfPo%v$gmubSI(_uBLjb%IIqdIoXy%AE=-W9?X5t=s`U@X`1C6vG zHQ|TSW!y^?;|i3(roIB3R5jy$4tT&ZHzZa%Y$L-f$pLi;#f@&!V}&N}hAc87Wc0c0 z-27B(Jq(%oa8;AC0Fp4$A*XfE3E1q3Z(xL*auhp>}T8y+!+6{rDgohY3y15lOTSpG%zk& zdjMFwrba`&_kaLMCsAe}D8%0x`AWnklY4Z4PJMz@uQr-$z;=&@RwYOJCVo?=s?238 zy=d*i&HxH8VD6rBn#3kc@ErRlmN)2 zIhk*e*yN9n6fMI(`$@#|44YlBRDcQ}#iA@i!Fvnx*bMJIu&;TN*iO&`E$u(pT;g48 z@F%N9Fz1P9{*oX88$G{2MK;~o8z8Ew5~vff8MwNo{DuSk6VlY6j=-{ z(k@L~m+X$}juNOVf&6EG2Z)kheo_~1fh!_P%|4cQVuB@JQlS6}g|LH9h!tBKz%x|Ma-hm{RhEroq!adlX&x+8am`MtT4M zPi$srXNcoag1s|GeQW7LK<{bYj|Aq&9N=AVIe0S3V9AeAod5t4^Jy<1kfI^A{!vdw)j$_+-527hGp|{9!Tk9%H9fAv)?(ARnh1jg2ogSUy`YIC&HeED{ z05%5BA3=lHyjLJUCK1Ef;{m+vmGZ`#DuCFB`b09Zwbq|v51uSF#y$?>6mxM8Z7!5A zNeWelxKQ<&%a`gbqE&b8m9VGaj@>9XG=YbHl`(I;)>MM+cFgDtjqEk^j~3A4K>#)eh`gu(Eq;I&K zz^CYeqkSUK3;+NG^+BHqtbC#9A^#DO9ZQ`u=L&;J@oS-oHGsWADXn%MUFq@y*c!V* zJd>!v>hH7`0d@K*zB2H{2>yDUVbU&rSX!A1Kmv;;I26uSVIuR$Y5^c<3KKm48l<{?zZzN*~&%8O?YtvfA)uBz`= zIe7gGwSKH3M3Q!GJ?8ZTeOqo%0SilTb~s4`RU;Kp2E#}X16vO8zY-I zc8+P}`lrlbs4H4l1D04Tzq^cn^^Zw~1Xxo~+O`OStua~1#Ys;Dk&VC4)n4E{u`s=j zhKBqGMu@cRJlrAH3(48_9#SljGU?ov5k{VO;)tiG?THwSMPlCrXrs7)guS>%t+P6; z9MBswlf?<8u@dUTewtgwK}X5NsPfF2 zSLq{b9;w^I7=R!9skoPw+?0fy6=Oc6QtkuN0Qf)$zfPiD7;~7rvY}0>DZdG0Pp`XT zIU`iF1MSHTur%8O@odsA6yH%XOU|-I$VA)JEZEc+jN%tIPgJe}PB*muJ8j0jPQC2c zTx`E*D^il9*ybrE!fQ383uHX48~i-(Oi$C2((jv0#Ge}EwfoB*+rc&A6L4Uep>vLi zc$Ld0mU1%w{a_%mVl*ixjDlN`qQsN-dIJZi7M!ur_{mUZUyAw@@uJeCS2!ePQge*v z%4Q);+*k(^yAU;SR0m$5@saarf^zdmY1?d;SXU00MFWpAgJ+uK;x= zOyB?j2x%<<2H8?tA;Z@*ZMBNjr^a^^r7w|Q4rGDBK#SQ=RAM6XJ74e z1T}#reqvd9@gII*_Q()CK9~ln%BKW@W=@mK)#AT{x7*lZqHL22C%{g#4O)4)7S*41 zokoev`WYww0VtXn(ct@2of^0)vlrG2gchvi%PK~uWYcG4oI8S?lH9;%;UEFrlrKiS zsN^(0YrnV}PpXQUKm{?X z)49sv4}7-Ei+z7GILJRW)L``23~Z_k&|SG}n9&!VP6`tSp?LWqR4KE!)@M<}nbF0> zRVx|Ii>!J4Lw2X1Wo{(&HPK>$M?iccmo);usbppwX}!sNxtD8tcT#1f4@+_Cy}W#0 z>QX2Sh9meW{%-KJ47BVqnbYI%-4B~3Rin7mt4O}mf=QF`i5y@3TNd6Ev|6>>euN6H-8mQYZiX48Q& z&0*a$L-x)u(+2!Nkuwfc&8mV(Mq&P_pl7cW-?IYuQLbXjh!|8S@7w?jG%9yqyD*H3 zECPYHvUhv6NU)9b8LOfY?LnwvpzQW@GvRSa`T={?x29H3Q|rl{hEJjve4Rv+qE-dR zd*T`sIUvQD)*rSArI~`NQY6*wps)H`NK46oW~!j^Bjqg)`f^ta_T+kCTFI2a00094L-9WYJI5f!|FyTXGj(rp$PQ$qqeM>7#3D)h>1>ZOIL>Tz z1>VRTSe)_)XQ$d+Ro6VT69?2MBUP8jgfIe^^T{(jj(jbJaBE8x;_)`zD z58iWd+9t^)Y^%|mckEA_Of98Xdl^{6UG^uU#MuEm6Yt|Bu*NA>%njihOK7)9=6H+N zR!#+41`N-}D_PdJ^X#&R$ygypfh;5!uFAM|S9D;`X4c#_FQa5}I8wkv7 zbIU~;%{adB%lLbAmInn?>Ys&@q|(~z(aG+0c?gsF_g_33oWgyVaN{33lGD-GF>>R~ zlskWN;$ZS8K2^+h`it4Sg*xyw`-o6=M4tTsi{T;>ZDEF0XWs2Y7?78n=EGYps`RZg z8uN6{=s$rz&XSTfCX1d5VcH_T@%nz_h(L7}+^Y5X@hXJjg~DCh7k7XAJ1|DwWmT)` zSdeTv`|U~a4Xnb(4H-z7My@hTjBIr!KFE3z3tYXnVn~7G(E2s+$Z5@dF$<-+%@ENL ztO%pL`a?uTsHy95Di&A*-;d9lUpsb3GVPlo3r3D7wv=w0|2P5>qEk^#Y=tsdIcq0> z5nb3t>DWms>?x?)UX^=~>*Ae4F`)Zrgg;q%n@k9x9`dkG%TE3w-7do!6| z7mh8VstaSjwXj0*jeu|=j3k4@u^LP3#R|t&poEX=s~EUfPT-#X}4=#Mgfe0b*4h9CIeh) zm$oOvE_w=$R;~a6?J74le+JU9S;q!C@F zBoA`-_~JMMpQrF!DLI5!GQYR_W>g>5UaAE2+uI0|=1-$UvBRvm ziJkxe)|A5SqS$FqkQv&Kg@khn+%HgcE%~+C;c{P~CF#$h!!>xLjqL2r^3A&2GkwE& zY{EJ@B`C-~9SRucqE-?B3jNtjfFkq(JE|rbAIDTo58$p;oJomOPy>bSe_C$RpIZWK zFi|I4c=E2&-z=2F$AOhU=eixm00R@j>WLv{w@6fat*%|0009406!4IF3V9!@FIyJ#Hx?Brd1IiX;;{7R1-p0*Xr1E z|An2*Au`3I^XM4Ivl}B32=SWcsoq$?Qcy{bDS!YBxEK#+T$S8I2cA%wGC7{sSmkN|q8#s+5?p+0Ha@766TqeVF0&&o81x0sg z@EGzFYPtXZ<~HavuoRbLtaVC%l;(|0#KG%J!dW;wt`D{?C# z0*ILN=(;w__joZWeNRSwYc>sb@P{@Mv{(^@Xa5gLz^79bpd9c(^M~_^*zC&I$8G=s z29)jyxpHtWdj=MXm+kpuVR$UU03jKuF%5564NE9yaIr2@E$#~M%T4{kn}urnfy`-b zb$PT8$cp3hT7xYZWAGKQ000IVAv(E9%6V_!?HGXTpgdzN5}PwUGGsqH-moGVN9XG; zcM-%(CFstkt{ox3a%Y-+ehLLe$2zT8Nis2{Sf%HhPE>5|F{ZEp00RI$Ys*OG_5StX zqIFwCS~=AHEYzzu4*k{!KmZAs?vI(Clrw%wB_*tlhWkV)Z^Fb?*{~;aN-zTtQZ^2z z&-^i6S={CJx3dy0wht}Ktd(2I%m4rc_EqlGi|W;ArCw31K~p_B$+QG%A>IexrggLk z7*e+-_;a4F|15gh&d8%pAOHXZ0x<92bRP*^sUP6@BA+&T)aYI9a-Ow9I@pAn;nTbb z@Hs>E^|```wwK28HKFJL07XBk`jfrLwvN2ux;y>UXSoya-Nt6<)580Dp=gZlKmY>q z8K)>L14O!)WO(@_4iFlb?$a%L(_yj(PYkr=f~Gw(96;~@0yrhWZ2Fjfqgcm2E*!x? z0U6=4p4=E?2UND|ql7xBY41P*Lrr%Pr#RrX#xek(@SB=cUYIDnq=dit;UG6(po#Dx z0iqb1Yz1LSjaP8QbSeM?xyl=i-B2AI>eBNkvuu$D1hvsL002?6;@(%lYuu)A(us4K zG9~by^zlsg`NNurY8r$ZG&P1m03}ka*z?+eJ~xjL#Rphzo}*wf;q=;TKmZ4eLDXRg z*5^D+kzo#>Z1znw?cDmx8hK6Z^^QxVgoIFXzgCFI6o1Wtac}0|2G=1F8VU$>OvUH1a2ttA!4Z>nOx~IMD5V}L3z5^E z&2TbyA@3AUct=vz{S#@dKkVgQEqL1k!wvc|Shk3ln-U*m3cQ~w&_*I%>cS6vzP zn-gh|I9%~}li*8gPMs<$?oB6SMHT6xjxaB{=E28>-z~Bf(C%R7TO2P$FKI+`0PPOI z!e2WzmygamCHn=qBA-6WU+GfAph^xyQT`*kHDRT;m0Q<1A(koT<);JV6+TVa`5H8a zZkRu~5uzRX(IG!r9gH3i`w9}BYD88N22_7<*qWY8V@d!5yZbw^0LG$!;!4UA<~a)* zR>P=e?ybdxp#@9rn9@Mhd!`0}0ClZz@U^su+-ksRQ^|MDC}T2*^XxOh9hk4pZ~&b7 zb;_p&{ButHM^t%qU{>LrRRPRgqb9sC&OHbZBu|p{ZQu3z9%k7w`I6%=SQwx)3%2~~ zR7Mc!sw7&17f%CA41<6Hq1A7Jb_!q^h*cDgwgLTTg0OD;YhQHi!Qb=+CX^{KbD?nh z`zR)CBSOi8jaC2(NcOOKuc18dWN5nHG({*`Ac0#7SO5gyRaTqG?P{g?47|6huHX9! z;Yv*@@<_cQ#%ZZk07{|wc8FhwcWJ47xMRv^$si&CB2Yaa`|p^`jGH#x+aLfqt$&fq z@PBXRH+icWv;YXab3N{=U)l1+?coj+^|*=#xoiM0g=l5X>jGkq+vur&6hn~J^MD!s zrAWSq4$}upRCf8H*cx4|XDu13JMqIkOK&#nwUrCT+7%QaFOXwio&W$x{$zi>I$?SJ z9$xD}6y%@_i0aop{M)M@CscZMhuS6=xZv+K0rUU>T|uz3%0Pdq01>XTnbhmCF7psr zZDKY+3|lLhL^NZ;15TIk!~wqEoO^{Ys?} zY#h-?32l%d#g6e;000#p*a!MdXyZ`XX%7s*ZSl4Z6tu}EZEiS8+&~~|$7Nsfc;f&7 z0|FoV1dJw`0(=HvSo-Jt1wG9Wh(cX{-p2T8P~VOK05K>F(V9N#rIECk8*@n6;aVo; zRF@Vm8a`?c00M!56qnu0ux)?V5^K`>%gV2Y%RgSo z#PPH=UM2JZ0Z^!FKvjhp({S7`-@Zk8Rx)6K!vF^9P!9`2ndqnxS5My+b2BYzW*Cd) z04V{0NfXqUlAkdj@mUu*#c-qu?~?mPUt(VFryQPs%V1k-=|BL(_ksqwkbqSnMyrTp zFb2=*l6c+Lt7_5k-x+p7npHc!hfVQ4Qx*WRaN7U?0|4#m?BE+ApM<+#*njG9VedQN z6gnsA^BKP*rup{+=W|-TPh4o;>Nt)+#C8Tz((#maUvCwz2oV2`>s}VX9(u$S@P+* zVd+Lu25t3&NZUhYD9>3`!5BpuRTV?Mx_hr=mRjV{wGqNU!4Y#k5x&?%0U9P*Cap_0qd-x_9;7K5{Gg$6A!ro@Ygcx~mg+KC_a|{gB zvA{<0;BiqZ6wfMgRH{v(5GQs82w6lK5DD0i>Tr@S%HK59ydG{YEm^zZrSD=mpc=Zx zw(cyEDwBH1vL?CFt!w6q7MEAD5G%&UGCgz;!rMZp;TIJ>V;Md6tqh`5%6rs*aJ5BP zXOc5lK^;sE7OEZjEf}IhnW2Io*c)AU6(u{N5kBPT}6Msf%8yEx3Wr z2`;WQ<-MPi4Tu6;Xm%SG_VF`z-V)%N3l#*<1|WYvD?Z>cPX**tJ(^=$u&u+52)hd6 z{9!8pCWxL=G6w)%Did4oA{f3|J{*H2|E$FX7b{3(SHQ1-;kQUt+dQ^ebxI!V zrSVxu&+*&UbL&dzW_oEK0i{*RzEA`2mc|-gpiA^OL4`rq#^}$qbDA;#l)CHwo=~>$ zyj2JgRasKwJ#twU6#=cUo)MaOemtqL3POMy{{rL9ja_>!#_V2kNDd;UV?GI*)20aB zrn8q`UIm2vsy?_v@W~0%ZWs}gge2_=XnKJ{{c|NxlaJE6<4D2;rNouhAB{_O8EeLSzfiLzTVkf4gI=&nM_b|sW1F|YbFP5uv{0Y=g6(C5-MRa|cfa7MLp zOkG0i4Ms{V-p*eDk@?N^RAM9V66H zW4|Sze~8PIQ|!cyzwGAkNMl{op`|1SE5FJ!7nJhu(2dYfI!NvtHCR@ zEBCCjc!g?C0Gd=vU(bFLs6$m9kBw4ZXt7N_AS%?{`CHC;Tku}l9A1h-#&hpc`7R|< zWzpVFOl+XT=FJ!oDdNNmN&5+TNe>q-T(&II6SJ|9-9fw|DzZjz(EtDv20@z{hk*i? z*4Dn3)`^tB00093i~jnjK=2b`;3J{GGqT4NkY?6|AuB#Bpieo zfRhCdZxipGqrrw9Th0BWdNJZTwU9N(SYR0|KlJ}-Hx!%gf>^dB^;4SN7*h0}*M`g=l{{qPnlSX!re>% z3Zr@~(y|#R{%})RaLAG1FO)`CIST1>W7j0t4A235@$5Ks1i!I+lwR_j->)Zyq6-V9 z=2U>4;br2`)iNP6TT6u(c%uWyMrXHboUWd48M^%3TMZoQ!08!!LP4<5W(fP_wlKx@ znqz+D0PTp!5k{Mir?Hf_s&_*7FcRoks~^aufH0EUiy9$3~zg?;pSq9hH2daayzmdw1pNJo*`H zkKS4we2rLHO?$a%Zcpg`%v0>+%6V4Lm357ES^>?K|hv z$?9_9>cVToOmsQCm7%-&RC+P#323e4{NvxBG^yrk)8VD7-a5_RRH`z1K*l$s17fp0 zCz@J%17szeFQX+vDbV;HDSpU@-gac(`H`5}We2>g_`i6Ea}r3opUC{Uy>R|Y!rM=B zeOtz&M$jeg+VfCfJgkb`7OQhK+w~2#-ojs6Y@SEyDy+?kM!7X7&6apr^?UmB1gc*F zHl$mn=%VE7mr|U8Dw9ymEl%0yKw;H>Uc7iThX=!JE+AP6XhrzJVZ|h?^95B8oPQ!U zF<+27ofH~BZCOB}_F(M=73M#;%hMCD{rLH7+magqF%q zhaTzepj?i6_(rwdM>FAA2)mTZ= zaCCrVbpowwZFDcH&BxPCPY>DR$)|{X%|(e5+w}S^9LhKn*pX}%JEDKv#&~2;k~_cv z01jMmbv^_f1)ovrduGMm7ZEC>(K?L)Z*BkNi^A~AALtS8CFNL0ec7i$5_XQWzOujW zyz}Fm3~}E`a#9?44}u_-t83H3b~i5c8I2o^EZj^LIeIzu4)T%vJm%vewNfpck~Cd= ztL&)V&+1jObH_8h00J)!CD`fH_RPo2%CDPlB(%KM0g(lCR;jLWRmv4)f1Cnqyzz&@ z_f#L$Wt8O1f7S<9frLcy;Xy?KpV(#_eJ7*r$Ci{eAX1oJ@hPXE{`hPs!Jtv|h# zZWNZp4>%pcM?$)4WPcaH0z2ocZtA}IAU+GZ9Z>)PzxW;F8iR{JvPhbRp7t5;NfApM z=OCAhaRH`FYbYe}Rkf*F84p`;8+JY}kl2(;y0ljiA+-lDEMLi{wNaZA#} zCPQhMRenFA9%XpgGvEY~SO3b~0A#=Q+X=eIUI`fCLI6L78ED0f6DOPBiqbX%25W*s z9B&1~UoIjSezanE0ve1e03s7zZk8~vl-nwD+-us9od}oqHAVYY=tg;KtZ}cjtL^A! z0RIu1(f@{^D(^mWkW3hQb;#G*1dulNLf#X11rImjBwR|s)Nl?TT}Mv>KIet_-c<`h zfCTe1A_xE-TSb3`8OzxtbZbGRXVQh6o^+1|4eFTe6xCkRtzzeK)nF+EgN1B<@_k zv6$(R8#P+8!vFSq!mbiTi#hN;iHiPpcb93}$2}XZ00sQO`+bH2|21oXZU zU3s<+6C%=Wd~fshu=5aZIQAgt@jX)6zi9pjJgJNpuj;-oGLX_zKY#`uY~kNYQ44mN zImO>}38di%aM9oD6YbtTNjPtlZfKG{*Tu--^s}4 z{>d829=R%nghAJ0&d*!D{FUM-?wgPH%r)7701B))E|W5SB1kSiVGuO{S8CH_5O^S- zL*Tu&=s8R2XW96V-|yZXxRAQhPD^)EYdIH!UPEIwO(Rgx(tpkn4ZQMHlDZD0VukrM zCxC9K?4XDM3Gb8CMfTru1)Y7)yvP2sIOD`+g&h;sDPZh zG|$nU@q36d*Lb_Y18o_?xjctrqy zQ^Fz;C2iU`HoaLN-berd0{{W)^{vPToABTNvo{)e`q#4P07U=@##lM$#$RO+0ozc; z?Cyo!7#mft@Lp^HAEj>iUE@u>C$U$Qg-T@I)TnqN5=;hC%zJih&`0kjsU!vo>3?2A z+W?jv#_WLF&+{NHopV$(hzAq0<6}+|e`*@WfDVv{nQ!nQt`mz_1;{$w>QUMNX5%0i z*MEvlR-&xVYSsV;9sCR|4&NylurFn)?ot7OSjT`U#98hnXNvx@vWJfxnRJUp7y$0Q zQ=0$W$DQsq1{sGj-NPNUwNzm8CBAY!KP5J(!sn{hI04& ze0mE*e%Sq&t1%93A=&^w7?FxMc>~`cp1I}AFMkP|paovqkE!)K&43k9_!tB4)qfZ~ zwaiZKSc>(T&a+`VN)D|MvjJksflvSfdLwX*Y;dfu?_=ju5P!sb4(0WmQq8)<8C7TL zTwNc^d+Ku8enoZA014Up`^37JCziWf1|ny55JO8Wc-fU(_b2vQlyUF?2zZU2a#@UE zLk~4iY!IJG;Egn429LL~W@iVHy+iXWa#}|K00RI3d%;<^ZH;VFu2U)%bym2(jdeeV z^el2&*AlP*01Dsy^nhELZ7*W}Zx+6>`Yu`3`PL>MLDzy>g3$bm<3f=OA-vAq zCXbxH>uw29P}k~jLPzsx@JoH+TLv7Y0F0oltLlcNjo#Lyoe+%L8A4(`2${-UfN{vf z9GyFk1`arlJx{S{M~P)7HMc#7e~!=NzG(~YJ$m5a^q=BBgj*XmZFy5Z;`m}Y)Gga> z|3*{vjVJwI_%DWYD4nD!`Of7&L2sOu-XCU1*ql1Hz1oU^#5eUg7XzL3meh7#Q3=}H z?NlW64z$D>#;*5hSOWkgPTm!UQ(oYZ5p}AZlwFXhiML8aNy@vB_Sv002o;LZ#(yQ0HCD0s%uO=fgmRAH0FOLk+6X!8I7KOfvLE!L|66dmvaCsc=mr1`gvs}p-#M4{ zRlx&YKH;=A&Z}leP~FD75lYZ$R9Zj=3vc#@wyo!h&be5zC2aOw;^S?O7-F_1-T(rD z+x@o=GU0vMKO(4^h>v#Q63{=e`-5z1Yt6J?>K^5o7-i2rr3c&RQgc1Dl#F>Yg4wlS zpdjf^^m&JrXD}_`s5HkfPCZu1x+{Xjn`Xvb?<@QTV;cy-GvRb?AsdNCa4-W_Mr(f) zl(Y-ym1#y6fmLT-zy>OIrL-^lo?J7QgUSO8qg*8!ZG8ethdRlw*E$IY-Az6)YhQ00093vRv$3T#x)bK=q95 zLzi{Fo-#67D_vKHd>V_i*kr}Bz!^g8^fv3SSW>Qc{%Vv;;An6F&eKS6x%^Yc{c~%5 z`+ykdyU8U9OIw%4|D49u0Kvy4p29y4jQ-E6Ni%a6s+JZyk=Xdu0%~fp9b6|8AOJwb zP%9I+=)Um_l{*~-smTx+QntOHoc|n&>AAF@CAhBH{phW%KVvx5000RTzcX&!n z#(X=n?uiF0x$2;gDdt`7_jGN96~B5g`H&kqnE{13;(xf`000FjU;-oeNARAi^Iwln z+AdQ2vxfEYZN-RRC~DO(AOIiI0I6>dbgO!z-f-9FIDX~Rn5k^AP2=F3B>tslnoR%z z0{{m2_tgM7PG_{!YgZ%Nt-jqJ^jq=%{uj2yc)4y}yV-8oV=;gL00ss7Jd0{{RThhH(J(;J5THsFlJG+oZh0L8Fd z$&h#w=nilI017ZWL|{9Cq^;z2YF(Oeql2f|XMeB~{*D_0JVJu3UDAfi000932Y9=_ z^~>6FJT>Vl!fLe!fDNCiS+?pY0ook5qDkj=0_)`ukN^M!00*uIX2q;b0ux+syeQ&4 zFsNdplA~yd00093V*~tXDGD>p_$I_fME8;b!Wc0InIHfFH$kj(h)o-trB;1nLQ~ax zKpTpqi*rGhH;i>8ez6Du00RIF>cnrOF8s9{W$ zm5bRp000934vSd_KzpJ7T6ds6`5CE*T2jZ7;QN8pmk<#u(xMUYCIA2f056a!n(6-W zQqZ_aoO-rbcPFEM5*#p81@Ak6z|YW3d33Vyoa#5N^3q^2+@hmmWHr#y%yMCirk9f; zi5ZTVOP5$EBM4*Y02f7B1h{sgM9X~_#m}51BNB%c>$cxnfjebNPZiti^H@|g`qnTa z3ewIQc_h^+5QHvuxCMURK}efRU{Zti!IPxWP$9hxrZeey)rB%f79?nDu&#Yi29CYr#4K0E=7b%8O{%kC8a8mR{FS_ z)Gk#mfP_cCGku3fn3&`e6lyg($C*W~fa(==QHuUjsoWyp>lOei;DAZ3Yk(*r9y*%~KrryW@mpglB7>-4(!i zc%HCjp^G?}vqK8Wt6D(gD_`I|WiP&1vL8Agqjr0P(r!p8bSH4$l)3&0ltKwdpJFd1 z!;g~+N;}vPUu-Q8q-Y`{O~Phsbb(E2pI03rEWXWiDT$eChSw?29;WXa zO-LTz2iY;xbA$i@m>K{A?^s*lceF@FREY*PW8kG3x0xSJOaDoU#stVHwP209wMdao5!5Zu z5iI~(A0dom{)*B;D>JNn$dQ_ikvQ*UtiGl2{)sd&r!=djM#aX9{>Pou-{r3qCuP)s1|O1 zpbpF{O6^(V;VM=)F+eWNk}VD%<4c6{J+BO)04%_a$x!5Oh~O7%Wg1&wcR~VcR-Bx8 zsqqwi5b4jRT^}0`NM$O3DeUc(7>nC?s(VI|fF~^FKR_iQ2dFhs7%gd`Ny~s+K>z>= zS3#R9hM+)NrM0!MrLtu(00093B7Xw%iUm(H3=BJwzhZrgwwq0cb$;y|aeBNSt$IVG z^Q&Fy)|9?&V3Nm1b8uaNVoG!D`1^y*fluf~;v_orn7gCGsblT^0?>uY=5E1mO zl`0K^K>LHE2mXcSWFtrcSb^XOF%R+LCF7mo7-X0RG7vZ`x-$$WH`9AsK6#G8n>)bE zf_1K;qi_HK0{{R6003c@sDQcXNxmib)km5D`<^~Q@pk%u-3YIkK;&CrNB~7jDk|mM zFDaHDK>EEzd$5%yhfl1db;Z*RWPGljKX%S1u3TJLF;8#Pb|91wziAUYEdz>AD%afJ zyaO>qJ?+XK?FX7>$I!;aM?^?q*+U3B=v__X_7}1hs@oqE85m!alzB^Qu{*XU#T$4P zJ8O~kxe@{%YGr=kTuDHZF3_*lOy;;*K?K`rRr~WCxky-I*zFpKAOH)0mbj(G4=Z^i zN`6C*Th4`1pt&Dvww})goQuARbmgx_(z=cl_c-+esx%tdjYdK~x}g)AKfH}v5So$J z9sE7pkJY?&H^4>-;gJwwu-GtVn!ipco9_)Gl%lu}_I>zlldXS7$l=QX9NiL>SikkE z=o2zZn{3RkbABU}TCBh2d(fO@1-v}WmUO6-53O#SRKb9`zHittl>W^ZM1})O2^xSPXl!M8=h`mq#LJs`UTE+rm~r{sHBg$u-qw+8w8g=*ZTo0y z1`7)4Uq-S)6+~QySVN+7_%a&f1}5xiFdT^$%A(?F&}YZ1mh2jC1w6%TgNLhO2DF6D zJ`|eiYB4~4w1bjlhQwD`mB_%()C|_)4p4d;UNrNvxN2xEFm-pV1V)&t7(p_J{3r;J zV}dJsV@Utl-B?9kRm!kx;6gIC=m)rt6i^F8xY-NU5wHMZ`O7?7?+xQhSVq7vaj{2h zIrAojX6X^S?6(8%yq=PpR6tx7?^p567;YL(>J|$b`YLM(F3~379lW8YJqSN6XZ^X9 zW_1eU6l|HJjFX}qNh+LR_6p3^j>=DOcE}M3__aN3J|*C_@{AXHUP2t?NuyMB&ea(Q z1HjZtDD$DD@oztv@#_JeO^J+&7E=v4J+T90e%}#SDId4835hzGCC?Z;h3Pc&8vulx z4zS;D(V|>`_n8@{^xj_Mr7AP22TJNk{& zLPT;iBe~nU7iD4tgB_JlL9#Z(pvFsD%Yivp>cVfjQ}Yms$hdbH}At zQxbxpN*|_Yt!d1y=&aWgZAKv)RAWbaZw-sjy{X19pZDTGs9q3!f)A%R3D#1EAqsWx zAKWd#STS_!_h*Epl~7jztig5T0gE{(0)MU{-SCOc{di`N+>9khB~i8y;sD)+yFx`h z`^0aRH_YcQ<$4iu-iXYV4io$Bs4unw)-X8KAAk@reBMNVC z@N)x&ncX+-?&G$ac27mLCT;475jsFrO`H(h6XqtFzPeoRhOL0Pe}v<)0tmBv68KwX z{Kt@Sj?0Q}>j!xH6!c?T#5Q6jYhCqu@ofsn)Ye#8X}HvbHaN_<(EL333;KnMQ~mu`9Ji78Vi2J2`9TK9yOs zwE~qWUW-l_V_eYj=#cjN6;Vsp992d59DFEp-2?hjrl!MlK8lzm4huyCoOHLbQ2x4f z{?=U<6TKHBB!ZG58}|Qp*R(Qwq*ampI^RuzSJ?yxUQ3l@+@x2?BF8!JKYMjROlxV*B}#`Wo*~uWd5(iushgRZ(|u+gUyMEl(I8x zf|c6!RR>j8GXViAW?0qb2fkY7P80Bd@#=C6j2D22C{Pd%7QR5%!xK2Sq}m$%?Fx+~ zzsrL?%0{H@u(_WUNz>vQ&dY1t)_6wb`KhYis~2trQKs}0pGRAgFKJl0=br|0W~smH z3eY#5tU3D7p=6Uspz$DbSqf9-l9D!zz7ed~!V5S87&J+QLNjqU!=ZcvdE7tW$4&yk z01575@!25D9uXCQmG985IKas9l;oR!jwJ;UV+`IV9ZpKE5pzs=V!fB$iLMI1%U`>X zlz>N%It+v{OMZpPiid0Trx_xfYd}ZIaFd9U3Rd(@b15%U%_y91*^x)(UGLJ8R=Z6; zmT6iA>I9?e^Ic5D^%z{CQO0$@~JXVF4{fL;z%%lQ*azIC?XlR-J!@x5RDcDva z)8^P}^aP!})1N7$59Y(#fh*B>uPu7m_D-EFj?TJ*hMqIWiX%$-ymTf?xyU_WY{2*b z{F)F?6MZR%Pz}s!dGo0y7%!Ht5{wJsMnx)VO{W+2qv8Fc#1l*w_}AM;w6q;rCJanO zB!Ldt>aTyJN#_0nQe|DX~eO+~ow>DR`KQxqF^Y%ufQ}0ifU=&=TSvnFmA1-T#u_38| z000C`L7y@Ve4vUQm;V;=G@o84ZyDoW*Ui@%@EFACEVMmbPLJ_yXh95(5o6_n0)onr zT;kY7ixjxo1N7)7;T=dJ9DckDx5gpNYm!4OSpF>XQ&FtON0Pu{*enPpjKeD2`)FQ( z000933s5i#2JA-j^Mr&AMeczK|pN7+fuQx({s@DrWPhW0Pv z+@~<8>?A_l)TcRb{G($Krn2j9uzSknnHuE96S|ttozg{H#}pP@jyg4V@v^Hr>Pc33 zHV`LuTLzif(y_E_jCD#;fh8XRf2fiJS3J|L9VtjQV_k0M>U6%B9NtDgA`Cg1LhIDT zVu{F5U368scB%T7V?{1r9U%0Pb{Bdb8FE)sW^pK~kAGHx(YyF|MfXhvmcj3@HQBIA zFgM;X%X)6mZPXTk9b?2D6sM&D0Tlp~nt`1*pl2=2rQf7fV-}pR87ru182`Jt`f~w< znGiv3SqQUY>h!~#-}HsxsGheWUz9VjjNPpGAWF9ipDn5dhUMfj?qZ~eF;HSfVrN7( z@1>$uv>sQYRtssdR*~%?bDlQ@erkBBy0E~q)SE3($hs=4?uo@el>oo6bb$=yF&x!;sgqxKgBU%iV(WLYcJpUDAP%IX;YebF{qAB=KwBPYa4(4R5G3;-^U?Y` zCc}&q40p3ML+|B<;T>C{c?voY)r)H*j`3i-Gc7mEqw2-5OhnsrTgl>MQGi?o9?#r* zHoybLe-VjP!oWqf9WR^K>2Qi^3(OzTs5X^b3Fm8Ueo zVcd6n!?60KuoO`_w1D7SCSo2Qf;cz zX#A^krpY|YwRn`Xs&t^_syXFdRIcY29e2Jc?Xd<@=lnFbMw} zDk>402KH2|(HT?-LEcAjqdW$-hJTbxS)6%+(6jWWF)4DFHnp>2nj5r!^=m#r4=j(| zv~<4>k9%f6JD9Vu3QSf5zhG4My!Zx^D=2(HRYXJ z|5BR1`AESKfPMtQ0006w0iQXnYAgR5I#fY1%ob1C{WQZZ%7neYW)cZ z%!VytfXs+-<>YX!{jq8Q05D#GlE@c8VWCv&xxiohRw&0wn1qlI4Sr=sE%({9NwCmE zaDvI6S1UPd3$<5tgeHd>1i}8pDUd3lOJB$m#^~Wl;mdvbFhhtx#x4UQe82u%N>J0J+z)uD=SzFSLz4gi9=$t2^z?BMtk}S7{gOr zyXjVAwPWW#FL`8}P@?8j@8#h+oo`Orx6Eob1JKN)MDHp=eTrPL4p9tyY&TIbaz{s2 z7-}X~Sqk&)fJUe70005t0iQX{YAgR4U>IK!0DVAX0LuV<0Yh6~EXYMb001UK4sw88 zF0gG(6(3CjnL1}dA6oNBp zF%>P0W4TT!pa9~>O)Rnw%XhY@oQC&C&`=T$Qc^k~W+L8BU& zFrP|Ykb1RL+;vJJkY^Q*J~+eyLoo*{2p$-yO2jCLi;d7R`BprFpy&HS#g_6i-pfi# zRk`|A-$NW;>lm)hQ$#Lt%Natm^AF&aK4{Uxky}sW3_0`x<6}<3gzJ@CE$0~&(S96Q z8`d;yGJ$INAg{J@Q0)M~&!^s>ST~^OL~=Z_N7Mu(;$kN?ocYnmAIE7HFJB<@L6I{J@R2)z9Jv_U(yF+kycUaur-Q6`1B#XPd z1PcUrPY79@5IjJDK!Q7g;E)i0o6jTf_j%8mKW5I#^sSz$zJ0s8>Wn=bgpsvgA0HaL z$kvv}cq=7wV?%SNHV>PSUhFyq*lo2S2SPfK&8U2fCa1LN8?O~`f)P}nAU;~3+>Byf zw7Geitk<8Pjh~sw6LllgEK}F(GITb{J>SF6NI}m+N6t5I zXqx{H2K*7JXQ8byCuqNV2IZ}`kwqW!S#R|~ALaR3g+a~L^b}(}2cpEs4+~?BaK}Vt zYDT!PMzAnL0Bm_>*$^^YaAr-UjLEFw%Z!lgV1)c3{V(0T9lTEos3Elewo2Nb>|8DE zAqJ<)FQv=YXx+y(CQE-rD5jnmevwpak#s%ZWn5BDQr4wKH_s@%q$8l#q1u;ulN})Z zj=+8Xihd9WZW~lksTc=bBJ_pFW5YEbqyT_)oM^xdegWzS+L4Ba?5Qn|v@JxMCAT+x zLW`#Ew(hP7<0BHi6ELox9T9bB-I^jN@~e});m00z-Xupt-2y(Or;O|_lSOlqr1j5s zf>We=(S>2C3Vvr$ zkQw^Z#PonbFAIl(CfMd!RjRt%5Cq?)Sq3P?A0t zv3qK*AFUfAGtp4!6QV_+@pa{5>7KlMINNmfKU1LMjD6^ZjYD=xrBf^u%5E?|{VpeEK z(6I~O4-CP;ix*nJbA3aO{93X)UW}M2#K0Ut?Tgk$D-@VN!x3qbJXYO&DVAbnE3Dj- zJ6fMVk8iC!&PfC4!rs7lvBh7*MNKbd6KHJ`noyKb&t8<5VFEno|z!DTs;zi!tp%7;L#E5jFI?`Fkp)8vfgcI9GyBz9>)H+J7DncfUDOi>G1A|h1{Co z!x+^mIfbc7D{(wk%_!soujXvyU}<482M7K8I3Q^ZCfD zOs4AB>7X%!KC{*Q+3;_TR#wd4q`v!F>ZGLbhlYiqhpOk8CTyX#LUQ7Z+?FT@0pi}7 z_-17Pil|~w1&3i_-sYA52p2rsCa9A#Q_`k5?Q?Cs)I6zd zp%rd{36|ybHeS{OgfG^#*ePBX;9dyXT@Lk>VPYg9tQqY9uyon%tS8h{$hPV{MMzuk zK)MC4%1{6i99);~<`*9pAro>Oeocz&e_zwT2hqmW9UTqw{W1VH`^xJ7z2pEG zZ(XO;+mspfwX1ok>r(#&j}lU@OB|}^;SehN1pl-T6qhG-v5CZp3+iunVKB1B^SVPt zMLo>pf32}WkpGI$G0x}o)1PW%!`%;@K?5x)oYA43EpOK*S_BK1HbJ%8g4{7*na}hR zQ2Oxqw^hAydREnJ@2^*Le!izX=H3>y?ItkTB4C0ZET2mp_UtN7smVdEHppI3k-oL=2q&sK zyNT!5*+J)NL`CNPSaOyF%l`0GGVOC8$Wv^Xwm&pi5tv25FTF#iN1VQQ4Zfu7DJjba3$?-e?0U}eKtBE zm|8`f)A15%=nSPe{tmxrJgf);QaQP7f7~ZisXWxTvLl9t78?O^Q;FoA*TvbB8H5yPd-q6neCNb~J=1a}@YEu#bh#h1Acdt4! zrLvQ76^8nWXdz$=?qdlpyMCU3NYlO|md&vS2$6rgjFrQ~FSu?}K0D*W$G#U(oY^7^ z`5ZpI-;@4rnuR!vpTc}ub-=;gSrv5Q^vFj0KgrnRQ2yv6eaZEPDla7jQV$^`sa9g>EBtW zd=CBRqBtg|EvWEY(9(##VP^&U1M&N^c!5v9Pdl=XU#Dtf5QOD7!0NyYm`QA=T80(8erCr=@u}Bh1E65>HJJ z511Smse~XXcb;nyqO2so^LvAXxDtU-IUy{`1g(lDs-%-gP0(g-ry)I;)(8@arHr4$ z3nIsbW3Pi_KY`Pye}M)69Q6O^6mPhViIETX&$$bTFn>347}q$18+#a-23TYg#JOk; zHvsX?x9K4OP^t~$lHZ7xEJX6YiWdB9Comi4RAuS?vO}D**>t+l{ww!GE{3|s%+5jQ;?O7umWWa&-lvkd_2r_&tD z25c(=E<#$#6se8=lk*5ZG&K~c|NS;S!3 zC^-gsgxXaP9hP}F@N$0oeW&o%Qe-+RB-RT&#`j~3H<>;A4noVXjP6I%Zhk(-;o}JS z(@b*=Rt5e>eeOrK?O3j`%7CKI;~;$~13G!f*^n@`RvK*A!g-tM5)sTGVbNb~X;!op zyz_2E_Lm$wa_ylA(t+&A4z^IPkc+vT5bWlsCW!4m6wk-LJ-IhwD_P-4YvLj< z2hSG_U?=%DYdfr{jc=K4@&l19e&jU-91-B$0SF@tXVSd0_Blv`+SEwJ}bm_g{< z_6tl^jSzE7A2tZXON>8ik}o|8h+X}@`;S;;kmmxP7lTpwJxgwZCnPH&s?(3IEIC9% z{wc7KX$WfH>veuqCrM`dEw!9aHrCPFiRoJ*9w9{|dqgh<=^O~Zhl%vO916Y~M!z6@ zayR;HnVq?Eb1L(SxuoAO_lr>M5Rmd3>8j%7{Vd+kN`+tr{ja;jZIeu4zu9|aW)q}> z3tX0TX`4P3y_0fg-uo&8L!OHteSdE9%aU}bdnqa)4EKW<<1DMM&W$W-MkH4K;#R8+ z3(JlMkzno71C1NQ&x234rd`jCgW^AMg=_cELY;^upUh5s8{7UsdcWE(VHeB%V7l#5 z!fGCA*pX!lBha1*W-F2;t10Y^+G38oYT1_E7A!5n=Xoy<*Cm}~O7+~~!C%xL0C&t* zY@O}>(sY1jsBgg)9W^imLcEQPLjoi)?2(8*D04j#|IGid@7ut7w5J=0S_}{T0Yr`Z!CvEf`RkV0M{!z^b{AU=Q%1N z0d`dnwn8WFver(Kdf|5^%k8B;Y2J#%#M_U`L!~A?6`m9H?96kffn!{Z2P?aCqZoto z-8vy${TK`PTplq>X|S-P^%R*({?}v@y1Ekh^u(o~k7FARRrI;MaanDc#^@T*uqgQA zQ!0_uUqKq!9NY$)V#sJYIkdRXAS}J^stK1dy<7hH3(IIG) z^V#-!pN}Og2IXi8^-_^v3c*r}VNv0^tTaoPo-YCMq*tTc9&%*`eBxnFY^6P?_E^z< z#Jh&xFS+#J*6m-IffWA8`o4>L$ze7c6yWsH3$xsFQoHm?`WfjAv2du%?MFz;PQK%@ zwJXT)q>~x_NzyNDMY2%>DUCh?FUlO@tK>}5h8@$uo%dw`tZl1E`>Ss8Q!!0!+weEz z!8xogB`g{Y6*G;kiXiH(i$av4kJ`S=B|V<7Y5D^HMnvQ;TI*gVQw8Zk6guVWld>7b zX2c)#ui`3kk$b*O@rDeLWTWUmS1u!}3D6X~Y`}5z-Sf5X`tn6*&m86X_nCS0WJ=2S zYgedidx(jHj@(T2-^8>F)~S{zK*qNG+3tko4$I!@3HbIdjFLD7`OAlxuTP3|&#OXz zEb4Fq!84DpF;U4P99wxQ$5sno4hcWEqV+h4tuQ`U z_$}-4mB$a%6V*I(wh!DdmKb{1VzGM>ZM;Vl^wR|XaDb3)-W6Ix1nD<_sIIM3Se7Z4y#lz*wkhhsX$TQ&_Bzh+LKv_z>BfxX^8UWh6=VMCn$*(Qq}tsO^+RIz6Uew$JHJ$Zu=;VJh*F)?swK_wsipSZFv^j)76b=x{gzWX(K zZJ*VO#fENR2Ep+S!|^5me*zX9Bn1SB^6&+46`j) zjV41hio;eyD_SK+Aa8buc%pczHjoVkKm(c#G;uW4U|fKj>Gn^CG=Qx_nSQ<6tFpwq z4@RV%T%m!R5FGjsB?9>ec0v({0Wpe34qB<^b=%hhpF15#CM>%!hP-j)UiW0*i~p8G zc0;=EEBRK6#A|{%HUQ4k->2^{Fh1or>8(W zY{~h#);IA}BvNW6Q9>}#654r@6^l9@N^o`(c)P3VXil7!$=r=duAKYxYdVFE_t-80 z!DGvFw(25crj)AcAquoHEm18DzL03ds`O+fZ zNiuVlRDnZXUO$(mBR0!VNq!TtCqdFLTy)B!a@^F2TsebXlrYNsF!l~cMTHdLt;&`u zGH3crT>lYOnDqWO6wLhu_Q|}g;dK1mNcLj!Q!=vT@@L7`{De~?3tSY{8}5tGQYi-Not!*BU*k)_PLGI3Z$h>ve|v0souUK{mIDq>j!%AbBz6aseZ8nCIYjoh0F z(|oMEa{|c|@%fWzG5+@c^Z`Z%02h})UJ>!ANFG{xPZy1@F;x0pmt1P=luYZL1nDOe zgtM(l=1x))GC8%!^p)pr?j+W3NV-L$(FZMVCeH#i@%TN9)aoQ*-jI&pj-oeg5kKO0SCLzoV==wdHZ|DSk9}&z>wF~9J()(6c>DSTK#f(6j@dA?R zG=MeoVd5(%&a=>&@2V8&1tXGJdO417f}cs{L$-tsk$Cw@X zq2)i>PQ`iA>?tkT)?t^EP^o_BXML(#LN%F7P{4%u3R|pi( z6Y4DyqfW--=(NJcGN`1;__hw)mwiO+592GamwO44p*o3SpQqcF32!(a6607KQXRC| z8$NzCq>^mN4ja^LW#Th*#D0;PtUe*?wZVkj(*<{0Ofsc*C;#NE2YlTp0f1n^morcI zuEj}BkTBS~`zz%m*(v!B8Sla5A5z**pqb_3+x`kpqNkE8bS;yR zu@32Nw?BXLFU~Wi{>E+cANv)^gpzuZ+OmbBoS$XZ4=;c^M-E~|fB^s(HrKv9 zPX6nDG6-_stA&1h)8h~7z*o~7CX$B`vdQb@f2{h^t1oNAL1CxxmcsUBb5r`3Rc8T_ zGm%eDsl+QV%jYh0PVZzhjR;iH-8Od2xps4(0^D-0Ts5lYYgx~I&oi3)cb$4GYh`Wp zjsl0;L3eB!?;&9Lo*>{IsMH-3?%o62|8cVaI~K!fOC~%!AXS2Q_>{a<1v3Ny&x`XM z?CXP6d4oLQnlj2nd?*C@4gjB<74%yDmMjBCL3S(;T8+sch2t<_faO1bimd%-7Kzj5 zq+*BI+6)G6FXS}LRXmV#uc61V9FZH@d^4k>jFyoRB|;ULF>O=EaS{emI$s@aiYpOM zpM82wDJt>>wWc@CmC|F9g&*qcSp;G7*9Q3E8V@3uOp(XG9PnQc{BH-${Di>siU-pz zs+?B0gpT~<1Yf6J_*8dqrP@w%X$6=nM;z-8z?X%OZU_MSq%TB4Q>J)32{^U;)Bk3P z3|_UeAoi1lE|Kg-JJEpSt7Ta{n1Bgua?QuC*?Gq*xy}}nMz)roOx#MEtpw3pnf?#o zJ17UBCaT1azUvUOCBve_TSvcvLya1;TB8}sX|-#*f;wCELNyu*kC=au!8WDRcu~5ySyYTl9!r?#XmK`;F8FGYUU!d0DB#z+0 z9|_A#ZS_YRhdZ!|m&IZQB1)%KrInrI39$_y^{S%7aWA5urrhVJ77Gj)DyWQJx~}gA zvbQ$#O1NM+9$jYf41sxugecYYv_xM2X{RUk?ON1aSM0pxGlr`X?Lr)a_^vzCNr)S1 zP*m%$ACO9BgxKsnhK}N2-*P$V6VP5jO!d~JfGVhnisJAI5aK)cWINE=?t}WVtElnx zs~(g8cUVojy#7xbl#HEUZ-rkGGG0EVl9ns>VWN(5?4qX~N|mg(y}t2=UeDc-Q0K3b zrkX0I3x2zJV>&K0MbrAO(&Q)d%&_V&WQipItSSS7tEBl+dgg0;bqW&$ zLm#0wQziZ}FQp0QwxFph78XxnDC>9hx=oM$5Cxx-F&vSPy=FVEU>9>KM`!e0>3n4QgZskS zYkBIjEIieu?k{?@p7eW?KK7Oz&OrAcuFTB_P z`srwN)1+M#ap+*!fAf^tL~b6GvC1gBufhW%cc#D356tZw&dVR+HgadZq;2NU=!ZTM z6u*93M1r=o>`+zsP;^$ZsC{xPYr+6_@c6*%E6ZFN?ICZ})ryGsGRHJ<$a?7^=v{Hk zyd;ggFk2adni|`&(5c#C(b>_zr|j7xa2f)zrQ%{^Ro41Usy$1Lcil9rO4=d z6}kq4!K<*}-=fiR(VR?6+NTvNfqw9{p-1@9_+eN?DI90~jK)9vfeKY^6iKD@mD;~= zC6Y5)2z|90EBIY06umvE;u)jkje?@+I05sZheMMtQ>c^R9d?r1Oz#i-lLITsa1%$x z?6;ek!7+o8HeJhcy0+Mt_&7c>nEFj>)lBwy2&~NO z;?^**=qn+!i;4%hpfrBFN=VLHNwDwG0kJO{SgU_x8dihw&AZ!C4u)jdhgTj3Z|vcB z!m8hu4A;NJw?{WzGt(15XB!b>_$tbmI!!W;()MP#b#C-Gty}K;nKR&y*AmSj*{{DP z(T1v;O&m=tX<}7^D@Sd|LPe`}aBovsy z2a{q+C`cx|KPGbFmVP)9yTE@gqjIyhYcg{6TH_<2+>NE^V^Q!V`_4)*Se@ZoYljkO zsZ$m8d#N|j_N8C6f$B3?JL=gtW*M7?Eu-fYnu}( zy0ID$f%t&(PRHjIA+xm>=j@kd&R*0)siPI~{qG1tY%x92{VO0l_1*mbSByYJF5{KrBwCGkKYvbezm2NCWv~*&WfpdWTn^PD; zh1<)vQiX>J*P{e-PLyDu-M8f=dkM0=Va%ez)L(qb=vaCqjjC(?N7tExr+`=^H(wdN znzprXukEh8CA!9$M}|H73UE*&V;xxD)NsZ8XXFDA z(^;+gwOT;06iH#1+%`Qx0JhGLok#rS*w1WTJsLmdvJIm^9|s)KFh_UsoM*9!Z;Ng1 zP{vnu8$5wesPUn;td`g7?h5lk#6QuZ*9zumGl8X(slzu{x|C9Ykb(#PM@Ax7`iGd4Z)%}WA9tn zb`nC4ejIXW7u?^AL#}37+AN z;{G9B1N_hYfl2CRE3rlLgDdh5r;A^-gIn8i`SD;YeFL}9z#$+M1^~c1+&szuYn~TS zpdIjs-av~V?q>5L*NoaoxP)TtLNRx~TS|ri8Rnzf42>|P+O$6aH%+j=@CqfhAHGG{ zmnFm&Px1N3cq$$Qiuin+h-*<=PlIs{QbY=jEE<3!38w?s_dxWc_v|#zw5k^{ZcqM} z(uU*pG&cjRD1u8Q;P+pL4N^nrTEu}pM_qOH#Kc`qNE^pHjq_(jmHm;n-$LO={reah z?Qm9l=~1q&v&5J;u(#xqH+x~4(gfALwUBZk2NuEGIM{*Uw# zGOP)q6~I$AXH9=N0Q~B$GJ4tRgKUI{f3 z7(6i1SnqWelt87*5D)okTmVv7_V16WWz!{HWdO27@y#8`5d%Qce)YjauL7!3G6r^z z5L8=1L4)kEBlI%<%VPU)YpSr63=L3F zH>9jbXbwlo7Lr;>gaPmTXxrC5JN_z+Ayv8Z+rNlz&=lk5GJK&0P&m3eJ_ELfwz{R=gVRkPB?$VGfy#|YMmE+7WtHW5Dy zzs;WtBED2-a|>}$ap^{=(DB3Eh4X&AgL&A9f=vUake4&{@MI zcT`xq5-=UR`lYek`)h)MXji_UPM^oN2jk;TV*{==e$Sy-j2ZPxGfL0#tGJrVQ zT4SJiPaBtJ))s)v_Oo~X0n`2&#(wNrmtB);eh2oF;5&1+Z2VDKsD^4tiy?3YE1(b0 zu49PwiyoqJurr>(8XCH2!M{R>lH$UlpMXlk{!V(}sFB~U2L0Old&WcqfTIb|ei2%$ zEjYLV$Q#KXL9>)C(XwTh)n^saV5k#pN#P0&Mu9`vON+Q;5bg-kKjvl~gUSR0exZwm zUg`F}y%@V?h^?Kf{c4UjEc^y!3}x)vJ;m$;13{qv4pLfaznw%8kF$9+nznK@v0t=r zAV>>2AOOkx+>-?i}LY&wWSJZs=A_yNQ+HWQK( z$*Uy4>2{gFvypixXrsc9d}!IYK4$-b#}t3pw@P2fDo`YyGemfT+4dVjMjrG9j_s{X zQP|!;GSy$9>c27-XtITEb8P7IFXscBq)_Hwk-ugj+-)PyM!alkRR;gyJhAMy2BvRc zg7cGwH(Y}bI7kSCtcE|*x`t3w4l#bM)MP9}gdN~b6W zm)H85Pg_o!RK}a|J7VO$7&{}@`BMq{M+c{t8=2$qRTnRC-t-H^?;oBYN-+`pagL6% zYvS}I%GJNAkQ91aL3Jzc70m2ga(2QUsx$O7%bq%&CZ?TwripCQL?%7&UBVx{6f8zv z>$D_=_39>#@~W1&P4jAK>W29)oYy{%i{453W<1FFW}kuX5rvi5drl!+=`I6#pG6~o zKQb-lnnfGqZE8ee((g~RMEtQs`qj_E61JXW%|YJBE9o1hy)#IgYlndkW4M)C*edDC zzI^(^1F2AQ+j|+?RVNIoq74XbLnDr?H?_-Ta~@zro~&?cZ>3$-=@()j=ik5z1^{(l zfI{6@t80Tp{>#L}-dlqNGUW|&-Et?>Ay{k3bN|h{n)9Lt*y4I&_dQN2XJ%>t$W+er z@;0{!E`ll-WpW3~ePRINlAxodLmoRX-; zKH7^Gcedxqu(oTM++t>U5ci%y02>fIyzcpf+|F;Q8gX?0yM>^o+c0Eb`IT~3lwBxL zP?zS+LD8KxO&4xIZBz`KDTr8L zYqyj;gHd6-4qnbb-q}2Sj2yA6BJ%?s?q>@GOLHqV^+YP_cDPD-4i_*=3_G@Mm%a*c zrQyFW#GtwV@*6tkThmleW62qr^6X8CKDA%?I{wyATXTtdGPA@rv2QU@vi5O#r9QV9fg5g@l`8aUK8<4jmufcwI0!b`#P7+d(X%$*xFnS! zi6oC;bKJHJ4F;0y){K?pJ#gjV$^KOS#oV4yva}emhfWXKYaRH2Xor*Td|BbCe)@ja zg+HvpbVq%+6#}2Ju*;OjB>xq&J^(_@tgjpL0byd+&=x7t8pt9(3Kr$xw-&VKxihr? z3xJY3V8|1=ie)Cr{KWiV2kH2I5^kp{zKoFV5&}f0TDPet?mqm^OA003$b%U>ZXm}I zn(*eghPOVE<|!;})O}UD(L5@tt(l2brEjX~Fu48p{oVf2MnutYsfAWHS{d#o0h^5d zy`#w#pI`3~o6*<1PsPm=93f+3=$UWl zkv}^3F3Y0U;I`WV2su$l;S&{5r!5+rp?HZMGHP`t^1#(#zP0vOZrslaQZG(Q)ri)D z>oq?mB#)gVupaR@C(G4W&-Td)TG1HNm%28P)Vx|-&+tBPH?3Lx`HCDP7BS1w4l9>W z%?;m%K9H_)K=mNU#WN<} zYJ|lr25GU!?ahPTq9OmWmh{9gt6I>eOWcUVli2E+j> zP5IBl8gdP`&%Yvninm`T&?M*Cm3M(~v~k)!MeEUIIo@0H+4L_Dx8XUZ{iuHS$;l%s z{ydLGNAR0}L13N2mn^6GIJ6{Nq5Oe9;|jN#C}G486`vlte0KE7{DbBstOunIFhUO! z5c_z_mSYzyII(#ae0V7LbhsmN&&YhgQs-M`=1m;PYVJBNyh_?I1))wttfFOJZVD;! ze-BnZ=sAz)aZ$}I{g$Qh>Vj>dw7#HNQ5H9S+wD`@Bi7^bJ^2%F|N~mZoS^V6^T2v2V$#|k2`i`OAa&n==gK7(NfFMZE zrc{VG{6oZ`G*Zz>Xsl?wYLf*G6BR_N>D-C-GaSP$n(PaSQX46sNav9 z3y_zAf7RW^%?Lc~V3OSDR$M3K5OR9CMsP8|ey=D14pM})B}i4v1*C}~`QT5GK}jOV z=OTG(qT&rVT6h-#sq#2_aJGx{-xnJXH|I@l%e!=!?ATjM67(L6gfziFI;=(}3TGN3 zm}6_i!mcwH_GJx>!SWddNYWlOkG=-m&jy}nb#irmmz~se%=3;Z_6#EHMvl)?ikMD9 zrxyXkHQm3#aVZV|!)=Q{36w*5IT6dy2s`Xz7$G!Tsxh}0UvPB@5t_m}{gt=;&U1+{ zdrTwrqfiivN36{i^$J96*&}T4Fmnw{qWy5%vD7FJ=GF26Fde~XbA;;bALPvgb$I6i zNU7asS;q&@(qIUdeoq1pGQoE~thfV=D=+T4= zyo3atl_H_}WHv;0D+%%_TGAb)KMe2>L|1gz*dNYC6woNV^M2-qNb@_5DmrJtM<2Oi zSu!ZmnD37n^mK9O(-FJfFYGcA_lw4Cf^gJ#lzZ9tG@_m=YH;kQaP0rf>%$!m}k!e0pSY@L{j~#iMIa z;tGI!4p+(BWr|Wq|IPo*O#iErgW}}xCLW7G%Zf3*Uv){y1vOrTqkbpaX>&UN&7LM^ zfD*8pn@?{tHJF*@P1usf)2G(h+t-eoE@jD0ZxyTm;bQ3-Bdf-vSvSi8=*9EC#Nh=0 z`KCJ(`p5Ii_{sG7*}&U?H)XvG4|wD4gxREp;^)RJOi)zwPPd$e` z&k^o=txAb2ZZR|^cNMu~AiV94Rb*MHclL1`Csb_RyWzK}4bTrb_%e(&_1S^V+-b|r z+G~4mKebuyJ;2|!6SjY%Fl|TUp(^yckgIt$ZX@T#U=KW14@)!5b*C;5xq35=$Al86 z=?%AKBT6Wv2w}19-OC@5t&&779d=juMW{7R6e>L)s7j6fcqVJ4CK~f=f+A0DqUbwS zO(Vs`y5q1317DBmrupOK-m2c2)2SsIbko}NtmA!JiXb-$kNSl7XU8e4qbu_`y+FNOXHF-iiO2oHLvAYgm>(-R5tec)mk2NI#Zj|) zN9~`?e2V+p*;Z>V-3lzedo3T%?6#Z6^m~u{TLwq&SES9)NutBQVxv@RKL>mr)CjLJ zIcdqpWZ4&yK`=@brV>6Qxx`8yBn!;h-->pz7M*1ni&FilC-7Oe+3bm1%3(~&%J@Ax zNpgGqN2~C`dB6SRV6EZRkC&fJn&CNoO#gg&wNQ-AAOndxX6+B)-1ZvQ-gBBQc^gof zkal)PO{Hkj{c=Rk1p0d$4~*~Lo25^?BH-5CX-_p7-qm1kqs)-Yra}0Hs+#*9&kK6| zNq4D*H7owugX*ee%{5OQqq_)#dd!Ij{2k;xx2y-j4wt^zf%w#Pn?>O_+9MCLXi|$z z-o<3^iyDg6D`}>m#ze?)r(nlNN3ZvfW>K(6lf*6>C2ZAo!3S{v88qNrj{$D=8C z>;t-cD7ISOI z6TNIN_u@Eba%R*R=MMs-h&${2s(y`|+Qs_??S?>f*`s^TbPV42^MbE*!=b_-KPl&S zm87{*QbhVovJ^SmB5#KBpY)&I460L-s=jpW{-MDdu#p?s43>oh=LO8TS4b8@{3c?7$JX z5!r(0dxi)0d|hfeocN;3l;*1cP1pvP>eYYcQ2w&V#us|yQ~PzYH;O}jJ6&e^G8LgY z#=HV4h$5hv9M9eq0GcYCwSF>Go{qO)C`QEG9fr7oCR*4U-6-nqAi4VtpK{8{+0%W} zMTC49Uc84CH;Q&-PU4dPe1olg5N^lL?g) zPQ)4HFi@JucUQrfbkR)n&G*rf#qReWnH+@y2b${fcN{fRZL!FDyzDc2!fS|h!#hIM z-UQU%`O;NL;?-=4sPV&VpF|63mUPJTNcdhtEJ{l9ZSt!tjLuC`e3y5lU6b6@mz}{M z5}#%{&JDydPU|1kr!_}!lJa8ca&+@j1|C;lnKxJjg<5VuDItucnc4A1{)mi5^0AN$ z?O@SecQR438pmzIe}%aAah9lk7JM0T_;W$B%+H08PslnK>Ozi>j8_;gjF2y#T+y_Ewj#X?1N#Pqr|Tazo37FoLnM>xeIMmu$X;c~O5H zgT>QZG{4r!2!rjupq~wc*!E^qAtpvKbc%$ovraJRmnZ}}3WXh1ITT^kI+Rs4VdY@T zBkJlsvwb^OQqqTtuT2V%9{nGQ*@ylP%+=H~>dB%6h8TH-icZeZJx$ zMWI0BQQJ0p9OM#;9A9?J*&1JA^#9wt?D$G0^uVvgcXm5bdKus#c!GEeeF z`TiS)Q-n~0BxdzM#9bl@O05m7chQrg!i%4dK?_d+z&@u7fENe7=GZeVqag>I{(%DS z(>AeV|8Ow)(+E5H1?=!tIF-qh^eSov;IG;Xd$BC0|F^IZGP>6Ra5cQ4AK(p5{#Qd&orV5S8wnoe z%HWrvf;B`G9>I%^=cm^*q5>WcKbW7HNj5D$&OfU_xAJqqU$nRL;O0QV{yBQz^0uQQ5xR9>ugAQs`?bkfkW7aL-;r2heH?u`qb;gXa&-m=a^z$SAT&VJ&7*_ebH%*IM)7f2L@p)_4 zQS_u%osK2axjznTZ5$Hte_P8U{F*R-hkP)dGxy(kUVFQw6mpgLmRmw)%-KRV@ zvOHpyz3WfU{Y4weqzEJxOST=32BL`1P%~LAym5kmTHCW~NFhRoaEN>`773zc=xq**+|Cy7;Q|WRQ#9>YFrAa_72@k>T@P zmjE7h?U_1`vC0qHPY(X2(TdbI>%u^X{7yjy+ia_3Pgq}Rwk1m>@=FW{?pWIOA>mux z*zl51482HQ<{y!`8wPemmd5x)XgXsq#=K9Df<{O~glb!HP%7QD0QE*SV{s#1ua8Hl z?Q236ns`5$ciN*GjhEWd6VJEh8(BQAOC|(})ZV1EGxQ7};S*#%viBl(#-fS@BL7M) z@f5ygpIMz9=Zv)8?nAdPc!&XvHF&H5zhM^Ao`DW*Hu}qlt364A^hdOU_|O<1jf=+whQO5{Vy0h`I~oCLnzPRKdl7@`W+aQ@!O=5tyn%M3CoknF7+zo8r%|n zdy^9LEh*H4P9;&d_Z<&PYPn}diqAa0TAD!Ph@QMoE^4@otR^-0ex!tkstbKPqg`l~ z^JKph^s3KQ)EMf|VN-Xu5hDFH@k~zW2z~bx1(vEcY{~rc`4BYy-is4-N=2Jq&|!7A zAx<0-8+MCx6ue8)>Kl}=xnek2R&LL;_BBBJSLHIVzICMLGNh{Ic7q*Icb|cEys^C2a)H%%7*~}+*`%qYf%_br5KG0f@2ui3*Bnu}x4l1rkPs`lB{u|Y3~`SQbP7j~MBSweZpJhMYUObK^8BPNKz2t2@tiPH96Uk95kdFw|$NH3TcA>k;>R z)k5&=H~vJ`2MqP+Ks(BsoRcwvAuXkAsn;O1;J(l}MF7|8LR_mH9h)(GlI^`q>ZB>w zshC{_Myk|S8|il&t8T9kgR)=v{vTa$9TnHpbPJyu+}$C#y9R>0ySvNa4ncyu6WraM z;4Z--XpjU6!69gnVEN|vy!PCC-*2s1Yvzwx=X6*1IaR%@_O7gVGLz{h#bNYRpC!qa87ftX$6bU{h=jIO`ow0~J6@uBbvaL5Z&9Y2Yn&Ey(6Dkgc!W)O9TT zm|dv!8Sa6N#9A!^GVn`|j6MqH!SvLLp-5_YGulw<@|;6L2tCBkE2{&w=EFtGix2`< zy*2go4ljM9%E3k!DOH92!ybIDqFWJ0`g!N{@a5CZgD+*q@(KzOmrnzkfu#I&TIxW0H_$}PqWj7HiQaXyPOwqc?5v)u&lfFevfse_ks=B+KEPAeH4$d4Ee zSO=3A0aQvxsJ1--11S3{>^a%(Wc@967*rMFpF5|5#lsLfo4SMmBt*c=OuE_(iV6In z|B^H^_>uO?@h}~&9DDuC0D~`e%BO;`O89<#1H701F;@Iu6UN&bP)-K?Pl@j)mji+0 zU&nFclt=mf$bW84on_#0m!_f6g+cllyWU~tXK)bS9`IKXH-nJKqu3ub)wcFE8Hdf~ z!+IbVHS@X>dMg@TF4$NFh7APZ2N+2>|d83a3oVEte#* z9!ortyG(q{hW7}r5N|!<_Vz?y;WbG7!>tlM!Rx`cB7l6pP!;<3e_8sUCkfy?>4XnL~qHv#1_Q9vh-T0JSh>I151RiHO-`9k*U%Ipi2>a!d$~ zbueLNY@Z^Zpc3nXO=KO%PYax0Gg3aM)aFO@fN_$#_Cl77w{U+^YY_ zH`4zFz-052*d7X18A(lR09mXAm{AS5`z`*nUd3nMm2!3}ISSMSKv{nMnCm4oQeI8EE0j^$9dQ|7uix?zYL4;sqk#!jC zO`H>ZimkO4%hwhqawh8-CqiSY?S#9ztV^(gaEP#aOuNSYIELbfTh6ZcnXy>#E$BDq z5`2&xvqfL5#9BM+n~VwJqPb+u+cz`;ESKsYx8TF*N^43MP}0lj+r-%g#!n=O81-Ro zV5Hf8asTk>zLk1T-I(sh>HtCi5c~??U@R`&VdETytTeTb)&=ZK9uvjd{q8~0+n8)t zm=vKCGPo*HB9g%;&?^USvV~8*E|2Utv3;&0xF`UQvqd0bMpF#P_SU#O^+al4ui0#r zw#`nCq#zA`YGh#~JPywaWAaM|L7LzP3o}%<+DLv+mVN7{2QUWt8V7TRSN)#79m#tI z+GA168FK=$)i7Kox;^y>r-&P((Ei93SP6QfJ#9E02u-5#nA-LzQlRM5XMRCf$@KT+ z=?4QTiUCzqNsn7FM*t*}s3ivbePZGJ20lxp!Ivq$@n2WMjc-2bjAHmc%<`}8enwv+ z5fB)7_l8<`T*}``#|#(55`A-3q!88tC2kT%wuCYEqNHXQM(Irv%<*u0jrV2)3&H*|y@OL|?!8+VuI@er;}R)ffGbOlJb_gnD;%Ct>MJ z2x_9mmz&Q77bk8wo)S|WgSt9yT^@hsREQmf>JNFtkV3M8S83K!T9hZ3a_)5lD<DW5*OR2NhI)OoX(1KEOL49fo!p4PJhW^<5W|JJ3C7pz zwJFv19Wt3}yWLE$hRU{~*+htx_QuMK5A>aPEMC|#^Bd4eZ1ZchsipMas%>uw_Z} zn5Z}EjyvY2(cLn);ECtM^&e;OFzR-kB&L-jb*RG57)5SVtb<)TVlw4^mu@T#bR{|#e+q>O$&t?i9=u)<<-~l+QJv~zln3ZyBY+B_ zMJE42G>dPF+{vJ9-eE!jN%5%uGH@hf=nle;$og6= zVVPj)!VkOzDvf3di&?@{8-E5wGr35Z{k@`(SEB{N+)_3|PT8NrMu(DHDJsLMIHplx z=1r-=#4R6*YXGPh4NpGKbe3>X>P%Ba$%S$$1uKJFeg@DghM}jS)EX`C`{EA*%^ZMD zS4}WI18m8*4F#r(M7}IQM>+4t-9U|k%Ap*ekoXvwa-N$RU)s_uFo(BDnDG!hpI;+)Uc|<$_|mV5q5_He*09!TZ-n?^ zv_=A)M}Q3(w7KHgQ40E;Lp9|0ykHDI9_YsqLy)(2WubA8@Y z;<5+mN_ela$5cTzb)f8iIY4s`;9ZszuloaF*v0!QSbSY9*h=VdjHL6>Hlo*3sxmc( zi}zbp_Q@56)H9Zddps?geqhZjA ze%cIHYTuz&La-Ta@WA^B$Jr?1H0dLH*iU{_a$4*(QPHB{gQGyk+pz-_R#u=40*-qg7qnHc-xWr+2CGfG%P(P6`M$O%9} z0g`~u3W>gmlbswZ0|2+u3|dUqU=bBJb1)G5B!Cup^a&<=8W0`!Tf_Ia z^mQ;c(9x$sM}PLe;3xiznj?VWAgFCzHyj-PKg%rS@Snd47?j7%;QS%K(qV%OU_f(^Nc%+qtTiD(nBdY8IKSALx0xp%jqR#WI~*;tgq23AiYunE zx7$%v#z+?VH~=6XOLd)cq#8h^t`&m~6 zy&@>|pUawsYf4dHqhEsK0qxZ+5XsgpGRbOFKH1{*(&SgGw~T{t6#d-40O={9pwoC#eU!#IG_3_u^OlhA;2Zp zMS+A!$2g&8HbSgQ;p+RY@>oSV1xkTjwBn)7u_INhwMHX8Gi^IeE;qC0B4vBm2Djcrl?`yb1Hv|mGb#3AzG+qV} zh^%suOmyi5PEgGhi!XtTsLAhk5Mv=o)6XpzvuzF1l0c|XmR8Y$*su;H@i&Zkhbh6& znN=MV2`iX~g2Xh+mSj#SeEuSy+xg#FzyCo({-^3Is22+TuuLkb@edv03LYK|!bkt~ zdDDPg=dL78u7;$uh9YUT7-$HSG3bTwMk4~=6?kNl?fn}MV- zj>saKCPMvW61>7#k<&-dTm~(f0BWm}($M#F0?%@Rzf7ki3x+}#l%r`ojI)Bu6fdhI z`in%`4U8j=S<5GlcGG}JeL&aj}^{YBvf5#?KvFd zGd=b{jEoy=vDoyvm|VI+@Npnsl%e!!yoVtb$N7FhKZ;xyp+U!Kr6~2=dS}wP)B4u^UAO*CeowB~nk%!YsJ;os9C!kxf#$r9ZnGe4<^`=EJVk!2z(PQ*Y->t3 z-cH)j_hZC6BJk|H^1k>y;J2z5XP&5+lDz4~3=Yk;rfbnB=0h@D$bE|f&o~Hn3q^!j z+~at;zf$<$>8InT-@F+-M3=H@vk9pm{sN|g_JwtEQd7EgBkHiWeG^ zy?3vAZCcbmWeK$IGuV*A|KMkMw@aWR_8K>MQ@pUS#8ct1=BPcTZeS7c4c}tNkZB?N zBW7G}Z2wpmo4&D-vW~wAMmRnHUM)Qgu`Cf)yz?O+j|gIh{NODIVdo3)JegZxM#83! z+o~P!R9RlFD}m6XNN2I)Nm{>3zWAQFr=R0gpg*15?|a|B6FXFpSiD5q9g+g$UzXBj zCqIn+({F|e`KghfPr;|n$|}{w_~i$u zI8uzcim{{h(iuk42PpSTj2u@zJOlV=sXM^D_;JHOehd0QgAv3F2jl-=JR&Xg&yVP7 zX&pj@b^2TC!Y1xZb6?xN#$gOIw`K3KczU{Ba7_86Mp&0 z^mC)(qXh*oUXXOUJ)T$8$9*(AI1R%U*pKv9s0P`T==85B5Dra=9lVZ!SS??qAVTYj z6sZfvvHO^0BcG`Y4#KU5@45(%KbPs+YO{vYig?sW@x*>s0jQSt=$>-y-f~8E+k7+r z?gVRk4MSWW@8rbs@#V5nn;X_nbCGQfedtSYaZNvdA?*}a7n|%XPs%VHjnQO6y_(Zy z92-Bi{nVNa+X+AEaN`uU4Bx03=@VXRs zwM}88quq^L8YA|>UpmOEu=>2TCQ7+7*3C7!4pGnA4RNt0jl>A_SDu%NcR#R;=`XIH z{kAB_Rm-Px9B~WBkT$mp5$B>XSI$A@L1^Ry3o4xWpCB+86#tLw0BvyNdY3Ti$7TXg zxiH^Ckon$~eFPrmYAiuBk@6Z{k>TPET>F?p3lrCXy-8hO9wEgn%m&U_6!=%Y{q($U z`%f*H=Hb}zSiSAsAEp+IpXk4a`XvDPm!e<>nQ^uKeHC!!l_eWB3;w)WFo21*f~nv> zxDe~PI^odVKQ$lru4J2*>91rWaSd7#kl{0ww!+?d3DpTe6HA0`c@5)6=|TNrW~3EB zA;P|MM+`;TMGY})n?jJwD=uRfZ{68=#z72ydAOSs&3}4l8Som_2U7cG4HL>-lTmwk z8n)<%tcj?ciksRj#Z3{D0amEb1QwunsQWL+%m*}C{9}h!b2~O1ges~yn-%_F5rsQ+ z6yR7fn)r1_$3Y|u!x zdaU__1n6+kkyX) z$%X^-!dV7bI4ci{x4Ymi1VnjK{^r7!4;b0B4-(tsx%*%0o*M3 zSblF_k%P6I1G@yprp*?(B)vuj;VtKlJp#`h3y%-Ok>^pXu?ca5U*9m*dJ_ku%G6|u z)1P~O6h_F+WXT*#90|{9a9L7&Y|`^*IU6nrpr3koI!qAbkC;xu!qKxl^;7{jV$dxs zxYxL6gAx9N>D}AkHw~#DXB&-*7nNt4C8>ccwBcRfM@W+0d7&D2Z>f{rWsfv9CDksb zXpnJH{cVcHAlNHQecW+2u zi4@2=>3hn!t&+D}Dj zVP_zyqx2wB@J)RxdrS4v*X49-5PXXwtY-h*NaL}NcK_C|O)oB64Cdzhg_4eqAHJ*1 z3`gTO9Px>ul%MJzRQ_;>IuR-c2Jxf zg!Wj*W#V`B5Ih|kg`v0G*iv-w&0$VD5bNL(L5l5;#Pi&i=139$ zRf2s2-62g)c&>_d9BuV}H;U)MQm<$zy{HW|DHd7hL_2%XuX6Q~rr`6}l7y2vY>a*B z5wUsudl4$D2pjU{I-wumoZA|&Cm`x)Ot#2R&vF=?Q$=gYJ^O_BM*Z0fQ+k6#Ag|9| z!hLUDTi$S32D}*H*|JSA*uEZj8YSxBuqEQaJUru{Cm4<#?uc~aVtsC;3D&MAe~#wJ zq(N){L8#)gqTcz%P8l@Ce${nafi_e6%~rX?zgw)EywBd4_W07^^bM2q_Q0o>BW7re z%@^$iJu7eQ3GdxQTgqS98e-c!02OZ5X&ttsk&=Z~MKE*|d-7G_y>zJvdVX+nIfbdq z3?y{STfG_;1=4&4I+?)Cv9Uy*TGV&!zo2*_$nIg&>*?#$0X z)r~HNKVwTO8ysIj135E#ihZeJH8<4-7j1p$3aG!N_nr*RNQmZm87wya*EA0q#0LHp z5Sud0G}D%XdtY?vo8>^c&BFkjSBx^WC46?nEjwgK zA1d}K9`9N1ijl!T(kNYq7Zv!zq+3#+b|HZqo5EF8|7*|&g{${X0*sQl>eY>L&JN!7Z>#h;hDEG` z99U@<@!8AuIs_Wkmi%h(vOm)N3D}69R+!UX=k2ARg>A0a^jP{MqP1VL--CWN&6aQ- zo!TfW04|x`*-ozbRf}2b5C*g@*ci0wd0f4xc zN!KMxqb4V*=cY{V@GIle*{b5TorUA%X^{sddk)3v9Y@JyB`V&X!-N*vCrg-)c}JN-Ly{f3|#i7@rQhKhZbRb3q!)@OYETvD$QB zT+n8$cuvgI=MJ-F+%hDlY`p(cBXiPN=MZbxilJn36@XZjSAzECCD=Rc^-bsJscKG1 zaM1%;g>&C5mFw56ORJ=I1vTNamvGs_&P(y^z{ivU;Yn{tv5{6JWu$Z3c!zu66aN6o zlz{3`Y%DhL0h=Phi~CmlwtA0ErBd=q0kIOXF4+h35r(#iB!-8Ag%n(R>y5l(9^K#= zp)8z-`H+qx{09>O;gQhDUN*g_#aftIY>j1k222DOnu}k1ZZCBa2_(K6kQr<+r0W&!AooIprwO5qEoQ zbNMs8$9){$eDzm0`ik_UIbSvCD1k}zN5`sJ?WrtFKaCp9&_~9vaN$X35WfwVElDR4 z-mHftW&tNT^Z099cCBrAi>Z>jek&q@fFEe~K~opCg?g)%3M`tQ${8&=hj zx%K$am`X%;(_ioRa}y{wb@9^}{N}6IHVu6x`dbn6r7k-$9G3Fux3OS>kI*Oszld*FTXoSa8`kQr)_ zaqy0Vn=g4WJrKg)J6|shm5&b%%$SlrlRud>vylO1un$($M_ZVbze9Q^qvIalc#G9k zoAFA4JkWP4E#)u%mLF_7Pzk;=KG4eXuz!wXHe?=Bdrx}3zHjj3V&J1Ws%36-!;7D{ z>scw*d-2rr)t5;J-@ic2HW}O}mPRa#F2c0TF#X))W2AAYnG3tUGZTv?>kB6_;3?*)FU*J-twXs;dCaR2-t7$uCJ$2Jp+rSq&6wld{d=}hN|N%Chm$8`{U5IJ zAGkmL7an1RW`|ZEtm$Rtq-(zNRjKsVv+*`DB|=t1EC~29%Lec93$n9m2pkQ*g&W&p z*-LPD&(wAulQ;6ThD8l(=g4xg@ny6=B0^Cb;1yK3cJ^-w;r|JiLPZ%E%~nAL6XL|0 zcZ0=+Npkx>s=YY{!FrK-S?WuDMbo>~3u_LHJFt`yAqX9KAXYoAH^?sgW9Bx_#gq;j zWJ;ZKcOiB_Y(*Tx8Et_#@S0Xr?u z9ywE8DwE4`Aq1n{$whQxP@tv54#k^{2MABal6+4@m<)j%5<~6}x zAS%)rFCG4sN8_Yf&-S-*G4wB`Qr6d3q}vaY4fe-fc5|B7oY3}7H^@*)7p?SDoAq_# zl3*%x=t%(uRJe}%Zx#Ubq23t^i9wGGHKHNWYO#BR)5v8=Rdu=_kw0XH=1j4chd!I% z@R5hCqe%pldHY?Waue=&m(gd^{1r!FebY!(EPF;~87W9yaRyLR7=cp8i=IbeSPvBR zy8y5|w8p&*;7&QcHj-4mw%8P>M(xr^wc?!$NB!rPO3>MotDj(eZ2~|eczHR4w&X&H z;~GET`lA;OImK!}c+#>!o5QrzS;4&d<2b5xu8u3fBbDufIti!KZE$n{$vm7cj1&bA z0b|9SjS?3~J*9i^E;754wJa#$9Ui(k$@%zQ2ZOObh;u3W^bhcU=2Oy6mQ^!n5C-Tg zfPMts5PeW{u>3FhXe-bQ)!M){>iS8}orT*nLpGtYAJDR0))Ew#FEo#I(eg~Hrm03F z>B9aCX%K-3`;wT*9h`w6MqMlcsE8pD4Z=6j001GB+}kKd{HwhS-yxq;e)$R6P#kH3 zngTj^FfqWQ4!{uN??6eQlv4I=nq91M#seWa2u*>Pw3AV{6XsP6LET<|i_&Ikaf&Y# zCu!@@kEnN77+g0~TmfGcTa?g)r0 zz8Sp$W);wD9t?>6Jyst149;>z;fB_5{cFzvvq(MLvA8sFi_NR0X^|cb0DzU89BxHC zzsN^7t=JfAy}Z~)_Sz6Ftxl=kg1XQ+eVe&5kG_TQA!CN;UjGR8$Wr z@@J0t1Z6pbK7s71JN^`LQ%V}8`yRoU51cIXu{n-suDmDO0vv?vLMDi^Mvf|MROa36$@>3 z?t6_$*U&IB5n2WiZh@B)frm=#k%&EZ1?0lihyY0ocL*Cill;#rfox#+kVwjetg4wq557$dg_$X2AX}+FO-*L|M zokrG$!CMpJ%XJtTOYvk3hG7;q7@&&CPR3Qk9e$>TxbN?q2S3(DZq zi}|UC@cr3BE!IK9cK_N~TW*Ey8jm@40eK`srcE)!JMVcDC9aDDlFko42LN<5@!W6l z|2Lu#1VdFNa&L6vvKjrKn-5?oT(t^aeK7C(FuQX0nlT&^R+_DLbF>jlJJg|r|NELr z<7WPenxZQ8^%|zZbZ)Mmz`jY(G<|p5>}^cj@A{6r4lSb@%(8`b+^vVYeOfb~l#gTC zJ$Ml0)}Gynoquhd5QQS87fUQZwfIUH{U@*5%r_H8o?ZD#T*u?C^b|-l--JR#CJY8CL-N0qsPjvj=Y0#L1FkvN` ze`Xa!U>?k8b}40|5{a&yDjFfNM@S9tNH@wYUXHP|z#!p^UPb**A>8{-Sxk|cdO z5xuA@N5NtIB=S&ZW7AtTb8-4-^AV)4S^tU9kLudB=y&AObkFox$DQdx1xX3-yeTBPHYA2)+JEGc_CH2(4vTD_K&$FUe3#fe8m zle9)3gO%$A{Tr`^JYd)3#14Jc#(U9jn_(3(O5lh)Wae_yTmrd%ev#Z2O64jIO4a)r7)NPy_OW?5!Pd4<8+sVsBTa>~t z`i$lJuzZ|JA5a}zfQCXd_Ld#dBb&&q|fnmn;dMEdIy#u!$ILyMcdDUU!}%mvd2fDIs>;iUkr&xiaSG zU7`y#Z5O|09F^@g<&~}67!(vsW>O@_c6Y+kyAubuRT6mh;%w}q{7JhgMpCEv1tdkp z@!>i_^5aoDwRFVYEaAP7k5={15j_SSwH2oe6-?6Jbhjy-G5>moDOo6$^S&Ydva~X- zdMGT}_C|liXvp`kZZSR3JCf!7SfN|?1#!~BITse=vmuHJ9^uzrS+|iG#d+Im4hFUJ zbD+#PbBsjzgL9JeCai+ZYq5ri?)-qQ#Y4+MGL z9F!$Ta$`7Jy+L{xQ#2UkChQ2u&q{x^;%}*yRk|;95HTR1HBnA=^7CQup!z-u*jV8^HSHcJ}d7?6uT*#=u65UKD29^td1^>wHLQ%n^Zc? z(D7JsdjdtZ0{YMQBUZBS~MgNDinjGz1aV0B~Vv@JpWNzivA_VK94KS5*7`k6?VbUv5T z-m4-2gV>thEy}r^D_3?T4FM@&7602hdh?ULX^El!ogZZoy`Y`R5W%pJJJ~hd{3oOr zmk!KcWKBDz=9yb@RZ2BnT;ub$8{}FJ<64i|1Iqi2z3EL>WWt)ew;2~l^k$V2@0Fa! zKMn41^gT^IEHi80$9Gsr>UlWkR-8(jJPG{%)-h8<@Z_Y*z50s^WGR|OhTT>Ebahp}l4r|ued?aD!hj6^(n z^;ktDbf4n`3))iH!iwQW#uto7ld4-;vn(xA++R=Elrc6R@66rk*{^TmxVq|K0SB# zTw)nI0dX>zuX-)rQif-C5n#aTiYLwImQI?tV(yyApFSuMa)l}Meo~?^5qk~K>yByx zk^Z!=CiP{JZp0tm6Lt7DdgVHC>yE?y;kT~|#>ti~pO;=FKdkTh_&EMFt#S%FQh89* zk4h>OWxxJ7Z}QX%r#3ywC;UCDRaw2+KN!=|{J2-A74vzuetX}!V-4Nj+PmXt*@w{D zt`&j;1)4&Bgek%w;P&)YpJID*?AYLho?DN|d@~=@+a%{|44&)c+rar0I97q(h?KK` z8fEk@H!Y3u4MZ^@&o_uc;$)BF=$ZbtaXZ&@Nq@txm%U7V614~Hkr4+DQx4q7{rsRP zsah{Ufd&yZCl6|8?Uq8aXjF~4=e8~2-;Oljh1Ji{;+Y^l9m`1|$si3^F!6dAr!MeitO^yuKc0&r?`PA zS!;*PV~Lb8uC#uH=#%(=x!fCigt_thtC_LCAt-B6WqHoCQ4%!)ZQz5pLFXuv?cXP>VF~71beX0S1X0Z^ z+B}7pk;9wcGDu~qmFtz_e0#An7_0tOozsSpSpdRxLXVr%dhPmYFOjQS9Jq$u)uh8G zhPRyw3@r5ZU}L>k++6>D=~M@^Y}u>#9jqjaIb&5FSyI+U*NBF~uLw`ysK8~&_fx{Y zOmc%unTiIY^#0mFDSlSxJM*6$8j6(E0=A*gJ+|m3XIQ1p94b@Yv4g9bW9UQaB$+=_ zz5mb%M-=O}zEF!~;9Dx$K_>TQ4prb-&JO6WBn~#T@o+${HApazS9_z`Cx7WSP+h$nlT>t%OzWr~Vx{*~ z0?(Z_oV-2d$~~0x@`l?#*l4LnTo=VGbw_MI7>h`>?r9WlXew?9BSr>%%lMbwdS-&QCY z7*B4&A1&dOjIQgCQP8?wa9et^w!VN9C8lJxuUY3w2J=QPw%ut$SUyIkZ8?f*)x(j~ zPh<4Vs8V)LRIATG-akR2_hJ=<&YW6d`onujWqs`#&mc$8YtPjnEU%qe zrJG{4MT4@pi#eKuOvFl6aISGV`2%|G5*+uu42L0={D#a_;y4UfFnouTKmO^gHpd*B zUWU~a!=D{l$k`ATDS2uVv%xBPEbh?|aSm?3Z;I$+it<8juYIIE_tHz`w&Zsty`A4A zIW~gm8dtL|L**L7O%Wef&zMg!8}bUuZn6Ht3sN1Q?q^pdJ|G)|e=xtCi_7&(mH$$8 zHsZy{;@a>Ih!^5chB1@btuHFM79N^SPJXpmySj;Y

ShweMJ%$c*9GDl6!B zfz?Ea2TgeJhh@UcUBv3mCwCYQJcDwwM*MApO$6HscX_k2t&wm@T#06-96NZXUbnJM9Kcftx)79SL3vnf0b~mCR;vXH#pbn1Wh8i z30Itq;#QkkH$LzaGa{=;@25{cn&jF(P=vQg#mIct+#+Gsc0?x28Mn$%@9Cg3p@g2p z@Wl&v9smD8_@!Zs@Z3VlY??ItU@5H*kt9=s@xE#F`|gUKpV1s9-!W%=z$JM115&k3SZa z1G;=`L5p-}qLO35v#V(U;Mr@RNI)<#R|uHHf14ro1se;fc;AF?-5q5blDFQXrigLk z+O_K47>z8IYma35{mHgVYH%F7Whf&_P=j?L;Hw}bCHkuG5k_oTG=c@xeUF;ObPxVO zh^nt=zSY}6JtTD_+|}lae|!Gz>ag#}QnO{wdRE8WSOoFUgNbZkNfo3`!icnf#g)7&6y}a`JJM_oD_ig2$IWRO` zZHk0Gg~eXHa6h+U9`r9Ci@WyGqt8?Sxtfi}`(XOA^tHY-I|trCFKg!Lk={>T;G?sm z=sMW!7ILsWA0sMPEVw?q*sERb4TQK2^V|YG7IEQ`eO!4EJe+E~#FZQ8@iS@MZ)5(w zJlY=wCBx{VNJLWy~7?NrPkHO2<3VU0auRcoJ& zFCJj0SNN?RdtN_{uF`rVuqjKVhp{bPtm2yGfD-ETA4aEpp}NrUK3{|hoF1*DyL~$0 z6Wy}ESl_oo(B3Mml5e^nAi&$7=foqmA6@d(tF(O_&F~$W*v$8>qd|EQi&R-eOyqw5 z_p1n>^$<5vu$G z8V`HCq`PKy93KW?{dadl)7RqJ&|2|vkI&Vgia+mwKZqG6Ry6-M6e%efZG%Ei%b>!O zf5*!+l+QVXLkLbVnTyHQ!~j_K_K-iSr&_ja5~%c;L;5G*z~8_Aj0NGC^heZY3ECaz zjKnOL=2%>V?PwK-7VjQuKNvO_B`%{(6*A_H)JfMO0Jb+8Hf$m1C1K z$5?O&7L}&7f#OBzPK-4DkI8M~%?%GXV>pQ-mccksEgkV-UK2Ii^6-|q^WAtLDaf4@ z*PWaz7$|^k{s5oGF+D(Bb@X0a`aZ-f;^NGXDHUy`r=&jK7H5ly4W3HmFkJzs_q&^UXQ6@eT7EakCT$k;i z@2w8F4YL`12$Uc8z5n_pna3mz%G(6HW_&C;sJel+(H{_*-d`b0w|ky z6h>@ritQF}cjB-oNwW_d9dh3=&zrn|n{d46tBqfc=5?aEavpv(9y%?VorAh6k9T zZe7Uj6A$!#6e$?z2cAFbYHtpzfPcwp9z*S=^uHuZh5%6hI1Ate<)vr&Vn;hw@PfH* z6$vPb61$P>#B0V($aEfsM&Exb@lRa?Xeso>ji4NMI6;WSWUw(0i0C^2!h7cW%%L~9 z0xy#v?eZe7qdBAT0IZ<3OJ+{$Ud0t2sjuMa$QkC@$chOCe+?(=XZ%hvIK>+*&Og?P zG=T;!#&+4A6!6}+Ulgr^GR!fR*P+Y1=33oYtHw0MtUDOD=-0+GWVX)H6rZEK z9rq3q{f{iX2O7P7<$>o<675JT96^nPWjsvWtwDlj=;nZCPEP)hWCRTbRKN5eywa`N z9r^`EBDx3<^rL}?uo$4Hjc@CDKy^8c(p)jkN_XA_^FWhcS^xa`pHGPkd3(QbTkqHD zW(QM#hbVxnP&JtJ^bYMKe_zE&-N~-RP#B3PZ zn8fx&uo7bgYdy1Ny+MpaH)x(4Nt$S#P@ehGI|=|0n}s*b!%YA^M@H!|HQ|i%pc6(r zONK*R^mMbC#-QD1`K2o1Wn9bcu{VE$>4owx)G!J7nXq#TY?`OYG4T6hQud5r?Aj}7 ztOeXByHDf8L+)MNj*y_&2jM|&@SjPE|CkEY2GAemWx=dDc@|85`yZEKBITT^^BSNM zt1EM*Y-3?-Ti|6C`?%ZUM|{w(brvnspxcoh%+`lVF__pr$#@>Py((9dYTX}Bk>}P3 z;qjE95o}u&j2gcRXJ&_*Kd54XzfDa-W*4hzE`fD!Sf|C_N}9$U7{VEKGSZBUJT`LL zKn_w%f+k6o9J0FrM5alQEv~4S?svB!0JN|244lT$>LFvh(+omnPS zD|?tbf?yX3{y>8u#A-`qAH`SXMh_7ACxdDLHO#*yA^tmCL)-|}>i`ENT6RwBa|Ac6 ze;}%Fov;!3{y@bVczWseu($1z#UERjY-^0T_JA_=<2)0Cwj)WIBKF0^Fy?S+O;X4$ z&r4LCqj<1jCmMC0CCHoKuod>$rD!3k@_`TSr^lNfAWO+ZrQWL!GmZ77dVugwoaDog z_--|467v+X{w;2e&CfA}oo%!7u1rDYS^%D+lv_@KhJpT5@|?$%Y!4qP;+z(X`k)rw z3LxTJr3oKAjIOu6o$nn-LD_zTgtixEtTc9;J zFv97}4jcv%()BM+;zGEE#4Dqp`S^T%< z{yL}}qwyT7j`S2r%Rduac492LKj?X5Z_RQ&OL$~5;McNrl>z@exFAoc zbOx^KfeF&3l$zupw2<)ZyX@ovEJlKGwjtv!sbH z@S~tLkx&@3or!M5&Nz|u4Z5Y{hq%zc7<8*?d+#uwl$ry7dDx?hSj1_SCJXoJV#Y)Y zOV*5h+ovHajG$Ml3zw_sNmm$0v=5VZiLO5`O&%K|I;$Hn5v9J8U6Rar##U5o0wO}7 zgcJwy+|$VaCnW@HSae;ki-zk|Y0GX){3nUAA_OW&>!w{;&$aYT3AvKSXxp%eFi_Jq z&J_#O$6et~V0LN|XtalWq>Zdh^2zAfnecS*72an1WA!A9*P74W>7hsw<3G`6HdMG)wGW6F-H3f*BxcDZY_qMPNqm zsnl)?aP`g7sws zl3}wMSWz(%nfffc>O6D4-e*lW1hUD}EAiCdQC;G>8s43Vr&$@&Ac53-JG)|er%()x zw=cpo>UIYtb9I)(@#_lEw9OR$qFPSoGwc5DI0<7cTH3F=m_@4(pc5!HX_q z#7UQ-Yt2WI$NbfgZhBg7LMm6H(21n5vJR)p&a+$O9gF$_b@DgZwOL^K@t*BQicvTD z*k;$pge2_gEf!`3nHQ98VKN!`*bcvrI)6t)r;t2rlI7E{v3Yb+wO_i_k~`opNaE>m z>c*{}Mah&(eI3k(_FEx2mBugz!EJ8(*2v66qz_cN^&xSQs|j;Isf~?P9K}|Jaad&K z*HCflZKdu5x3;mu3rG>zC6#Wo_~yVk0F8%ox*>4hg@8s{9_K+lGBQw_||w ziVsMfJ?b5TPtDWWAiGNzY?PU)=)Pc;&#;Bz?IpyLfMLI#T3lHCOVw1a>SoVqX+!ay z&{f#iO!TO16OpRf?-(UGPF=>NzE>c;K=w;kVr!R$w}9K(@t+O0!4iSwzbB|4qu;b@ zAZu5SZg|jL`rmY{XUko^~Mk z!dqQ~H|-jtE5v7?aGmHQO$!X_uS&&wb6@W6kibS^<&KwmWmQgstueQ>MKcHD~Y8zvU#GM zmeGo66mzRv5}vCe{R^L8oG!aK04E^|MULa*!o$d8oCgz*Vma|jRM@#u z9oeuwUvFslbIHkIGXSJuh@TGOI5>O!K8__5|MveQ>l~vidA_#Yv2EMt#I`54ZDV3h zGO_K+#J0^zCbn(cdGh;zeBbl!tm@v~XRTUws`kD2b#L%PA_dSu{@7=H>b32G^h*~~ zvqyxokj*A9q`TCp@Qjtb9#}}?43^xMCY>AFe3Mw-xJ8%}sj zn~)p@d?%I`#qw*yDVk>I{kia3QqS>uLZiVZR`(;~^K)b!^msO^1Dci2ioA5nBCz43 zO}|=&r+#}O2Xs?)t36CC%-e7~hkaC__ta7##a$eic!oBOe9Ur*nOsL1%)_@*wcJ}` z#lIoZ)t~B+Xyi@9(pC2hrk)r`Y7C}zGj21(O2^aK7S9rk^?(}(VDSx<>R_j>#yI$@ zZh;-IBgy#cwRN^hRe>E^>IeuEf%Lg&h+3HaTQ$W}=>fWJZ>^Jh|7t={Q>_ra`$lo( zrX_wcTz>i{R6BdZ1k}3(k2ADUs-e(Gd#ud9YcKeY*k8T#17JK`v{A_kz1mBb133U) zNYTxN9jItJjRcUaMkAaj{oo|+6;HMk0RFPE7zhXIznMdlRi3LBP~gjs<(;vM9+cG( z4a2xX1;!rZB~urvXJBH+5)(_F?{Cu%Y8i{$rTTCAA6Z>k*~_w5Xt}p7(Vxqyfb_ol zSZ8Pl;6(xNr&!&m;^*LOvwogb`J;_EM#+>!+0|M3?dhpxA^Yol#IGv~CbP7(4~7U= z=&Sp1TDr1Nk(56;e<W9C(-Xk-LY|mTkL0Ua-5~RZy8H3n ziH;X9gtwhSq|l{_oK9p%`0IS+D4cuyzpCF)z}3-rc)a{E?V>KAH_l+$I86>x7Ev|9 zcoxhT8Ba!!7-d-12v3Y9#I%bVoadu4cH~}4+!C$6SOQ8?f@pHKAxWL4YXto9Qa1NU z$Lmh2K?wt<2jUzwUIIK2hdW;^hj9po%3;=M+;Wn<8ighY|0?jOKUS$IrQGD(<0Uhp zu@5qbAUljd2H(_t7RG`5Z-RD&R1{{2n568?IW#(*$9`A-&Tkh(EN^+5JZu=VRb6c6) zUR_b4ZD>^@mN(O25|zU|$<(*g-tDW@k9Jw&k#X$66p#W{Z4Z#DOeRcMz>Z-`VA43K-LiE?n9IVM@k zGjN&QVpQRk&mz&lUvzVqAtGN5o@w8Wn!(r2Ume2nthF56y9IyrIaa7$>$~G~MOeU( z-}~636{>!qSpGAL{w#o+*jsT8DSG@>dResnU`1~M9!X&$Ot};-I_(fP8Q5R- zvTj}@E~o?Nq9@x^c~x*Rue~n_PjZV*emaDK-gh(p#yI;1lb7Nj;Gd$EFffozMp)0>Wp(r~;HbwEibqIPS#zx&v-<|lXhg$8qIFK^?tx%xJq z@FO1}voE>4KYk8s>(j!Y9PpVwrd1eTxL`R=F#4xRzvc5Pc-73_J*_kDgMnrWt=}PM zdSrKvNaCo4)U`2brNaAa%9BacB%15k{n8*KvFbEBM3RS_G7*SW!x9-ISOlJvx< zvRW9nN$n{R`b6ga7li!|he8XC|-?*xNFm6 zGJ+r2s&esV7ffFb`pzI*TJ4Lflo{R+dUti$D;L-|tbq1}00g8 ztwBB3`6jKwNP~nZhv1e6Mg2lFSYKvFz**Lk>PS3Z2pP6~tAh0l6E(QEF#P1c0R>)Q z83K1xB#2pLK|cpfjMCcX-Q6REWKoibl?F-~Ef>O&7UDWCSC&BQO(!~LHyLLb?1=U9 zIm9=F+}%wjh7Q!OU#bj#Zq2C>()KprG3l&yt?aVt7{i4IORtK-Ys{u(F}ZO_)`q9F zkeeL84=E}JCh~Nk3(u69SyW`u@#Jen(`#cV zh2BagXW#|f`_*aT0+Rdszm%uD1NA!4r)wyvL&c&ED%fqv#zl-Wx8;bK$CxV&5ZJ!d zT1tKf`c<>49ok{t`EBeJ&{b8qj0+{pj*3ic!*svQ^k}zR(98W;!#Dw<4Bo5QNkQ#^ zE6~fM#R5&1J&SVZ%wC=Pjx#npOv4n|OC3&T6e;P>qip{hxQf(*{yXRR&RRN0<_+p# zCp3K6I=AC$v{3tN<3%H{(Stb~EsXPtK%F!utCKkBT`Mss(a?da*Ah*|VuQR_Lf=As zrUDb*(vZR>p}0qgXr`%WQn3Rd46COf+qV8Cu5kjkN>U|m#U7i%4H8Jrj7PNzo?H^q z@#rS$hTLcmKK!zd`NuJlfR8VUilA_7C=iqD3G2`#8-DuHcv;g>*bkn?68*c@o{C(ugtq3+-IYQ`@mcu6{C zid*Aq$8?MS6?%Q6Qau-rg&x^Pjv&?oQTdZt>zFTL+Y9`V7|t;B(a%9=?Ch5O7>KJ~d!3slwD zBuPYB)x(5~7V%-aopOjjv5r#=Te70>^S7(XqAbnnQPpUkLrLJgt0!A(&pI$<_gCvB z3DYWV^KbW;acuZ2*3UF$#Vm>imBMb8Lb13-)7?=Z&hnl#47?LLcdOR!4$ zq2@+Xn)w@FU%-!b^r<@dC+@sB-2UW$=8@Cof`@sFY9$d>wLg|et-)5AAi+hS0e!OW zbFsvnRXzTN(pXr3(UK~6`siga+mXEzrbo4D^qf}Djs%4h@Z097uE4GE!&sCgm zU?O7ZJz&Tu*I#46xiV=Y<;}Bjs!tB6GRzfHWD4}EF6#)QC^b6KInKZ~b&%%UhaCGH zg`kV7`kAEg`|VF!9E$hke_kC#$?|T;ln|C3N`y z;|voQ2lg-keU(G}%doy1AfvDkDHc{f)v7$7Xr5TUk}$2DiZCh{-`2^eS$LXp$|j-9 z+IH(=&$94&0y*8}r;TLp*{A+5WRnj{+6`FNeh}M#A#`@7Buj|__a#ujC}02PWwSjP zWH8U@hxD~GXUq7BcXkl=ygknV04`1Bpn3NdB@(%yu1;Abwj*8csWbkMSE^;z6w2OO zoJ~54+kRl;^|U@QEL{TDxji&Tjg|F?z%Ip~vjsBCxA=CD5IUA`+`pPjvrF2W%BAW9 zo2gSWSHLFHiMzpj%ID*CGD{2bp;iGdI$UtiDZUBe^0|+wI|JiCWn1Utt!4H`(flzw zw~1{}o-?6%du1!G#hUA|O0A+E@D-9!=n6vo6xbB%pe=HtaUW^sI<4ITT_$%l5HXf; zy@MIpRqKDHluhy}7F%x>-v2{l_D41RgS#w)0oPnzc;53I#(R2U+Xe z5x=>rvKpiQSSxViU{n`NR*IJdikCEE7R+h?`l^`zl2)MNn{#$rib&mLSk#4(BZ+`lr$6$x{BG*^2xarnI1BEm>*z1lO_-#fk z9jnkve8eitMgx^{JXgo_=Yg7g?Iwj_FLa+;5JRUmVe(ezAa6{_wTr3yN)GhCe zA&GFUqd)FkjL0ZCNPf(G75RVl=)WHPzv)v02qO7Ym5Bvj1?!>9kncjp`pN6*HU)yF zg~famB#fVU=^;|jvP59>f21;rc7CErLLX;;m(FU*$m0=W_`ot;{^pNqH^q-G6it*j zwT|Op9sKQ;GOX+`zc7H9rLrU#1C=9XxasTW6aOBy%@JP(P>M~Z!nRf{eABplro@p6gN%1 zMNiDh9%BmPBOPKbb&bqQ?0|buV!t0!TfC^J8@zeFn^uJ{c{mYJi;6eHPqy+f#JTmw z04(eqkr!TTOAsN5{a$HXw)`Zk5gJhFY}g~9WyEl(ZO)w8GYoBJ@?ip=05DTvaA;k6 z#D`xY{711q*|4(iC4N641v3}!Rwl@Rir(IrkN5Y(5Yno^V$d=Yes!xOH*ND3AD(aR zFUA}RC$EaAN%^1HxA)zvA@COiSstWm)8H@PGdOG_h^(jsM!}M4-a`bo^yw3gJ5`GS z4lliX=6swjM?B~j>w$}Gh~cE>Kp3LGiY{}4#2}0wR?L{gV0quzzNz^5wV1!5vPjm2 zd1L2tiVscD*h+4<@Fl+xWih%Ee&Hux6ToO8UZ6V>MwiGHttS`c*tJx1Rs37285`AO z{3KIaAk}>8Vq%{Fh*tV`)GcQ4SIyh#513hs7|fG)sed{>44%jodkzB=gfcCRFwb{c<^MbY za~AEbf%!suckUA!W(Ux%ahmWa1}0>uH54dEs!EKq_#$@wsmyng<0(Uabp}8#3AADp zsLp}F!%LUgosufksgB_xy`Ckkd8ZSqd z+y};~lT;2rNtl$CCzXQAx8UCp99o(WCLse5;Y5b;4=y81;~7SO z*OJPr0!02>I$)X`Xo_w;ut0mkKa-+3dW$Co*m(TUey#h~WlIip|8}0IrLQyKPK)6a zOC*}C(@=bgVt*O=-=ecs?8kb0?7K1(`PhnZxeG(NM437rfqFsGgHJ9&FI>!9I~HP% zgNc5L=cdbjaP;3jP%2viUq`|Mw;9rkyK!xLlxGRjZt{`|6+E^{eua))~_kF z&un5MGaq=IU)u&rs75zM9a|UHIjEUp#d=heh8?bkb^Q6I+j0ab_3hW0YTHg#B-2j# z?5DLDK=vpH{Y!4&+ibwq4-6y-06-I!VDiwbw%XTp&?&SX^g!02TP^=dgiPc+u-KWN zX740tAGL@tCd9UkeoTJ-u$~@?0}zJdmonC1VP&THr2x?L0ih4>v)B_0ZAV0zKzd>T z5xq|Yw;Pe>4H_DJg&WjW9*i4UhsSzLcKl-H?yU%3&VkY!)dC(6jJ&G+T|JwQtgA6Y z`pwRs>c0HQ9RTw>WTzr=;nk%+@I3_EB z2E4#kM*6GO$`S`HD6h=FnWu1M*po^>DTSy=dLkgi7K8(+k{yPs+B)$ijrDYD8?8L} zKSv02h3*ig7!fK9IinN9he!l}^9j%kF9-o-5(?jAFj)T`oeoF z>u_K{hU$pV8e-A^WC&_9-x2~Sz_PkFgkoPm`+m(RLa8wfAqyqgxKO1W5d$ROg=o23 z2aNW0ot_6>Njwi_a0!y%Ic03|HCbXN%4AT-dv98=_9&$^hbcP#h+2HFiv7#q|EVI{ zhr|95`kOD=ZLkWAh*KFUF8ENR3ML$N=@$`-WV4!0UHCK$@v7bk@j35K&xk|&)0wIt zFI;6A?e5KoJ*fnRfSCKNp@4Y~sTo&_rMv<6&Qayibg&uC9`$I(} zZKr71XB97|mOpqDAK9o|&6F3v_i_`Vj5PMiAE%JGWDJ9iVeE#FpnBz~Cxk)HwWTP9 zi|_^q>zKD={o~#~WoU6|MVhEa=d5;Nm!r0un#+WyZ~;U!1+tVpP{(^mHS2&H_xQ5{ zpO(ao^scL0cCgUXFMrPJ0|^CEqurK}%m-QCP3&jFwB2trYWkW2)9J3+l}DE_<$RJo zGp;9Zr7cF5CZ$ZXvSIo%wSsUyIlCQv#9nrhW+T2?-BW; zT^Q5}zp?g6LpdPq=sNn(m$}c;)1wvoJP?DyZ_tDCkgg#b)OusxZ4EIUo6Rt^!UBb{ z7Y z#W_B`YH19i+R`7$tjM#Yl~n#r>mMmAy9d;}6G=Z(U%SF`+=beObExAajPBIo*Kqbl z(wJRw6iA4e6Iv@JQ|i6>IaE_P$9Y)Xd%X523SbD+ZX@5gT_#n&N9*OjEHpxYR(|qe ztNWVgSHXSJ#M~zyiO979;76F(AMtlN`jw$Hc{tc3+A@gnz6!{JT~+uP;#V^yAGGc_ z=aIX9YgJDqaZc1j>lkrsjxTTYhd@4y#yr=H)%Naoi3I9@WxJM-?i2I)*I!03eA zdH~R|*dUUFRWJZty6uB=+t_d3br|>Af-Gth=U@F5Io6DYV<3N1bjBCfUA zdpbcLakzS{dUz5=TwF`|6#&~bnBT#xLP}(8%-QP=cd6}D#lvdJs7ofyDUyL*U@E@{ zz%kFT-@bJ0Wg^dfQJ_+z-z!NKcpNmF(wCdXi6&y_z}my}M(+vXCxefm9VzP<`hc$< z{fpWv!4xSjoj@@#Vz_e$5A3gQ^l}Ahgx1jPgx(=Ojp?6DIFyQr1*INI4s|~ffB66U z39#}g_E4^fg8AIYQzFGFjmL#0;rH=YRsw zzxYuKqg2ZuQBHdih|)(`)Z$zz;^-K(#u5dBg=$Fg#7Ln{jU{QkaG zlTLkEKx}r;!*=#&gu4w6*gK@Fgw_tc*({_-g`_Ff!7%3w#@_nd-xvC1QVDf`i1Ni1b(c zt=IoX=;1T?ED6JbjSuSkU2g0uubs44_`-IP?PsQ4Pqv;MzJ9}ojeM==2dK(n_L31! zm5=F4GL+)?tgLgX^F?w37~jY1PSU;N57jL_IFZ9NVYT5=$F?!`Y!*8uh+HdXlq$!P zzN}G*(^j75B*+8n$76M8*6);?Yvugmk(69E%>O_3)cmqf#%uFhP@_7@iq!3vbdpEX33RRi_E@>JD-UO2F2|aQM4UZH2 zG~{NnCd*_1$h8qD|Ah@Ut)P^&CD#UpdfqnxNa+A_Y#egN_Af70rY9cCUs{WqfpYJF z)iIA1tQ`N}R){`c1KG~_lo$b^kPx7bxE&?6Zx5}y&#}VAK5n1&aig-HK(=*22N~i0 ziW!Kg(JX&)H09(d;m@V68zBs5G7D?*$D;jgu{Qj=g{!9~p?C#<_ z9em5H)U5#tYz%5_&o?&5gagHCT!ktxeo$NCs3R2b1MwzeAao(sfwr)yzbl>7a;l3G zO0Ll-0;RSI552-G6Pg}6J}@8AE@dC7e$(9vCO!m7>u%X26PCQjtkaiZj8chPhn-tGI!kVe6Q0QEz!qN!}$~cUc%<$+F^>{^ld6ulkPh$BwVVOA(?dvlK zQ5V~(!WgNV$Iq?{=3h8(HBv_I#qBfKM4EZHc0c9z_A!Cik_(^VQ5EKmgKhtN!NCQ( zOIGT7<$YcNV&a22j=2P7hWWdy<#|fs-;eEjgSjv_6Zow57eDAE{zz{OCR0dTn1*gs z2Rj(#E|ZA`q?^}4ROG;nbJ~&xE;p{Epb1e?mZ3KGEt}T=X`c`f+b3)RUuvb1a1L0- z|45s7@(mHh0F%o|U7}L4EuZW}_Ailu*E3@%>-z!c_P6@%dRjU>|K zp2D>k*|n&I}P3fXzm8bIz@GVeYx>s%@OD*|q)WLI^-$Y|A5bKhlA zn{GMOqF!xCWK=5*@$E7EP{$oaLn<6WdDJ1Wpp2x}51sOw2R+Y~SW0RuH^rFjUQ$$W zHal0)KG7!U2VBwyxj1bS^%=P>IkrO6!|ro)78?uFmk_4|GkE?e`}mn=t-=V22M-3v z$d10!tA%@^5fN?1k4=kmq?(p3yUZ4|8Q^9UWDDhGQh(PP@TyE#vYpKp6ox=thWA7^ z%O-46)fz{r`PQ5?y{RfBI*zT1U)_*lO0(54E+7BBDkoa^0uvYcclY=}v>vmYYzEt) zp25#tl=DcILO8ydXgSU#(9&wcJ@gwe;xrk_fy27pCE0Te6s&BBX39AIE!ZrFYnpWE? z;v#=uN_uMG2&s1@>QWk(H;1aDZ0ekqy4qSxQm8>2&9=EeV=}Y{dx#Sm+VSo5cnKur zoNzTPQ;^11p~#M&VeNnZv>^ByVk@WM0L@|rpTvbhSS!QD$-Yn#qV(=-wxRqUw3xZE zPnFg-HJhutTP0_xL=k)2M&QBW=wtmC7MIj9)Sln7&+=8Y?hbGUhFN_Xx|v<640#T= z&Kxk|W`u(`FBff{n$`2Gi!%Edm^~7_gTXD5s;YO&TAH&t`+DtA4AX-uWt*m!ik#xx zagYtUypNhTqq(3ln&y&kqpa3^3UZY`oOnk~--m?)2o8UC3-@UVoLp2oWy{nPl2Q0I?NHD)e9xdwR<8+7BY{NxeL3@*=p$ztMmQ*fp;%s82kf+xR&^RrBYdy`f zyY`{bJ>UAVl5fA+_h^CBj5*GWs5$54FqF&W*oSQ)ArEPW7T`sc1|( zi%R`PW4roi10rOgr|HyWnN~{1Dzg&IW4u5{A+KdSLQS=fJf-5cJbg1yvGf5Y4il1p zTKYR7Shb8{qNj+pqp`jPekTFN@hi#Oeh?K3W?6;dsDfpwa@XE{wC}(yP3Nm>(qf~p z%(3Fg>Yoi_f}mrJ8zrmIyce#00+~EC2^}HcQJU>{i{Xr7_>^UaSoYmxd>tipRWH=s zPAm_f7~veOBAgp_vf%)5aar34KD!-wyKxZR5^(yjzjV+kFAK||AO$P&YQ0VlkfB`D zwx3;r{GejA3x6lMGLR@yYpHTkF0>|wqu>spgvh&~(QFc$>y%L<%R^yZeFnMfN~x`S z$?K0rah7qFiig4ystZ3Ry=9t=@@Fvhs<@;dZ|rK$DAm`cpPTpANAV0vjGa#mbqVm( zUiTrW=B||;s3Ff~^1$jNFDYcFq`%}zE07$xuexfysP8fLF*CML#d3`ND+Hy`9|ngvJPtb$Me!*c-E)?-KEW=5c&f{|d}? zrE}5OGi6xIqYUZbOAtLLQ~AxP5J2ntSS$1OC3F-PWC^-5)Ee%33kXYgYkZ{Z$gJY` ze`-hzx+N~{AGZZ#(yurcVJ}@AKI9Or^&J)E&E+B#l-$9}j8UN7ubZ1=b zu>9;H5SAz8bSxDA_W@r^+p-8GXC}8aWYAyYhyWte3Or9Vm$A7zM5JhATmZ+yIa`>(S_h&#_D1K8H`6@ ze^Y$mj9I5ZSi&U$Eujf2R`HduuMy6G|NjU$2H>w|=T}9iq4vN~3Q`mZeGVJ*K_hae z{j62N=x45DisuzyhPXW*8sr`v|_n-;oh9l^&};%_`pQANT0A3FdQLJ z$J^7J8wfd|eM~=<7|Qytr7n<=`fo#9SQUKx?X9^5OpY+ikc7}#Tqnc;F1w(V&}hbO5smkI;0jZg|%u0`*8R!K@@RErSqiVfJtKcfghhUdj3y=4eT=# zRZ(mOjh&2hm(WZ~VN(qvG98ion)w6OU&L{*7`dhqZFEj8Y1d#a2}$Rk8m@ui?&au# z+81StW|oCMiN(vZW-@r>8L{fcg3|9J>Z&mD@6A=Aux&BAYuZm^G>LA(V`i?rUL6~@ zT>>Q_N(8|Uy^8PwWZvNrj}x>E{|c^|JY$5bT#{ZfesGqmC30|4Zhc

8$7T%F!+B zc7HM>aQB{XQN=OCySnRT14cM{PawZsr2AV|RVDlG&z#FMHXh$H{0iVEqJThzqC8N& z(FoK>Vgos)Cgjwcx*CcAJx@YoTumU>xaA6sGZ-`gTid-u<2=x^9_Aa`(#419p6rj! z2lsogzJh_aqhCb{`m>O2elnoc*YY7u#Yd2>NW>6$;LvusxXutJv3n)3`yVq)urgv{ zcd1J^V_a_$e>*4QA(n&Ye?V#n9Ws^OK!O;9b363?b~EW3)q+6fG=l-$ zgWoLvEjc0ob(z^`1N-U3oXETf_iqV~2z0{T>o>B~n%Ia?{N7hL6l~&RCY$Sk3@7(z zxTu;r_Y{$$q2Aw$M6JJd5T3NKQ0ce@)X94?%hRPWi=~xSv#C{#r0~4Hp1(1YwwlOy z0o~fwq*-_~-P^GqQ4j;%CDxc4BtRJWsSS+uK>d#vM9h0cn zmZ1?`2zHXIi$w@RG+@w@AW~`eZXUpS z$Wz4$@;O7-*#b(&g$7f5!(Ue0Xz>?4&t}X-F~#||d}?n6?KL9|ML_LIMS8w% zn3mi_BGO?8pI?b~zNF&<0J$ckR;?=<^TI+F!}DmrXtW$u?`d;Vw@z5xWtmyCNktUy zWn$Pjl$$VJkae8wPm7HRI-KI|w*QXFF(H)@4T9_q1F)-{iBQoR)^jl<8h-3nQ0{#M zDK*Vk+L*91_0%vJ;a>^_)VJ;~(2F>v05}A$6oykuF%!hPAEqd_1*T4UZ{nnSh*#_} zd=qKp!8D&*NA-pPjg7^fSGooLj~?)`q26D9HvIhGAyf(T@p_(Wxq>#Y_^F`tD@q5%M$;JCpt+aC>X z#oDL;x^@-rFyL7n83P;%OH{fXiv!Yv+EDn)>D(O4W0J zW-Z_2!yJ?o1>~!p6AXZ4M0u-8YfnS{Y<`r-Qs{I$z2{ymrQ-97%i=4T7(H==@6v~a z!O`~<0-!JW|FAqP5mdjt_pR#q#S{eQ*0KoCS zO3x$k{Hyj`QOYqP?@GasJPNSy93^}LGTg{Uu8oHk!#$Qb|)Kn`QUMh5($21=YmDA-OOl9Pq- zUd=qA8X$V?0lSx<3g=k96Q=18zUJok*F9L$f$|f!=PfXz0X1f6RXxaCBw0PK#-F*k zrkdKl&x3aW#Fy$!sQtX|N#0?hxjf-czu+nYXDoUjq!Rl1<*&D?;OCWS%nAUQ$F9?Xro@?>lil|#oZGw)MT;I5w1!tTsg^4mDh~AL6R}nH z13dtgqK<^Iz%%I1#i`&=G!H>0<0_;CDGW2)4rPAqg;DlOVE_bO6qkm+8@>Bi7?X~L z{6K0c2yuBl$d}jj%?Ja_HQIerTP6dlj<)m6w03$iGvo(+p%J)!tT$?R;xl6PkOReh zb}D({{SyrSgax@pbkr9gXeq=iZG5eX1$|p1UZ+ z=jX?mCv)c4jv2}kko}MJLwEC_c(kE^Qq|TbHJvVdAL=kn7 zec{#{+Wx!T{O#!S{N4*9p6w4+Bo1*1DvfsDO=TRx79n+}rRA}@r;GVg*z^Cr7eEwz z;S*#c!LG8qx_4;JHs^e;H5{IMJc(WhsTQ-DhRb#Io80;Dd` zVUQ_*=#)hgo|@L?1hWtT4ZAa%pkhd)c{V-RBaTy${lsydVFowyvd@7;rpM}dNK!OD zWGIVJ+4)vfTvEJG$m^(ZGTksLgJ}}qIkoIst%58tpNi`f>r#*975Rsg*zEFsr{yql z?yEAtECA&NslfWfFgyjko6Z-c;o(;DGR^!ZOl7*`O7lFCYP->rH}_(Xzi5jt|yelmuCLxS7JC|p)Tl5omixVmyW-dDkk4nIps|`1?eWrg+3myO_ zQJz3J^p#-(wuk-oZ8maYM=fn&iep5f6 zIESu60)qoWqh6xUu;Vu631qV=@?c^bRhfi(hpI-=X$(jU`#5UcC--h1U#~;t;ruhS zD~bqn*#hJ!d}H5EcnT}FG38BFHw{Qz>yUn^Uu*q=hWDMzbz?eg{s%)8+)50kiz7aw zBE>NcA|W@lSb&MBEK~Nc;eOcQ8NRBy=D8E%W28i$3UWS+a#R-OU?O5fn;|T>2W%l0 zqwj8$Z>F4cDs3?Z0|5`ic#)q^RaUk36+bLYIoky)TR`VSe^D<$tvTkASUP8<;v0Q? zx!O3~hD#6FK|oqgu_VlK<{!XEh^dF{`}mXF3j<5_Zhry*My=ArSs*#h3!rI2!Z$b@ z>-p=|fItBbori7c&obBOW63oEq;ZID20xCwP;2|(@zbF}^n0uzN}5f5%u1c+#Nf6- z7<*}#P5D6?nNhDfbzG8}*R@c$00hd=wp}02#d)Iya0Obvn1D%42+J?_XH)w=ZQ7$#yI z0N}c4F-{=dR;dR#r)cCFzFvPG%=o`8ewBHyID+uGo$!7mR0uPTX~XC1cV{n9{VCA% zm4pAcwIN0_s9d-1m!c#~Q)4y#o#o}n>{kLEs*l9JPql#I@j=)MUo1R+!d!>eH<1+Y z>1&8*|5H025%Krlj*RXj5rTVxyy(}$lro0ynqy{EAo1;A87+=HwOKL`?&1UGEq3T# zV4E8^|I!*=y1zit^iu+d@%ryh9{N8{0;WhuCcR}AoT9Inirvud9aO^?qTA8~Gwx0X52vST*=4HWuMHr0TUR|7$y@}q{33xcV_}A@@Iv;fR|A+;@yAhyw=pl% zDP(W(Gl_Mr`|C&ml%#ErS!PF#YY&aRs707ltu$LCqW#vH0;J?}XPrGrx_h zK9fSWu{2J0C*sHiN9W0jp#$kku-Kt0T1_=JBiJMOD3gFz zn7QdCH(S!Q_ks5--1M4e3;bBm^Aosp5=%&tv-~yMM-3 zPZvfIC9ZjGRUvJM2n@aZJ1CF?;ijo^0wUp7Y{vS#c}AIc_4EE%$wQ3kAMh(C0~^O= z8LmlxE-alPr-jF5>BU>8q$|R#8uE9Xet6_zp#dRQFJN@Z*7|Efa60WqK7)&CIYoPq z{)Sw@TXihmrx184sp<5u*X+hZa!MVDa7ab|R&R2O$&6lc00Aj=VW4$1{zK6bvq^Q1 zoXzBk-~cWGq|4WY;BGcHtgW#Qu4aV=kyV~{<1^#SEDn2pW_xN--`F*jY77;Uz3m&4=mg?C`l(kL^64#^EoPr<;etTzaXSZ2BAXY zVY`t56%Ou&9e$GLjQUNS35se&G&K*Ub>Y8jKzROjo@fEgFqp)=Fqvh^j>mJ((!tD@ zHqX)?rn%F6&YT?D*1<$=6_!wQ!;U6O07zY2bPr>{5x?lh{VvUwG*zV$a`AWXvY8{6 zAJANi{@ZmORZ``11d*N#CVX=MNPK)Y0IEEo%-?w=Sb=GQIU1U+SdMJR$SRwv_fDsq ze!*E^1Jml_US^6mVV%d-7ah=~k{kj+WS4UZfp(Bm4or{X3Q$juzf^{L*F1Ylhrw2F z+%E*zL-7pD0oiAGei2|(F49@Kw3@H77T`azBid|0%EHI#TI~W zn8?dq3i~|tH9)8isf~h$CYo6a-^GgG>fyp)J#fnACcXs$-(>Vx^d^R4e*;k4@bP79 z;2a76e40e@RyTey$+kjhXa?HBA@^Cfbb8PDidvp@utF6kR-2y1_kgmsW7`wEmII!| zHtcSKvr43*VgWqp%uN^I#G7I9IGgCc{R={l0L0_Q8bB3$pe~0RMUsAd z;v67U@dNn`o5)Ks-4(!1g3yPaGUFC*SQKJ`JA$O9Ss#9GX2fgC)qd$TJY#Mglb>J^ zZLay70roMmxO96#&b(G85t{ekobIQMzc>0JFdjSPULsa!Ss6B#B?M6q)<^l@D9HY; zPdM}Z4cG^QS6)K~Dr?N*M;$Qp+KZ<*UVtGHb0zZR?YPL-c?em^VZN!rN3%T`EI@zC zl`D`DBtH4vk^bKkzQRDqCscX-{Rd?|>aO@6#mn(4SF7}=vo)tM3C-B3x}3D8{_~8c=*z_!QWNi%eCNb<}o%e+sB(N1a1Epb;Cl}wc)4Y z2J37qf_%VV(NR;vUZ_Td5U4WN6FWm5{O@i(f3AuDyOc_9<4tk6CT;dYXXH|X7Tw!) z@e@}Ks@n^8F_qEq>k80ygFdkZ0}%EA=q@n{08c<6@fsv1oQXs=(?}LRI=O`U?tHdw z;!5qY|5)z@qKxHR2{%8ExpzI=93Y44>c{F%ZM1acJcU+5A~c)a0JqV{8v zMiM!?U!d>DV32`vCey{({38qeoqCliYlP!4>nr{jm z|8R%{1v%CtapnpcHh!PT(;a=jhh_J8)xMh}RnJ`ciS}>(?>3blE1=NaryHHQJ^2YKl0(?_Rke7o=hmWBJ7_eTH?$NIl^++T@I$7|wdH2(;%R@28K z3U+6@P%$Jg-p=RVpmg?ynbhe|8AnM{W@&R8Mw|9z(Caib6yEcfN!&v4v!sj&pzS-l z&~S~iwqz;yq+Dq=yk#Xi5Pn#d?D^tnOb@SPc*DAAx3EM?wCpzMeh!=|OzBGD+%S#j zMiqqA;DmGP)Hk5z(wu$Z$LktOXmN7xg zsJ^arT;?!L;p^wqxqS#~1t}kgW@RlT{M?+C*bKzfj5~adC1zK3z6a^|b6)E~ZcB`! z5D#)spGzq93(U^szY`VjVfrGfLFdvU;WGyidrU*`g{1)*rtzGNC z2=~xDXmROYwO+8&AX@Y&-+r%bIi&bMmcA)Ev!?6ziEZ1q*|BZgwryJ-Cmq|iZL8C< zZRh0u{!^oF_SpNPR*hY?G}l~v@vgR&<0n%RUT)T%Mj=vG^bAlX*I5<6=R#E6-TWOc zW9w8!C|VP*#D3QWIWeHGrq1Nj75$UKnYiXi;ZTbxd~@kNm4Q`E-z($Q`L~4Jaj`Bs zW!S>q)dh|Rr^d!Z(ZG>h-ET%RO1)P(YLhZEdKI!AryS&|zS04NaZ;se z5^JJoND$fu++7a}vHr%9J0T#9DP89`8>V=eD$z5-X4gpmb%^HyPzpDoZOuX7?ZY%l z(sSziCPG0!qGe}~_LVbfP{5CO} z<4V`;fQOS&JwN|(sS_dBif%1e3S5sKJsk-uPK;;+Z3;y9^=NH%JLCg|rAMyY--K)G zv}&zYmJuVb81^@|&FsjWRVSrdbOHE5g(k*BlWii;c4h!?Maw1F@|ap@2XOhcu{yHi zfF~9_-Q&Ir|RAe0Qq=Eb~r#t*|83 z1K@^i6&@+c9G-OQ_|w$Gq5I~6qQuP`|NJ78nem(=y#FUaIJ?3N0!W+%%rUGD^?Ep01(R-9hz4Is{dpOSgIv? zl8fS2?sCHBQ~C#3l{e@Fl3GoeOODAx;xLRHKPNc|wZSv&Q1L)QN8c-N696D21)O}b zAvO$KqpW8dfP_YzSX91u=F&hst{wD5b5}?FYojKs%fZd0nXOiOZDYx9_6tIjm(G}O!IxrPrV$zijD`Y)1pu3bdB-#ha)VXPjw@L=e-Cna01$FeG$~9RfAFvZL`TQ^g7NprjC8$C ztjh1QePjv+^g*;PyOWUL;3@Z;K0%fkHulSmRTyJ+pomJ80F>?<=|uw+xP(nOo`xL& zaD$*`hy`QrGr^i$X5O_AY8Q%z004+B%HcK9dW-SiVP)-y&ntnDJUsVIoi11B3l#hovN^MXv*^9O*%2lHTNjmh-7&pp2Jw&T=8@S|6NCLu~|tvReP zC;@kTL3@LGi&v4^1k8-9$UJrbshz!0{`Kv6={+V>$dCS+2YiO{007YMLq+UFD0PY! zFSWaFkQID_gzJ{`CF^{j3YnrAK>o*}+%5Bo!08JBhzS%(_3|OPtOTtjRrb;Wbm4Hu z(rdfS_){KnlQ5|YI_UJ0UH|}w2<$5vn%dk#w?Q!N&Az5tQOWp#H0JakUuiZBF6UCW(sYUgq&F}u?EQ@;2 z0iX^*1@3}JVJDWD$pfPnruIcsb^z`MtQj!nH@Fvk!z_@y#nZZdKzKFUyy4BT~78Y7AK5%tF17*HNs899}oYYWbxm!1XYnI$><0Gqf{7BYSFz% zN@?1Dg@| z{FDfVD~D1)m(0xBCy}*u%%i2=cxUe4D60D7(; z>(EgjQFc*K9xPpyyt-~a#rd9W2Ls9BAQBiOz0easne?5;RtjREhd^Y11*ahPj<|=J zvvwJR@a*(;jJtXnc+Jp9z3i*L%Gq1A?t#yRhQb+%Vn_F{x0N~j&BQs+vyY^j94A3U z1x+w#5AgxAV;w7yv*t)O8Vn{0N|>jPPeTPEaO9^865-&k?bt`!zgMTKobzzbd3wa` ztfurh+vyqyoX8?2myPE$zP=bub=^*x>kp9$1k`vynY1~ia#`(qLF2xj7j2Z9tg|2G;;8UOo&;v1Bwa4R1jHUhK;c!uKo z(OsBl*C_VMv*F3nJ^FreB$s`M6}e2vxUOG_iTLaYO>4*RG_IMFXwrccmWA$MFq|&y zZH&`}cOhE|t+97v?OjYd1kw1&JX@hd<*qNdWzEytMq9}pUD|21D_=QQ7jJWI?5U!a zB6ZLRSPKa+KPi1*k(Cw2z=G#a)u`V{xH)R1IRi#BaCg8XZsO`HpF-M23%7oz(R1#OZ4$b+)>A|EhC%KAn$RX8~Z zSIQt0g+@>r6;BMpC#I1Le%CZwEHZUtMc={7UG5{uB~AJu9o}~O63yvRKGvE$@^&S= zAK|hu35fOu!ZgdQu(*nBpg&CeknF^JW+ZsIb9Ebr($NqlN7ZF+lG)m+6>~UDNKzTt zT2+Ty=3fvcetkNtLs0ITq71IS;o{pvDLAF@z?B?*QVCaU`(m(r=qXNu#-ba68-dpV zkEdBjl9@L$<4&Otav!6MAx7uISEVqQ6ICu}?y;2&f6fB|^90ha{u@bssS8a-{g>`; z1}Wz{NnXIb_e0lPuBI-uoRKC!>iYvqGEz-9_FE;a@PtPhiqW6N1)dy>?_ju zQ+)WT9nl_8!EDVXl1y@(>HIH-wqv`_)R3ik((Ij>AFuKn-cZ5)FaU5XvVa_HZ5YL+ zjC1SDp=Pf{*p^Zm?snl43bUSL4W(M2w2Nu?-8@wrDL5j05|+$p?f?+&LO*uChHiq2 zuca0l040UIfX6IoL9rfRA905jHvB z{=H}quFY&Qt#ANJfVt%D*Q3^)uYmjD!4D5E7E;+&J6K#@iKi=|M->1t6ojRB{I=^x zR?th>3W!|zhN3}jbEmOH?MF?9vRAZxtWkQtE`5eYfWa{zU7mE*WX-LQjDGupTVOiQ zLn;G7>jVcB;Cw0$A&^?xO50(x*1Sg>bj~_lwE&}2^eaq5UW+>(O4pL+*>_a1$anH~LyeG~x^U%7;pyoAdd1928TK z*CMPX`4dsx^p2R_f+X|Gee~yu^{N{p9t8-O`yKejEiWc>eMnYKCC+HAz67{(kb@;> zZwj*dc4;)}ozz~mTT!g^su?9kD93j-dVtHVOld(71o=B?3!Vo$lD$YzWzf+^BeJNC z0RX5#D<}C)?FTpcKsC^`K9|e_V?iRn5HivmB_Mh3mS=WgL=ah6%>#a%^D#v_mbdx9 zg}3jC^$=_v*u4pEtSn1OlUP$3FPDIv-d9lxLL!paWi$Y=iuq(;t}rgBb`;s&3b7!8 zq>q83%*`w$)D_m#zE&I~06ar`karyJx7TXwUnoTw(=%3G+ROM?pG@4Y{)Ul(aK(Ip zYAh}v50zF1{A9NvzJ{zR3D4GcMJ-KV%8&*?e$|MCQ7xn(qy`h{79bAqKg8F`F9O6J zEcC2kF{}TsgCzw2-RNrnm05m|%r8AXo;Pg#=k!toKb`)46P+Q)10dI@_P4@WP=F!8Ug_jIt9Ip{muCxg-s3t2|v6t)N&i2ce_yL$}4&xnpoBT=C%Ko#QXZ=@?vES4;qi zmmJbNafchtQ>j3p7tYIz&GNh-%~Yi3JweSb$-Gr-mG?%Ry#Vl>HANy0)(s@z2&1aL z!{^?gu7Uur;V+J>=Gbo@+8pEP?g;m6_<`zlMpW8DS-IWP_S3XaT&;kgp2ZG2Ahz|W z2xRL9M+J}Qb`yG-78*^ckU>6|=xwj&CEY+l3GrxU_1%k>8G(7a`X7SKD3n+9e3q(> z*{n2V%Ej5GK8!?B*sB*UL?raT||80wj_s8Bu+MKa*^74^ygb?G|mQDSTUjTw=l82 zNq?ODHCa7_{e~$%pNeCa1wz0u>!kFffr@8Gq4c) zSJckX>3MAyEObc7A~%qEkkx}xmqnc~UC4D*Pf*76~w zU)f>4ZC%wJZ#x4X;}L_{y(a194!-YkFJnpVnwXvd88O^Jq1VrB`xjcJ&*gQ|D;Q_L2uk!}cJr9+^cB3Yx;7s5geeznnXt|pl zCL;yO)@q4m+UCIZYYNh9RLu5(%u=;{Y8Oly7MwasXV!Pu`f9W-J*Lpt%uLE{%Z_%B zrECMw6*BnTGzXOsB(B%~;Fd8@`Ue+%#(AX(F?xV5a~un3)5X{)Df zrQvUzVqCF~sIi(A#?xu906&>#Ie4`9rN6ZOW>;O}yJX_T0DtmjV!N_KegiU_`gG;( zv)rCfPS&4fl;}}^Zkxg)+{N<&Gms@$(q53_W|I6!WMaTcPh*Xy?hc|Z!fo_&GCZN9 z9-9TFu>Wzp$%4)9ntkHC_WlXrtTV_qXe&DYx0tGM%`^kX*mDLd50Cz|XzP)^ak(76 zmns%ftmN9HJ7&aO?2H455x=`|4M+gF93%^j>p|2GZq@P&wxR2vMz|*m7zjBd2=glh zTdw0lN6uW4f}l?<(+$th$pmo$Vl{1jdK^I~eV>LV{KQZJULQ{!+)Ly1hlet{&_?-0 zXf6i*vEIxV8aj?V@-`#T5dWkLsLQ^2MttgyX_yMsE{>w&;Gle7b8E5P5Q6?G#Fcd4 z=5xkox`H=BZGXnTs^2POE}fp%^8eU+o0q*Xglf5kJknCt2c0ic8QNZg6z6g!ciqgZ zs9)G?Uf)G71mj9G{ zxm$zI2wMqq=IJnzZ5A)8fgG9zH*|2swsXko=v>U@df7p?CfhVEK4gBPb_BR5(txs@ zMuXQ2auokM0^OIKqZv>=DnoRz#T`QL>!Mog@+bv;YTuCdZk~odcnxN#gbadx$@n*~ zyNSw^VZ{u@H}n(}dIN<19<#s{Ub?m^RZN`4ULSSCDpqnW%NcF?t*v2DDOe>Csg=0U#ohnDM?RE=%(;*wPuxiYD@*XD42 z`{*fT<(HUtq)ZG5;@jwbldU*w0l`7>?==;o^Pu!|jl@QMe1g0F*XvkBq6VAPfQ>|O z?Soi1UpC-BS_EwRz}|B_zxc>AEpRm5v7$mqHtE0s5!oUG0FxE)=E`7X(|tM!cK!y! zIO-IurbdvO^As#?WHw;ww`t}$*h^qsR2`cFuS>kQ-~VVA(QTI zA|JGA$mJbp%@d{HvW7Fsj32Y}ojHELDt#nV$-Uwc+nje2%H+@{4}2!5EvfLM=#=+bjJx)A2{D zdiyNtx-wyqT((}L_X}(s4DeVwmH&MhMai-AxfajoRYG6w*(3p2r}NTR97#sd2gVTQ zjohEfe21pqRVQSZ2J!Z`g#*v|mA#gnqO;ZIR#-WA#7AF%s%ovTNMBi0q(>W*ww(xT zk{`{@S(ll;<_qy*&Ms&tIcENaEu0=75F$@d2!_#f;$(KuVS+E;j8sg^ngf1a=T~)1 zk*iTLJiX4m94?Qo5mP7h`P%@P?3MQ?_X>tAm`nOY*%^fQja_P~4W;KiJilgRI1^*W z7gB~(L$hu+1x(K`9^Obe%s7a76wK1D&9J`(zs82RH2zTU7^=_eJ;Wu89bU7u_3g+X zj|!<>YAMks-yC@0k-3gidbd>r+kk~!n2UIZV^qtyqW60L`f{50(io zVj__@fXk!OXL1Z>nygz+>^ZESxE3$DYQcLYuyavG{c^_;-IuR{ZV(mfTpj*-nAGn# zyTE952txIILWSYc2MkvvNw3s|m#yOy(AE*5lTaziBBTN+e8$`_b$(B`Ue&T_Qn8o`s&JF)>g38W_dx)h_3$zrT{S`*Ak z1nsf|+8`wB2zhX~isA>?=5`o=e}S_?taWfF^xGGAFmw$_r9UvQb*GZ7@2agR{ytBr z4yq?e<4A<|HwR}HiZ6_GD4j_}VpFNOV1|q7Zd8U{hDl-Y@4QHg5VIcp20!o-QNpHz zY2$2PD}+X#e;1-R>zxS*Rl!2c?u*3O616*+4A%b#JbBh9XG6t4UQ0HxcvMLkrX(Js z^FV&rUZ!JA@zRBGI49hPToK=2b9y|T;OknqnEb-#=+t_bbK|;ehH2Y5b4h`LWwY1; zWgY*!$K&z~ShNTbr`CPChRg@HBo3gZh!x|VC|xm#!wZffY#sIiX`5Yqu19>I?**)R z5}1$n$=cZre<8(IXa9c>{Kv(H5K%Ha3oI=`MMknxHm%r_8SY`jIDQ?K2`=h95$uA) zP#^d3LuYl!wrGlLm=qx4*8Q8yQDN}I8o#bVO44ymnQFib#PBSEaX(Wlxgc?ENc_G2qF1~Jgez4NqZ z^^FhBF$eMrbx!luj1@?_!jcUA2#A8xol`Mj-YhT5dgVB*7&#ozN_yZ3~3Tx7*N?+HzIBN}$lw zG$u$faFDs;+L?;3meTr)hIpbF>)zH+G&>C{jN}Y0Vi#9%Hz_O)P`Ly$8M-2jen0%b z+sjygzNmy(G%3i>s_p<aK)ZXb$+=|yZsQX{fmAN z5*yko53Db&<5F_rr~O=6ePsZ9+U_9$tsS@$WDTB$9YgDbB_xsRP`>L3y$P%#pXlw6 znIb}Jw?8)A*scMjUrxGtvk8D6o&oC?;pB(Um@O`&rfwAxVpehN4=T6XYjZQM(OXlQ zgIrw&&HGL3%;TvE8iJm)d^pw<6-x&Z?O}A1d&{oRN5GWy0dq{AGGm0Ho`fDDV(%8xNnQ-&+-c&Fl)yIQ-6yk>jMXo9n8%L?MVA9)&&P z#J1%R>Ru22x0F3w>*vd6#Z6g~kF>>~seV^YO+J06;7@8u6v9U+ybLB`Qfb4B?Z&jwQKAFQZU^ zJQuEo-7(XOS$2*wc%|@NHY)3OLMI zx#rxW4^gva-2$s++B{RUB{Y;r7(|(rH^EjND_fi)z2u5)Y`FMeiCEw)vu+>(=QI;! zNf7Y1p_=S7;TB?HXGI%j6;lBGMve^4sUvVopaOd!R`NJdfS)K-m>2JEbdTPimsMo- zfE(qyCF2_ZeF-b<<$o!XZisvx)e4!^vC8Id~8v9+G}_xpq4OOE@j*j{+sU>z%M#g{Radcr^%_k+k8bC`v=O|m-? zlRZu_qkLwa7*IkTy|6YmYjCc9dzx=-uGv|G*0)2i(ZzF7!Eqj@ZP@~M#V~h?y_!0! znIsbudwYc|C$-(1#e>`oPOmB?O)M(FWcyG&fwkt{c_FwZ7pUX3%RWEMRwepq`2_|~ z=h*Biorxqc;dkn$V5RxOp7&f8zmb!RJYN*`0gOYeQ_LcI!+?cqw`_JOJ zBETxciEz)$;HMgdR4|jaBws-5)b?lC{2#y$G7m%u+}D3fBO){QfKVWFT<#l`q^dnt z5o>0g{dS&EKTppBBpSP(xz9nQx^2#{2>Dy7~lw0=HfYtj}9mf_j*h9qyCB-Dwm9ZwZ=Z3%EV;`tIc0_%A03hI zbe2kJGuV3dcPI4?8o#>#bDTZx`oP==;Rq}sj0ftmH zN{0pT(+<>)PXY~QzwEek>EwJ!rI&a0OdtY*h6iYu_^~9kB~#M)Szx zu0}DL=OBH;AAQ(mWGczoWvGV&W1KxrSO}dg&9aSV;CPObfQs=!QfW!~t#i9RK+`Ym zgwiO4`&z1ldbg20U7&GNlJXAy+^#qa^T?MYfDmU3H18_JI?@b+g zwf=~bKMc37OK=e&hvw@wDo*ed%c6L8g80o_m*14P-FeC;#?(2N{F#Br z9+vBK(y?_y4j|VG8hA1+34z890Eum%+?O3&c2MOuv;pX#OL`xG@@C$E)uj(;YzO6V zu!#ImnEix)*=2)FCy5N!T9nbY8;jfGA^`jL(~_9#>?;qEcCbOLPOZMOkkSd+2j60h zsTLa`a5UTAJc0Fc0TS%gDv7!+IF_}-Q*n>KZNjE3{|`(0BY7y$8c(5bWR8qiJ^VtGB3vV2kJOscP z?laUR%Zn!~^!wrA$Q2%6h)v%d%@ilVXq(1NYwRXR7uYI=$5EGh`mCd=ctIKp1S}M#-&n^%H@2#f9Q-PgEWEiU2(V; zvYUJXz|!rUxM&jysDDiA$&(g8V~0$*k^&#y8nGdn5Q5G(XB8`H`v6qB;C#D*SNS7O z9kkdJe^xu`EcNI~zu*ZV!X?{%CA9yp{z{M9=w8_padd{8b(!fY+hRKtZ3af;{PYmt zYj8--=Xa5ww&0a6Yx+-}yt$)!bOtbGj-JM0*YLE0dOx+`$bpUgQ*ZhHYMr(-KXR6D zt|(3lZ`LKUV}JO~ldr*7?GZgF=-$cm$3o7W1so)q=jha;!+{ zX}7LPQZoZfQ)Yx_QS@&NhK7@})%g1%xo0=Hy9)OBtW;h+ot@}(ecI_8mtPcN&A|wG zan!}xgn$$PUdJ(@Q2umJFDzxEVqPAEoe(^t?r35C@w^zQ5kY3&_vSKx!MFaxR+Y>6 zFhCly6i~N#4djgCK>=VCZV@PZX&&fS`kD1YSAKA{dW9^jM;tNh`| z#61~=0~P^5G3~aB zpK-W4tPFd)zo-Et#|+Rca@d819*C4kLwfRwI$dQ&TTP*arp_~A&dz-^b?ldx204rW zJQA-eL2c&tZrA|J%$tI_-PG12Z)P!X%z9W3-lj{O$EB~s5QTTQ&Cm4&0&uxu(%(cJ zG(ug5Vy$xc7Y*UlPKxs)GU zpjZe+w|PYw>W;{|NhKfg!fcJo?yu%KkxhC60Ke^j)`{`HT*Kv{pKiU4r{Ny|UPWpv zpcl-0vPjK!Q&9C?rTtiXDSWypouO134Re9owm{qT{vY!Z+htL<_a8~~of@SskK+F= zQ)8~BdhxGyq<0pNy4IFM+skoD@@wFGT2;2SPfx@WYF}6v)i1A1xgMor7w!4`1cDi# z%}g}mOtcyR3P0s>T#cocZzi>7_-EbWb`P_#tIwgvla~Y&>dh{SSFr>5`c*BfeGRB- zF~3RZD2D1V1_tQX6OtF^~`;8E+zaU#gdTFLaVmIy$KrWzE2BQ zi!qn|-wr{|zO(;(gVjWP57MooL)RA!fnRJ~C76AOWV@ewY}i3bv2!CB_f2%behPw09_wm82mo!C7u?g=m8wa%R|dZyK(l z07d|s`~Fy|KV7=!0H%o@Wjmt8znE3>5Ot*j3Ni2+@h#lX#?jy?XvJv;$^=l(|A|jv zO>)e(GH^$b+d_FX?t(fT*UTK`RIuDQCAM?mu*c6LMS7(4n# zcLS7(ILk;{g<>1%Njo6`2%i>IFqMu;WW7_@2g6ejx>6s2-x-tO3GAa)!MvFIPD?$Ld7HGA6_GIY7sOxhKgM~$Cwh;hUl(z4 zjuz_{Im!b;_BhuWuowV|Gi1o0-?}qU93MiAAT`k*LC}w0tQ!dj8UVZjIi|!wh9N(Z z7$12YN{V-&p*(N}0HF0p+}=!YDNw~ZQ~@PrIsx*I>V7URbAn%1y*_PHSTMcinb5x} zNBGfKd02*st9VPhi824%m>-?r8O$lwW>nSp9L#riqW~+S-I3JCw=TtQfjlPB?7_;NqDFEfwxeV&|wA^jWt4{c-usR(*C0QLFNFk?h?Z+dwk7n zie&xVyG7t=l9S4>Vto}<&F&rcDnI6^V-M`|A=Tdh`T=@>W7qA(L;klW8*d*?p8hMm zo8e`9NVRe_D1&gVgwXeDX@wjfO}$}Fw9_rhCHVfJXd*qWG}q4m$;&U8w9Ks!2VOy`5+xYygyKkK-1xH?*b@^O;w$+Ldv7{<|Kv*BXa%qew3OK6jvXJ- zRv0yMA{*xpwQc^Aj|ik^tkozMVGCzn7lGKfL(EGEuJ*OIm9nV(aC5RiU@l-q|CR5E zddp~%wLydu(M%7WdrKGb$kJ^KEJvua1y7jKVi3|RGM{1oQV@(oft)8r^a^RUv?m=P zfG^|s;NVSo1r<|%A$&?~SJ-J}1s8o(=WO(W|(-IltMO)r*2!=GfBl z9QQ3P7rcdfO*oP4Lok2eAci0~WSAo8+`s3(mL#wEA(0v;m3kK?w5?4&g;CwUzS(Kt z9ARq%fJVu%756>OfoLrWkUl14|9Eq`Px5C0TL_ynD+0A9LFFrlG6^W599 z*u%}jhyzTjN!P<3)#z;eWoIpe{7U;u^aEc7B#N3IGO!X?xrfs#Rxv?_^@>|n$boh1 z*Du@~;42ZkBbO07^O1FR5vwsj^7O({@!?B+>59R6!P8{~?MN_}k*J2Ztd5W4*X38j zs4MQBm}P%O!3344n8a z_{+hA+e3sGTcHGfKeSaEi~{1bwJ^&f+3gLo+oP3pGv%xJ?CLP)<31l#*< zQZ<54=?WdNDkA-@6(k_g#oz+$f_xnN8JTRsAY}K1Ave>zRQA<&cv*hwmmS^}B@Nk` z8lgm4yK@u(`v7QMR-R;(8g%b2`MRESR%f;KR@Bi7U5EW49E$K$4}V08`hPtNE9&u(6Q82;-nvhM?6Va_!>RbsAVdv%V&%PdhuP| zu^ze~Vwo}3G||ymlSMc^YmIF1B@&@rDI3*c61>Efkrq6=x-v3j{xu4(wKGi9NLMrM zr&vOP<#we*fO7(EYNba}6i^PFjXq1f@|hZ`es;W=Af9!J1*=sUVGgztntv9p{3mKt zCc=WDPP~|f!JIr>L@MBdrb~h_+qf5DS6goBErCF2zExESWMZt8*%gp$U^+8On)uE{ zgw6s%l`ou&&b=CffeQH!W%_7@zjL>GY(sX)Gr1_>tYH;Ygk@89(1y{R8YY+Ew~?XI zrCs#Js!4>T#Y@n_CT4OWHt<`2M^PHZ$3*&!TQs}y#nf^!U3y6E&7pBhg9?1+!Yrm4 z#ghU8Arkw>p9$w+S1g^VQy%9F%0;SIv&;!4sw;P&A68b(>BYMx*JdB^e$Gbucz;EP zTd)!URJH4B74wL$1K`|7iIr(byt%EkVJK1!Y-!SMETZ@%c;L!djp8UG->F{v6!4g$ zL~;a<0Y=s&LKar;pa!n~KMD ze7)78+mvf{w1@4TGixRWBrJK=TVhsF!^#4ZQw5euN6pc+C}aHvfbYUJEavuZB_?l( ziUR6E4|8`<>vS*AU6&}s9Fc<&^6RD`{`N>U1j5#)-`_kFRvQKbh!6Eq?CKH2=wShf z1fH@oDw(p=0>t&debRidlghjTQ_ff_NTCUycgah~2O7PgBu;}5VwiGi(-P*_gT6u* z8#-4H0pP?X{d&K_Y+V=ed&!Ma!KIIkrX-7WEn#FJ#sBn_A!ItPBuk;32BzG)8uXfo zEgzc`89ATUG5sDPmluElI;3#>c-})Y%_Ny+RMu(yscKx?$HY=e&ZU_+oe9gVXz+&n z@#q~Y$3ot^7A08wkdg`h!gv$HhQC7NJJbF{l}u~bG_J=ugSDMi+%#MQCG~WGmqS8` zE3kA*6yPo|E3b9Mr@fPWr{;f>!}Y5H#}fbmH~E0q9?zJwCpm8)TYRJS!}u?vZmT2%sl(zCy;N|tS2`H59a$$h(s-@`v&mlQ$%+7C1x5uCm-d!) z8Zv3~(SMNg%3<9*)oR5xQ12&20icsQsrqW`+n4jDJRWyXL)YX!fU?8)cNtX1Gb|na z+qkA{_;2L!b}NlVxV8H;rP1N!F&O} zYnmqj@WZbBf%DcNfIh{D?Fa~>y&?mo%Y098s%?NThCtPSDj3Rf&(Bt<9aW$u*x>7r z!d^}xoSE4G0HfHjXO9uvw9l>-03rk|&P>!hm*kysPQ@=2&34uEHht~}6Kfsx^g7ZR z02FrP7(l+i55d8_>iaBq1j=whI&*JDUaL#DIE~Ze+Xn+r1HgDW6+%iJWjTg*A&J^U zEO^T4THC|mc=OGa2Y@z0BGS4@zEY4T<|*Z7CwtgRV-ER%a~8O(Vg3*xpx=OG;QUjU z_IPq3gp*RXn`U(Nk$v%xDXrD%Z|K_E&VgD>>iuUQqu^{$700oOr-!qlQho_oj8Cm$#Nw&AX$|ftk-KP*AE%}hJ^HmZ? zY6IX0=$zc)0RmfI2DunV%&L}#H*xz4$+e(&z*S_1M*&qLfk2k}44 zL^U4;$SA1Apk|o;cr54E5vN=nNfG;jd+&;IKV)90~TejKGi(QI;i$yn-RSw0KXUQ{W z`fQ-ONcfe3%zpq(SWjYRLu}atVRfLGUhTO<6KKXHFsD;w_DKrj@!ytQMg!!u*6{sr zho3vP2Vc;J?-O8(p9uTCH(o-B_+v(a zfTYI&4i^HKatI*6_7{+sPRf}I0T+E;8^7!sGvCX7whWIk0-(~9Y~IbD#YS(YCWr|E zAT+!n*{!`jS<@_D?;)R&SHi+VET2-~-+0Z+os#W?VnC~#RLaq|{wR32f#)tUg2QkV zM~(1k$Du9#L0>(}u73;VKPpxXvnMc=_rRIP#^$kg9osYfFzz1-e?&`~z zRl9!km1-`mgb};*Ywtf2#%{!mFvv=9CScG4s|2$&G&5azxR~St_H#+0)kcU&5;QHc zRF>G7C6k~`F&j2n=lUM!b zzH7TP%9;Jprebwj;$%q*f~YQr8$oUs2@Qt*kVYACaJqA3UO9T|Z0#agfHe+C+Y(Va~4QbL(sz$ZrJl%DNWE0Bndb)81`%`t!BRxv6E`ZiylNW0f}N9KEy0TG zUSWdi08Efn2sn7U4<>?p-d3b||711<*}vQE%s~00Rl|rp-$`b~id*v4Sn*odIIqfQ zS#jHh_2n;JbG+!R!FYMB5dO-qt_Po;&@JSIh{Uq$74w`|!)>1uy29w{f<9ypLyd}E{myP>4E&S_9b{)?h` zLw*mKh`(#l(yhKwY`JpwyD6oGzp2L+glDhN7Y^toUInFLcM7Ir-1b>#K7~il=kPz6%Q%Ih@!{$;GmA!4K?YO;0s@godo!H({c>ad+;QU+hER z!8;sMvM=w$&_Ed^|N6d65lv6XK(_)Y^U-sXmvg5#RJ_zml z?+*HJM%c1T$HWe~1V=w10-u{{hJrMB#_NfxSZXs&{vZ9{t(} zT#wc3z$BRcxGdtwC%Lo>KkzB5Pv(^RUR0Csi`&1Yn}hLZG!eYgRVi2T10c3$k&-#- zJSe{CulM_LB7m$*5F)LL|GCHTuIWS!;f#1vQ|7ezgmxgR8bqq}U2LGQ;QEs(AvuKc zVVci6&vJL_O}Y+X__B>adH7zx=<7~hv}H3X?37;!3eVrN$iGLRMOfwmS!l+NL*jw% zoLInmjb^-W^=9F?CWY0zEb zsDo3T;$Xh443Y^A(sfmfFD?2^pngpc)^&MBHZ|}Q!T(D($99frD`0#t#e_!sb;(61kd~=Ur#Lcexp+g3fQs64zs} zEfuycrnko#7V;W!EPWq0e_x2&-iMS}s5C(CJ2_MRsedTo9)X=`&0gV9=c3EEcEMUm zzJ=nAa>}#^dXmT_r>7%o{a8p}x16Qx>e2IaYk=C`5}2Q(Albxa2r%0XP!?cqSE%MhpRl+sWT$mH1IRz8h0)&+h0UV1-jkhvX+!n5zyXGO$`^MbbKx2v5JIW7NhSj zu6ZCecn;?H=LOvnxLAR5*Hhw-4JSb8mN!33XM^7*4;25>H>UZ+n=GD39*AT$tR7jn zXfUN^<+%dH?xDu4=$(H^EurC#O=g-KC3lGEo7aL#B&|8yi?S*H zPY#-<0tT^p{aP4My0Hbt7UcFiZLPnE%07$+KWrchT%UtZ2BnMGE_J{&d|V`a+I?|a ze@|EQaR#%3WIPQ_Kq+jzSc(fo%=KZNiX2gG$SoZk{DdFeUPhwlW1%hc%a~ULt?u+0 zm+o7sJ$Uz#_>o|c+F&Q6b~Y^;XJaHJ=&8T_s{Ry<w|LGWWKNFB*lSk3qQ9bGUCX zMRqN4v>i+&A|d00qG^ZW!mdZ;-7zM4{@F@H&xzt}8n8KxKUL&aTcTH*9I04~)=zJA_=f_(E)u`{&re70-q-i+Zylws z`KNjEpHYcT#sQc?wAYwL=FdDrs-x0fWx}=2121E-3GF>-yt`%15sPFVyWS4mU8N_c z!IG(-f5FpQpO60Pfhi?ShGJTp4rP%AKKk+|)@oT9JrQ;sAOEX-1%gwjWI>_R`t!Y0tB;9ImD;|0NrULpOQMr>A4@ciQ`UcsJe0GYT%Qa%Y7vsY$y_#T zk*;7`dn19eM7gXOa659|$1OXG|4NF@PQ%(Fzb#}AwC!(?TjwrIS|{Of9oTlzJ84uu zr@M2sCSRn%ZA+5kB$gNXzK8GgVpv9?Kq`3@bwWfwHju|GrcQE-L@+Ov zfx`M)cb&G6f?AqcC>UWUPDVD&CR5UkHz;Y`!D7}8jr|ChS$~?BHjkaUhy`djhSawfIep&1JnTvBjCu*< zhJtzs8LSQxoq!5~p9pH8D8m%UKt2q8+?}`#5^)c}4`t5XL9FsXrraH>jtlOe;7QB^ z(;##vqQ0Wpm6H)FsEJh)mCD^+*)2`x69EpI+9xn^LQB^MgWR)dY0kDo)ow_R!X(Q? z`vi@SY&5CfVd}gt0?Bw-uNR1-mB8BKl!>Y1ujD4p7RwhWFuT5QtrBs>CBtI|I|7-8 zu_*OTUSTq76}z3JF*pnLL{jE9o*AW@b8rTexP(GBX6W<@ZtcoVgmB6s?v*!0X~89 zLA766hBvmZVMh2T1aSNcI=5mRmMQ_E zDE*!Cpz1hX_sWZiS@;esKS*EEs>&cxD$CfjjgYcRH^0yZd*p(H=yPNi2P@cq`49kr z(!c6Q)#w|Hd#jjPde`!qTg1gi>p-2~mE8(D8i3DJov|stOxENdLBd0TXzQs|BZvJ( z$C}TTNw>^;^GByZhm!$jhxia9VQ;NYx)fu+ocs{0v3G}TnM&>P=j6%AQR})?M9X;y z2hNSzXfKy7Tn_6W9wedBHE1pfy z=sITq0uGKQ>p}!0f~gRE?3HFt75rFjRFH-1hn05`RP92;*u-_w?HW0E4N&q>Z@ooD z41Y{MT%6*U5-%FuW?*y?9HH|{2ixFI@YL5iV1%_;F^kK?14-q2qvTMEVLXY8(aKaK z@+ge`JDHn#7*KsHf#?S0rXDl-PlI zV`8B#G6(G7{Qv0s#^6qy=*wSh+qUgYjEQaAc4lHb6Wg|J+qP|U^Zs{htMuckU;Cy484A74?KyO zFFjGGC*5RgDBskfU)@o?Y7$R$0z76%=hU}io?`=|4iibT1#;uKsRtm8|C0+N{vdn! z%zj26tCD`Gvqlqo{)=iOzJVihYOPYbXE>IOmpL}INmF-w%1c*;yS4FY_+&P;6;w`7 zzLx#g@OrBD+(TRF8a;=93!xJ=3jN9e&luQ&O+(3NhD5`!Hx1zA!olsp3qpx?nf+UY z3-SsuT33ur&D00g=hdvQcEI-ovf~b=`hDwT#p~=UQRTxk0dz&f9INpQ;kI_|Tw8&h zlD?%Lkbfz0;YLNNnB6xT4I#yayDxWc-9O>C)QEsIdv%Cu@GQ9vIBu-9E}>h@HCS-w zDaEd*q`l2TZ#?-M&1m{@Iaz{Iq{16QUmUDCJvLEeTp=adR?NRGk{CiM$Bvx>Fq6Y` zm`%B0;B2FNFgvDZatnds3Hk7!f4KZkg^|OOdpp|?WY*ZlhL7Y-5(0(3W{TVH#U6HN zSCz#a6T?)ZCngZX(ycyQ462aTpSHdhZCLzWi8K@D%NEK)xHn!=7?A@z-L`=-vJH(& zX1~buN>tpBDEP^NeFU(;73(a(ifhGPF%!$xYBSVF_Radn@l5)w*oX;xb*Lo3DPP{& z9S`Fm#(N^EiiL!o+jc`t9oe?3+l+g6*yuS3 zMnK)_Q=O0EVFld5Kg3WVuK4umY~j+1Y}bsr+nvlU=v<>&9k@s$KM?4pR3 z{QG|ax}ANuE*~;IH^Q}qKe5QDxL@wa5zN$L(s9PHuEJ7o&>O(o-rA`2w+gBRXp@TP zII`P(#RNKf2RB9@*}34+IqO%)*DwlADf3cfx->~Wou~j5qdpn6oX9pjWGA*H`JsI2 zmfvm{BJMIaFC3QdFH0quC*}5p{priT0~%K_)2Vj5c-8=x2w9n=5s!DWnVGKf-&$#@MFfqb&SmoYo&lMULtmCbA1n$ z5rA@w286CEk6e5~qHp?8JWQ{uxJhh-1J~GuC3{%vvN;k802Bd%|u{ZHU{Ix`18yEAupKq|CT%$2CDHvLq z3LL5SX7Fy}Fzw`7EV)=AnDiBr!^AypQc|T3yS!Jx1hJlJ9FGcm3eGJg)0}2t?sbTD z&&iQP|53ei&S>$5kVSHis>egicSg8z8D$nD<;3F(iqSqEz@+<0^jc{;$72nL)0$q^ z&nTL}zZFdmWU3<6S9*lzY-S$OJ>H4Tq_%-bj~4iw_sxdlKvs1f&tziv-oem+0LJ7J zEflB6d42%XRQe(BtjcTj(g1HKV(#9AF)S3z~56-S#*EHi;l%nOXlD zm`F`v36!Kz|7j|B$gfQb(ab#{FQEtgL30t99(jXT52wD{#{@vmZ<5e7+Byb);Qc98 z5MH>I7bXl+ElvJ6UigocKvtK|NLUGUDA$8&iC>+-0yoRIc-jA#`UEk!#KqN!TX@we zKWk67V${k~%B;vSr7sYrr+_66gWmEFp|+knKYoIa{d}h#cwO$Fa}@GK=xVy5aQhtq z2x-53S+G9(A78M7G10)^yF`2SA|%z;hRAj`Oi70c2rW#2W4-a=F%kd}>5c;#zFJEV zJ<{BhwCQpN7LZn{&$yapY-EgLgK7<60!_~4%NV^61}f3}-vOAufJP|=#K0g_TEFRd zdviJRG2B{hl3&F*bzo^dI{e0zV)8?S=mMm5;|r!957tM+xgvCdMk1m-#KB#)fV8Uk zU;5|e$-@%$N#I64hF<5fYm#vPU;KI48Y6e8A3bQnp769}qnmX+cQyn4Ey2L_6)dL6}`1?%O)o1}IvT*+^qq5wS*YVXA( zXG&32J2BPKBr|LKIN~!P3vb=lS%sE@>X02`Uy7NT`NFila(ue_Exg}^Gz!5cjUP!T z1HZ6LG&DxO#^<@R^s`;D^aL(kZT$Y!pi^qN;%j@gl_p`+GeCoH3l3{Yw`AS2MhQ85 zEDQ>&F*n(`hN5s>eEd4ec}pYK;dS4ls^_I!82|-}w8{mYamH#{pnVs3yhQm_ECV%Z z13$tm^8ltua1ejD@Pv$tW z{2RRxTZ<)*xHxUSYL?$`7tEq2-H_6*Nbe^>cRa3j755n^rt34zLb2L)53juELOJJn zvqlds$em==muHYEIW()D%0C~@dxBkK4;Y1sZ4iTA|4=Es7rZ(#_n_p;$uoW;9uPqD zi}pf~QT}PsK%`r$&sbU;nnAd#Rijsuq?9IA9n?oP*Jj(ZgPha*tGPlo8mIlF@1j9Q zGlh*i&3ed5w8uTXSBcciR(B0z$?P&Yu^;{}zU^#b`Z7e+0`o>%He)4KWKq zww0~8Qy><3Y#E>s??;O%nz?%LU zW)$PpFgY*TXiXR1F75DifhR3^SH_m@OVVS+&lx|)Fsty!$UkJ#V+TnqNN`D~-=+bH z20-{OcbH=MBSLt}p?72iPBIgXVQGzNDa(s?%aoVi$phrh zDX&R7oeAH?Z}P%mX?C~56DgAJF$9#^agKrm*B;*DsslWMOnF>V5ryb;{Q*)EEbHcf zezR9~2Cx;17)u%ZomW%E)K_wCsM#cZIN+xUno})^^6G{HnBE?Oh(*txv9JbT;!I&} z@I)sK&_GBCVg2Fc*Pr!_JYErEC2#s=%mVeKQs#2* z@vWROEMeF25k+f$T!XW!x_BAwUfY6$at{FeAVL;&@hiYjqhVFDOZq`R8stL63R!kMHX7|H|fCwRXCpR;`Ao-dF7ayypWKjawv z1YMX!LlMDZXE8?x02?XD2tbE2+Bv7*-OVB;%&EB$E$~f;27))tmmQ=AWD)9XwcX;H>77(qJ0@7>h~yAdYd%j9gkfFcIiCQq>$HqU^DL#aH9f9wbe zetg0oe*x^{w9$qXqSB$MF^(q6b0wir^h8^Nij`SaxF7f5g4{%yO+^a+D5-N%mOhvH z^_4I0e$`fc+bDrfgN!Fm1Kc|a+BX0k`Ndb9q;=ObttAHHLSO%kb3K`;NEl>LY@t7m zZo6t&LOlSGUyjf|m64&-*a2DTg*oR{MO11xvd{57BuyWrmW738v*=kT|HFSdMcwCF zA-%CIl@-H5VE2a|(o1x6RP7GjCxCPM&^kM`hvHp4A45g^s$qs*LNLhavd8BaI3fbI z@Sm({6eGvjeWo((d0!t~Dil2z23l2QcGZm=QB0_lhKf1~mb)WZ`j)vQ(~yBWy}Sw~Ml zVBF%tK=?nobfo9>DSGJ-s%#Ll8?Bb?5#s=mrVJ!wn%pEk4J%~~-gzSk%31Oszqfh{ zr6#TDmN0|3O1~8Z=bjF)GwWB}^72A#6SE;6OH+=#weixi776^f8_|P2tcK21m_IRx z8iMZ3!HKqN7*PUMm=R#zVoz_vLsb1;LBJ-AdnFa`1NQrLOg8osqONKpXQR!rCKY{tjVNY8GM6jJ%WZE`EBWb znTwm#Y6{oqMPji+g%NxI5GWDU5=2emIXgkq=;yCpg&zO=qS@GGoJbuC5N_oV{9IYgG*#BFg*#EK^6Oj z!eyj5`utFHCnT|)9WygXm94n9cQc7~c<>Zi3pb4Ig;aS`lLr60C7`6zOa{of{2iyp zL$O@joYRPlg4l`cN9pxKm6Jo(&raF9Hj?{^`?5o3hMFAtr1%w9ILI_tzxwp7NE`P6 ziUb%Sk(}axZ{SJ7d+j?M>G%&Iq{$JT7}{nfE#lS>m1(cM3#!Re6{#p7)1~3#nOC0h zm>bWL3YkHv{&Q5J@p^s$n+1YdqO|{8=u!a9RynjS!!8Kdm%aE-xA1x zvBl&g4RN;KPG^MsK*d|9osH#Bk4=<+{viU>@mQG|RpB}MGX(`QVcC2bq9VymnKpu| z6^v5E)w;pVx1km@s@UmYHlt=qZSzJfm`xAt;1#a#X-icREM`blouckG2)hAsCYHl@ znEU9&mHkldF87osvrAYTSElctv{dx5i}wQk z_)6mUJK)c_3LG3{B`Qyv^Vw|d4vt!TeXfZcmC%y9rCo`Z9o5;{TFDt+Q=YQk#5 zk9Le}>hH<}Q09`~*Zf^hqXdk#SsZXQ_;=mSa}!AllZX%wTr4CvLNCuLm^W_JN~!(xi<6SaZ?`KCL`X z1_sqmy&otJ=h>zKatI$$58PL8ThYHR-N89z z{@klC&JnPlxrPyXOU)EG5py)i=X3FEWW@4sqbOTJ&}ax~6@5}i_CWE4T8#~Fd`h?( zi!OkKl6w_GS|T8CG@qSK!u=AH(7{T8AYfIO&XE>1@gmaqJ~;QR-965;F%R0u%tZxaw*5P6B{*LVS7g}&gH{M_ zY?oTS8p&0%#TLk@snG~JYCP2>70x#g#{vPY)mD!p8mf|k`lqMg-v|T=JkxH9!2?-B$&vekTNCNI>?_gCDU<{1&slR64$j0sW2IL3g8gvxN5 zy?e3-0iOfm5o&c37=|AhqJ%H1p3U>CX6>w4Z+`tvGDF$ey@zv+75zX!!f)c%$udis zP8J@zvOQ}YYdt#rmy>Z$9>0h^&_(lLaBu?j_(Gq@x(ZV(#8MwoZxu?7>;vsqA&fCG zt`>(kk;sXm-%2lP&ECOy`%tQAhX$0Rzu|8xx+OJ(W^g$xK=>?l1g{xbvj)n3vuqX^ zh5)aTz}xCVx!3W(;0r!VMcaEi(#hL+v*3v=PL+^d&NKl5B2AAN&bRhTDr7g``sixn zKCU>EB4S!n=^H{uQc+MduTCO1+_Flqy{GBh+lA9X`DBKKh}%-Xm|(A(cgS?gp7Xf9-z*^FLqY`4~H%JdjvEW+om@w}00rIF*;c8c#EqIV3W=2?R9J-MA zogr;*2Yg~#gcRgZneP4e>)VYth~13l+gMdmh~}%~2F2 z0_-i7L-l2-dTppcYY;+pr%X}H`zQ4)_AvKW8qk@P70U|}><$JQ4ILANXtFV$*Np5j zcy}1#b%rg&QR1J5C3rRnNzV}rviEGW(n5&fgl2KS_<^8!Y7{ZJc?T|z6I3BK(l+9u zTx4)1oA;$7&0qELhF~^RFkFtbSjr`7-eO(WtoYL`E(e93lx9Xn#mJNC)+$8b^B;FE zyqXlCP*%q;$}&;(TcOG%3{f zQ`tm7)|{*7kYPf5>kUYo$}Op428nr$TP%S)g6;Z87eBuXS0!W<=bh2pGM7JcxVS?u z)hEax6`^9<;b6Tt71N7mh6527sD{UB1YxkP&rI!zrBte;W}qVp$0IMAT(Lq!Adu$F z%>#=SPy4_Y;Zkn`ZXrD-Apnz$$oTSNZ-^1?v@ia^N1JZ=46ZOQ3at{|{r#sZt5#sQ zNO;MTZEf6O-2k}lz&g-oI}thnqQX9=$M(|_lSETxUqIjh*jpQ^Fk||yjY+Eq9;(=w z5`buA5EGyI!tMCushmHaD(zeiaH$qK06-NGR%`aa9f1Yp&lX2^Cua*!SS_^+5r<== zr{;Krl6Cjr2a9NO3czgnl|Yc)*j0yp1q3{|0>m&X+eXD*K z8N>v*CE+pFRcTQsl$B{9YR?73jfLM^zw&e%4`S z-s5Q$$m3#@Zg2J!`_=XFe;Csbxtk87#Z#G8Wpn86^FQR-Hhbr&^1=uuynd zoGYE@>Vo490JwO(wP;W$H5?k$(cthU-_&nke^rxH#oY;hYZaI;VPo-1Bw;{O+JL4x zF(*OAyFymPf2f1e(ZuhelRO)Sq(eC7>4wxnC&Gmkl1tdELQ_)=;b`dnPANS9uV>A_ z@HX238cM#HP^}QVwp1%T8l?nYx)G}CQFU~O(H`QG3nNQKov|tvo7jQn@Gq@nb&eMh zn1u+la=n~hzn?)E7{N5z;Q!{)t$sK={|{j&u@4At%HsWvk8`!T{=B7&7bze5Io;-@ zezJP7RYsF5=LomRWm48oSoI2`Sy2I3Y?KKDG$3iX=wVksl-L&w zT5q!?YHRIH7!LUKa-LlknNE*Oln*pXZW9W`7BY5X7TkqOBM<({N#`L)Y3FxreOp9l z)B#qRIdMohxSNPBkxK)Yb>!b#Q8&0}n#G4;4e?F3jkmLQT#B8V`KHurDm~7w*E3Wr zAVN3ru`#&x-+_Cq*ge@@{;aQ zEp#m1VL0#~GlaA{6MSCyz6pCwQ6Z}2C?5*4Dyn$X*+g{e*9v01=>iA}4s=4>kzXDx>r_xI zUJvNKfs+`v$fK;?A{NenA2O`916;j?F*On7hQz-ccnlkpSiQ`jb^W1WdNZ{dxlRrI zzEHikf91w@xj+kT06zGL2vQ}9sy9z*gHQiXVt1>`qNAw%$inBhj}PkxapVgna{xX` z;snX*2h=IOfPNs1#m709qghPbtwYQRm37pF_pUGcN9M)P~vp5=@bm(VI29kS(SJpGDIznjQ zr;DxH!1VQp(-W#>64)9nIm7G@oZ6}c5*zVqxBpthrTH=sQ_qw z-j4=@?(3AyR`+a$^GH?_It-yu6;106-h#xXQ{=$a8-nSsuzfqYL5ixe#gG!0HU6*8&f8OZT3sJ@ zEcn$Z3}~AlT)1}R7aUf3ojAU2#?Er?$`g=108r%&ApjsSrgGVfX<}{(i2?r?o+1bQU(a{; zTM^^3Awp?}%dVhdR8#unX#L(B@zQ@q7mXXhmb|pl&@W>GE!5!D>B>h%-~g5xoVAvh z#sd+REa_61;G~ZE|31Z(0~Y$eWBBIiFGInol*BAI5T7!+e!oNZFC0t^VvzM9Gs<`$ zl6{6M9+?f%UTjA)P^s#j>cfn&p{7m974L2$K1@TeWJO>3whm}T&42}#{!Rx3E?icx z6X=P?DgPwGYFGM$_o1ZmWXT|(9${D2H@_GIqzto44ce>o-^mYfd>gJy?9%?uWFh3e zok}OehhV2>B5on&^TW z8|?a`o?e}VrOYM_mV5EV*dn05kx*_O@oxx}1E8g*w@>|V-z9E4Fl%mSE3$X%37Yk?0jR#81y^ z$w1C5&7s~B1NwAxJCnJ&jUskl$6UMiRWI$?k$)zzA$?+UVUr48{bmi&`*E-_hEq{m zpP`2Bf~7{`a^`Qp}Ct`&4p-={4qwEr8QSzy3CFy zgPh2QlG-Cxm3&ZZ-?%29tM0`RWx+6%y-u19&C%X7FB9tNbSK0H*1wi1R>I`({TXy@ zbmMPvqkzp#3zRn5ExkNB_;rIZveuz>;v zC9RcbnD)88YnTp*c)Hwgb4r|A4xGnR^wJq)k|W7cLZ^n|BjF+6h^idrcd}7_XeYH8+3zMg;?|$0c4@Nw`L?V;OtZ=O*iX zS6Urz7yH*aV=Lcgwm3mN=)iSk;p*uC%NvvI+RY)=x%@=m-BXdiR*Y?TS2_N+Hk$x9 zGbdz^i9v3jYED(uKUQGuGrSY*TEi)|!mne~}E$TwwpSa73U9;={ z&n-Nrw{@ooEPo!`1DA^5EN$TP=h;tLX0`{&#x;0*l=jTrl^#EkgUH9pnj6shD3M58KF>dNXIx?&A*#fsq1u5T~3SC*FwiJ%8oqE#fq1` zi1?_8QhSc*lFf?@99=+Ak@H%3#85YXunO09lC3EpZcUJ3T)+AA1gxQ)$I0tQ1#Bx& z7004>Cr&L7*q|OkdoWjyDd!{HUcx~fR9Y)y9M}V zk1if<#>YmJvEge?e%eDfnUDIV`*$jU=sSjwm@HX=FhkUyuf7Ll3G^Hb9%tYgxH#9Z z@x0)_#FWDN0kAQM#{}PhW{`eJ-xJ7hoO_Cu{|!b}pe_arehaLtI)655<@o95eznd> zd4&LN^yQ+)PL9R;=udRpGJ-NUjw6x%!Vbu$rGmuMtk3(Z%+c*UhXruzmu`m;#~j-Zz6x7*($Hir3QG13>>MTJKB7#;9gki;cH#LWju)o& zqIb9g>gR;9%lV9#Yj1@K*5bte$|Sg%=^^?D{P<0608 zW`5{iNT6=x-BSwQ>PUu`k`e0&^zg**uw@YmXW+CTtrit#mWO|V{Uo3MXz{H4^zHZ!#ky!JQH$y9fFj|a<~ zA3aNVK_r#PB-E!(zFP>Kf79oH@*Re>DnJc}4)%v!6IJa<6nau%uyka~-@rH9vQEpT z;1cJ{0CHb<;w7cZx};T@e|q}2=)PnE0DvY4W~p5KSDa4%#w5hnMIAwmEexdMAf$(Z zM3@n3eW9jjdt-o*nGy{URyX|%akvcyKp{h+vLh=daW?zP4(?ZL1&7&hH4S0hhER&> znIF+b%AWAdd#Z~lVK`{PEI>w&O|r&a|2Y0#oRX!xB{01ojvWqX`5V5++<=SEWsfHX zPe#;^prj`i5ubogx(=+0&wRLH@2|SrzB-8{fd!bD_{EkG>T`@p2GBQQ&b^qjA(mue zO5yvhgBEC$eXTtm(2-Gm>p`5bO+hyuDkQ`QCd)9!4j*f2d9vB?o>~44#l*NGx^VL^ ztgF{1YN8M3b6;A}&uSQumV@M#PdT77NJnd1GG2mu5J83|BXHaLDl$h1-vd)p*lKCc z9-G57CH|~nfz0gB3Or%QnkRe4z+nE3foct8O@LKGqW2A(0Em}>WR@`PV#q-Ob|s$W zos};>Mht+&{bQcwmYx3Svzhpg1Ibo<{w%ubHg5|ZHMx=Sks*|o0%wn?;dA_T{k~`W z*=72tbu7t9sFHn1ClgmiVs);okNLeQ$SW*uGd(&@V+rS@*fzht)4CI|MIe95 z?igSPAhmz$z&Nj+;yabM+8dxP{_&lG!|Tx%AWdTtz}u6jo|DRTV;HM`-f zI|usvoZz~o2YdaDsoZ|wqP$VUjB7}<{xdqHh1%QG^u_A7_CZklx;V0<_Ow!;-RSfk@1lR3(=n{qW4Kq@WeB}h2gV$Xm|(a4;aO}G~d zu=@qa8x-<+S%Bs*_d(n$0@kUJ!!5KIwZMCF-ZiyDZ%$Bm9!Ns;tE7-^B^m7-ckj-H zKRJhS6zV=x`IA|%?jZl{z?Nnn7E3Y}&vQXNA=T*(8u((M!3zG$7w-CDn+nDFZduVf zB~8}YWE12?;P%a)6^ClKtj%Gq{i0bZ^NFM(Gke(us1;RY1WoGH0 z+BeXj%E}4uFJAhwiFV+W^zL~z5Xd7%p)X4!l!BC}H z=t(fuRwc(Z%<9>6gr|1TS?-aSL_W7~g2}gw`j`vtG32|%czNGD>ICZYg61MMRWXA1An-B(Ai(~fw(zXfJn zFjmJ@LTuvZ&8{5~zz7ZV7ADdz#MT#LdmWYF7DxdTz$5_~fmZCUqcvqqF$q96_@Y#a zGLo~I4f9s2ecQVR;&VWvISgpEekO?lGC$${qOh3TD51_spaDqScm>Fs_nyBPobM!w zTI7@vi|lFu-s2$yogh+XPp43UOmm=6bkv*mm{i;}yjLfzc+p?{^a)`ls4L>42wA(J zB7a^S;69)%oyebJEOrjk3LF3wIq7V52D*ErQthhy>&gN(jTV?k~njulbB z>MnE0kfj+iocp<8N$y{P=Gd`nnj1D0{%Y4p8II$^-vMX&=?N)e(|ipaLx~I>Ze}56 zY~#WyK~&yvtNxmcxt=(B3o7wSB*(r`M}LyW)IQT(|h$;d4Ybwe$ ze+VHqGRHppY@77^d)3cnk~B@DgiO;l!NcWpxub4pe1U7<{DRGM3G0Z&k1S2pP{+By{5J$4^=R>ei#?x=+Z8v~MLceBx&&W@VTMcM({}AZ znkLtTecjJ5?i5Ekm6dZ6f2*BOaV-(~(p@kmEfcclXFJo$3sd0!ov=htJi27Q9-M0R z7)q+dyTEGV-O0#QK!&iHq!=tX_*=CzL!4Kj&ik>)X4LtzVpmKeVGEZaSqY;vE zBv2|)?Pz7r#$Jj)SXb4UdgN=kq-d8W#R?p#-F1SRHLC;`K_;#1p^Y-zW@|TjiU-g+dV+)YX23wLk z`)+{EV8kQ{-G1hNWz6fTM)@Ptcr6A4OZ=V~_L}zY*Vh4di+AYRUJcJJWQJn;zof;I z4bKJ^GfkmRX^u<`5a-4>YgnjOVg4#x{z`7u?7?55JYmD?{Tkxdd(sq3h5U{Yd|+u} z+p)ahB6+S zimpE9Z&ezPY@U2aQ{wg%iV0$s^4q89iZy zGRBs9dJtG+OGz4NT#Hjnv5cRr={rQ0e*hA&lYqzmcRW(l>>M~^h{*?tRdr#QB((;L_1lht-071zRqqV)F&dWXV%F#yIsn7;PNODTM`&@BR1)ca z!s`Z<42~Ak;R|nI>i6L_eFql13MbA4U5w^89UA_cAJkEfs;)%S)yNdcs5}6Brsc!e z8xF5!#uY7LSygny3y*`QahrGCfKJ-IzD!87tVC zoY2T*s!R9EI-ONUw5JOP9m`)+!Fx#1Le}AYsbo|Bu|5p#ax7EcgR>RhPtU3k6a=5t z09ms9JxWI@mN?glOJ>HXw7lh29^Jljw(|}EfH8oRmc!QdP5nUy0A>An#l(+S0PI~2 z1pw5f;s9XvBH!YH4H3ZEXsqq%K&%?Ew5G)q6d=dZ**VsLFOjTHwMZ|SR#}52!{%X6*)RVBQx&trjQI!EU{SQ+NRF$Zy zILLW&-hRI3C1BrBXZlZP8GfM>o>a9GFl#x!_N=-1I;K(x#XE3IbfQuwKA0 zC!w#g4u`Mq{qUJj283@1`IulT&Z%qR9l-7M?)|SL3F3;2goLX3M}b}OEfT$1Jow;4 zllLMP`80G;Nn0iuJvL)(4zafA;@yT>T-*f|BB9arSnP^( z0AMMs004L(d^h;UznLKaOvLL_eSnAnIHOE3U0~3Tq;?XJfjgi0!?49_GPG|u2nsm` zTQ+<#ZgnP*(A{E}lXM*&8Lmz;9HucPv|l1i)V~oSk$xkIcE)6(5dgp=o*uAL0Q;-$ zyTcIbagObd9{{{`;g@u%P)}(e`HZzTt(j2gnLIY$;38xy+O%)=xO{Ay(rg-auMz(} znSEdfX_-((+m6+UwA2T5+Ic^d(EUtPX4eZcnagh?dVc7RP`d!!@*^*+6b~@(KXaiZ z9>|%8-K|RGTMNo#BiU&#(FK_;A-1<6?5D5Ecok~yinD6Cg}F~2=Jy7#k!7y|M>lh6 zR)^@isAZVHwyjyILj{}T)T@fug<}2i#Esye0>9f^;51;{md40ab9bW#JK6o&!0ew5 zr2W}IM~8R-KqJp^0zhYT0l-#iB`Od%+Df_0>T_Lb`2*%=$%mB9IWz{?rd^Dtkm#%;~4(+wJ~Io(LEh$Gig9Se1E2 zjZoj&LnYh}unut5I zIqs=g>C-C>m!M|f8213c4}SqxBy1Rr!X1C=+$ntEdF}H@7zxdjcdX;}>f4i{ z6m~#^ZC#LEwJ=h8;CSS32239uaxTq1yP)<~rBRZy`wpoUF-){ep1xZXLZQ}1h%5l~ zQ>g?2!ec!LcEs@Y*23kYR-8SF>ya_&e~CiKg8d3#3&!9ny;VZQj+jvAz6zMdkg6jC zZ6#LSA1mql!wC8Uj9Aga5jDN5(R6_7j6q^$5W+_5B|~~vc}P!N2_G2!mazIM>Jz9? z1i73A_TA%W>DV$1uTQ9=95-xVYS_cQmLFlN!W+oxTU02;Oq}bgvi5}tvaJ7OBEKIK z{nteN$?l`g*#S`J$Ae&o~2a{Ah^}#v&;~k1bNnHn2z2x&zR{ zy^0*bAtby{L6WbOt!xC_a{; zA)>yUxI@A(}Fo92hr{ zLN6kaqFkJ3Sqp!|a@*&EdN_EGSy4cN@DcR7sx0M42b^*u22DiOEXWrvi@9aFy4THj zh0|Rv2>W$G*M7(_bBBVsS(kKd zA9=(#KeT0^QlRO529SXLF@njD5v>2eMnGO{QNm_G_5E$YhEQw13p*-gjJB2@8joB3 z!yAE59N4~KT+WFDx<2_RV zIBU)<0Yqgn{{U*Uo|cjM2*Q`9Qxv?YBx?Ax4cBg7Pzh1L8}5A>Fz!X@X$eL!{2Xjy zdjK8tzv;DnlzpqYBWMd&Gssq4+KT945gMua4oI0;2x+N^jBNzoI@?bLbPxmV0fhnK ziwC5kzOXd_s8B!$=mTvCK(Xf_#6c$y6%-`V3V-)uJ^iD*8f@PW(jjbrDCnMYnue*w zC8rN$#YLJ89dZZ5Sb7B-Gna2Uu7F9N6zVxlv8&Rwt0_nD?k}aV)vqF9Pq3Zjjik;A zQRkcmN;Scw>s&H?2s0TgDW&P~u28au;%skaXAi7)(hS6EXrmn`sGr`$ykMGMQI3Gt z|MWfoZ`%_%3QNBR6HZ)3S^D1sM=zsaZ6?_0sp-~*dBOHgkkskRk8*-ee#YD#`2-c&45y?@+LI2t+S^#3{;Yow1tjA)^l1 zQhJ>Iyl>5_8U3_h@`j`Vaxlgol{w;B$_V}(1{&U?JnJS%74`3=7$2#ZyIQT>0;<}mDog!m! zW0n-rv}5F!p7i!ygC1rM5E$%^jy^Kzuh9@5dLwoEt6bZ_!yI(Bb6J!o6%AUWn}opNY366?CZEjQZmFvaH7(c)2@avVoa^tyf&^7;NRP(hW)XBjz{@>sj{Y6vjhc6 z)&}@7v|E6H`{vq2C^3J~q{C>Q($T5iLX(3`yzS@q zq$$aNcP4nx7$K0Xf>4rzkf|e?5X@sI>QXI&Y*pfGVLWd|8TT@hXTpD0$wR;v%p!mGPCaQg{NnB58w^(Oigz% z*$t;N6}xX;?TAmQY*!YJQY0`Dc!__FXKga0nCgCg#PWmM`7pj6K*LMVH>?{M-;Yu` ztN~m*0uy9Ma%+!*mtmMM&f|5i&zhtW0_{ecup8UzGR6C(`t^Fmb@>TC(cIL=wD`20 zGtLRS>Ku22bQ^zZzicp{^5W_>{tal@_P|XJiN5TNxOP~UH7eZFn~fox%%b>pt7fi# z$tLuQ%ph1OE6vHi#o)n}L@iTAa6F$f+uzpWt$?2YE%^J^J?4!D(o7EF_Xh?s?@%`0 z=y9#{s&H%_oJUc5?r+8fB0iVGzt2VjsOZ>{&+l#R4Z$u7Donf~a`V6(3$!Z5rKJRY z7TWw{b>cP1ro!;LO?KjD>o*n{Wv1sk(PhBhuas|~!GiSi+8zcF6bfpZfTU$?S_Ixh zChr$!c@TBIyFSQT6@2xjuUU}cDp^BBt7D|1P9K2>RQjpx98-*NhJOv|ISD+75zJK( zq2dtecqMT&SRlO}`xdg)KO}3bf^tT`JdsI8GuZ_XDcYEAjd$r8xHX1G7%}`btTHWP z#4m(ZSdz~*Z?h4&!gCXcG5vgg`5aS7tT*0s#whSbs6f!yqxL{ivP&tqm1vCd75h{a zvzalQoGpaCqz@0YS_i&Cy9%V`+qqabS{EuY+qC_g)+y7f>d5vyy4Q!D>Cp(gmM;q9 z#rQ1%k4cz(F)@GFTi`FO_}=k5JsP_eAw4*Nk3%V~_)0IdX|K~W@T?6uZ|#LU(eJ(Q zwXfwzc)_C?Z~X3*Ipog4qAT*K6+Cg9MR_9D!Y6j?utA~_agJgYQ%DKPxRH#d$hs}h zlJZMQO-@q{f`+Yb?o%3JGpjIS6**Sk2Wc=03rnV|;g}nh&P;w7)+*PR#fhOAixzZl z%Ce2)tL=ySK{kng{@{3Lj!!iIDG$tKF6m1uXhN&UvI4!JiR93w;R|z}_8LDE)jy^e zDrbG$0M}`UWDfXWQ;qSQG8XuyGRaZi%nf}6XKKfuq_3nMYO+)Unk5F}Nn+sTo(5)q zp-VfdH3@52?e?p$BL6uRf_ReABuDYc7Ty4TH*8U_S< zWu`VQnd>)HEeaa1`zB}GS~4X<5i`B$(&CH+f(%TuL9$r&bFXsZQ`O5H$TkzGokqtN zh?PNWYiWIj?o{vb%IuR0A}BMN2PmJlG*R0fa`tajDup3(k^u%i9#NTGjd3p0jy{+> zGi!x&aWlAA!>rsN$u_&?!Lvcr9lahcpWsv0Vbo!v+>Gp=Sz8;GH019|VVmkv9N2rkVc|g@(!M zSVaL1K*#4fUs8z8JNe=<<>W=>A}X9h#{x(!6q&KKb058F%J8OCsM&3a$BHy=g{8~n zX>0v!9LcC^FG#wFo1kp!_pXzY~@ro3?opM3c6nKBoP4FpGW-hHLCljW;QmH zOdWN-ltaDw+FY=Djs0-jQ4)fG2eW!1xGKci5|UO=@QL?oU%?xR-*V$`u|4if<+8}% zJUdG@`4=Eao(SAAA1vQ=$(N9g1Rm|n{f2UrKmFz`=ac4$Qe0+C<&vH#ESSgd(Xkcv z1|bwaM6=Gb-q!w7dV0d3z&COH$AI?_Aq}V0e7*`y9z)Y9MljeA2?->8iC@w{K><3) zI@1ik?A+|)Vi|ujOZmTC4a%DwMuSoVox;0_+mObEztHeb9 zMnc3#bK>Pp*u{u7z}M{uQwpRDlx6#00SMr74FLJa2B4!u*=}H}y#WBEP+8~s-Z*}M2LBgR-x!=p7j^r@wr$(CZ6_1kPA0Z( z+s4GU?M!UjndIjEzPh(=RsZbM-Fx-vQ+?Lndo7rtzqEKrimmxfZEwi*?$+U6!l&9g z?vcL&qSTUoZ0LPjIuF*`QLM*S3Sb{?8s#%HHbc|Lav5c`n zsgk(@Oc$o@d@NC5alMduHg(}!BE$$GG#^o;fa_4!Xxk78r-=KZyn;a`U;%`Iz-)z# zSu{eoW96yy(qYe30&X%P@ZpvzUG-EH$`6JkfP@-g;Ez@wrhp#uY}>xs^Y^uLEa>ar zW%fBW=?;@JuNqS*24x3PX#2 zy@|gLp6S$hp>PigEkS03MslnLRhkn^Rg99Kmr#Q(f*uQ_^8spU;9aZXTnPP}sExM? zZ0XuRGz18Ug+HYip#C2V-f*I8EA!62sw@Dg8N%Cg7w+?4S&L*YG=dT|Bq9dCSk$lu zo4NNSXeIy(1p{L3aVh5&!^P{a|wW->mz=A z9X2eDjK|b*8~k_!IW}|j?f>6n0eJv0z|4B+&Vg%}eYx4p0T4>>6>ES{GCDJ=-!Mq146X1N;LM@kWClCPKI{IcF`M zSv?XxY|~>`xXl9dgaN5Q%fq2XtrlSCb^9^~8UwJQ2LIjQw?8r>(DkQLp=w*|Kqqcb z2xI=D=kPvsHOPe>N&a#rO@Nxgh+iM!ARBsN7Obh$nbUQyE`AIRJnrRIv=wgPSSr#Jh=lU^WR>7WG_zx=Xt@+fl+% zDPT*(!HFkQX2HU1iJUv!JkH52RK7zhwsgMdfcEVMW|F(X`r6zT;^=<0j?=*(q()Mx zdZy<-rwCdi?Uf!BS|jV&Xcs{!Pufbo??eve<`eddf`UvV)Hq{mkKs-6j_P2R;Z|@N z6R*+pdWd*ZlJx+Je+prN(0`!&zgurv0PZoXk>LN}2Lb>-@~6oPRRw^g z<{@1%0s%BX%D>tyE(3k^2B7A=I6zzgzMmm*6%w9PbrQ0@Jyb6k@%?66N_m0<)haW8 z4`E3ItG95XkNg41xq}0>^YHt5^8HhS0O+Yb&YXr~AEb=}t4Amof2%$sO(9RH5AOJ#<+W#(HUMNFPL@sX(Wxvrg%hs#{(l&>atB-`i&f#`-ARzaF z_&PxS=^Fz+>U6X4y`cXt6IsS%N-x8{ey`aJQ3yzG`4Rjws4zBu^@b9;!9Y0BO{d${ z_cynMVcTDP>oFnkQFCpUqKz0R(j+;n18e{Q@b!aC^#4anlvJ4fFEYR#0Kf=0gt!9$ zf>cltxSpTTK^+#pY!^^<9vHBPt1j%12}BAY;n~B3Wdt_*Z%jd?&vq8x)k{(3eAiGR zmEf0@nHgHe7I(cna_TEL92yEFkjJ5*D)bJh$gB{#T!KHDs1yJ|Q`AlX3^nK`*_g)| zwJ1vYi45eLBbpNKc9w(fE-~D?1i|0u&<9&@5V%AM!jqYsfeQtoUc+vs#XBeBLetoF z>KkNne#;3UuHnEv$W5b4{?62&l2hDq8tRgaUMtkEzT=S@v5iv^s)zP`3D{|?xzfCk zogn%pAod0Lk5)1*6w0&!|6vRMhc5X4*aBirT5vGq^~a>+z|Zm_zQ0$#c-mgVIkIJ0 z`mSN=9MyyjDWWRCX{O~|@iP9y7S@R-gB8$wzO@IK74o_yNV_{&x)e-N7s*KIQ+eLcV*nf@mhNkY_4^I-bzYG&4%& z&{xO4S0sRnZ<*LXQt?~_5zMM8wt;Q^;VhIIQQK*%%^I$#cmUidxCq$rP776rE_{VZ zDV`;;Rb!<83Ncwd%s=a+dNeV#bz@cILhbj+0M16_{a?wI2@xXTp`FQm9tq>_97>5J%1}W4g^jQN^7Hhd+!i2ddKhOcgME=bs2V8P$$!nvOMwe*3Hm}cnZhA2J#57IG z$u1EbNJb8_yZhPO_-R%nl8lv#{r)opdr4Mw2+@p(g-guw>xA=*R-^)t;2`M4wb7sZ zo)(3}{g%D!56{|&cDblI zmeB>A+6vF*iOc9UTSFX7_7Jy8V^b_>79ep^o+SLJ94b8@2;0%3el#w!{cQmJ)o8B! zhzh|LEN^D;=%B_QWO>F111mUJrZnA>Jh(&1ZlY`Qi8j zuZPA?7fU7vGfhN^I=-ttnoJ}Jm9Dq&+=|h$$wfF?vo+740-Je;y0>~YS`=APT9m|@ zP9Glp`C8{%jlhvjQRxb{1`M788%bGP=00+dW>C`gnbLY6VPgL`>4JZAXjsLA^@H(? ze~i`)UoyWR8e8a8+~=xB?sGsh@PSPGYG)$yE<>Mv+kj)0-7y$}ncqws5H0$@Q%izW zb2VaYkK6;Rlh`$>wgB{4X9&E7rt^-Z+;q&3sUsbr5J0gcecwct{edRe5~-tE!PFqq z$RGOpN%S#~F~?f`+x{+wzZy}7wC)0f{4|uf_{OrkpZPL}j3hYvrkYaOi(Kl=S&?rB zG0?4us#RMly|=h6W-Gkm?GzLy(kES9a!}O~|M+rZFr)M6sKz&mY0OH~a2&e|^1GJR z*3a_r%b+fXRjwMw8!Fs_qFYaZyYQShJM13Q60$+V^>aLs`4F+Z*=*C*m^(ml0h;D?84fjpIbstFTR%e z3BvEoAWs4lBju?xn zC34Pz_LQ!`87}*-ktn&scU#vVv%f`#>`t?w7CieaK5FMZQhGLo&Q9)kEce~n`~p#N zs~S&hh~54>WTRP1R{2xhllbChf)kNJGk`lgQriBbE_--I z-22?Sr^%K6q#vt}?0sz`j#sW_&+45YFbDs&Y|HV4&rbvZ;0%KYX0`L%;*!HQqTs{Y zpI*PyOS*7%FwtT)^UU(yEsblmjlnGg*BT$qlkyp15Y0!A_UU(2$XZKX%`gcNwn)a< z#Urx|8=%EMTBQcp6k>!X2~h$`)q_oDVby!v*ND^(bFP2hRwO4S!B(&6_-v64hNfB3?{-mC{gAvkUV!l_)i{frzD8f9f8kwHh^ z%GQi`yV!MJqgtAy94^oIP8*hoB!n+&z7M76bT;O8pnC4yerJ(EEV`9|?}BL3ROilP zaZ>);I74DwJb%%i6N+NQ-S}p%Lv+smb&~^HtW!sZWjR3|(czV*aq(G`tx1|S9Xjn4 ze{a#c*C|Y44Co-gVV{e0{p!Bt!4FyDyUR6)t`gZ%Ye$^5o3Y#-8B|gJEYS z?NcImx72*@Cf3BEWZ~)nsW$YLoZ%iP}wH ze2s>nHdr!DFQGdRM>M316BGEaLeNz;Vn%TimS1)=<%q zOEdm!&KO3gTX_*KHyhNfPzc)=;84rCog2(=WTU(*jt^iA z$fJF#JO%WX%qrITFYIT!I7$z$-DeWacUg4P1_~C=8k{&-5|^vI95JmE&3=GCkAHZ& z{)x!t5=<;xH^P=!z7-&>Bg2|G816Y>?~1&duRr7G@m+QyMnjTI-z2IRjHjLxl%2N@~Jg9eqRCDRTlAuV^H(u8y_w)*I+rZlrdseMY*l{$El50*c~_l2XZ zA>kogVnHp}qfL?<=Z~Cr-)uNYX&yJ>IsIWn7b| zxoWnUi+BL_5j9HerS+nx8nqg(HP|izB#GgTwf)nS#OsqGvS*vNN%5k~ zQOlDChQcaq&4N=M4jya5_lU3bTV=xRS#RRy#`uKF;AXjQjabviR>_6e7#jIse$gh6 zKrQxc{S+WFg3X?Ctk*@E3713`#8ooF%Y)}bZ3UT zJj$T~hR~F?PqLThy6jjwn*w11)fHh@7WGfgl-%&?FZJ!n^AnUNY|;ac4~j4$&%c8y z8&xeY9;RIRPgvPE&nK_TTUugDj9*NWM$n&fp0-bdovNm+Eu3TFW#uU4${t3Q*GuO| z(PQj~JE4l#zRUG24$?!03x~G#HgkuzPLc5wjRWN9&*5xlfgYAE9Qy3cM za?fK@Nk6Pcy6KEEQs8~W2>!`;*-Oi|R_!A#&(LUv9Mt;%{g=_5*q5#|4k#a;r{2B~Y6tQ~DJzx{yqgmZbS``U>hBa#e9&nxc2z{(OP8&`xoga2*Zt{~y<}bU^pft=D z?_mWkOrJ&Gq1pbo3hcVx;ml6Tmz2_lj$eaU?pro@%Wk7Bn998B-(N7PpT2pq&k5zC zP6cghrR?=7!zRFt=^e);RQQr@$PMg?Ts{!W;D^iXW=2>y!ht7}4CA6ZShvw(qLdx=_h7YahB<%2a`rA zk_%Y?y4a0CfXMMy75h(##}54hgBmAK{$LGSCUiikND#P{JMG6o}B zGpd50XxzPs_$V0idyQPPI7@$& zM~_NCV<8)0MOih-briUgl$9EUq+K)B*1>@nvL%BhV%LTBoGYdGH#$b?a0I+f1sRUb8(~)1h-jxVkecXdW6a77}raE?Am1a8q81D<|9C0xmUm^cIQK%XNuHPjn z#mCsQ^fyMhf_WHAjjkN~92+@aG^kgfg}4D`LboO`suXV#Iz)OrlMC=c4D2}2OD>L3 z1^Mt#-%4UEER^w`obGu;iYs8h>oVkVSy=RxO#d()iJp+sO1Gj2c=|PZsfTQz5(=qO zd(vmCaUFo#hSSAe=|6#PA1_8#74xJh2qP&0M7s8x3@;!uF`h)1JtL9TgoX(lzVE3yjsevjd#}; zQ-9O0#e~viqY;t>>rL%$K8!aco|ZkOQ)}{7$OAFqY?hN(=eSDM`W1MV{kY6`-^9XK z0X=VOp5A$>BZ7y(jxoHAAAR=k5wBMLNYR6u%p~x5=w0d&dnX8QAE_Rn6+TOW_{Z#N z@Z=u18zY=*QU)Q^9BAn+$vn5ClXB`3CsfC*lm`J3yOy2&O5Wwvg}r-={Byk_BN!&@ z`Y&H!#zq`1)=wAh2otw!@5=(yka4u@nBx{_NXW(VH`eHj)xctJ_?;*mAn2BdPY2;t zaAa3guW6JkJuP**ZH%W6BT{?`1w0`i+Ty)|THL_ohI^={a0}>_ED}7DnU3#S_9m0r zS|}=WS?-qldcrPvoxnH+gxImjsm_0fHglD7FiQfR5Jc1jhEjN#ajyeQyr1kF=l2^Z zpbN3av;L=zTW?pbVOHedo6HYu?_`?hM!cF{T;6(zdz%cL8SlJ0LE_N@7xIYsw%{RM zdsZvRgM|S&iouYJ(2dyxxwCe*9gs7oAcwhrJ|Ksa!l-3ed;a%BeNho!aweGmkId-4 zZNJd`Ar2vhLgNA@KEqjny&oQ4t(81id()`%(Jqf+Yt@L`A0NEXd66WaNkf@{SE}h` z5EFjexJcyRSIU=eFCGMJ^+kwpL=^Q7%*E+^xU80iQr;O{IZ^uFuBA_z4aLMDpNiLm48OF<8?9DqIPq;^A_{PkWZ7)z zY$u-f`%lJ%{%2E9D&O46RcpFuux+38H_PKw zbc&s#42MuE6va06V3QVi(uWkLg{Jpcd)g+XCBc%Qc7+8-6ndGz?`>yiR8c!P3fi8| zydO*^--hNT;;eBWE2CIey$ro%L?A=|p`^D6{Oxc(nV?urn_Co;{7F2$D4Fn{Y4At1%IGXIK~U`M&Nv8}8~Vy$=sMRTQGAeIggquKLv~CDVnmk(ga`^h>T%h8MJ}AS*6vnv z((T?|Of+_$S)R~6M)ry7KoaOWd{nD#8l>3jXmQE$ShNY1{jrQ<(7_PH4pGSeB46@C zRzsAbdxAF?aXQ$349zde7%>~r6+T>2sSW-*(K4(;V;rEgMlgxgu==`8`AZFHK{98`v#=uCI4i{ToUutg6234AMTm@2WL%pC> zxe6>EW}iS|&w+g^b=?tpki>RdS?A=4{^oH1WXP|eGJxsVwEV@&bUHM0c3ghs8L~=t zX3gpd3BZZmq*Yfq4rxuG_Pu2wFShM>YHiRV{9fb5KHGc29Qo`2_w(<*rSoJK3kYE} z-8UlY1TEwuyj59zA_`BV4_HabbHhO+_+L^^%wZguq2x-#*pDY&YoBXd$|gUuLQ|B@ z!J_DIPwas7a@&Xd&n3i*`U*4*jS*Ud878{3T8FWz!MT&7VXT$-_jQr}HZnB4+N1|K zwVY5+wPXw^Bc7(Ckk1Ltt8gcxV=HLe$`8px01dts0TtZ!(W|SPs$ag^J=OsktryGk zWAF>B0ZbhQPF7|Yb9KL?ZW|17Hh8l|N5D$NltWLvk0x_>HeO7DMUO{y$9EQaXsKf~ zPN2zB!KS_h9bRVDUEa=T=^t5#@;aDjKRt33Oj9q|mN=}WkzlK9GVrj%4HwOYr3PC< zID!t-SuL4LZjzr)!P)(0!cN|I2gU{5&X?msgb3Q#vZ;pew1UkQ+=I(3izPvdlytpM z5JGV6DiZELOG@J$t{a`JiV>9~xn~Aa{rBV7FifW!{ha4}8L`e_cTeZ?wK~U zY1L$rB!nUZbM}81$N<7f=jfEpzn-V;3%KK>9M~7#yxSN%1YdTp+kwN@Pl7L0$ou_L zIcn2uu(f*lZj`F1lzEDG1_WV{HdWPPS~#3`k*?9h>>ad!ZwyD{{cUi!Bm{-g)dd&z zS6Dsgz)I^KObY!Tx258Fo_%W$d$2TlndHZmM`|IHpbIrqQzc2Pd}KhCjGJkTElD?dwG?yJHOPn~wtubLepHajr5H?s ztYX1S3=}AnhbL}At1F(>c7XBhk{ElcbMKXWv6z^R_oK(_3V_Y*I1-~wo+Elozd|vS zub#hfrFH(}{`K?2g;rz|@r+ut3JnG0$H8nHog$0FG)lek&w|SN3rO8^dC7I0iMr&;}dvzkvwa2CMSPBO5l85iB_#V z^^uZ|N0hZ0D0^!fN&;;pZ8bjqmxxD65K*`mpDS$SIcT4ZEOx{LxU-wsMRx*T?O1DH zZjIuR5=ClEBtvBV8|O1-#5Ir{{il=@Dg(`R-?^P(u07T=?BIexN_8YZkBTgM@%m1P z`jW&k&{cMF!_SaLDT5_-CJ8aiAV>bu%NKg7If~cg%1RD&NCK@S)q{;@er?^qHvl~w zstIPUaR!M>qlNh1(D!Ft++-WASz!cHRQOS^=ZrLC0yZj2WcG~8C??&{d<*oEAu-GP zR>1Z4O!XDzg1{DqlVOcJX}JopSg$$j77)lJ!thC(qe-O43B*D~(*zSgEJO+vCh=FM zxTfPvg>+|!lf(tPu=dnnvvC5Z)NrB%ZLDu^S@M-JXq|T8)71cle)e*3i27YH1+!S* zn0F+5Eu0;r5}~wwIAbz_gFIj*#Lq$NU%Y?T8_$6WgK!5*EQ{z)G=fl8Uupyj5Sfk% zss7FOhI?3RDkV&Xv@(9Z5HzOvN}L{Lxg)`b&tP`CqDtU74F`+~$OFT5AbD@1pj< zutbCg?;tJA0ddkYxWv3iJkuW|xQO_FYyL8uL!?RvkGW{=eeweG%DChu>TNgBv5_Of zfYXhuxCcMx1tOwYlxv35!;{&w%4lGrsr+&15q{14=r)7TMfK{)h=%%eM1i6N?U*L7 zL;I$8$*>#~fQO;=Mz^msDO4F=fr&Y!Z3^1wfp^W2vcY)FeodFWm?Ig4d~oMIE_GI5 zo~AKFtP}Is9Ks&C$Aw314AbqweD3i&gZ;_}!j zWz?nTg2QjJe2|S5MAj)83@>Sf(2fF@k|L?KtCLdZuNG44LN8(UM`D{NbzMO2mh@vi zGwqjVig==FUslJURuflX{r*Br(qR2$o3~F5so5rhCFtn)+ld9Mar>q}=wN1ucRzD2 z!8kAo?{BuM?}Jq9Odx)T{4u>PtPkMyciHMjjvG6Z`-y$rse>%8x#p^Qvq1cgQ zj_2EO5s?K(y_I-U5P1P>@di5{5^1IfP-P37J&Fk@)ii zWwKo^`~r@w_msMQkoSBil$kO-;S~b%Ptm1-1OZNbw(UdXiKLG|II-02&ZR!Ie|N;` ziVJX9!0v#%a6mNhn(z2a>|XB?~4BqZ<%Qrbo9h?gHn7DW!W8r;WyBLb;g| zuW3zOOoD*-lLgJi5AiwpN1B{~VpcT|<-XlrX&X>T&VU>*;{wzB zu5rEUG{h!3+t{q6!^{ZhoRBM+nKfVrjH`VXg9qRj;6>xZ-x@2doX4y$HPQpr?5*K` zFGW9$p|d+nsGEmnShitr(aNvd`MI(ng#VDtFehuk%38T(5rt6?I)+XZc4jW7Bvrj# z%6lf=6f~-56Kxe0?z!_G@{Ic>?%}2l3$ldfvUI)jGV(p=AJ|)-?I}Gs9~3$y$Pq8H znCxn_2h)Q2#RqPzxZB807AdwULblL1}MRg5si-|zA2=&eyMSJQI_yKMzZ6s<#OxP_L6 zDEObdW{EqPp_v9mk+wyyl)c1!KS7s|`O~%M( z^_rH%xPh8#%IS6GBxy2>$$M!Im+OJ>VZ^rR2TN70{;LTByuTJyIdFi2SFwH*D_udy zt)OWO%DeEl4<6ixjwqS@{rLmIm!T#jtkG7*i#+zEkXr`RDU+&8#lYuJ?}6mQG?KI9 zI*yf76EU2Mz?M`kJabJ{a7P^uK{v&^x$yJ^yPlB)#bf&#iPo94v!_3cDT`PaT!~{W z5M)p;{?^os77TZWncM8#PQUkZ_|Wa|G!u49Z?*;8U3^L!{##oQJUp=)XAO4>z_HP` zg4v=P2mPN978a6;lSpp;-pm3LJw?U!f>mXdFk?H^Q)N27MzU{+wif=UIdHg*a6pv= z4M#R^wrT6z1;htlp2BJVe@qt_>EH6@(iTpM^N1{qatl4Uo4fUg^)>mV zlz(l2at$O^H8ePTz4CE0k3Zo%L0xs$*{x4JlFHye_ZP|Hh$S*my8;LCMMz>?V)*m} zpf05*eC((WpPhi!kG^;8=RB$gub*4Zg^bg!)}3(VUp_D@s;7@YZ;fu8?Vpa0Nr@?^ z?@Hk6Z7S4WoszaOC83%`hzAQ9#joHNp}UklVZl&8b8UR*otjPLMwhaIH?1zhG@#Y z#E$(fo1rknoHs$VvyrQ&;NggJ=njxxS)(EwK^}?X&&j1z^?IbPuFh_QHzAJ=5uDML z;vpv}dZcDHEY!6u@$;(H#Mb-{>(48L@m}TY4nmoVb&f-7K2>A&{oXX&E%_;^=zyfZ zY_6_=K%ZG!7z^I`y4Se4NN7YExkeNdWyc@87{c!Lk#1I%OWqRtQc*4C+r~n%?P(-6 zN@l`tCGq*PEMyxh|0-=D`Lyf*k;6Zmg6y)?{P_C9B>!dFLho8yKl^eXzPY5VRD#^+ zw2249F&si|u3&C4G|Lm&u*}tePXqr6+&=^-qclVbbsP4^|og+I7 z7BkgQ<kFXgq=*LY7}~1~(M*+=eY$LRC_qJ9 z%(ok@k%3ptG;CKD+0G2D`3ARBzr0-pDD;;dQUAVL56%uQJDJDO_G^%rj`AR=J%kLl z?VBrwv)#4(y+5ZdCX*EQ^6TPw2jvHDm6@2jx<88U6oDkAOBzt;P)mN#&0yN=Qb^n} z3QitBSFY-YN?4Cw#~iaj4@k%-<1&8*9euQ(8@~)Zwqu__#&`NE3%1u5wL9as9da|) zmSJrZGm44%7;XSA!mHZxj;9bu5fT+HSUR2a5;7K65Go|OpF*n6Y!e%^RlDhH1%fy- z(1W`T$9o{83?xq_9DUz(qqUI(M3|Gd+T z1WoyX#`-Q9AD}2-yau1|`YB#6PG68U26E0Do-pZ(Vnc)}*vyJ*aXf9BVfWg?=Hq=m zyVP-Z{vF;E(3u405pN{46M?V)Y?<}gdLZ|nf6v)P6zt;S;m^8mm{pkm&c}kD zZBfk9U`~lIG~sop^IOb=`3`bV&{T`)p4?> zG>T&zWx05vX-7iED4-KeBDO`9ZBzNyW49o90*i7Rd`2QNG;;c2@dx3nYkAP3BnH)lJ!lgHl)8wUUySiz&bNh?Jhw) zNebKst5)2^m%=QH&Cu?1^t;bSC_(`S29wCNZU=oAy2#+i7uLtqB#7GOwqvQmp9r}t zjLNvzwDez_wW8@?pR{?=F{WgBtb3VH(7rO!32m#JxyXUq64gK)w=3HA9H{;Kb7wnp6<1dOlMkQtHnQvWp16%dRVR9?Rt%X5#lB z4hJJMC#4O>kB~NLT4(->)R{YXnYPbg!P-QrW^aPChFgPr_GIKlk>-4SI0Ey3ku=<+ zIu5)X)FG?bc|4i?pTUaTwBm4XoxcS_e7WzEdaaKlk$$s|9*Eo1j!pxyH*Zy4v zEFK9K$)G(U%D#obLITKKc4@otDPC=Fkf>lS_b{;0yj!Db^mCNP7PR`jN7X+IH{UPM zLChc&sQ0nRMjARF-oLj<4!8cjhXbHdsbr{7{y^0^kc`PC@(Y$yD&RP;zwwZ;Y%{(4C&XW5Z94IZ%{)u-X^P)i-$gWr z{>uYzamve#py3K)@SXz_f!J!)V!DC;G48w^u?+ty=q_(2HY}R=n#jum?Y-_M7+SiwQn2hJoQUgc z(>lH|KyiI>=IhA%m+rDi1{xjC+Q%pG^Da<`d8jUr7yY*`i{S^JII5H=g-oa#IgJDelo`&RNealuq zHI1s-%WF)xy2DMMTkB!M+i1})M6W^uVTpry)xRR)m#-WK^*Rgq0Ohci_+Pm!hEm8AR{_g zpCJCat?)IU>r?noIz#WGj;r0C^NaE&$e!5!0^Qx zn)C7!=VQx2*r{ge+}&v**jE+5I6(W-QM*f*JF*(&S#8O1b#`6kpR8Cy-!{9k9H*K} z0RhZ0Rc&^?iE&@u1=0wd%(P8iDiB`4ySnSLfL)cJwmrq7&+VzIn&()-0$6KYcVeyg zj$tes%j(CyZ}reFO-V*8GKf)33q%$Rb-~dN<2@-VzQbxVf>{9ri>aNSb3?LkPv=>J ztx*Ae@#MTehR6gJob=_?)oAxBN-y)jJ$Z%j$SZe2cn^ZiXxM3H9bLv!QG*&DflR!1 z@M-5t-=6_Ac?U9ApPn*mwMaK?8ADj`0|}K5-%lq}3{dOCf96KlS_v_#h0+{t?u3^- za*F>scTMlxo{NnpeQ)EX>h(ocum)gVw(fAr)Cfou64|L7u@)O=?ip)Hx{By#J~689miSfaVtugpSI7j_WXDn)*vZED>Z<|L6119{J!ya zN`UKvVpQp@x0@M~VpmJ!+h{`0YAHIZY%G5nl@_XXicdph}n3wSUjOP$v=f;ZxO2Rrscc>fd06XvKPwLclW=w8-|%|sspb>r9sn-#<#@JPmU-} z+#b`?99mnJgcmC5Zq-#H0$=N@QYI-qZMfx6*!JDAp+lo}g8PeMSXrWTB#tgw$|Fda5a-;G>X7!myuwhSk|@2Qvw$+P=1l@YyW zxUZ*T?|a?tM$9tq-?^TT!Q+C{k>4|zrD){kd^Yi!I2jtc=O1AG@#D40CGf}R*?{GP z&MIMvj(x&z!{as+o9qngcQEHfK}`Rt6`B(-RS7=@X4>LMut?5sP^s<4C%1X!-)i#^ zH|G0UK|LaWd6$IBhDP+WYMzINM5X>cX8)-684*BE>-Kn-eYI38)SM>&QO2;zh0)R* za6nf%xFoGhMAiKLs3b)YgV7 zOiE(bB=D_ulOffxboL->BP}o-YWnF5df9R)yiQ#$6ABGaXml`Aw_q2J`n#3w20e^@ z$3nSte%x|ALSw$Er2(d8D#GDy@Hb#6O)$rvnK}2#MmG4?HdVxi<)e_C0P{sECf+ap z7g{wkq|G$anPJeO+Q~X7L)<`JquF-_6o7{zzxYh*Nr_6o{5$m^OW(% zTHFEcU8-F$HJ&4r`+@Vl)9+0CQa%NiyZ2Y|vIqLo-{G6U5EAx?YxiPMY$c_w$sl zFH=}HrEg98Z+XLibo)?Me~;4~nS}sZaeav+f<(o6F#-zAxrlmAAkLWCGbqK2WZzUo zwTe3jb-vFmi(wgU1P$XuCOY1Un=c!cOtG1+Fl1szFqFEW@NIb{c?Jjimyp$x`Q~YAF%-O~r`k1~1|Lqf;)&TbmP&J)m#fogj?ud&1X&a38OUe&-k zOR3l^@W}STK-G&#k85V4M{DC#?1^Po5~?Var&4qF(JtkY+hq7|eYk0;4voM^bdmoj zaD!xE(K+gN8b_?jtNCU|F#%z@F)ldq#)AN~@Aau^FQJP-2;5CsPp3}Y1~UTqxz$Ge ztGs%w4#M);GsCMll z*!+N>g#_>BWI5)O%?e7RfG2TypMKQ7l7B&TorF`anr;?fQ9eVhk$ zq)WJS$@M<@xhO7zBz?PZj!8xRi=@NZCSGc{9Tn8*a11!HgW=?(2V&=Y&sJ7M^9AaUA3dYD50I}!ENSX&;TVV5xKbN-YxnbBbbrYy9cheQ zYZg5k!4I!Rml%;`^Lww7Ajb6b@5E!3aee64Zb)Lqx*Vu#9nTZytR3)vL?zRfigN~2 zGo-JZkemfn;aA<6UKVc8cr9v7=@nt~7xE)UKWE<&a1(Yuq#9O2>SSs5yZErj=&UmJ zrh%OBF|XNftEs%5o!PH}NbUWhi30Gv=YT(Jk%IswGySPCd<(&PEl<`@7%&^y7ro&z zQg3<@iN64TsdU@2WR)8T79)9|B@%g-fw}TlA}%vDiquDS}Vdx@@z zrlsNiwv*D7J2$yVb$`X3aF_4XKJYKH)D&!H^uY3-7U4kmC4BI_4JP&~O+W8TtRgmy z!KXq0#Zry(@(-AkEK7Mvma3boWi^H~6Xe*zU;hozGZVhGi}iFpj@K42ghWOn+^&5Y z2^6Iu=ma`cfoCP8utpb|{s@&frqj{Xqsq2-a(V!rSrst6vde=D9!`jpB)6*%&Z$kI!&GQT%p1 z4d`W!PlHv4)d@^?$JI`kthNNrnP`(Vrrn4E(QH5ptQ z;HHFv{XLXsQi^%`%O#puXGXx|4bSjHX;w%uR#Q{VT+j3q(Mc51cw~!GSkITdy26`B zK5=%l!Lmlphac?D*`!TzK)Gu{sT0yiI#>%#yzUI%XM=Y$Y6F&8J<6WK)=U-6hZO^% zcIKVHt+S!awVXIm4(Jc)#P92KIRAEZ@%;{)eq!~YXq+ZdbLEG5c0O|?pO=cW`(R|Z z)^lli8W-RmNWzinAQ2h-(RY(*@LOzjSbfgA-zh5tl%FWy$)48R*W#^`H33!~+ zRbW=mg`n)v(_^PtGU}x|2MQtcAQl%gq|UhH)3c%1f*4 z@AcDc`_vlgAI~cvfhMA^O&xVEBLX zckKMpZ8G*}S&aE7w}O9`$}@c|Hx_t!4-Fxy4at6N4mfSQSLJfwdZ(Z0W4BnTVAyHg z5K6XDsvmT`7ig#d^)IrL`Q`M5#|3N~ak!rCA2gEynkR*Y(1v}I-JmLS5(YF;Mf4o!hoB-s zcoHbE@3J}%m(a29sNcFbt)`2QC42_qE^-K1Tp&=GQ(h@_Z&LH-(0=Bnt?sueE=*TZ zk?<1PZFbqBk0BSF!t5ea`0h4e&vWxtm__z@H{9idBS5fL5g@p8cEl$2G3bU$me1gTcQL`g0 z)mbBAi>=b0!lEPOu!))r-GJIyRPKpXSGPhK+VI$|Lz^(XC5k>*BtgKQULUZKe0k;D zI^`z~7AZv>|Lgc>BL$UAS9Mx?_9JF~jOnnTP`1)KsWoW4nke4fz2y!GfMJ`DdsQJ8 zHi>GbNt4k{H;BP-0-_$Oljb*A;~OF-^g#cp0!fjuZzDB$Udua2_TF&RRJ{j&J^u?D zh7enpfn>5DV#jeM1=i)fQK=hv-pIvncIzf}AAg@7@1lteT z4){V)`87vn-6jKI6yAE5>GceapSCX2k<}1h{Z(%CVKL5>HBOT!0R*7^yv6jB+YHnd zpnN*FT$z*-V&Fbx^JZ)-!nldVAZplIEW*qnppvkfyHI9Ds`GB9$48La5AJ@jrc{O3 z-64!AW@G~Ch~NlGK*bwSv!c8sh92qb%m)cAwWng%$;L6;3~rtVv#Mp*SsaWRWLDs{ z8zmH~kehMD(R}RKGV3oMLr}BdW{0XNaq<0Rv@z>G%*JZX?&xd2ST@z%al~iqmgJSJ zLB<^9R7B61yBk~T)HfSX02xk$_sywsdag+-~RzsxG%74|Q9aolyq zJ=yg`$;tGdTiowdxCpdE>rM##NqBbo?md%ya?MG?A%moQWHt(LF{-r@IZ)uu!qW;` z!!NCyLEAM{C({ko=egWREZ3pmeT3kl?dCxWww_+Rf(H$wUL-AX7XM;X#0=#UWtwKk zeTcj_?_JblW}_YO1NdzlA?g|V0l z4`Iw!>q}I|vzQ;*^+K`lz!tlsuIJmbBDc$9EgjZkC@Si(wUMylCZE{05*j)&qixry zZUL>;BQXwv8wu!d0g$s@gQ3VDtG$w_VU{jJ*pDJ5|04PCBfwcDK1!{muPNZa&n?J* zqIG)2QWV?eN{XB0QJA0hyx z1+nV}o9BPA*&8LK&pIWQ^hOdCZC0f7e;447Qx78=$&q5aZ8c&)aujOX%ml?Wwg4{@WEyR=+m&<48#JSsFHr*3;opIRI(oO3-|S~dqbHkMijxv$ba{c-*MU3@CKPU4f;KTbzB?v$}q@zUz(Ca7(-?$`m-wfAx$x-S5gy*bt>E% zFaK&VJa1D$GX@NgLBZJ}!uw=0Wxjj-0tVx=(B-}9VR@fA`Uz1qa6|ecIRri>A`~fJ z+E!X>#|H-Q5()AokF0a?k*m0iV9muHeFHR&ZA=;(bf$#?$@SAL|7&48Vh|I&t+p>d zcdQ^+$IrION-zykJw7@lk*2HFWq5NL$Z0KlGR7s%0j{2EaeqB-ZCBdJuWMlk_x6Y| zdKu}AQR~!Ks;c#6RqFb@cL>@4lSfd6clu~{trss(Ia!1bh+moHGes(IO>8Rff_!?s zBFbBcZQ1hgBFWlQdXy(!Tjb06jt@~%SKKLn5C@a4dTi87ZeWrHVfm~{ul5Y=M_L-{ zo%r3#tslgnFzeO{3;>5l)Pv!2UC8eijy_Uz(st+jW5D1+zU9X6C&P;-&Yv>o6w}fy z=%;2~a+D4>zLlx#7LvD>YieF-2S)6Gj6Z;rXREmA_;Wy|_GM<;1+gkiG~*Eui8wq2 zO0e3l*Gwi7GXg+ME=hEbb8Qk{W1J!j|`1# z*;CR%6>m{U?SZzPs1*mKmgS26MO827Auw_kg7ZxW52WL@Tgs9#BsUmyO%?t$Q1R3p)sTO6QnIKfHs5qc*D|MraJ)Mo9- z`+Z&DIwEm6ixGNjE^&+*iKK=eY0k1hTT(Y^!hQ)RevBq0)aMl=hB`>w*q;mn|Kr$M zGO)h_=$No|@xMT8^|Do>g5H=>V>6K>9lSM1?RN0NA2~pB$0|inwCEQ>s>g(V z#(GZ0s$(!#gOSkl$p@R?HZyOhPLZ+&0b)A1CnnYVyC!7`iwK3@MBSOM>B-=y` z<)>EKXGv@JywVQ0bj4sscHsWi5O$3cXt}`$`^G5R;o2LDCLeFC*b^eDjf`1?#6bkC zRg!@!DD96L71Wb(A0^egzs5CK{jCB4<7K9Qq=idW{Fa1O)>dHr%gz{KoQqq5!Q(o8 zYjPe2k^vpjG`Y-Zt$c6_D{%U)GSG{{jSx0NwKOPdLzbw!-E{TvB0&6zRCJz}_gWT7 zFnsya@DRFOPrEc8g{?*4dfE)`@xp%i^t(wo~dl^klo;^^BgkX)rb5Op}*bb~01~qZnXFBzgO@B;+7KB)C4S zplf$nz|vOIwkHcV+Qpd}yrT-E)|Iwp1NrE^*;NsP)hg|W&p6VBN@zg9E~T+K+g6$b z-(|!(aAS(n`bo3Vi2a+;B!%Z_`zlGmr((?*D{=R`L8B*zySJ3ciWms1N#~JcUoGLeG-kF5!P{9goSZcZv zMg~mvB0YLWvXwQiF4h=cPYsUPxNp~2HGyBSA4T!kk*75QwIV!#b+PHCIq7BtM5bZ) z7Aq9~RWrv=@F{G22&YsQS0!qWXz|dH)Q;+KZe1Pu4^e; z^-eIUaqgh7M;9M`#M$qbOkr|dBnIKxRc(3dXI6GN*GT+iT&s@m%y0bzg@(b%YH`Sf z1O;ft$$B7c(mGlHTURSGUNXcB~ufSKVT~o!80*{+1EOp`t!J?(g2sQ%W``KI`YL71YY_V9-&D%c! zFO~MGJPz*DDk_!L89=y&B-;AhA0J+&<2~too5PS^F1n`_LAbNxA~yeCL?eGc-GD=TC3+n-XlglI6b?~Mv?r)eOnsqvsRVw5kllND z7eb4Wpg4$(p!mQ`H|^$ZtGSVv78lSaH?Z!RJedTfnWlj+jG~5OZKR{9-7oshk&v5-_%Km^&Cl`twtIw3Up8w&$mQ*Z zax#QNTY;fth?En#?!P-`r)1H;&@P{V2yr=KYjjNNQB~DcT|z`y70QK4qH$*t@)W!W zGa^HQf}KJpewS?+CH4wpxoU}U8z9Qb$wb@ur>X!pP1tHwtGWBW>k%(+89SF>!lOOq z_@<^yFg8~9HXzm*?pK-J3+%5KwdBugsA~#l28DbtP9hQ~t^-C(U+kJ0oxKVN*3dG}^A1)XwY8te2cSXYWkoC;uyz6j&k*N2+Npf=v`iMp<8e^^~mSgl2Ps6m&d>rvtB!zw4EqF1(^76T4!2+u^$J zV^hvNKb}sOWknR7t2pprrticqjdu+t@4W#!JEqrR?yUUJ_4Wh`vEjio@Li3Dl2}FK zB|`13`(#$3SNOZ+zq_m}k|ks{r2E$tk(@bA?!cvmmYDg?Ct2msYcm@}ESujjhsq$O zGY6B5HoQQx%Jl5aG%$f)v`aD-o}8_?@A{prVw$&_ongQ!~7vh`IRfA7oeF1U_g6?-Nbn5c&^ALh*0%kZgd6@wrVmLMAfLr+=4d@F^3ArMa{EL#zPGr#3ALJ+1 z0+r5zjnhcZUl;VYo20tf4ns9X_L?y`#qWGpEuVn$^==a?Q4eAJaQ!C%7Ff^z^Cv*u z@JNq?t`-%MU^|%7Pvp~gNcJ4q@@Bu$z2O}^gR2IXxxw+94m}W#PCcWW_svm&qvGC* zgL`md>G^f%w_b4aum9HF;5ccrVd68BmmtU5;99vD(@|&j$=Ani5JOjPLSW` zs+{nu(w6|o?vup`HBRL{}*v3BlEYu zWub1;0dBvJzvNVGJy(}xAyncQ98JbP@#r;S@JZ3mt2n2(k>@ugEw!XwN)hBE`=e#t z(sBaBNrQK}3?rmA1^%WU5BHs2ZRE$&hS|Dtp5;s)j}2#71kJ_WbSj^tSCfXr5aG)L zlvcclEaT#Dpx3jDSE1|A&uRWgd~vQ-osNP+Z>&(t-cxz@Rc~%|fkGgF)4H88mH|$Q z&`fIr!uW(fqzx!S4u2-*#r33Q`^HvIyV|EH6yo`{5wwRj+dh2jUe#9;Z&5O zb|3IfhrG$3*KUuJ{gRQFQek$6HUsEngtu-I%i0E5d5V#@Q&kzS)a*x8VBg@k??=|v zqtY@th7*YT$WOvIySL~*L_(9^ypM*$>Jhe;5dO08eME4&3muucRO1L0s_wA0Lx-zH z6-6>F>EWxzv%%Y+nuSX)*~iRLftN%H|LtD^slmpiCqxLVd**ZFsbP$5J^yB?hk$_d z8DF9-3P4e19sA}}+yCX3Z6G;}Zo=h}1Cz?@G|~ns?jg+MzXUda178uLF~w0s@V_&e zfJ(}vM}bXn-(EBax=a_E?ELs7{Qc_I!!sm=zer^cRCWROV{S*5Fl3Q}4)u$KBpl)% zmi=2`MAsz}zPKi+lFLEM?mU-vS_6W#{g}@25yySDoH-ol+#E)wMcvhFSYN%Nq}%0D z#;o(H$z!h65)y6q4`+|RmO?s0FmlpiGe4kkxGob!+CD6yjDO*5I4*=#q54;Xr2yFd zP2A%l$N&l-<8F>11IMiLkS^EmG<9`a#Jw_)l!V(%Q`NZZ#+s=o_;S9uWM{u0r#e{< zZns(1y_A=-U|L_VqD}Z91M^aVL$`BVV>MOUT|M5nMI9z9{|9gLM#xK-vWMFlD{@J(p*zp1K zl> zPgkDaw{=g(dn`28IKTc(%u!1L1o?X{+3`{S=3$>cFswlpxcr@fK^hB>LwWEsW5l|m zU;2IJdz(0q`z)f1V?J`dlR}!(5xUsk8haDNKFqF4Y&-?-lz0q)UY3@uH)-5XL4bS8 zAbccb;%t(ya!EtzpO<`+zih|$nm2Fy zYA?I~+5bc~=+?u*AAwXqEWY@t6Q7HeDv8-BjSEdQ0gM#yZ1wOB>nd(_LRJh6Dcaj;yB*A5YYe-?uE-8 zV_|=O{Z?8)rf@PmCZ3mgW$Y>U^*yk`ObD`+*L2YQh-IkVdyQwM0*m7V=8G4viAdP;Mb>K{|36>!r7z`3CIN5yG)K6O|XVIe2hef_gC@6q4 z^r(Y9nf~rZvKJQzSeYymzf46-%wkTV@xDd^m6{83a2%M!VNx*XqJSAtzd)G6Qw8pJ zEbK8}R$1_bjYDhhXexG{zmvD^db8A-tr#!JAlmrF65Enwix_Q#PnSGD8TUPNoL7J@ zyl6wExf#+3PvEC5K0$WlPR2N?LU8WW1BXO^vQ+^6l2~xW*c%5mw-eS)bsLXG_y~QI>$DryLM1AAe7jzZxHP;EsE+&1WKjgZn3u^$iHghzJ7O_e|=ED*sp+8&YZ4xtKN zZM}=#FL!DFQR_x(h?^K8MgN?&zY1^c26Jjp?&H`qotf`^r;a<5=`WV7pehd}lz(bw z{cNycihtl{St8aQK{U&0ad7_nJZ_T5BgtB8PUh7KA#()p%Q@zdlL09+f)Ac6OC;^h z;OIvWTW)5VMA4*(E%Bmua&4PB<`1-PaX<;629i@ch4I$=!wsr`WmChg8<~ed^xI=} zrJn`!jdH5Ol`Km0wZ-&T@&_^JR!A$<3TAl{&a#v!W9x9Yf;MY+Y?oJed&y&Q^yFRi z%R%QHtFo`hjI7q7vNVADBVB*f$xT51Myd+3T;U{$e(_&?_X`x92a)GW&A1e4#B%8( zy32;~2IHkCOs`mS9@JNWc5tf;=Ru0e>rHc~M-^IAiah;tl9nc#jz~rHHE|3FHn-6K zgLu%%4di}B(Vs`GYb<|Csn~v&ViKKIVRikRLH1J2zZ{;lD3p=p$0F4HYwTx`ZiRbe zI-r+(-Ayp$><@syH>dlvq6jm879c?uh-MGc;5Aabq$Hi;X&h+&z~*JOgWB1s(H|LA zNNL>b6cf+#ARU_lXLR6KyBr^~xOp$$pZHT~f16Nb5^`MngjMa+tZ`x50V;*<5Z=u| zH2AAoddS%TM+i;qOyjTkN8ODj8=4H`0V)vj{@&-O{#Nw@TR6d^RM4lys|t#uu2W7_ zYstnaxuII3bJcqMnY+-|>x9AVnHbk(SQV-%jnv;YlWkPp(#$Q8X!AN${6^@M_J>ak z*m6zXM8_F-&C;{^1J$EbxjA$0o*kq6BfG}SDt6|LFLO~p+c4ZJT68_K<&;s(ZgwB? zPebU$hy5YDOjv!eS>S}#HhtK-DVEunRwGJfq!SrPn%FzLp8*v>F%cXE%_SrYXn&V3 zNSDs}+VN5@V^gM+4*t-j2ichzunhw;Qb(II9cp42RjU$Xkw&?B=N9)O(X`!H!tP*H_Z}WTlK0aPTxqq`xTAS3sIuT*W9sX` zbDViAvt~uqqdsmWc)y@Jz|za$RN(j(QphwS_|RdWG z7>^KCILs!fXvmwPd1$VYSV$Jqo!*_o2e>1+-?6T5jeY)^81c-dtq0eEsdUI>9PSH z<;n07V${T0(6bU0)nF?RcR~wS#MQRR8JKhYHXc&zWQ``QD77YkxHlQIb;K;efNe6? zu4%!dQ?m$ETMYjXlp$*80!P4L*^{0Ftnt2>{xk&92T?_{W`4g#EZ}cU1jGV5JfO|9 zm5`>fbZ6GCfGEhWZq#m&QvX}y=f$6=HIj;;i>jlDbCsSMfsvOVt2``R?Ny|ZyCGfh z#&Gm6nWJS4@JcJx&aZIrIrgJ3pWi&&hY@h*Cd#l!EzTsz)*r}9H$U8@-K7i1*V-ws ziSL0rxj#OwaJ}(bQAga!!jc5|pI$?=YQ_-*Q^pJ$kLVA4dY_KDP`n@5MSNiQFJKQ< zkLCseM-%>oHqmSkVXSf13O{IWr7*SoJoMX~Q@^jH9oE;@(TQNN0Nd|8SpFQD9i_-1 zRV_FDMDf$_FyT&B?tlF^+)*VpNTlkz>az+#{~fR0c##4_5kn7tOq8!;0BUHs&icTC zPtc}>yQ}*Evh7kydn^~8g`FQ_5mTCd^&z+BsvDx8$DEA@C}W&|TVv@|@oF56okpKO z$RrT6z=Sg!etm$6B?1*2cr<usf9 z2=bBN+CA)`duFN3k%?i7BZXrZCvaB*g zH(R9HvsHuk6SY4z;z+@*H~PFCsI?{nR!5q_z;+EYYEtS@!{$8QMFYbAym&XtxAkGHaDg6SU##Nn-SAn2%8nuwbB6gbPWE>#DVRWS$_mZxHsgA~-+N-t7nN)g5yCCg@tz<8PWqIvl| z>$+~iiHE`y$|J=VoGaB1FQ&5aFJPA}89(3avlduy{@C+gP>eIFagBDSqM#V&U@vQt zOLuIe3w=3B9f{>*Ei!QRQzoG@DdX-_o!6tJH5RB@9 zVa`Mi5!d#`<`5CTSjhc@g6^~t;8RHz4FUem%RinYvy-cb_L0_uTDb?0+jd;q&joeN z*ro>U`RmMQ_XPu`z=l8%*FmFVs;%pkUhY%v*?La(o;aAmU5{40)<_Zp1~2wPeml0a zNJW4(Jj5uWUCcT=6cE$m0QVdT$x+&|{BD?T$cBy8xyh6iqKj=G&Ek%NiEqxBvAJPJ zVZp%6O{&G{@EY_P(!N@-8^GB|jp3eWhO;fN-&uwC;gHVF*V#-kU;-b=pS!lbrYaN3 zthyc>N6DrN3)Ei}D%xo|hh<^o9Vd3n-w+nOf_EG)`t-N7DN#)Thzr)GKo+7vJVY!_ zq+BF1x{nW7)asn341q0l__qLvG_O{E^;SQmwE?-}O6_#hzqE+bzd93zJjU_OE z+AKBGFXf2F^cj{~`Xgc>RoUMNFTC9E)85}mVGr!{ps1zmp=LxLm#XUntb>dA)Sjg| zBC40VqH)-Fvm)Z<^Pzx9z@||repEFtQpggDtM2BBD0PZ zw))Xul_E;flQ6>VI52$9sfXLGO4sYD!Plz<&yCW(28#%*9mBK8sQq@z&~NdG<#asYi*5!e_@N|64^>+g-n`e1i0BoaI2PARkW3^F9<`)uo z{q;9^GlsMak*|N` zg!{cV6`}!yMutdl6FVCb91E$ny@@ndJQB)y$n%IisGHP1g=7U%`wCBj4 z0wv*+%DKZspgmZ&>z1mEcyZsKzYKk4J$t;ZCUZcadqvaCb{Z%PFPy&; zG0l>zRBW|x7~eI=F&e?vL2_6@8a47Vk^s$7oV-8h!itGHCf%l|V9Og`;-OOMYC}_$ zg45OTz5JN zAC?{^EIObTU!E>p?H$L4wJ4BYgHz0RK7vHZN;ZTztOezdu}o{KbDSu=hN;nF;+8Y4 z9X{dyqo4ewh>|d%8jDET@i!+R=r#I!#e{KW;HnEG2>u+fvAHT?|JdF@j_lP`lM+DJ~NF#S0*q^ zL}(Qs9;0=R%HrDG}?6JfZF|ISAoJ?Ssrw^Gs)BQ@+wk&KK^+&!UgsNLk9-zG5(Vd}0kS~)4o0gd zKM!aii>s-Ndno9cZ;W`5JtV>!ovfUJ&d9sPtE}n-rK36=OX;ef(fh$v%bRic-GCvj zQuDW)5aWKfv&vYFR9U}FjX=V0CkS9HfiV?fg6~u3JXyuC;(xzZxe!icwfKJR`QcyD zJ;wb3f9?7}NtAB0NlWcYl@yiS5?IxR?NyCOENOLFR@7Mgf zZi0D|#2LRM8J0^@siv^k(qBTiVPwzu$QhZ7YCpnksX${(&MXERzUEl!D_q*JY2Y{G zr^(W%aT#pZ&)yBRv|Wpp_jL%W6chr!e^cYOoQvTvu*r5YHH?x21+rPoqa}j=Bj%Q1 z9TJbd*66#f39;JkTtUY#cQK1(7D*exdG{Z1)r4FPYA&flaEOTS0fWr)H`IGG@gzwv zEzWS76ZVm3!*Cm0gI!Tj^O+5L11x;|nz-L2$5goH5 zTyXL2)80eFrYW%Gfat7yE-*yu6O!X?L~pytV&L>q01Q{U20bG5R$cp2;)(TQtiTZj zTfmi^*ybsTWv-oBk!_-?gKPuO%m(KusrD4GAFh%5fk$RK=pRB5C3MXAChV}aDD^eQ zUzJ5=K)tpDG%6^&LK{;4Jy!-nP(UT#2hQe6G&PD$(sI_ER+d%>eX=zJ41b+QL)mqS zRx#qUDJ&w@CnY1Y9_Qx@TkGcQ_g<*8pS`1fHi|*dvYc%HH-Sr77nRRPo;1U1KkoRC z@&1Ga1t-y_vrX}@crNVN#b+H*Cf%Z0@Z4%*TdUFluS*%fMz{K4wK~y{4@>6lzYM;v zojop`CseEWXoLslsNe`{{K0{FyQDm;s?ElsR(OvI6%H0m(ztcKG1!bsFapR4naf6u z7ud>sik+umZc%$U@Nnc-SMhSNAeg$BbN zQb3&a?&xy`C7z5jX&Ir`+klXeiC;{kcRL6ojg5SZIdI1m3LOri$Lw{`*KM*_^>^Ty zc~G1RVEcd`(LP`6buJIsDn*~Ad5P*>CI_H>7ZM_P2$r#TlEmq6rf$*nx*Zo*@x&Ow z=A^gw#3*%FafvI<#_+uZP$Q{l)A0bhNRD&k2ieU9jxm&hOu;b1q)>m-Y)%FD>VDvV zr~)~zlmEg0en3}T)Ty{|IJtcMU}QoB+^9s*a|e0hC_t=FS3IHL(3#(5vt-}cD27_c znbOYwz@;Y4cen5%m&2^^kL0G^2)@pv?y6c89Y8R=DJ^3^{n2#eWAgmpPFR%ZX&nT_ zqHUO~@nV1Kc!^TWanYvZ^}C5Wkx0_ ze2Cc)4*CtsEAs_b9EWLiV8U`WrFLQoCGRPlXXX(qr$DxPpbjF1czr&P05SSQS&2*m zfHSv3e$AeW_o1~a^aS0pl9@uVQKsUwdpO3#tvxr>mQ?j`N-2I|kGjq<=_IWOD>wN= zzhMAKy~Tx5w-!1{hbd&vInMRcj2t=_q(T=02d8wsP306Ma<0&$L@y?zmAC_rt{woY zc-sdIIHJDB&7e&K&9-PZiijar!Ucl4Tc*@cvfhCn=5~Y_!@NG zj}>-TqErdyK7g8C*ipGwcVZUvt=~z!-sLN48ueyS{)(3#RPHtfO-or0Qe4UbeL8$G zGEl*pn&8MZ2G8Ci>zO~q(!%TuDBl3PorPHCP;eo-3Q|_`j4F*VDJFW0H8_gDpa@C| zn)c655!Z^t)?b5L;ArGmcsA0_yOyg ziv%hW43iQ7-;x61k+rR1kliS6BbJE3AW>8X*Nq*-xCAu+&VYs3@wwHB`9XMe#-nadUZidEXnXoGK-njc;S4&4{4ZhQ<$llq0G@q1;}Pz6A7ca#Na zT$Qo>+7m_h)0dd!D27YbXb*+NMg=L42(#S?!3e^e>N@OPhm#^_(g<(#`s*3w?JR=W zk32WUepPMrXPT)fdKU2GC(cV?tw*9h= zd(JNCZhm`)0=4YP%v_JNuBX;XeGvnqDYXh(pf;~lZd!E^m@H+rA~=Pj?1_BSXkcXa zu&>f=BTv5`wY)@JF5@{~UnPQfCm82uHY5E7%i7X?{R0Qs!RmhFTBVIW$ob;YZl_=Q7KL2{+0 z2q`+MjM&Zu-tOxenYOG8gk!$;CK#{FJMqP3S{h^%7VNW#;cY8gKM@R zxu3Sd9@Z;wM`s%*gOY0hqe!4>v<#o%>-c9ErxW-*G2g`NV`ssu^4phQP2NT|rVM}7 zKD0F#BI1N9<7YA4H(nrCR$=Sg?n)VpyyX*(P2#sds^w;RzTRKXCwRWn+5yEI5KPdd z6N{P{FcdG<75C2p6Rs;DkkhMfL5Cg092vJ-T%&G z-72#>2@rE^HrykJl~XBC{#J6>;R2zf)ma`uQcLW|h8QnIoG`d`+MD__v~3~mL=v8j zm_P1g{c%oUa8`Zot#DzfmZb`z5-y=Dy%Kop{`G1f+4O#)-ytSFB;hc>oUw?2n2QGQ z0*2>pMog+@^e$jPu6BjOE;*fw>xa9v{gceSfyk((d$i>P~mTUxZxrX4KE0u03Ld7RDO6inHHj)_Z)+US5 z7OJ7Pr&=eK%o{G1KsIaIUo8Gpi6wyiBn*-2VZw@W_*{s3khuCI}r`~xRH z3n$;yL&)eYFe<|WzXwg4=>C2hg#4Jm4~u9Gq)3Kp6TI|=^r(qYtKjRzwywfE}qPIyby9{B{X4t*1vT;9LtF%oV* z;w_$&bdxlkk%xn2qSt-D;m);TC|`5i9+P&{dNEc_7^Lk;=G1xhl|@=J7~#>h;F~7^ z8Gj>!Hs5hIZL^m8lkZ=5^|z&u{JYevB0FuM2T+-~T*O+Ez;Ofg-H9Jkl~Pw88-2&J z=B!@Ggml$d?q-f#@V+P6PmzEeLIyJtuqxt10 zp$a@kopr}!;zyK@OMW(5V*_~U!L$$M6L>k@((40HnvH=ln)c%=0rT7rHApcA%m}mv zvwIQz=swVhK#rgEkM95a(R~5}$VRN?G=wHZPBW&QCg2j@eb?vT#}<9T!||UD$?)j`!A;LvnpW`xdI!h`pCR(OhWZ zJi_6{WMk08^uEmW_T`Dk>0^lDmtwLiLD+8Dpiz+!0nVVrJbHK_`mBHRP4E7!r3afU z^|00GiGER$au8H4{uTc-@A18E;y6|acD@rk>);T4okci2(Mn%?!lK9#9nb;tJ51r` z=qJgmt{EIq@B#*z>qz*Ix0i>6P&wDfvsWBPxwflkZ&IY&tG>W9G)zn07?VW#gWVox|f*$U~5-0Q% zCgRh&`@v{IYRT!o;p z@CcB#xvWAMb|V+621itg8n;s1jO{U`@>osA4w5(fNHwIw7-p?Q;p%@B7lRo>KGy4H zu6##3b6!TBGfTx4nK@dGf<*KuqHT}@$s)?f1Z3o+5+2aCEsxN-OWLvl;50v|!5?sE z81?^1r8F@m#6Y~n;Ze}Qt6sO*9?)Z0-20&Uec^muJ!eqwK!v<0AwK*7xDvtmpKdr0 z5darcG%9ogK)B0HoF6R0No^gN5z&wT(??$qYOz-z7txj1!tZAiV9PuXVpPh+{66@q z8Z%h+f=5Bz4LpPH)+zO`ZonTD%5EAI52IG)PwE2Z+ZGE0;^*?br>T7qZz|1EJUBL7zy6tqa)1yQOL7`W^27*CGP`!ZY(D{#n|HH%rdqS5hIp4_0aBhnnXi57Hjj&>cqGd6XO;*E==edKCS*N(po1kf=^D$so2}}- z-mSGT8SRS~uPcLFYD8HNj85o!voE2>$e>$-9Z9~X8~w)1uNhuukP|Nf^HEYlL>jN= z^jwWTZ}F7beKbN3npE+inCsHm)jt=*&g!8zxU5GAe8Q^*})*dUH*+eE!c@*MPm0p?Ucg_N_rb7f9lMrGw9yKk1r@Siqd zZP5NDVx^S70b?q6;E6s9WYMHOUP4reY{OC{6RAJzuk{HZFtV+QujhBFa$!h_iX4`- zRf5UoZ$fulaK4GSTg)rkm1L$16d0`83Amabbw8{}VVCC#AB-k7n zlsTGbAYPcPo}Ls<yDfK*J*8K|{=b1lKey-q#yP+^ z7>|kD<2^x@zHZ?D+9in++J-h@OrM1F%mwVWAL7meG=>i|l+{1)mlo{<{il#t5>%-@czlIk1zQu$6qW(#ILl zXW5-X%<3Zn=l<=#`H*AJLjZuN^F0_Q*=gnZn6e99JY|eV#e}c|9qJj4XBk>N9iy;wOp@(u)Z~7Cxg7P|{Sk?XH z(uoHDX~NG3#3rY89ssoqAS;t7=`@2tkyI3ff;m`JakPPIgj59jk{}UiAc%I~fFfkU9JPz!E)X=O1^g==l%YD>(4 zA?il5lH>WzeMZd}GH}li-E6Wd3mdB?y0BA6s6q9b?Tjt!0=r|$OBD4Kg}jex_QTT9 z#1cLfhpp_D0pkbj?Q|O5#7lmH$_z!x*cd5yd(7-!*jNiE%o1wj^vj)Q;Rs~=$*kde zti7@MY4-wt7|1{O<^L8K{tFKPh*Sjtt=clg7W(z<(Jai*89%Ud zeTe`2{`m&4)rowl}qbu}+XS01V<*WB2_Z#FaegHrXQFFh5VGOD<4?cfM#lUjB z9smfme5kvLony8ci+pvpzLp5d` zASG;3wob~j5g3sn4e4*39wLoXZslvoTjds9Xy)m#aw|Ll^7SW+hY`rg_@88JYMlO0 zvUC4`7B7{3+71aI-5Lc+ge3oo0w^^e_&U&EmzX|fHeO(mYJg#0rYlv=T<*#9iW=1lBOqS~ma9o|Ax&oX3HJj*Y26Q^4LI@fOx=DOK?nIS5Z@z{@ahLS{VEOUhzoQ$3mFL#;8b=<^7wvE`BeMFcA%90MxK?SwJD8$O&;$i9k zE5UIWN*UOTOS`2w0V$Uz-}*9Y2d$~$uZPAAQ)L2T?HCpGOa^|5W8XocwN3ZZgp=Ct zL9m?uc=Z1Wdkdhrnyqbg5AN>n?!n#N-Ggf&xCaK;;10npSdb9h2~L7L1c%@bLGR@K z&iT&y|GKws)zs9M**(2h_wMzqr`PI6ytl!mmVk1=Bf=R8tmfNat-Y5zlb_R{4P?)X zE`v)Be@qu@Q^3yAR%3|Sua={0R8WeRxE}r`;lK2wv?-0E@TaMHeg*Nn-e6tLmoF$D zDOq3q_v=~ne^Y(ZZ;y@z-r4CEm`s~xJSWY{$xS%tFL1Q(P4=|wq!*|vkFJHYuUobC zCGgw^)Y+Je?0m1h*;wOqUkMtYtzY22n#tW@MdqW-ug>lGpAPu}XboIZ2ymG^8)_l| zNETYt!LSJWBsz>AS?T*-1jPgLtVYr36pdanK=KD{{FDCNuhp<}J(ifS<00Q_T1HIB zb};=$DzINk9!Fph%35$kud|(nZ|TFGNIResRN!D?Mw@m(xQb(g_>1H3gRd>oh4yam zFRL3Hdo6MsaNMZ`EUXnpJTiTxVd`u0xu^5W)85T_ZHTD}yO~C2$X}1Gp~=**m1p=q zU(<#}Z;;lZ?u?%^e$Xd7DZ;b4X^WVKtoh}56M=|^iOG>{xAW!5Po%SLznndnw`A?k zH(RHy1SL>=2=9n3Fl&vWY%yVjxD#}!p=QFDo_usQ^;CY^!gykxTAsb;Xrazj-3Z7gz{ zLIR?gphJHRr<`1>Hk8PzSu1`EeaCOf^~KEpk*E~YHCpeXxHY$k?B#TQu>nbLbhYj} zQ6NAdDFS!hwcb(n%qUhiC_Ydr-t25130g6=sChiSe-F~x0mbNpUEBaMySh= zeVY|m&^)RTfxcFl#AS2W0m@5;3g@L!Ko7quHcSE^!KuMlA!k0?3BsszO5_#B{q?Lf zAg(nuKz}i-{Vw(#fWJ~Rqi$#PU|7b?>u1#8;wN%6cK`r%(>A^wb^Ed}L>T4A+~<~7 zPxJP>a{k@d0WmxqU&(fEU_HfaDiaWL0+Oa?5Yn;D(1}OM7J7ucz&kKdqbIIAC&Hj18&deQ1$=`NQs&RXJyc4 z+nvM8Wao?bn+l=0rH&x^^Ook7d6VXzdnm{>&xYPnQCmDXnRdba!SD1qN5|fLJnVeZH3vj`>^Y21F`;+s}vHWyrEX=SA1p z6847+tBXrKOIt{tMLvFAJO3z$E_;#TBg90t<+~spR{ru?eTJIh{aL``@Kc8VB3?3; z)4S`;I+thXvkhf$>*UrGau3vG*~rKHafVH|i_zKSR;OKAJN9W4N-#6XZ?>UeVfTuU z$d?MxyOPV%CQR}TclQsFCzUn0O8+|8$HYa{q7TgkK?xS1ywCsk;aPgdAT0y^kpO`G zq5l&eF9rZ~aC^cc`U+q1b~ekG?{-|N#}IzUx<&GMef=$2pjIKZXFMvPVd6#zJsPDA$l zbWJl<)ncTYBUTIyoMe~e@H{`{mH&msppyXr^&Ft(kfH1WurNS-i0YivHXr|xzICN# zHKb3u?@8Sjw*(z`5lR?XmHa4q3%84eKb$D=)(|vbA}BL%XY6AxBKjs( z&3Kxdsu`7TPGY zh_pEXIFXoKX^K?Tw=QjsgZZ%lx{u3L=~3W6B`g+f?ixgqG9PHu2~;lK5}C+w;>UlI zey>+UVo9XmVD^lv|E?V#PFm;tcPq@{CW9LI`n*Q-?Fh+X(YU&wCM zuOF#IwiS36RW^)9G|TLGAi*Z;_I5R&3rINu0Jwu_=iR@N>i?j!f4+xHio933#yfxc zSj$5T^ibX-%(T(g8rF{`Y$^8@9Z}H}q=p6*USF^o6l)$785c>w?Hejo25IfhEt$8E zJ?@MDOAmkh7{Ybo#F>W~oNY)C3^%obG6sN3GpX>6x?sb8OI{qnzh0sm`ubqnonLC^ z5)Z(Qgi`!{7|O|kS>aIQ(EV%1mlLl($#wZ_EeV{ZXsxLwlVhSMTUoe=NyV+7S(Gzv z^0Y?pPm7PaD||CMzTezHLesiXGL;kyGX{-oF586vP^u{&QV73jCiFG~ytQyku&tJgR67M++K-NR@3Oo~y}R5TEbt z-&YuvbX5##!mhe zW9L8aiUJLM)iva)GZj3&5faLH)muWtRpD_74(;P!H3f~L!td>I7h6d~&fm>8*E6apYbaWo=qGM1X+ z05FX%a9~*7D1aBd0*1@yKk!0iqkyY;KlE=&bDJ8F1ku!I#4E}}F#guL%GIem_O<{Z zawp&ymuqIgT$wk2hdV+Exd+u31dzO(v_2P~s!__>kJ_94)dLK@u&@j-5iN4#Pstv5 zNmvc)a5DGMh=8~E%ey<_jrL=04M(ZG0;dkVit&pzoU zGC*6{8n_qabX&rcm!Wim#IMCPKxQN|#u80lh~aTiEZ z)z>x1tZE{wFqwTWS$p~%hcy>o+1lV)XsOR_UM4@bt+AKIo|XRXr_=-7{5R;oG2j#Z z`)fjCA4zFg9p4OX`+7?{SU;=FF)%lO?UtL%++^bN-yr@z!gXCvZZIEifpMaD&2CTL z#u?GQ-Aei>Y5HG5}d!Fjl9>~y&idrd@%Fj^fDd9|Y%@!mS{Ts4XA1E-kc3#wWsT zMc+Z$$bdiNpnXuCIEVV^SAmn+`tWy&`r$HIaUQ>Ho5aj+p%DBEM0}4@zn{=o~0cn2FFA zTabKQxO2uiuk`ywZEn%I+VK;pxrcUOUYaYj$*%{)<9=pLD2S$X2XgYq7R{!+8S5Oq z@UGtmotpYH*r1C${rDiv2>ZSNI$Zo)gLAn8Da}y>6;g;^F(v9}e!NBlWYg)N)U5Q* zB`0LNoK+4XL{`LSKJp&=DbiWw4TV!v9pOpHN?qa2PkU0hjF&MquN3N#cX{Zg47GMRu z3lV2%?(2a6#))U;h-gi|<=)<S@>+G`Vs0_AF2gcoRmho^wznI|CFx%7{#L5wo(j=e6<2QAZE<#Ojpn1+tzJqO z1v8ka@79B`?EHfzjjk+8Nw^zkAY)W|;knbxA5b%tU_A#K#B~7;SkcYyf_C9n45f1qH+Tndcuvpbi%0|NM7U1x0s(0iYK#wgW)spoHARCa~lwF;vc( zB}s=$5q?Ju?&86x%bn2u+-kBROaUm~sqlfKntu3#0Kh}%Wj6Yg=#zrs!t05!xp*3)9a^Dh)$af<<>o2;_>4}l=56`-cF)Q3VS3PRrbUXRieAr zd<%s@9|+T~h-(os@bqSFwoV=Kp#aW{E*?Pfh-cx)Z=ivi1@9$w5M_Zx99Fh%zUeKO z;L$d0VDvzHxfY};1CV6ZSf@9x>C$|-QtBW1ss%UpcSw)Q59lJRg8N{ynmj-A>h?iV zWry6UBi98~mD!e_vU7Y1Q3PNuhV)3V>MZqy&gppnOp)#^Qno%$o;r!NCfP@<^E96* zamaRV8%eT!mT^x*deG6~)ft&BicCfq7BaMZaR-@kv&9keR{@f2+Ht==Z}Yhi$7Rd3 zqJji&eSKW+VO9WBB;+bG^er58P}%s+OAqPWFCHuH)q8lJwE4f)rzY1Qods$+opI7| zGssvHoq2p5$Az&s;iy&ZY#LE1g;x~A!o;X))Yls~mns`#4Fokclt^7k?~~Y~-4+8; z1~z~A+XRKPP~~FI*~w$$K+kfcm|s&kd_IYlC2hQ*CDaiu z&o8Qpru#F}QGVfZa5Yn*tPn6Z6zmV!(Vtu0NA2}<&3`9xz=|nq7l?FdjQk25;P~8; zFVq$na8?SrAynRdi_l?p40*XY;dM zc^jjFbB8DdL!2Da6Kf>$`l|ni8+HQ#EI$zN4zLEJryOWPec4_;@*&JWf^%KOih0(x z#l1cE{j=2i>6UC3i<;?v9UwMe0}7xmMRPwt<~4YC4Xy;*UbV3WW8 znt*alo(Yb#JOlva#h)a)zGF}AGPSaVlpK-(6M7e^jdEFIVbwIgT16;R`n#dgZY|1r z|B$!<$B;HmFrXkwK;n)+KSn2JQXbnx^EFHHi)JBz2g2UG-bVsO)}iKHm^^rBqX2P1 zB-A%4h^pSj-G9oH6bO8Mv-*48Fv*6K!GKUaLpsI!kUs-9b<*sE6S>y5HfY*)k-@z0 zd1u`)kj(Jn-Xbe^UZx(_!mwnb;5rKPcX5tihr_h3grOXC-)pK%Mw`&L7q-FmIT2f8 zJ<&|f^awn}Gk25`eAFsT3f~Cr+f_Y$%};L%SFN)q0(u{D`aT*x`C(WOxH0rZDreZm z$fuKsH~PrL+^CFxQdQI;=WRwCn*EHkw~lsRCGeBwKrBX0xg9eq9kN`EOPOg+=q56K6e?7TmZPcYljywSM-PzKlo;)!5@!RX~!P?SI^>64_o zl>TiG>n9D%>`Y+!uaN*aiVzAlZK7nmU?zVbLhMCz3S~bGvfP`|tK0;t@y?g=f*UGH zR<3#<%#y*2ctkwz+8}Y{3GA)OGsR_Lw?X2)KtTMZOZr32`Ke0>S@KT)cK@umB) z#m=}TCX6+Z<}svRFQ9Q~D+|8S#MCA=B207YPG>~6*~Wgm#P(iBG|EBEt{c0YtC>}V zT4aF^GKPk*KENtO_-R{!D$x8-c@{WXC_ukF|G9~-{z0Pq z_xSxzQIuEz-z$vPnIuDrQ4|XrorQ=a2m=IkV5lz~@BJ)I6$ej7j&OLQu5!{<*qleK zJ_ABVH(Dh05CW-sicYhY?U|`J;O-j3hxyV zjmUz_7727L3^|u>8Uu9rY4E#+>332XGx?(XA4Vu#8lYt;Xg-z{p9-R7zp-p9qmHy@ z9LDPDB{(V{P6Z(3EC>-I-@hEle>`MuGkoI`(Eun8c&kdAhy5(54{T89u(+`b2|7R^ zAEe;{OmShTwo@73FdF$dwb&t~iZ@Rf04xG>u#U9?3LoWiK`7yv2?sYPG1~nvLn8d8 zZ%bGVD?B^V4yUDPk3|%&iY4wuT>f7POHC2>_dha@=wxUgC?Lwe43?GwT^%6T3u!F`iR`hmfBTXD1_|u1pc)o>5!_+~$yeT&soA&>M{XU&ApsHo zRm{1h9wXK~8#6A*LJ-YVw{OZ0gQ33m9)0p(&7rlX> zh%r|*@q<>Q7{lt0T}ft2b6YQqKQ{t*1By|9!flh?Bq0O?BYxkN}GSJzQ zJhif-%JjS5;uCA}8QGT$!xJ);TzgL{Ut49)k>+%yFN@h%2@`?EYH?(S^~w3%HQb#G z{&iPa?m3hi^;=mw8=VapkAvi)INxZTn9J(Fez)1d%#%rz<}CZ9M&*b0M+6%sA{R%c z6w5@sx_B8)mz#Tukx?~#2L(F~4&=X8>yYQXR}5@3Cgj4JaCn{~#QCmK+Zv*x1$`yM z4l~|TUOs8mIAZRfNlbp>eP|b}&uqSKr`;K|s82pFUpzZK?Z<^?`-1DiJ7#heg}qi%?XlpOj@!H z2RmQZ!;^!s0%V4axq3x(sOGn1}*>8plpRg5an@_Mqjn8_AGHRj%&(L`GJIJd*%B#j@F;V zM!*RpjU0g{2Q-mmQWs8_X@VKk2^RK>qRJ_bBT=6Rjv6}=NLa{sA)dlS`cEAh^AdF# zs#?fc2D+8Vn^FE3Oo0Zd!8`f@pti3w3CsF5w1W!$XvW!7OL~2lPHPP8X+1|$UoWn%EX}rp>yRu zql|Ihhl+wi*HNe?rtt6BjfDq`DNIzgxQXojF|{QT#Rx!OoY#zspkVAcR&}TgK#XZ* zo1iom8XSa{J$snk(G|FN+VA(LTi8e<3xK>2aacYJee>&Uu^g$Rhzaiw)>5rrUpuVGZC(>MNxsHGm`wH$H#O} zAkjylJcMa3fVCNd_LU~|x^p9cWyA2n*aY$0OJmlza$E&eBiH*AHV%X+>Sbu)siyCK zlaJ;Wb&PFwxb02#b+g>7<#hv+G3j(Wmx4ra9gPyq60K;NXEdBx>4&SL@(IP;r08I_ zQX9%b2FoxXTaB*ZV$Gp9q+R-&7}pX}u6vJCq2^_AyC4+${PxGsz;f%+XCpFEIu^K9HAkaziP?~{JVPq{%UR@Z z>M4^tdD2ptp-z0Q95o4k8E`kMCQnE#)~k8C3Zk@T3a%N{TS&{Jg7Q}WJrP46%J+veBq+7i8(lQ`6TgYkcT`{Tj@2hQ+2FvUO3@%}n*t_rc| zI6R332l{6}`dl_#Pt+fkD;@N*=$=sWR@_CVE?*M|4R>w3NVFsXp%sDwP9X|;_utew z{G2czIa{VMG`x3O>5Ci+m?ab_`POi9`dVx4HU*>>QT$aJKuuA^Ery(QcTjFZe(KZ% z8UANGpq(Vydc_T5gGph#zETB#4dATqBar#I>%9JNSqn;tWzlBQB(oDL1{I}@obx*EgQ$MCbo&XYj?ie6B71qz zNgfQXJpkwbCtwp#i}hLD4Q+qmEdvR!z)?WMb}z=We)_~nO1khM9Zv&SoEn&`2XR&ebI;Cb3AKC-f)6AxT3cGK_r)*R0Aa3eAgbYD&VzL=c2&_J-i_i}ZaOhlGWURkcR zE{*xK{o3m{sYs#0>0ZKBpzrXCKbf-yo_`a$Zz1&@V%Lh_5sr+I0aQJUfZ6&*fE@Aw z@v-C zXo)7|TtJt35!<+C>hyx@(0N3`j(?ewH&71SLaxJL-m8k<_hkc#LvdR=VORq$uBMoX z?-owbCLpz^dr}{7K0P2q_*50gKAy|YoxGf;q?4hu=U7`SyS4CXn9(}dv}vKwFr8O6 z`%FKBnQ8o*=PLH>I;&89*Za&ewPV+?%xVn#VxGX7GzZBHh>JS=nnOMQC7x1blV6wP zcaPKM{3s(W)hVjkO~}3;F=n#SB*t&;*1jXV2+ytLD{cad-w!7Ux^mAoEE(muQ1YtW zeaDd-CA0|yY1jft(k7{8n4d)Q?-hJ5UMUE8_Amk zmpfM!k)wpASEdlz!CqvGOr*~?TBsVyqQ5dCocjzE#D(@`&7oO-RKN@L`A)$8`1sz; zc6XSc<-_6AHdBfBjMZ*nDB6oeHeC36zNAZAv{8NwZW?M^w^#TF!&-Ys(IZiYR;+n| zw9OzZU?E^$`M$pxLc&WZ#uE4T1tz<$jKRC@2YVb2hn?R<8c5wotS20WECd3>ZH$#P zCrSJD2HlFy@|8QWi#kFmtO2G!ynG^Gqj!#Mv%{e}zeW4Sr^7BGgkYy=%1*{ay+t^} z)P#0BkbxjvC=ZFe9SB7mLkfw^K!x;k{hrw5;s9u*JBN};^cmOESS~phEPPEoYg}~4 z3NbU-yB4JF=~HE!VzN09F7#nyC?LG z!mDOMyaD>(y-&-~d1K0k4SokHyq$yfQsQYT*qBb)f@FSvGEikONpAX}__Xa*0;)Dt z#h)89ArUOjO;aEdle-kDcvy_lS2o<;$GmPeB=OpEwTE1p4%zV|^)2GzK zrdDo48B=a$>lmaF(WN!afVvkxbsTH^)Ej!&X~<@z5*v*1jvm$rs!p>wgzR4+%)0N# zf<0Nw05}`b#5k!f6O^vk)i3N9v26sxWc-FMm?68(cGX`i3D-Ab#_?rVZD6|?*xSlf zr~U5}{P&&P+rpyScw~iztSzrgH`oN?UwJ=HCmVm!yHgQ#1fM*>jsAHfH5qT&ap3jb z=vOviWU_1J!G7Xe%>p-eo!xJ847(QaiUVw;O+4Wrl+eOd8vX2|tlJVLI4zMy7s1js z`{RIK4)RbC&c(aRH{;)cUxbO5hrI1vFg!cwy`k&q-UpvdmJV&4(oICkvnq-6W)w-lzZ-6rp+gv5n5j$0^yAUq557T1YLvc9`-XKDH{7S6eL!sP_0O>^Us znT$;l6njasZRft>K!qRA1W7ro$_f#V+hpuztHY8eN1-&K*D}PNXs$hSydxE@I@O>a*6%g zOq71dZpG`K5>^fZS1ss`bC@gT@g^TqpZ? zJm#H_MQXkx>eT3m45pnW#28`>pUBLHt|4r4)D;^oAA~CQ9RoF@XVk)1HvM=z^vK#x zIJ8|)Jr{nq@=iknu|K*jT=|3#U2J9eqSNG|#Qvvq9i#jwY6Dt`4QTj~Wux&Z_-))0 zV;i3JO-G(UaLcJE+PeF@?~A*5`mwMIjDvqn8IlsU-9!owx+F+Qted-t@)yT(xwBQ@ z=8}#Cr0^Ygds4Mpa|V?nV_6xZ)Y^mD4aP8G(DFY7;5nzVDF1M< z{Q!?7$=7fe=xX$%+DvCdv#U^43!FZtwZenX?P+h*++B(p<_iUAsI$|(3(MMoCgfu= zm=(-1yE8@{5g_<<-S|9mUb^`EbHM%O>i3okxXBi&FF1R7glGZU(>Akw}vZJS_yD*y%|Gw8qqDDPPLzacKa+)!UiWHzEm z68Db0KPZ7Qd8HHTa{LTjw^4D_80h9|DX;M3aNq-~Kro+;bqA;c71&tjnOnsXHLblNy!~8{&Vt_%A@;W z5SqSC@l}|aga1AnmVr2Qc{V;pfUQEXNL+ygWq2X_K)o8=`SO7*_~R#aGEUqtwrj5P z`r4y>a;YK!78op(jp1jJ0!IwiyWgnj^%z#KDDdlnpMZ#V3=!>L=>1;|SAqpTrFTw- z+&s|-aM2_2W@Ms|%s$;xPGLWYd(5f731?$)7|~6^%!~U@{4bEd4?g#0s%A;h%};Cv{RN8CE(VxHOyT8l(UIxQu&euWg zJnQ%Q$T1l=+z;=}B(v)qY*?Zv9C2{kv>5zp;CQ8U}9` z_~1tzW77{xT~M=D7VFC6;fX;V@3Clj?=MGdOpgl8!VaQAG_9L46%#3Xh}s8hD=zc{ z+~@C=c9Fr*kVqpCJw!9r|EE`DK^1`HG8hL1MO^y{!2q5Vo$Gc-qM2veqtbt~)sF#t zmJ*^HSal=@t?`AWY>Zw(XU?+*?9ZZO`o@ER7`M*3R9H@7rbJ*675C2wm2(a@#f;x) zX87U^vGP;3?|;jB%SI`OS)Y&uKr?~S=oawSLSCvqxbFn9Q|R8iys+iVa;b-yGkM8; zjXx%P4mI`Bzl{iBnChzE`$PYr=rQ+cDJ5kEvy%?~>?SY+`q&52#b(PV5PrDnD3vq*Nvx1*;D zTIJa9#NK0C9A;(~^YK0R%>VMPVn~}Od0RA$LVhp+|h*mE5q6jMBm#Xc2~;01GLt^3qI_tIb;Tk?i2sC2RAlGHn0L+@~>s z=FY?<$vf(JbM#HMgr_Ez)mw5sJ+r1j9;`eix?cR+Kt!-d0CX#r3W)%AmW42@m`G-M z;_z>ul44K&<;ZkL?^fk!(aY#hG=4MkIBPLUS-(^QZk|aCiYwj*^CA_?5FbU)A=NiJuxwg@ZcEx;^`1Nnw$qeWu)I$6$!xgvZ04CNkiSpR%e+`Kt& zmW=FogCvqI%pt2dWPjw}56OC8h3AKVcnmmI#_VO(xg?=X6^$QpO8Ch?7IyHEg`8~Ylfy=kXp0(;^>0FZ-H<#qPxj}X zsccaylE$dUPA=&FFip#uK#%TXBh)ZzFh9XHF81-HDz88Q=$jXHx)>xMM}K6-rHfw6 zjZ%EDg^8ZUiwM(=N2n;Q>#_3IB4i2vX7&f8VR`6zxr`KSq+7 zeYx`RgQPCuORdE;nvwG2DJ4qYu~d)#-WI|%GRz{OD)v-ug?pYW-(d&&wT<-%>&J=r z8i&qXUibCk-)c_u?BWlu0UgkJhrz>?~OB~$au?*8rOB)1xNd0zSboS0h zI1a&|(%mKd;*B$bNsqiR$~n|)Fh@@I^#bXeJZCtMfCrmRg728Inh)pQTjtQk0p!A! z#DZ1I*W^>xLScVGtdHmm8Fb%Lg1_!8=ds+UJ7~4g(@``GA(>q`cejv#xo;0N*8XIX z5~LyZTuPY=`qBD6`ud#1y=};j!5<$VFk>RU3fssBr*|ACAfcIocR4~!(%-h2t-8!8Hwv9 z@^1cdL%aVD9?)7}0Yo0HQj935g;^?YT zH*FDGXN3QZ(#NANMM5&W?wjP)HSwhmFn+pFB0e|dLRTC~8XC{Z zM?_>(ebhWZXLjU)+dy0RqOR&9SoaO{b8XB=Hnp5|uk}@u?DsdSi1Yc0Hz;<|ym^ef z(wX?MrMhxx1P&2z&5~})Uy=jL{gwnt&@VB1JkJlF&wx6cb|>X?lz4p#Y6f;w9^aS_ybMNWl3>r(rG0qlT>Q5LwjK?;?t(#{SH zys;IB2ZmTQqQy+kQI(@QLt!d6TlJ^{9~M910f@Yj%6(jSWORLn;zB`^+zzRNMs zxV2v*4`)u7!zhhCk5e~P6(Xhh1&wlCJ@6>|1rGK(4Q@~1w-wL0Neqy zdHK+o{}qAa(wHJ${ONxBb658 z*TUZ#E`((5TmZo0?5&aQufN4Y%|Mp%LHwl&lBvLp=!+>Km3)0OJE6Z|(ept98T`*5 zr`$8@-SNh;Pym2TD}aq7JR7G(}1zs8duH2@! zXWZmez39)=l+NO{tI{?GH+208(4my$ZkKZu#%K$U|nmlK|BChrX5ui`>d+Ynq?P&~CRjt`n-m z&~h69R0ZOI-&O!jJ>I{bfV0G8TU@HpHQjQ5Ow~Zo?I`$Q$hN*Mq8mI?JbTcnkEN_? zw2_E3*RKLRh$&aPFV0U_1oG>NLo-7v3<;Zm{x9!Bo(h`vZ?Uj=E&`1JxE@>l@0qkX zLsQL2-v%fSY7*e+u9BwK)fnrHLNS|g?g5FMNke{w(|I^ZH#o&q8utd1Bixxu9xO@& zIL-DK1s~_R0Wc3bbrJ#V-%SM3?z*io0_2Y@MN%Z2+#qvuQf`yYDewqM%Rd1TaR3Sm zAeAnL_LxlP`Ncgfa>hX$;Ej%m97E$cjWD$vkbD~;q`8|@NpQC_(1F}|nN)?bZ_zjv z_dZs%TG>3F=p5LFc!N+{64@`Z|F7upZ#?yKO6^+$)CAHcu-reQE?^%ch8EpVA`_Ep zn#$V)aPaHj)iwzP_7FTP70#1{>G(g23xb~Bg7=e$po4OFKG3MZIZvWWZCWL^Cv@q+ zBiTn^@ZWcq*^OV=8_3@e-y(-OS2ttc53YPKb4W>TmwpqF3=0kl2Q16kVNe4PT`>;byFK7-KVyIN%LUQvj9ce5 z#=U+Xrdw%YU-zChI854AB6BYXPh3p!f!x1WdnddEcm^xMJep%|Q_E#)TC^rx3e>)o z$!QJcs}DNg;}g;5%UnBLVw-V|t_QOu!`PEs9=^Y%KBO`W!>1U1h%ntI0KLsvp^cfM z2Cd)tk_q70*lu8l+qk8{=hN_+_fRcOLFXE4)lS5O5~(qQlb@>UH>$if(n-;!Oqw|rp(A>peQqknJWX4HS3YsJb5c(F2#n)lDMWgo_SH-@`1w}c=57m z{(yB-ClUW)_Z-n-Nfzq!YNKVLC4}68O0l$e?FCG5!#cL(h-DE3z3IM|(&XH>i)6ZQ zOm8N0VPV4g#uSKBJ-8#tPo}^+wi7Bi$2_*$TDr`o#<9E-;i&95;E9G+Bj<(Mc}=HR z_6PK+j`(`(Zl4)=@5q7mDw9kj$L(J;mPG0;SFXwAO5YWKYC^w~p>7aWkRI{;ufKSy9x z6#dyc(J{A=GX~PVpj3>tz{JOMH91kr4v6?B1xN~bal<0D!@+jG-VgCZ__I|liRc(H zP2zwvf74gU;Dvt{lGrMMoS%v)`(YG%YQHcJ_1W452uDpN7=L+B(A!}caG!9Ut09hC z^2OzAFB(@3ZoxOBLF|PKb;vY#UugQcEa~I?f{0Ga*%GQ_a)yx*;rE9=O2-ALh=}Q6 zHWhwG#%o6PFffj?+c;-pi;Je)3-b@`49_1o{E+@IWxP>iKE?0lU0Yycl*jHtVdLY1PbFxXA&iaL$Dtd`Ou+0> zFen+M@+UzR_!FS{0PiW*pLuTWa)N!f{bpIbxtl5PVI?@%Tz)zKO_6RC7sJ|F2uo%- z-JZRkl&T_Ga%x4B>7@*mhUz#;J;l?~*t2vXvN%O*z@jm;a`3fvd}OdP2olZ<0)z5V ztN%kOLM-|ofIuN$b}oG@s=8O6%MxcP#gKO{1-B8xnXl!@;e-K`zpYAlwSm)``xTHE z2Ve%UZ7&;j=}AalOB|GbCRE#< zzi-i8ieVNkC^qB&Y0wyGG+vOR#B$(QZUb-7cV#g>U z5I47Ja(159Tn?9vWRiGv8=>s)zIt$HM#NE9EP8vq;6h#jwBtp|?*nVqSMP^$=s=4j zfkN`(7Yt4d3>J`W+Zr|6iEQDiH|a0Z3JAs)?0N#`n)!ZI5$ z=DbL$&b=8m>wyniidIT{qx5`?I1#uPZ05_U*P_G6#%!fO1>eYD_gf>LB1|_j2HnSr zpV!gKphzDK;Br6=NHL@h#{WZJLafEVKTvJ|dkCTgs3-u4KZGho@V^)TIpAO(e1c5Q zBXxikZD?1`KgQbgFj; zRql6Rh~|*r%N+f!k7wa=6-hDlg(8aqM0FUbD>2h?FU~B^R|u(QBPbsY<-ZBS|E(n| z#0dRUX&65bP>Jy06ZTVve_ex|^nr>$tng4n$895Q@yrr_J%_B^!_lP=KzTxzZPx@V z#0-+3OI=1#n-&Vv34}nN1DU`bIkQs0NpJx`2x0gOB){iHMnKEWqtUxf?ah;z&%p8S z{`mK-cJ;1;O)o3j@=D#*ow#;p!6PTzslfo=5cS5uSTlfs6H@ITkZQC1hw_o90C20t z0WUh3gmdJcf9hBTR*e_}(2B=N&jD-@B>xpN8tk%DeR z65~~8&f*Pl=+6bvT|@zH`ZvM`R+}Wn{z)}a^(Dwd+ZS&&a`a@Yq->mjd1lYk^gPExT zf?!z&D67an7-Ft^fHCi}K#54`2T+h*_C|n6*_I=Kd&_{%dp_@t68LR-< zdPz?(@FJ%wj~3{(zJSCeZ^x6BzKKij1OBt5pRx-IL+@Ng$d^w*d5o5+&0NG+A==-OvZ>Y3q&yV~k7_ z3fpj6c4P8FZ)s6FPJ0}wJ|*fiaTrYgD(xC({vH*s1;enG7Or-OUuS#yNckfXQ4WF_~7uYnrUC_2CQd(>B}a$L)LLvcxaPDx|$1U#Y}#>HjwQNLpuYD0xAiwwF-0jXsobGxBJA_Pf#DW*uZP4`l4!Hha!WmH?N4QB! ziAgq=2IaRQj(cVcl;a-zgmT>V`|gIe6%2J)&3+pc`Y=wcbv8;93&h^N1S+hULz8(u zKzNb#c?0yFx+*Jr_s#mc6pCuYBunBSNx??#%*hlyU3gE{;m-cNch0i~yHzRTJu^Js zLAD~!-$mMn$&ajAC@_}$Oh3KBj?uPL0${DsYhXxHgNm%hNH#c3QtuZnpZw49W#%>LL<6f!>w_qi0^&n}XSm%g>nw0&Tf(5vtfkeUK~?(C zB6B+K1Xx6p4;UD7W3}2RBTC||oww#|uc+qSKVIk9cqPA0Z(+xoJ>WEvnDL~`L1RX-I@KnogES6 z*ghsI|Ka4qq6k_5h)T*5!GA6h2|;GYy+d*{Q1vSPpj$Pc(4q;E95wKlq&aVqH>hqm zWO*Pq@EvmyA57F#Y_uQBUiZbJYlP>Yk8t5KjjjeIYwD#5e&oXF{IG0bKOAFm6km2<1#e4UOR9PXTx0DnC`wxc~s-FIkDPH6MU_%L@6~5n=}% zV6dv3gHc`e{7=+L^>9A!0m?XwXu1fbThkLveGa{iIVtLVC1d_0hd0oT*?B@hf z4ms?9_w)Y_6F}DA3&8JBPJ^&kng9Z?{?E*y=zanCy#(;(0bs-?;sBytteqL||CzGU z_7o|6qO<{YN_>|H9Nr_S2gSBLfCAVYA|QSeWWfC=dIfkc>u@*VYNEF`$&>&PKvL5K zxBk-{XdCznmj5Tp0|Ds%s6*KicpeF1=QeD*SRs&#_Tm&(Aexx}oJ6g{ykADk{TDC5 zzex@2&8Seoyp9&Q!YaAI{^50mlmw?V-H5vf0j2{0zyL>+aDRW0?~kAjXgVNPKV|*k z#<7*A-v4xAsHk=T>6)GIT<yWG@g_)vST&t(~H&!DdZYW6_%QwHX zpmnyFksO_8)D<`d-G4SoZjz=@TN}3%eXRie3}ew|cpD&KwjdDFNRg#3VB`cxXgjih7X z!lQT!3*QF|DGTQgzk)kvQ9QCE&Kn<(^JM+cvrT0(MjhY;@Yc^KHaix0)snj!F`70V z_VTjf)G6@JF(1Mbid*`U*a=sPTyWICzoFWO71DoS;^!qRQ>-1aq-O}|h_sb<^@KH52Z6mwMP|Us za+qVBwyH7AoF2{Fg?V~ylS35N)%1Mn6{J$`9E*vCfAEhyYgs4;={Wn;0B*>B>-Rwx zg_%w}$ijhqK7VRUSA4mprtxC!%psYPz3se*mT(+XW5K1A5>!{GooGidFMrE0IhxK^ zQlDl2$W06CH}!5k{G2=BOH@kGegOHdU8c$G-;e?_$edrv%o+^CKSI1)G;8i4=q}c{ zv1;DWYuH}$Xum}hu^MGwplWOpREyId%|Xftz7#N20=D+O+B~!Icj`;I<*#$6eU0T; z<6sN0Ggd^8nWXs&po9fgr_-)B5gJH6MJo_Xx-?C-XwLUqCj(EirU`QF0=@AK!oXNN^92pdUs;%af|isOc$<*T#8}wuBGx(gT3~u=A|gY(4@SYh zBkH&_0~_P(M;NnI*_HA&lAK+On{L(l!8ou$ARdrlfav^57%BH1K@2nvx{2L^84ZNL zg)W_BAY4M1i>cf*r0q?`jkPA}uOyO5>t4X2O7aB>TgbN8W-lb$s6NqDj#jJ(<7HD< ztf=iy`;X#BTyTmir{7SvppJrehY=#N1tor0Js2A9MySCL;&uhd;!v(#43)pCMUitd zMHMGH=bFw@`*;wz?Ygs!(*PE?OS$MU1gVYo-PdfXxmE5mDS(i1ei2HKBxDYfVoleH z0Jm65t|!lC4_*-`8Pti=gHI8xa=mOt(ObX{XFY(qfN$4{#dlGt5DTq&T`Gibi`1~{ z3q zGHJl~jT^C7?=u{!=;a0|V*{L6VstpUn2PPDO@ij4&NdN$K42g)F>awX)aIjZJRwX&$ zuNBlK!b1?}lK-YLa7a1&3%4!$`07dp0>kE(ijBIs0-sajjbc((q*8;3M*Vw_4xP(0 zu2;Pl4xWI6kl=-c6ldr~JyIZJ3Pb|;DCwb+NAFrY zC&Z$Dlt^h8>5kt(li#L+TzeHsz5y2wXWF0fOAuv%jb4{-G7QiX3au`)Vm>XuofY>s zbwJ)GjGIOZ6^(dX?ZiO35Es%lf2HldI}$CI^b1KzsWhgsh|yUdFy_O#WS zpoTDnQqE4zfvG~a2+kM|_|%iMP>>TK&jkMsjuk`bD#B~40Ce^XQZMJ8@~9k7^I#k1 z^ugzdLqWKF(x$*GoP8Yys9%HOb&hs!2z$Kr`^6Qgfqvo}lR-I#)#64IQuxP@Uq*VE z$X3un<~s13oK@7#b%eV>JtYj|pIOa3X{c0s3<*7Gbv`JLwMR0pemk;&i2rg$(s z@FIjAafLzaWFz0_Fs<_H9<<%MFF~a0C;druy)Ak_65!ld+3!!Ed@O`x$YL3hy>QVZ z2nQmfM2sT_q;FX5h;lL8{0m>dqr>GtkvT*<+}ptyJ+ zQ^CUw(Z+dqyhvp1mzoyne^U}?3kvZop{jmBtQ}I)R4bh$ z+J)NpD5m*x&CQcaf94U9=1Qd(cB~sH2}Aw6{=61MqypGB3*?KKNlC~gxjdp#J56tz9N+vUrIci zx2cZU``IPd)8bROP!us2cXF*D1x+KuY}B$>m>LWs!baCHpASyHbI;J7XyJf9=%zXc zr2oK^tw$0vXze6|h33kce>{A;zRUn6{#`0a)tLEQgvO*krrcG*|E91wKl%^=8Ww)x zcN}pWgIp$b2&WPR{@d85`5r7{1#+N8ai#Bw#QT`%zJIqA{*H?;z4%6fHYYvNWQ8ra zA^wn@HeASKB1x|a71JH~X_?Q48SLh|L1u(8zGQz9slyV+%#dR%AxYF3<&%$_pY^EY z^X+ySJ$5ou@xoez9}v}8-!ek>FL6Oo0nIcvK?t3mn=s^NRDjd zG;Jy}v;#^|!O9vujyp`QU@?$-5_5am%|9^q3%D>-jp;?yGP&V*8MfWaUsIkbAL@M! z3#tyWFkFb;D?Rtf2uQ*qu10#2=-WQ)RLj)A%)wTejn2e8lC~gi#+0wBGxUA|>g$iY zd#C^{+Abr1tp(`brKCJ<4DpI}nHiKwKfN<@(s>TiP47Lo&**;JZnj|usri2?jaZxs z8$N9Y{H}HhgQs~T$g%nQ>tsYR_8^?08g4Lnv{X=2XS=WCNsLW+kHG^`wQYMXPu$TL zKOy9=I>noS@XD+D$lI0q`=m%k!(OQvdroOPo?eE$uN9ZMa{Kj}wI&OD;CnU0N7{+6eu)M#n7 zmzt_MmzzKHK}#{>QXZPaD$%zR{h3Rbw$P$OP1XP2!_wWSr&KEj6JHmJY~4=VcXie_ z1QO4QDfxCEyZk!OLF=?8_fm|YiPeq6DISA7jGQOcVo zlJaMC(6vVCO?%PywkY3kXWC~+dZrGJV_0(*bJh_%D!UT}0kdMT=jG+`fs$E~$UnFG=nV4RiCllGD zGDgAWf*$np2u197Q@s#I7JsFZmcZVxZ3@^~GvXk=a!FH}y-!2{Wp%r^3T8NtKo-?H zUuHcOThmL`Ea15ve@p#O45jvUDPdxyn0D(#A$ar-zeXBP&P9>mu86EAd0T4JmtHlZ zk>L1Usgj~edSaQIgLlYTW^EH99e7+hpLCotl?s_6xV1%j>D|cOTWdvNaF3Niee&3; zTJCfi+>*FPR8JI-9VQNs4kKVp@TEYekp5H+dS?K^Lo{XZ!{c&&Nt4auaZNsgVZlwD z`*U||SWvVh^192Ou{e?CfH~K{jC4)C2nbrq|7@VWTJG2JLWK~p8kzQEET=ic^j!z` zK#BwVZzA;GO4LA7PkI&gp->XlM|z=Zulv50J$k8rqbjD?D9`ST7idAKO#e=~`O{L~ z@~R+6UT-dkHP%J?O=daf)mf7IefjB$Z0Fvy%mJQ?-Gb_+$NWFEEIDUNp$AV2VukQL zKL!-Hzn5PM8ZkkGWEaSy%rOYyq)-RTAf!*Bgq@gk2jt|L2p@x8Jr#yRIQGu3Z=XX@U*(xgJ0l>GMbX~gE4JuUSsiq@zov-2>q5-JQOy7eInPSYN zDMs{t(mKVzjQMiQcQlWn1`wzu-IxEd)}#&?FC&ambR;>7%99rnt` zKx@@Qd{OuRZ|J)!reO!W30K#P<=7BK$kz z+ZKMjy%Q*>CEV&?GLz6Rj0CW!ds>w+pKdF_4AM2-VEFkae_qIhbyJ?o5$Cw?;Om%r zY7ZLnt7VX&3T2JoARVIxnwaKN_nB%CuO$B!If^lN*ozDD!4s4jTTA78%{X!^JZMEq zT&{;Junku^zjAJP!dGSQ3)B3!9PffevF1cmSTj~Z6K!)`^~3lVe#tc8y#aBK_4|xW zkr>x^VVdfdIWI{Aj1*6^*bANWwe(m?1-^+3D$C=`V2EPS^9@Wb7O@N=+jOP$^!tI% zRW@W~J3Qv>u~UghMp;il7SBEEBX4x4P#FcPaJd~fYX4&~+y98AIy5g9_?Ij{i#oFN z!v1e3%CbQxgP~r<($oF9{0)y>dbezeU!n!%z_^ z>4B)kksUZLzx-kJ6^;(@4E`Z)@f=NC2p3LJeb9eys9Z)qvTS&TzGQ~OLVW#TKIvs| z4LeNEh~WWFi4<#}$Uq~bC#P)hsGJ^mZ0`KQ(G0A@SH#y5hE(YNOtX=x6wU;VwOMdl zV*YDW$w7(9!8LRkw3_)%RkJ8Vu+qTj%$=cJy9-4=3JH)gNiqlC7x?&S)9Q&hERQPK zI#Qz4JHv@BESwn6_1jwN`i@j^=XQXu36Gecf8*#P*f%S(RJoJ_2+oJ1YRT89Ao;*0 zc+aRl9Zv51Hoe}@>}tm?hLTfu0NGp>-W&|{wVc@Hqm#k7%~gLmU9xGIX;AB$DeipX zJ@udaY~7kb%0bV(DgQkdrzp(rKb|7$sY-A6*16-UY`c{%Nuy)?by_M)5BD>ia%stp z`$(+Vq?@nNc8P^iSQB^|t)g=6W`eGoA*0bG;u<(lmU~1?2E(?9zSyCX63#Y0`12Ir z{Fu`Goes{rR&J8C?Rhme`P#Jl3xcB5b>LFfcb-Af3tvJz+F!K_=|v_)QW1t5rjC<` zXcrEPHlXTvRb|g)uFv4j%>SYif)1>%eLAtNfgz2wJ?;xIhmT|u(;n7$A8be;t;GUa z3M++R?~di`%St>EVjp_skiFVgM68Rov)0zP)rNG|xDR|pSr3!`nP_k#R3H^DN&}1t z?KB>)k)l~lCSK;BF*l-d3d2M4C5fAGK1kZ!{gm>(X7mp@?I@b?BQ2=yy6SfrQ&*zP zI}TG)kK4k$2XQS1^uOP6bquDr(|={zo3W2_W8N@F(k#DM>C9WfFHcbxi*OS39DtFF zDjx#A(|nT2J~T@8A8__CZRY>Yg75#(I2Y{!z+je5(3=L>R*4b?+Q`=0!>M@JcDiLx z0Zxz_L#9eI#Zcv;o)=uAS#HZAy2z=1`@yi3OZg#Tvg4(~fM}rYkZ9z;4pRpf(k4<> zLm{^Lpk&PBaq~J-h>WOi;hDlBV#L|Y!ZmwK=;3d}{Qe+$7Z->So;dkDket7M9sUTW z1$c{e6v|-RSk*RSB=3{;3i`L{aMNIL7ji#J})oUUx`Ukd_i8UDnBMi)=Q{HzI=)suTd}3M>2hhme%x0^hoVYv+ z4{6W_cF8fA>W$k5Cu0`3eOnCu^8aCQx`sODYu2-3+PlnYhBkI;KQN6aOzugHv--RC z>XQ9I$>ht+1*{bQHuHdc;rHOH$O?PCA;}c$rAMm~Se2(G_rv%tT}v}aOKj~nr{#~i z?8i1^6;cgTe9TA=i+4~(PE+26c-;2AW)+`>?-pC+n3*lpQU%2ft#=(Y&ME)#dYmD5 z#L1R%jm^u^+OuyDT=sw;OD2pdP?-mTgYaW`<|d~`pkG+M6k^%diAj@gK$iY%?`9~X zhd|CBs>BrSt?SUr`>bZvfY_DJF_w>@K16}X zpFXU*qsydhvu|$36RH>A)nQ1NZ9 zNcgVh&Gm}SiPZ+57{reOwtdFw?!62V@L8F%^Vj$~myT$mOQhLV6@k-(MgCvVypb}> zlp1@6e&SxZ`6$`D1!)Pa1aJ~Ry;QIWJyy@N&_7@-Qj@)bduvvl+$RqbN?xe+DlDvy zxz*85{xQUT97DQ{aRLV9?qiv&j%1j36wDIh$Hp zY!ElmddJz%sR2$1wV=3Wv@&d}eN(@WUH^o;-I~7G`cp3?m(JaMF38!HQ6jy8=J9#d zX1&W(J6&fW`w7x7N*wa1*9|KDV^$z%Cq?g_Wh?Dbvz?T}9LmY*#eh=N<7JPQWQ)b3 zm8=fYuA5vA6-Z28lMgj)|B^+$f#jZYP*8c8Hdex=DHFUITm5;AJnU)ck*Q>f%V+L8 zcG(5w46S$_&oocqGM+~jm&t4DBi`t~642mHGrYe~^nF(&UM*uN?7#;lFe-!d=~e2{ z$yMFVy?G>_H2s+i-yw8j-5~Kck z@1bI7$H1ggB;M*v@4=n5r(1Esf7Q@1(jUC6t%2d=^;7=r5&`&s5~(z_!m4TXg$=zS zpgkM<=?RD!IlkBr>_{=tcFCPR)9Z_wU_;f0uctSrS@ncAZ{&Oel-z49F6;6Ttkznk zR1#Wd1TbD$p5-MSlJ_&w*jpSy!oKmE*WA!3JM z>`6JMNv52EJFxWyQS@FOz)fhk{k{<`XSJ;2A=`iW#8q7=^ORw>Sa53;H= zeJYY+)pWFND5-RYbt@&p@*A9}qAL#G$%)yikNC=+o(0U|8E4yoz}C8$Vq_V&G=EWo zgTx&%MaIBG+W7H^q2YoMe?w|PzQ1I!8?J8)DqZ5BAn85nOQ(EyeDQ24kK9&!y$tOk#_{14*bj=7 zl5g(}X*oj6xo)Jl;U_WOf~H+a2VNq_CPK8!oMVDJw%H%mFWf(hdjPq%37s#Z9QdU1 zSj+o}vO1AVwph--Hl3VdYi$hXEg0VUvDS@8g>%j~dy!=dEG+Sn$}W&eV`9VFX5Szm zs;?ynnxC#|lq|r=km+J|{jJL0(rG1z(nhh3&-u*AOO`anQC?qYB(Eg>!9{+CaIGS3~p z)t|;@h<;(_blx3!hzQkqIY+{6!o*GSukkCAJ#T^OOKi(?K05cbu=MB_aI7M>Z^WF}H`~GBkS%tNrAJK5jZcz-llGGBLYGvkvRczHi$U zgK_Jpd*rzLfvaYmpV9D}bU|_68ah-@zPOK?Q=Me6Zh%fMt8=wDu{RA7Rs_t?J03=)kSMq!;d6-)hU)M zMAQ(T25;Da-LYSEy+&4lF2>ig&gm^;xJXp!J_l&ZgrUU_endjc3E^i+Vglx? zM?R^U{UNnk@|mP4a^V`?I?F7DXz#FJtWu9vTM>ixbs{p}W1JLUL}#@ER1tyZ3b6@4Pi83)$)?KJM@hwlD+|>?Pj5}hTnqnooITr#K&>ei zjW&?md6M-c+!|^SNJ`)J;%aZvpyoi8SVZHEk(tXi+Qp(?Nu-=^cYt1Vz-~oUi3yp!#t?*Fji5BV{Zxs_~dt^ex{ULDN|2~@9pW+9S8I0W}idcb3xWfNJ^`w5u`@fh2eL+O?{In z?tZg$+~eeMo007LEs4sB0%;aEPkd&fwh8iwN3xY&>4ntS(Dx8&%?Pxini0=-fACUb zc0Q6?czrOKD9((eq8jS$3=DG=PQGE_7_YtCF5A8(EPgjDRKjcj$0eZeW_;n-a4wKg ze$-1T;~DUfLyV+kp(o7Ec+>>IUN>Z5IiD5gf6dz6s8n=21+>#J*Ftt$1!dbM(5}<`vM)3(H4slG;=?(K*u#X zllE1j`>$-7l>Mb^yt&UKyjM#C<~k;4on+8c?54irNbQk7=mle>)kkQbJLDW0?*gz7 z!`$+-k#kN>ZpgRZVh|72-|AAoS;u%qK6P)V6iz-k+Tz;^N#5HAzw?kR!{qLo6h^K3 zp7e7l4hl+ilFf0YPZnlNnw(Oq$|8{sw&e6o*E;I&uxi-T;c`Bqb6K)R_*c!#`&9X! zAQdGB;~+A_5=CJx4J_XVhCN+LWAHi^MAo~Niord&DX$$JycQ+=-(g3H`cvwuK)A{C zXXj>zm+u7dN`23uM{AQA=uo>GtBMdzm)ZT9EHha)1qEQW>g`zlQ>!XRQCI7k6hNX2 zp^~7%K^L8Au(rdq*xu%&9Z7Z@*?L`t?uj7^I#3BS~o~Zx!_3*WTL4RcNCSWG1(hjzy^*N2L(GhPBczJyOz# zD$!{}MfG3}7ey@(`D*Gs81n#kVg+foy-&=qc2u*##w}5S>Y&*t@IRB+O806#?ZbXL zIFifDNxDtNS36&Bh0FfyVOYKlF_xivOE%HhxwK#q7ZrD#XVecpiZ|B0T#=f(qG+QD z(?&HOZHJWul>ZT`{gOzT#2Af2v)^DSRAYD9Ms5I<&ALA^&7cfe?A4E=g!LYgNrv@wy0N@iNTKdkbTt@EeWZU3u{k6A-4UAE*utxQUw~G`EkD`i{qf2 z&Ka7N1W!EknQuZcJI80y{B#A>aCqyA_0%2VB6G1=T25YOZ22cdoRrW6X+fL!P>o7ZR#Jz-t zUmJu$@-(jTy76q5ka{&4AulNC}^tZo#*b zFap6RQG z&Au5UyHh_mTDMfRjC`Ht9{7D+EZLa^>tCAYk&#A?4)Wwa)xbhM(^45;s2Wx~dUCLL zl`KU3Q!FcrH+y~eU0*iSDpLW8O!p=)_6?QsJRO16R<_%&@Ct&%sInSw+7^<|)+#2` zLzCA{PFH?Lr!837En)9wL8nsS3!xZGh16ff)I~>C1+CO_EckrkP$@b7zo{p-3Yzhb zy);(Fc)=4vP-1}}$mS3t?qz|T?}o1zEj<~OyxF!bvHPzb-oZ>!{N8>SnNuR+Dq47E zdbR85!m6@1`wOlz;L z4IhA45d9II?@Sqwf5!3R{+vs_+yxZ2;KN_frF5GKyIO5!KzFZ~B!s=7vP)vY4x()= z&+3FEG>BQvbIWICQ0X?s-=Z2L{92!hKxST3%zdeG;~7?F6$!X332@`vcll@cR|2tw zNa`+kVx4#ar`aQQYUF;~o+3C!ix=;BVx}!V$5_NV*J*)yNWsZV=AZY#8y-hnZMc;P z`Vk&-CD3fFEifFuP8tfuFYzXTbH_*LOUO^O$LfnL8C&8JadaU!1uH(VQ_=Qfn2t%v}?{TM^F_R_dr;&e} z&{XU_iw@Lo(FftSoGIsX&+MUt@=pM`@=kZ;O9U1Ib1eLp!I)975$P0*)qHZTTC5mb zg8(~xzYhH1y>=unsSRv#y4K|kutAGJU%l_FugB!^H~q`q7om1*EOVp{jBFsZ$ItW| zOg%c1s{r3VM*ntDKPppM62^M0&LWZWYmy!cxm)N2lc*Kjm#AHa{Vlh$*zo=&w~D$9 zO`N`OBqY=kSHbPyd>1CBTChWpT;XpFW@6WLi^FO6rmnZ_>E(rHe#(G+RtAVoG*{+2Rd2o4BV2@GB191Fx&p4oeY+iNfCC?&rsr4 zEJNDgGG9K@4g7O3C8-wQ0y++9afR873sS>Qf)Qv$Uh{uePb%P#EdEs0 z0Vo!Y;+?<95<){KWIN>2oOt!%W`kMP)S#oliWZC?s4T0!^C)WV@8FUW+8UFzZ$X1; zZW6NuvqkJx+WpJZB1<{zy!x1Ev6~RjXN+5UPO}YUpO{IR49W38yQ`H+nqZsrO?sHT zX~(rBc1n}(YRF-cCW$XxJAT=#;*<@AZ1ZobpfZ=RoYAjugFB;mP+LGE(vaZFVoUgk z_?4g7w(i-)#l3!2bBHQ@`j|>p)7tY(J=o1sH;@ML$Tg~-FN`Nhh^9eF*hV*la7~@> z1i)Sz5yN|+l{VbPxtI~dheGo`p1l=F)z(hE_}3?}lJGTlPLl@&^?FV5;QN%^&a))I z3z`uvcE5JbJJ4|HWWYd~HsH1;auE|M*OwjWt9FAd+HfFzbI<+RsxJmdM!-mr!5d6D zy>(lU#9c|>Y2Y;Gp)kGdzc%Sr2#F`n!7!)yDmjpu;H+4hzuM$bb{Eq*MlM}mdY2lC z2OkRHI_-|>WU*={DV_<09aBWsu3LoP4i)}@RMO>8h};>N zhdf)Q2(V&tk=kM{2G>J2?$Vj>5a6wK$v)J|NZm2S6d-_^A|~|JC><~tNR7sie`@UJlk9^O;_T9 znOS~7)+#OIFiT&tY8fDPnt49pJ?V7a|dNyL%*YI-E1vIN`IiQ zQ4Zl(I;{W8fgr+~8_c{SzVGAsi5_0f(v%(FtNe%|9~tcOh=^J*_@0;9-Y6Q<1Qoy7 zZ7=nPd@7N)Jkr4Y#PFN=k;*k*7ZL;)aja)1=XBCv)c1nJO{d0i?{oe9kuZ1AZDHwM zcrXqBMQbmfP(&E~8t+ek?fAP^TQQqB&?=A4cvGJ|L3)`ztf+V8P4Jel9u;a7lNZPnbf$bVVtSzKm^Gg^6PxC!n`lEOAD~V z6g0-5P5^L)rdO%en@_|8I9+wAP77bm~L?+r(GDdn{p+D9ApaUwhZ z0MO2UT8dWR{)d)-*$|@O2dqb7o1{b5A%EB^@7|YuX{x0&o=7nr`}W(|X!x9`kCI+@ za=Z6gxjtw`C*)^jlqlYXJDIemuT@DN&4@q_RS3~$#XaL z3kHf3g++tWR|;AE{Ub6bzr2>e^~LaPoe7{XToddRU6*tuLx5`@ggj97oIHV9+KbOL zDx7)jS4AQWJL%p!M9SS6&Pmrc#2Pmz?5etZaGZMZ>AVeXIp9 zz(Pt{;qNf5nG1p`T`cSdglq4^qa=5VKFkeo_O0-OH)+5^mdNMtySkNHq}@?B zyv^0?fl-M6;E&`VZjfv+16W!F60(!ZWHHijLIOl>n@yQOA5tU7X z0`2j}#a08RNsDXXxSKy*3LeB#wK#T{y9%h6_h3U*6)T`vcus}SCo2ixq7{cZ;p?Hh z8R(4$FH>!*j8DB28E$Ld4o1ZnoPF;=T}9o`4ToY_CrECYRs~-5ke%7*W$~|W{F%34 zuy#REo91^wRbcffKG*)n-t-9;7c>fN4{wNQu$JyIa=u5{B#WNa$~j=|kYf#&_?qZx z@0R&%OMh>&h1e$p9Ax!l@80Slwp#G6g++zm3BLjrs8>$-s42CK1jd5@*o-lRet7{! zvj__A+*hl~8`hL~*sSE8*kp83XV^fY8QP?cr9XWRcASAkyUcjv+fXX_mZ3At8BddKM%-E_?0@Dt#unGbJ!YiDgaWutwxXPq~ixD~g*$swcf!S@ZWfotu(-99VaFoo_+7AOEAqibhh_$^&!q zj>^}aLH3pF$}))%y`S_Q6Lx*9gpE?&JZXi32iDTS?I>oS>cM7;-=1W3DZwHCzFzSP-%T zs+sYmag{ zK85||q~Q3=v67);Ns-xpvK$A(7E^QY0lu54VDYmZZf&QE9BI5J4D&P<(R2Kj!e1 z5Ver|ktO`Nvy{X3a*&59&*b(JPc#NGEW|Cld`k5BwTAgj7#Tu{2c1w;m&Dm>LWxEN z^TJFvF)qQ9XzSAi4-wGqXAXdf$LTfG{cuL=Ysd*My%EKS0m6)0Jj*^Nj_{9kV#~?o zJVt14#>JK|qfe&*3XtCmg{9E^0OKgv=~!P1d@D7kFK+0ThU9nSO%JQr?GxJ9=3$a4 z6sZ{D$OUr88xRVCtL!W*4!zYQQ84lro1(eLBeJo-|1in_#$he-m3lIP>c7(xv4IGt zG>lg`+u;?JXNN^u<=+hHynl?sA2(}MWg_5L$}N1?O_^{17D?XkC7jdD-rp|rd*b$i z&&;1a_f;<&sxClR;9lm3p4$Bzhg$nf6wW-B;oH{=6mZrgI{GUbL70p&ycY zgc%j}Ef?-;3w|OA_-uC&pAS(dh@^x}1qE`9mxxF}+pVar^u!A7iyyFhg&45d>8lUV zl)vJoSA8fb8euR8`0jO_SE;;JQ&n^B`|-Kv_UGC*(D$HY{64E?Izz9Ghqh~3>#a`3 zsAmALTvK?F9`Cs1g~?8-4f7vniQY{*xOk!R|4#}vkfkR8dH?Q_{|hps;qkX)v{+}s z2rX2!UHvFvKD3~Evon}#CnKj!6~Ca{0Z06KYg=P6y$H_NFm-+>VaHRgL;{n7@$_Ay zQO?SD&1}3t`noQ2jnH#DM<_qKtpc0lS$@DW^fVR|shWI- zg_E|3IEb--xAy*dwmxr400+N(fCVR&7AkRFFinjF&g*`l#&ru z*tu^qO=&0N#UDFTXHdYj&r#JZ=;AxU(upY*LF#7oyRFk%8dj)pz^JUanT9|g93g~V zY&@UQxRgOCBW3{$$;x?JKFF-vYKR{!ANffMdRe^mVtAfoIOrlASA(*7K+hoU==p2; zqw?H6{H|;k8N|_Lon0J*i&#eYEz^}BA7nQtpFlqD$_-Aoa*kQMI#HmbWOge+`_@a} zSp@kG5r14U5AZZW=Z><$&fl)RZ1}6&Rbhlei1Ssz!oL(*t`k+4UN}q!B#bOCYyNzC z4RxQ0A_S|@A=iNH1PjgT*E@AqXAP;fQ1@p?aQw3pu1qIaF6{$Dze3r3 z`3v-Yy5H7*@%R_9PXav?8uRI5=pGV=-BlvwnbR+47m_@Iy(butf{`;ejZLR?q<4tF z8Jo}W?rvp52QJIFjSSU0B(cL}Q~=-z>%qI;;Is(9Wk^W9Bhm}j3qWf{2+S-H+I1!% zS@8Ew(3Tzu2@iox8HnVp=|RSX9$xRtw%3eMcC@lXrQg#{lIg!41a9)PWPVYQK2{Y`7h%@syNi3YIKI?8!qCx-_beWY9aDucC(v zm7kSzTxq5B-p*%i8zIw-o-to_l=sWcHU?QWYM`HXM1|xTxBG_U4>DbI?C>*xTbe#I zCaOU@&b!==XS9g-kQ2mA z^NRNN;ql3rFr%jnr0~_tQa5&m_=ypNeY_FNZ6aItNaku5y<6_e(zwtzt#1=)@G-pVLJK z{{G_m9B`|4>A5+*PEWuem({tJ+OJMQ^`}i;*uq#p$0M{ev(o4e5-L&wJKNVwFu{!J zqTbLT#+)^=6eA77qf+Xf8jfXu09=wS%uJ-QK5Z|6#Yi#_&uIuIo{ZmsgC zJev;Or+g#v$q8`G=ck+%C9saL0eJ43Ew$7r2d*bm{Y)<}wDLGynAHd@0T&tsS!o-u zndwto!`)F7b8y^#Yl~D)=+^IU74s(b?N*nW^(~Rt>?WZX+RMYhn>^(f=iA5jnezVK zd*wo5&r?ULwwUtXNGqv$%(ow9W$Psa;laNeOSElVfU%yUkki(G75wTo98IU=1fP_O*5dS>1tP0mVcsK(k zT)jQetW;^Ino-%x0dilrXF){m#>_KhLf<(4l@>C&w$RiK<^85;NSnZZP8((f` zV#*mrGQ})}CgQs-3_~5Z5O5`ay6#*lg%dH6F*AA z$l(9I96xI^vfkQzN17${+e>q7mI&4HqB6k`tvF?0iLd!{O9kUJ28~ zTKga7=c6^>1?gLzxr?usF#GS;;OPRip zSJHS9w2hb7NOYHH&x<}K0nQ&?S{4$P$pH`>DH(v$Bt_8^(Ly6PKrW0}LGAP;WGXgG@+1pxppe)i4LkVx=U zG~?f_AdmIV->K*ERh~FYkT;E&F(X zT>iI@XfXs&9BEPTmyhA3vtZDyrSfsa4`jYmIOy?meVtyE_nClZF*iI z`*tN@ccNU>SkzqC0o4@PAqgLQp@y&Dt|TQpEkVb^Ji2J^3ah}fLGj3p>2rw+sqIy~ z!By|pPT{pw|LzV9S`wyO9#$XRS*^k&vSjg__dHGALYMxb`RVLl8gUW5H{7C7;BA7) zNL{nl0}^?4O~SL*t`{*#cG)?sCJa#>6s_b4`bK<~gr;mvBxrtdwI9h`?Z?zGWe`Z# zc2aZjqwYiYsE<cS<~o!R5$^tM-jGt3r#XR!1VDm1i?a{;jyUjb;;8U_!!BB56JK zQG_h_F7Ik+!SJ0(5RAqZD1SI=>U7d&=q9qEu*IU%+3nTVG#NRm+P(YJ)rIh`f=mBbEyT|weJy&mqeVVnbT zxGtX3#z&(#67&B6OhB{0>eq@{HJ0YKmMu`rinrm45r5`SI4+yoAg|bYPJWWRl2$>W zeg~okfKY`M^LYE*dW#p@uv2qc3BTy94mSal8ohA5?v6H+j!}C}Wbwr1k5d(PWso~{ z1?B1)z>I6s{PFmzlqqrhKKHfH+o@1YB_!qonJF|VeCoKzx=(<(H`(jI-WV_C1}=12 z`EDWbW>VSnJRpo`j!LW2r z;SLPNC|J{ON7KlU;r~UiM@v_)rJ3No47-RyW9YWv(v3N`e8% zhNVCSIqA_mG!16GJ@)VmgYC;kfL0UJmu5fNG^nNQcK=n)UnbZ}$v*tN0no_w;1&mi z!&eEaQdwfKELcur|1do3$0gJn%enVMwO~-eSo_&|M5pUnAe}P4A;FO~*kki@!OEZL zeud>LUhyyA^V`vDEdMg2tFLsrMj?*@F^lPs0UUIcozhEEy2%r3?KItgEXpEXQG?Q# zTri*>T9+u1ntd+0xPYGI_shj%v(75Q^&OhC0a@bbvMbeEpV}oPdZ=Hzu&Eg_K|X@0 zMxagi_LDJX5v%Awm?z2?dr0WVcBS{;JVxrlG$}$R3P?kvV7{|5kGigHcNc#+xl|7bBv-%4&`2eD;^oMe~@2z znfR-g6p4ou(RnAVTmR|7K7uWa%K(7!*y*N5B6(lIaT`*ham95ySylWCEjOUm*LtZs zE@|%y+|Si%7Sv}$JxWE&0kP2?Ns&{pGsk1LZx_>Mma0oi9;HfqZ5QaqzrODD@Oqc33pm=wf~ zK)f4OG8I%_8zrMlSF529^YS4!bzIX^M;U-n>*B8%O^D5YYtBP%HwP z3U+nu%ivyd=3u6tYgEq@qhTbSb4Av-4UhEi8~<{G2MqAhwsIY^o8C9L5b>*e@?4C6 z(sk-FLh)cVVY2k!12H9OvZ<93FiQX*jFE z9is-rU_?ZIhbF2Kx>S}+0s*HRs$&MU$ai}S7!HE30*BqFj8jcr=`C4Om%!M*4;QbA zj#MX>${nE68a6rx=>Kx5e+^pk;+YNo`2Q-?yAfWA5TBUEeC8sVvcY_tuT$A~1PLt8 z#qxT)b6GX)?ed9gf34o`TWY}4fYe!%s5^eWvdiflf&PTDt*Ka5vRKpU?EkVawC1?X zIU{!K5`EN6a5yeDmGmuMR4sVRoJ^Z>E?+5FDurKZVCVg?(;zow(&A>Oqc<004=F!? zp#SX19zLSgb*#J2rHJ?yGVQ4uQ)W7gIVRy$cM}rG$n&N85OAg9c}&}kAE#!>Zu8`w z7&t;wkXFKt^K@82A^QRBM(GRuYKBM&q`D>6&S`OmEp=YV9aHxP-5xVx;-cVjp8z9gX^LQKB7r~Xjh-pWy2UkjjUB4ZjzD5x8JhoM%AJ4 zZ8{LiB0!V59et){_lnaFFIdh?VjPnr*)>&NV;Hp1uZ;y|$eh8fC>99W=xlix0M?5G zP`l*$)i(rDV+=PAGpCi^88h3jncIt<75R zZrY-bEg)+D6wwDH>Sh>1@IrLtIn<5*860AjVD9=$$H>$mY63Dfl&>zYsZc-zL+lj8HZ0>k0rMg5J)*U8_%!h~T(1T+vasmqS3 zi)cB`zs1LP+GNsxGLZ3cjr>(4PRBqKM zP6Wx=I@x2Rq}4_a{DhymOrk!VrHa=R``-hD9h_(RoELM-9DES8IGqa_^k^QPs!;J; zs-!gl6`n6=e-?I9sE7mLcoanx;#3eH!Z73hE7E}sz>hzwu;WL)48%(2r)lSk0e=6b&8p6o) zj<5J^Iw=6UiIwv|09!eOYO3aDlS`#(t@yut3kbTWH&PuES0@gZpW3f;d`+vA#~=e` ztfm_Q2dGbJcVulyM-`FC00~A-PrzCJ>*D`V24k{?;&Bu#_O5V;o5I(8OB)xpx2L9$ z`z!(tU^<(A;^(tg5^Pfp9L+(p;<(8Dmb1Gsza3j5>3Fce7Qb61+QX&W3j&wN>Uto;3Q?xCk>)s&zc>z0c5Q zd@wsC6D&|;Cg%>mJ}Uov%W`J??K(NL)5toGrmG3t`MkB9%IlWmB^Jj|?kK|pXK#_v z*L?f9T_|{tmI=i3UJoUMLxY*HGUd@*JGQ~pT?v5Cdbm3K7yim2tb{tk_NIKW5)lFR6_VrVfp5xR{V}<}rPkz1u73LzUiXvnlH3Yy zU9J*A4pHG8wk3rb+f7BDy=~Qvy#8TKq-E8C@5QvhrD$%uUR^Xv%yg-<09M0B7>xKV z)F8*^Ms;rSv!mrK7TW>lSvJzqnQ8J3K98j&T#=3EV!Q123U5zjVgX<&?NtM>2)DAw z97^P;yDWjJ@#iLQf5Jro_Mj+P-C5r@vudI~nLXi7@iOjc^5W%peP@-*vDD><*}4FIG-W~EPVc)8P>(GRB+i(DC_aMp zcHFdc^L%l&c+azQdXqH_Ujk^XZJKl5)Vb|X4k3EL%D&-eqSE_b{0|8P}S(Y%h#C>>>d*~J*aWi<8=V(|GTe7mJv zpU#QVBwIP|pGNvQN45ys$hzQ6>v(u+&Fy>Rs=+eYEKL^t3z034qEHzKlMx4!l$xSM zIH%F#6yqMc2JXzRo^g>oT>mVaq+Q;uERZt*(a;_CxCAj8psi@dLKlewa3*0t;=j}C z80VK}B*6~%ioTrwa6s8L^FlWfbG-u ze6Dm}-SfdJv2DvwwT0)KAn0s_Q{}(ket%C=(I_Bb^Cw?MhmfE=S5y=yWtdLDqE8oK zF~Qh6pwY+6`KtxK`92Nug_p>a35jpEvbd2DWNxwR`zf+M_53Of_t&tJu||c=C-Kkm zkk;}0Icq)3?jU==#;MNd95KZ~9BB1^A`_(|$(IqlmzM!Mr=fUKu$8H>{hE})DT|-5 zSGD1&aAsGYENhA0l-A z(;ky%t&E3p!M&60!m2DohxsJMrWFcVU5$Xd@5r9NZtUQAETz_eQt|lPkiUq*cRp-H z{n2SrWHa&+Iq@5onFgj2$nRHOT6c6gmp1x6f<}ve3kAseGPJE>09eM^U-tt8Nb(s2 zTlZxzQ?)@|`)Wx#zh)Tg+u{k=mkmtp=Eu2Pwt8^o#_=;$x40Jbi}_|9;N*8=K;i0| zw{}b0ubVZSAP>!YW*G1eioU9(CfU4W{M55LLtPy%_$b~?f=O(0(d(fI+U;y*pgHgc zs#b^LZio52fB3JTgPlII*Oept3e|DrK9BBWuNakx59p3;%>V!c03o<3Ez!dCQdKEi zCDfmZk3^B))m$mPRL2xRJTgT`fg*Vvs4qVjSO5T5sVio~fUmtpbxF;4<2VazC;-U5 z1J8Y~w23IroPQR9>_|YQ8KZjE-_g2cfdG;g`M($joPoIo*4>Xl$4OAkM0`?y1C8-^I*-+fTfvi@4 z;1x7mC!gKz8I^3@jQCL9`gvjq;QMWBSYVa>ZayV}M9hK^ZRMOP#)<0FzRB&`x^IZj z0o=nQ{AaeuScm4Aa2LYO>XgwC(Ia*ScobF0MxOOm4fo|aLI=!)y!b47XYUW@+$YkXe zRsCu`qzzssN_z_4vzqyWgFhjqkmd~5%z9WHY%2cTfCR~a0JCr9i)%5A%Ww8vvygjn zOS}f)@P=}FzZj8n$`@cCc3SX^;Py~KHjYO3bqy}TD|oP56YyYR&J=w3)nKSAM1CY= zHoyqE*;Ja%vXL`-zN=c|c-V+9TTb{+{{n&G2F7l$oFTc-(1i~9xJc5B8kBnHeO5>w zcDn7FN(}QhuK3V1=u#z0l;Ft(n{|el>Y8l)2j8g%1N`UU>7!qHV?O+py_3SG4*vPN zLNW*pI`>9akE4aZZI%8>NE*u)2$aW@M%W0R3{OlgA$1g!y};QYhcmZY)FvoZll(A- zb1*LuLO$qn!UhE+apjBPeyMYYZCdUsH%k|B%ic)1>887KEm!g?*y~u`?nYUnS_4yP zm1~0Iq?qU$z*ME(vz}XVS;{OSRz%8aZNfNjQ+jAjP{mL$4sowW2}pf&UoNUE+QQ6f*r(*Rh;w^9yf% zpRO-|KL>Gb16dOFy$vz;w>ldLr@q5Qv05ibBhHt663lKR4)9z(G06cp=U5k# ztWUjjGAKU62j~$J5rJxll#4!5VwZZe9l6FvZ37{0GB+rtqI;W#3-Wv*Ml;zRU)hMl zJ286*984*3Vr-R9(Y*~pqZ?AxPHLq(Q(|WQYA)nEnwN9ud)rKT7+&5nmpGkOxR}fT zi@Njj)2bCsG|s1yevjH+ zl)oOqwfzoXLzj0fK1)XDI(B3AZ%T1^MhcsUx}&0D{Nl74&wEQRUE6>aI{*hM(cBi586miW3z9}`Jdx+ zz~_IO`?GBeAI7%F3!Z!9A~or|JUcaDUC2p?eEB~pK?YM{F_(ncF6frR@{cB34xx-i zl~^vYgLHfcO4!P*C?lb}kdUnp{X};>=j1ym>6nDVtWI`uq4YXk8u^$GVp~)ka5hS8 zT=fz0s3~PAQh(lHie)FBHGU`XiSDJaBof4lPEr7ZHIh+hWN zI#aJSTik34*ImoGE>DBs7sQ0eRvi$9xU+5H=x;`z>t{QV5e1%}|o(r0x_vVaPkR+c5d)<$|xgiHzf$!VqO55>t|H0i+8x1!ScQ4U}hg zME&k$<+lUb(JnhwTX?#-tu6ko_&9;8BS24H7PcUt_##d<9M-r}W3{mjAI?xjM712p zz<|t9v#qguqnU$bc`VR86+lY(8D#NF$bOKw3XTcPhxu?>URBvQ$jC*Wc|Kf>L?frCFD!}EA7J5(xUAMHHwc1)aq=pIpzAXd?}F46 z5w>u7cR{X2QAmRI!RbRpEvF`ZhJEEU&*=yXK{9>G6~!9P(x}>wz!Oz-tVzK8!JrmC zu%G`x&P?&jM+oA7JA~vqL*IO=TC=whFYX|7edKR1S%aA%wjBHtB3DNy;}wZt&qzKw9q{dI2gODr z2#tiDXK*4GMQP9R_WrgYhc6bOr-CZdw(i+G5!(lufnn(Ip^*xgE7zMNB+@SKqMv;i z@U0}vdL+Bq+4Y$7yLCvib8NKwt3?)c39!eHQ_rSusapvJvp0}BU@X&%?jWYQ{s+px zwj!3b_aA5N=T85;TaPs4PMW#w2~W=)WHCGi$)uiMCpBjNpr5wO2$}B@EJvgku{7Y` z>Ld~Q*Do!fk`=zx9l-$en)MAgs|op4n81PUg8g=Y_#2XfPoUHe+1|wXvDP`pB7mcF=nSb5z#Dw zaOhlO-L zXfHX)In@1M2}vEEK~=q;-?1R0sWHO#?4_nOUEsR;g#Yb>J7NkYjUkJVjYmA-EPYZ` zp5KnPz~-)?%w1CLfm1WryV1D!$dLlgf-Sc7ZH|embiu-?w*g_1y~F8sD}U;zXhQ3T z|EzNC30U#qgbH2;HQ*x85lZjp5Qx)!8y5(Y_1xO-r$Ges;S>F6b46qo^*7tdEaUgT z@wGrlBP-nt(@Yh)2eOz-E6+ks$+bKumV$LV032DhGA&tg@D9=K%I zrKbj>=^2tYCc@V6wdy62WxY=Z;_;H}@wYkKX`-qNKL;$ESsTP?RLS2c8}D7ob`KZ? zh@*J_AxvkE_>x*1ogN{csIQouCaneK>h78$c189&o^?q_5O6M42c1Ck`iAR~5Ei+M zIBXLHZTfnd_)zdK>z#p}Sp+ShO{IHElg_|U2EB7e{|Vp7sy@61<6L z{UxAlsVcfnTgtO>9Csg1z}rpjJ4Bjr@JwpJ*tHUyUlNQi zo=1832C`AfLRGcY*QyipEB}$o7V=;0&czwf0lB#`PxC@jR zjy-@ZFST^E|>krtF4RcE_R zMCmV=3T-2y-VtRkeQ3n-mo(hQxm20BUd})vM&iU=R-s?dCY#g9_xFhmN*t;a zW^noC391J9%v)Zgcwp|f*F#up?~1^`>|mZY4S;w@KDtP}2{0CyK9!61bs+R^mDs0L zw~3$>O#|{ioJSA_;03H(r=nsK6uOpj zyjPR&=3F=Ic;irKMI$eLI3d#IP$K{U0{{R@x17DuAIx+fW=5qGE!t1KK)622*tX5f zs+o>U^OuAUhQJa6uw;f8w-AL&>JH^Dt|Vu^#MUB#ez~f1h#w$GUY5*A6yE5(Z&JK} z9I8AUfn2n=UG|Q=QNZCo6VgfNcVji|OGJAVw^wI+yXJg2@#NZq23@Q`p4|9HfM7wJ zGWJgA-;|E`rA~-0@xOQ5jj*!dak&0kqUYSu?eZ@N$BL(!xyZ5z-Kuq-dt}1E{Z#M= zm z)^rpD2gq)Ldo9azi>p-}ZF2H| z)yJN)ljIcBKY+{BW>gRpYTdVOR{#YPxa$6fFI|KpXUw}-@f{m!DSR%omGEzP zSY&2xoE-Ca1*C6~Z=Z9-5gSm5`6cwGG&tmQz@Qd;EpqW!u7Uex3}0}SS0eSVzY!+@YkCA_7e?3{)c*~Oi({)6 zKVva&4YIcj%_$pqh5A8mty>wTSJYk~Lx6`*7TUw18| z-5vwMx{&f-BeJAe#}(qq)z_8tB#(K_C&*GKQ=APd>>^Qti0vAz{j(NFMOUiLj18y{tpl|@ zbchTugmMd+hu_TRK{g@o5OE*@7(R2EqgA9Z?9Sd7?TSV=M*P(kXz1~yim@h98fS1M zW^`(PT2JP+(Q&4YAwyb>2ocTNmHlYO9wGef#({Z@0SV^s%{(@@%2HnIdsZf$VXCeR zgeGU8oQ$o}BE0GkXqVqUD4KE;)B88TmwAKo{BDAfLgrb(OdjXZZ`KG6EeaAm(SK%7 zD26QKI2)s{QJ(uRS)HjQ{*Z;eDiF&PGi`w`1d76WZMCtDW_Tgn z*zr_;&@|Wb4B(F1iDL~n;LyBIg*z&I`DpI>9~B}An2TbyjUh6`{drO(~pEM#yd0O zP4-Ctu+pMG4gh6?iYy+Y1u+Qi92HAq(bF;Zmnk=#wPM#-w-<7aHg^LEpC1u?(6`uD zGqNBH{77i~%#yu2haX;~Z-xC%T>=xVxOa;;k87m?B5e!6EtT68@|Q0GM>W2p3sAgv zhs_S1F`Npa{C7!l&pajE6znu6@A^&7avC3JAqSYr?l^8`omiCU&7(Xc&Fx~S)n0Cm z^7)_V5Wl}51!>BcjV`Gg0pAom+d9o<_;DE6FZ7~(_J;m(o5zbJreUOL_y`9#% z)sJY~M)jY4rqA-h&s{#ujAA%Hs4g*!GcexR|G{mPt=lnal~8g`i~1x6Ia$B1sHCBf z)MOi^pF|r3N1bO$IOO>-|Bzm?RUOL})A5IS{N6;iV#yToDV=9CFDb9jSRkmI0gW2F zaD{F}VgO}k$G{&1L*=esuk@NC2G%ttY@JVAW(6>!v=nMp8}~RlQp_=w29+c(1oa&H zLRzwl6|3~rZIhWI^C>VITv18BDiE{z^eKd)_SY?^z3BQ>?HmQzdLRu`s(Yy9*hA%W zX~fDp$tF&_4#W;%>;;n9*ThpGdXvGr0W66*aYA$q>mwR9h#(9J+ngca+@qjA)BbMV z)T(cA?y#(I5Mc2c)!YVFM^hZT44wjDn4-Z=)A$3bsWyle=#cfgZ&-jTw;IW#qGh70 z@s8a^=VY+)z99f>Uk4N9l@rpL`&Vu09bG%o$|hu;hEYwswdLzMjXM#Hy`5U|4dI3ftu3ipq>juPW;BvB*!Be%C#+p8z-t+ znL$Z9k&U2axg*hmUCc+IUno0Pxg+QcGk$TIxb9BfjY@=*(NkCdvM0GmwLK!_G!E}# zhqpiQ#;goJrCCKj5#W(zlSl#dGPti{@j9%!pQa3exm8w%$YQeW0Al0n(;wp_P6yL@ z_a0*^+!rEM@i>9l`HR!@kwP&IaYC>@(+R}2akV?GhoG~~)ZM^5TXwp?{EOh>TbuX*L3VM|r(+R-yvxtqStBz(tX=c9h-PZPN8(4E?x2FKJ!HmS#w`nj8RI)Hez z#YhlM28;w~@v2>v3@D4^LAq)fIIy9;7GN2j49RJ66P)prl>Xhl5PvToSGO*iX^nRi zOtmf-pX;{J97qvFy`M;x+~PqJuqb4gHQvG$1A%;7*193;&7B%oE5HX|oeLbhZZJvp zpetxKE8u;#y4}aU9((jCt;DM?F7IBROF!rU0{ola10VnZEo;vgyiA%^%fL7nti!cmD&K=xA zbY2MexrX*t;Vi#`uc-^Xxqo5WL8OMo_&}JgBGR>}^ue#CRlpFEYlzUy)ztiMtRNx! zlLr=6UCR~+_#J{*^ag5F!q?8>!$A>bqEPKxnvPgj5Jv8|B@{CizYtD>BYcUKCz7{hZM0EW>@8{qRY0 zzxhYjtfNuv^*^{e$~u?H?S49IS@R>wl1fWOR!bTwMRo~7%pYe)RBHd}Wt!(&*HgYs zVE({w2eP=byzI(%53=8X&kJ^}KMgBiq#elwfFs@SOL%SVRD|fYnUJt_ci)-4>2=N2 zh1`}-GpYk3MF{9{eM~rqZ8JHeiBOA)+;gg&#1 zUAmkpdS7K<{7>KBInBoVqor#s6Ao8>k7o1rL%;1P{r!V)mImcs!a*s7eGSS0gH~~2 z+*TPZT+_y|xizjkFM}9;W)-#A%^*XDkWY^>{^)+vKQ1r($%Mt#z!BIiR3rfx=nVoz ziT}7Fz|<`hsp@zYI~P-0@|S?z2h0k}d$*Lyz3ld6{$MarO?%iy?iGH8?deQ^|0?f5 z6i!-X{{y#K5zwIaxH%J93-wtG#Zh$YP;`i>mK~jAcLb6HW(n7)MNKUCtkzB#-yG0* z!hkd9N0zq}gh_{1QQ63XAAa^8KUf9L{oC~aioe%QL)GmQDFDUsIWREOCe3o#xpbUD zLT=cQ>(y|9`>);maP?1K5AnS)r@5hDc%`$nes5$)qBRj-Ehl^?1Cv#X6WwH1rR9Ig z&`ZnBb}lRRgZM9V+|GxOl}y@YW0M!xu>!i2H%Om{t-hHwN8EhiJfJp&~SM z-$Rb*Laa3DqLC0hXY)-oOS9_H;?Ml>IzA{Nnrx_#iZAJi1RQ2f$r1;4qbTOi$I8#D z%UD{}2fss()ItBWL;=5zDo3c=@~z{Bh7}4}1bJr@Qo|+w;*E0r2cStIMdMJrm@cN0 zZSEPoU;_z9fMVa7IjArV#)l}4bxZ-L16fR_YWEn7;YPMkO{ZmQ$@K3rRpT4}`*xX- z&`C1^!bn{)u!uUdqg+ndBQtf~5AikHlR~_|jBcR#`C;kg+{;r>4lJ8-yut;$Jf3u~OriW{p}utzY$N0Jxy)Yls13jB^fCWzSz%du0Bjd|!WLZ8 zG~?xwTcQ*_|Cvaw7;&x=@H>3Sg%A>G zWn%DNYQ+J3{P>JhLqej72syj8GG7pU2+b$Y{Co^Dv5E~xJ1;h9g$W1vYF)b9fagckpb0KNK*t}SgguzU0S30wns#CYn_L4nQo?FL9vtT7Y^ zFO>@QE&RSX_6Tlw?}_t#Ho1$?_fNh9C}40a;?e*BHB8>(d088@Jo-%wBXWz1 zD~OR<-|qvmU-_V#COcep6-26iz^nIW;K1jxTfslZ)4(vF2@8jd-Bsd%ZD2Gv>3sV0 zV*r0g!S^9vaLQ*=SC$PEv6w74UF>}9U70uPZ0E^cr{^O39qD3uB>zT~msD!n5`hvN zRUUwA!7Lo*kPN3HEZzbU6NrkLW_Vjm{Qme=OU#?d>3e_!dP4N4(#5aJD%bW^X)g8q z+Jmye9#L|vUyU=it`V~V^&?O0FQ3L>1PF1#s7nxln&GeZ(UHCI1+Aj&0~m~Q08?vs zlB~|`yQO&$!C%rnO`x^uQYay9!;2KVj7Q`-Y=A^aCbHgJb%Byb29O1Nr0Xlr=%*2& z@0*`<>(M$uX*nuAzp&Ru<(vj`?3B(GB>7~*e&tP{D-XP%zWi8vSlZwF57XjVg#c1p zfbhoeZE@8KG6>4gknIb?$3cJ7^GM=*`gv&Dgd-JIU8#OOqE^$Se)HelkazG%%U#1S z7U~LZFTdSrPRL~o;&_H=Y6Q4C!NDy5r5e7o64#X|xGagHf;bnL2`qipGh&Xe=bsJXlgkMerV8mfs;2Ld4*Aa{fGiMNyc`$Aq{_ z>YUXHbs1Zg9?BJV8;QC=bq{aQ7QNdxe%6(6ZdbMf0ynM5Dail=%+G+ya>VM$e37HX zg>;m_UeB6|onXHar3jHlu4@<;zH@OGRTn2LF+%aK6vzh2n{3Zi8AlJp?XgwfI_%AF z057m=RRh|sz6=o3t9Q~+WU{;*k$rkq*TUHRWmrExW7CFa1LA*>T>OG4CE^U*D-9t+AF;|KoBhx~K=GC%+}3x*TA8*6&X5h)}RZ3sk|HsC_b5qS6A< zHjNg6$R%8r;gAK6PX?8rp@cVQ7WXwi{~#4Z<=t@jujyT28pv8K$s-%DN>>?1yNEgn zA@~=-Z%aTCtmS~mNizUSiI(u`;8p297!-otZD zB}YeE^@XU8foKoV4C?W~u6WZ9*s;vQ)F;z0LZ+hN5mQb@b;npkQVP%OyoaZ+%z*a?33QEGqN`AfVuUyC z0Y;oX=HJ=#NaJx?5ke2hgbH#U6`%H#aQWS_q(s4Ax+VNEcn zcotckKJzAf`tj4aI)C@|Q}+~J6QtC1tF=Ls&94VLMFq+9@|p$-Bpd0i9O)2HfAXiEga;vocpx;?#L6UbEW0 zkIEm!3|*w1(icP0HS42YOHTrE9%L`;N;Ojkq?(e!V4YMwI~y@KyM#LRO0rDaBSX?N)kcxEta(<23|sP%9|T0!Aln?ijJY0B)fU^-&`1qj(o(#f$(>Ypf#u@-zDDW>Q)PB0wM27T$u#KfFl1| zx0tW*OQAX8rDG(cn@GRajs`>#W}Z97B$6p9O0AO>%JAsjl)n03oM9nN^u`)UG^gMH zFB*cVxs~QfzB=IXsv`)LcPxayXA3x+wL0bEj+87)ZZuHiJB@U!kyC?zAHC4%G!*AR z4i$i>{mLe0-r5RUAtOjZ#W6{CaquFSN`ePw?dd4M0Np!yHTf>DOB#Hy9yihCX-x@* zjymAG&cmvayjAjHY8nJPUPZY_4E3Ib7FAgg?5i1Sy@QH)CwXuay9eb=|MMdnRM0sc z>-m{^BJ{P*TYKlO@|LY}6hY}Y>*Akh*^DJyG|v}g)j)31@_ubcXP{<7u>K`Zouk|V zEY&l&0N#9CcSar89<9rMEkYn*+BUcvt0s;bwwd^axs2L5Q`};@%}KUp{?}Z^;VH2y zmiBkXSdt>~`1;DDw+8&o71qC6l9+qNNlu+LO+zauSw7hW7CFF&MJwT|VHHW66jQ^zH-*V(WapGAp1}8h8o&AK~yk*(? z5nQWlQ-Q1GWM`eK(wrKHQUW6mAEQjsG%`xq`0z-CH01(F_AP`i7JoSrP1!J_Z~y?o z|1#vUEQdJvtB6dPFxuCe`9`7qIQiyUDu!#znAu37^)!`I-)2F7P^fS`= z>0A;_Bu#!rw-eX_DeqO!H-AR5M_XVHU2w>GX4(Y1po7YB z`668w$@t?3m*N50Xp#C~)3O%SM|uc4&}Au}{Mu^x{KumcGcPjgCs?yfb%HpV&Dq8j zpeJ=}3os*&rKKS_CsTw1QrHZAS9-m}u(6>p#^R$-?I%bbq4?5oX3udGmIxHl#}D!% zf|e2OWc~N;A4t`~p?IZ)@rfUFEmNwce$VV`p^6&To60J0of-rS33H#KW8N7rl}*YC z)Jx8LYasIP=F5{#CZf?F0MdY|N!b;!u#e>wP=+Z*0GQX&<5OR&`kxTCULiy#1MO~G zNY4WWCz&Uogf?zcEyMiI6aIP$#J(JwW$u(-GpHjb-*2OHy%cM~bN?UJV;@-+ zg+Q)Z%seT#(!1PDgCthm^(9}rHw5o1{LD6|Dyc6V-gmSWUtP#)LR*~yClOyi#K;)5 z@s*HsPQpgQ(_&5xMK(~!2fEQ#%uE6+x4NAr0hv4LUC%K7owLx?edYw=*To9-xN2Nj zqS>QCJ;h8uMfSsxXFqE@RrOb%&K|s(c);wyzv4JJ3Da8(FT&&e?L94AECb3z8>s*| z!E(_D%if0vOCyf;I&^!pM8b)et=fA*%u*a*}gSba3C^5w+EvXHoS8{@br6P=@fW z0ExNnWj(1wfut43L&F+M|n#V7`!(j+d`}AP@vix#{zZgu`D~N$vit;!>REv6*8JD2CF>>Jdh>!?W1vt zhp(1Z=yWv!hrHzYUH%WoOGH#t zMw-Mtk6*6orVs62HPp*pVs3&##+wNnrq?t_mI_hI2MI9tG*CZVayRrK_op^S?bt{{vA;)lp!l& z!qo48K1EgUUviQez{C#0!)H3kLAjr)%5$7aBogHpWGISL+O@E$HBd)5k)TW`NZ-Qa z;KjW;ueFh3-H_yid7-Fk>nJplG!mzY+m~W03&GEULt}cRe2+XMP+1F~vkX8RvZS=p z+JYM@<%e*)3liX&8lIifLF@pqXXsB`7Ace4kn@EGv%pV#BXM`7-jc84Kf#<+1H9pT zEQV(`z_m)?~5)qtF1}JP7?@>3zKh zpY9g$nUwM37!uQS@McAa3B~!>Epe7rX8y$mCj%Opo!5}HdF$r@?zu|WuXONGVY&2; z#OhbRiTa`zv!Jjb((z~x{e8W_KY$X1D zZ3sDz=n46g0&RwrNn$0EvP-Q@jT7vGogqrcF>`7nbHxezTWnT1krg;AkE$?*sv;Ax`_bdJ8?D~&-@VAz z{WNqXZhF=`xD5#c8i z+ZNhi3G_JT;t47LWH(F86lh)e0%O?nDjYvv9cp*zLp~-5CMb?OA&dHU32I9m7dpxh zHSMGlyh)s0^c$miRS`^N;x@ilir%9SY?cfSb%d}}iQF#t6pI@BE2Ff!kMfnJHs3W6 zh)meHRwQc!WXw2vY{%SI_IwtGl$MX!7U0Xp^$M+6?GgkbkJnDJ0PA!lI_6o1n)YN! zK^5cM+F9Ye%Pk z-H%zMU|7Tm8|si?5-G%X&cH&l`(5GAWs6p)Lm|++G4hxO!if@H+-CJ28A#bhhzvRb zAhSoWN@7ZpB%7nb4 z_d_&bz^vCqV|z*D`FKWigV}kAthZnYLd68{LSxaH&({o7$?dv$$V||c825-0_}~(t zo^5ebuc1MtK8XLw0qqij=l2GuI(5saa$UaOk$z}NT`i&LPalQlTZ*p@#HQ-;qOpAa zPtJ-<#X8M#sNX*CjzN4t7jmE@FiKqb2K^4uOJZ=0#Mzu-$c|JM?aIV-SR2c(m>F_FnP0$4!*yu& zNMhAiFgkhX8iaB`h%knz#0$dt*mk{ogH~YS!I-G^Z}^jb9smjvVgTJ9m!=3=Rf!BF zt1zq+-hiE0Mu+R~2l}_A_Z)(mwOJt4xc#>kb_S+wukMOJw4P4>R=i9wpdvz`bYZE} zix|^n8wP>A)3M0$nK@Qnm8UR!Y5G4IvX9eK|xfv8@tv)8sgGW zW=Dzf=Y?x)T;r4WNKVR)ucFwxNV*o50aU-f&b)e5JQN!4A*-ER=L_6FN8heNsFbVJ zVO3(}M$^X4H#k`(lOaj=;P$)hdkGFmBi+Ob8ZN$o5}k#co;}w-T7Z!o<8!bjbK`Nn zN>GCW^V+GM{Tl~3KKK!$uYOiTK7?im8vxJls=#C{I4$e72|?R2n@%8|(Xw9Pl6{ni zG$Yp@No?B1i`bQTmuAcpY9IQNMq_i6ozig&Se_c?9r;_|b~_1e=8-2&&yhC{$xb-% zkY-lSpGpZjN-}B#WOsGtWjnLJ`_MXVV@@DBlhV zM-aC<33GFHpcqt-Kfs5WWbi-1`F?fb-s!q+WP*Jxj5*e)W0eOygbxLPL|^~evt9Aq zDtNFV5QjNqF3H!Aq?&Es@rzTU8-8kVfcF0A%rE92)miHh$X2)2``5jF4zukGW`@2n z!q}ouOzccb!MX|<*PV3Wg7d`A)mQbF*T%gY!6|%$9{&HPL?`X$c@H(u3v++#YMy$m zSwL5!HisZa^t{Ib@DXr}^Wtkm99r zxJA`8l;Wi5rk3URvAnE0*X_rx!WWq2V zQxl2lU~hRUReL^Nwl^_8dOpdI!3Xc%pFktHyEELTE(6@=3DGJrf(~H{5pJHekoZIr z^+uoTK5oLDo>9=>3Q8B9Y>($KrsA*1>7&-$1N@S?X%ivv=5 z#cj-3tMW2I=F4@70jfnVz*O4;2Pgjv`reglfzsw2Z`ZJ@5-{LS3BgB;#nR`d#ne{L z)F5IjzaG7QYd8=u-0N7BvN(jn|BrEo$~%SCAkWJH=GBV5aFhBV zTRB_#S-+s;)Dj;9q~dcnPSVu1pGVn&ro{x`vwRC&n$rADe<$i3qdqRn4+dzs8r!qO z($uF;lvWw!8({66Uz-W4UzVjezKY`ZPY>$q?Nz-*_rhem)%;vyH~ zneEtz;c?tkl%CXz2!RoH;6nq4U7@utIkeF=uYW_SeTP7X^IKb(6y=q*npI0!+uhg% zKCB14Q3%p8l|Q?i?wD0`Fu@chWVsLvME+lF8f7Qdazv4B#{Ni?HZ zJHYuSqUK3$Y1?q^nZ(u~^uIJ`% z=G(!}@EsIeW#h4bPl80!bM1XtxGY(--+&RTwFJ`|M3!XT1$>gh!TM>tqoe@PfBw8A zlnt_Fg!_-=#y76b3-)L0KF9D?&W}I$KJ62W@_%BiN7r4yZTBVn40&+F?{^mDN#c67ny8LFw*pY`9y?p6q!BI&`$@z>e+ zga7`F!XH9(=liAU8H3Uj#`U252!Hh^`v$Jh)U3;q-aY=*FG*wiAPhNG7v}71_--FA zk^{@3K_lw=%Gg!_Kwsn5by05<nXesIv;yhk!#kNVZOkNtBigDSvLbX%sd~s6*Nm zS_K2&7YNF2R_ZJX(vSRwdnr-@K@!m$G_jsT4TMqqYA2!a?@gNmSi92!qx%;vYMWh> z9^!UbGkd0%&|JRh;sw8UevY>C!M7}1P@IQkkOYhqu4RFu>M@}EI%dq(rNOz^js%O+ zg8OAlU_UVN10e)~5upNBRt`@j#k&JhOZ~yLUYz#&u=Q?6b9917?F^U__I3)`b4tLrwt=Y)^1t(kV>r;kMvdIiD?B}$%)<+fVKFO*VlE&GZ$09@@Bxg%D zv7xo#H*n|+dVO`g)8$&5paL134Z3);+kpFtTIaEP zR*crBYBKA=WD8)3o!NK$Z+F&>tDM4Nu7sIa>7?tlHzzNt-4_AL!RR&lrXZE34+s0`58WBO$CAL4 z6|#W}ZPc5jQaFz9g6@skJC`YAcGn@V>!EV&p*SJy;A_Q?H?`4|v27a#2{z&$#6YK>^J_u21%F;; zPs>*tv)ZhTlfko>m{BJehSEZm(J32^_v*ZwOjzQ}9BAZRvBKFNADLWaV@o6jlw$|QMdBpjP z1or{RB@!9=$;4qb%wt^s_8jynq^E_W^6rqMrG`;aV zk?G6Es0ik9Jg@{#+ya zU)aSkzhGr>C_8ET4 z6Eu&ovJ{?I6H4s<*du<63`Oa~ z`N0Qce=z{D_{k%T0yCLwox=eU5s7H**2&?a!~=RI1JVNbgQkF14`|9pvCC~F?xPbcm|(YCe!J_~eO`A{~Xv;DC%hMQzB7yq)Wcn!{VpJM2(kjj_|2VUCY zZ&q`vN37+IZB-AQrPcPcB{79aYX`dV1&mry;LbWz$WRWMb~YaOU!o%&;m&)3wr30S zEha9;o6Z8Ll8_7i0&c`T-tcR2>>?b5J9=HzsEAz{4I>5z3~{oG^fb#DbMkw%q7-VH zK-Ys36a2_|8~4x>IZ=!xaD5w23B`=nO9!1)PG%tt7Tkr(EU!N=5ywG^JZtr*3T|rS zp($8L^Sj~-`y4^nWxTSF+)dIaE^L1GfMb1Mvr^mbq1LlwgbwhKNA)k(OK!DM3#6(6 z!86HAh5+i%+CST8YLJ>tpb!pnNLs*CE6h;MemYd|1G#wZ`0TMv`X{i>@Rvc+SA{tE zN}eAb_WjEwS#FikPmHGfi%__dJ>oVBc6V$=QFTR-GyxO_G{$d&7wqFeK)Unlo|&V_ z-D8a^T3XPQemk+V%7z}SL#y_zZ8GuV>D zE}mLQ)Zz75h$X}SwQ64BiVLEZLI+yTq%)KLnOC5DYd#}X-Srbyr&`9L<%P3>Ja}eQ zX+z>STOAz*oo8t#c;p_HNMlAL1{hwq_(U70H-2zUR*yqctQg%e&4s{J6(Qb}8G@fC zOp3$WFUO7L4k=Vx9W*=*QV_=|Z{=2+_aXx`7R)#K#lL;4T^LGJXo+dC&2V8-8eq{y z{SdrlNuTdxVUY;v>cNM3>)?NI?EhtiXCUzlT!FYbwhB-C(r^l~hiMWGNgQrQ`>z4_ zC*6p>v?2F%nDC!Y)wv#0ru0dF5EqV%gRIKD;%&e+Ov#|o7Fkd7Yo$$lZGu{&JudEcaX~Im zyf+Ar6h(4+?SV`y(H3*&9!Ug;Y)r0y0x9zJ8TqB=OB4!mQI~>Tna=btPCcNqjl@KJ zowj`&_i;Zj(auyg>W*Ns;^q*{S)C01oyHW~KAg6pwWIY}I7%JP?Usr)$4)0*FvL)g zi~CfsH(HmloZT9)u00ep%}~pFV+A2x%iD0|0VmDpEYT&+X2cc}c5y1nPUP~3S-uMq zyK>q6PiHC^r29De$NKbJbmAG1w~4pwB_Cv`J8`2vd^~(RfEGZQX<9WnLFX-ZcA_*H zwPkH$%*J}#*&PjKo@OJtOxPTG#1{g^ka1>2p+-!k!vGrIP_1X3lfg2P+BMQYZk z%fE)|3jY0n;-wr4Z|D~L4tMk$4hRvK76EENmTTw%tv39NWuh&n?Gj`D$jE!dLJz9Y zwK}&RoNkQMaL87e1~6x=6K-TVPJMoAkV?75PvQ3dcC}iAL3EiKl=6K(2QnDhPBD%O}8T0*hG`XrD635sMA0dDfKI0pH#9Q1j=^54mV(86E zX@#8t00RI34MZ{BT7;gfMQlE^0=F}9hqGigiXzuykSw3l{v;!_Z*P;t)T28M5-g+T zxBmCxQE3c*M`wXdCV)5k?-&xAD~p2;B{M?^eYK7F?z`caCPzG4Y?m-XJ1DAPNn6=~ zbV!}{`lCaeR^5{X_dg(y&D9~?-^le@gcEkMwu2Ukb8oE7hle$LW&%4ZsLO#M+znaW zOflo70dX@!mCz60Zq7ex$;BHBy3lg&gHA}YOFGPsu#jMJGyl8%{j)NT!^_A~ohdpW zdB#N0V2SAbDB5C4bKHN@UY~?QE;UD2=7un$D?q}ly|Jlu)u)-!N%tIj9flY~A@yE3 z_zqy@d8T1_;2mMF0|g+#$uJSyz@xwP(HWL26B#sHYH!9PraN-}$t53=+Cr3XUsKA< zHKmChE6l8~gVe*<(#u#*z*eudHm%X`I-eO$bJw)8GRpg!6D~6F5Hj``8HSl!o!y+V zs!Pwn62{mKUoGy9#o@!2yFkqlc`#q1C(=o}P7TbL1;CaY_M+zK=B-8BWKN zdBXYxRU>_!*sG4jny**!l#9e3A3=Bh@4Ml zJ6`p{#d>$7Z}*1VZWDaikNs|Q#skch6DV@DT92LZDhdJQn1mp$S{iTshn|vIBJ2?}K?vhHFD83t$5LC4 z%z!^MB{$YJmLQSSh-Ihe%YdIe0^pX1!~{uTDUqXQs6+8LcAgMt-HywmRq`Y^5ASf4 z_7$YMAg#zogC=iHyS3HUfIhGGH>f_4H+Wm3&=3n;HrPe*HCsHzOX2TgY+u>)k@U!! zZ4}#h(Ksx8=q_S-6Qu)#5d<)%;5TYJ;k|5x@s3_uHeSzTJhg|@#6IW-0e+Y*?>?3i zE9w6d#RAiVSmZc!p?rJhTr+T56WXOX>&9q~5~r6|pRu@4?DF0${IR|(5KUSdP1RIm zP>98m0B10C9V}R(e2}zDQdi886njLBj@`nso%d#2GVoK;fG)GhYk94Z0+V(6vkp(d zJ1`b8ey{+-XRZJMG>{_2zZiNsClo3_jzhOrKmvpzslY9tp*Oi8;Jn;AdF+}wkyI%( z+oO|VlmuC}rP_X{hbq}GOid1X9E@Vs!+g^^*Sej&mhN|F1+(==)&P;An~mcACVu!F zL;UeQsZ6%Uf2h`zmKX9(j@`@6P&FZB*L*(WJ`&6{sk6!Nz* zj>=I*X*{l?CILmB9Ce?jBC5je>u!ZOT-8;Eq{vmXmK9~^?=a|qV*>pg+qhkb11Bd| z?>=c!>(gpNp$WCC)#5*32ms3d^Oh!6vtFszFYKDYL1nm*r3N`IbEiD(SNlsVFYzVz z3q=Lu%rWB7Al9!A4>JYSFOy_{hvpSGAS{ zC=1<(avEzf_K1mh)hO2l+)jDi>MoRyI4a=;?80PDzplcF8d)L@z_v*6nVwJ;-TzX8 zxF`-qI&Ff&SJ4L%Y@+E7rHV)YEKu>Q3c&V5v^dp~WB|X$buL<9rgEpuj-yPodkTP8 zO-^5cZxMg;FDmIH3CALnHmN>jJ(f+8U>_%OGdrFd-{>68|9P5QRQ5WKRU>ZrOkJpj zP7K!r;6{_^DsOMrT+uzKY%IdZVdJz(+$9{Ny5@nwy%Si0GypmFi!ju!^K3Ys!!>ZklmaPYUE!bV=l-kYXZnA3kX*INvy{bA` zT5Zw5RC6KvGLT#n9Zl_1xGou3m$gvez^Z+N^^TTq;`aYS>(wLGkg@Kn&)H%#m1yM} z7k=v7<1&D@l(b$%I)hS1=oe|>v)|u`g_uxI>9HX~$E6nf8r)&}34U+t{k!KK;fmgw z^hoXji3_H0a}Mm(BXem-#RHyrYrcT3@J??eEn-eLXH=X;Ptd=#i7-Wj7je#(uTH9s z^h7#W607Eet(l4IrjB2)X&zMUDsQ**vKh@y09q~C$qQm1^uw;_;f&+i<_{Qo`+Z`l zdF>_m?WDW6xX6=_m*LB(FZ6&(bx6F78jem5z^E2niLL#NyW3-jD*gYWn|vlbDONt~ z0AmYM#TqmLXhCxMW72Ty$Sb`My@L?`sp|I$Pbq@A1k7beK)ZU!bl9Tv!glL+F48J4x)|oMgQp!T~C;#tYoKvi26HQPvmGDh-npZ+#ei#HLnlY6a1 zj6LL&{0!Q>t%Q$aldALN^mgnFzswfsy33KQlKG4aAQvhUGi|pn^-XSE0Ti@CVh+5P zfh%bd9DbSp##JgPH7wEViZ@;L_1`Q5dnqWC`qQ>LR=H(9W_g6a;3=hW+P{wbo~Hhp zX^_U>8lXg6u+A@U3VkAukOEX`|w- zszi{mZU9{xKO*7DrTjk^fAhAEa^tkZb|}XB`XMd)_2Kg#_F=zR zd}@k!as+aBXmk`IMv6Y-%yvBv&?l&UX8TEF{l*27*ANu%A@`rvCSqc?O4MoYY$x`) ze5dv4Kq(M$n2O2$T+S(K_A9&IszJ?}wp9rCzE~HNk%l_s#`&wiu~7A@d8dz-uLS+` zg2fgY)tEssd+u8V;P`1lX4%u3ACd@BHLLrX$J9H-|CHIuAk_qURrsj#cVEo12I%%M z<<12Gizqc-DgzaEf|M(^QDpuCi$2)Sr)E*c=x|KTzPFk%#u(hgyNnR+lIQ>c0{{R6 z00oiDt~z=eO&*Xw;$bee-ntpe64LTjN3G&6?nN0J`;(5;dmPwFs1bYS{k%~pu+D1q zTCBS1E1<>1FU%s{t(z5zg$G%X>Gu>~xKJI30<#6RkwXhAvx@)tnX86Nb-UcH4+#-_ zBwAu&B`bXIeYt`v)2wEmU@axtXDPZah}dt(AO`r0S2m;zb^kjU<)2ngR>vcR;eAQ) z3t|5-*l)s|8LKI)VQb+}{uo}yWhL>_VjcKt1KD}K=?b&m>n$P~kJ-q=jZ++oK>+7c zCVLcUj@Uxz)W|901mJ2j6zpOBSF z^=9&xeYS^o&1t(@*!E+x-o$>(M$4z$RrN))lo3P<@bgBR4NOyA3#2H?{}IfJxlAJ4 zc|rs)@Q`tf0O)+Z0GOGf`yL9vf~d0IE>jd3!3n+fA+#;-5W2{^wvm}MA)0IA!@c6%+@nSkoQ$ePQ>*y5VL2iZ%v3?| zkh9&>Mt0ibjgv%efKEAUJR5}aF|Eoy;Yk`?tnN7T6(7y%W_8Z>gI;;g#hD2V2FT40;n6>ap2aCft5Ik$uXMsHPZ@gNC3U}_2 z73+7R11A7-&9ta>&m%;-UBFQ%x4>iwU!2CrF|^SL^sFZx6+YviVjK6~wbL8M8+}2))91lIQ8+t7hVvuRMt-upGZ}OoDeNnU#mKUT{8h9(^{H zTfsS>pfHI(seC@VL$zi)*Sz=BtCb_)ZI9Q`Xl~7fBIhB{P)bgQRoU`_69LPTwdm=s ze?W>^Sj-|_$KsorhYffZILh1RWih6pT`P1-%!!#_*`_}>5gPbs5ZGotwwp%bgE!-d z@uIqHco0d>9(7YI&ArS1upWwS;KeMVgxutJ@jZjRn%Rc~SQ{`(7p*(vnSbMx34BFh z&0HeS(u0${m1vX;VI5o{OZT(RM|tyxbr86bCSPC26_*ppMv@Mp9mdAjs;}#^6il-w zD#AiEo#*U2_%sPVWnzy!il zv50{s8;GyJ$3bDGwPb~|D^xTMKayaDOIW}=hen_7;&%g)wz$MG~YPh?z;Ng(#Jyyp7!#e!Ib>k z9ZpIahqRQwC75|5jrd8ex+c9iEgcO&Z1T-fW5Yi>+#{x|rd*podGBQ|I zSo70>a3z`CJ!uuCci(!L-1Vq(o3Z4Oj`NqF>PSa#{n(JRZ+OpF(;l6ErK4z_9BI@B z1R-^4_j0`jNh>~Ti}%NnG!#YHc)RtmcqBRavoW9jR>eI3h5G^aJ3-foCK!`AX=L>O z71!Zr2K#PPw^98wqs0L#CJ#xccFnx11Re9X6)xO^U4A2zUUZq#rk|CsE7_A^20n0M z1BC)bwj$%P85a_+xq_~%db+rTHE{ml>iGP_38ZnMAYuh)QT+$6NjU|4jw(1sS<%< zmgCr2vCri$S9#%ulsooN&(LpX8dY>X>3Wo>Y$apGxb9SVW8Ie$5$2Ie9oQTrX)7iP z?ayU8j3WHN%aX%DD4P2(e#Cx9x`kb5-Fqm!g}<%*ipX(KowWQx)i-z0WBp}=C!jN@ zz+2QTTN>DVf1=;FKs3=XWt+PI00RI3(FpM%h#hyb{I)v8;n6KydlC$Vbv!_B!091T z;bpGIm4@UJP_Sdb_u>FCv7z<1Zrh^u{PJ(R?3QKNcex>owbM}gN7Z5i5+(-NS^^K~ z-P~%trQS&fS0Be{IDkr}?qqYKN--@2)eB)R>Za!rPypwJy*%M9w*p?ZHI*Z+bTgNI za8!}b-?v7o-2M5769K-hYwcDZvv5u_oA}|O=JXQUh68uNUxn|YcXJfLxg+CzF1e7 zqh2rD5u$+WV;oPc>+&k{Eb~9Z$U>br35t+#6Z^&yeBUj@8I@U?)wx2yldUhEh50M# zBv} zVr{*;1V$zAB$cHLOcg$!{#7Gv#i{l+*X4-wy9O%L)!6FlfYaPV`Ub$UUjcqD@4gvY z9owZLrGk!+=@x+6G+t+KnW1=qotzS{Gcg*P{hOIepuU&61}sa-SwP8lZl5@(NjHir zW4yh+tp%wVjLS1SPZ=Y#zTI}usF3V1;sX>mhtTayn_9su5qJc{Di`N!cnQ(EZQ%xn z#o&@}v!80coelr1c@-!lFRW|U3o{H8XpynL99DtJ^^+edA)SdNyRgF){L(u{^kq|v zn4U zS(e}{?*r=(UA#>b$PRvkV_58hrNE*aO8bE-Lx(ew~4*pPEvs@)=k0rsPDjOB{w2O&+YfK3N_tH4~w|s=kTQ1xd(a?KW96 z2m=qdhEzlL9j)mBt<0<7kJ&{=GNR>B|9ge>OM*KK;&{UHqf<}}aJobY&CFFXE;ADU z_JhpgOAzSbW(+tS{WbK3?>}&*E!lFc=WD?xp2I?yDAY-$`J%eGAa;_t(QTe_L-=hA(%8B^j3{ z$FzHiC=ufxjX4#T;vp&i#)})9^vqc$_ZuN^eZZHbgb$*3q|Uim_o5mvT2ZhIEx*4htGF4n{`V?OGpStZb%p@Y#WnRO7}GCA z6*|u0oIDrK%m`y@g@oDN2QfC&(g`ec!kn)jEFTvn&m;V7=G)*c*iBu~N3bG_@S#Tg zM5lB%Mzer@k~Z<9MGunqnbMmLJCusIk=sZe3%HFNYSzmx_plx86a?=3u&8%ljAHoc zlIl_5KQHRkM$fK)bTSQ2pWm42+z#oMwlA^{zJCqfA>UAZotqNajIqQo5%l2?$(NG; z@ZRGt*u`ggCyuW5?m={B4*5AD-?9!u@9V=N0iEahhZl21|=7 zz-sJF4FsLY@sjDV{8k#30s*RcW7>wZP=B-|(oMVOO(M;qCEC;%)(?H!|f zwLxj~ypk9|wtX?}K@s1j0lbevF!QH&jwO)6JidDrn!ItK z`}L@L;^uoWf)+-Iso%3~u&p?5J5~5s4bm04z-!gx{QdZ{6+pe($PyYMPkOm1w6tq@ z;ZKF+n8Xj4A2v)z-^22dE)O!C%(euulWl6UqG=vHE{cKW>0%CTbYD){;u9|%K@K7p z*kiA~AcZ$yQZSdk8Opx(i?UXdM50{Icoteh_T-_@6h_&i|Lujd^%YRXxx3XlMhnoY zD-_z@XKFl|>wejVcUJuQ)(;TE1>THq>7@ZD!Ryni~)4jV7gI&2g zM+1;S3i6;r%oVfND7FSHLC}ak@7DTY|D&-p73&_z!uVQ;LxNL!tL{GEIU^?96=XXT zOO)TvghXFD9Rk3*dD}1*Vm@!2069X-Z6Z$H#4e!XGUL1cd%RNv+r3sn2hgtLMV`Bk zM=9-9ymM@$+RD=4s~hVrURTl4cjnzhom5Ztm9g6g3)$RPN5PvM4Rp8&O|}p#PaUnh z?Z;%ygK3Eny7j)LclMk$A)mbSNK37~SRHOKj?euJgrWpfn`9`5*~BT2`~Sv~-k)Ef zG6OkPz;xNQfh#y+O4$0M^I6tPqjOEVvXa`rX`%E=|8Hd3Y{9*#7*wV>q>R?es`c{h zv$g~q|GB?xT_wd9GT0boJ!c&&=tEbY5dowuk=!6j#tjbgXt_l3$A1l!_;6~!7?KaA z>I8FTo3ELG?G4)Hn{N?0p$7rn+SHDar&!_-aoL%0Sy3CXeoA+Tgc?;&G%yC+B>;*Jq_6pIlQGD&m|zf3-edCs_0QJYc%Z z2s!9t4gFj7^wwMgjlhqo7u_0PPRcCbwpu7R)%y&vuDstd8*~e z@j98I{?x%zTIw;85*)Q9u#}95R2hI;W`-9NhCR~n7||tufqC#4edkbpmW;eSJA-<& zWC&0a5IcEfyAY5l%+I8V=1# z-NkOx5E$bsffG&cdnw-f0G#O7! z)AGZ$ob#KnQ}q+TtvwL3&1Yp+Nl&SJKt?@)pqfoa0c2T=NqA^Yk~X?NZRT1-fM)Vo z0+UMC-LI(Z-w^1$6ZK7ACjX?V<m^4Q5L2JpD&q1v(day$pL;iIj@ zzcm)tVJ-|Hn7HWHNM&!r{=B63UUAgCH>@MKc?qfb~$YDU!A0<9Yp@?GF66&hFx5!jNb+6A!ush-fh2v3kcomi`K79=EGW}%;N zxs(gs!|;(^zp)9!%6`hN9k-3l+NtuDrv!_m-r+||rQTs(F)>;DzoCDK+_?d%pyqpH z+1s;vBD8H|2~2HwF`neQDU0$Xswao7 z*G$`t6PlQN(<4{($)uM?tN9KLBkk5=%nmk6*4#}@pK#n-dM;)5IG-0iGq8pwVg9j@ zX;!;zcQ$=IW>GSBV8f?Ty11oGl>yc*8N@2rR^k&A8CDG)sDde1Q!we8mq^^^Us3xynP!JII8kob?rz$SDs5ce-4N{`*U?G? zTdO@$;qHaR7QF;<0009300?0LyP7C2!ufwoNntoTr<@G4#Gq9T^B_>Yr6KpkfQ>g5 zdgbh-_0{8L|4Ao*LmoRILWSz9w(T!JM<-#3q>4?IgSrX~j?qWjTgJBrKXw9ptzMs1 zO!+=N4Fs;#O^qbMZZk*W2P_$a0EDz*qzgXF|6l=Bi5Y|9YG}y}?c#}i+3Dqi^x0f* z!LDpX9i6S%;~tv?Sh2{xMI7OrX|D6dt7(V|t`4C5yMbUa-vEL4F4c-`BFI1@a!z>_ zxMPa+|3SaP-Nm}KdXnMFWTl0b0cN&xau9AOeb4hm((aG99-DcnT%4)2+moufzn0Dz zeHQ#d1YV zE|~ury#5tKH`N|b1c1s_5Oe7SdS`3`bL&hx2EN?N_bzO0taVq0fTho= zuj^iIr{dkK3TXBSfOD#0Ub;xpzK~nur6swILM`gF>SrB}*BO9_Yi2o0RMJd2I{Xz9 zno3jv3sHuu_VcrzM!M(s6^-%No~-caZX!+>8!`AQzhVFQ&nEQIuQSZ(R6@eRSje1? z*^W~CN{OrByWcOD>8WSqq~IB>D2V5^^f!rJ`^otIjogag{9jUnA(H=I>(p{6Rae3@ z0CA_-s#ik(iWNDWF10Cy60qPsEF*k7JWE_X@+JfqFjg8ho=!X%cB*|E6TqS+mVEIP z4$|tlkNX&{m&FkSILmo~tjwbwKA;lO7{i%xR%=F z1{vrsU!`sVVIe`6R=xg~z9s8Kgn06wJvgCO@x(~f)Hmk-;pD5v(>T|WP9eTrX&?4u zI}M{!>pMy$|8kRcl?VhhM^X9vh6NFqe9hs`cu(|qetsBnBSTNpR!%^D#~qEJyHXG( z3+#XUd=;`o-p(*lk)pS`4#(G5{cj#23RLPM{)oXQw#V%-X9k7T=`FMX;o992xDk_s1X)dgHi}jhF<9e@iY((4h1fADnZGDO3`K@DGIvsy_h@^?pv7=+3%S<1@$#$x)}D%1zLRyihq_mnNh%1} zKj9^9y87+X4Uw9JOR%LSq|SH%s>eq*tJQVU>4hl)G|W-1(>%k zHPpQZ!`ik887v>{1GH~2^kDR^NYeK9g7rrxD@o>;-va8%9Hc43G%kf=_95Jxu8$S# zsKF}|{=^6qRT(fJ;^^(L^CT#fq~^}yk+!2{uVxP|`P#Ga3fvDoacQ-!CFH{qbSl(gRL=-^c|5N*5 z?|I#ZXaj;k^L9}7Q_UIbaabtt!-H1qZCB<3eer47TO=>cY(z^xgEHEl5rHLx*Zdz@ z&*7);Y-^Dv4w>~~Z3a!DYK6j+8P&BC-RKVMkE}|bh1l3@EgGgBPii!hVid-#{-qu7 zc4H(@*Gk0s9j_8h?iTbsFVJqF#IUUBR;FzM`PoY{pHA#DT!Rr~p}Asv?=AxHWBu)s z?-3qeW3La>wXkeKn`_QN*<6b-jd&DDjn;ivP@rF2p|ojN5g%>Wj9B3`6A&)mHenk7 zX2V6HNs(Nqf$F_|c?`RhF2p9BRRTFl=tAq- zrK0`-0{s5`j1I%s`F)L@Q^Y3+H~84XNwaZ_?e{( z*pj2OlwtAtkvXJll0RA1Jl5{q{^2PRTIpbXitA;2$~QujM<2_;g5rRO()BcmDS64_ zIv1}8W;Kzin1L-ZvdQ9QGA4IB=^hU zJNyvQ3gLQ+tkZ`zjdn0g!_EO}CTJsk&=rb@GuE+Cz@u)WT{0MY;PJc;i0kd@<4V$- zq|5<#_Km)@zkmP&==>7o!WsYqRR7ue(!a}styW)A+9@V(r`0onKH>my3T`P?`C_=&~JV@c;1Mun;JKLQ9C6VKQU)ZK%l8zt* zGMZLrI>R(j(AtvYTQWQWPguV674q+ha_;MlT>PQn4Uhdv=?YIL7X(NQ!rPTY00 zI$3t~(K)ijk(~A_$b4|Oim`U_b_QKZ$u1h`?LSusD9q{u{c^#eh=CrMP6wGp3Ezfc z-uIUN5X2$N1b6a}n3!afx3Q@!qOz>O^ibij--LwAGB>R!9>L@nQM0w+Z&qVim_1`* z1PO-hAjLp6-JEQ>jblHk$!&Z)^oDouNzv9&ABY0+e>7U&g$j~lzw_$lD}Qir|3`!p zY19%zkNR9X0BDt8I!5^2gJfb4I~s|YT=1>!-X9656t6d{b5cu%s+WRM%oG4VGBroO zjK$0TJShXmu*n!k?Ua|X=GP%Q(BM3{K-B>jw+-Us#_&u2XEOkeQAG@r@tTa2mdLGc zf+ewa_&4q_^fd(StO)M8NrhQY8$3h8SXITRwtzHgHFt4TKEN_ULMsqJo8qSJwIxhz zBz~7)s?b?Wj#EONd+XG6LLIc=9YX*;K*GNttKH5uU0B(T#mMY~4e!M#yss|)@;hHc zs@)uWBVCpt-jWApCvUEM6t^iI27wXmyFX#p=z%Y-fOnQI3G|r^UW5~00vt47%WuUX5{@!l| z!{6Q6;RkFvfoW94E590K7}`V{ZW4qDPORYL31Ga5sxBL}VF~VIC)?$-PrruFdK+-O z0WNZR(v0iWmRfC1ZfUuuRiyCLTTmU+VoxOK zZlw?z`0=xm5ln02B!tHhuuvRz~Lo zu<0sh0Y&&;2b_kM8V=(RuS{I23K&lUVd8tG92}Qx1<*P-AK+5_D_ z=Kk@ep9?KUJz zt~s^dD)1+wz1R~8OPaoAwwQi)R5VOgz}SyNL@Z9&{{eaa^r$;E<-R{k<_<&!QKG7} zr->i!;7^#~eO=IlMGgO1eKtvm^bJl}aM^XpY&2IzS1#%(_Ik^Dx$`;_6z(7fQIQxv zR#5n1;q|;U*YF&Kk^t>o%IBv2kgov*S9XSKU_7B2?RocH_*`je?BGh`OCYxmD(kr* zq2Eq}3?yAWWTHHT@0O&o^_veqY~YXOQ&Hu_D`F-ez5zQUinaK!O|V(Taw$A=AJ=fY z4u7Lhy$I>ZpKqh^b_n@-&`-?5@pHg6TXJ00seJvD%V_@n24cx!!DRdzXQQxeFAXncVlSU%EN|M5Tdfn7Fj=c zVK8GO=e7;0#Is5z0061B13UTA-nlNd=-`S;&zngu6gOW0C2LuUOI!cV0?*Orb^5AP0#-Uxp! zdK>&Iov@uFBA;>zqtd(O!$x{d@DF+g-gNh$0WD6A;FV2`Q;Y1f;ppU~P~0{COIOnZ z2cj-AB5tX-L?zWbeVU`rrqs1}&bXK%FfG_nVEfHDZZu!!l;crX`ow+eMEZu|6%v1k zbNxf-xzqyh3+bM6Ep2War#`*!2tVuRdu&Hy67O`DvUEBxV?CgdlwBianMB~er{@O* z_9-Q&`)EM!%k@BWIf28ffKil&nk=YW&A;xiL41XTP;HGT$KGw~rD-R`!pq@I60xAP zF^_n7au8J%+mn4O=HbYioX3=We%lne=5qE{lUg#9oi2mWAd#N2b}cr%cX%(}6D`tU zt@w@PSpL8-8nLwzRH={r(FhZ48V9)MU?DyUx3yzajOWT8$RA@BHC{~Rmr#S68c2&nDPvD7`R?54AGAs*<%sx(VV}3Rm^BbCu*w(` z_O2-)KGB4&X(G6qDikheNDm(2i#)-HXc`Uef3wrCe5<)rc=-Jduy313MX;t=uNns1 zaI4sk#t4O~j~j%vN(3N)irzEs*fRb@N`{F#+9iInlR^{I;~Ndpcg`BmYT@$LTVnsH{E0eT6= zb^X&rTf~1SF|^fGtPJ$F^ZNw5aU)i7=r!6k4KUqeLB}pFJMVY~rjGp0LV1DVkxdiI+L-7BzZb z*Y+HGjxNuZE3o#2(uo^#=*ZT)F^F1lA*`+qcZfaI0)^|HMW>y+nc{2P5%ilt#u(#S zA*?0bj&ll_oI%FTvRCCaXT`9luIgh0(Fuydi^9 zsaF`X5&$v_`{EkZy#7wPzx@|wWN&M9_sSe87FYFSIK1%nPRm}E#<^hZK?k@?>;^Be z+4ho3)%Ud3flmTS;^^LJ(G|C_7=2p|(E?3b3S@9em2}onXQt?OVCaxmOam_pJPDYo7o^v!0x@-WPx+H05#cjgWHsAmyk0p88X1N00`;t69rdaBX%$VP!V0Vx;1IG`EA; ze`q=;6mys0pck%fH2kM{Iz`ZMAR<+en#&REDnRBNf%}pbgkFUNlhKD}uc%ROAe4J` z9Pz}K8=qG%O+=%1AQW3k(CL1kv5aRgK-Lo;C5rj>6y=TlMfT+e4pclr<0I5H*fALF z!a8&3IRL%tNWRH7;MO3%Fjo~xOaS~MPM&i{^9&(;aS*;)?V0e;G^I7HxULw~zeK{2 zsa2QGgs#;M{|TjyaFK=|-cY;kb`MOV%fc(wZjN}MKw+ZzPlx@`a^zrj{ue!Ol7e;i zzsuN=^CJ<}+ZBho<~N<%w5A4E@&nj@$RLj*^||aKHi$8Q2M_piTtF3(^A@?rX)q`k z;+!jj*?=(j@;! zI?9$MDJhXD?~389CcI2?TS_~6f2Fk6mQqMWWpEZ0XTW^Ok>Nk5EB$KhL#*wRj|PB2 zCLM^PCBE897%eNOz39e)(D6Q2_PiHv7GqU4^^fC%a;5Rii}=$!-7STyw8?o~ppNy& zz0X#F*&1P6+7@jXk;{=VyYKYr-ew1N*wab~o2+hm3zX<)8NH+o! zv(zZfeRnTZbj>Q}%y`w}A8hH)NrA^)dNlCp5#EXDuBWE|e%r>}7leMBvo*7%daNPw zxyJwWBI0UNR(G5{eV#GxDViJ(nqP7hA+)*z>2$8LQ>4Vbu>`Hx(oW(Qrg#Yv%Em#; zu|JhCw)mo{n>`rt44LJk;qB@ku4c5!sVm6}q{#J?&h1BY2rFLEIJKxFp%(IAOtXsQXgVwQUuAxXCOOI4cy=;0w$qu9A#f5P9>8lElUPcnJ#jqa zm|)U%QFy*n*ZWbWtXW5q7#HDWp{KZu(cVgKd`c5RyIB+X0iRxYcPxz z7+-}3$gV4j>ZFo(L+QV2H(@-cm*AXGM7)*Z(!`ERX0m8BV})X{0PCS)1&-boCclQ( zx74NJd=(Hh73UCtdTt#hAXsn8&zS-;UBvv@V607)wc{-PxReVKov`0hgmXX|co$I> zT>dGQrHjBiMFf$0tc36g#M*h=gF6T{@w%=fI8b|CdRqoNSefyh?gQ@L;0=j1a4*-R)G5 z9MGsk^tZ=7Y6QbX?v5(|7ub88G%xOB< z{lrO5Hno6u-$gH*$`J`kvLn+%Dzhq;qx@vAO2iKVqLM?E2v>FeLLLc37=3>V%aJ6i z(a2pNoMIsN8K3XUK76)RFv}_Y>2m-rctE~;K}WbWeEy3kqxf>D=QhicX0()Dn08?|S4J*(>mPPvVot z8uLeR5J@wX6QZ&qn*g8SI+-xfcO*epTMFK=+N7{IqdtpzRk9YMU42T0MGBP`Qo(J1yv|%>Jo;gF16HsaurQ3q({3h%WbvRA0Eon-4LJI1EJ(R@U)ua~( z^{ehdSe`|EjN+THTz;+2x7E0FhnzV+V7PuDQoLt>S~YK*$n$%iKUvHWN9sJQW$gbC z$l&j5jinq-Dpg?zOMAU=)1_$x$*p`xVhM;kQe;7N#MlRjOqB%NpjPi1rT8P&Dhxv* zoSnD}CyrLe6JyaF0bJQWGq6GriC9ii_${H36K##ug_xw0HnvZfnXgmwBYV?7hQS(Z z;yKM`fkGSBA~J6pJg70SUD6{Pw?zXZnSSU9k3CQ9v0=LisQyh(adFcSUPHU@A#dl%*79dJLWKLg2ZKm2p82_yly!M~>-OM=aHs_a{SJ6gPqB%_d&vKM^P zwP#_)HQ%{Yy85@-QR9%+H+epDFczs)DVAy4J4%3<(}Gxb-zOw#Vk)bBuji}J`u+{i zQYK8;1!su5sD9X>k3k~y;)2#mSY)D_$xAyRzByaBxLVEEaUwZT1eOF<%VHU6%b33E zaMKMs-5Hky@Z*}9ssiK^000958g=jlj!dnw)zsU!Lks25a(n{=)5u80|NSdh z?IVH^SR!|uWxHA8CJDUtd~x@YZg~Ua^x2U_n4sg$y>NJGV>c=~QP|T?;W$A^q@OwH z3}@GpC>pC)R`-XYmsbA%uXx~@KgXyo+ke6&&mCNhjv{d7I6}WmO6_o|=75Dd`vJOL zaAgb){q1K4Jlec@HyUjV0H}l@hJ`I0 z@sY0N8Zmeg15ManjXD-!pquW;#^$X}2L)uX?Z8srsW;x{L2C^WQn#a?q#N8d*y2*yn6*5sULH zATb2*`1f)?hfHduss6Egy5+oNr*$G!p~VNEyjl)^tk?Dgr~f8M*w^7WcD9aK=)cZL zIEn9ZFz*(Bfw9<<)1dcwKTYp~n%fMHP~Pff!91 zRYaQrov}l19>p!}GDbn+k14JlA~X8!?-0o$djhaUXtL@bGGZ>Rahx1Mwk!#49v43H zIMSGb7Ifi-BXw)P@yHShuR&@5Aen$pfd0Tkr~nwt@GW&oea;mq)#>9{MA%xPM-J-2 z{inJP0<1Qk+()qlNR2K5IF*8vZ~Q;xaTuI+YMy?QK~ zL$cINzDa&Qkr_enD%k8AQ8O4lrJpT3EKGwp5r|Ak_)tDIeCb9h3v&{lzQC#$`iJk2 z1M7t{S`}NE-<|6C?i1j)M?YGT8JGlsS5SGt1i3-%CK0$CX%sRItcK9V(Pi@Rnv0pD zpq{U&SZ0r4ufums|3)Ag6L4%lzt@HQne-SEWVWhd_9@TemT4K>jz5zj_?fc{`kLY_5OVM1fiV7oKQSniaAfJDh& z6jWta7=1LZjhv9a;twxT+ z(H00#H0GW&qnL2IB9O!(W(3&E3KU(08JUj5<~xSm((%(!$pl34I1B0<14fI==%YW; z6d8G<#}3C^^bw@!cCV*y%a>G_y6YETxwLjSegeAHd2*1#e8phjGCim$)$JwemB~s8 zmyQt-8$&O5`$D3gwSRnbXj`ZJpLR#mh&Xq~@_9M1Us^Kse#Tk2AiKXpo@8ngf}=Hg z94cxG@A z3#8un;`U^gyR105WiaEDu0+3wk5+_EIkKE0)IcV|;t+|6A{}64?oEC27 z7EYQE{V$t5v;(wHTMaSHjRHT}&4L@FLZuwP5No+*%K-E?tDJ83!QwZl_Yi0h=$TZP zwFHtun!diePEP2+6BAmKWWhfUrvP-R)JqpW@??J`0QD(g-~e;T7#BxX;5a2A(IzpF^MP>j=y5*~rVsO1-P7VkI&kyGtX!o}rcp_RQuGQ~ zzl)hag$-E(7y?DJ{|bia(kJ=J=mbfPR_8c5Zi24|OC zUYfp~$}xRXOgRi2Z5$np2dHs?J=Q-2HBVEGX_=q$RFu?BGga*MVwIWRs930Kz_kxR~ zhlv?W+M~+7?XRM9XPtteo*VpO-Ne`c{jQQtwIAxei|8nCr201{#V2dfS(zlVv!Dya zsH&7cZm1#ZG_vCAAfbTed$Gb$6Ch#aBth%$^GRsmiNCFa+U?_XQ{FN26W2~cG_U|G z$jX2&+jqfsTK3ci_1AwL^S`Q7Ecw`}@5uk=k$o}^^mgK1y!=!xMI*GYM)#bkzOK+X zR|7h%$$!A~@q+s;&0YR&(m znIxVZ^+#|x{#?U9-KT2j9^~Iw9|Uu*)iJZN^VLPk@!e?@u=5+^aZdk7TIe&00QDpA z>XR214l8EAFi>kkM(#4 z`9`hhF>0YfW0l1Q1>%hnCgbd@(x5}(7XNss41t7clF|_%KqUliz=W&x z^{X(7ByS5}8?xAXLAa?sn$O&|rYYdzl zxz>t?C80#1_NvR6vT|G0L=3eDa>~^t4`?ZJeaAztwf}Cw%1mDU^d=~hCIYH|(BVq? zmaH6CmWzH(4=_>t$GC!%jW1uZs0B&4ZAz||9l}@`xpe<;_c3&L;P}ZzxPDESa|35y|0U>f9G)xBh|H#aad_PzyU-jFHMK=OUX!K*A)#p^*;} z25&dRCQ)3KrRrlH^U>ZGsc3^Dnkp6coiV$x8M(IJA9e{!d?HsjY!B3!A7S-0iB2o0 za<7e3_gZ9Jq_(?1uC}SGWGP@6#lflJSNx+GA1?P75B8@TDD^@Tmb@jzKreQE4Qcho z2xyGS;tF*}4oUEC&_+k&1EqDQh}UdTP&B<@&0!tXOnI!}U22t+7s_EmRGVoX(O&Y_ zn93Tpj)ks?yI-z8A#%z@jvARfPk~eNDUm=fu9T3HAesL|99xzC+}2&9UxSnt2%nq4U;iqzu>>Vw+#o6Aq2wJ<2G32yD@fi`Of@q}2eSDhWIy(Nh}d&@ zVk20%1F@dQPt%#x21Cr|Y)iOr-4+IYRQ_CVET)qx(ZVMaZKBE~&)N`J7AbIE^=(#K zse>;i@*4#;pO@&3NafH7|@-BZ&|1ueq%bQ~#aIVBZ8v)$N;xaK6R&*6l;&c$=6>01r7fn)-?b+}L4 z*D(RPHsb%Kn}C2%O5lzt!N;nPh55=Bat)z+^b@3aGwe?MOX8O0rBnMainipYynK37 zcB37RqmoL)tR+J`mj$t@QpdMvzny)rn+35V2AZuR7d~;N=B8))`>8{B_Xr0zYPG#Z z!=7`7?%fhwMXWA=Z? z;u;_5iQ4?Qvk<=DO&Lpy%(0I_%H8fRqa=mC)=OLG763%_T!?JnA^hM;yOc{Skv5`F zK|EN>G)A3($S&dJj3;++xR7?X4g;$M30XE@fN(=L(rqD4l?#8B+mcCv5Jh;D+Ssp-2W~ge1hy3Zu7GY|KGUCoCevhtQDD4!f8xB8LM+Sl> zmrdaaao-N_QzVh1#Ia>X&XW|l&B;SKy#yrW1X&a9-mLq;Xh||7Q4t>ql+eUtYBFHb ztz&l-g)}=Vm{}iW`BdU>)#|HN=liW zqvF18wx<&q$RkRx@g-mFcCbnE3DK}W01v+Qkg}sPW3ogjGu+FJa0Evyb(*+*Mm3yn z9eOFRzOq&>31pJ7mYkW^YB_kvZr?WDffG675QIVx+ZdYEJe$;~1-v|gkY4^yK*{`) z+a9n}0r+W!xA^gzB;rwtcqH5Su6u`(vsGcD0rYyduyD9IO@I1naBywCFIXC&00093 zdBP?P1Pgb$P}SP+5@#u%gB!MX?B#t%EYQr7h8kqH+6meq{}6Pso{BAte2xAsd+L6u z7uWP(A*pGgT9{^md%au#U!_H3GbO}YoGAApkF8!q9fbhzxTr3aZQC&ZGmlRwe`0HS zCthM244Wkl2yr-l>a`tT+?rDuv-&~10fvfqt0a!Ojc(A)QRbL0051Vpqe6XxZA~HA ze~6*aYss;t5g|x+4)5Nvjs*XXJo3$F13KIPkD@w8896ZSdeczCA5Q+nNqW9=;qusS zr|SM)XYPWP2LxM~#gIb}OJ=)>n@somnEP_Jm@eg3s_*Y)s!@80mm^Y)5iEQP;F2km zoHyrSP}k1k;VLt3`(IR^?EbdMy1xe)&jGsUXBM5U@z#L*X}GruGh9P zIyN#(ixYBh6VM`NPTwKH0Pr^Pq6M?lWF^ZVp9u;fPX>>(oK7n={7VDYQ@j|Dtroz8QUG$y27X|P!4d9asG5)WVVNFQE^LovT=tJGb4 zk7OFo_U9xi)og0;&=@QK$ixuOy@2-p(zl6SZ>TVXw}8OH)z?_{0P|>me!d7C75X6$ zo|u>kjYS;td^wDljl9{p?;h~sjS#P?A6}}Ps=8uH3Mm42|11yKI4hBIu<>k7OmQXY z;SzdkF4#!@19&9_J?lIwIABi6c|OIkV3QF57X3R!jdhe&(z=8w@>{He0e_0*`|B_wAuH0oNraO2 zt9cIt#>}&3yuoT=?f=V_xTLi4PcB|=O0Fl2cF1qgN=S{JR@{6~dwZ^GBZ zLqJwy;0>g<3B9HJ0!_XXKAWtiDoC1PrT7=!P#l2tR+qWW=je=GPrx{&Qws8%{#HhJZ@rgQ8&gC8Wn1P7%4}_kV z_q621(H5kT;wp#P{djFGszrt^@<;zG=3LB>g*bAy>#4aLz$ELe!4>#A3@%4&?cNjt zP-a`U(+lE(?Rv@aUEI>+G5~Zrxw{sRY;TFL`$F^~{TjgJa#FV93rop3=ZcY|gaFNu;e_*%fis@qXkJ+@ooG;UQlKeUhGga4*Mq$+ChEC5IC5M7Tge+Engn{=>x0lLXVDscmuBbkraJ{ z<`-(xAqECrq7@lhV8A66aNgs-KmAslhWEyvM*x}!j#x8o$5P|$h}WQ^-4gq&rRV{v z?_MRkm~$dNO7*PzcU?Zfs-B&&&ivtV>p9K0$;B0`FZM0So^E{Wn172Xe!&(3))6TS zjn8N}9piec5gG(?93U9+ z-S?R(BCB^_CK;!pY29WwxyX{CM3Ox9yB!@haYsVSyL(4A&0@)m+@OaBWUk4~Z^yQ; zx~(+ez;~6Dy295>+ML*ASBFES^d_T7x34c|m24T#Q@lv zQR$dSFyshbexAjM!_a)jmtULnM@|1HQUc#*lmsn`8xespjv>nQb6}ptd+7r5ChBEo z3!5lsB-Uc&9Isb{b;)#GWXwjLdVjxK44RbzG>Q_~*HmrzDb&G#DG<|e%v&Xa{hg;s zN~#nxAb>y>Dixf6BHf-Xuig*;{E;^#@&si;%shKUcqjs>QEu@)t!g>&)Fq;Ev}`t* zN2fpl0Cne-iTqzie-h+dH$CA z2jZlhTy0#}qpjkBh3}4d-*y+g+ZhY&-HhLVNo7~@bu!t8h5frko(LSG3?w;UXfM*4 z&nD@BL*8zVUEqVpnAh|EmYhYy2j@RcFQA}_`J^t;?V=0Uz5FTTBnVGlKJK>YSsSJa zoUuY_0H5{VUu2V4Hx^yJxnhax$Spdb`&2Hv>>nM4Zug-bDWRN`*y*N*NkV46QqzL+ zX_4N}L5AHRg#f2Nl46qXmN2^}YbNgyErup=gs8B^lrJmWQCMK*^}-bkl?nA8(L^)3 z6Z3Hd%(+j^XI}u+9OKTp_w~YRfI>zS8+0vwcx%$9u=gz_{j6~`UqBn5)AtniIucm` zW1-Trp@im-(M31^CbU)|zBUvDwgGfM4^Tsb8)SGx24nUG#`vtwuUJ>2#bq$=p5?=C z=)E5Wh5PGG*`|i1E`^;VBVxMtqvAu#ULD6p2qcK|9*UvnnBiw3s}J`Jwb3`KcC#&D z;U}X904ezXXLNCgo#M7UVnpFlxppfM9?8A7-Ef69Tj{Hal zILs;^v{<;Q$cpl`O)SDMALOa{({MV(%b#@3Y`MQQtb$H9yVn+F=H=JSO0wy8k@pOR zoYs2F>5Yyn7i@1`We3C}>SXxB)GkRdltCS?1~h6HMO3;;)=SR!2J<5NLh~+{i&B?} z!Oy%xOq0u0T=S@P+03F>4IOrc==*-J3WlxxDBoPzs=x#_V-H2nWCrG9iNL*}Y(X*a zjhY>r!H6b;{8q?o-I^e-$HED!dfWywmPHP!h-|cP9;OA0eYP~^bVH&6`6r%hLMA}}YqSM)(*t34u&g&MnA3sBF@4GZ(~SNm^Fo%7}K+i9G9 z*&)7R!UtopO9!fadbwYu+p{-e!~Z}TkPexd0cZDxCm_VO#zsSOiwA(tnyI{fj*p^- z0lS|ftw6|RK;Q~5aQY8YxhGqETkYf_`Y=szjQPH|BGDAb*4*m| zk^0A)b7-^klHBh`U-KKlIOm`BnRY&XX_i{w1@TdA&03WBKAWJlPy-A@5qhQ9W=#bX z%@#kad~Ww4#okEeRii6x3BtdlJgGGqImE`+=|5Rv@j&8s+Y4sLOezF^3nGN`1Pl5d zQY9S6%6W#bkRKWL!HnjHJzOQNgU=GMUPZD)q!>t$8F5#4k`U{}92^FZ%o^+;Rx#0+ zFJ6_QZ2RY(8dHup#h0;2{i4M*U0(!JxN77;Pk}1jI!fn?83|NCD5dA}O^XHj zijmk0e1hz70%wwOeHEFf1f8y}+h?=+ptj)oMr-}(-r-)#!MeA;aya?>;?d3@^Cr~( zUAX>#AZ~kQF~;!+08NLR;;aYUA`O*v(w^=1!y_OY017uHRo|Z*`)_Ao_su%qekrxV z6Y+;39M%RGGdgtUW9gO$>Gf)Ml*{3>5*q1rVvcO&zwd17&~x2iT;r`QT;Zh*E^HMQ zBDJ0FWHm0OzkOt2CN#X=IH(<_e0@{oF9W?{s_mVn4AIvta&H z#P(pss~E&)F5!)3XYOSjSCVReO1c`AmZ!WS6#1+`TsNg5Y`BsMBULO+7-GxlcL)fq zXL!EW96KNKr!>f0PiPPsuuh|bEWJ2KIVF)#_HWjYU?uakwopFPisA7=X%VqM4AhD#23B)b0@RKEea!lZpT`Ol&?JG znEm`#bUexZ&_Cr`^E}DZA;3SYzzUUuKa?$_jCW=bF^J>+JBim;hL%Sc5o6Lkd)FwJ z#mr>zSd80lm&O6{$pu6@N=L%Bh4iW~T*DlFft5s9Uu358X` z6pWrgo@abLK!x`FvyxaztDY?O{SOwnW>g(ut=76)Hk-=Q?$Ru{6?E44x9EZ_H$Vej z*rfGbXyM_Rbq**JO~T4#;~(71OM-UUi7>sZ(>p?S+n{G;+ZJGkhUDIKFDWwn8N<#V zvTUFdTV*!OWBQh;S(~19AQ^#m_KrYC){6;hI)B^U+?bp!LpH|wZWUC87BOM5_i`$l z?;MwwM*}=maA7-vhjCLN9z8YD_szHm6v6_iJtBu(fdl9*D0kmL6~9I*cZ;VykmhD^ zYa{g5XCnTt31b@Nhi92DH&%$k3Mw9u1;kmk@>+8*y~zCONCGFx*f^F7ebNbw zL8@WDy8)$Y%jv74Zu5$fgf$#Eqg;-qi;@|Vzw5eL&wDhB94~X*bi#@q;xi4A+KWD+fiG@HPbXCMS78 z3XdUIa|_^!T^2Wmc)0|4=|QK?gFFaRVi>xNbm6%2j&fom83)g|ZmqLqZ7B+ZqypbP z4z<<(yEbk5|K3~=LT$4(uLWXntHGtodwo4kUrFCQMW%j4CFCWt4AH;6hL`Ymp z3&DgASzQ$d1^ZPbwRXzLFKZph3%b|LIa15wpqr#WwRibD-)Y?cJe4NyZW!M~U@?!! z)7em-M_MkGkrsskKR>9zr$)c^7V6*lIik$`)2M6_0d%MnSo&b~w56FvRa$L?^Gkw{ z;)+2^@eX^+-0gD8@ZAvLoW#@!^9Yy&$|8cdyoZw3lJcjj{bwX;s z7WDuHu$W$3f6jo4Md#D?tgf}+5rFU~;9f88zrLUje-uS;y-sKcs&J-TyHS%VD;2b4 z;SBLI!os!Xh6UP9&bgx@b)_o`uCd`z3Md;EXi%dCyVmIo5f+#2;6{Wv-sNtzGp118 zOwnH7EO72MR>vq3eq<>1i5^fIb&UgnUabL{7)s4-2NE!{SwEXJ{XIyFI-T)WMEY{_ z*0Vq?!=atDHu~3!_HeTY?4lZ}1INJ%+MIMGiV|Ip_i};x`(Z+aDSV{4aT~h#a|A6d z5n7i4hIW2Y;xK+s%VG<&jJdwvXiC^sw%w#&GyfLoP| z3J#=#)8HKg4qR_Dr^r*sp}G{8NA-K)N9t}gA#9I$bN`ui_48ezcMmMDWWv+-^KxEe zPLk~NtL#BDw(@_Xev_$`9XeJlmNs$X zzChEBB-N`VkQDSNp!wKBS&~f0kN4Xatv6j9sb39h!eR-?puMSkgO_fne|1R?_+9EQ z5XnfO*fk~E{KAsav94v1HUrM|`9vnq|M~i1#_J0-s@EL=F+-H-7HHQP$TbPQj zz=CCf?4UX~hK@jl=fn45qlZd|)o0sMKQDx8$v#}*o!aZFp7tVc)mS88T8w&wT7}Ba zi8R23?k%s9j#P&EbHOxo+^)#v{UllXa!?6PzyJUeqF2UB)Z%On3kk@EdH!jb&V%yd z)_uMU^^sjZ1EG|IGTLC7Dj=-?)E+C^@7L$F6xLWw42zRL?6Z$|l5<1&rtb#l$B2_w zjX?NW!-cOyAy*IUyW)@k^Mz2`<~h4GwyckkJQt^I88<&iKZER&519CcjVGYkh`VYV z-CT9F&jrEpMJ2wfoOv=e!|$f4H3xh$?8aZG@C#kwY;xMkWcUD{0IOYpQFq2%(W46| zycDg=$4k_CX$#h z5YXMkI8TnSBodkBTwlJ39dCDU@Xvr490XBHv<>`xX{C7R`RRQq+!2W9wBq`O2GTEQ z?z{YT+>ZN6(oTkq0s#GvL5JxxN7Cq7Sm*JLHxD&A&^Wut;4hebXT)tB;z|4LURE)T z-_Y77zJ{skc_JEDFXycV>UT7aL%W$$uJViz&2xjXmC{@J4g$ zWn4skq-MdldCS39h*saIJn$(i{*))jM_2UVLz~E zosKF0oOB;b0kix%TQ0I63g4OgOTCGrCz$cCQ3mq`1bCwuxqsBxwb>{8MMlntL{rdz ztQ_dfw8_>r-xJ9rk8We2ZPi>4tGQH_%2~2$=VLvVSSUYh4gu8~HOAlh_UAfh7g>Yj zgiyXDYqI;6Mt68~anX13=gWVBo6TI%_zT{1-3d&YV7XVkdnvfPpV5!r8q4K!#Z8(D zAVlfOHMohC7(;1-zoKyUfFgKZTJ{^hee_;kWzCYk5(Gwx?7hK8h-7Rtl!lNq~ti}SH@=^~z+>VQS2$D5+r)sde#4Q=OB9GtxAOXOGUKFUXkgFiZ> zVs4}D&t6_9Q>oIiCE5vS%cv(c8d^z}h!EMazJ7RE6zqfcqan7)Ye{(ByxNUzGt+G) zd{dMSD*cmUovH7h{3>NOKO!~D|HCoQTjP3x9}pkAm%J~5EW!ujz(h*Cc`keQ0Ri{V zclz-3h6HD+sz>#ew!p{y*t?&iMo+H4eIBCHJD5HfLaKPXiR1#T>`4RCdjFEW*Va_!?e9Cqw?x)Cto}17p>? z72*PE7AE!gDI^V@SbIT8_13j~8mnE3d4OL~-E9dyWt+Y+4Cl`$9Tp3Q_~BJ`dOJ<} z=?`p%9#b>H)LV!nRh9qh$RSZFM`_$}tN$J8#bsN~Dtme%f_Gz=?Yt+Ksr29hk%iHkHq(ev$zRAQ8_5H=d7BWBF43jk zby_qiN@EMe`!`I59@sT-q&@BAc%Z(2ybO!M6ATJ(1 zL^jkZ6YbO@jmAi{fB&C}e$zqFVw_N?Ib)T##kyl2S|3Vj5}yCNsA-D_S{2QJE^wg{ z+RLudbi1JEV6W4V4u-T^U4cgsop(#AU4GQ0TZR<$$U2ErXryMy5Rx?q5jC)IStu<^ zW~VGx0>cO5!(G&N`86R*wBT(ocdq}`IWCF{ zhcK-!``Y#eMey{eYBA1_B!Z0AgbxAt_!cz~NenBK?&qT<$@x8t92qQJVcGU<7^*&M zI=nE>%h|vPGH~y@C`vE+O$X#>Q?lgy*<9?s${<^>UK*?lsRlC408Bu$zrm4f|6jJc z?6~zLXR*E-L6};ehMBo0WlTxok-~9d)+6I~)9nX3C;}tKKg;Q)RO!RBukabswB=dP z`aUW*u8^QM8M@}uFR>cW%Q54;c(H~Fjc9g4XQpU{Qx{Y6Y^O+n0&Qjy;yAjY9;@IY zf){p|SzgfgXI7+Z29C(m4*gArDnphX4hb*eqY=BHAJp&=C;fv08%c`e7DvQdn?VZW z)B4yDlqd@}?rNWQi}>kwj4C*LP9a&IijTgkJ7-}CoxnSotzhrdB}F*m@rGsJW-tkZ zGl0U(6CK7;p7z6(3c$g%eMMT?CkPp_t@p#WZie$Izb&XIhZP(uOn*}H{wUjRWY>1r zHkw)(&3pK>tt&2c>A9Otdu%633utQTlBLK~ZOjr;p^e$}=ss`V<$|V6;2KJP2*}V7 znBtSv?_L%|hd`B?1t%9lKhzpzRb%_yrJ#gP&7-APxmB1%zv_<(k?Vtz#EU>2>T+Te z!Qi&V7}FyjQVN|C{e&h#MvCf1fWai;f;t_Ty!mD`;M~tM8 z)sx_x3a|Q8ghG8I#k#XCP06Efl{%Y@8~*+%&_ZhiyX#{|X<}RJT-Q7lw$)zcV-l0P z!ayosnTYO?@@7ifsNzBvv@2Y>ka2N}rL+qSw4A|KjyIO>6|mAAPYb zNK8TxG)4gntNh~W16q&2RQhz~Sx5i{j%f&GV{IEIAi}rR+_E5WtvngykiQ|q`y!(f zA757F7P~MG)Z~|W+Uq?5$%msNgL<#=QwqnU*AF0sKsMZU``yiwK%No*C!*x&HS0A3 z5lu$Mrw`ZI6$~sg!H0>SC(+uTb9bAWHm97O|M?``5s+BQl(#C?7ZDvXZmm>y_ae711fVwt6OEwES8wp}gRuO4rbI2E;#UeMiH?NikFP&KiI`7)l5wyq zicKkFuu2@MOwLgv?6?OPWXQ|;41&IDUqu+IH1{V)z|p;}tgG^}W+5cpN-m3Plv;au z8TP6~4_bWlqj<_cqmBKd>ZeT#Q)Nu$-g*;UZsI zbWD3GjZiEfEW6Kg3=9bSQB!q-+KvI)IF(JF{ zL{#lkyI#38^PtN+>?jol{SGu+u~^-6;0DRBjMr;ibL*+ExP72wcZ z)=vTRHFwfs3-0V}M#}p5f{rIe8zxvEwwqQjw*atfJ#(8(CKCER~oCzr*p z@^=S@(GGR)@eDey=1N*DFYv@C%s;f@Jy{5Nz}MtJ164mN<3m}kJ(PSjr-Lrz_wC^eL(5L3(2kcV6UoYZFev$N;ML-Y~VI z@KD!Z%j(wk6Cc_$KDG^(a{v=q=5T_KPumDdq_jqGLnS3w8jJXd@imsScq)5(2(MPO zCpaRVC|R<%)FsEm6f$+_=uMGSj_D1{5_uLtuVPwTw}8Q>X(uZy0m$Z$SwsARr6yp` ztEIe1i{o&z$4Z!&%Lor^IqJ4v*Y+)J3{IU$85rJrzVz410q28O*OjbJnM_yO2lsM= z{fGNVPWc^>8uYhpv0YYrfADQbBDCBW9cn#VgITkS30V1Om!A1t^i)ZF-!Wdo&j1sV z7e;Sv_}tm_^fji%>zs1C37Kb$)0??wRsbQ64g8}kJ<*FhWt>)`CLyB4>TMKwA{<4| z8iYN0f+|Y4v{Ie?OD(dtH#IE`0@qGNK8G^>h*lRo7**}wU36a(f^+jX?E9CMm-&i` zX)fFNQ+F(f^XuE0w?!OZhS0zkc+F;&*W9&vpVgP_Eo&@G&;SO!sPmXZH5&i`0{{RS z!c0=<^ze8eGKoL=FD>zKnfmqq%tKd000ideQ(Sdy7f*hlxf@C?t(sxyTS$`;1G`Jz zf9Z0*_FN*B(l(`pl#F>HqJbL<+~pmvA$PeHQFp9r#sjN zK^)6^O;1}u0?U^aVo{!*#H$b)rQ(@_6>mOap~jXp6Ts?_U4d9^ zNo~E(L1lQQJ;%8vTM{tL6&zH3{fx<`iPe=Nt>g;plh8Fn1a*zq-5x)PM zQ1dSqOcIM#SAlmDSQZ>9b0KX-uCXfqbDiQDKCz{aS+LiT7<11?_5(ReonPFEB7QuR z3l?4#d$b7crx`qK!!1$uTdnc7+BYPVJGC@(xj7x?_=d-@y)xEI7fCnk#4L@z*gM%C z6mzLJ?dNf~;MC+DPTT)xW9?fuWJu#fu zqtO3Rw$i1`F)nsRO}d?O*FxvN;#Hr(@C^0=U2|gS$bD8ZKG5A}6Qp14gu)4#xiLnd zPIsM?ffS2I1VbgHW=MwQ+Zey}-vwq%6zofHW#^ZkoZ0&;p&^b+NO)DYFdk2-9Ry5` z8xD+{Mzsq;KZv9iKq3$j)wY_xy(HSPwwPpR=OEf@GJoYJ=MSZUmime_Q^6gSa8gL# zwI9L+;Me3qEqf;#>E?nWLP&!lu>=+*472se$b>x@z;=cF;jcsWA}Mm`)CAZr_u~>4 z@a#aUjCd#R$-s_z?Uvj4-M7UyP?8u^h9iH!59$GTeFx2iikI%S~vKU zc*0XgOb)_b`4Lvh47lwV-YA0`;QFz&NVWY{Vj3Nxo!3x6OVztfETItmmt*mUk8nY+ z8uyUS%*GVnKMmqI54d})ZOd{s6tu+2F$^?N9D_SuiC2oG!p>tL|!5v#6DgP;;PkL-d8Ck5Qyoa&FYfnlI*i*(5Qs& z<-tb7HQ-O-q4uD87C`!Z;7>1#MIphm=n);MYXNGvBu}C@c;a#l4|4n7Li@rih{5u6 zXUDsd&;F=L={huey`~!l5Hg=x920z0bf)b;kR~NY`ZdgiTaWVai*%@}8=yNb!*6{2 zEF0HS04fCGRi6RN?3Fjn z0L*SjLnW=o4DH;V(wEH3(zZKS(}0VNvCFL~tTThNo*r3mcd|V`llC7_YxdGNk-$*= zKUG}J`_&jCSqR3k;%rt3P z7!)SL0cTWcZuchMJyz#-o>$VN`~aewL<2hid8sND-$}DcrR!i;Yd%V+N$zm!a_% zFZ6vb$5e;QavCQK6z!W#n%F^gMJ}svb}Z0UKS;0H+ar*qEV_oxda|(610o0TnGS>w z{DDb+eczr}6pPyaFVlWuf;6NTsNsU$gotx2nlBt29bL||90cQA& zL2qdK*h7K(1hh1d>@-g<*&#*~w$?)Fb9z&I0_zl+VkB06Pz@(VM0t_$<}f?paYyWq4)j;KlOT4Gm&uP8~3mg zG!@F=HX5NQ(=f-<-k|q)P(Mn+4cTkdub=R6I@YsyvUr&}4wZSL|0BTezo}aNFq>Le z4c-5`ls#MVDA*k{r1c29&QEoFZm5ypZ2>QOXpTgg-j$cpQzyC+d90 z^655ubD8R-@Bjb<00A9KLO2l`ooM)tONt44@E^SKzvQcyY0LOelkAP)sPj9^_D9>M zELIP<4*%=&t$?q4l1HYa){6J`n?pn>05Pwo!ksb^Nr4ZY4&^%eIf;=?zZQ&#*Gple zKj_v222_qS48e?S{g;JC5Xf-2<5T-!nRkVF@bt0%%l`Emk}IKr!4&DD9qF6!gXV%u zOj1xH?8a{>dD%uw}<|DH{6f`klq;?YTRr%bdqMfR^s8iLRcBE4_l(pGMG*^X!rNW(p+>d~~92 zFVWtS44QF^qRzYn*+(=}7|*J|c7OmVh|_MWy+tMO&@puJ-5RZXcWyv?&r5aIxYo#I zA&v4BW-t;ii(V&nt;guldx#Y2yCP&HxklKCdkf5bqfiza$9E4_XzO!?*n73iLN3fJ9DzSqL1Cqhh`^I%Vp0J)r8oms>OXglq zejAY({}L0@dMfaRAQLfj{HN#Fa@xPV65jA6rFk)56d63|YG$RR$($gpDA@PIJnpVk z2&K?H`F?aQNe#H;0-H@9H<`jzmi)@6-z1nqKu$nx@q3#uXXPXNyHL->sDpp`bPOLq zlHkgmV%74E%g49WhIj+<_RQOfUtoY3+}Xx~ZBEd>@z^MDQ*WMtfYS+I&irLFAY9+s&$Pnj`VFc9PI8P+{izzpIc;F=z<1aLunq8=)78t zlrpPuBn8Dp-`syhOy&Z{M?9FuUZ7n7!$qPL(fvU{DKcbeA1eF$zHMK9itk)?N zIm2Ff@|G1A-ZJ#cix!G9(h4mxzd^e@on2Ua{WvbE53hs6pP9#Gf@_8akoeK746C+1 zAE=?~K+7C3I4&_9!M1hD&9$@NN0XzA%0?lE{ab5DYT!v=;se69NIVAAGNquWQOy?o z>Bu{uJqP|aS=P4S63pd_k;d7GQHY3e!%Bzk6%zG7;*=P(E{W za|7i{FrNemAu{x^Fk{Q(xRKcs+`qJ^pUZvus$?rjSvY9GDv6|7@-6W{`4OY$Grd&Z zQ&hnsn~F@QLs#D_<=gTz-K5^m$n!SBEeEb}ZR{L+ntbgICK-o&AC!=uvv?(>zm|m- z6|_5=M8xhUHN9S8q0=r54TV<5?Y47z+eZ^LA~FS=GTHad@N+)BMxJdv34*Sm*(VI^ z!$QU`n-4si?U`}D+dux-#B-i?1FZk4VRk&JO7sqCAEI zNtRj3C8hUe5e}DIzfP;xp(GUhEn~br`mnQ_x(ZD%5GH*5z_Oq~Ywb^#d*acl>3{2i zxchuHiL6xdsxm;|V;ZE<)D1N|GPxi~Lbjs=q#6bWP zWZg8;u-j!>_4yR)<+rGaVi)m)3};zCXV;OGnb(ns2~+FEa-SHg1xuEI8DM%D5z1Uc zZ;OzX;vspFlmiKYxGL}$VX`TLd*8?Ef);^6-j52&AEK_ETrSN5vrySgOk#Q**_Gl? zm~!!}D@;uT;ckVYpi`2#Z`)8KS>#%Vz}W*{I2sxYKs6T{NYEW%MV!;1U<4h3!WcV= zP70JbVHrF>_u+LG~A5{~aRAA^uCt&}E2p{TQz77WFnyuB&7QnI`oac*Nx zec}D&Q|A=btuS+WT@ul4q`0cK=R(Hep@0K1;cJyi{aCzt`L;9dD|=0&p_9+YPJ7br zsNoz|?Ug^ok$tlXt@6`m^>!PxRsq~l@p@`WIV?C_s!Mtp(m9TaH5jQN!NqE+>$g8s05XKtBV@=04MANuWsfib7`}=nBwttT(azFi zdL9wf#yjg;I78%3DpfLfkXtm2$gGkwsYQiwF7l*?eu=27GG~Y4AoufINJgC4xg^Z* z2S7sfE6W(GW2HtPniJk#(VGo{-T%eg0o-@PUcu)r@DeNtbe=*E@eqv0V<~1``19yf z-EgHQ>M=_*G$t#$tPhs`1l`z=t4#Wnch;$sfZbRl_ZBj`F_h-*!aw03sDI*sOQ|`> z_$t8&_;xMZfkv$*gu;aZ|2h{xtsXzvi|QzGy#EA2U1cZgwhc%)pI+COqLf{! zMZKeU04U^^=Gx|vd6%OZ-Ps6U2VI)Z2Pc+|!4i!I&HB=|>n_@t0*9YXgh-b3$?<_? zR&|EHYCgZyKhL<#bcMVz^H3HepIXA>CZoPqY+$$03u!6lYgNrCUxK+ zqjT}VQv)_OoL>ffT7_u$EqBU9$3VuJsqlPClxfkR$kX@WGnPET?KKw_^%Xuh+@p<& z@on2-qN)8Snm4}jVWnK@6UvB&ck!z~Ya=u$mxix3@+|4Ip+E_ZO4LoQRuUF_D#oFX zFhJzjwEpU_DJJ`}ZRXQB6oFVb!fFFRv>Uz^^VMF@A=xYPV6gf!6{gGyqyHb6!n*hv z;A!8LA<#(Y?1cAy9U|v1Ag0(ZMqQ==1y0Wj?suFUN<~dap zJJIO)gp@(B%5FMc*JE^M>RG10iT6N_*BoX&sR&2~i@yG6#~aobVYLXiu_7$$3b z$2o-UI&V#}%$51%phHQQR4cm80%cE~zDEMr=A5@9G8?f@9y~UP=Gv?vDV=}3?XqfB zjwPPZ5`qkUmK8xA^KbHg(gkn2EYvjOsult+K7ypnJ-p*D<7PAkyG_aWE0|j>v8cR> zk`bfK5uzUDPc6ks7LiMl4YrbzXc-fzwG39sl37@1VkR+M|7lkMQ}n0m^nx9o>(*i( zL;O}tk);3?k133MlJA}5N9|Im{yr zR8vW`c2XOP596E?SR`=_xMH~V*koF7XahN%lZiu->SS&Wy@{ur@uJF9$kfZOBKU1$ z`DiVdVNLGNkQnh~SlX1%rwo;inrue_zuHXTfu=UNRP?OV2Z zLQ%Y87>M@F3+wAi_>w1wQ;01^?H;CZg@GR~a69Fprd_r57rZ#?9-)b{rs|!~n~xh; ztg-$0>e5f&TUxtY__mj>{S#J@cuf!b8lp?l#9~P4PVPKvDNWSbeI>(_QOz5SP}=Lv zRQi^GH!v7oiI!KeDOs?EqE!D+LQTDV_dkD^$nR9>%x2MH<&dhcEochz7 zSVi2MlC!Qd{=Z=;`y|RJ?g_nY*|NvS7=pW?C{ccvI62Ntw$s^^S{*h?Q%J!Rm8O-jogc@kefi8FN219Xsz@5gz?JP#3G^+$e*iz9) zF!Uy?v+`6(gl|gp*U+ycq4Ou^Y#mY8$zGu9*6l6Kf~sB~C|I)?_$Hf|+eF*Ft{7?& zMr&e1_#-OhCA*^fw`#XI3>Df^vh$=kAniH|&)EuhFRh|^!OjI!Z z1yIS%#D-6=oX9Z>a z7S#t77d<>qi3XUp$qYK?pA5cj#b($_nv;o6Zzp%b;Tq%cakVJoh%;HpTkP=MXF-^T zkl&#OSLgbbuRa(=A=V;ge2sJ@wa{QAIvS(xLp%teU8zlzd?~-hKu#9A^WaCpf1U!sU_O+UBC<%#c)BCcZEjcX0fAkbDq+Hk9+)h>7ldp{+RIg_4L zm<}{?#dd>l%1I-1M}~>6t?g^PopU^EWkXs#4v;-yHF)p-$jF8j#8uHjrj2d=hVz=> zjoOn{MK;lSAR-&hI(LD;gPonB{5J5SW=+?;6)dR2PVz$dI>m|No^szVJV4A;Pm^C@ zkU^gY-q0GwbSQSU4S@6`o#-_C+IQwelWRNAggixpZU5fPrv!;XN zpBXBgEE*=Wv}pEa)tor;$X4OW*(T}R6)8?xZk^4zsDT+3xS+{uQTH|iGKxaL2W6g? z8x1>K3AU>4TmHebX4H1T5s{@XR|RR4$h!_}TG;$WE^g`1to4D zgcES*?H_EGX=dcQ&6yHudU<#t6U)8~_Ru)9duV0&Kb1HEIvgYYLEz@4?Y}KP?qd$Yx3h_+`zdgvYeqlu(KDavq52_BqbcNp(2c+SK5!T!?+-yki5?Li9K%#Gl zW7(v~%8Rw#&;$3z0wUH(?GRtcyipWpNDmFY2@=eCP_+R_kpShe(@nDv{uu~B#wy?b zeIi?+cncA~!Fo*}jRQ-SV{iZ5GHYrZgfD6|n)%9yjiUr@a(uY#^8k16t4Uk6pe^~P zzl{v>ME)}M?6h@%eqY}C*i*-0 z>0CWmfaZBOP4uKJ7L}iv0Ynq^C{XqE{atQAObek4V_yv@GW-e9-4-x%6 zC!FMqtITPRTus*L-GB`Q+3f{~fKWma`M!A<+@{vrMgp#_DCYj5$a*j$(QD@$#i833 z`*xeMzzMt)Qhlr!)t-@m*E0SUH^v5;#6Vj%`5g;Y)&tY#E`J5|V+_%Cc8WTg1Tzk+ zz{4jKWE06D!+EfbN<_gG5^7)%YoMMBOYsznJs7B1CN@9&Rx6eS#B{t6O z(x&;T%6|Bw4_Wr?{KU{G+AA%a){D?sf*o?9J6AkX9vAGnBdNl$PBRA!hP`TLFBv{m zd4s?gs7XvZ#afe}^&rcZAZZ|6u{ha4+7Qj2{nI$+K= zN=X4-AVmGF3n;$6mKq`}-=R7a-L^n149EQUt2$g!z7$Cveh+R}w#ZHTZa(ImeX{Ie zEMJtR2F^8_A@+^*0hXs1wd7~fbv5Ih$U+qGtdf;+s4)&T>wjC>vk*KQz#Gp`3FK99 zzgT5B#6feB9K60*XSCoFV`y+fLaofCL!7VP_54kxvV;J6 zkFZh@!TkM^Vhmd906Q^(M=5u!|7f-YOYGhy?o&oVbjZawvZa_xW|dHNn)*1}m<~qg zhS?c@d0Tuo!G{qln;^S=jHDwMZJ^dgvpMKb`nfw3=w*8rKoYQo$_JjRP1kW9v&3CS z0{OMM3xjbbl0vn57Y6fYX}zCe8ry4U2)XDZ0Kr!EL<`MdaWc^*nPgb%Z^gqwu|RVx zBe~p!h^8yG66@>|8v!Aiz{&$EU~y7=R{!*81-yc|c2yAYozT33w^G6C=3dU!ZOqc& z1xEZabTI61H0XaV^h2E!WPlJ}t<$zLb0tN_W#l}5s(@k@w2*!W#pa3peYWU7a=~3i z>*D4f+oL*nl?{5|0ckI0xD6bjh1s9fB)sILlD`O!0Z4(o^Gn29^iP9_>e1CnLI`x% z#S?W1woyteFfcgZF3c~R*yA=8;+91lwbVk;%%7LR$CSkgKmcOIb~;QxIJ?zJt#7sF zRSE%oTD-epm`nOR4Bv|7^?Ty5V;V~QwLZs%>(g(;!dlAo4f4X9rf|GUf z`O?7c!nJFtJLQb_YH{)%8Bv4p6Uzqb~ZD#~#s!#j;-Gx?1Hqc@y(;tCxH)4WZ>DIIaa&j*hBE zicMK8o8)y-go--6FRz9`i9l$MUxzN;JETC~wr@*a8+l$aSU3A&?lczPue5Lbi@aw& zsSbBmmkVJPRrgI6HPYL;@w22HdapC4C~F%V!#bfzh0p0d3spLGgm*F!zME~A1~{O1 zHS-jbx|V=;2hDtsA;s95x}*(JQ%Mpcp&ij{llAr+nL_J`TlLg$mj{5dJarElhoB

hcHuVwIZQK4fc0Qg}D{|~+?VnfF6wA0Lv{Y(7 zR6Vzhxvh}5Zws0SQj3)b=vzn@@5NRH;OYO9ZsvTAsbsUprtPN>T*x39dg@VBU!6BD z5Yi`UA9;rG7jdsNW&uUQP=c8bH*$x^_}tR!4rS-ht`!q;8&S#hEdUswB?H3^L{nXM zb7@$Np+}u=n4(4Sm*MNWU%U~9_OE#lku8C{(8aB?poBNu!+JXq$;F!vsDvYl{|$Xc z4`Ouk(;4g9kOt_AJHqVr`Faie60gh!A>d@E6hlLgX`-=M_D?=bgm^dl+Uci|DtOoyjg>3u#|jwQx9J8w=`QQm!~ zN3Np~_LKV@RhVofZ{0~~V8(W#kX`GnefK$RNfQ;nZv6DsVu={~uzD|v8UkOn%bk7o4rZT^qhj>K_O-_DQx-o21TH}K5IO5!dst;-ju~2=l5#mQ6xYu2Jei# zt2I(QJbr%=&MsJnmTsVZTUg!F5eEfpZ3OY?``)4QIO9=(Uw{nfa}6i=eB3l;2zZ~)MCv%G9N zIoQFD#R@2Ca_a|aDAIQUqSE)|?ZK2RL{I}+hbS!Lnf8E51p8XzOcA%j69aqjPZ&Uy zH`|wiuJtU?D~v@(-gQhDzELJU56&X=-ISxXk%n{qqs_PMZ2{1Gr>kDExwsu6OCCoh z?P)AZH1#!4eK=!njqVLtM=WWES~b{#SrH#}}H-+dgY1hd* z+*xoR=2r%=Tey$6NXYRWWA)BU;u2=|Rw?I>7Ki)s^KPg$$ToBBrk0rVQ{41S(cMv0 z{PY_%qFNS>)F{c{{zh4WH|O)ZMvMwe$0(e1Ch@sbH0AVYa8B@q^dcjh#OD|9i-EjD}EucY;v`q4QSY){YzFb{xwiWv0`j3*?S4! zasy#RriFJB)oTQ)L#;878Tyo5qWGE}8$yc;BEiNl(seb;eY2gaj5ab{6I|dZf8>+7 zjB;E^2nOue?8?S^?qB(tTzs=dSVYYxM;mW2AzP7FO>dSj#p^p@jZkPU)%)=d&DsDG zsDV$EsKbfgyp1SR*1l>v2qDO|n6lgmcgdoumj|AP#p5; zlbp*PJxO`l5vxA&mbVkO8IL7LY?B&*Nt;W&%C|HZO;h($^2jezr@q!;p>Bl2iYuO+ z_${~tO8!51|Leonu`ff#w}M8qHRtjeT68*-ezG2P@3c+R_Z_!nu02hme+n_7w{68S z4B&tOH_0; z-tx?Bs5&n&g!tG2_r1y`d?d|)#&YH8qxT+rxK9&_U8WieaxH0sbw4f=Ua4#iqY`~} zCxu1tq7Q(#f*#l~ZKvGte$1)>6ClLvsWQ$)W77^WK@}A>8$1zIw5;6`n@vfz8{jhC*4Zz6Tflg!FV zxbLH|EYi?ZPrdm0C4w;`ZG77Dp*BBWegJw!&QEyeMjmJ{Zo67BfWVn1vUz;E7`Sep*yOP4v)9Dd)EjEh5Y-sd+A$a1R^NT z+e?A_>HLE2-yT88)MGg+D-ICKkow;5!{N^U)xZ9YjR$mh7Dd}|oUrxP%46%5@pJ>$qNRqkxFauaYIdy^GGn8553bT+r`~~V zHcey+zW9oK;;!QFut}Jkn@|j2N;4xEJA1%H3>zobBXcq zvgrIZS~6wkcO1`PQ-i5uS{{ zGM*au?vNIKXC^*9^ZH?=dz$7QLy@PT6&4zgBNj;zszrGDNWMim)Z>=eW9VZul;c1? zgIJ>euMG_ZfLQMeWdCh>w`_AjDY&i;AwTQB@L$QOA<8Lf82NQf6H2XSKg?=tvF*;@ zL;%gZ-x^Pd2|2kI@`R8*B$A%?!loMY2sRkaD*f}4V>_wai0V1V3A!nkfSdR9*IyDy zjjAex(dP@N+)fR#c{iH67Yh%>5y3pK>XG|1-RB5tB00759Z$&l@@jQVMnhHv7%UxH z+ZA}S5zR+lsD5s$%g79wIWYszSAD=+?H;N;Qi@O2L#>&=@`Wds$(4hngHVQJ{NLuc z%A;%0!;z+F;8=KKBi_|MPp6?5ajgyzN0+(x8r+GvELOoubvk4x1X@$uvYn=rN4B6A z^=8prl7$H83@U`t5!?D_-Jt+Mm@dNZRsfOXJaiqgMMKl@UUhfj>SUEUj_a_eWLbq~ zv2C0)-VL(ib=SDG<_6qNd6)6aI;4?s1tYt-%XM3#4vIIh2+b!hI1e-tygZ=PItVptl-na5y0r_Wr{y2xpAfq?n)H3zHp?9uVc%@ zGuP*GqmPR(A2-gG*=KGk$jLb_QJcusO|+uUpF+5c5k^kt($=^6m-HFl6xnj)_3?iB z^+i_6kYe$zgbK@t``6bw**Wn({|eVkzgX9Z>f2Dj|k<`ya|M z8Lde)xdQCv?;o&cZ^71p!Ic5{#09s_fUt69!rZXxHdRLnS*@}dLo%&PN@6S->wu5N zd0H<8OjNhzm#urDGYd8m!8oJ9lC$zjD>~Ld) znTn~R;XZ57+TnH@5jTx_$bLL=WC_1n-|Qor^YRS1nSC{3A6#`WHpYRb8$#aH$;fWd zdKW`JH!)DX7*a3qmmIeqQ$-cBGZy6>k>OM^l$uyaao26Hn(1CQD7UcY;c+_2Vqffm zZf3g+^6rLYg~Rx@8}DRmAl#0y`28FvBNm<^AltQiEi&U`i+UX@Swm82f_)+dNdvkB zbzqS(uku6Qb-;RZqe9@WpA61*x%(Vx@_sqN`=yszi9$}!vBu7OFWJ~_5+p%0eNSVq z!TOR^1K4fP_f{?tho>RBbREy)K>$j8IAwHJ!x0REJ=4(|qbpJ>5uCw#Yx_n$5PMV< zhOC7yKjCt8Knz)LiRe%|XE(Lmu~b>7&!?8yZ)MrI-jzr3v-?Xkl4mh~GvGx%TC|a; zvy^W_G(Tqn4RSGo#Rtn{UwmZ0_yllsvqzxYPnI}w`URK$R$;`F2t+VD-9(2r^fidKx@GIFeJ;B$~7_ zI5d2jP_t_(K;p%CSdKih!0%Y^Tk5Wg#Cb*v@na_f=J$g1&QwH&?^s400N^NEtcGD81|hNf`Ix^u6z3Dn)Y6eK0+#j zYthyNit{sfp|DJVNI1nLJwi@8zIqlx4{swVfRuaaY<6e05k_4++@ zHF8Hj{>^uXW3846iKU8ee1_oF-SKR~@pA_~x=;(WqrVh{-&#Hr9BsNvh^yD{auql@ zPqT_1hB&MFCcS`pCJBs(xT8wP|CuBD{VJIBV@ndTw+QHbsI0an(&h2+b~@`!;ba1? zz}*}G(Yg<&PD##TWpRf6H1!J}0!;=10-{j1t6!}bm)Q^Ts-ajFdFP3j?fJo&Gkv9qMu{Kr`2 z_cN{Ge{99^SVcmw-Xnp9KlNy0U~Cby50{!WO422)6Q3-FgJgV%$PR@*r1Q=g@V}DE zj2ifHqeL#Fe>kt{eAWf`^UL2mgwUT%2R{ z0mZ{6@{jvx!7UBM1miUZ%kLy6siJN8#x$LUYW;D57}+6cSg|a_zIp0%%;FOrTVyc@ z7J^=3dtCaw8*K*|Ja3kBvuo-nDlUsD8{Zb}?s21%{bSbHr$*1)!o`*|XVIsY>80%} zc(_*dD8(ZA;M*$VqrxqG)aonY=0~=G$*@_7NlU5IkYbwH|Ma2-AJ3xVsNN@7=0K%9Vipd@VlplS{&DMS#6c6tf}TcQ(L z-JeuzOHPh>`v;fd^qDCPw8M_e+u?aeMBQ~TkG!h_nB zt4bv?zgYJ-oB?VQG8>v433odcES?CTP3R+s#j;g8ia|+P6lL|U6ZgKvWj*=8N@y#b zo4z!KcVkPo#8ct}^}milR#>ND^c(;FJ`A->n#P(@JJdIP==xbUc>b33d?g*YWxZ9F z4vd}TTTyaN7$OjD7TsM6jJ;vA-IG~+0XN_%wz2ccD_YK6`9(LoTwDH1ZJW@0?)u_; z{k1byLZO`@PHCtKBlMPjY;dD1NJT3xmEwpGpwG$rp);Kr zFwXlim&(y}y%oF(Hj%+AH(to`jH_sD09c6-Ig5V;c#dexr6GnuG>#^tg(-8@*YDgB z27*Ed(kMZR{dc~UN65;N#k2@uw-bU!*;CPn6|#0?AQws{;nsVcT#3`M(5!D4U@b-m z#myv2^*3xP?Cq)3Zit%>jMHcNTp66Ya^O`hn^LA0s9JqJsCB+VZet)6=XC=YZx9TEr zN)t8bPF^Jla5EH&wZ)*Y5LYJ*a`#6k;r;aLpIkUh&bx?fS13Epv0FsDnAf!4s&VlP zSN=|w)hO0uNxTJ>kU@x&AJzZ;O1zkU_E8EIQnS@+ZWKT>jK$C$Npk#U;5!C<$+zz_ z=U3q_)!&B-FL1AY{x%7{40=f5T*`c(lKvAIVVwq&w-rUB_fqVO9%u-B2)NADVR-=d zn~YtjnLCmpG1i6wmwuJtNBs)@y@m}WG4gASzOD$>O$h|0ltOWgw- z;jeNqIYJu?1ikU{l{S@1=&Sy~R{?sIVd=9|MXRzQWaqsQ#ud-bsZWax+wy3>Gfxy} zPFcE5@ViTqQ*Fb)!d-JAF{15HVCzbZ5dO^63K0&A}TzbB30?@za4n*uOWz%L3KmONE2l&<&sAFP{> z%|Hlmceb%;@a7)pJo*wG$cF0$yn=WSAOskIv?!!fD*7Eb0L=c^uVqbgGoz4~cx{>B z6Ujup`WdhR?U4z2cIrSN;oa@!(i2x2tG{@PVj$}ma7VYyQM2=4A7Q6If&|V6rQdO1 zc@Hr4U#$K}mf6lVuTFjAykp_|du+{V1CCtau`qVs0zd9U?)n50jU)33?ANgL=pniv zNH89%b~_jJl1W4G=B-AuRuYWlj3UZ#XAb)k!Ni5pED55Jty%zjDPb|n z@o*0P)bnTL-=mhP2~ru zS<($W#LE>Uy5L-`Vpu+pY^OkPlHkn6=7vC)LPw6E-_nfiWC|NNzH`OU1z z;{GGf_Myr;o;>=9Z|~H(kUISn-L{xynpSRXN9a~?4=;D(IShchLm7VL48-QHl=f+S zpNfVA-Ae#FxRe&P!3W$iY1ia2iFR|Et}NuTq2nqACa?8KHgtj(@;mn#Ai$N<#RahF zWf#XaP=+PdFIc5di$vDxSu}`}_awp(eHG_{9F)@pD7pP-<~63QANF+5~b2i2y@DyuWBu9EpOVL;>RnU^R56`{OJO%&sW`^hGSn zL&O!lrD@{-_$2>oEG$9p;K>Pf_0WR^4FF-pptiOBG7!W2~b2G&#QZj|1ob)2=D;5ahMI*^)zXww0 zX82d2D0CN5qIPK^@c{O$(N4#Qg+Q@>#Bj*Fv5J8OC9LZX(L@m`wh)r*N?0_8u!fzRiS zW1ouMjX9s2uZP~^v^sr~KNxZ4k@sks3;3C%isRg#_l<@H;^^`DePxU0V)WX87sS|} z;r!@j&u4O}P4@y!jf7d?FT`=%X%PCKW$(O(g-CQ3dtz4+)Ll~u;hukMT$AB|O9R<_ zO@~+Omz#C*Jt@DJiaU%veWs?z@PT18Xj=hC13e$|huYUdSMv6fH;PKMv6MW--K~E5 zT*ShgiA~1QZ_lRURAa zPpE6g6ciOWJYrG~oU_b#>-Ao2p*h9{;%MHMU`ir$6!#YP8(1GGQ}usZiW(WtluCN9 zA?*Pc_gt6KfKekA1e+UDfy~canJbt69!*of9fbq^NZiBo(NRNQNszZZ$;g#f3Uv)o zxdP-@iW*V|Gn~c*<-mDM-`Qbe$!gxVdC2t7twxvMivhjo!IY{s*L3^?AnrI$c7;<0cF10(T-#N#z z-QnW!R|hE7D8UZB4oq|;`bM3t9I2sAJj?!vddUz1mrcBRqs$F|^RB&bCyf_0_^;Ql zlc$GKsZqv7+ImJ?YovS0>6SxFoIUFNq&QzXChDa3GbfsomIO2&P3f;=Oz;nlkEcx z?U_OtcAmyXe}BQzkpH(L`q3|@)R{;5U)rgfV3Ui+4@xFYM3Mn@P{rk{eR<%vTI4Q! zz+PYE1paKUg^+&cBO2r%cQhL)xcAWh+9Oqba|2loz7#OCQ(Lf8;_} z)6fVY_o%nTyGRHW&(RXX9+SUgX4g`^N|q^6wKBxkCb>ORj4KRKrn(^T3TSE^_a=?N z>0!e!^J2$yp8$Q#YOtd5s&e4}YI~9KjM864NcJIdkW^gZdAi-s!9OmE6q@$mELGww z%7SlWenXnBznbAf`_HxdZFTuJz3XuYOQYm`ZgOOw7c7MUGUAlsQGlyR3g`V5p3XfA z2=0$>&?a)XLXhe-h1W~BnD?oGD}NnQIu%<{YPUG0Cl#=PyQlihWkDa$h&aj+ov!&z zAee91hvM7~K&|G}7Grw{@bWku)-GN0d%{JTfTj|QGI=+!L;RC6U52>>CjTXrPj3&T zOI~7~$X|a)hI`a<#kw*~9GER&D(1Ab5=6y@OJp72fZdAt`sQeseGBuMTNP%p;cP$)rgv#R`{bx7{v8RxGpd{sV!DWv8Yq@Ock&pjLFA* z(Jmw}Qdi&va{U!Anh>LBTn#4kc<9}amKv!(`RlPy(|0XV2zAX}2<%DkPzh{phJJQ~F=(56369 z;Tz;Cj3@2|n@d>;F>hl-f3!pH`4k=TY7 zb2hEB!}L;_Py#LHS~~y&!5q(DCB{{os!FoXBY zia)&3hsx(Y&F*I+w@Wb@`~0oikgi>f)HyV~Q8Olfyo&LXKKr)*pdp0#dJBDa;Oxy( zg)~_e%{^*%B_;;7)PaTgW_L83U*yugBB_w}Ts(eBje8F->U8%ub)Ch?hfyua_hsVu zPCGCOG$s@={ae-?OtN313Cz2dFyB$1pHe!VH(dm+B4bGX2A3PS0=6&j=|**;jH{y# z&jV0dT91)&%=JToD)}ZVn&Iihc2FkhzyJUP0{J)q?YR=&gW6#UUx~l3f`B>6mNqqs za>5>G(e>Y;dC(`J>|m@+h5b!}$Rf7|QP0O){oF~_(O&y~bzuC3nEEyXQP#{FO){8D zOmM6#sD^r8M_UGDE~hs@LX3kUWM3QVYM1Pet}t46Q8U#)^`sg_wg&Db7%Jy}PI zz%G$QP1x2nc*|BIWWVv@_d(4zFl!qAwT9AlZqSTruX+Tzepo5YvpW=1BVKyWyJcIn z?{u?5PpasA#e7!Hka|n)!-F)6(pg@VXVH?A zSU=x8fHI`6mzvlN6!5UGn|3E5;D4X1`fP{o0QJ1FE*}8M2MWS58RxqwKVI!VZx%oVxsjB{aya?P6Zm z3Y5OO(D}m17jPlsh{{R%`#HW%<)Kr>;1*`bzTxLRa*3{{RjJfo^5ScgU5_GiPkYn& z{mwl01iqIezvNAU34M}xMfxn~oh!DX&C(4U03f@asv3&LQIE*{j&KOP>6q)r%J4%m|fPO+*} zZs#7_%Ka?#6D)s)^;CX9k{>G%Am@kCicD%?*?Z|Ps9TwZhj+_RBA4d_9nerzRdWC>s8%`M zi3>A{A1bg%3RM@m9<^_HZ5v=ysD8K?{f@z&$r7CqTF`G-+B>6c0LKw%PxDwZT2xnMMXPZCPMN+p#VX(A=$I*7k+ zL>4v9%$W92&Bd_)*Ksuah|Lv3L`35b5T$ngY%@dwnz31B-&oGZ1LY^{7#z~-3wlBO zB_RkD$Im{nIfayPCdtQZzKzL57Q-$qc1_f`5-;Hz>DO!G-!p^;SFY3$Jt$+r`cp6h z7%9{7D=8SA3~`utRyx_FAvv4jKWh5tzG4d{MV5mO-G};>HDtUv@SglfY=Z`>vx!g%!9A! zn8%jx`=7+AIAs=`c*lIeH^rBFl{?Y(i}TI#AnOomNq-(y#cC$<9&Q8E3EE?NP;-1n zqv4cBk?Rsyp!AF3(W{aL_y<*mVGIgrNy{T?EX0li3r@6J_(~Tt3UP+hvzD2^O8^Bd z`Zj-b;(on*${K-(%2&4zA~OEIaTJ(p(qBI@TXD&dztK4a8F9U}&v-WIG5|=18rrDJ zPqxH1F(f^MOl~3n1pO=DPM|O<=`o*Mg1RkpPm5$jJ978sONB(Y9!oX!3QZI;sTX|;K zY6-Q%hoN6yNlO#-{PfskdS)*V0#nkvvOBy%p;r34D_4IWh~PCl+;X2V-BX+xZ0{~* zk9I?#6lYE8){Lge_#idkgg>IIb!x4`KoBJ(x3qliQYfI_n|iD`jpZjdN4}C(%?4a; zm;v!tDabR#dhF*g4M)jfC}F6z6~1Q5*#Q9wvw=r?n~0=@HUg||M0p*BE2l34C1(^5 z(^~1mf-Zu2ENjpGEEJUvio4xO{+OQ~)}jr+Ew z0Yk4UV*g zgG_xqGfeE*RLMo8QV!^R!mkECFUlrGF5l$9rhy!QYS>$N^T~`=x3yAu{F9^UoZk=` z&SR2LEO`tbXnzFjtFe|TTnS4uo&ud_QEvuZYb5!j?D4a}VdgETczaYAsDx6TtD;Ve zM<|Pdck}hX1i&=?tH7|_q4Dv$W5t@05K z4#)Drq%mVyrZS;7JG4m6xOa=HF%T41y>Dz!=Pt38F+%yYxHf5HER_ZH==(r!M&mOl zUPiDG=lih1DmI?_qz~zRrjBI)?A~hVrvXZN0ea95lx)dVxkbsxr`z7K3?8mi1m)O% zJ6GQrQNBaxyW2t-Dl|6MfGgf&BLz3S$4>ubi5P7t;N>r)~5 zJSMLxg;(h4=`Ip2LT)WJH=TQ;D35MNiebS=L^APSeJ61gCIHPVIv00RI3 z3G~1}Q(t@`5tEIJt5c~DWq_6hB2dDY2AvghzIl-SBHB#e0S(Pwb;?uXtir4Cx+B2! z!E&RnE&e%I6PULJ;ZE$+{U#(8ACV7PlIE9&+^x+WYbyQHqui+bdW70gvz*zW;cu?O zb!5ywR=oq7GFNj<>2ZC#Hu7o9mPGbN!n)l-K@5oPMrCFy2QQN5I*T-1#H2%~ zEBc*bfztd9sd1g9Y)1YagHFtswmOK`NR>Y5xdJgUUyEuf9)NQQ4AN> zz39MShYx3h0CEQKzWc=Qa%%Afx)5wyl6mB}XR3bt87g$L8C_R#cOXQ$ z_Apb~L~<)buvcW0^a4^vPf&Bv$1^D?A)4zo@kaMrVfs^>v-ALB`b)&ImBJgu;cZPm ziY&LVWyA00`GeeeriFHSVKnHUyQ~)z5>X?F1rHcP>Ns-e0>&#+d*UWXa1J-Z#_H9sZ?hyYNR{#qfGbri& zYkKEIaX1?EOhG8F>!k<_EaMeWcrIy1n1kHKxXMZ-mnm9fb~2{b#!YnX4^saqfsJXX z!>Ps})Z|omhN1%myoLE1(3*^Dn}Ffu9~F!zE1 zg|~qMt0e@n1~Fpd4n?&s!oRqu@>KaHdjO{O)ijDX;r^vM4`lDD&q-rOcej`64y=$f zh}LYkE6VDZ(ny$GR$u(~HMB#NpQ`|gvbjJ+C?#-ovY7YqjhWo?B6pLphkip+cMNR?5kiX0MXVwr5u z%;k_B3csK6w96aCw(S&CPUH6$PQB|8~k!hGFnV)G~ex(vGpCY@8 z4?pd8bz|@ME*;p}hLVTH;{JIUvSm2cpCYKOn4 z3G}puM13cX@Aj=P+ob|C7ao-GeLGIGn{2ONHc#dfO*Ah0`wLl|Pf3vc?%|n9ms)aC zy)-z@54FNzMJ#?h)r7Skb3|8)`IVAW&QD96?FUWX-Fqmw51X>Z$+I0thI>sdW3lwi z(VP{f(Dfhf=4<7=RImPHm@axh1@A&rgcEdxsSTCUTgQ%B7!;`eotT3gHeqEAgx)6spJy?AB+YriQf4yw_Iy7sO)6D9scda_Bl@H5QT1%Cl z91Kt2gfDX$Z4oKrkWwL3#EBO?{{($*P=CtV>OCmM)e&-QXF6P>C>v4o+s2HwqTnhv zQ##DYaYJ%7BeD4?bR*q{mGfMGFHSlxW=&-;IFf!XQy-23)=x@(QVZb0GIFqyv_2e; zz8b1(gihzp%|C2^B1iKRG0t=`@H~x8R6~(MVY0h zhL66Pm@KuC=X`?1WB6aS7o#WH!SrWn%%c%PG#O0J#x`aOltZ+>Z6B(SZTpJEk#~^v z2NN186Ol&nU(pEcZb=yhMY=G8=Bd#b;}E^DbL$pLmB60r#ly1x6wxa0E5lXm1ta$yM7@WT zgUYpUpIIhx^v4O7aH-eNp6Hr}c1l|BD*(58>|4h&mB!lUgUIOH4g|GZ-StPz+P~P2 zj8}2QBKjWCp^~q2hC!r;GeWZ`p?u<*%X+F5=j%jo=mk{;lti$~Wido7*CIWH@AYpo z29n4OF~nRdgs7^|JxL#mivBzXNnP~-yd+~wXTlgZFDf|Y=y1*D zMoXu@{MP@KU8E=R*bpmQxYm&kobQ-=4!%YVmU9a#gEQd#2vsWc*cw_D%dGZ1&^wux zcdKy*_pLOcA(D2k6|^wf_i@}Qc`|7WY%pXbPtmYgsoKTu)>%buWleUmm2z5Ote=rO zDY~J@nBKs;V28!;48Ui`trqkjmq?ko6jBQN20|bb*L@%SeoV=wgT6muftTU49G8kB zWtRNFSsg-`@%6)dz7&(v@Q_sp=r8cb~byB$c2rbz4Y#*?1@cQy5(mvK;8!R_$0$)C^S=tcXayU|Zo$A1=R? z``zdA7XBG4JjPJ->|VNga&)kGcld!~ot4{3C78@{>?EsBeOGVuQeV4yxhJMaJSRAo~SDz4(lr=t>CN(i;>ExhJZolSthS2Kg@1lt_x+Vd;Y7B?i z5etz?fm{RCGgdfz>VpLE3BL~DVVf;o50dZTi@xT^ujbsykE9x*31>OU=-bBkk?HpY z?QNTopW&^QCV7EcU#-{rr93zx{;lzAc3b=(nZf`K6;toTl*VmFi z)I^(^hX1t`Ja-M6^A7j|7@shF=F^7voJRrroy}su55H=&!RF)XVyCOCLw|7Ya*kvp zs0<>ycwx4@r7k)M!&~zI`Q@V4vB--8?P?=ypCv8fW#uv14B|Z2$cLhkuQdD7wEJ1o zgW#K*nwb+Yo_IBeOr!#kUxq46-cd$Iu1&{)M(&GqmdgDG2!GN#XG{am2sOdZIYY+SU^5tGe$~8K!=!)`P0K!m5d>iF_guFDN#r zC>|-cKNh@!@45wPn7UZchbz>?gb+3)UXT;40YqpT-&!xh5}uc5Xg2fCL=kU42ZQBq zH@VNP5cphixf;I64^Y`G7UXLKDyq_rJF`{XmX>BqRp8$AA5GRa&ES*b;L1QWH8tHn zR<*Xpj0+->8B^qc_VYCx#g-NiIY!UeSY@b7!VtNwY{$!cPnS!Q=&uq~brMCI(EgGb zj{?y1=*!#x@;LiN-J8nGlOF2N6@|2=s}4JaR*3Q0!tI>*We}#SQW^>Ek}ePfv$OV= z_UhK(NesqUF>RQZZa4U`Dm zODXPGk}_6~DVub!fyDC!`JL4w5DyjSVadM2q-1gAK_VE(fiOG68R*S=K(O=94v{A+ z)QxEj7%Y{ybUmje@OFveUqk5ESO8;S=+DlH>i0ZY5EdJ%5)!0p{j>t_E2SM^Y=hNNgA4tn{R!jfYMk26``iK9C1`UDQqJM!?Pu14kvw3@WdPAs`;2Qu74L;Rv3J9)hP0kD%7 zBi{rkN(U$Bos*u1&ggKKau`c;W4vM9e^LZI!u=yQ{pImIl&CZv7{xcdxI)UrqNSSx znlll(Z;w^@!X+$YxO$ukLls$$@UB6p3t(B9PBAiYIh_?8flU-XK-V602iLH)$gF8B zN5fC{-`Akm^3o+OhY`q7lPaHTs3r{HpW$CxaPQ+l`*_O%L-P}^=lKY%!9t3?1YNo$ zkDqKJ`T%%gIgz)1?4y|w)0XF+FSS_6VWR@=93EhxoNt@x81FI@*K9Nfza1~@v=5zZ zYv|}F70@Vo3PKudl69nx*XoEa{c-~7iO+e;xg4+_sOzpWhf()UhT0GFViqeMNgBB5 z8wM7_JShcX?SsF1AS8~DpZL6(q*JBsc%fNWqxr5aZrs4aac2xUi(qK_W>wEfVfHp< zX(BP|&MNkSi(5d)KiQP|Y7?LZM>3bHR3$l4-P{ro7%C|FXIXLOe=r1oNSeOrL1@99 zDA82lE)0?2$(ptX|Npo8KEprK0>lLLSP%~+fnBnoLy zuNnS8PVEce%O)g_8aiuJ5*ZdPry$HDjRurSkye6}b}qC(+wer)zT@nD7V+RHN`VnK z-3&uy?lBrgO#56zvLI|4ZB`>ICWzkE{P~NWfJ+PNyd|qpIy{^6P}pS}wj4lED3+}| z&tf+sagoV){(C>Omzu<}kmkmQf9e3oD#RkVLNNY7=S?@MirSB9Z2Aaag%ISF`7O&? zHWMDPy&j|Z-GG{u=g*e4*~Jg1>$elFgIVxr4wg*Oydr-Vsn7T4V$J z5X(AT5-94SNKWpF%sF`W;4@fxmZ|SQWOD)QQXMyVcSiS+v>|)@Me=)Dw#g;A`dImk z&u6xVZN+625#SCtpwuq(BE?ry-Y`mWZ#64hD!UVR)VMH<`U7e5hk2La_-d1 zY`=mzul9&Qan@hiSd(Op`dEZ6|X( zK(C~3P)0zw8C`7HT3fn z<6#L`yxn*hmqoyw!F;0HFZ}h~-!cZKy0HEABQM-7d{tp)-Qgg{)_da_BNXIaAi6vm zz%~vrvD@&gGKey=Qbm${)A;vg$M1&^<;eh+i*uo@1ny&z{h;l@7HRAToB%6Izq2wN zl8}~P%B?v&eKgUMQJOuzNl4d)KE1-6zHlWYvH}JhS9bmWtjn1wYn(uu;;(!*!h#s> zEV~sC?`@Y9Pi0J+Di-$9jXQS8JiI$A4LD(?$6C+?b8=PN%~3{lBcJrMXou)q0Zfkf zP?eTp>>m??uUpf%TdB??GQ)LM&7RhS3-dwYD}+pa)_pG%^jk%VTUs*zA!(} z^Vi(*BW0mYuxd~Ao*}iXS>eWf2^Uhft_S4Yoy!lIe`eh`3vIF{@*Yec^aR1fg&%Y;p<5YmWogzW zEf6D}RctOG4nPNf#j@Nj<^L7wTlm^0ogM}N!V*^LHziCl0iScpp^;r9*(TbBR(jz+ zw04@v-M*Su);@a|_tAx)(Qe};$^@`Y6V)XqnXh4fsxZ& zu{SmONI%O6e)?RA_1>eF_s2tml4;Y{kxXVS;3pwihh;1G;1*v^zjc*h0te*aaFY%s zr?3Zw)b4gHex7mIju$wdoVjb2fx`Tau<=vyD9B>Zg*~VF9Yf85O`%m&w3-liCp@Ym z&P<+f+uQ{4+}c*5=P*6HUKK!>2W34ez%*$6=q*Et*jf*>kuGd%3%t)Jg*N(eq?FrT zpKw}`zkE$Z&{#(GRgK-l^js-C}}GyF22C!nSe^8d;qUD5(wx6@ zdv}*-arK|qrRQdU&tV{{Xw;-QH10w`>=e#@k^B(ufzR&e_?rZRh~#yjqer36V<;=y zLweMqxI-dLLSerNrBEX~EM3wN@GaLcOm{J&`Vd(Y5z~$&(5)X7^uRa&4a7N@x_Kt* zB(BMS;^_7C_iNz6>0wijjB^wm{k%_KV<2M?V@YA>3y?HGog0FMs%HiP;Q)&TWOzBh zuW1gsBJ9v5NoFUJ1aE*92&dys9~uN!8~)Hc@wx7v^T>WV^~i(k3RJmd8YyN;yui${ zu&z?j2IX0f{hY>5aAHg#7Ip}3#GLtDl1R6Is0kUe(-s-7bzXTJ;VaxZzGX`CP<~6U)t{81$a%|2>V|tGJ@`j3DtZTc)->wO&OA}b+ z;0^aUa{G`urK2KFOLZqf@i!04K1nJ*7naLa$=et3;`4f_1_NjTX>Pve%}g)cT{o}% z2SsnWoHPB_m@7yUKm1PN*2J)P%Gd;Pzt3tO$&%;y^dwU)IMDUe__&ePkSh=gUHImp zl01{hV8?T$Pv_gy4UnEX6UFyqqwOVsZWy?3Q#NWjx*Mv$pF%>HrT#Yby`3rPUI$WsPQK7jA^O(hbS(I{2Z7bq?Bv(=X9GTXCL$##Yx4mq-=Tr z{w|u2cG>^l<_68_5e~o4R&Anpw#>@VuTZ}9P1^i<$Rfcir7u zVB?ILmT>W0=AQzqFZ~8vRZD$7&;i4B)j6RA=+NXFF(E+l4GFWRFD+q; z_XPF>%q5VCBHTRs9@+G~Fo}Ae>Y^Spi*SkTzvg`>S&Q#)x`lGw3?jse`esH6f@{}} zwjV-mViTsHfvoFHo-O=lOLPPjHw6^i)+o9K<^6cF(&&t=Nr!e3y%Wz0&E132%-bRpS- zw)y7U+G=E7*)M(91dl2JcZ$F_*$Viu)2}Ec=t`xN<}sTulL<-D1eDIzDy1=$58NY% z55)`w0^7CzfwkX!4OjY3pIv)~ldEE^rlEir$bR#-zdeF$bqaZz65gLs{Ph(etEai@ z2Z6rqGQk!9%6ITp4p-X$x*fNPCe|7Z1ws6PIJ|LKQa*i!Q~|Yt`hOJiFhNT(kKyv@ zbvZU*DTzebMStAZn$d(oAz?#%z}Y1bScvjwtB27?ZQ_amOQi4sDHxR=lSL06oHTA8 zsXfR4&z-*yX!K}f(H*5~Aq#+t18~8&zfVnLtOnvkc)p{^tb*>zdtiXl35Z!~2_80f z@I=1BmN2-&{MokKSxvH-l$>!v>n-@N+6wR1zT&DZ;@%m!31SWXUKtTu+H5Y>(Yc;V zqozqQ)Ul%zp-N-~c1qVS@qSc{FpW)4C48UTZc?;hPt8Tp7UQ&a? z1D1hTV97jicVvh~$QfK9lkp7BwwlE$6$4=64~HIBh-zz%YjcuOB!}>Hv>8FPNeE7% zoRqx-w!ws(r2Dzk1`yC>%O0hLs2;^mN^t|yG=+)|ExUZ%NOESj&;}#YnH|ST#f7v>1rFrHPn)qw| z)j-4Y?*#vMo0LY|-BoZKCI2wP{-V!U!uq6HZPrH4LAMW@Bq%JYFLztOL}nX?)~sQN zahStQaDcBtPofh#Dnl30WHdxe?F8th69@=fwh~19!o)a)ETdWSuEjc~KLq+cO{}TtZZ_jU#QNH&^-=19v0A zB^+|VBIp;ZXsXxALv?;Q_;7{`SPVE9l(3Y%U|&JNJTe?E{v}4SgPTfK>>W-o_?ZlJ zaLj^U^!M+LLy|eMl3JoQYxhZ>4K&f$rM22TWGICDmANZFgn!?9LBqSL?T1Eyjx_|& z!2_4Vjd{WIX1Q=G5{lF$Ubl9D9Ijq$Zs#e-Vl1I+F;YRF=0Y)(At#y&XZt7bzgw8N z-)ymI^FW$k#{+;Xqp0$roSa!anS|t~)##8oC8b8R(#c6xZwsY&dCJsqTBa?%xHFIy z{~a461}_R3PzwN{W5DaH9mef4kwD}S@G%#lcM`?$LC1q_xvUj)@B4_a#%PwnR)9Qq zeiLo;zq$d9Nq&Y>4-5|zu^sFWxZtvx5lr`#V7!0U9Uib)dVe??Ut%RKtnfVPuFAPb z10r-nA=4B2bvTSSNh|Ik{NImDEjrfCJLL;U&^1+vYBwGXxpGPjU(B< zo)GwP4(6!*pY_9csqute zKS}4s@Z(0I;g+a&dOPtPLsuuOU;S^d6WFQPG+u8HHz)=>2O7ZoKc>#vQnTFyid1 zBmOVTIL}|1j`4ac8)f+pMOh0*C)_8wXB+fDx+D5yYyQ(pY_v0VST?kKoq z{71d^Cw~NkhoWS$OwF9l6Fm6~L|G%l4W?;p4E|h8ctf*(=?>?CU`o=-A&E05dIEn$ z!@R>UgB#GRKXZ*XV?e4rnYr-&eWW+4au*BpUH4^9v<|p~V}C_ZQVFNUE2PCpNPznt zIxKISkbTYX?{LMCZKtI%v{Sjx=1M*;gpbBuyqI-%$0L|f*OK6JJ!|+Rqt3e=id?1; z!F%4bO~qj`zev)o+AKS#O1#+yY3Z5F^SgIMKTo%m$B9qjtNKnVb=S$QAQhI;)l5^S9iRPt>FI*&m@6Y3Sen~QZ?d6;OrVEmu0#*T1f zalxP5iYVB%Y!AgtdZ%8KtapQo8J8BE*4$$)CO|2-8{JUvhWgsp zk$5VQuV$F9zF{r1-h2s|I7B$M9S2VYv)-nWYnvqOGHhw_a%PM6rXxhv;ZX*)DlKR? zA%l1i0+CwFwY<_4XElxx0Zx;a-Z?PJ$!^$gqKMgU&JVo-@8aJ}r?l%HB_}nITjtn8 zUSz4@dUk1G$ard}gCIjbfVGM)PRvMX+kXf)r&2l^wt7iDFQnwg!1~yAp&706wvGFQ zN#S{J(c#day7^cr1kw9r02$@ZP7Gusd=lu{@`ttN3ir~g7Iq9V|W9&m?@mI68Q>tyS2XGS$5x};Yt5`D6- z(jMFk8BM0Nl<+$`TFQM?FS-UXq`K|Qa}*wgkQ*amqWJDccuhEb+C!{?aCX}d-JVZ8 z<d#5@Ae^v~J|tabc|ULB!>)qV|*wz54J_xdprUJFkU~fH@v>gzY8r1}(T;jk5&L z_Xuo?Iy1{0E0?F_TpNVqBS&@$=nSdS&Vfp5ozhO%^hQaX7v^&7UmgCR=1*)?RmU${ z5T&*Ca^a??a@cIGKfv)R#5Z5d9J973*^p>K4k%wZ&jXClahHZa5QPGlw)Nx@k8xS} zJx#BXjHpa-*WI}!K0Rq@3e%^%OOyD`zVZ>U^PONZp5UOf)?Ti^%8D&0UA>;ah~V99jwpX;oYBQc)S3Mq@dcxCe+X<_b^ zS>tw1$v# zB@xcJnzaa0sJqN5a)!niCWF@f`_4x+7}llM^}CIxCy|tL07;3fe2_(iV$HBvOCx8e z+jemDxZ(2l+utLX@#Ztp`0k)N05I7|k*FL5vnvMARM+vjL^olU!sjAmGjz1i+vCS$ zkUyw8K%cT=etlR)@O|p4QfpuUNDHC8zbG&xEnNLAI!!gk!h(9OBFJCXMb-Il>g<{CwU390f29Vp=KVS_8%FWg7U1a3eh%7Ti%Iju>lKkjmYb!(EHdqyvb9VKVE)zaiG zunN7>WrmOB7Y_I^)OdofOo0RKw6L22s=*K~qF-Omfp`(mQA-y&znfQA{CNXcf_b;X zC1k7c;UYq1O@#({tcXCtP{E%~I6sF_X|;8HxC?Kp-WN-Ss!seO4>zP=KC>}DgHW(H zcFvESIK+pdqaKyKsPVwklkj2d=vYc=JrRiY=z> zw$#GbJY2yZL|q_CWL7HpN9OmVUxOi~rt1ist?1hID=#e&rgqfM`Q_)Q-`6+c5&|QC zFN#FL-$=3g*jC70>8$3|*!>TrGk#v)9hoOmxNF7Mmd~_Dya@`H)PV(JcN72xrZn?s z0gCEZSxqXj8ACL1=vKjL8qbSathS61d}7o|JiU^DcG}g4jrG4?A9NcR%LAt(r}91K zW~C*m*3b=?>gY->a}=P`@}?v@HKH%){p{t$Si<0xV%mY2qZ(-yaQ>V2zJg@sb_Bzy zO>l3+A0rOUg(?-xQ0g%1n3r!sdX24zS7#=1MiMN1-( zwRE&@IZ0Aaxq_5TWz9WR6IkO}zEj{7?py9c;kUjQ!v?-i;{IfQP{#P^7=ziqUbWnb zY6ewB74_7>Lx6dv$Dc%VM*Bq*XuI20(iB4Xs2RK)RV4@@E-PDF$%mG5WSi$WPCTP* zuqARuWK+#BPQ*VF7K9Es4QgQ_D7(lD<3kcjPC5-Ymt7Ia93gjvUx4vErpAjP?Iy6? zp|i@IwOF2fs;trATqKZ_BE^7oigd2{izN?rmMj#lFq%umA)@ay%Dy$71(TT|6KU_rq@K~vE5};( zk{c@p;NRNjzLKbV3u47&Y=$Q!R*M>gZL)2Tbd5g8=i#FN0+;TH6;`C)i7VL)IQIz zt~F&Ez%pD*{Y0SzGy)g(-H5k0_*#0);b8g7ciRWQDwBEYLOAMS-Qc927q8-h6G6al zfp>Q*87$A3F8fPF4sXT-nA>w*iyzn*%?NY$HvBp@2yJ;(M)S5D#zr-Tkli!Itbd}r z|KY;5v0uvLs?KQmoT!tCee+nVdnPc#%BzLAM#k1rYRz zt*WS>mkpXBwY9WwIyv%^35zqY0mKtZB^05M*aME-sDSOItt%7#W#ZX1mT_t;n-5;z zrni{3$4-8)4)#tB zr};w#kvwlN0hz%^x|gs##T{WAkGzr|$r=4%!dxCxA6-;TC!|++G9>>qNjdpcU}!dT z2BX~2_lI=V7Z*aRN4rL<92KW!CI z3V{p<%zt+&J^d^7;SdM$UabhkT-KETEO{hY0aDsRVO_nldl zG*3aqHPRVuwrO3iHhYxJir|Y75F}K8D8^OYdNGCsTl2td26q8-q9@Q*kMJ4%+DB$Z zDb?2H%O+g@s!A6zUb$|$WQ6l?HP_QYUK4SX6qSe98xk}YF7zaoWo%nKAqq4G@Jk&6 z9AV_hbY<=^LE#1QF`H%ycs)RI1R~kgOqm1*J%te6+Wew;aAm0Vw4Pki&1*#VgOY@s=uYo zZ>x$l?@(VM25y19Ux?Osag)anQWeeKRI2ViC8v+UktS-8b0tmcO}Vb;%}S*!5E^-nm8SHzNc5A8wmh2t((8Do zHTO586M59*e#jj0NF``0=xj}?PPnX#g$)nob&C)!KdkO+<-_U8TU_kMb1TO1!6EGg zl7gU=pXp!LkhDS**x{X+6cN!{lZzmS5mR-NFVZOYs$VfKd0f^|seqz!|Q<~D7f$S-Swf&Xfq zn@nOVLV<={!1=uWK(_9{1%+U`CEK&r!xq9c9J@r6g+z!a$Oqc=Dz-oKw1GZBOsICO z|7X>%)W>MX_|nl?@lUB>5-MI#U*zX*4)u(Hg`{$u9G!KB2OaN-K4Sv1A~?uIV<#>E z26tnOAZZyR4RE8$v-+=@fSOeLGvz^2uN|fVZJoVSO!%8#ixe13G8eqGX<>l6^W>gJH!L&TABU;DN2&>BRC z*(f?j`N-EAC`2h~=(@|pKw4Zv@el!-XP5n(%Q-#<#>4GjtTQ#?s5gCUPECXU)Q;9# zJ$i+#Y)-y;Wg;|m0EcBqkC`P9rT_tI_3m)71C44RW%B?~mpm_g$@?RmMFoM_){}|D zzS74)D3PD6=zBd<8@1OnZ)aXS$RDLBT&nqe55Q6Y00RIF?-n241BkWmyR#qzZrGBB zk>@O-)}?mT+Cy;l14^`^QQ5+RJG{E0;#lxhy#VHhdWYj)Z;uWu>M+>Z9r?~gt0ARK zdBQ*?d%N()bw8AOH0Tu`B+2=Z3#$eCf6x_6qwJv-JPfPQR^k(S)~TCR$6dHioc2>}9zXxg7(0NIC703Od+)E8CeZuaD)X|$ zzVG9XW5&K^BP9Iq$0VwYhO0xYLi#c@d{{ykV*6b>L^(ykRLQ>KfiE(Z7i={8>%vhG zxbaH5dF;WxxsgYar|bV@tQ>K}I=Wm5e3vqgog~@HN}Fbl@H_v;eq77>KrFZB^o%!S zh_o3-YVz+22kJuEb^2W!x5e?ry4G&h{#3jZD zLQs77aB^7PrfJ5b{P`vZT(%uJ-E z6x$1plAJ)1eNhEQrUh>uhOa0Yl_Kvqoe?1%ob)>Yd})OLR6d&4FzE#U?OLbE5qde1 z-NbrHN5#w{D;Ypqn4R4cK^{{)_J3Nt?>r{-Oy8q;+Op6Q1DogAWk$@Gh}ORbdcbRm z?uUousdBDm1i#9!29i~W3Io1hKgsD`O2UR9wQ}8pllhz>nlAY%&>|@zu$LROYYGek zy>ALftrF8J4u;Xse?kUj3uXi zjWtB-H0ym`cZbu}7*eEP+U|PMg_Z38rlJR8$24ec`WKlQvir+VJ?5w*q@CG-?^q^E z`*kv7xpOS_1so)I#C>+yFRXfWX1VWGHeVoI`o#?19l2(L1T_d)(t62l_6>1d))ce5 z7Tuev_nrATeqqS{QsCvjqdat)lZtLbkVXoDGclF5IF?%>ph#LWh1(ny4}Pk~pX3s9V>Rc-xvRU?3$T~h3|Pw30DIaGY~(?CfNNxa zQK)P}zZt05*q9?k@!e!w%%`<(eAAx}=DqKH{iBgQ1W0f12R=F0@4Ckz;GucrNR+G@ z>HP%CHJe9rwVuZ+8cx*lyNQK(H`f>2USRpnZ3#G!^k8S!>Dyr7MSU+dC5Pud4;F;` z1i05aN#FA6TD;nA8R@BP7xR>Z^-vZA~MXhKlgjY8By4Dk;~YGMZHOjgFsm>S<<&CZDia5 zFcvjHoD{T#dre2PwOK9EghCGp+Mb z?jm7Rox=iBL5RkJuKIFU!1D_x?zLVe^T_hSa7V&7$JWa%%f}(<tS>miaEYYZW$qSjT5H=d#Ki>$G6I9+%BrD{_@@8LiD&0 zzdDMwMOF{AmdM%X(Bq$s9EcFOTIRX@dB$IL+%)Tzes$m5RuA2Mc5do&ERzj*y@TG!>xn6_qI(n zz}ZX`x)q^o8;O!0GQX?{b(kQPxIZF$Oj+yk1X$S3_EjICH^zc|54W5~{~Y?^!gls_ zrw%%eo%-uJn1cRFOyXWVYbeS;0iAoNtcoz-JE5sV_TUXOh8b)5nngsghA_j6^~yg^ zd|C6VmtXs8CJvY9N^H~?jsy5mlWQO~JlBrMOluE`W=$hi%-I45Kv;raiO%PR=Pnm+ zW63z$D2p~CjA+XM1)$nWcsyAuwN5Id_m)PU2YgvANTUu!a?zY6!)gU>6fc`T7BTI( zMJ%CyTq14xg^@LPOupY*O3eOB7oz@v{Q>`OFVcev_k{6^YeCPT5Ps!HcV955`p@_g zb3RD9Uf>sxw`=XXsF?3dC&(yiFu5tQbjs$hbB*tZdSG9d7d83K-6}_)%}+f>iiF@6 zTFV;B_w;(uydTQ3hB%QP7kj7r6~XHR>h8S#TV8v-TFZsLW}_ zJfA_3O}w!l6N(4>3pEs8cH^;9p$IS3(Zij~7HUdgu>y>5Lq$0xBiN##XY0>9}(Fp5A>nV)O(x+h%`b$Uaz)9U;+y?+xbmdFq2w zpYSR;sb>wD4Mue&drTJK?b-r!mrY2EK|DHjKhb6N)gjcOIg_s>Y##y~jX5Rlsq1Ff z0L)-StdvGkBqZZ{gX0TRc$^pItkX*Rxt~dwP{XB|8Dx=>0Ws04_VZB1cx?pAM`fx@ zwTZLgE~~-$6cT7I)jTomWJxDvfjt|gzVr)TFXSRm2%qZ8!Cv~6eqkRqiXZ?FQ=3(u zZ2mTIW3YInKmaaM3q&(Aah`p^O$XS1R)?H`N7-v~(fbwq!`?rG3n9qU65&T+wjrn$ z$tCqS7OP2uQ~C)<75sNF5+2WVKHjL75t4Ncr@bf<>i6&9-0B+}uc@$uE8WcI2L#Kx z5?C+ubl5;%C;0nmcpe?SrKn80t9quv`p!~2`m>Zr7#B^>UK`RDo*RWz(Ak|&CG~OJnkq%8$e+1 zimgKfc2zT&VPl$W9hGWbkseUB$~@WeQ7XlNs#Eqy_JU(ek{kg%=BA*C3xM~EDIDAQ z(@xq$rO}~FoA4pLS$tH(RM7)D3Hvvrf*!kb-WvDTS#{(lR|?3pRu41zMw8u$iZYs; z128SgbOQ0(nAhuoWKPSpryB9ZN(~qZx6hUZ*7fCSfWhR64UAotHoe$@xk5`K0cqaI z%IP9&6PpPG@=yUxt{pZ$cN4saO_msrxNj7WXh|&I#XwoUwuCZDHScii zfvLetXq4&YmlCrC8a;Ku9sEKe6IHOTw`ml}hK>_Z%cvfTlgrB9lQWo{DTMd>7O(LZ zZ3|-;06;)A9U3-3x0Ml7DwJBHl8`>|fq~;ZhN|qUk?iAjo{|fC1-|xasnV#_BTPyC z7F<+s=k!}<1ZmsfG)1Cvb2a4h=X@uv)HtbAoKMq|0(V4&5^(N^oe!iQz+%h%4LM<~tXX@8yh0EB zERkaI!i=d*EIcX!8cbDAQsZ{WhXo3(^<#F27?{xPC6X_azy-EUII-+306%%9W=6jL z(I!{>{!7lBY-3u5PPuEg`nxPi7=fM<)MlRjv%WV4t`|f0{Rrgf4nJx7(Y|IiJ;!Iy z>vGK%7mFWaJj`E98eKkg!_v5xdt9_B4zJltaGm@0_9J5PP+us zsDn8uZp{^U2|Gq7gF`qhPfXQC#KFb?p>mERwmguV2a~PAj3B=G2;WT*-!}L4Ff}mS zC$+i=Xz=F1uiy-L@_~JWi1Ycr{uyEAVD%9D5?d9SZ!MyOZa&KHY|i#q*x`+|3X>Iq z<>~S>YJD=H4%X-zJ_;Mi4Y--35`lTq8fgMAYhI1uJ(x% ztkbZz+Y}tEjmarzT-cg<)E4gFB|F72AixVdzlE&aEiw{^q~2x0O?A zSCXZqG5{!d7Ef`SK%hcF%76e%u{`qp!tANtFVG=|Nrlp-JSqSNPVrLy4iggnP`SfM zw~w0&WTd5nB#rcDm?Fakk6t{UpH(@%JA-k8UYNKr9!K=76IsLi*(xFWNuVZcX>XP- zR8&Stz3sq@WPyQUUcQGp=8qjS70&JsxAq?|v=281FL3ljG(t0imG4-xnd(2KolmCVW6Y}C?4 z@CEXY9usnBo)liZy&X;cHA z!*53$qG6j&uVLZy7iZItCnF*7KppU(*V2_?Oy5`@=!DAG18++dDrvq3$Lv3JLQgk)CkO z8^LcF^q(H(9khO;Mt7{t3tN;X@0IwKq(Kj)TZ9S5FLAO>w9@EtvU$Q`WT+%LXiQ}V`CAZ-yOoJMKHLQ za#?#J?@fq7(yL z#rTx?C^2XGlrDAEF0SF6TX_jl&AL2^*9C)1q-6B)pQt;4Bhwigsm}jypqApwi#z-S z)?6=A#{J)k^z9oLdU99v+iJh^VpP}O0OmY?=jq-no)zcj8bntqSmn&|+hausAWKoa zUc^(f?Y2fSn_1%znpWtk{$T9J78I2c0PXF}#im3pYuM+>`Z3%O6UJq>WD9m&Z5(?V zb8>Jdn10eO25^(u`@XGoW>{W29$IsrkE7&MrK?|jNNABM*AO^W5ev|E*yY=f_@AW^6mGCsyv?k5ff~C-jj(j=ZXMbvL;J}b7DU5PzRb&njOwh9 z{CIgf%cQi8Pb4H?MCgFTtQET) zFgZ0^{Q8O-#eL2l8zH*_>yeif2ku}*Giq!VK`=m1(n)s9hSb>A86k?0f4hU+47gsx{{31 zvKUKqDF@i9I3G*VW5WXe3$V40Ox(+uTej~EP}IHCr&*1`NPt_{+JWyd8d~!=B9|ESa?3A4oY%g0Z_A>^20-g?Q| z?}m6z6;32t;D?{t8YY8$1MRh6&NYH~0sX28&S$^`!>Ndo_z)BAJ~>QunvI#3acJw+ z5@_x}sS~#=?+WC0uDS4C)}S7|%R#9L(yq>}0~>gx!%`iWj>w zgPr&beeM~#P#SG=miaw@vo&yG%V`(Vmvko7g!ULoLbrOU7IQf7s^hAOq4a40yXFlsHaZs4GQW3Z zr5;EsW4stqhG6v2FO-};NqjCmU1UiG$Hgfo6iSJFbElIF*|IX9?-f=kOg3ohyR+4<6 z7;T#{@?oPUE~K{VbiVZZmmUCfWx1a0;q-YH* z%gt?qOsh3v)tAmqjG;}{M492~ScF(@kFA;yrdv>F=8369fAD1_qBXLNx z@gOKS;#u5uE~KcIiJIuD`|qaFzh|9Ze)`StJx=xCgItiK%F)1I#+IipUI#r$NGs!kw>}p+mm1J@N7?r^_*(}ol^UIFk`lqcO{iZbLeN1w$nGAwOXxY+L8pKo z&+aCnXoz`=a4{j4wxPq^xe4V#P90g&;2NrB8w@j+MfUV(`$NpJ`)8Dm+l?Zn&la@p z_hZ!i1en#wN-10{|I)0~tj8EX2l5U6J;-ffK*Jv*Luyb?RqRZ(ob;cvG2K#?qII6L zB9-dH2HsWC=tn+|sL^G%1@kqR4;S7YMTa-!Fnj5(L(VACgWN#!<4F9f*XVZRPbeK^ zJ0}?d-_yOh1i%jS+5+<|ea%LDW&@aD+~pXmlT%_i29eWcJX^#AE^%kQ{6F0SMP=XTq2qu z`*0??VTQ_$RLKWo`o6>0T=uPHMR%9($%C|!msKJ&K^e;w;Wf6(=qe_UQk6(}52s)K zXdP9Yt2fXE^^_GQqi!5=3m`F@X347xiyAv$W^&HU+`#e+Uk9_INdR@+rHhgkq!|!{ zgWxh5QfB3=H#@9T%QPdT|0|~#Ai%TKQ7r{N131OA3~gl4rW(E;e~a^DdjLX^=!J}C zb({K@mhs7T{SE4JlF{XGr!3EUU*-0RxP}Sw#^sdLR)H^Q%pM;jIFqd1Z+AZqz(?1b z8Uj7hM~{qq|I4SI*!-(G{s)1wUJ7(4dfy-2kxhw;K3`Er`^$^F{4d27M4-eVi5tPIl_GS}3UX5+Ix%kBaxX<;EA`)Kmzb4n$>cPAd{ z4Dr6;JG9daUxM1Bs{_7Sn5L|*-&u754>sg>YZ~Q_B8zg4zNB^x|AM@TP0qGI2V{$$ zRwqBURMv1^U#6I+!M@Sf(U#r<;@lsj#D|u@IsNluZs+ZntMMEd^o4fJ*4!hNOVcY? z!u!uYb7E+Kxz}t{fNEF*QUbvQC@Z}b2H444&mX|kzBQu<`bN44K=>-d z_Pzt8d!pzHBVy2~S0HG&BvT)b*E?%c0V!!3+fdV#Pm$=${r=6Zxz4N~J`5IkSQ+LJ zi0i0o&{n`Fx}Tb+nl030POVLE0f>3n?sf#W@nK4ZmWD_g=Ksy8(=pfof0z`Uw1Mv9 zp%y`nUq+GWh}OMI*Vr_a>SNOVDXQ2>jluVCXp{3=7!N8Bbd*bgsuXJJU$Hw11ekP_X5Ad zDB-+__-``HAx#SE(`k-q<$KBfH3Allg>+s=oquNH9==qBQmshw|k1IZ#TB`PdjBoH}|XXzzNj-c#x%S}VW z$>VDI>a!_qdNc6Q_^lUiAb-`-`C%B;PY}di&mN|8r*XgW#QK{Vkk(hKi zb5*ddaDZY>RZvASX@1PFn=i0{szJYdot%N@EdCn>de{qM@uTddKwX~#-caBD$xgSP zaWs5s<`jo|>N?N+&ef78f8$ndvIHqd`hOm8JbBGoRnlSdX8eF)>!4$9*_Q_1|G5Le>iE5SkE6x#AX*2M$2}KOsxKlFM1=ks}x@W&*#hD$ok?SsxjIW zW;VWT15iUrG1I4XA(jX8tq4Cl-NQ+(IY$HGbDJaQAE1QGhh zkz||=Qk$M5;09*1p*rwuy*C>zWl)#VNai5d2GHUCl$_sR>H+8}?wk%Qz^BK7nj)}w zb4%xVn?1=ZzKK9`<__B?v+GC|%}43r-QSUfUJvzlSTZw-%{=kS+`l0?(;6qBRFPt- zP+9m-i}mUtUK7NkkyY(o-33Y>bVuV#ffX9ZC%5~|mh;m{iW2uXvb;@g@sVq!NiQw2 zX8f#7hqC_MO7mvTA+M%}ONOP|X%z})@J)XOh;3IKYwJjt468Cg0xS{UrMDJlhZLxH z9VUW+XJUZ3()T7vZ%y74ZG-hH=psvR@heStQ~4Yd2jq$-UV*AmA-Y*PdMR8yyIEzz z#H>ITz#wXU0m z*oP?DPscn?r|Eq5tjE&VcAry^UQ+4hQ?jCf$5ZP4Xx@~HQSecg_|6l_b3QpK%wMHZGyPmVNJHusdFwlJ zmj#nxtOk@Ie)E^q{B9)p5$RNLwp>}Vvq3aIDv{&19haSu>eRl97kFaczASy;2e}qw zqGJq~Iczr0EQV;kPf!<8ZPfIY4&r+v+_z-6v)Ha&0Xe8=6wJ3u)s>Aa-F|p8JDP$6%qY=%>w|xM}mCvusmUiOSf9Z`sAgw`i>&TKM;A2vDqQH0}WG3l8`vy_c1py6Q>xC5S{I8?8z$n65tk`Dq;>AU7_H zRIgzAif|jIijq?OtS6;&>KJWYfry674@(D;QQg=8px6Ka0|V_aX;{M?006Ik@R?N* z5aMbUz?Ffo)^bdwO}*A-t7JN6+qNhJ58$oe+v z_W5ZAK5_aPn%LZuGkuB@@LCST`g6?~$eH&Evon|8&GEeGnV*e($~T!Myv^ihpJ!9cmoE7=F1ncmZy zf4M1pT7ij0pbq8_dBqxKJ0212-}2amFTC`qo3?AZr{Dy8mEUh{y-sH+L5DMM7Vhz( zWKMYdOWT=~QGzC(ueT~B?(y13WZi5pH4h)IHOz#fmD!!`#udC_;WA4&OFOV|r1qtn zqUHc6GoiSZDW?$B*`u=JkB~4gaEiw-JimXIODDTf&Q?GudwD6df+9 zC!8$s8H}>BE}Q@s{CU$;5GX#EN5n%KV(>AZINDwx6B7d>V}{TT(%6*$o#~BS`^IdW zMk=DXfYg2wy4EY{XuU>P9pB>*3A;y8vy0X1n8*~C7b!DxW7;yqgKqp$tE zxObm+JL{>C&9WNU9PTMnX7JsfE#vhlE-O0@YP7c zZWIoO7Goy)R7Nid=cU&r%StBqoYs?+zn5V3EOf<}M!QCMo*FtI=%_j@ONRq}H7X6DMD zm_I?R7);c&hwcXS_w4oWmob&U@)7G7gOdaLztyXCt*;*aFCn|Ra_v*i33hJMr|=v> z@@|-hhiEZgj00S@utcSY1(n0N=^1{6p4}2@mWVFO1>9^qdU>7@QP1y5js0ad8l4n= zB(E)h@HiNvCkhjf+}oEAFu*VO+K|2rzTviOH$hvL%}U`JC2syshY2wwc!gc!fjS@@ zgl%IavkFxdb}WxO(2d6wmoxb88M=EJc5`#19bt-^gUS-o{H8b1x=!e821>Z@GMk~l zh?ITS%a7qrB%UNp0xePB9KVu9H1OP^bG?%MjI-b#ka{y%Wk>C6R8JfpZPLqM)euoR z8)W~H`L2;(o71%JJ_FN=tNN0!GV@u63o%$4tniSCOvg7zdjY5(T|!OseaIEKQ<3I3 z1U6f)P;)gp!{q_dAT)zxYz%AwlddI{(Gaaux3dsZSep3mXVN7>$i^l&&9WoJy_57TW73l+|+JO~Y&5FhOEb~WqihECvz?dxD zf&KNr5BKj*iMIoy1%?YryESEx!yy|33=y{SqaZBYFkOa{&z5T$tKK-_!nW^Uxt)qB5wq;fnL_f62TK@wJvCe>m)J-}}lFc6%HH;nj0G_7^1w9IxIwwZ3I z-%6_LdjTB~uI3qU3RE+H}rz|Dc zK6jK^(OXr#)$KHw+Af&OK_o$63^KmVcZbD8%aPx&{!mnj)*Ze6t~voFn`k8T@+hkJIu7(ciKJ%i zJ?@WUAU^A2?W7jgVZR3AF-2XVBIyXfme?aVgMyPN-u4XVk=0Gei;Spd3NBDS1qe{g zKx%u{MR))J0{}MH#rS~qKE=p$6AkM`t*?M(3fEvDO|NGgZ+Tq^p%EgaQdjQ!>9JS-av=Yw>w6ZyZt-4hQu`o z9UD1d%4zYbr49m}`3mgiRtFSd0lqGIY(26^)Duope!eYb>xLDDdIbU0kc`7IoC&-! z?u;e9{c=f)T#Uk+(nJPOd~j_G@5Tj%EDU8C3f zvgxD>w8);+t&z&0?BdR;OiT+v#I$z~c*y(ICsBsOLDpY37e}W!ruRFO5uM=+wHu)D z^VVXYnxfPB^3hJ_B5x(kKyIP=d`)L)j(0j>GVV<3$Z)28#fBrRt|QRb5kYQ20q_xD z-`F0yDdJ9ZIfrRtdn<@LKz48tU{kUJ{n}^U<6G|+=ug%A8Z?9Vh@a7 zb}N$DJt1MuAQ0S15`cs^)v2D0D#y$}M2K5SgrtKb76b%D3X+5=0$1nz$~K{)xgFi? zaS;QZee9yiCaAAScD72ji4iOe@&MEx1_rOx6ZEi!UGk4isH^W?`Rqnl*>GUYd44nU zE}Zd_GK=mE$E^AJXYYqyV<);)oTh1B7zI* zG}#Q127xlw!Y+3Kei|SuXWl5{FShHQz?!86kw1~3@OIt8vyw@%>6t_ zxyE8e-YNQuYp77u(Q};|lbVziLjTv&2xMc)NB1gSqP3XDP+*2`dIbHmJ)-J`^6AMW zxTR*nWmKoV7T)D(b?Kl}Ec1a!?4*38Ai~^Nu0j*l=iyCn`oBE?89WWxTFx05jY4pN zZGZlrdpwy`c{yZwCF^Y-YL^Eex~bv;y%B7o{~R)^Uz-YEa_bvM6tr`#YzLN!8sv0z zin0yn&jMk2ELr>jj#d2vlPz!kUA((GYX2nCej10Z56>?%dK|Z1M2`;`<4a;=E6wAU z^#El{O&uYjdC9iTPVs$xsU<4x7Z$hTf27>qhRxUd5^6pFu}Yq>51aqVZ0%EvJFpVqp%iWLFlYwByN zA&6`Nd-*nn6vo^^0Z=K5ionmUOdMgd*Hfz_paS<7FuVfL{x(T^`lc5bLvYm-c+p?6f;B z$m+GMUq2zc*2)_m*X(>Nd{t0=cO~y^UdOH8pJ~2SXwD`L4$;|4ds@ISYPB;ZsN+Ct zY?)s5NXD1yNkRUoXWq3eJ=SK7_2Mv_#WV<{bxD35-8C_ePDxW^8NUCJD2UM*|rNWSh+1M&W|MPHE3bLpd*>nY5yS z!)t^A{Kz3ww2dmHe63p$O{N>IqCBC_p@%r7P1CH0U}SC+5H!!7kKEYspjfq;qTCpF z#zb1KYuoZ+EURtM9&gsfU~T&7=pi|z18ER}*Fc+cgn+)Jq1L)9$Uw8DrF5g-`Pyus ziyyv&excwTfF1ng9sw$~VZ?TU4&)+`lZlM)d{l7ofd_#bpQ2MOPp(s(hJH?l*86r( zej{-ge!^;1{_HPKXk+$n)x-_YP3Hqaj*Gm27XJfu`^xFGl8fF8IaXCGyqMK zo0W=~2fd=>c~%{nTpw##D?=Lz@OAsVuZhoa<5}>Si`magYIf#O02aZW^wxz@UoQ#Z zT1*4%gn&n#EFKN#V)&i7Y)F%(9em4~NqOC5Wir={Din)<9ibivOL0S}vS|9?G0c_u z621{+*rS83gPYgFAOvu?)H751%e8Ln2ZwnxDQ*Q%YM^xcKzqACg>o>tVmRjh#=#d> zp4SW_x{YZzM7my*xLUrh;!vr=+#^9KMR)3To4IQ3 zXRu$*HDlGED}xySAnJYMfWkQ`2Zuhy7WEm{4=e{e)N3c9F&AGI5|@{@k%!pNkgWJ5 zt>(r~>tp_oUtS*MU0@XMyW1;gKuqyr2fO1H>4;#~H|aKd+p#xAc4V{c*fVnedW%kM zJCCb=0_yFLcTuf2hY-vFZa;7^gH7G09qQcpI8PWhD_6L1|{R)$KUmZei&tEo*Ob z$-6dn5O;xtSdo#Z7ru8~L<~PUq%p<$0<5O)H0Sz*i{O<6xGCkcK(Nq-DZCW!9_VEf zFMnc&s3~0EQD_*%G;DKANIMAl1jWCwraH1z%F2tt)@h|0J?IC9eU! z9+@u{0$MMm0_#gnALvs)n=R9pPKV0BCLF;sD(63_|L^*}O`>_ALxB&)hrRBmsdF+N zXTiZBcBKZdO~TyCkDP9^d&=a#9<^Ts{I4gj8sJeH(uV+r%1N9Qh~0pW*wLDL1+1-O zc^J6h-ukH0r*Amo^8#^GG^}YoS@YCjPT9})_3EZD<4YE%HBy&(Xh=&uO-oPF&=LAE zAZJO0j55CNsn^Yg#%OCl;#JL$6o)f~}y za_mFT+3JJwAsN~@Y2xO+*QLJMO|E&b%0FW04~_Ksz!0W4gwTI^F%jL>lCXDSLZYzX zUywIfCN>;1L=XDE^<*xK&pG30jH>y{;!FgZ$v#kJHsL)Lbfw3?n;SegmRUNYtQRkv zeq>IoE=Ad(VT`71f_3*pjzvik=M@CI6H$LZq!Vu+296T9?KESB4g+RuSzb8BG#~%&wAq5{(NoaxW}WGh0NijYSHIjf$H2+#WjN4MMqC z=1g|wW7t|OPp{XFA^W=Bh8TBi8yTFuMc~a!%c4EJihpp52ga;#QRu&?q*JzZ~^Y8vdR zT(0s?5wGi=>y>Pl3JucWIr&K<@o|-5<<~g@?TFccSMgJ#K4Pz;9+EJUcxE6=k>_m3 z9WXMTQI&|#(8Q29*HDH>Xspx?01bEVb$4a1Qe~s#F22l~S;^{W;iN9G=nN)blwIT{Hasce1VJ z^Q00K!f!p%L0RetAVWDL0ug-y37k_5D30yzvTsSEd{i9Yn>B(r&2~F15fwsxNFljh zOEYcLGTgxmOr5l)i$e91lZO!cs{xRTn$}hV;QwD6L0H=5Qn)4kav?Wyu|OodKv=Sb zWlCa;y_Ea}rN)vTi?+ldvz3dj`SK(g(Ruu)IeOz=39(#+U5T>BfYKNlH~NQUARh(#K5 zz;RB0j9UNzNn=A!xB@{h2LQm3U;q~HH{%t^r0MuZ1S#6??W?2YWg6RatO0e1Oi4~X zkEZk#zLw}_BeW>|s zv-@-*82+irG%IUy9X<`T0heb7BG${TN}&_xS`|9#=io?d+l3xQg6?9~0us=amfXVwc~4A&&m>}nm}w=$%aGdy{ipd{ zqb>Wv)PTQIiEEOMi;N%&?Vb(Yljrw~Bq+{?q>LdczjSgVC|NF~NE1P>Cuh6+*iDxBP4Z@73i;ES=8kCs)hs~Nj37g( z*Nng0;e--0^_opZs?GFl^YFGF8af+`yu3%7jIT#SF*BuFJ!~BRof+!8o?+uUDkLZ9 z<~ZxM)`V8W$mG9X`%nBKSD!XV0S3zYT-%s(j}=lKKg3ga!d+Z*NYRJ-dy+7*BAS97h*$oCP zp?d}A`LbhU$!|G{AIT4x_J$nbaK4gpi){~w@cTZ_tz29a^*-l5nmRFQIl?O6nb;*u zXT;6*L0>u&_f;mTVbqz%W%qyaM}xL_3&;U-~DWWauk7oAAWFpRO`aap6QA9GP3E+Y-35-+PZ#t*g@qGJHuXs#lnEcU((zGLJamw*B0n zmN4k*)VkHEjdVb77?`_;NT~82fcRg&sB{UQ>te{11cwKHjv9#n>K@7oBT=nBPqVJX z<<{*U5IRr3D#MK8G}yv;>-+7~SUI0cJs|*erfw`Jg?1Nz1bbzimvI&_pSTYG$n10~ zfy(L(7wGzCugvHW{AihyQVEKW!^&k3xTISE(3;6tAu~)86bIZQl>v??GgiThn!)o9|1v3zH z3hpwW%JLWQWmB!1&{^>*X0 zgZt<2gImEWr<#6*JHbTknoJl#IWZC6)q?$)Sbd4!W>`%^V}C2JqW6QP%ELS(*S*&8d0s6o+IPL1o_f(5(EV;%oK)OF zhGe~j@CJ}>dwjmajUmSxsCy@-<$OPU@><0kDesc^h<51ahST)&6a z^H~?`OOgwNFWoo?i8Iu}9K+?zuTCR5^stnA%Q+kM=w&X_XQjk>`8|5BPgUpa3Bzne zwLq$C5C^!9n6l=Yc5iAGb6fX|~RJz>NAkr73;>Z`P{qc`|Q#H z&O|w){1{Nu6ja*pa~IZwS96s3nwGgOpCg7g@wN9ja%9t-OtuW3RxNR3aU9cq`0XhJ z5TK_?Y^abJ}tkCKmZ?+}gz=APlg+IlwTQNB5e@P9_6mF%tUm)&~Cit~&lj zigrjGVu4W&xP?`q&ZTS2LOec{UkoK!fGZC%7>NxvI&(#*dqk%6K`%GBPiXsurTJ)7 z)=YA?9;vAL-fJ)o9bHH+jN%D>z4+ba-bY-BJABuPQuC-M=46Br-Qs5GPUcqZD4rdT z4sD8~k8cgfbVSZVLZzMt2{n~dPzkViBg@DmHltgbsx`j$9%DKxDWU@bwXXHGQl}m# zAFZIivhS`;YDEBZF83>?1pnD|p(f}{RM2zM7t9EU_^^0ZJn3Vp``$xCJhJ}k3`ow{ zN{c+c)kg!BISGM9K{Z^Rk_e9Is+&I3jfEbCzfy01B7ARt@U9b$iF7MES*mAN>3S1( z36VRt9G9jaT&^gT??#&=?shL%qB_EWbpW9NK2a7O(oDzWJxc98`jJ1 zOAJZ&aY`k5spPJprq?9MeRAr1*OR+_@Pxw`(>6ETZ|u$vA;F#DJ`14J7akAwlrl(bcBDQc2KC|f4# zKzU0L7?2;rqvwqreuMhpS_LLic_9meiC%h^srBhDs9? zi9{CGAq<{{H>oeYzzct^HcGXklY!shm zMH9qR`uv|?pp`jXp-{hLIn~x#s12$?g$7F39m69c(QVK(xLm3ykU?+T1jPMXlhnI~ z`)xeaG~;IeWoIy_aH;Sjz!kogQo*d~$!769E-^JBAm!E|Z=rHHYuD=BGMCN;Voq#? zOeY+p5djtTEXwl*63??d*d97)T!a91)8JO0qig!@-@8%mzF zJKf27B12!A{>_XMZ)mV)v}DD>Dv89|3NPp+p~y9lAfCa3 z&xz)IAy28|do5YwLUgEJs1_Jif#zvgo>KSfC8j)&KTD(QdaJy`2rOrcxk<*dnL>z# zVLzJDp-X9m-!o=ADt5AEJ-zb6YpmuK_~q2g0dd*UPm1EpXuWVCN+jI1#j1YCUkQD- z83gD600RKPD?lN*qyVF(y>nI2UdiYKJ)D<}`v^`_RbxZYD#bR>-rtWk#gXV=Ey1}v zwNtC#ftPJHTrYT$a_cMeKUjhXO@)0cx}QKDd#8nBs)*|Gn{A@I0f4f6TGt7VZoHQi zyb;CB#Xoc`?5-dPPBSAFN{a$8z+JEGVq~yZvR6K}`%5=Y;40sG?L_OzpQpt&nxM;h zmklSH#X9fwRS!ZI=UN_)p_XpiAl%1C=dKV@B->C2e^0h>hx;c{wJ{uE+9*7e9_sV? z#Dp_= z(80fO3^TPOuRPY>gHfhNR@TJ85XpP~dqZfrb>H5;-fPp*5-sf#&#ooC&llqNqV#}< z=hdp!F}``k(^Qm{*#q$CamUwBs&nGQutqXc6`ml)=Y0R%063B%wCBz<@%2-6`$!wP z`KF20o4FD0M76xu@HajWTAtkz($LDZ(9+JA@?c+^doo!IWXp|f6}cBqfLaD@@B%Ez z*3i~35kG&5xTDyX(BH$LovAT=N1y({Qi;KD4#Ia1INwNH17ib|u!jrZ;BkWN@Ma=6 z2!~^F{b9xbi~;y7$S*Izhb(=8EOAVLG71q%%uE$*Ty!n0lLsAPS_F({C=|k-cUVpO z=gV_JpE~nvUC6qZzzmnQ=^rsA7=}O|Rw2A`aK|#N!p5rPF;Ot5B9fG4YSy;yhCm!` z8}Qn#s;q@-b(D74sHWH00(9-oY%8D&{TE;>Vc3^aUc!S@4mHm<7Ygb?MAtl3e8p2m z!XE!@9dM0?2mABzNHoENfrz1pOaWv_3XlT=>x4U*oxO|Io+xSwgMTfDtbWttt1Qp3 zy*~E~Rrkwmx*$X{F6+|(00RI323neG#{8S`J9QYeR%5+;fPgW9-^}L*)1-1VmQH}U z-RaN{ihmMa3Iub#iXql_=9ea!orj>Jr!rO4SJv>GV>EklO#!Hkuk1UK*dj{@J3YrI zDTA$Ab(VJN9`#-YCGnGuXFRo6L9hBD`tUqwUN%2#(2n!t7$~fV342>)KDG@kyNisE8Hu-qYv=8g7*Jo`A76<}xZ&ftOOkW0m4G~G}fQg}4 zhS{Cb=QJ`iV+v8MsQt%Fk%{w%sQp4HbUhYEh$4^`qJt&4E2Yv{|5;_sZqC&gKG0_U zKfcVjB0z(@NGFEX4wTa7|BQknA){*rFiXgbnmDQn)=k0(dD>~CzT^N4BnW|g&?f5? z9x-1wbRp4t>dms)Pgvjn3rWHp0+nHjblprnfF zs;f_CXo2hRaVjwkJ-+MgAU%URr13iao^?3udG=bb+?4psVf+tzPv!c0v1)?As~Ghr|eUxI5X$OFI9c(ZmcwR$Pa5xI^; zQEcG@HA}pO0Q7KtTuEKvA^h-LLH8E@JH>)w9;mY!B|v!>EiKEDchx-&HF5xyiwa4* z`&j=j3ND}Hx{fi-bZItINYQK$(R3``BVz^O7v3_ZO4i6q6P?Qbdp|pJTe@r1{iKvD z8Ip=UkE?%-4Y8d<-(g*ew*d7%gM-n`kSiBAq_<)1<|t6iHcm*0rRnGL4XO#JeVRWWaL$IE^iU~AiDE^FNR7c2xyFL1r#guwCb2yU&>8bk z4sI-7I;zjETB$oEU=oIlrfmVwF%2FtNC>akZx2*nTfLjXfVt*scJZt|k$T^Mo0l2} z<~a!ID%9GX(%)=zBovRC5L4Ww6wqP`k8j~)WHFa9Ked}Wz`bS3ISANBhpf5teo?!K z;6vC>B+`Pmb}*rzxr9k&Cl;yhFe4Q9kg9L^nMkuLUoRg?EA_1ZaZ25oE+RR(aO7-^Tw0=w|&u1L8;^>6dWlieyxl3%-f_rIbcTpa5-xnIj2 zn|=W%zx6g3>P~NIQ0dY4vp`3rqo)em8ZzIITOxOM9F}k}?~<&3!WRFUUcupJypfRm z2iqeTzTkhDeiI=7Rs|6;kP(w0hfXj-72bVoU3W;}hc;I#IvrlvLG+#@UZZOVzQjp5 zv!+;Uo0;^3*yd;AB8aoaSAz)EEiMde5jEP$yh$wakjmhVN@`YP)1K2R7K^XlJ)n*u zP7U*BJa*m%(VfY+`^YHKCfoJ)wAuGh$*9g_;_N2oolkHYMwkU*(uu=N>qr?nnjpW1 zI7%gu=ZVaWKw6M>Kyo*M;k-MEXr&hX@~r~iLcS|fouh2=LNuE4-)B1IJnfZ+6ih$w zxuU21;`sJb+XMB-?qy8}ioEw4Kxhn2swi*C6&g?w73t*BmWARE(tWdLSu9Ll*ZRX_ z8dxZh$pPF`L#y@yhUk8LxH`2X?wd`)3rylUVi-uj#;uC}X|7}04|sKYkM zDP6sNG?lSCw6*U+f0%(Jg<^2gaT45J*!&}ehBVXEb`JH!~k-8040>XYR)yH2}v*0Ie^5PnMIbylO@?%peTWg@uJRjNl0I8 z2K}2EuB=>uJ5}|f^_7Jws4imi*jWJ=K}HH?;O57n?R{AV|1E$9@A}Qqs7l;jq9aND zv?_#>Nr*(cszm?$%8o@eWzbD2b+j%ojs`UDA2(UxW8d&sY*R zFr$zS7F}CjoeG;8I%o&oH+*`@3x20)+?yxHNI389@1&i%)JT%IxUKRCU+UHcxwm3X zh{U4cF|oRo2`kMTd0Y^jwe*?ar8c|TH;s<&eOZS zttqEoWMgmkHRSe?p{^tjN-rA2xW5c1S*}x^ok;f}(p#SFJ;V^Z)<@07L|f-hG+Kh&UyCP4wfIbr)oGl0Gxvwl%5oZsPH# z(+krIx{Pwb98SrMF(SGyG5~!*yXBR>#S;SWSuruaf;6A#l{zn)MRmh4I~MM?J7pqk z;?KECm77lQhG zGnx!)#7vY3=pgx64-lS8Mx$QesUAkP?ElBHpXkKw(0 zy+-6b-qS)JO~(j`5TvNy=cIaO1$Qc&liHJKS?TSpI zyIHd($8kE|%zy2dg<#?#%iS1|d%vg9yx>C5N4@JjHU3G)vQ;m0RAg;4A;&a83I*<4 zxh^}}GBwy53v-P1yqdB1X~eWq?ey0-aNEp4rNIw^=i=w`WZ^f9DzQG&cjKY01lA0a z7d9rBWzv!CGUjVC)uh3Jexwe;yv}1#2NH11^&3t zZ{=8a*(aahr)m&YJV{(MCkGS*EycC-I_j5%@-Jt^@;>|!l38rEGmr!b&1FBq)9C0% z`NRH?h=P^sCV|d!1e`?|z4*=B5;%ozS)HPI0009300RItWEA?5fB?bjIj6xEYAk#G zfm6xL{xY94{Z`Z^@;GSMI@F%O<%cgl=kKocXb%W_L`+QDRW>WyNDL7i9RDY}8x{VU zX^m!Y8!wX#%lE@+Q^#||Qy@GzoCt;NKD(Ed9v3h8L=Ecbc|-{dUtb%u zg3pE1ME_oHz8GD=#)=p@R?D%+Zd>Fpsutztnsgie5)hoXxETEXB~d-0h?j{#Yb$j7 z`2r{BKj24v?}}$k5pQhLF{iRYOc&35RacGl(;L1PhxQhLU~O=&NYRNBQq7lHU9DgW z$E`@jv{MLQG1xe~VPs_w``zd?aeX5@q^E2K6R}uI-W^CZ=Toc>`Of6TGC<9!>_e^H zlg~uBTI8Ox5A(uBSb6E@@n`mH8`fd}<5)c}%va2K-)w?!ec{DbraP8< zVd`(puW;6p3xLMB*0$4_^;#-J_U>YGy}VW9bdBdgq?vEQV`_UoL};#gmB^u=l>q@I zPHESjw1ccM7ZHq!vZUPI{$@G$s3FcN&Th+$e4DryUN)U12fL01g1FZ&&l)+|3C=6G`5b4G_M$kE%90zJc^L9zMQAmUhlmb{ zEtm)gZ$sKrF8#u_0cu}-Haf_4Zp>N7SxS!ZHvkDvYZ{3t?sNx{I2**R=QDZ`G4r^H z1z;E9g@VeHHTSrYQe%xh3u!*%>!I?)&s}9r4p@BP_6@-1SDk&BTnwfj1|s-lhahSj z9r+eGQc$bq?X^yV&5LDF-f5Oi8j&dA!{Np@f*V~FZ`_XFpjpx~ehH&AnBu5D82)W2 zd5y!3WL!*(7u%_^X#Hy}Hx!T1Yw6Fx9>Te{qxNoe$qvZ3meOBJ8Z@|NH)- za`|1DS#P6rTEA|*U&suq40mP}VY&2~sqDqix+U|Yxxo|+poeOC0Mb4bV#--g%43AO zJN*X`(Kb;c{nOwDy@M9Nh;?)Y3~H~^Uxb^a%P!_yYoHE05diD zv@woal(_d4Z!;R~ORrs;8xBm2ht(4zb|i+f64TwZn7((+RS325=CAcDAxV<_e3?BpD4pmq^9zWe4`M#R|LQ3)&tzx_DIY1awXRRI;_i@RSxSx**O@Xf zXmu*B^d*Yoh*vUp+T)m|0K?2t)yJ=!Z4Ck&OzgSCA+gKh3ia-=5O|rPGxtANaJfOQZ1$gj?G`W>#9# zL#q)5;%&Nn7N>M{CUphvp~wOn>&(Ij*y(~+LS2ct7EoslQp@vm1*w|H8c4jSO-QoE ziji0&z%o#w{U5y)mF4B>h?^V3+xjaPA`&zs+?5%ObPayPIh`a==z1bN+|t{`zmV^j zro*O*O*C^UFK)b23@>8NJpffoWN6Aaj zr_h+Tdg|af67cJbYd=7gjE`Rw;9iiYZmqRYSZSRBL%CXJRmW1VDtT9CH4RE1(E)Z` zkVNdNst7em;3F#bmtCjNrCW($J{`bo0Ry0#G6*MYNv)t(dEcUo%+iBp&@>{Huw*Ga zoR()KG_?S915o6)kbaqVBvZQf?Fca8YyeDyL^W*Qcin&^7fR|gLIQ5`KLLo z=OWsI<-Z~4U}O}KC2Gt0^@EP5Tg)!ZCIA<4_|%qK+QXQDN3Zk1l*V`l*}jD7^KS$l zGwJYbS?0NTmopnQDTJ%fh3iZ3?^m#v0R zm!)*NVqnQ64V225M~{)5k-`ap7QPqkS}bzHjyA^t1zR2P((bVrD9NTB<=4ui+ynExP_r_7p`mYgLd>TU+bmGF!ePLoL{xnGUtnKv^nTOSLai!g*vwj znPQ!5V^`o|uYD+AA#t#Iv!3C`SS2bjLGUbz2>g}RaB{~QfLzvX*5vu-y>$8WZpo$6M5zdb+#XIS>LB1>n{N;LW%YKP)pQ}3@sN5UDidIk8hcclc3nqgz1 z1oe!4jy#9Y^DOHkP2}fCBj18_Y~QXtd=2`2uj;Q?I}giHN$j909WsTaLE2sIwM) z$Fa)*;*xyZeODTx_QL5ZuZ}=LwC6?+JH|_(mUb#MJS-Vx!^Mk4A%LMk?<{=1`qqt> zw(k+wB17UDhG|>tIAEQf_a#BL0Q1cYtj|*#O+UA8&7X$e^{R)^79(vEwVW}1sB;iW z@56v9HyHkY0KgdO}=gjMZKfqf`N*`?ro94 z6T5mw3|ihnfKW4?gD7D|*id3z?yYs+fqA*s7%sgjf#7Quu9gGJS#NrCnXDTHqA+?( zE3Nds27hLHLVpp7BukZRp8*XA`}V^LDY%|8z%dzm+&^@X&bERnVm|<3*hlxuO*Tkz ztAev)Cn-$La_1YfP@73zdVmkn*mOA7qUI&w>Rqu|{xqz#U8t}9-p4Xc$bO{_y@*1? zJ$bg39a_ET9e?0Rg6Rh!;srQJjxd3*#DP{Vd;U*Sl!YIm3$RMKh}ftDx5+oB4syu0 zf#NvWo$l}M!rg;{#f~UNjF0^PP+_yvG_V*SYmz?VMn^5`@x!|rUsbn&pqnLT0@#Wn zaz?t%o=sxNb{+@q&jU(vRBD~<`!CF-7M+%!MskQDxEG^x^0P5YBTFU4l|ZLWrmF~N zbEA32Wk90Iv=NZPVy`s;8+Damy6!;i^07w)ZG^Fz#yRWI+Orb1Ws90`ukx@wN4gT& z-ukWJJYGonQ+j_^MyMqd+Pr*{<@VV$t8sQftRa(R%E|Z$feNIr!d{p z5|64UqQ8J(45EW?0@-H@KIh^s?^{h4YV{UHhvXA@#_?yvs`Uj*D2jLKy{k7kj1C5% z)+lXv66wmf7b8iw_o9(h1l4kkA=ltuHuXhb2p)z#v}tV-m#-L}b*Sf(nt0ZZq?mh3 zQQW<8N%L%MzVcA%*G(XNq@x>h4{0Q51xIe+8QQdMNiRu}Nj057w$VKQm&o}DPfiPY zzJSD)gsf)3)a4mb!O03K_CAd zv!bQ?m{%If_oV_P#NK;w!BhRT#I8w@^IY*{)O zYkix9b@Dc3V?pgQDjMG=ELXmgEFLnqo@liHd8_J~k_4XKV*YVuRHSoW+H4e?wmgSF zzZ;IH7@dGmoS>X5($k~&U+0WHwrUSZqjT)Q99MYO5^G&& zJ3064(f-ViuhOfUJ2kclH7GSJezKzML;L43DkMAZMejVW(NP;)N9lZbsRIq<=N866 zA1Kn79MeHsk;eTTTf_OwYkN<2Jd#NM18sr)0Co7nN&dDCwEh%EoCBijUFmn|wRK0; zPT>kh;m;ggFXO3Pmg>*a{s4A_$5yX-9gq;+-9QGh3n*A8k1b^rI6<3*w>%QVK)rSr z7u#WK*vIgF___V{ythZD>|O~mI!s%>)J%>6mv?i(&T%%PIU{JRBkb;t#VK>Txt#~& z{%$U{r4u%6gHU^aKoN`whkK}Q{x$IW4RAz48{SH)BC#hK0_YO2g50-PEiQW6)TcI} zyhQ)L#rk|o1g6KdJw*YrE7T~C$l{u5Z<%OJx+Gq;-wh0Vy11KHz)o|&_u8u#04oCz zQq-rB0>3T7aRC1Ttj=vs&J6Htln_k~C7if%6_&R8QC}h^}7iyp)A* z{8T{;EZwxTDllp+-y4+`ix&ntC>?aLczzFlEe!Y47%qmN*}N04P6~UTXUKOHVaaf3 z=Y%Cv?7hOB2bE1AYa4VT zS63!6Kksk=lI|{7Cdk!{$}g;Z5;{uZNT%1t`bm$KB8C}5yImvfzAg#tsu+bEy7tCN z7r0im2=9A;5w3{r>$AVvT32`=lwWGz0T_e+_)l@ zt?E%VCLis!Y1^4>LN=z*$oe(E4)gBZ=9EE1<_IpIL#SYu0}ReK1M2=vp#dx-{N-<_ zoD50iZStt|9|w&J&O4WphmeG6F)xRcAPzSHPl9d<&)xK9c1^PJT+gMpBFDQ!JIxp>hw`P&8AugFUtg+{NO<#nZH%*aR zk+ZllxEw(K)@aT<0h-dqJ-cIpo0x!K(_*1JV3RMyrSDqr%Fh_p((I)gqwMQ_lz5(?&)DviWQ#cT zJqx~L9N7&6QU1mZI{m(6zWQ}wsyi1>x9fJqNDm>RSpX%21gl;rF;Sg6NoMomFIY{M zDMW~gSN-0d2aFi{8#j}3fbY6YEK}x&9q=FTs&f{sR{q~BWf5RYhYf|B3}k@$eezrq z@pmI0sPeO}7{$AJ`w_z{7rz^{f5_}BqFm1@)sKEzJ~KsIt3IR4gro(vxRF!dk+`*w zy5ODcYG+UdIM`twZod%4CxTZ>c^B-&Jm=3JM8it3PtY~VVj5qQAKz(}(3>FlgQctJ zw&z?Bl2I)k7%dj8|9cLnbe@|~mYH9FgomUil`Geyi(FIN4{wu}ix6~2GAEHxM!dMle_P zoG_Pm$W37 zlpTDIFXxk87qND5E?j+QIK@UOP<(4)=e~!Y%PL`Sr4lKgoPd%rEyiq)57RL{$@MPF z{CZ!7M<}shF$TRVz`qVGSLi807D_rqfrHq+1{uQ;16A5^MHJkm_9=eJZ<|2>Y+_rG6M1-2xn7Bz)7iU(&i)WA3Vb6xIBmD zHv&Ii7WTH%gjyFT!XU|?mkm=K!Ua|l6O!!ob@0*BWHhPLTF7)VQsqZtA&3W^orFUJ zR%jtlZZxlala1Mjt;s3Pzp~*NMh|yTKNVzmomj+6$Bk?HoiT%>n)eyHf%_}9s;pXi zWqCHzK9_Yhq-zHDZocH6YivJdL_cKz;oia-BLPykA(VGR@7vzYkza%cBG9Hv=mK}A zF7CSk=NeujiJtMz_@TqB#7tDnTUB9F3;dNjDd$tRj-IyM|bR~@5Z;7lP;M>im?TGh1S6h zQD+6<)-lsl7sa579vac#m(8f5x=&G+O2Xw*I|^uQ@knYpPZ#M9GRs#u`GyCoE;MRo+*QJcl216CSNm!d{ zFzx*1uk!-w{;NW6`9p9laKxzVBtZdK6@IWvy}7v83)NJY`|yp$6xfL+RSm<^_b1X( z;WORAIlPO7WVu2(Ao4}|%6l@h^dZ_>sQXc&7RS_&E5 zWS6Hv&rCT59U6E+gOXF7Xgdv8{yhu@Z{xy!$WT2BEA4>j<+T(_RG@Q&eT->sm2E+- zL0N~uC3~`M*4QL3ioF6*Og63leHF-o-UINaT2dRlEFaRz>e|>zpD~=NbuVM~^GMOe z&yKA?Oa6Jh$~QJOGM9GaC(eX*Bp%g|sd#}wD_&Ysx=tYpcL!po`@e~?X}Pm8h0!5P z1Fl30pu$+28V?8#-UWE_S=0~bn^45PxxJiCOePvypADyil+mFW9X=d`abJX-d z_~y6czuj^A;BXqXO0|;w<{8+^pKq3xhNvgD zq}CT;L(m6E#|B+jC{KpKeXBfWZl{`0sI*tm@ zE}1Qxeg-a`1j;FtP)#~2`Lw|`QFGTRY zYBgg%vE*wDyy+W=xl$RjY0QXNdL{WL{l;M_4}1Bb)J{;8yUi^^IXxsJ9T8(RGr;s^ zosmT#@wAnpdsmh|cPD0!m9@&Mr~b1KQ$RK}KaQ4XTp!A38s8s2e)@w#f?+R}P+-6V zOb)8h^USdPZ^F_i_W8jIls_vF%2g-9)fmVOkg5~W5k;-7!L{@yzOX23I{`=Pf)^D3 z%`+73f{b>iu6v#Q0RBc$43jqhWnT63p-Zyn_cW{ZO@!;BB6OCjwmpsSlGBAR(Emv7 z7Zd+fPE9A|bwg@q8kiXQZzokUOMsKGJhPY{*Os{UBi61{AD4CYw{)?^e~3U)N!27N zS5gKSJ0Mx5>9Y>tt)5*gAja6~M`1YBQFgPxh20I$08%3Pnbc!$H(i;n+a1@FO#wB1 zU>su%0PE?@M4bqN6N?5C>A?BBJOVu$yig_dpZx%|zl4i@48g%)##<24A8{VGWE!Mi zMc_;_qK3^db-t~siHkE~%Wf=V#Y!a)a~7_sQD;P^r+E!=8QlLROnX1V2k`AU}HbggmlJpZ{H`$cyHrCU{4Q63-{~;MfDy*~-jX}4w$^;Ufoc|6ckP`Y5j5LsBL~n;) zo+c-{L75cXN03QlnGt>Uxk)$@NxlV;{B6gxG_g~@o)w6pzx4wuXIV~4+^@_nlB6CuJGWA;lp+{f?5vP__L|^ z*+Mh6XB$3Jf4EEeAl&b1w!!u`Z%El_um8H?V%+|*(XN(Pld3l%lli+l;iG-1)HHhS zSq_mUR6H=~+*y`|DlzZ*bJJ^$x9Lk)p6@q#uDSjkorR>{qd(cBq2-0S*UA(l-Sev)T692dr$Vbu-QI za3VRB{qqU*`&WfBY5tKL>O}9F$-)*#dEkqmALJt_2eah4k2A?12VeodwrjcuEpw=c z<@~T30aK;lTVu#B3k}?-zyJUP0E7Od&raj3ySmOhte4cX91x$7tK66?Q>pbDj4%gM zq0tgAa&8HZ%v7)J_S(23qwVU}HoM8ujzxF8SyNoEu`?-Cd0q!|RCWEZi7?WyI_>8) z=^!Fc;D5BmevFTxVbOKcuTUD2`5#j?{fQhFf&Cae>%KdyDakfbX}3RkR8;HVmu5pt zkX)C=kvzY7No{|4HN#wcA)MsO%HL)6BD7r?N}WC(4B@_;R)eL#pmp#zdBdIxsxv>O;+MOC8;^AlR*|~M981^`~my+k;Sm=-}y6x z27cQ=l?W)UaL}RZGR^(BXuoNm2*xm^8ZZx-wY-Q56>+|u$^L>iFsnXC7dU^#D^U#f z0Cad4x}a{li0-4H4t-$sbc5hvu(fGII0f9m4>Q>ugN_gm)&KEm*E$;tXVNXZR>C$@ zaB}QwWS^g6J)rpHVT>a1+wQ$^|FvWO6#Q*&GOWIdWT{-+J zD4-t{77J{cE$<7Mn@ckR1h#^!`eFAesX1H(Eiat~iJWbngB8Bq&efa2+YPR^NG{L+ zx<6yL7!`rmT!gqcTIQBg_TM@i4UuuO>$^J??vF~+Gz;V)s#Ne!u;>Q=^v-grazW}w z_lERf?UTF+(wM&a2vfcuXZJr`5q+R)7~9@0v;pQ5Ps`$UJGgNy{<6MVNgVR#52HlfQNHNF^ zplLeQO@Zb>8iVm-GNu&0>OS{YeYW54j|5OE+feqGx}tlY!bljZ&(@d4Tdd4AM-rb* zzN1O(1bZqH=O7Evbolm{KzXb1Fsr(z>wBb6QN_1#7>Cc)p}VL|w2=%M64k}X8Q4W7 zNC$_z0D?eZt2U;JJy~9W_pHp`_-9~?&E2rLnP1WhoT~mb*jp=$jXCnT^R z@qZ7jixAP%R@K-_DRuYgr8?Y!uwCnAT5J291!YStfTKU@6`mM{HgLXO0onz@(C2|x`JfvnH^1D3MtpP7L;W{%fq{HdP2+GqQA2(VWhhtfq&jL z%k|;~ym8M0jAA7wK0*FhGhLEq`XxHd083Ko<1+WcLt(t^jpW!@0p4pFDKsaowRvR@ zRBD`P+Z_@aL+rq>R2`^bro_1)6MfCU%OHI# z%0%%CXRcr|>%q0YQ}E zD@Wq4kKih)F6QxFiSgu-*mEfW7J{yuVQ*ULjAlD)TS$9Q5Ytl*KKEoR&%`r69lPB}n=ICkvo+|v z6^!U$tejPpIYx``FGJKDP0Fn!EPBKGHQaK62~R^s1%#sQ1}l402AY%f+X;gUWl))K za25j%Sfyi7=XPqG_^j1~y8^0-`Xdo=xy~()b)$CWWUlsVG^%x{#QJXD!=aWK&vj(j z;{r1*=kBh5Z+dM^A0g^esb%laU5Y_ej)jPz>76~h3Y9qwF8b2ozqT5?jDZbO3OlwT z!h_Av9y-x;^Nr%rHWQgXo?Y$04QEWhPU;k- z3w)RUoL)SUz|M!z>q86T-5ogCbNj?aszF_FdVbNiI7pUwl++vM)qoi|R)Uz&JEuvP zi|n$5-b=pDqE={rz#8O&04C$J)5U_GJ>WC#Ybz_6=zPZy?3q{(3S}xT09`N?aw~Io zsBpdkz}pf1GxL87`GmGa`jgc`{VJ^$<7GR>8FjpZIO=$<)m1ZGO(E-s+@4v2q_`k%M2u39dGL37nhgfbb@v<_odNMzL7i37C82+??85;rewJnf z+wo@Kcq>cqGnIL6J`sU}89D1ma;$QOqchDTpDLA!;YpcH32&)1%eQ9!1a<8tXncY@ zvf7DH5&$#_K+U-p0H7k#w8GmVug+P|_SmRrQaK+YR*7`TK=~+WMMyLyu_FniVt9`4 zVXonydR|gPWW5QN^@BAP5b;tbY9I%>4}A+@YPIbW7UoFC7>-m^m`K#}B8M%iAs;8p z;HEx!;?9ZC zCp0uN(znq2dJnJHR)$?BGa`Dw@EEQ6>bo9WM!|KKm=m zO%=6df649EZOjlx0&G3;63Vr*;n`UwiacZMQ!w*u;E|(Qtlk56yWb$aEq+Y6d@hXlxoCQ71qQksPojol-Rx6fZJyXc+wWgR zPS-kVN59^V!L`7G?{d**E|gG|YUvB!Q>|HG$p85RY>Vv@IfHKKNb0cbj5Hz8+JFaL z-rG|ITefJk>pkhGtV()jv0{GDX9hzDo(}(TF*ifqm9m@{eZWx@vT$AJ1;kzNIGf1G zg*bMh2Qc`D{A^SuGN(e&dAMIVRk!J({x}oHM!Pxn7eot0n7D0{q-qzk%pLWQu!Q-y zcpJ``SQ7srvPaCUM$U;NYe%~P00uG_9Y0LK@Oc|#&xEtB@{gx;?wKZQ(ZD1kQL#?& zZ8dy}rhe*9iI1KE0yHS!l;qN%#z=d)`_nOX?*KjRCPT2)@tGdCdJ_W5F(mW+P$+!dU2CEQhrJjQ}YaRyO6g=%`4y#>vj|^sTwF6+dTwv!h?Zea7Xx zDSD8VrP^xT8=V7-&9hf&H{{bsG1oW*MkUJxC4GfdF%Ys*=&Tk~fC^6pYvUYLqC^}F zsS|i4<19W)`FB-7@@_U|?=2A#+y9^lfdUoHdat-|NwjpJmmm+4D|3;y74jMVoNQ5C zdUKFq^jiO5F>Fb^+c44JX2XHjU7@5~Q$dO3(CS{vbF;?9s*FJjH zt!Z4#7VXWHHJJDwrj<)}cS@7w@r1=Z!a?s&gucAbssy#1y#-WU%eF4OT5xxFC%6QM#tH74;1E2x z1QHr|f;*(KKnU&@+$})R1Pc~I@L+++YqIw~_ndd{ed8bh7;AKwt*Y;uyEc6%8BBg=MPZ zvIjd((myB6cs8DtXL&%Rd9_Y{NVorPHpj}$$}M>Q{I_$)M}!Ra-r*~ykI9=GrpB2N zA=@l(7bw$&3m-TzbkmiaPko+OXlGDeOFL|{V;^xzerdkFLeaFPYTnFzwCM+XU0f8@r^E8Pi$$ z08C4)Wpjb*$Sm70eLb(=&l~C7I@L}Sj2!cQ8Y##9iuMf3j9bm9X+h(?*CC|2`PwSF z2PLobIr4<21<~K(eM24wmQ&T*KLcR}kt2BAKuY?FJ zg5D?71J2ZCBOJ*iiSvSCoG8C-m{kS|3~+|XzPqr6;aU{8>*Dh3oyDQ*K3DV=fkU&c zffpN$a}L*mT8O}a-J;52LA|{sPjqlHGfz$eHM&)yoRO_}Z2A32W!lAFrC+yid&6S{ zGb9@VUpDnGCCTg=XTGUcZCfC&)CivJ2G=)S-}(NKhMAKW;~W@QxTwQx*m%kmm2G7? zN^i&t0>TgML(D#^z+R!%1ej-j(9Gh`zGvI&lxx_h(AL>vQC1%+YZS5ySEy=Rf59l+ z3x2XrQ}u|;=x@>H(=7jWh4TwjA>ezA{Ue+Jr&4WQ`2w6~^Oz)@tM}cX<%O;C zx_J9w1M4rFZHqJ`S6W#Wt7}Td-!F{6=kN&GFoU}owosmD=%*{%kyqyGNzb_)WL#~8 zS2;4x)O$FW%6g7poqo?vJ$&anv!m6&|HRkKuQGZ)?bT{JYq33at~N2&SV;2GM*>~p zu@h-a$!9b(Bj+{X&zb^{TJ>hl`Ca7=xZhGAvIov}es_+iG82@5kRGD9*<3D~eBjY< z-Yt%M^76;DvFL~XYG{x7+DQ6RZwgq!b3}R&kMO=4I-6k2Gx5sbk=%*8BIL?(24vZ6 zkKP93?ox}&!T2CNu+09a%46AnHHhF`xCc z^!C{nWE1-5WXN=Z_c!C|1}_rccHi{=T8dO+^(%E&vQz(Ayj3mJ`0;C!+tY{IIiE3> zL`V*gB2wV{?7RlUSx@DA4)cne&yptVFpXDUE|Nr-j)_mw^pr)rW>u#zjVVq*;E89J6rMtwi7Dte8_E4^OJYD=_%}<@$HX}dfR%_)JR@7yz;@? zf}YKxcfg))eA#(d_H_QNwd2$7&T!g30zAO}e)nU|3QJ#q2IdqTmremcW%64c>E@^N zBBIcHW~}&RS=ly%8GF9DE4d0LCMTP}3;VAj*~-1luQV=8Miu!&2H`rbVXNplZKjF- z_i07W+`z#mY>qhNJkhvVIOn9SBF4(-fzHZd#HnA8fOy$wVk9K49;9jkVS~1LHzdx` zx|48lnMf}H0L!uk_*!&E0EIgM3IzyL+JV74{Q(F81Qg{c=cgu6Qi=5;56k<`tKC56 z57KM|?}w7p2qzCj#V9wtzYYK|O7g-%>*y^)>>i&jfPPazmM{rlP*!Un04>~ZG)8)= z*Me#gMKPMdTP{N5bEH`!X zgpxd`%bs62Z0|q^+D_I~i=M?bTX+IlY5k=;V}YZT%&pR?5XVDGxA(i8+>@qB(Y4I7 zymv8FArjl4?+t=y14(WPR6x!X``c9MuEB{;@MRW}IB9xh{Uo1@IWh?>vLWOO=aG*a z-Ka9GFME5mB9Ii@wM9npMxV{jf9L5O@bciUGeG8#Vd8KQrPf_F2na?!0MNZSd;n!e zo?wg?;ksluB`eSQrIGor>@#2|61omx!KxG&7Fz_o~cwxS*KGp$MsokMn`5G zyBi(}q}`BHo>bJcg&=~pB6u6DJ^Pyi&=8F$W)xyiPl?nIEY(M&gYO$_lrX?4*=v+= z7r%nhHVi0Sp!3>7Rz~BKXND;auk>0HE`ww+8?;VRuD( zNB$HkEXyAas(&{Kqn-F6)e zI`R>zU?$bXfD^rMWpFh=e+P?P=3`50_iZnF`$abxjiaT!^-*4~P61WR&{4Kf2nNpM7mX@&~Isb6)U4(ABccrgzYuF9J=OiJPNyM#*65 zI!Jk5pQDp^PVU2^7|kx#^?)y}{=M4dHudGo7BLjz=&U%0YVe!x#T-_{MqC!_sAJy~ z=x41_#g8QnVISIg7GK?W@mKA$o=4a*xRri;4?CgC6L$5T#VRx5|DD0GocQG|;So{q zZxH!a@4-vC>q+m32W?XGS#^{>Gpw?svT4R!ie;G>r=fuv6itx^@- zn>g8g1B9<2X=TvyzqM_+%-9-YFr2;i682TLg&;DCC=o9*j}|y`zGphu z^<^H8O5QC>Xy>1Gh}xtD z=*0A;S%vZ1g|yo_R>*L*9Dn=udgw&~C#hnicE(rd>`M;+0AK+&ES+!M&khYB!oMCS zYrEaF#6E1}A6Al%4PeL+Ces0ok7RLCX}#~{3?i=D1&w5B-W4&N=mBBkpnf!aOPaiI z$#YybX5jKpjEvPtSnoth(^h)zZBQ-Qmc2UrX!Nbe=BQ!Cgd4~Rr&2$b>gh;`3&$(z zRl#-iC&yF>`~&fgt##r;mao?`ibp@pCNsEZ=~8OA#A`A{%^dg}SD5T<|rgcK;FD7DNiFD)I0G zqaoe#ugbS{EKaEpyHFsFKRMei`_RTo!&C(N-u4ZSCpjkm{2hKe7+@hf{r0WsZo@f_ z8CId>(e~-lUsEj{qK)-*k0arrNq0Ma%e5aP!iURWl=PDx}gts+`fL|7J*eF z0xfTo4m>S+r`TV&u82TT;3%Yr%E=Lb3=)0kWygt<;JJ-UpZ!qYN+>$n&^)5jppM+u z3m-v4s)sBL>bM?+uNnluC^YdsYQs6fRIO^r^LgEZmqNskRr#FYjwDb*)xdmTVm>)_n z%XeL&=bYh3E}eYrhE2)L>?&1dA4JSX?T%T|ew|0zp`=ex6jb9pExpm0qi{SL66^jz z@Lnx?`kZ^~yYqG4cgy{koj&>GFrIF|S8AYD@&|f3DXtRNU%p_1l*%(k`lGX|AVMFG*>l{1MvQTB1vS_1akSS*+}2^6rx{xoR^jYV7+iT{%nF0s8sx z9Ma)0+5^4&7Z-0$E&;*u1v2P817@+yH3bV!fK2SirV5pl+L~&N=9{E;;iqWl-4Gvd z8&^*Xs_ON4D$;MN{ApZcCkr28r>lf0#H0(BQ>pAWzE7+sV~M+qg2gIA1jO)5LTGC% zL&ah&&>g<+{T4_g>kw9)F;wAK8srTYK|QZy61fp+_*hl-jp-qC%AP}}E&rvxR-*j1 zO!IErR!0~UtxQ$TE-x=F=JDl$>v4*PG~miCSDW*y97~@d!=qu>z%c68WqF<499vZ8 zz>-)`rhN8EjibbCBZfe3CMEcSpnDP%)6dQ5qsOdMY!tU-!PwiMmGQsw>=y^=KV~!W zaC)0js{xD#F9e$=VK0wKsK3N>diXNSH``yd#e@rGCt}XvTV+jZ`+i7o>Fnq;)2A^F zCvTcTORt+dinn(z+G`(vlQn&7aLXefL;Tu--7Zl=ewK#MY>s!^X}2}j(9@eTDw88* zSyX)d8%bH`z)cU(`2_m>cYM>#FO~MPhMMYHN0K1!rfEk}p@~343oD5ix&=OKkDn#Z z%^w9fi|r)!%KlR30i&V?o4jU_xwa#~Z9rfb?sgKP$Bui5pwd~}KA#e_5-+=_&hETx z6^v_rH*#i2*fo|kT1FF;qAnWw_Nx;hJ4IIbTX$!n$jJ%vgUsbn9Q1*X<5PuR$px&0 zqyEK<_l`$+3w(W4ZTG|rCPoB)JKUGuCd`!a>FfufNJ9()5VMH_R0@(H??)+6z%cx# zU=P6J1FfWXVDN%9>+jPBQ{_eb;v4=1xVs*Kw$U@1Q?OEH}+Vf#1v+V1n6K=MXak5?HR-&a$=G-Y@e7`?@p=ExxEvI#AG`Ou8ytvZfnyHTy` zEJGj;#cgVFHIK(lg;X>1RoFf=cCK0KDou=nnO3d6N1R zf`c*;|J47dl>~viC@OLTX&+91@*W$&?E?VDhcMu3`)ohyE)R0(0I183YFg7n!zv;a z)IW%_6$%ZF2{Vyy^lc~9XYzBA1zSlV!i2+nbg|ug70y_NK0R0luwsymHj#`b|BKN- zW_mxZsbOG!QEruG(n58oc?f023kOwG=5n%!3g~)?n3OL2#kFD0kHYP6 z%{Xoz%!l)RXoN{Fua#6BC~lbk2Mw_5-_bres0&9s5e`6`=^^(h&D5@=BdT8*!_U+K z;7Lfq53F7KE}m?B^K_z>yskD6s($oG3h!mwu?f`g@!6k#fAT}%(XzMhnmiR5#_n_+ zAI8Hbf9dkj2XOc9j~tfiy%CJVH=vxXSBwUSt;OXCK=ID?>;)BYV5j`+xh26-6rwSZ z-OP$`1F)6=bo9Tlfd$Yp=t*K>{{bAps5HJy&_7snNh!s0?Fh|Fd0CPNw=RX>C4&Pj z&U-i4qIjOnap0%irIh;wvn7FPHPJWN28(oX@;O|jNYF_ZnALE@T4VFX#!2kBAJ5#7 zWP!iuRP>$iNqF0hg$T3DGQnk&VOy9zCep8H9Q4xMMB2#}ksj&~HjYowJ_aO-c_az0 z{~`ea=xDyc0Si0;<-H0E93Y$qYV84lHw=ED{T~ES&;gv2KTy@7g4wXK1Lui~Pm>(L z!zPr@KLu&`RL+ANg7=Aqh%Yw)d^NGz<}P{=+vcanG((Zbm1dGynTpT%Vo4X7KTvk@ zkUiiUj(;}hEf~ULe^JF&+|~4%n~+ z&j#X(vz14Nu;&l}N>>AdRq?_A`f1F1P?J~*ob*$Vg{el%*Sph%DMR7`jFDPr$lp@H zp5AZ+pX7xFdP(3#mADci@uzysdnQnsawN=99K^V6 zg(cwRkE3H4ZMFIx5S{R7M@z>zY`4W1EKtwH@nnv~y6R;*vva_ql`8kdJ|r;;_VgdS znR4W&^uF07z;x+j9{~WGmkt{+g)%sRk?3C#do(Ty#R9$OqiG&dYx+!UbgKA$$-g`d zqd-&x+rR-oC~%ck;PKcq$Lm3Zrd7q}O)jQIk%-nW%_S`XL@#;}V;%k`;gIN#gsH1X z2qx)rx9{Zm{J}g;_5tqST-mZgkH}lJRC$4lfts}u@Oo)$6VAoj*e9%QgBoV9Ce$cCwQLD*iKQ2xCR6Xl&s3SdifFUIAPv;EZ(3cq02gs%gX3j5 zJI~INKI$Y46dbf7?ynr%4!j{dclXg-)Oik0K(8cw_P6NYO-#m`vp>8ue{B(#k*?f zo+y`+X*$_+^xbDAa)N_Myja1O0PpjNUh$e)(LfFD(N` z=yEjBD`%&_7=D#n=(PGdH;1trQb^=7wD`I5M+5r@4%Glf`|myG^I1vUylVZ<_**hF#!N@C0oEBU-#GS4N_g504RPMaF8&hml|!4 z;&*{Mn5L*Qff5j<3E8R2!fp^TAY; zuVS@1^%3R`UE@q2JRVa<;AqLssmkGLjc~FKG%=~S{063fX#TpUBzrB=1O0?>yk(3M zKcZX17(o>Zz30Y;8c{^`)(iS1!Wkr0vRF-Imo<8SZTLm`FzH}7ix)%=Pc=Sv-cAB_ zf+kdzq8u{CLXV`L3@Q+-oc%}bL;lz}e<_W-IXM8T_eW7;#+@Jw|C=rW)%Sogkg5g( z2&A8=!@%@QKrCxG{7)HnpOUq^fH-j?#3%^YfJ4CcaxU*8%cSP8Z+U)1+iCzYWy|fY zm)LZO?J6pR!AL^|fp_i^^(uLJl|WaJ+CpA7M|>{<25)X|RDT6Pwf;4)HR+;Wdsp@S z>=)#AC0mAJ&W}IG^NVCL-K=4CXo+fyJp6P|x7?=1b)L)yyT(E=)4ongAiZgE zYS`(qcRoHtw&VjdNmt@lWW866_Ok_lFe5DlFaiK{(LpGEe-fCC0KbV=0I17iK#t1# z!g%s*v19%7T~g2FZ{YndQd>!Rx#=c=slzX?D5zdg9?Gq^p~Iz{)&3Uy~)DyHpc*{P;G_ z$}9aU?sxcYe1sM13(WC)IgQ`8`{^=WVc+(FB3TD^1Az2}DPaZKU4#3LC}e zR4?^%X18G$=2T_<>PHAY+ppa}iTJSx)DqzjDC+HFMd)rHo%_mdSRB8Jd-cT6WAlch zhw%uaJn^o8P|kShW#ByD^k_P>rzaJIazD0TMrE`hHm~3S8VafF+wh_H3fANyi*YRc zdsZ9xsL7L`?gz!k<}fYlzepwPxe%6ZZ6PgPs;>_Z*vSvjd6KFKexQUOkCV^5Ywl>Y zb^li-O@c&@_~Vh;YsEt)?!s8kiDOIc_mwHhr)aDS_l7YB&3Ro=LVMSjKb;z_G!-)% zEUGrqaGsJ1L^7U^Epj9UGyLukii7U0s!f??Dq`aX56}sD?!*!U$3X>~3g4i^vf_R% zjvJv<0`XAs?|Q5#wvnEnM|6xFpCMfaC)oly^;2HthOqwVbWTzL^tgBEL}1<$0MPn) zN9^F(8fyT=4FG*Ez>VFpm-eZ03hNw2+XQDu)H(kVf~hGK$vHFy#`3>q1SDiB>`L;* z^?BdPjfV_77x2vk5>KS4ei25LTXxBrIU^NyF(`n;t%NgQnqO*rWVZ zAWwf8VX5DXWp3Rr&)|d}Ghvy}=MTqKQQv>MRvgMo&uVOX4IGDG?*C5v0^v;~dytg< z)A+jUP!jJ$K|9;&mdGoOG9CilU1OFUx7)h*A|cHrI@kEwZES zX6|acGjY6f>`eLI!1gq;IXlOs-nwxH)t^-aE@>zU&rjs&&)|37%3U?Y3)m3B9gvXx zfj}O+cXdzwV#msuP|_t40DxLh!GnXnn!mdW`I2G*J%1v2t~ZrUAUOc_S_*cT08&HF zXum@IQxFcvAZP^)2=M_B!bW*oRFLThwmGyozHi=#k6=Fme zEljXhTa7GTefsWl3&dZMFQ*^02uD(RM8;3k<7LzAKB;XG*zJ!v*V?rmdE@=M?12=X z-0g#bAn#6n{;6od;&)HnbD^`HV(?EkNr|4scNSpd5I9)IKl&60VL5`fifT4ETe z<>3Psq5viW0RR4@I3dUno^TVBc~bx`zkPbPt9i@5-l8L#-!t{Z(No~tvQ0Vn3@x!E z_E0}Xv@^D`zqiNQ;&vw9E3|2j;sE{F@Liya@0)}^rM4g62&Gj$T zAS3dBx)N`2XO_B{1;!7?{gPjdc)*^K#=7L4f#KSh^SO z13K~y+ORR3Izj3eIMQSw)~f{o=$sKfsJ(~9F2)uS5YKz^j-3aMB%-ny(kCB%!L%YEMx5o1|A5aD4)Dx81OPl8J%EMhy{D>FGbco2 zHyq6g#hc+1vRdA9X-0;s{dTs;%;Y^XaFn1I)Ae6M;Aq}f-_U&;AAQu15+UCZh^s%j zo)0M;n5a=6q;{ep^5C*8A0S$e_y%$F;#mc@LXh}Mk@zP56CY>_ANd5`VP2W=qIPgN zQPLl5mUmY4#6K{J@PTmvqW>HKFrPBA49IG`D)@DvCqHo`=6KKxn6yxA0GP(m;}POo zfW;N^gOVqz+&w|AbQ+4wGpRHZs1c{Zvh_}mx%Z9q&2o#scER24-5tu`!!C^F~O}nktgg%@iQ41zOOe9YiDKJ$!606Zab)EGvdDT$5;idH@9Zjc%^0XJ7G#FwJVQK_!=# zu(geNi*;xe601?rM3QjQYb)HlxbjlbH+&E!pX2h~^bY0e1g^-_Y4&Z1BtZy9TJG`O zh758Ju~4KLwfjY{0EXRJGM|EDWRqkrqxAefvs~+2q7%lW0B9)PuHE;9o`m0>R7F*I z0r$R45TO)%^;GT=#SZ6GbW~jF`{-J)J_bJ=uLP|`rL?>tkLJ&qv1tlbD^A^?b~k(t zZIbJcd*~Y=Y@#oTni%DRB14gJ#!ihF2+*}MsI*E`_@!ep$;-abbZB%k1nwQOH)$`^ ztyjD-%*3e@G2vmcS=M{Kww{jz;t8enq$Sn2@K36CU7Ike@BGmI1z2}%*{lE?JZZMH zSiPv%{ubsnD@5S4W|Cn-L%#nlLz^LX=;;DE_OZQ6S|%tz@4?udkv?06WA2ZmvZV@5 z!mY65!?}WrO~JQ{za*{|`%k2VLHN;ab?Em7Rb}FJ5<7IFPq4T;P_JnPIIDlkeyt_h zKuZPMcUAU`7Eub`s#iHHV|NyA@xqO}!A5fW4;_#~Jqjw&!&d*7MqBe|bJ=LE0Wgqx z$oZzxX&N`|zn>~nYVJO)N%>EdSU8Cc^8~oQAz=4;I50pO2PY0=FAf+1hW%V%n1$}h zrCXX!03-+L0^Ft0ySsi{I?(!E)1x}IwuQ|AX~oW!R$RA1EfvhY@V632Q-zW5Y0j;t zR5SV4U&X}_O<{#$Wc&GCDSXV3MO3+^6DBHb6oxQ{g>>Iyh|_*mf`!EeWvFnbkWqFp z;b`E7->GLXmu!wcdp8(`yQ->+hyyvf^xy4jDspeEqB{zruH^Urp@Ok%38XSU>p?DN zTUtIzMoyqWfOuy(g*}mF**ePGSwZkE^LHsY$aEXc7EF!Xq|U}(iC=c!z8JmZ5$GQ8 zL42}kVYkC)gL$KD8%dB&y-NJ;H|!(DbNdRH%|B2`7rX~y;n{#>*!i- z9tJcOQnyT9`S4+1?wCdum*f@ zB$joCi&UuCMTu%Xnp3lf2L+X!QI(KR!#BA%00(VEze7B3YeoeiLgz%byYguxLNs8< zc~4b=rjJum5!HLcB=JnL6t!5MxQPcmSHIZY7vmQdPw0zpTC88h z!n#zFLU?8?zL(mT&QwiH>z`xIc7N<8cb9#wO3Toyzw`#N@D$^rrt(zHlLEcXSI))c z;iM#4(ZwM?o%4DNWl!sSVjEY&f68>ntMLCEe`zy&wOBmLI*?LX`DItBM)p;obZd|! z58s>f67yA#?64Y&o3QiLte>UFYMO@mJ&|6@I+=A(Z!vCv7_^XqmPY2kWnN+63%+vW zOYzHPVci=%_CD&su~RES{Y!Bn52OS@6tV?omHKLTZZXJUe;y79!~fA?pd20mtpn7m zFIY;&fRttA;M|l2Q9Wjem@s`D@sHqOg~J-?7C{nnI<CE3!)}iFM#MZ>^Tw9CK z_)(5~ZroMxOx=Y5LpI7|HCYi&?OBF$+bY~04>L~VEaR%(uRh{6)C-X4;E%FVD&;fe z-PA$iIp`a+op$>zaR+$4WI%Wb=`aa%o!jd{nsUp;DZs@ zror!$z@7jg@AX$Ea@z($=^y(d!T{~HxjOPxg(uNV@bV1KB46;!1Gw=cIHT7wfED~u zISF|OI8msD%y`1QWV=-CHY`uU7P-N9#TSl)kcb)#7_&8xG<@}Qh)@44zPZTUy<;7F ztU&=ACtC|x-_ZSnYZ$_WD{n7)dz!he{A?+$X4Efrm(l zu}FyV|2xEg@96&_jPx@)VK4w5F5!lM2M2jAc*|q!{2_*!hKz&6zQB6!kwt9yH$gx1 zihbAh!OwL(MU9<#pA4ig@yN{1nO7$*V<{$Kh#}FuLZX>?_|FLNSB3wNUo!ZgMxVL# zfEc`b0Afp4;8_ETJoc&(?TIYa6StSb9Iq@}OQH0Df2hKMK9^9448vzo_2Qqq9143X zmlx^fM9&BK{2zV6H)}H_-^-Sls~jpWbKtbtVpYv(b?=6F9z2@E=7!5z>Pq9Z4M%4v z0w%IZq(}qN=HP!ts)uxUki8KK`}6m29fvlQ7=4$9pF};phn0{LD0LOUYx2ej0nWf+ z2mE>iVTuGSEAymxWk3fsA?{`oaU-1cGXgq=j$u4YTJ)@+r9f8f*-c*ijq#0KJRpiZ zaNXxDSS1J~n@lb_c!aM)k2Zvnzbl9J8SV>1RbKm%X{$_^Itb^n zIs(6DO!q!E!hD?`N9Orrvuw>}zHGQiEY9ASV7+QRt}=v_?#?K5md&v(UxmS&)SR82 z6~-))yRw48as7z9N$L!en-_noN49`=lmc;LVIw)KfUDD*YM*XDHzdMa!{*C;It4Dq zn4zYV2_=4Bo@zAjYfjlr0Wv2Gsl5jUybqr2u&_s?^#GV*B(Oh>qVgSgoP^j(JEK9Y zt~Wd`_h$t@C^wJ}R{mtAm1jc8k?<`5pp>W{+@-)v$jLYQK`qf7%*H8&i$+Q^%+W+= zINWR_kAC9F%L=7ZN&jn2_JcXGg=6wk$3cUMG#eDhV2SvZ>xAF1r}qZspGIgGTvpPo zSP9%%zds(dG_dodz0T`VGCpU{qVkm1;R-lSbn^XztHO`Seck;=`h{aUq%0Du&0KveYd~SbkEtH_crGh9IO)eIgBZT9ApZ_$V)*+s9&z#X9XS}f4w_4m)X@fxEYQ4sg> zdffZg`HwT-1g+WUApM%F72y65i}L*4b4TTsgCmDldf5UO7u(=JlJM8NxDEHsEDhj! zm{zAEnS_iPKtl-pX$ zZD;T!>vA3tpb-^v^gYHu$=|&yQbUIKD#}wZ+gj1}!p9Ca;-MUW0>(y}3|%Ja4$9F2 zw|eO&uTkiz-mh#Ba-eRBrbo&&-7Ea)*mVs> z?6T4RNf=$}!#vXl9n*`CGgPU^md|=_#hls|5%wU;$jv`-C+8g{1zg|8NHt~g8yYp&g$i=cZXrnv zo!$aKu0??gyw$D$eS{UYrX>OgI-XX<2GnGSRsoTaG~Ve32ME3dl-(2^kFScA2vmC? z*}v%QsQCLVyCxLEIIp-ZU;u=0Mlkx9CLfDj|ZMjZ?2e9$66XGyP%ITrDb})VzQh6n@qxjq0ElD^c7bWfiAj@?n-fap?W0pb~ z01d};P$*9GC71G$uef~NTG2T9r7-^Bl$V*3f`@iLnO`|!lUMed^EsBu?+!Z5Uuh7SM^-#@DbYM3P;L}*!6Gb6vPz)GS9Exh( z*_fmFQXE!*wkp-{!9)Sisz0VSqsJ?xkuobQ+7tl>ebsL57supTfc>VGdW5(`(SR0f zoA~I#-n?fziha_f;(=6sT+bddTeH>FO#{4y*FojefaU!$|bh& zzmmTR&yQFx^XGC>ARgc?_29k4e{;TSZ}5Z|He04mY;ZtISV18F_Vcv3igu>P$e!*n zk;ALq*R7~z#|FP!D6PM9JD6XXBzTZDk&TGg-(nGDH=DE7X%zs3D0!iQ;>H%Ee(pUJ zm@adP>7Ddwf$lo96;T2G8jmTsrekk7Dvz|D6P27*YQ5GYv5>gM`kdPj{^auTyCsJO z$f5hkP>`8M8tFuaoz=nuDW!-+#RX;zy7kMa&rGctaz_JV?t7F@y?>N?6&-R)aMk}% z_1)RH#)ICmPmf05wvLm1V$f8*IUX}u%#)uj;r`_?>f}I3aXv!(qAOFXY&;ZsY&X*K z1bN67Jmc~%{C=mP{xbc6b)c2$kMKc8qyd}(n{Ol8ulbR$=^yQdX@Kv9ui7^DB!%5l{GD$$c^;n)N=f=5 zCIOo$tnaldL1!7pps5Jk8T2FFntcRxo3JP5T{+Az8RH$PElStqqrBP^NoXuT#rqiE zJv&QkC1uP_hvcB=9t)<<-031hfi$$8gwwLb#|5Yf2GdZR5G$;VqsItF@Ep1HPuz;g zwx1<&eoq@%RL=;sT{AG*t~Uw~Le?K<2-@lRw~!SVziC*u_8Coi#rQ-~z%SC-6ou$e zOpfoHsz##kCrfjQBkg1+lejcl0>2D?9B>9Tpuf~5L(U>(!?0T+YRPZlm=ceGi%+QJ<4 z(E547;w=UONMYrDOOv^!&Wm;&$`gKXAxmW%=#DNSS2}f-cHa*WO4?wq?3;T@V;@`D zxUMVq$c1*k-(vq>yR=*utiA@YF^~j?kOU6?2LgY|2s1qp9X9tjd{7LfU`*SH3%R{V zcsS52QOE-lCMHT#KzYKHi$Lz^$Rw8J>0wZIgn_yP0iJMp7eLH$2!+O0gXkMxPI8)i zQs7SMjO_uRF=$Tvvvdgr?-4e;8<~l~vOZ~(nJOQ}_3RJOxT@84kX%G*s?qQiK{p$$ z?c2YUC#i*C_4WBZ3M&yPLf^=VF2tQIZqSSrof3oQ@gp07N34?_s5cijKeq@&oy_ z0fzR(7;Lae5D&UDh6rSV?%mCMBF=&ox+J%e#qUkz?FFBF`#BjPqk-zxJfM$N!-D2C zO2Wz$#6<9IafU%>iJ@FLrw~scpx=W;ja(LpQ1|}NvEyGT|9e2x`ftF0Wzp~wJS&MH z2bezoaR*3I{?5fUH$u+cf~n4W&>22D}E!cRGW)-guM zTZqe-B|SkC=8Zbsli6b&Sr>o_3P9p2K;m-wUvd5InEcTrD@s8xawO!i>7jhkbE*vh zu)*p;N!~Nfr4AqPlFIa2UeAGEjv*vS7?#?CXiS z*3qR7jSf$*cG{;_wpxoA6|{MCVaSS)F=y{Ees$ohRt8T2I|DGn&7cR{1c|U4i7@{E z4?=o+l&n_9cRh-7AbI3R8W`vYBQ2DaLs4K1TXrPOKMBUsG54Oqw&C>1_3^uIW{~ZZ z)4{w(N;nM6(8f}y{czL%-85*x7N|&mt4<->RIJ(rCw9TO7|!K4$`?;u+7o#`HSvs7 z&|t-~tGBJsE~r&@O2k!3N-VvMyA&gxGkKv&8yD#<0cA)EmH#t^fAg;HFgTYF`2eb8 z$?Yn5f)kAN+u?lZ{-Ahy{kUj}Ul4}9s_>F0q2r;;ZfO~0=KcLIcZ-rvTKA2H+;AzM5eILEN8@*8A<8oz!2ng!)&FM>ng+%e`uKa?61=hpd;TZa5-mT`1 zRM0)o8ptK3(%U?tI=}l+EgnUst1pen<{^Nq_A7KbvosXPhH+-HUD)bjz21QB=L1xO zcl#1{x)1P5*EwAFo|AbH(U!0G`aEBTRft0i(H7pr7hoQ zCb#I)b+5GaQ)e%E&a<%?e(p;itq;XAfHa~%-BD~aR){dfxco#vJXd$Sr^_Dg0f+py}C! zOhx968=3FJRYkQ~b_rs$Hp&NyUotorqlDOX%XiA)jSbfLQdZ=mVWHOXBRUcLxN($i zpB3J*pa-MsXm>o~D$4!TB{62hRP?4ZIuhVDP|gM82jV%#sqcNgFH zEtt|ae%sX7ME^!Gee4yeu~fRtbrAAWY3-2?q0dA}&OSzn^AEBw&m_yHS`ts!yiYqx zmn-5i<687b5X{Y^p5wzuDwX)zvP=v!Uo=dxyMJ`J(;1QSTr+Qw7}!%&%26|r66+J+ zpxb~cyz3K*1r%%xJZ!d%9n{i&_&;ON`tUxs*M$cUNm2W{C_CF;xSB{DrO)l);KVo* za)@DYr4;Lk3f*X6PUtE5=c z8=ZXpS~g;A<%bkL6Yu3Z`4or1uiZtX^|0Q=xti17U#`v}uh{u8I2zmY{(0&tb;GLb z!L!$)M%}XqDxFzPuts`7i|0dcba$e+b6j9hn5*RV+vf0OgfO>mEanBu+Z2TM=FY#e3uX z6+dL{rZTuHJ7v9cYk;9aZ}8mpZkiR|XBH5av12LET%kAeIA3pjk!X^2#jH2i(InS8 zw@9-egG!s(a0cW}uRDW7U}A$Ok?u6pU7BQ=V1K_H?OuP9^GAxFl0H0n(9fLfhdqTI z;R{pqg!PkRs*%>&QJp`kF-D|(wt3Dx%x%bA>LX(6e?H+9myZ$!9^YvWR8T?szgZY} z+N`#f^T`;%z*$oJvpPKTgw&Nz`;|UK38`XHY#IB;08d%LAvZ6|2^DP8LVP%sWQY%6 z*^*6<)rM99=T3DdjOVXTT8x% zl%>n#IYy!3Ph-oqms=lHW9Mg1`G}VK1 z$eOaUIY-Qd+n^M_hYFOfw`+xls2qyG!!KV&$fE4clCNV@2f1OynX1^KY16g5N1{dYd`3LAuvqi=EEhp+}Czd@bupiJbiO&o@y7gxuR+7oOw zL12I_&RZv(jwTH%TKH%!ga3fp;vq?C6~u)f#|#6nWq8!A!JEFdvdMV4DE62q9X)O2 zu}0=2YK&+<^lZ%dPJ$NdL9RMH8YeQS>eI4E1=v$R#ASqrSY{2gfTshCua!`&c6fj* z>m{l7uFo1CI5`(NZCvvyztK(m!$UedV~4TjGyB+!;*dh`_FRR0X_yK z$rB_=_5X`x*P;y`Ryby_Sy)DB>5op_76=Y~o8AHKAgxwqiX^)C0~Bm+-#mM|_5t>7 z6r30#^nq`vge(d+o;bw)r)p0I>$90KI6KX^eh%JhJ#AP`R5mln zA7E|A8x@>3Oo-E$HAxzV$Z#$=*NMmZI9c$%m>L)nX*#7+eejxx!9OkyU>U`{DN#>G znNRmKg8J7xVh3UD&$fm4`V{UjjteMJB!4_^^oFs2M0qkq@{#F4o}dClklEi=tZk^5 zm{@wt=8eWv7o43FGLI9;@>h3&(-Ns89b|JdmF@<|KcnOSV{p6^eh9?9he%eI5cOG( z^z~&bYLD(js{(Vld(C6mQi2{;&5sMja)-!^I5Y{hJ%-S3S{GdJAzikJ2JyL(iFOqd z^?U9tOOmfiKhQW)GJ)V8S+bv$A8yH}GrFbLwaHw0i=ceFc$Z?Lej$gmKEXe?N(NK@ zfU#H5e&qxOro;nX6yyEmpIk(piM`}ysKf4f&Q?Y6t*29?@6q>*97q<-I!`Z{W5zmF zFI7PzsH!qjGw+tLVwG2zpS<$pcU=#<7s1=ye(2&38=NhNA1M~s(m#x$)BVyu zq+h}Q`m0!qk!@8=vzam>kJfA>W|#JUWnp;e8;&)W&Rnc0KPEq#m{bovJ-;R1=dqhn#AQfCr!^zau@(^ubLT!Q-%R=SE@d=HJx9`>y+8duwDV6EWCF$nCiyxs(#|F4< z_#vX_w)3$copQrjW7O|yWgR*_Q7FqyTUu+o=`7!qEmC0I;*gMyR~+d$)0Arua`6$F zh(qa-OF3PjNx@l>l)gy5BBNSx^@g5p%FL}T-H()`rDn_#y$9j>@rH2J!W8!1d1+)N z7HxE#^xZClih|^hL(P$0%w~ioyql5RWzQ~ByoCG%`D^7Najai@F~i$VTyKi-t)VSm zVM6toSx){gy49lj&>KM~Se^#11emr}hV6OH2UtdZFwKq;_Uljkk{y;QXn=X!Ngd}LYevP10i`SCZParxi!Nd6mEGxVz)wv z7F#uI+QYqmd3Slay6e|DvlwKOwW;WH{OqR5XNPFiIP3MTH1 zlg!_LTPJrfRW4x%zsp_R-1mrPG?|cqnMQe{W%@b7wa&m|ev>jt?4$5d+1W|Xbj+pf z0a>v$+YeB0c6=3NS6%UIGgq9W1FZ)3D+9MWlu5U>aLoQ^ELkjMX?x3S_xJC!rdUvz zmN&lh{VuHOPR_3L^~scar2=xSqCa?GHBUxNMK&+7yH8UXr4maRVHQ%`A@Df$mG$*) zpW#%F=TH&~clw$CyNY6w4<1obw6Bx+uys7&oBjqZ69==rMWHX>h+eR$!Vp+zc^%fp z;S*H*DELFlwP+O0J1~9;gSYosa20T4v8iUW)9wuewKH<|lVfMedAU&t#(hyW{ghs0 zf9;G*GOvj(m_mL%tDiD~2zqI69{7wLf5R_*vHt__(lGp$SJqA1b$f=jkEssXZqA+#O;tUAx+hdW+)6Hm8iQJ?GBn_g|UqL+=R z#W3-C{vY1{Ix5a(*#m}W7~I|6U4y$5B)CIx4-kS&aCZp=cXxLuxVr==xLY9TJIT4{ z?7h#u-}leE);nt!^Q@+&>epS})m7E~F!0IAgNTVQMZjyr0Wh;L@~!WJy1oj_3&lA&}s=)hGerj^k(~;Thcf0sv!T zzbMZH5Y(ICQx+t$9x&Mx4^qIc)=eH?>_F^E&6kgoZF;^rAQS8PZ;onq!^2kq{PRo@ z^gJ3Y50X7xu+Y6%KnjbWkpvuXqw!{8@K28RQy29SQApF!a7<%EN5f$W>?xU}g) zMv$Nq$0Ws|15|c9j`B;8IEL2{QG`Vp>{4*d_CTWlK{!bo*_UouZxoToWO0Gla}daDyM1NIuIY=W3eTw(5Ajm%?(*#qwIQ!of8|4{~h_jlzo zc;nk714WVSFVK!+LQncXLJSp%-4NsM8Mu^ZZuvV2g&jM$jzHVA_{%hx+f+ElO17_{ z$*wxuua&;Ogde)^*Y!=ej8&H8B#Y)X@FS0{kUQXDAOsLIir~`3Q2huc%>3{s{LnZ5 zxRc?t+2tF!*Q%L!1$v+zx&i9P z`>Mx4vlsI zq9FkOfajS4GdFCD1INn`m5cl}86YYGz~4Pmts?D?>r6MHL040Rj*m?Bcz|;%nGl9t+^IqbqLy!5JI)s5hsH&Deot2KD(K&g6E?z&ZZ>Yg0@pto4d-KXO19PbeiY z-B2}wwqfbUt=;TRi&??K(3J;&(s2$-%@1$aRwh*yBmXY0Co!>U0 zIM-5G8{>5zey3$ND@|}!iH7b&BTRk`FQhS|c|w7pqOYQJK*?Al_+kycP?La_(=!n6 zF+tA7N(vLj_}uiVl>pr-88QKaLMESeE{Hcpgf4ULPVCuX&{FimI4PqZCIZf4G?}oK z?nDnh{do^{sPBc$*ah%2&ioA$I-ux#GfHE6wakMO%5B}dZeN*hnC_Fa4{G;faA=KV+586C2QEhUg(BL?B9H(bC0_9T{U}YZ`lZmg<1Gi28*GU;hGrYCcARtCItdT=fxT%8zl~VD$Lj@XrkV` zPz>@D()oeo;M69ypLDBV7o1{wzJ-cX9SzZj8Ic{JVToV`>z7ZSA>_TH)eXc+d!=<( z!=VFGxVfV}_bpe4RI94DA%e$R0{3_X0OSgwh?p&v`#c%Er9?rD?wt@j_ftSGO&hc8 zjWW)$!u37B6Sc{?l>iV}p7D%4PNT6Zsnw>B=S`|k8Uu2M+m z-uNq{Ww~I+0NMF1Qa{Qd_wt?r%_#MmzkL4iSd7Be+grQ2T0rZkgR6&uABpbCOIes& z2|jQ#yCArfi*&W;I~^6T0j-j9to^D0-Oie$x(Z15k*I!*H*nYVW{SUZ&3fKB0078f zEd#Iu1W!1Bt?gj14*(KVxgMx20(J9n@CMRIp@im7-|GQph5&#H$`4Y!ML;K;S(t!+ke~i`<2ooON{p0#_&jFg)A?Z zQ&Ss;MW;Anp&^K#7UOnKB%$}HsKc!KVkX)|;QB$}Xlq_0Va{)?7H=iL2dgis?WPsd zs^-`+T59zruNs-L2DSiswb$CddQ?5(8J_i1>wfWH?(r31z2$X^HDj0Ytsl#i@)+PB z1ge6$+XQp>H!bZCcT$w|_7|A$Q8g^ZbMsJs2yT^BjNpbLQ~-3F0IKW-{qw_XZ1|Rv zCOl_f2nevLBSWzD4Y_dv$cv_kGFBQv#T1Z$kIA{7JZ@?pn;0KvM*wH>*)v#7soY63 z_>fb!GRUn-5Uq1VS>x>}3in{-HMB|$JmCa(1ebY@fa5KNwQ?x zFKHN3H~d{3w2o^wH?6JZc?d%kr02NpqoCOhZ;Ag1W@6 z5#1oz@ZQwLM+udGl2nynjHE+y_mH#>55eHvL0S4eRb{*o@lpr zPoh~cB))$tXsZ#FpWOj5&iPsK#%}Y)7S(5i58;qN;KN*@8@n`#?f`H{4qpdt5UjD; z0o~5fj=cD|q?9?@l<|#U^|Rul${9apMq>A+>i0E6vn|Wppg@yKraj6;X`OghEjXCx zzoC2qHBXWDQ*AfsZ9XLx4;-cfid`}x>c^&##bT&#Ac5Y^P$D6hcU&@ z^xgf}E{5m=CYYD6QvPLNEeCeF4nkrF|EYKj(fKp@p~PzXta31aQPWJlNz{~Rt_g;9G(T7kUa&+Ng@Myr>aAE( zsVm0ogBiAc*W~XCBk~(v0AqL3%;3#bZ9~tawfZL(EK1g9Ud_sB?>@i>jo{jdr3`g; z77%B0_p9;}I>S>pmpDZ4vf~`??)yw8?QFgs!QJJ6xO1xn0j5_Gfwb-^{hN#fGzcz# z9lm^@C&`m4h4;Q7@Z17e1Op-e4<$QC3l-Z0prDtGRLo|i+z%vr0w7$85FCP|-?!!A z^z*Uqhq&Ix0s!Bj0mw2MrpsjIa%23AkOSK<*BI@747|V8O{GU*FZ0*3xX{485h!r zJhgg=cTmz)YyFAPXVx031j>F6ysgP4PNErlc9aSHNcWcS+cJvkkl}!YzkC&fKcSU= zNnk=no-C1{AlG(`@WeNd=~Egt1>i_~bXP3E*_dPudElzhi884bO$gud zdn1zHUjrKsQ>dS)n1h2KC)gHRo~{2d7OnIQi!dy1dr!!=ucinaz>E zjYEI84OPG;WO0RegG0JEL-Rc41uIEDJwwo~1fT)!+MV^VdAcFe?~yG;AU*F!IMTKn z-*!UmEqJ}H{``#8m+t!qJymR?*4p!0OI!)+%viRBW}=p}%6nw{W{_e48p{r2rK(S% z93dWOifDMWFAI#iWU8RnYs|?3Hrp@S{tgu@$OV)^%oB$~v1?^l!ngHW=;3w>3|MVoXhkDKs3kbSMQR9w>xo&&Qg&sWW+ch zLU?nj#xo1k^!&ZAa$K%zJilGi0@A?D0V;u+-R1v~rE;aRQx5>tZigKQkXsE3j&But z@pq^K87X+R2f#$VgV9w?=$VV(V`lzMI&^cWg-H#n9S7Ez4buTjKv9kprGvnzgbkl~ zsT=3l##^exYX-yEP`Xhhy&E(xrLsr0Uet;VNNxy<9IXQY)~$Rq8dd2oOabYFb`lE z!zdF0ovlNVWd3QnvXFK)!zZPNK<1IreM-eRw{x<-P_1upkKs9weq*f^)ObsvNRenf z-=HkoF#%{<5&``D>CH|KbaTa3GrQM6nR(TIw|tCql{|jUe}LFlj?6;|)6!5$ZKAb$ z-u~STd3;5(CyWhp^+vZuB$r3tbt*_HUKP#=Q(SZp@(T>J*c{Xg?#48*uy@tspu?p1PR(gd!4F2W^~$eSf%U1*Dc|jsxP(+o&+`I*eMNqH`Bv> z1hrXL=8^e5muF*t;jN-bF*o3v2}mSTZrZ{>4q-WfUmnbvz{X(lD{=c!x|fhyIq$?@ zcPpYZ!~?X}nR%=4B!$vrCFriB`!8u8X7tMTC;DUR{hu48{y+^z`$wRITs6QZ4WNJl z>J>;JQKw(5e&TlV635wMH z>MSG$3xOWi%4R3CqcW5w+dg7N@6tcGaScp42g@5yH`AQ!)Kx> z93#;CZOfWJ?&<=mnZJH(y@v4{^jPFB)uc2NXq#rKPT$0Xi?}%kc9mF+)&$hm#L=)< zJK6|MOwSP5>tLPHrr(+Br&}%tK+9%2a8LopN8czieC$9>-0w~2z*-ZUKE(G-29)^$ z{+twHyjb}1keWD<;G zbzJdnV|0wle{DFeG>FrI=(g?qxT*IMG@?Wb5bpt#7!AyvM*P1?{6`yqZ}0arS@!RL zLx@4}^r-^@kZ-ui|CxOQ0DG2gI3(j$S(Cb1c|4MB*~w$JRiK@lq~Q@8A)dW%OAh)< zbzzZqyM0ifhN@uH*3Iclxe2BSd zrB&XMsdzW76P+X9*8}wajL=Y|$e~_pGyC^lzJNS1eINcYMgN_G|3CDx)Osrc8s$U) zdGP@$vi+1ul!)WQDW?$WHDlP$;5#-q3BYEjXe|Id_eotnog_ahIPBO6Ik4Ln2zL$@ z$4+R8YzJ*2QLdit#FnukCaZ?Vm9MzwvXu**@h7}#TbnYb(nH-0Llyyq{2qJ7U@{~B zZ!-S`GeMw3qynwcY9#)G5}64qXA=OOqVErbKnwx6dlRq%$h3yPN;t4!Bn~~K47Qei zEVTEpb_3A%0sUbluKyIZ6sW!r(8DAJUKvjVJpnYI=0s^?2Qr+syD?Cn$4*_c^zjBb z2`_?@sia8j%O>j0VS_0(gOtk6J`a6%A%(>S4{|fn)S3S==YgHJ|Hm5QavLB(3KsOm z;ay z^ssn6Eh0jgUndKTN)Q4+o^-3RiRX?sN4$KrcU|)66WjRq+}UNnOn{;IeBAcH7jF3k z6+R#9Q$!x_rm@ryQ4s?atD?{@pr&dN3U5>J+(&9I?mY6=@!5k3i<8g!utuKj(z_pq z9tMw82q#GrO6i1Nv zd6RX1qP(@&N8^R|x@;*=TXayN*pynrLZU}?Xy`9#?cTxeAfX8~!z8n*z76SzGR1cO zReSPCZ(JmM#Uh{iUEuTs0^)%=8X9d{>4mRAmk+BNt6=-YJv}IOVBm9IG>~M6I0NQM z>)Wm?C$i)OU{+JEt?i5cRH=o`gj%U(4P{B_@G7o|ZdEmBTl?LNuh&poOrt^Rf@0uc zug|_Y&VBt3*C$L17iqZ;C1bnh8!J+0n$f6R9T78Bb_F@~N{Vp1x>bi-(^@7Y=K#M{ zQciRu%$2%{&p3ijn^dCw+wCd20}fwZcPr0`J}=gyAFYx-LF{wIcG6J~wx}mY7jF?# zd>t}p-NQqC)oOZ5=2kj*c>!_tt#zjeJdVjue>1|>ODud%gxRfiwObR?UPyezAlVo! z$V2_4<*<_;w!S<_8zUALK0pPk1KgtBcS(|byTIBuIOr0kwgw-8Zx?&)VZl;>&Dr!Og)OBKfYMBQmo#)ywJuxX24DVs)lWD@o10hF^W07n*T<43hiy)Y(iaj zeUWHlA3*AQmHzQ`&H4_*{)OPu0Z8vc~`l}H#-QKwlEGCo;BI^ z-LSWv*7TnC*L(z1$sPyxEb$Y5c_Fuh4mI|reUbVX4P0~9DAEl46kYlo5f~U=H=u(N z%T`{!Cb=jiI9>e~zuu0YKeA zlGtJI=x2mVkS5Z-5!SxH$whp7LYi|NR=>6_g?~2hzcfu_$0vmxS+{rz*HR+P_(o`I|plxFMPdnNQ~=^91*M=X*2T-MB#R&nETLnnMpUTO{pzm z!IEK734`<-DrP%96yeic>exEJEFK|72cB&wzXW)~O3U$fzf`8+r$AKT<_b5aZ6jdj zo5L+E*=-h&85EMHay_b&0k-*YMXT`D%=h8V^D3I}isG-4=v{g5-a0{Z#n~6q(YW_t zO;!hED8wAYMd4wNGs>OX?%#PMVxR!ki%77{gH$;Z7pI}sU(n%_GMkI6L=fkO*%?4$ zZ=e{4rb(eQ+?;{m_4BT@Z-*H_Wq}X*ik!O}4#{B)M)Cvoy^=Yk_C~yUXD0_` z>fg_>19VqX@Tx#P|3#HT+i!rA=>!s5dr$#F1;s)X@c6(_uxvD=my;n-d+v2Dd|6>fPA-r^;Vk?S_?{$=X6 zj}zLPclMZ6-`_!rTv^^)oPaIxYxHpyJrG|_BPaW12;5VgPT=;JKI%IpW>LAgoM?YW z|9Uhp>ct6i+xx+5TdCgd@YY@a6V&ZZdTY!o-Bpo{OK0>B;isR=B&r&n*c|tS*&ZRG zoqQ~n``J|I)pHLaN8S+px_w2iOX#AKPrL8s=$lRU3l5vj&J76}>%$2+o}deZQeo!w ziQBU~%ro=PrbhIzPy{=L1Nva`uhL}##qdll7sDV$(4%?CaX54w%s9F#=Gu50`Kyi9 z6g?)Z2-~svagd_n-s3$M7t_ssHxuCyAepXK6_54MEQxUph^^^UGIYU^pXA#cq|7=D zw-2!!UPKP1b3bC>xv9?R^p@)>)8*@6ktxC?t=S~`l#1B)s-zfbJmk_RJaduCJ~%z= zgONR+w*7c$xh`Knh!S)2>_gGHu&AyfC?}Wz0tr*Ddq*G{hhE|_zI^dY@#c9?b@3v( zI4Q+{07)s2-V_Gk^88aGyELD3<--j`6K;GQbo~^<@vmAkvVn3HpVTXwSG-cJXA>qE zQvh?OFWEtwUs{|bIxpiKOKp@$v%%+0hnu*=rXodR`Ip1*#2Wj1!k@lRnWNP&=D*h^ zJys)46;stsgHx9%(+*1ufD%aEyv)9WAFt7+mOcGSZ21_(c%CyXPa{h`NZUBoDV4I7 zYX74(#(6)~2C-w?asI zkfapJ~OOFU0#b24fXPXriCbaA|Y zj5DNLFn%I(ZN1*72EAqqkV}1C9Do&e>Oa*|GRZ->ese4yyKx_MZ9pdH|Ju(Tw)Ha9 ziAP{_BTF~Tub}xJ?Onrz3)SPwSuhsk+OD0i59;h3=GSI2hYv7!w~RtFk`7X;xAPH6 z?G=Hjh{L)Dcr%L=#p$y!j^AWU7T-OCLYl>XI81P^++kEI?6i>GtDq`aNT@61e}yn& zN+A=UVE)c7L3;hW?M}-N<6Hpeu!wyI5qlE}AP3%%J$R`i24-%J z{k1V`2e?z9@)4+FW7i1cbzjpzI4T~vqOvps+>Lp0`{`-XF+A6W4`QmQJl>CetK)p3 zRern_OhpZ}S*wKv2lDB3wHg)P7(&4=}xcK*&gz_ZAX2JyJ>4G1+Q<-=;I@Z7=uojo9kCzABnc{dtjAdFaJ zLzNdeD_f*}GgVL^iQqj1S*-7Y#zMpS?;6;mHg-v=K3{hMB-l}j;8zwpF8?Gq|0p7@ z`d{ra@$enJ!`|S(fD|VKPE}OcZ2W1DxP9jQVv)3qv4JD$Z`Am}mMBj7=+8@Abh=+e z8s6(H{o!Th>4Vn!|EiixHLX5-!URzDZjRU2L7Cz3*~-h zAo)Tt>v+Qaepi}+Wtn4#bdod8eUm!;0^?Q`l9Eqv7LIbpM>=hj(gNva5IL)}>$5lF z%n^@oRw*nQ+05?XdDVu2WZAs>Ce4vQtc+8O!{hPY;wm&)%v!3_E^X-jJ zpZa?U?_$!x5V@};;7UGYH_mJRy^{C0u@QHO$6VLl3RwTHs}NnTKQo5ATV{gbIhsiL zv-iU<(=Xz=^%@`Ha@!%Fl|ZhVB{hNQ3BEK8? zU!~gqS;~7o<*Vf1x%erR98s|QVDB53&izQp_nWVKj_?0fC}V6UGoeS@>zl90w+BUn z4Jv|32u_PIisUYCbiwUEBN!NdUtzce;WiV zt4rkl4XcI0zV#b7uV{c8?ugpb8TOBgVI7bAy!7mzQbaTQ53UHGG=5YFdTCE68O}qq zCvx!zwJ?0r$n0d@r)9Mcz>`fQ>RnB2VNf){ar}bIDH>Uz5WQt5yP8;3711(+h@U;6 zQaJdriONoPc5y&&7aB>)gih6@SvS6k%IbKB`BMONG254tnpLJ@-T3<3%clP(k4+iORQ3)W$Ywkqy8nLz&=5MgD4+8@Mq2QcA(52{qaOYj5< z=g}>@;`jwxo`CEo&zF{twY9a?a$cFHU-!Pf=t+YHHBff4-_L5G{)^Re(*I&r1O2~P zEraL%C#&;8g#TpqsCVKYtTq=A6|~POSO8KPx)tXkQDYAsMKJ5|7Hs!@|CWLUO8M^; z$p4k+zf4cKCIJ#oC7~ zJJtgA^Qr{U-IM3;iid#1XQ{jgEkd0FFG0PLq2g`sjD8#33_y72jvK>Tk+^Vm@Qv~M zL5DHBBHAzqFg-5cehtBU*y%aFX^B$mx3Tn4LPiu-)n?7- zA89g$BR2Xv9=SmIjU0hgi-|E?vJa45mnU-kCGR=c;}c2bHT1ohC`SbM^bvy3k`T;g*#S8j87A@5YD6Ert)8ax zb;cD5guBZc`>8`Jv(EJ8w`*K|?Xdj*x&TTpA^k$Tf#{z;+h}rY05hBUE_Y*!-pT z75x=?WgK8dDbYd=*2W0$DgwUW#}D$dcpvt2d0>-yWHrlDij3?~Nm-;GEquFJb7XMU zlrqF5d*fx%UtgBBWYdD*YrUf*Q~q?838($-F>5_!5IIytws5+c-H%kPWysCW;FDL) zcCm(fBI|`jB=pcG3ADg|oZv`~v@amcA_Ri_s5M0@E7ZXjC1s7J$!2&!sGjJ&27AGv zcesbI_8yox@FTV!zxonkzr!pwyRssM+y2t9arXSADD@z*_B{wo%i3ExQK=eXKBQ!j4JgZCzz$9GUvImmI* z)ScjeyUYG<>hyus&AuwoM8dQk{0fm=`rE8Z%@2Qf5Pef%F^55V0kH^*vzkYK;GtnL_asx>}hqSTf>lPnYdym)m`)vq6fjB*o!_DVP8JB z7^<8NQeEy-bADIN4mV%CaeRvmZFbMw6%X0pr`LteoK_d4|AXe>EqPx6+UBVUCYJvJi)lsol9+Y*POL{an%K~qr4yl8>2j-x-Bh` z)ob=U@s@E&^L)=h$XwVnH$KMr_c&5Vp1!p=5@&0q=WC-Hlx?j6moDFhy-s$W%$8Y{ zoE#+6AvE95xx=@@B9UdueRIGzFJ56P7TQ8X>};C8>!;9r{~-4zGDvfA2MY=lF1%LM z_(yUk1GEBV^j5i?-J(unu-6RvR=*|Ddo#kLBA%aj4`m}RN)f7ztGVB0S|c`4J#*WN z($+q_ouH#5?46{sN_J%~;|MLm^fiH~>)s$CS=aM{e`k9j^sWC|CT4zi9S;e5u!2uV z4||Cq-G)hYxQ)(spL zgsRg!*pE@U&dQ2RvCeG9&ZZrJ)Ia10nm!>+F3}WtF=g$ zVhAj2lc>N@Hi^;Ct+URt$qKjj6Wf>xBOSt)PkAMf@6w=I?d~+sGECAfkG4nY8_s8(v-YV^;N|X4 zn}=*MzV9nlUtlyWbFwv?4{+Xt4!g3_3Mold;jt>yY*$DEm_5p^!biU# z?ewT`^;-QT|c5<(?L&3 zu1iXIvwV2_`SUnc*os8TZk0ElR13j`{y}ZvRf<8LEkSPXG(ch@;zPQ-M~_>v>B~#+ z7~#(!%tCK&Lk_wi3@q^dkXV}!(ydkUGp!L?h6BeR;Q90d?k{QL0wpe z^8=jw_=Q4yUDxbU?bm%)NroIT|AYos<@jK55f@8+w5?|zSg`wxJaU_6}>rhfv zXz?ZxlFBicwYPM87+PeDTKW?*n}XFA001#8nt62c+oby2EBxoMS}2H zy+&-I0r~2(y2CZ*rP;`0x3v^I4moi$gF1Ku$E@gP^8}HZgXxJ!BdrOge%|~_qfm5G zX>kX2R3ul5vF8fmyD7h7-w`A$UrkwjY@t?^-Mk{QLH!WpE4%?02jJfq3OX2T#li1d zIH|@N$o$exh;t-zdX+Q<9H5e!FazegKcbXQ9}v(i`xc``uS+1NJ9lTOaL(R*$`9lR z^}_IwIAxsBR~8!|iU@Ru_ia@t3aWQH}l4?jZaA^U_WTZXmd~6;O z=3DSTJ3D;Nj_rq3MOV|SYcGn<2ET-Ra-@^RP@cK(!CQcWE(P;pHY$oN}rE*GCnB6`vw>1K>*%yAja0j{R zp2_`ew`^7Y==BveDCRtKGQjo;%N!(Up)cANe#He!pt|R(5pVd z;+*ZNsI3Rf?o|D_Bb;w(R?e>fB~r#H0GyiMnO?akE6o_B^C)BIdUx2y;ZMX)9)V-W z?eRpo25rK1PFzJINi{E3hY64IlTPwIy?^u!Q`Lv<1xMOukTN#QTOEYEStK|cwaLtI z3tV$Ue-842>8;PSITwPuVKx!HDs~2?KTsL_-vvXTs9`>p4e+C#ISmxnA-9=E`f->^ z-ksu4OiRfK!(c(V5ht=}8DTP10m)lI8I#;{DJBWlBn$azba-k#+`8G5%y$*gH)6iD zz{jWb4|lVSU@eCgn0XcXm(k_7lezL+({nXI2{SY)q?~ZzCo#5ci}&3=nzS+*_@>(I z@RAW2O0P*p6UHS^>@124v^hkH%Qzp@0oOZH%F9R^`tCa0JZMsecuq2Cnelq))l>^g zWjDp64rFH(%M&t&_Y(UcNfA9uI1+A5#ba;5bySVBZ*7U8q$LZ5*YB(h39~Xj z$XofLoST|p-33a%{!X@F3Q>}V@H7E$9eUT9PbV>Vm~hj-DfqnQ2ztlG$D zY+63ynBJ=Q@Mzt|ez?@n*}E%9D0;C!`LbdeM=!4f_EE?WdFpv&^k$t1z5<|x_`#U5 zfiWxp|A|?iI>c5_1wu8>SnD*e!i(i^-A1F-ikvTCgiF=8`S#{Gp{;+U(<%LtX$$^` zMOzWsNKes_7Xa3R6wpzdCh`1IYZxa?BWwobKUje}mPc}CWx!NyIZ2fV)A{pRP zz-p#Tfln;D$Mby^NGSp@X1KptY!eXg&hH~23|HVsuylYli<|~)>n1_ykeR2`Z}8Db z0ktC@Ry19Wn&*HYhNC@piqTv!&geeOLEAy5*Ir~xS?}AIRcso|qBRRY?vw;MWdpQV z1q;lHq|e-TO7~8U2Po}+j>e0W^A0qn>e#85;{l!^9o}z>iZ*wnoS_~KC;?>az{OPf z4d=Sy)Rvv9JzNY+Bj`2r^f~}QR}>5y5g4?;S@-^Hp#2YMW#fe+VGOY$#=k)$)rg#g zz#D%Aj0Lz2+I?7oD(`9{f!tYNl#3*1+_io4N%J0n`@vx?y^qWpmQ#}K6VWG**$xOK zYmOf|)_aQFcooS5qfAiWWa(R9?s>xOYtgOJPcD*4yfVgI%xQ`VX*kiU-+?-?t;^dy zS(CDtH=j@n^DUgA1u`>l?3I|1r339iALR-1aI8L8Xy@90QJtz>cu~p0cDej~Y}(U_ z zNOf9Pc(hA|OcHG3wU&6N9y~fiY6$QU0Rton%)CbY&!%lE@r*`g_A8*y_Psg7M{nco zE7gmh;#`t#;tHtBxI?bIOsGk=sVy}Zl}KwQ>2dFOX4_9POGC*VToopy=}%|I^@aVZ zurrhpUYRlLpt!nT>$ac!x7yE_(f(AotB>(x-c(|BDc1r6!yjYPx2p?jdA7a{|GL>i zz>zE_323Xk55O+k4Z2?gb&@8$4r15WX^9<4NZA>PAXTqQ$&HzPV_)TZo87~fmPpBC zcE+-Qc{ZcOA|0S2o59=voozQPkSIqK(sI)hhN>7=$<;d;vYiuO)XTCc74R!LD?cf$ zOw$1fkLMZBhyFffK%Ad)2(eqIcDcoLyclDNLndf8<3_deog%)VuyZpbWqB71!Z~BO zIBwMjyVTrPxX9$aM*?JSjkC|zlL^6v{sUCQaO5w|R9{SR1PM?P4CG(C-~Sgt%JvR_ zwHcX7BeyIhNaWdb5^z>{$d+1ma72Ye#BSXh8!piSz75Xq*Z4#SzxvK143e~$XM^9P z`U*nbS=DE-;F1x7xABVAxV3>^v(+^BjMEFxGPyDyB&Z@^M@icMC5MkJ_@}QW9F6P1 zlHY+ZDHh>2<8bl0MItUwv`7N|LI;tbc>bbK=_peR_pK0?X&JzGwWm0Q1%ufe_0==$ z{3oGOjO|YVLsoFxAKKP_6a?;9tZUGr_Q$koLtamIc??S8G)2* ztBmV{*r-sEqseyYlq)wsKYb(Xl|z7rUcO*Vq$M^ktLWM@Zo7z^7ccn=8?68Ik3@Z)?h0Us!Q`5v;R{u-1m}LdaXPO&YKkSFLKk+7JY+eRLF(i$F zkpDqBi)MbgOIMBaC?-_`V@INgSo}{wUy_q6!z6hVSvu%dz=QeWdk+r3>7Gap@(0Dn z7w&tg>!h?WQ|we2E8mh)uP8eY022LP0$a>HXT%z0fhPY;KztuA?~(ci<}}Lw-DQyb ztZ-m-^1|{#86tZS#GDK^>e5BTJ6apfR_x#cQ#1X_lco}#GHq$g zVM%EsgBg75%FpuSde2f!V=NpZ1nGHP}Prt$i!$y`L zeenmymqoaYEeBTl{WR-vN?70n`b&Y2Pr-_bre6Oig7@Dh3GiV`nt#0rU0gQxUOmZJ z{Ock$CIDgyodiYB%I5+of{;QU%%4zo+)Y=8>?R#K{xXJ}VL;J=Yz{A86^sJMNHMZG z;0V=`UfN){di^;6!;Zu9@dx+s*99KaevTFTgr^P(EhaII6_Z;mz zPGs}it?7n`N(C~dR)@Ljr1SGFs1mn5VJ`BD!xj@&CkMlUI(ik%sw;ldw(<;GI2QDT zr3<)DLFjA5d)(xR)wXldEwD^uNV!XVJIYyQv?Us(tVC=a8h`w1cBku8 zM%Q#VBzRq^`pSZbB1LvN1t}%4G9D?yG#Kxqyb@b5!~Fqz{!8#im2Nfsc&7|vgRQ^^ z7ZY`(Z)hw+8xV>h1<6!6M*BhzNTG_PQ|vI8x}g~*d&wf8IJVqPMClPVoQY?C2z#tX z1g~QkLa_S41-&7J#j3ZGq>XF7%n>9P@|e>3rEZqBSpuJEwcOc#!Tfw$Fop(fQIO%P zU79-4_*1`o^Emx-k%P{T{QH0P;f!9pI;u&i--0=aLcib$ zjBH-f2`oQg7!91Y5B}OyY?bU+NA><*VJljHm|gxto~A+)6e=)oM8ewu=}3I&ujXFl z9InsGko;p<(LV_i(BzOQ)tHHcbvTJdXgD-MAY3pOtA=+??Tn{xzo68A?9?PKfEhyi)^=HoN_&y?r0owEULzy^QJV?6gt=QRdj zqsO+-JgoNzN{}ytu)0xn1Y9zSt!deP3hRXvam$b6H77HqTR&XNDrqR98h&QSnyzSg zTn09j7ABPRc*<5~V;?Z?#!DcsWW+p?ZkdzYV}(mPu(`m=e(^9l#pP!WDDwq$lx_ME zePoh+(4|6t<_p&Kx9<{NA-D~spPTYmuh%RLo89yC99Y>$60PO_R^hSnY2OsvgX)N9 zh;`i}`P|kELJ!Th>4(Ma7<#MI%GGH6a~(UjT%!TUjar)EVrrDl)?ml8F&5+^ykg+U z<-3<2Q zb&4rn3i-%+z|-S-Dli#=_6W@CkS+=ye}ZgpHOG$cbz{h4dO3;n_ic<>!tLGO$E!vC z*uF(C_ofoT7Mo{HD{T|HVR<-{kqv+RB4GbtY`_c)9dC8tq%O;^E7x4Yf;{q-ZE z+RqF6j(gSQZx+#)u13?nWsm`zH50|xtm&K4JfM9V~)*RMJTUTF%L$@ zpoEGC=F12y;=BB#)B!W58pT+BO4y$sNOYwS>$)xcBtNYdvo_RE@%nJ=n}GuYfi$SDk^OEq{C|sXo=4#d( zUCf!bU#)UEXM9^xdFMpUdf(YbL!EAjb}c$&N*A9KG?F7F*&2{3`c+J~7yTAS0p@k* z^G0gm<}{+^6P)TyQ{m}%NNz5jC<$(_i6#E%Q!5BEYAutuqdxXozY0ZZUbXErlSy9* z9sITd*Zsvioa&dKIfpKT#M?W&baa68_=pC>uCRRRL_NxeresFa!>RTTOgGzsa9q>$c*J$oc^gIa_RR&P;8`2-T73feewl~_&& zi>gW-!BoMo9S;|AJa?g^nvnbK*O$#1o^?sf>!;S!mtqETmfBtJLViBQg#lO@7opb3eCG>k3sMS~bn3wX0x=P9?+*+pi}bQv4s#>|FvA2FF_0J&T!ic2 zqj1jYK(VOGFRAR8OeoU+_qk|2;Rn*m3 zXK0w{#Ei9%{`eR06c-VTCteKUw;Q0So@BHmBqxd;dMai{OYEN`&t6LH!yeuE=@}BV z9+zK6!5cQnHqq248b64nh2NjK6#3tKR@kin+-&`?w@#vEx9+@WtygLu5SS>c6&WB{ zIW8lGZS>Mac4}4Os)E%YdxIn2cQQ#kIEEhJ54g-x$KrPoV_^CqXMo0Q(btQ1pws6(JiH2>D^@`|_nc3aXb~jmq$^3_s`pzOlb3)SOZ5-O{+UOTefKzcseA zL!&9%z!3H+CocwmS5Lg?kHBWn0`e4_p)>vdXUyR7r~u4I2Q?JplNWop$6jqwb4PW2L%Kw?q2}Tl6PI{FdquAMz>; zs{4vt3Fj%2ym)^gnwen0Ws_ZO=9_^~W92 z2UxY=4qV@n)l--3+i!P-uFb_e$u|3fTJ&LVzAa^~sj)xH!DrC6#4TXTDWj6L&JJ;%?^a15)yU8mLf@nd#&j+BAhDqbu;rbR})Lb=&4ki&_PE-XyprDz`2%Zw*0|=gH!~zxi&xq%w}!zBmTlAyCurY!zkf0QDJ3` zrXQ_r2d(d$3H8g#>p0vJll9pd6^#p9LXajw+I~9}U{0kA?4?7LG~fc_>jx`BmAU8} zm+GEWORmYZ6P(Q&sd8}k5rszW23TJuI3RJRPUdn1V5j zWo%QNb$Gw_m-Gl%QTrn~RU<8|#9aG_a{@4grzJ{+;gI8bD)#KyIsW?iYS^1+Xys(K z%1T>b${$v;ryvB?FH%g+cPIQQ2MHF5$HgM~wO;qU)&ol7h+_GpS3Wh&LAEv8uwoyX zp}J_n9@&__GhfQY{qhiN7drcGMo|#t@lqi?a}*XM))F}drz_7{S%jM~*+{=0{f_!x+9$-3gX`Z8dR|2%#INy>y?8w3%`XWo@lVomq>|#amvcQ?L|7BvN}1!=}o zl7lFOsWS#0RW5W((aL0Il+boIm=V_ap&^M+Ht>*+32P;1X^$dPzaT?uoavwAR&sFh zUX5oUe0zrSQ)g{iq9~m+p2DY@4kK*!2WZONa4+EY0yd3@bwf}MUzUH_V`}GkP%z6i zVra7kT#|xK!WajF7Mv+qKH~odcsI>Ci$TbU2yQc5PRBp5w?UxXBlzs{h&(;teA;oV zu${ldd>ooHr*1!>yjWmulf)zkhK@aIEm?f)2v4xU(oGO>f+M?of%!I<)nN!NQPyY> za_X+{0{zE*rr%IIYk0>DN;cmoEYvAU>x;%uTaUpmuwXVEow9xbTmcNV$<=&P>wp=) z&){*cLjs)<&dNRqnAm?LQ=)p!a?v%4iWH^Jq*sHSzcK8=*)a;dj^{-ZXmmK%z2cNa zRkiwPE0dEzsE|6!4BpTxUGpuuc&P@`q8&vNlPw6gZRfbJJ5GwQ!pt^$$gLp1dw&$_ zgyRU=DCCF-QSrHo8BYbgwtXVDF!&~!ai5p*Vh8r%QyqHEH$x~XA-PCE2yea6k31nU zLH5<@&~qF9`B=R1mWq7OPGxM<%{fxf*bk_EGDsVvU#f}{S6(>OR(=u_@j!x>3|X$r z+H+3%T$F2#u;-_j&8rDE1lL9P{g(aPxB+Bsre~9uSD&@dpEldCwIT#N9Xszw-;GB$ zaf1y!NC#KEnPE*mw!#<^8meWl;61f14leZc-dMb9zuFmM9M2qH>WWmY_uQWx>kr8M zWx}UY2#N>+Q`7SE*R2r^Dk6>w45cqM>eJ-RI`pAM_pc@^`-Xw=$GlCKvrxT6FEm+b zuhoA{{3B)=d4&f5yvjvbY|rRw&%O7fV`=Saj>n@x5m_RV_XFNR$= zvFJyj9H_Lz(wm{Z9mV8Cgw}E8;}=#@wBnTw&7;aNGQX$(&2W%I(RSG={|j- z0s+r=pDi;nhazpPH6D@JkdsMkN%uF*)KxlZ+PspHbOF~M;_r$VX<7eEF6)`CZ2li> zVt&(P)=8;}eJx~0*2E);IvE`$SCZQ7ncEGAs@j+#1ysbB6Nj&~F$1NcIr?AL0xHwo zX=~O$R>@~Ib3HEu-5oASquRE=P+rEy{B46nmBV-;`<->xX%)S&i->86lrbM4Y1AsS z5ROJAet%aTEKS;v02NMIJ2rw>Suw&kpQ72LZJGzcNhu}5xh7vEXP|O)=FT-%sOVT> zHP(HtLQbz`VVT<9fKtJH^$9aNvWJ}h_rvRc^qJI@_;HX6u0|RGkqMe^k4DcTo}>Fn z2aPf<9=5jh^SVAHg8bV=*%7ZclSlS}jdKYq{f!b|jAFs<>H)Y1{q&|)#I=RwZrBfM zr4L6hf7)U4(Zsw`C_9r?o{nbA zgEV{V*aTY7-Xafz7~b`1NKRzzq2|kcl=UQp-flQolgtj-zF`EVxU02HWLNEHikJR~0D< z2{1Mt>~858bnr&3R*9TXYojnSn>c|{!nACDIV?)#U=GH)WcFoUXOf^9XU{vu$O^iY zorGfTH{6I3Tc0fhtkGilzI?uH>A*n=>LARZC}b*ZROeSbTZg>pgtBi`rc8uy2c~&v zRVzD<`^3#Ad-%3Okl|CjJtT6mVVqKFE(y&}8n8zrK?F3}Ml0oWlBzyuPZqmMGJ)(q zb@=67%z{WoMGY_pvm++BpB}2=*@EK*ak7TJ_Bl7XOE0 zMsBZL4$6w#&;C$S#!?_RZBCW|P#;e?;h~iCtc?IBims$%HTjt6}S%B(&8zWI} z@xR;Tq4(6N%Af8C3NOFc7EpTrHY+o%`Re&&_&CA2gnFx41I*0$!3I6Kk^->K^GPLp>Zn92wsN0pqU**jqLf?*fo zou}<;_d<%-7;sQawdVkYTI8zkfk%K%_)q9TSaIY>xC+V*mXK&NetjCo1hI4Ad=GLo zP?PAD3}b^%kv7DV#4t|O-Q$+if5LnXL(ufzEUVCqei5MnU;_PP6QkakT+FBQ^#v+( z0P+Y#u{PdKRseQf!s4qM2Hjm+JV-7I6I++%5}y*mT7dSq>*H+ged<*+m65xw-UhjP z@W&U}fL%b9=S#!a&v=;NEe;$3K?bLD?i1x3Aoad4mXG-_=$HS1ML=#r@hG=EEFS8T z47}Irx|;EqD4G$m6ytCK2{18IUwyvPQ zccqb`q8qoiFY6722^Ja`d@l4!L^@It?pP(sAEqA|A(6-XEkJT?(FBIC($Ct1DBY>t z#O0rbrta`{ncIR`O8|1@+OLBfT>I)cU5uwrXgAWoNZxU<2#pzAmAN>78)MOCa34PA zm(NY#8SV02MQ|d1FAQ5(!kGzs=T3F<2f`H0wSjPHP(IVb+gPE=LbDr5p(G;V+NUmv zaj24yc$mVC)(WM!!OMP&5I*>Mgyj`)EA0300{m_yjl$n&A3fHau_3&^K@s|%>+QJL zd_`w9I@$!7>k)myRW zIem#MU#G&eqCie*7@ZmZyabnZuF&c0;k9%8C$Ts_ZFES{hc?hQC{r1cc%0tkiJ@j(*eCTq;|I4R#dNY+2JH72W@9i??J+}$G& zIZmt}uZ#q%QJ8sF8z%)kOuJnjb_bf+^^;xjVR}-^u``h+w!|5kXO2y$qS#L&Z=b+S za89;e4lYllx=jY70*+gLM|;_-kbE|rC=t&Pe5q;aVE9dtw)EMWtn$;~{f`@+n08FN z`_96*oZzqiD;4&w#3IGz1%au}#yd=@n06W1@rkZ8`T-FRjBKljzrjwtvD=-6nckfG zRg*U%^aTkPc-D?r*I0Z=?a*B&-Nv6xD5V>qwuha58)f{wv9G`x7t+@`6n*{~p45KMP!wHb|wN?KC$pdv=G zD`=)d&N|@5djh8^{Jhv3q87as3LhqpiFLmU7N%&%R)R30%fP8u^-GhP1*}v8RzM?H z#^R{z=dM`3wvg4giUwk|eyw)#4ZjN4`=seAqn+W*S(e!kD&-&TwL^CfQ&TxOGJW;K z2TkS4hyegtK1e<&Ao@6z{yC26oN*{@+1yEZ9Zx&vWSg1vu!P{e`x^NN z|AgfgY*~!jC0xf2?y~Dq@k^+6Cv!5c0eeV`GoO90Q%YW)q;q}{RVF*2!gBkorvBQF ze*PwZP0A=T7S&TW4rc!}34t?BVVd94_VLiK$)I~VGT3%-u_=#QFl#`{=(MKkf+0EW z&{V{}>_AqMob{NwuE-(kN$+G4kVsdsrfi9j#Y2t`+EEFh(H z)eR1!0mqgbVYn&wY8f`|U5!@M%gY=zDROQpdNF1_32k_8AAL2x9oTrHQCcOM@WOj_ zs0v!Ml4dmN7p8te+d@$|HH^y&)x~%dvGp@jV}GIc)152A;G`ODnQO&I_ljRHP_!e( z+*u9FvpLn(X6o+%K2=zIjHQu7svmm(V+mea z)ebU#i_HR7aGZ0tyK9E-2Q9Q#gyHbCy0l&dosncgQS~`vtABYM>i@;b z;ctC%1r1f#4LHvbPO()%7Xa`wASs%Fq&WHiBE_&7Qob|Z+)RTwbrxe+LL_z3K8|Py zXDFxO#o8B|n!B>>%*jnWSwnB7AeK`cD*<~xeJydFAyD5&fbOio$t`pMgZ zCURx^sH_cDe4lL@osFNaU`mF9ROiYutd*QwJ2iK46@npb&RmZsS%?eXqa+3O-zajr z?Y6|b&j|3nNsQ#wgnO2=m(x*JhJ|kCl$GX4gne>?cWQ{{;UPMiRH{b-{D`e!#qQAJ zJO)F0ro=`ZekYFmu9g)+i(fQ!k;ehgU5gqky!2t_eD4~J2a%*t>@%ukoofSs?Bh|Y zPMv&p1zI6TA~^n*DmqDxKD!I=8(kp1TkTx-?puhZP}|-}uT`jxOIw3k!h> zxi|ZKKN#60`B`*|jG)T2om@|E9z5UaS%r^Xrwk5NB8wGB2f68BAOtzWv;Ti7|Kp}l zf-g+{6^3nwyFN%|)&6%Tt(Y}pr~QF4qi za;h?_js&5Kn<5Hbu;9c5v-lJzo#w=S7v}U(rAseBoa;sUNo*ANHEZxB6AfQBQdDDd zwZB=Pd!rLRD4qe*-~@qy%Lrv+dKKBXW8E{_Q`J`R$Zx|^{rRi5w+F8W# z>ziYbDsnqc&-U5nPEymYRYnvGjv!UMl0P%QHiOe0VpPJxnGFV(w~>Vs>C!A`4t%N@ zG8t&Y$fDk`U-jQ8IR9H3Qr^bi3jnhI zGL65R68l%faG5zc0o5yJe2aI3#TYBqz+k1D{bWfY8O|FwD+kI?eBC_uhb{kvnLx)h zLOH*H*tY`U?dM?mXXnjzK@2ESfJN4ftuW(d9zZ!?Sh3s!l*MuIuPy;-_Bp$K5YSQg zpJjAE0N82%G;MFEZ36FMURh2a4^zyp8=_qfE561X*vTC>P1|Ri~xNq#JQOOFq-aGk3j%xe$g-hjI@9e zfD2(U0$gXl0FdptmjM6aI{@yAqy-S&!T@0W;h>tfc9;MlHS;?wAT?1B3!v!01puXW zrrI2i-Sw3K5aSSSnqxTe}^V(5r~g-0_2U$eJn6RJ*?@LUYy?6f-* z1;7#xs9*QJ=iuE+ZM{1;EkFD|06K-8grqIU-00tO-jfeoG$JIP)0036r;3Nt_iZFBr07$WUpb4eYjsXo>`zjd~09IEM zKtln$YjF<%AazAR-9<(kd3sQTh?;hP0|0zqmD)G>HwVxVKKIZWo05HQTd+#% zDLNLHBcupJ-^{-ewXjW^YizXcPlCG?{pWcZbREYOxZ@=&=gB)r|2zmx@XA*d)XDvw zvb6r7L69nh0M5@pioKu%0GJDgmxJ~a5F{BuXkLn=ig@ji4v*@ku+cw0=|zrw1KuL2 zFMdA_Y62~mPbL3Pl)mSm_Ml^7-i+`R=OMfW)N#-WQQaMkB0E(^M7=+QhCW!8Fd06C zje_l|X$fI=6gbd));gRDcuEKX9cmapH>to?IO-n|Rx|h2UbFJ4VL2>4UoWdqb|!j< z|769M)^EeX`X8NR*gAvRgeSYxVUEvTr{xXv=cujdj8L%OziuCV+Q&Z0YWcjTipsaW z-b~8irRHFiKZaO0#WImu&u;m|Q6^{8<8$eg1HA_yNdxVk>s9_rf#ftMlwCkiWA5qB zlXDS_7_j$j8w*>cXU(DU7t?IWlOw^%BPRp}W6_?UQE|M>NMY**Dd0w)!nF*Y7D_Fb@Z}%v3v0BNbMKOU!cL$d^ID)zZz}AXlJVnN$&Sq`=^$+k9yiJrj%@FPYFYM*8!`p;sv_);1a(IV%>h z$v?ME;ie<56m|f+k>%2_{xbfCOi3oEv=r;3fU8F4b&NyQLssAzB(H2|i)0h&=&Z#j zS)AY>2!aBgMao@l;Qa#KS~T(<@BI3qER)kUdW^nvmWT``a-|uj#5fBT!jWZqBG(dq zNVFZMZHnr{t^$Ua^tm)iTD%0iaNI6|{)eG=y_`US77LQ3K(xUPOFA?azjRD~S8nLL z6Qz_F<3&!zW}#ADJ&OunVWIxqpHW%FS5#}WV*#q~he6R@7~M-miY$n>c^`crWhuFh zI4l>wZx$sZ6mnu4mawq0M>MTRt|pTCEf5e?g&Od0dA!i7q4+PfRnHum%R?*%AiW#| zme0iazh?D`tP0)92Wp7~F1nK1Agzf7-)gF$0<9$t{0mW#6<(+4jgnz z$sMs6dtN?(+@Vha7VPRAHgS?t5QFuN>Z_LGv3|aXx0V-BtHP!sV=<}qh21Bt?ro@S z6HyQT{7Mf>^-?RwRY3#R4bzSIC5Kam(5d|lOtCg@YydN}X=ihzs;`dZ z2+xmg_Jn6o*{{5_O>D%lF#z_et>#e;OuVDLB^L)CCy=_wWYTYjS5DVo4BD}MKob6a zOX>=9#+t9EZ_Fg_@7{Do2}T70_7=e=ov}2|F@a<@tMM}=vy97ua{VVsd{M&~EaNaD zw0gy*QB!d%e$ANlUYD8Z)0r*-TR>sfv#0g(Ta}&3{aYT`lF;u1qUV_zU!F&4NYbDU zUNe()y&eiPo>Ft#pcvKkTRC2DpA>)#^xXpXLGxkzA3F&m*Hh}~-=8QTa9%FLt4s^G zUfndBqAV?n(&`TzCBJ!ZTQpXaE@N3-f3CIiceLXC#u>67;1PtLFm|b6N#TQ^c72}Zq>~Fvt+_Gr_D-whMprF|H?b-%Qy%+@LQ;+#gJZd zWYd;93F0Q*DdNU@y)X0+?GQP1{1xdef{5m#mVU@}N|33`Hd!T{F{C^$jpVV5~ zW*QRuL@2X_XU&T|^W z`7(zb1GVKdBWNOD$o2=`F+?@LyE*rB0Wem>g2fH+AA|;D#*h0i0#iifeRfaJ8!_4# zHx%diH9WJFu_P-%DRt+RTeZx@p%|^rGqAB*_cj1R;Uzt$lrquB?R$>Y+nK(>kat%M zS8j%go2469Jcga1j371wQo2hA|V)#~gBJO;dlz+B;-7$g60 zg*H%09cBwW>_5{F#q+2m*|4^RX9WPbROD=&07BOrIJ@NzkLu;AD}&x^n%g(heYb}R z_gc57%UEA}nMnG*H0@^q!vq{EpE{kljIwaoD_eT$A+KmKLNjz7CMX1_@Pw+WoP1p} zA>Q^KfnOBn+fo3^mw2*YzP+4YNrabby{;_bFQZC)VG}K}5bwPZr7M8b^FWfei$|2n zlapO%UY>!|LSYN3)IgW7HUg3c{!!Yy?!ib_KEvwF!Nt+yg2{;p&{XD-;fct4`%4iW zrLm*7R5+mY!U*q|=w-}UWOL>$x~{QW&yuoQ}wT9JEEX`O5*kTypDZ_=LsDF z@j}CoRC4gHw2QFDc{SBpifMnouZll>1EV?T@63;|rkc`w<;&VBJC`S&7~j0bGn2O_ z(wnt7Ji{etGOguqA83wjJUju1ZSi;+rH2k7K-VMM7OHF%gxVSmC^Cfk&^Zi z5rM*c;0*2QHIhjFRda^`GqESb0`pD-;5Fu=Lj4TMd zG`hqlYYsj#r>n%{IO6#^pqIWJThrX}{=%Y)aC5_hMpWpkT(W_vd7J4+h(|#~0>dVx z4#jwYwHOL&?iX-9yiOw-WIDAQw9C~uwIku?5{Eq;b@TxLZRx8o7p$S|wD&TEjVqky zfykQF9G6_dqMhcMWyWl4F$#ykpZ;JJ>@|&~#sPJxCk8JxqzB}7_@~c5XseBhzDpJH zm%Pgo&`Q|F4QNj&XGf2vZC){VugN{d9Wi?rDg1N`=iSX$8LU~Z4-jDUQby<{h`iUy zgw|AiyyeUs*w1Wa)lI7V(F{hdP=#uMXf|VTNYOR{!uC~LB;`R=`fhIMDHiTo^SLLCVs^m!m{HVWzuuFv;P7|u#A?t60;Oc zc5@0zFr#w#A;jnS_aV&hdLAp|G?_A`_6nE9^7b>&*{~!6=14|*@>;*A#Q5F9B%Mtk zH!6#ZYcl!?PuJ5}V@~+@DfL@1XDrawlhXeFzzSJ00yBg7MZ5eb)QWd6oQB72m(<>% z7dfuzX}3`$o{U#0v=9@a*p#1fAXPO!=~H%e@4X36XJEy9aF{#w~<1{aC*^@gKk#9FDUpFo3f#=j1to(%Y*CEIR$MKQYiVY22 zxs6L7#G)_n7z(i8)K5nh^D@8TB)}$Ed`1ne zi)uSz^G$@qi#qxT<_pfaJMFx`UmLqxt?IAi@YRYGCzioZC$D^5A(_;~#B}~PdFrt{ zi)(1c)_kG$_1DXhFA(^7KK1Z}udrFy{R)EY+-7~uSj59kxSuMAcRdmi8vBPQWNT#{ zr!;osn(wu^K5H9WF>*4fG3Korq+;?f>r-aPUc zpo$gD%S3D`CT@>L*oYOZg=xmdFt1ngD<&e|y{iMzwbOA#mHQO2(BmKlG?6_b#nW}H z7H!6dn%>ONb8w@ob1z+N-ILvm6WcyH9*I%fn~^$@>DST8ZbKfG2H-Ur?i{kK5M!b% z(^Prg1E_y1&+!@@S}a`kg}n%F;~0AlvoX1UlGv+qYm(>gh9M2LOYP9fpg{ zXQ?0~1{PO?pPH26_!|8ZVg!8Q^a;F0RlntVyZN4@*!o;)md}I~LVNaN;}2|lgB-nF zlk*g}L`Wn*a@&&qypwa`V73^_#sgA$JWFOL0a&k6q?Gu|Vr5Ed{FiU4HqC}-)e!|~ zM+u}!%*QCt#VO$K$Bs#79@RH~wG$bs)e1*%7vmo(3)C?CIZeK56~si)CRmOMDj^#M zMNU=8#>e@euleufpCbmM|I|s3adm3C(Wl&uiP?ffsiBL){~3Yu{oAK=9*L-wMJm`M zKPqC4_~TmjxNcpcO7azf@#zB4+7^49I2$L&XefSzc;B8Jg@yB5k!r&}FSIVw8wJt@ zz4~1uSob!GT8UyuFl#Q7=HXgzSHFl|6{1>bm6O3HphFqs5u=2M@Um6Ie3f6yTc3F2!ZQuHyP@WTwLxdgKOaEw_rCWHn+9eSv(WTzJ~T$CAQC zS-oS3Mg>dFdyK{wGlXzl{u80{SQPl_)cTUGC@h_TR|o$3+fj_+Dq>f7)x; z(AbGzI=m~XNHQqjPiy|qJz6lgeH@zNI_llntq7R9 z{-j$KZiN%jvXTA@UH98!sNNaKzZaQEbPm}_(@%GmI!$+hA$n>>bSCOb3vYo*omk>M zqbVp4l4_p#onN&7Jb|QJOmKtEy23ZxB|$OR>u8Q&82WHoE4SV3w(a0rGBkIFK|Nj1 z(H+El!FWzV2N5@OLkE$%WHXoLf&#D8wG!F)fsLm<$ayRv`}m39a*o)*5qlJy*_J^d zWcg?2)0kRRlehE|;{rD9&t!QB=9i*ZmWChb76D-XAryZ8LhNta5bW6rf7GBim^)7aS??7U*6GcHeq3e%^P-91tx%TW{7Q>EtM<8K968mXJDk`S# zypFb5o9XC;H@-DTClW9dL)uFD{qm=zU?(?;uyEw97O!glXPk4PutR=;>N zi=IKwuO6tO8)f8*njrg9N-Ue(@?SaEm3DTv{|`CWm>jq@F7Cx(f=f4GpFDmS<2!|m z{{LJPP{;(M25NaFpm;tRON{i~=>b3!vE(T}iF*V9m;>d)r%I3SK!6A6 z(JPIiVQoeLpP)`K$IU1Jp6Mjx+Y88Ri|LK6Si|l}fIAYv&sdU43V;}ZwEmN^u;T!%)rPi7nHNsxW^wY*1x7;cjX=lW?7IDf^2d$PERGjgBU9w zl{Ds@x!0n@n7Lwgj!?A{0D<9n^|vuJj462gs}G8 z_gJJ``y@Z$xOPOk02RH1X7Q6^dQyqzrF4`;jtIT7A|0MDoi9+@%f8p9KMGCiNeg;U z2rs@4OtSkw0v$uEV<2JSo1HQM5Z@#7w3RZTuYq7$_Xq%yfmY3yzCgSWPc%VQOj;e9 z!!{;esP~dE4>{$#F)<1Ff&O~{{4rOi0%-_Dl^%H(bnr{E!QX}+tpI`>7X~$%fc`P1!1D+^jeQ0B|L-d|?o`MHJD;KW`!E zcvy-NlQ;g(oZ*)T3+L58ZcU4PnSh{(-&s6uA_&Et(?7snJZH=lg1=VI zPiI3zd{)`?YxBC#^!)hH2|`e>_JV}7Ibs>o)zjjWuSf*g*%NJ$<4jie9$(yYY`Mb2 ze$?^3n0;!LNvoC|&62k2@KSDSE$m5M^{w`1A7FL<%)z`1lebBdGgiHZkT7$7k}9dD zIhcZ}qiPvFz{|oN)={u;LlLZCy1s{7Ds}0PH|R`z{c>4P69F5R%Uf3IwIJB@^w?N- zNe3>RQ$kY9*debNz%jf|H>&Lk1rb9&`8(Jp=rs~2NoIxBAQBeh(Hhk$xzzLC5vZ~J zolp>tL|5WV@vhxl_T|^|$L^->MWMcj~wYsLjl@vko zaI$OsV|W~#3y3nYay3;QgSTsrRR z&&rHwj!~Aq>y2zVBu3>7`JfEaow-~H=FbCKXgS=1S|6b#(u#C?Zj*?vs>rc=;K1FI z%=iz4lCK~paB7Jh;%RNVSpx+xL`EM(n}nSSq|L7|3fxdV3VVq@A-tuK;#MLYm=UZh z3T8ovF5^|0n7xU3^;jOQyaZK3W?k5MFOb$rL{rv)dVHz!WGOZWaN!>U%r&u=d&cKm_ z6gmFEz||&x$kJ{;yNAaQW5>S`!w@Zo8q*oW!QHo;zWJr&Te?8aSN0Re@SF{>rzM04 zaz^)t(iroZM0Fb8{_2QIyvHGr4k-xd_>OHEhyb6Yo78Z;oYm%R?lIJfZ>g_nybfva zVb9Qmdd#s`Za8DGy*P>aj1Yc=ae*M2&Vyts|DWj7otZZ0*1s3*EP>LUd_Af0H}2b+ z)?KG0>$`%_<17019)_)q_(#O8*;I7V^#SDeM~~htiwV4DS0Oq_L89Vz)M>}-If1;) zG37rRbRAqCJu%SyM)l!E_NKx=V|;@WI2lmEtv`8*(Ff6PeJT-Js|^4S(98+9z)40K z&y?D(Tzu(!NHKgy?sJJA&*}SxQJEkwIXN;lYA5v*mr8iD&@<_JrdEDM4@QiKR@4+N_F*b?e}p=h1`;&u)=1}FZja_be#Wcy?Ah06G`=n zN8;bCU^$+!IkcXv$V>V*{Db)|l=pI)M)@c@*~O+h`Gy{w{&?H|tB~iCW7L~rRd36l!dEFZ>9d8&Eod0w;l$iI4l3-bY@i@kE(f0D+M zl9`qIX7xsATonTo?2AzkS`kogV%bu||C6R$^?%0z@;_<15P+iLIKJ3ZI&>uoOspcS z%)jUUpQQ!YWiGg$JNj3V@HFf#33LHGRYOTC4MaaU;3J~|>DLP^7)^Qu2udnjut4OO zBmgx;M(li&A{5G7&nrLxY|M0_q4w}bKWTfys-)a-8x=D;xqhz46T4Hg&1wdv-BrEu@3eIar?8XyrG&upjp2YhQcmR zttRPDk{7nl|F>5MSu{b+7m@Z2*{MY9H4$c7=W^(yB6y8CLB+b(TpXv@-E&-;tugJ+%h*aB-S?VfgEiv!pMxePkJrO113ijw6 z+74yd0~cTf`$p!}XAQ$PmA#N%y0-sJ_W5ob-^~Al!TA$3PNkuY|$dZx#7k6XmZC~HaB(qhcvO^0a z_w3`PH4i=uG-KlJ4iD*jUr9UNcBRokm zmJh_zYH2_b|Vt|QZshkq6~rix**JIwwNue8>wXo^c5?r#Y3xnMvKz`<;Y zR=n+q>x;iYYIdyJgw%T}{cTb#k)#2?imFG_*h?`lVYsOFN&lVcM+7`PQe<33c5yN% z_4}g>K&X(wRxoz%o06eXp6dkW)bj*?y3O~lIi#@lTIqUkA;Z+MgSnzKQ+HL`K}-XV z`V$S@a)$T-4c)zn%baU2AjGI6;~2Ko+BBXBIfx5B39QL*cw%Q{8!oAJ^A$$;MfX99 zDtq^+KPzw8HdG(p@}f=ju}Cqj;+t#6YlVMrbha?P&UA1wBUz^hvYaB59JWBp2{_lp zX<*hYT$f_k4-Iz094um*xtgf)Bv6_OmdodcBW4DZHp<6SZ0d^~@@6|&-bB&+ILtvv~4gqd$ z^bLAhJ~yIx2YusVJ1ZO}W#i7+fc6&B9RsW1b5Zp0`TY`9BqjJz!KRDFw%h%E#^SXm}LMM$e)9d$^f8FdI9Wu z0AL1PvSb9nKxz;I0zCtOcJ2i*IC}vOP~JcR==Q350E(E{O9=q*K>PZ_y#P?=$EM~8 z02He~LCqn+V*qIPGkl|9f==h3QKPXE4gAI+jp`wm|0U+XEnkRV6};}C*8ehtA!6&) zsWuEM(;&%-704pBf>isAx<0|7n(Jh9{QS}hd3`o?NA&Vg{^P66;3!zzzC|omxiCoCy1yiU8ifdMTaTlzO z0<9dW?qxy$EJOajFE{yp^oWC_T_f<%Q9c^L-anrcb6K}vQ~EL&6R-#JPk z_&U{p?gjt9l+$3<{i~d&fj(!Py9?xIHddwE~YXt%RodvPx5naPL>DdpA!j&e4`uXv3e zxP$bC&;T~eiN72o3Fb2oFV6g<#ipr}RDrb13nUuv{c9n}Czgs)InGfAOcf}6Z;S!_KJpQ*Ierk+!l2HHuK1#%;-OG9s^nL5f8nlvD&W(Nyf zDkOX9VLhQ-d8cy?a&?EVv{q3>XJY)uS=KKC3_rEWk`<73ggTi5$x z2KC5sy|aL4N^Tlk?zugqGam9Hn7>P7O8vs>g&A6@Fw9jq*gw~+3tkdA_9La1l3yH? zXL3>fup?(w+kQSMg=HOkB)gJ3({|9~3T)vEgeg{w$+mAhH(@pv0kv`e<}8;v{q1@V zFJxb*FhQ?`aZ^zZb0`-tvn+-iydb)fy~i`(?srsR zuj}DrltIS4+BTwd973Oo0V8jG!SA;09SzR1_>bt3et48LgRt-8Xt3(Cc;-1-FKa1r zqMoJ6TK6;Nn?!38I?@(j#gd#jKd*C5)t;j=>aI@4oEO4nNS;UW6<(HlFjzR+#yL&A-$%r3n9Gk@bJzknT_o!dUe%b=!?nwe<8w+{V2z!K{? zZCBnBu9)9J5^}5=9AW5$7>A%DvZEf!mE?3haO?gl-dGvwAnV8pU4di6BmZ`gdivR? zM&8Pb*|E-HgZK;9lATVI&W)@&GzW{DG^iZBqhr7p!?%%k49d>3MJwC3s$09 zc5gap8a=GeDz;DQ?l)t#>Nk_BzSgr>Ay=KM9>NIu0be{sewUV?w&g6Hja%Q~NR zgpQ(|gc#n4A#cb%M)s}71&aF+IKULwhzy!@H-z0iJd62>J;p>0E*SoKY01NBMwDl& z4$!$Y9Cv=Bv4HB6PKfP=ku46F`}+mmQm49+RV%j&?akJq>sLmx(VH z{<0mxt8?~rRkgZZX2EUOgi6*rhUe3JsmgXdS|qd1mmSVfYq`43Gb7Vze1*t%#=IVt zXMgw}K5(wTb;J2ev0&~e&>m%iA!}AcU1;}q_gaV?>=~s+vYF{nze^_clcNZ7LP zg(NklJSR8MBwSuPtk1jLo3L8u+-Pq}V6SqU>@{QpLsLCj{?`q!V_ju51#=kpMXIga zP?reit+fdq9yc!Rqcew;-ms(gHBKbBdrd>rY32c+q{++5`s!HujXDKHoB(+{*N^o8 z&0U|rxa}y1NriCrt4qk}ZZVx}FYKyk5H7@VB1tLGxI^keahz_>X7}@}Y$Gk{Oe|rP znK{Eb9pf3^+PTfC;Z>!wW}g*>v&c-rX>|ZWZ6YG!#y=q&-VS=@^I|!73O;SxM*RZ% zi#(N;-w6E8(Ss%IrnKW{%p8?cx1W&)Q2i6?e%=11*$Gd3l6Ng=E8w))`Dz^T$Z;+m zE1yxkvCRZ$bFXsMxxt-m23e711h|-ExCb-P`9o@XLU@hTb;^;wu57mc!m(8-gLn9Q zN|ig@)Y}uYoYotJ`ypDP4zrgEi-zy;f6(;~K$1nxws5u0Y1_7KPTRI^+db``wmq$B z8`HLJd)hYsntR{-?)zWFi>QdI9hGOFQ@OLwS(!U?W!F3n(c);zjExl=s&X@sn+dj=)|B2C$pXN@n(< ziK0An-Ydau{js4&=6Oa9267O|2uR9)Rlz3-4l?_q)aP>FsVxZ|+!b}5cHp>`d9ycQ?^Dg-cZV#=r`a|8sn zWgLS?B7@!rcf}}*u}6nTfHwIV%p;I_XsxJE6>5|taJ6y|^JNjdh^WVWbfUNL6Mh5wvi>j^n9>JpYd?to@+jL=cj;|x{` zoL|cmTI?`EyIimd+3+vkD3Ofv!LL!PdlhY4J%{4A!SG2jW%234^8G3`t)Zg@?uDjQe3a4MYuhSN`>kZhx=Pc$)Z?P~9e?7;^59X8F2nRALq-qMajQ13iwB zbY5Wx)(-39b&^_6kpR-Ev>Q^%zD)hB% z3>m=JMJHb!ZNF1Kq1(K*=oFAco{#ks+<=*|9c)Kib+eK$%tnnmc-l~JqRP(lr z_x0tDxSKuI{Sl0Eq-itWCUTK{5c4fBp|_}O1B0a&X4S1AWN~@cmi;o~UIEN#p=dho z=hG32O12~a!_#RY{!*DCpfOe-jjkVj$PteHDQ3RR(Bk5ZU&nHCeqs73f@tUR=(-w@ zSlEE)sx^4SUBU?h?0`CkGv!{n9(Ey5JARhM*z+b`8^&_uyfo;OBdgPzV3!^0Hx^`- z?+Km%$T_?iA^Dl-g)#+l}%-o1y=}uJMdFsb6As2apSe1 z9q$$mvAtPQLm0J}!cI}_S`vE;fk8>nSv4{?(y!+WrBO@J@`&~|rj@j1;+>Pv?g{8f zfO-k%8NmOa=>K(_Je{NxxoPQ=-l%~7nxhXgi)Yx$%g_Kq{A7TadtyYIA35qVM@9a4 zs=H$4(~9Jg9Qgpk%(@N_Y=dLFpjTNcIacqJ9lx}_ku@{Vr{1vGt4;b8!gEfG%mqBV z3wHzwWV@JM)=ZZx(mR&7rlPZyBi_YXLQ0uV=1%yoRfwV*++V{@+MH>YJ91iVsoav` zCAI^gNNlP32ehKGf{{T$MQ>}x?^`EM-bqClo{K}-DK=@+xMvqWSn$s=bYTx^E#Gg^knr3Enb5-kp%Y1h+iI~%*&+Cq7K0R1d2ZTgs6nG-b$QI;1&n$rcd z>JQw$1c3#~Ge7@NfE)z;xkEtO8=fSxg4XJ#uY91fvCmD5s*kR$%pEEu4du6lFB6YO z&bbU-XvS}7sv=qz>|Yy{9vUlAhqd015zP5BI+*ur7rq+KnE0CV_9@7 zbx%AJ-0nCsnc09=y-TzY2DY%2o_)ykS}!!3qA*s%WNWu4N7QW@^1}^PZ70XGBjP<@ zHPV7`z2c?Sr?Go0h}yL}+Ne?yQgyAFrb;J7j3Lrk9q+U^Q5M*5aF!~t>Zzrc{6mvp zjpN)=7~|MTYN9>AK!&-5i_FOyrSu4#v>QB}2}VXij~nrViR7#{!LE0uNXfkC7w z%PMqR4Z4}M&5l=t(b5e=4Ty}g`7CV25ej!b4e$8}oIW`^?_<4jER&49oBN3EgUY6@ zVkkzlod{lW%$H9e-&noPZIga4_u@$po|T#sAoy!+9wOub-IHUw&%IY&e0XPC?s`?b zn1<@DfVt1lsz_)2m}z9RUad!_kB3B!2=3v4aaoo9rqYDJ8^9NxK^DfHb4Z|rKdy*E zNGzQ$=>98b-_f-<&IiwKdDpN5C&e@om(dR}sN6C6i#xOZZv56^@xx6J986WaAQeR0 zP7>{>)jiB{$-r2cdsd{JsXk_33$J*8^)(wg43TnNMX~I8a%-iPgiWhMa6)dY+1ki6 zogZ0b#Bv`%Izl5<;tzDhCk%VNF@@p^7sD%ee@%$UA-Cl0o|*)8w+(Zma{AONbWq5LE~>a^W}c3KmRtM$Lu68W3IJ>B#%>SBZ8 zP)HrQeS8VJ+v(+0f31PAeAwDPKan%BcVTS*u_OrPMxl2x#pYc68BDfw&Lhn;1R3m~ zrGQ;isYtQ92l&=BZAD8I;1tLhtqeQ&=Q11dO6v@DP&?)(XPpJl^o=M59!3nnr;S#X zqm2GWx6K907b+s^i4BtBC~Qer>>a*IgF5ofzy18xp?Uf(snAhSx7NJ_0lF2YDmTaJ zfv6fhy9#XeCMHi(%K79ednN*8SAM!lM#roV&aWgs?$^9XU7dJrpF04gI4ZHMm{~Wi zess~49*i*U` zc(BeE@wF<&+V0CK`XOJ2c5Dm@yO?!*X@|e2mCy53}MjhvE~4rocH{~`u4NNUgb`f@Z8ag z)afd+tp9kOGhHS|-SYzDDfJct=7*q4rT4BX>Msz>#H59O5-WACKBhsoN*eHPRp=6r za@%`UO5Y9U!sbGgTteEpok>dPIH|T@fb`=E{%=LAE?lqN=kFa{F}rbqm%ya96vHgK ze1<7SI^6Ie+tW6dv5dj~ol9Pa(WGi~0y>Ddvr5{h6N@?wXw$-y+MfgkC3TbJnY@D! zDpUtWJG!)S$x{w1&6(pe$GwGg9zGig5mfB+=YkCLN^Hzb#ec_W@*u zQqiXejB3*9Ldz*~bz>L%VII~4m7#a;!hz|uQ58Ymc%Yp&ptVt#e@&bRV zrThq=Av{NfJ3lQZP67|mXy&J|_ftTvm$24b$n zz?%=nPq>#^)wK~3SIs#TF#}rnTzC~DP@>J}dr`M)mB`T5F z%OdVIi@L`VO6@zV_neYbmE>4@FK-Gk?}Fx>C9gmt6 zt0N!om-6bY)4ae(gVbb+vbjj{B`@QnS+g{Ph5C?dLn;#6dBA1_ECpr5tH@T0-Mx8O zAkS5alscFuqNbz&uYr9s|UFkJk-I z)J&z04;rQ#h^T^);BpIiUW%bYtr;Y}TM@Xjutq2H#9wE9$4Lg{az_qw6Gykyujs7( zv`h?3WYq`Glp7|S?6}yq$JUoF246X1N-_%i%idbYz9JiIGANscVLM)TaN?}XIns*o zqUT|U-6I#i=YFKj-Od}orFge~HXWO$J<~X##O_t4vI-&m@p{;RXr*D{4cIqeOUmN! zOl_rGdaW&YKyT6{ns8i5;UIZ;=7PFdXs_H^IVC@{NdRJRXW=}Df01{>|6R;>H&xx+ zkF`ZeChtf)K9$Xm{1d0N=R+r@w2YOnbQfEy6ExWfCnW~rj1^~1fVTL!?1Nd1hn-?j?GAlK9i+b>RwH9;uu$_%QfGZ4b!(L8*%7jX~ihlnq@*$V`>mVZJ7 zi2LCS^)Nw5LCP@f#&&`!4l5XjY&5+uc4o@``S5Sc7=9?yA4DS#4`0B_O>P0qUBTP( zrm^lW2H_hZA2D;M+NQEjjiA*TCIqH%29 z#E57aa#6X+K;7b5MUq$Lkk4wBiHmZ~szl@W)2}J#eHV0v+FV15qv5cmRrG4-{42fW z__ocBAKK;2+;ES`I@1 zfX+w=-jn)73PKtr#ub3$H7}C??@JJIZ}@Wn?5Ao|w%vmL*~WMiF*%5ZhzX1X3M1x` zOHbW3dbml@&3%8Ubp$6-+rnmgA(1yS-4KGZzP+ad#G08E&^F` z8235N+rasLpSU`Fki$-a(QYirplRwY@AwieSbzBq6LEBgC6E5Bk9MPuoBEbl^%Ahi zsWX!j^EWcIkr5??&R~XY!I``dghf&|9Q^J+X2B$-I}JROn|XIbs1DncwlPCU5NQ}k zw_diX$}ts1%#`qYoQnXXRJycXzV=jVd0XKpammBQswT>!XQUhx-?IDxfViaTrU!U?K>#lF ze>RsuVDdlJ#34ZgTxt{xa!xyweA5YavQ}yNAXhnOsyMK4&Bj8 zwpbUXj8FwsIHdD1Q_(+<*d z2%~4=arMqboA1TKraDMD$wsxioB<1aLtFwhMQ?$f=!t`&si>Rs-|6&N9p1aQqkEVJ z%dw=iIDqVqLXoCR;rOf1PE6g_bleS*>kf_+*f4$0Jz(bn*N$0r(onHy*do}auxQ+} z`PbfO{sp=M#P(ro%XOY!B~bGkCbu6%6McmJ! zYPz?nKS^%Wl!Pfw@e`85emu|kOj_N8F0VE&ImL|kqB*w>0PMUP%Vea7%qxpJk~sQrQu-=+=&b8Wb0;h|^_(oD!RVkJMq zBb7x9E&4OWq3X~sL0yQl^j4=jhGl#QkH+hR>wBRo)2TzI6az65P+KM-lrol3_T)i2 zAMn{wEiON0+JZvh)qg7g{du+A#<7k=&RLFVBnA zBLh@&X@2>*iwqk8J-$z=PrX)%XI}Goy;L-US|nP{tZVxL@jFefV1Ey7BA3Wk3;JP^p7d<05=9D* zIfaARXDfr<2nC~6E&~A%yZJuYh0P0>}!I(`l{rp+>ZH7eLLRYz|&(wm8FXLAgtXq9BadXhGZ z3xFfLiAjSp_9WZmkP)`$NZ<(Rk!B2CrBAVxu3ZI#xfPP%P6%$|rJ>@~ru;4lM* z?o!DMCz-QnIX_<*OsV>ss`=xXI8y3#^F4c@?tLQ$hXA;WK6%T}S8hSagxCClb84`S zs?`|7K7}nN(@)nt2HHmp+N?m2^5-ElGO?2ziyTuFyBYN$Ek+2|=RAHVB6aM?hFp&W zep1STw3eXKAP&(t5E6e>Py=Z5@Frt>=MuJ2?@eoCyh3cMW^MduD{mKBC>l>RgjTmCCP2xBK)o-j zsCv`SlpEyPMvxvB>yXXDMV zlz;tTKVY}@&axG9MFp?e!fv}PkX$D0e9E&d4=-}l&gLE^d0NudKuAtO} zKL+!Airo0_%BcR1w;Z5Zyn{+io^TOSie$_2n}U#>OJM|}H6*EaW3>K_A+rrf5HdKc z{uZXD63})$U(^2WOZzPStyvQV{RpB+SHNkX$R6`d$g&cgd z1G^j#d`?XY=Xw4Y$;W?D2mS-0w>-bIceuM*M z6quHrx~7!V#PECiehui;EV?`-lI>({;#=}!Iy#AKNSP?#v$uX1le{WWS!yBZwwTmm zoN+YyGHf?mNk9`mTK~Q(4siEbGJ-2xg1@x@CHS3)cF1#y$WXGmw7n8M`V zG-!7z5nnUco1_Pg@~9p(!gp&~D2GZD>y}25C5;qwWDlU~@|P@?SpX8P9JhC@lHMLE zy^Y?A=sbQ(!UmY;v=yDRRQo3>rZKer*Em{87v+M}8^G)cW%>_aC}?F<{>oFV;MMt1)BHuU*n+e*TQ#Q9u)E zeVjcPF1iOIw2?c5V*?jEy=YA>mnZ}f?zJLRkB&GVh1AD)TJKT|UdK#A*Gu0VmR|8{(5=EP9Pd3seIXyo|%%Yg~NA&Qs5y$^J`fJi*> ze+mIWV1U73A!xaRN}y?jR2bq_36V_&f|x^G3xTS3$vj}Q^OI5l6PQt?=zzpfVC2zW z++-s#>KWtO+Xw0_uM&Y4QADq5ODX%%?ww?{7saOT+%7)wd7DZTU;gm8`0TQ#o4&(s zdY|P^AIC0y%KcOag5+-iod;C9FmJe&XH!rUhR2x>;!^z5?g!C|PHIWFnh}CH8OLR@ zv}SlWhNI1TPigc&W*XwnoVC>l;e+wh8R6ZF(t$4Q&0py)ozNaG{Mqp6qtmity9r~1rzHI$U$VY4WKjSNB?;q-fu6DXa0GTnkK9DdbpmP8K z;0345B&Fk2flDnQFQ;kgBSs;vy$PvrK@vhZ{$XVvqth$ejOTS z_C8qb2A4>PEl}yw9`9O1x)Y?It>oIvh%Rv0Pj-^h?u(73X`=OsCt`^Yl`vdz0M+ z0z#JNAAasUDkCq>{M{FQx}3dwm#CrjyczvuL=k>=^VuEJB$_&e?omzbaoRN&SH~=y zkIU$3@!_!*m-JW33c{u1_K{Mc$h2^302C(R?JXPl<8A)~!_l6P7EQq2=g!!wg;KDu zl41JKIVK+SK|=kT$m^M)kC^1%lmKg%_ob=cUd}4e^=ytHz4eHK6=p&3xLg7$1nvUy zmy!floBHqm{!E5iUvi!CmY_7QvTIv98t9B$eGZ*5jPFX6b%luFyE?Kz3>$TZ+t2X) zzL=Vf>2x5XnVIh&tzQy4U*1dL-e~TRevm|SJ;ClKKYKO)#l#^pqRHyvZ$d>G=5Ld; zklG{<)sG1nZlN+eT}x#+70e`7P}COnR+jiVaV)N>cojqhM#4DO<90wJg?f0z3s@Dh zpH#|V&bMCXCwQfp+TnDexgZpn?iXQ@)w0X`s)U!x;Nw0T+oQuI81Qb#_R&q`Z`0va$ zUqTF}I{#9yVN`FGYhGI6EQO|8CiJ0>#xq+R*2_sUq&{b7$Shp%VCov3?w_#!MrAOBDuj zkPpuFo!hn{Fp0^A{2|3uS8C&DemT(fW;ZY2XvD@Wa*+*j3js%WAlSC;y~FTqTl&nc z4?P*=>6;`QdbkQt7O%wH{(M<{qh6up1QW1+dT7JY3BD}WohPblVM#gWSL=2o+(nbq z733TOpx!Xkt+{d61vZi~Qjgt8{t8+dkds=fsu}?=porgUe8;{-5%Uq?zE+%iAOG6? zHd%oCJMr|BO#Mf~zySb20Zj1(WdPb|%zx|?C3P7x=ynO?!fU{+A&x4$aLgmX+Z&bO z2j9_I;g+bQxB?#`g*eXrbVe55qhHJE7L3O(eh@fDJo8k?4)3Ik+S~L60ej@Ta+2GL zzp;c8s#Y{0QY>f|L`SIMm7q{Yz%}_y#X~PsR;pV__a3<(jQS6}{l$ej%X6tYQy(Gd zVnFfjG8Hs&*tvN~bkaTuZDQ<*aCI6iQ-&^Tf)SJ0kSp~<92Jg@D>P09#`ojvWuE3R zI05lIKM3VAbEChVsFpit$#o*LmE3E}q-%J@DcSg@0CVTt?=j@kvbCe?ui|{+V!Dra z@hssyb^BOid&3i&hQ9fqy{eM2c7b+hW`Amil@+>`IzbI0I3D1Dn^dW(UunRux-tle z7{195w2#p(GEVL*C3rlq1sq37L~iZExE88n`zvCGzwT1SeG(eON zpV-iU^Em!~TvP5_ASq-+1ddq~id?zGTy%|9m9pHSkUEB1l?d+0Nt;a6@o>H@zbwyL zBS;c*Z#sFBQ$l}zf(JjfBgvSyH-wxYRfVq{(ffFlK-j@jX8}$aYQN_aP1DjnAoMfb0`#^uTQO=?_b?mYQ+s zzICxDKibbT%<08WNZ##)4gq1uuvAXXBAa%`BF=)FY&Qf))7ye|6hMoZU5mO3zDUKh zd7qE#EV1NpV9cGXGA}*O2N_WUvqCy-b%(`J{+!LP`5DXhYs_7T+N{^ulxg~5V`}HE zgu3>X-;ZQ7Hn4JQnKmSPRJn8gE!(*Qv@ezP41MFzViLQvJG5Pg58QL4MuiAF_G-q@ zkT4mJu*8m~`Z$4=OuaNZb>ZtXyz~)&FT1}FK(3(gA|xOZ5&oqPTxoM_OB+m|Rebj> zkHa~QXaN(y{#Iun#rq=$T>I-nv`oA{NaWjrrJ3mg_lZ`X`lH?Ob(5d+9O`m}r?w;G zi({0iZh(0O&ECNU=C&E#`t+J}x~o(Y+plrDp0e!QcUBZtFh1}=Y1KJ3gWw6N z4+U*qG`X)C_UampsQnEyY0;hN16&$9l`gF)P`)|v4Jp?BonMa#RFU?>NC97vf=HtF zjyRIoDp-R*o z7wJRFNF2rBrOpJl(qnT!U-_`waBzFh%rgl?q^uG0ki_gjxBenO>84$SR%*M09<{=B z`^#$8lLQ4f6+nj3iH#{0&OwCJ{z{qSvxnE?=!Z-(j5;DJhVm?fl^GXW6(az=i`27V z0H5-;!dXG){}qV%$F}r;2O@&I7?6Pl69uoo10;AUCcxGsA5Qs1af^#YDsJvE!@sZ9 zh1lMYws4qdGpi^178=S-j*SrAggUgaeb?>&aY4pCgwv>;H(I)MVI~a^Vb>I?!iK!8 zYJgw3?>$mQTE(qG8Ze<@T-5{h!jJgtiGeI-QmVg|D7CLt<}S8!%cZ&c0XyIX#06aZ$9SN&0V!heE`rFr0Fbr28S=x|c52uQfI^kiIa zh&G@iHHULaH3!nBD3eDJ1*5k~aZO5hfeSVE3r3BHKsvS8I(srt=~i^YTcLy?H8rK= z&CW-;oA{J=lvOKlG_NGsb4$`+dw%cZPozd7p1{GWmB&kwH16bYamEmA_lXKLIg3eEc;jZMPqXzLqTZ;v5K zpm3~+CJVrEdE#p)Po=%=RG8F_(7Y=1=bh?~HQr`$Tky;g^$f56{w{xZ>yA`D{qyOM zvP3$UIoyI+$r?QtsOAB8C(4wjAcY>0VH0dSvLW@B7 zG*^1U-!g=GUxKa$-%taTERDNw{2M>t7OY5DoD-DV1J!ko4+*v^?SfaQOVDgR+@)F3=2RFM}Oc#1l_6JKzAr-`|tX(<<=JeNNOmC9XGZI3qZ8kzIeunj24DO0Hw6MbGHVf~ZMiDZw} zr)N;05FlHWsMHji|2k&{1SKB@k>|2uKRH7?K_dU|d+s2fVRq_ka);cl7{n zy*_&YmYx8BMK=f$0IT$F2SB=A4dNRJc^Al==W)RB({S?Q767xXujbyVJRkaY&~3O& z#*tmbe@-|4a}km$v09`>wKp+pFAx9%2LB0%D3sk>ysP@0Io==yEKB060z(Fjh5aF< z%!y+eW(FW*Uj0?BinCkPLk57h1)KChyE7G!;(F!-guDw&KQ}U&ccNwM13`ovjesPk zpn1Z1Kj8mQD$cJ1`O`h-PMN0PD|)*jof+IH9!SpU?_*}q7xJcc_u~LNLbcj`-XFF5 za1l(jP?J0!ok*Qq3@*=ztt~1+SvhX0bNn2~%Wi0^Qe{8>3K?QOGmTPzws{+#(nx20 zuLJe2qZ#buXCvGXPoA<}d;iL2&)Ld`Tg|a8(@&U0WB^R(gf!IbDWWm#a;n69NOB&g zJVdvgL1JG^e&GFvprk<&YN#;J;zzg@1>ki?3SGN3wkc)@swl9yCeh7N$jdzaL9Hv` zo^?b%b8D2fKD752!fpj;m}M(i@bQ?IXaQ#pM{x)!gs8>}tsHQW_rQZx99F zB7j`!?~%bqucotY(pd28-_1PcPmYU^r%|^BaXWKPuyEV`W1iFA(OHa3z^{FJYjQpstnTJ+S;dN6kBDB@b{x9B#iJ#t+cty+EO6xa^ku_}8P6sNxqNBL}z|ABCZ zM!*H`d?q0HnO01m?a+yL2|nCg>ej;%BI z{jsZ`+0|6ho}7}u>Vz#s%orvr4jB{ErA3Nf{}>Bw0FZ&~hLMNoegX8m2|)4^{wKfi zpEn6;5NpB|6+*}d@ST9Q;6y{yd5F=TcIhtwz+rwV0&tNNKzTr35qHF8#C8B)Ao_C^ z^`Lj`1)q5`7-1otRvdfj3)6&a)YY6+=zJ-Z6x>r5U@HYS$9 z*8g>|7ettm_6AvWcSQd75^|VMxz6(}@%L&$%1R@^q1;Oil2OZfvcVd@xeL)%s|_H7 z>UxPjRV};E$Y(?D1j*Q>@(MjEd_~YmpExUgH$}-zF*?;%P7Q+N9E2KkZfMGW-wYdu_={!xyw|cu*2)wTuhv5 zAR#{A0{}^47drX38B7O~mq_;?td9ruMGbD}u81>G?oqfQLG^U8fP8b5Lj>dC+(&-i z(%D>~wFT&^YpJSXU0##MIb-$+iuf0Eqx{)hXI+Sg0n*EqvbjZv6HbVi_xFJ*rCB%nt%+ zHGSFF_yt8*6dTnnY&l3flM<(0SeV(wdiPH1A_#qBz;GJz^nc4_iaeKWT=01VfG+tmiKmta6a6H z6-OhXoNR*-GoDKpL9D>`;IC*qcot|3Yt@}ky;Bc|4NSw@79#ku^Bmj*fEh@t&tA3zbHe8z01sCmLQGc=a%$!;Q~$t&JLVEy zn$nov2loabFPb+gjdV-6W*ss)^_d~$N)FUKEHGJv!($R5*0CWZXt86>Nxkv!U8Z|} z@eMy4RWoKR;LAw80a)s5G6Ak{+NEB$s7Bs4bsPwm^nBtAw_$Z4)eSrHJdS?gIDHE_ zmRw9C874wfea<2Ga~}>DAlyAPF)#!_s*xkeDl?h$LABs?-TGGH+FZTYM-bG9!n0PfPPO+Tk0a9+)h0bS7B7%|NOvG_pQ z&3O(2MZ#+!*SJ@5=QmaWKo~XpqI8Fhjuha~vwx4rKa>Cf5wN@{%Lm{#U&mnR_5k2W zMZUU0a|Xe5_1Rhg0Gdev3h<0QLfoK20MyBd8AJe}hAn@e2mtj1+7SW((8v_4Q3QZD znEN6I0%#`%BFX@uT8)CiKoCFq3qSw>G-igph6@3p;{B(?qnbZEPPT!J_;bU4rto;1i9Q6>T`x3~g<1JP<$%yK?YpSBiR8K6Jx}~o z7QbsSE;6zu0E9gM6N5(RR#iQLQrr2TFa+M)@z!Eul$?reL)xv0D!{04K?@E1}X>)^sgonaE*xAeFA~gwDlGC z002~r!)pIdL{%UI9LeLewgYF2V95#u0J4RWHUIzw?*rhDG>Fk4#SQ>KiR$|FPg?(i zHy;4dbo&duNSFaXe&C_YeU!if&T}JB0G#*PRqYO%qta`ECJeYjV1Oj=9I2orta5jl zN$As^6shf!i)WFX#~&+&WbFTSu}qo{Uy;-SPrPpUFpB?Ad$l1UhvR!m%rIdybgj4ZZQrBTMs^p9SJg&YTt6p64M{vD{BFDI!<-vwP zz=ZKtSxZNNsM@%E9EA9pngC#<%|W&GY6c(>138VFy`k_iFak&45hje8MRT#eY=m5A zF#3bO@FA8=`kQD}2@US9NKh$PV-SZsY+17tn&{>>Vs&&?$nUy%_^5j5w0-Iv!|yiY zVL$080I)hD_7q2B=+eFM&ZS<(fd*0$Q9{hBPFq+UTb7onO8d-;pnm^d1$&2zB$huJdv&Gncx0ltr$F&TonSTX3bjn6L*v9t zKb9#X1K2fvMcBcu2~ZPRJ_#+v#PrN!<-)&Xzf!oOPL#uQ6i1)cEXlF2x5hDD`KFM2 zlf4Noh<=~8PUE{e-Vwj~?tK0iPRCnIr&OeL;qNA+J`wf0oG+I=XK&^=28%`You&0Y zz8zdEU&hXmWINg{qyduRotG33R{J704=5;lPpj-1qVX*0Z~OaUhC!U(1Srub$4N)K zir%ac=UbsdzmC~A_{cjzofsy}#Dr^yn&h&(rWR0mP12_vERBT^ z^Dn0A3HwJp{SOSwKG){-VQx&IOxAwg%DIH~3aXdg;WPVWA`JDc(lfToDu)=f&hsNO z3k)hGf+{{U5+WtoQo`W1|E#9`43SifJF=hEn>#^CSd@%gqp&$hzvZ(6M$XA}{NzSS$f2b2T zFv*Eu>a^uxw9n11vhq2mAN=$le#b0rvQoKih19zY6ta--q5L$pr@B=Vul?QwjoJGt zj{3-_*+bL_P@>7!l$<6%UU4h)nBD+W&Ai4H2trga&)z{DgZUZMo>-HCUqrUXp0L+t z1X8&2(>?}ltT-&ty`jf`s3B_DkB7%)-5gX%Rd*RYDeA$xikrB+nx)2k9y&!B#yU4H zFQJWD?%vTJ>Sn$Q%4=wVS|na$ZEdp1WBcS?_Eqfc2~*O~=e^+JBdk1FWGeH33Ln{6 zIZas4CUFP;L^dbtp2y6WK8_@(Ye9vjjEdx#(Y%qZV_nGyJZM;vP4oCzp=U z$vHFNg!`0o&9(v#=fEP8{waOKQJm}i=g*Rk!nTUT@CZhh^#h?|X6V!>KIp9wZqN2RfLqBV;|tLdoyC??VjxrI-qvDaq0^od8{{f&F+uQ3dPH|124 zZ59u*pDDJS!z^I+(=P%Ja(&Mh%Wkqhzg(D&1D~_$(48UunlZQo+7&99f=Yc{x2zKG&U9F7z>Wqw=5P`7_f|Ak->xHqPlx2SxKRAgL&EfqAXpUfwd{I%4k zx@v^vEWIO`9J#B3hw#m<72TX8K_f1*-KZudd_&`JQNo8cS{@i6{i%pDO(HL4G`}&^ zqVn{^eMiJzh>s*JVJS1THt5~Pxv1hSm6~qTOebKv%8;R5p=88Sg{iX6PH3gJyB= zJR}QPBp0QG9_ZgV1Y36tZrv%pkg|@eV%9Tfll~NfXYMDY$A&{rKol$xU}zewH2+WHjY8_e~)Og!?zfZf}}1m zHHzt3ti;=9XDMtKD>DFco0c3e$_(WpwA&;|t-slJkEpc()|SiCb^?=Q_;fh*MJ}fQ zl$;uK^Nmz)w?t=xzzQ@giq~w>|v(-z!}Bm;oja zKjSc;n;Znh2iUCa_#qzsvzV_z1Id=Rqbwk@zL5YJU?wIpthNuz!)Yev46*!+ee*81vB}F~T2Cm~{`o@~pN3rWG8eCkDRF z{&bMI8_P()3+>1-+wm<1(4H3^;T`~NS5FEM;{ql?@(TX54F&*rE#oO0@{|q!zT-GB z_79Q*Ul1sz7eE?ORl+&iM-qHHKKZ-nL>@_)x8eigzBwVHwCOzdL*DY^KKiIzP&EXF z8^q0941<*c>@#HjSb9&@e6{hzwn1^?qQ}<%kFs};uI%aBMfZ+v+crA3ZQHhO+wRzQ z(j6Neb~;WvM#pw?(!cwD@44@HzH`U8d(u0og~*Y;GXFTW$b4@ zlAfubiBlJ+?W1#t5I-L2p)^Y~fU433moj&c4|$vF7a5QA&rr@qdM)_48p8WCSEZQF z!g?HuScjNCN5{ACZ_7fHN(NtM3L)p$?w!Kl4FQ0UPiZ%Va*8B^KucTyeu~VP{#JnG z10-g!APW#voR0pS@OK@|6p2j4RFcV_WQQGX$_Oh{I>=E1eOys}{;lO!KnC-Ls{){%y-Z(gpYU@X(jX%K zt$gtd<)Jsh&*FeL$i9cu#IST!ceN?QufcQx*6y1PIq{Qqz8iliMhg~K2vEBS z(AEZ!ye)I28l`fZ1K|N=P%fj^@(*g?nZpa5Y2v3I@HU~qo{s3AK7qHIpDojjV>G{9 z8PL2PSnkYoEmuHyIt#W&Ay?`zvxQJ*h6T2{_SPk*A;OGLhs;A@dTD(*WJj8q2lif_ zB*Y!fZ)okxw3a*1B~`YuwCGP(+CQ^g?hWj={ZOIWT!ShRR-uFcvwr3>DJ$5JU?YrU zWg!hQ4Ehsg_ge>is1j)bdrYY0&o2-|5y-Wm4a9CfgR$SpewKaZZ`AF=+_KsK#!2~s zIo9dO5~l|QMl!baW9eBO8ycsCfS}dBpEdU+ODmH z*+A$Vx!aG3wil@G7?4X}d=47+5D=RM)sm>W%l%b7C)g2H3?y)&IOc&obR%a;($T=b5$ zcDNxQZ&C45GITOea;aF^uyO2f5fPOBTXO|+_^+$|>9W*;HHx$6ZRRBat!>VmIFE~G zvrNT&LmbT1mUO^NHP{P+BGhclLVqS?9}w{mFWk5?7=t4Kp#VS^XclZqk_ccSIO6^x z2;iiDCjt+|=i25chxiS_2F0OLS^1A>a_fDVr1Kwie;fiG# zJOPKwZZ}|j^PBb z{HD(k1i;??`aT5Zoe?4spk;CN>nTs<8$!o$#p*2+Q&L_CUZOCcykKnNK&ymwED_C@ zn`=jSh3+7hf!W(=Au7g^UkRg3?AVS5EFe$g-W4)gA6m;Um_wZ0B{1`b)|zlrB_)gY zo8c4R-wvTAW846oOWwEI?ObFi>3U%7_+l^eS$W5E+Q8R0NS`=V8QD%5bY_aiWn_ua za`6Y5#j74{C&8n8H|C1px94f2Wz$(|eN+=@cwiHHzs8+i`2gpU?*;7NBw19e9Fe0J zbEIN`Z>55hdoX>!+*+J$EGiXBnHOiqRT@9?$cGO~`f1DDg_vfM;po54I;mso7Pflt zs!fLTkYXfTVZt1`*w%?8?OiX$Z)%G!v+L|nT=!SBBQAf3yS3xu#Uk3l5X1_Z? z`T?lZzzdF$==XpkQH+cr2>@`x6aNu?ss^&#jah)bl8xySorIHp0zm~m&M3IP)UR|h zg3e)k$xwfT?K2rWn&)77Y?AO=@XO{0a&wV7HhwWJxT>u=_peYSGZ1uxvv@XNI0|mH z%7<j>HKH4I;6lKj#@ML2T*K^dwkSAVz&(yeNSp62=}_ibAaq@TkUBblr}c`Qq(*G(Lt zNx)b_VH25lWYz1&2W^H9scu_-HxRF%coo{oETgw#EG875)=R=(uEVlAOY%kSHBNv+ z&-<`IJ3wMh5tV-+12<7|>(Yz?pE00U66KRdL;%pYPfZ&K%y0U)+2S8C|Iw}>{$K!* z6E(rlGr*qkf6kN4e+D}Ia}m9?lARQy)j-fF5TLjp2)7D=)ldc2{@t$ncL8ab+Cl;} z)S-cg@eI`%4?%2Uq{8Ub7E1!?`bwr{IsSDc7BQ}Gy&lqFIMnAB9aJX(fCeIz(=7f; zUwdr#`S~v*{@(wlDq*l8ky`P91iTCqF#;ET`#ou(&&E(-&KMx6)&45c3EsN+wm`58RM%{vO-|HYWZ7_^@YIT+Xl|AgcCYbusj^_3G2Q@`BL^PpfV# zSG1VFMBHubCRglmdW|MBrMG6N7>zX%Nb0@&Yh10GeT$`@`B^W83^FSP*gX-{pl(|j z=~lCUC?YYW!Hq0c{6V!1^E@f>43h+6%OIEFu$tPcSSITiwq0>n))GDRGwmf_V6|AF zO%n!$*3e2knV(R2K=T*%-6q0oBeuzn)m&KUWw#q!f6|L@H_%FiA^$V_%ca@VrUOms zB=#`?{Kfv|wr9UguQDwozG(qz-{tp@sOYNx>v0_U_SPC^FM`ezcsiDxIONuBcC-jLl!GYf%R;L1vTI z4ES%dnHG-~%84BOIS=`C}SYm#IefP zu?RuH%q9H7nJ00p-{PPKF~){L(}dmk9o9>*vJl&~+^ISp`S3yx&o5`#dD*@*LPstW z{EWb1IT_>}7o|5pMhWd$j6O#S^SQe+KSzf4D^shczsBLHSdESaIh1>?BXO7?0xnG4 zNiBaKziLY|-rNl@>J5+R_yJ!+1#$VUhXYXwTQ_uevR3SN zFo2Z7dc#Z&#q7y}N5LG^GcOWGf>B?E1-Cz(13~DAqh0}*)Yi=PZ?(PLP9`5D2Q!C`>|IZ-ZV<0+Y@m5W7%V`7p;Ok#AU8H+_HiN%J8#hhM# zaj7Udj0dxX=N&lUve~Vy8?peA)WruK#6yc|=GFi?;X8;)*BChRfUcY)D{aactCT=o z?5^ZfSj~(KOR(Efmd#oQCBwYuN>af+Khx}7Kj&f@eW7O3@$+k;sdESmDO!XDhClNb zCIk5GG1|qC>}{L_XW3bORyk=MFF*#F3Xg@^BOsc5{JU6vD*2L;iqV!2q83^paR=!_ zbHk4Cwr+yYL~XP2!K033;+tUgR_W;O50YX&`|>KG4y6Q z%7^k!F6B|a9!f#d^+@DLT2!hF?Ux|XPuItrXTv|5Qc7}Yx2+U@Q zy5E9UXuQFe-pzi1rmpUwZZDJsagzso0xj>^>PnO%gwFL# z$9w2EupGWD=A`6U&DGzH=M?xyRHG9cEa0^jf>p|d+O^d={H)qK4VXdw;-=XZ6-c^| zA+LSxj)*4YpWw^3%g=ox_;yo7`h->1m+_sN^>J1L^3N!_=!aF>n5RgXaZ%aDyS-PF zz4J1IV=jYKAQaXV4VEr)Gz`WhV{^KJG?J~zJo!)xIqRFUkVv?86y2C;hfw zneV_c>EIeJ7UtadLiR*yexnj=73I3Bru;w^FXqL$F)%MLCLs4f@_SnuM6~Xp~(!J{UIAV;$qD07Ym&aYXs)TyBCn@d9}@xO`V9acor=qPdo-4(Ljg@o(<@` zia&oy*&nq-vO8ILi=I0B%#7PN`SHp7nx%S{LRL$_!_wmq_^(Dt`wh-&2y)eILfy(A zO&QUJ@WiLxUfv zg6AsOl;k@U^02Sv{tC6(o@V5kxl$ssc1gAGHI1b-tf4Cs+xb$cu8sx z;MkJ?lgxqnlYGLdHMP2%5JdeJ3GmvvTsw)2PU)mg)+4q38w^$BUB47YjFV0YbKc8^ z%SzvK*l-g|yj=48{L^4nFi~c}5PMD7lg@s@^Xp+6yfsmg%8WzJWk*O-Lz}+F53{w| z6UUqU1Sv%7&KVVw?W=`{u=A0Ps$S>C0Gh$VR}|`Jd%lJ#k>rmb=-2j7z2u#aas4b^ z)jDW9;+MXjA1|U}E}~f}s|XD9A}pSdrwLulT}a-M$>GM))i$?1H@8J)J^m30b`mbn z&N*Z!072o4Yo1IFqZH+@3?>(9uN;@u@_6?_sSYkLU#O+Mgq@HwhU5|eqfZ09@*vh{ zclOP4+yk0aoL&{^y_Da3+5$EPlFNfUFc#heY1=YEijF8FVxi?q7(x9f4}#y=N*>vwQf1#%&9}b;|?;Ipxf}<#<<|l!iL@&f`?z{Ck8lHOg z**GLjvupb;3=+ERiQYMv^jW7frmQ*MJa*XA(|wSN=bPoRjzn;+^|PWLoLe=+AIGsT z`=j8Eu4O`tjaj+3V#Q>ZVzKrulDwXPLhd=dh7gKlT_3qc4)qps%nTBW9dnmC?{Kj% zK%X1!7i{?&b^*_qJdM3rtGx9!4f%%;g%?kHRHW1h-{AMcG5Oqj(+h*UliL%n(&UTx zWtnsBe5F)KFj`l$^!9=^u9!Tx&z#D2u7OwZVYNenOoD1C*|3VGF=l@Po5+CVoR+cQ9EB8BIWXiNuI?KF0z@p1^Q#vaXk*8U;;rI!zbu`nr!?0U)4YQ z(Pn9>~t9?Dcg6zsk!XHf~Omo%j zn|tYSnAo=EEzY;x?97e&D%-ev0PNgC#tp(ng74iNG5yOgaI)_;GJ}`n6sZi zP2EUZwCrPGXdA-UQI*l&%KXR|#vU`Ennmmb$fVbW-z~4qN5@5q(`rK?A0r~B)#qR} zUQIoE`Ie#;_Gw&MR28Q-g@O;#rMm>)jqEo&)%{F1l!VD5Is>0eF)!o6*Z8PbqJb!L zL(ug}=+!Zuzboa5a(Zi^WrC>->1OPfbRrAEzphSy%-w|J6B%_;fxSNH+f;{B)t|(E z6vSE()EX7`(Oj-aa2&PZQh-t(y+0UR!NfI+ScP(-sCb7lsSK6*Sg!9-22`o9Ln`t? z0s>;4Ds_G9Y<`(qbL!V>8B>jbYmKSaI+~$CB~W5E=9nBOW^L`*A9nT#+$IWa66@Z_ zOUr9W!UH2xBanEzddmQOCxwtoc+%X=mjkNpzWeF9x%lJz>zF;uyP?spbEpkN>uJ~y zR<=8h6D5=rDA$pMZH6|hDwC_gsNT$F`M7*WlhuvTKV8F>+q6UrIP%ztgz0hlioLf1xRF_np`U)9^-HpCVF4zz5`GmRHA!hbB3w!=?SLk+UOaDEoQeD=xHTJ&Uai?@w8DY1Z8L<`rbfT^K?)S(3u5*r zIff4P4*D0B`+%&-aBK>Dt5iBroH%tzASrl*ZWkRc0QmuV)jhtEgkySCofKuHaHuvJ-a^nNnJ9s% z@M;kTwR45Ze4G6%{11DT?Brlyg9KSU6`L0d(v+#&FI$a2fEgXqXH#H< z0$@=#sI_SG8DYuebrS8a7H;&+do!<;kr^`SPl0r30V za_5AvSGW<*7dd{{8f(h`ruEsE2uG7Y{3OEOL})`+$7daU_)}1&w0~TaJS%8$@iB+1 z@%?67eXQtqzpQ^@_(GmhA6@m}>hzVaSh>q%VF|6|q?KICU#82^Jp(U?rRLE~z>b$h zD?wCNz?(c-9s;(y2aWYLDzzJ0*fy3#PSL)!%q2@ z#73q~m!@KD= zzi*4%)>0B_VzH7V+HX8!!hMnjj!efT%&7c=z;74O(H{9;F-=wr>fRF ztPFO%891woR4{@|prXHpasOOpBBCNMc+j=F@758x;*UEnD#In>V3M}yH$-YweJiYk zj8rr7SAZbG%`rz^YmB&`tC=vG=2{q{wNk@G&>d&4!1u(vOen_}Wcv)+K3-vZq}-g2 z+`Fk!?=d&?X2u+3=P}ZITBZRXUakefWvDvE3c;mKf?q80$KLL$EbEM^E6s~Da@fXJ zHIwuk`SQ}&I-Fr^LWE?H%;%1SnQVN?J6M#aR&EW`9H%%7Ljp;{0Ej%l+L3WVXnt#e zrw&xI2P8qdwrIZW8&88&pubJR?qS3skIZUu)4Ex0Pd%tqB{eeIq{jLOy+b%YtbBJ3 zs+*bB@z|$UE$X{wG`oA{8!z59u_NHw)TZPWk>lX^&|E;sT-e4^FM^S1$|Y+b#Z6 zp3DTj0`^W+Sks&prPd-5o5qs&`d7E?;ei}_Zt^V zX{-IA)y8ZjlwhbE(KiUkMfmGmw%kI1l3b$4)Zq3$3L>f{J90+OtZ6@kX+41&Fj$gf z4=97&0r)ywiq;=|v(}iGwZd8Ol7gvi@h79s^{v(ltq(4|P{w_)#@78$coi3jL)^?R zM}10EM76B&iu3cjgc=s^)g5w!d}Muc`oYst)-Dbyur=LYo+TMVf!?K>RV9pT97^~efasFx0M8U6JEjs0QRAPvIjYB~-t^qs*98PbTt#usSr zwmPk@U^laqGOH5x)f}bgXVay(1}%nej+oxTe4596!3RMI+$l>fw4#@WF1KF<;=ST% zQJPzKbqE2*b9)XXHLkAxMw!;v{1hwBBR@ZxQ7hBO^d&9@;UXWUD~nHHex8~Uz-CWd z_|k_FK-Dvl*>A(G2HRDy4;k-6V^LXU7v8=H0=7MI{oL%)e`CDc`=?G1VBT6Ed|SH0 z7R(u^ZLMvtZf7HxCQ9KUJ~9eNA?!5j z|iYxit8>AG<|MufAnet!a0&tC1cpuu^!~3*M01UlZ4hOVkOXNXncKwbr z7Xm_tO#V18$4+Bc&ofHup``&X?F%XCTyFjNM)#O(%)O4AOVzA?;jCx z_hkmsEt{EL=??Oc9)nLdT^S09o2I{6^V?6eL>NE$dG#~`G~I$~f_Bt|5E$~%Sc}#D zSxiYHXQi516vb6zChkrLqz#j4vv#9*ATOrHb)(b$s8hB2ekU%IV5;!Mn@AbVAOSIH zo3R`NVYYe}3-g7Dk1b!jyr%Je@_u%Ztqyw56y=9+)Sb~)5b~D}40y8ZN^HQ_Z8Cv{ zsg)hm_^0mVi6z|`;Y)8hAp)dBB+>@Wyw`S2W z3c+isOj@&W8ME782a1v}e>=ch{)^sf=LrD#8ie>28uW2)e&7ZO>a}cbEW2>tF@HuK zDH(_-HjSKwJvp}}UYlogEtWX+3g%*@C=&nUlDZFG>+B%sf zXObB@As*^1w*BDGT?7^Tex1DZoSIQUy<~}U$Q;MbTvso8Mas*nq&8v_s)!>0>CPJ7nWpdvhg~f|b~@OS#oXrh|qcrtqM@k;cu<=s*i-OS;aEcJ%Q$va2yB zdfZ#x8hbmSAl6(=;4@fmXJ^PX``PU`1G6ywm*;ZmQlrVCF5!NHpyggX28kFjg?;A| zWor$O<~la4awEPikzPi0sk##T5h-Yi`{-V#F#Kd2g@dO!S~@=-{ptS+GzR7m*#4UV z07&$V!z~xImUXoThVE%PxNP*sQxJ)Hj_1vv6v>8!^Kl_NHMkGPw00?pI#0*)Ie+%?4U3v`cV=O_Pg*KF*e^! z#ETdy8|@~Ak7gQp{Vr0%lJ|iOv3JF|^fI1q4ERwCe*}Yn0qAK>Q`!nlK$)SHGIP8E zW2VXw*N@o&Fg?r{=%b8Q(Nh%;s?DeX;m7~el>Yz0GY;1;Q-@6riw^Wc}#@<0A`DGBzERP zwKm(xlXB$R&XngZ%(||ZTQ@5G_)I%`T1YbgnMjp!70`@{UxkRWBry*AGqg!ENR^05 zCec)=z>Xl!IAIPX=I%1Ak&gPb$j3fZ^CY-0|`@d19_N3btY$ix8_1==u z$al&dx(A{_2Xxea+Wq!2Ctw4H~`GLt>$oETt94~CP?O-BCydI<8@ zMCzzsZx^O2EM#a?4Phu2C)k18JM3{H(xZkx#2Q(2at2y(5o?XORbB9Sd}v6Fd8I$$ zxSu9Y@v#yD_%!rMsx?X+f zrHGUR(VafAHT=Z3=KsLfmBS?fDr*x$Dk8E`7v5M-Vo{OC@{q~rjy$5m6!V8r5iTtA zApMGlW$%fKnXq^-IA&_iunw%Rtp zzW&i6_Yae|Lm$FUs*cYHn8j1%>S&}p8e{ehNah1A1#;hGFU6qvaf^jP&ze#7&NkcQMk2H)PxSP31jxzrwRr)r4NH3SA}L2 z;hF41oHf;qY5^cofj(5Mm?J$C3%uEuGfXjp3p%9P&DRaAxeheI@L|Fz?+Vjn*1YWP z=Y~`(BHJGoc?5B|7Lg7dJ&hHffyEgt@|uTdT^h5%^$J#79FXXsq!Ewn;aFZN+ddK> zX~}X2o-{8bYH%&4AB{tbL^>~)%2nN3Kq!az5Wpt*7J!z2V*F`79XS1WxDDMMDGUIT zYe6?#7{E&1(o}fxQH`?}lzG&N62au5%W5J#!P7^pfSU`~QaQPQgDprHJhKHIwx`Ne z`W;8WEIt*|`8B{gz zNfI4-%V=qSn3aZ!5>zeXx`1gQQ+~YJJ3cu*)SHaWOT=vR8Q0`N?#&;0(_9i*SjVl) z0cY$aB7kMzC#(*@{6VM6SdqhiBqbJ9;yx_XDPYC;tFavSsZ$XpVwG{abH>#z~!mdDji z4R#Ptd%hH--VR@JD9F%8$$1Lox7yPJ|35!5j&t!LlKKmmC^#7=`%CSY6RTX4FT-y^ zPLK=>gbufG%tbXidO`_CTX0|ZnrG~$Cx*Fm>@uO)D$@v+DB~~d+RK%2SAWJ@80*24 zb#$j(F{UKtO(vvEpsqI*B8zVk>2aL0rQ2Ue`Z~b6sHXXYf+~T~fw!lcTN`SbRM1!bg=5BZq z0=e-rb&JQmC|1J~$y%S#En-?x$BVqo_FJje!N`=5TcTKl&S;7~>4S)08ps=DcEFup z`E}3PqBH0EG@16S;6M7>?!caNDPvZld zZoJ-7NG}}+3XxZHSWvi#C*?b{!HT5kz`S_T0^{?Ioru+_ zO^A<6Ma0&2url}TR|3w|hWizxv8w77`-Y!q$dqtMA3^J>)m=4v&I^cSbf$~!Ks0C} zz%U>m_fB_p+x3u@+?ZFn3Wv%unAMCoS?eOG_EZvDKkyy=h-cB|oIBXyW*}mJsR|Xf z6iv1*z73vL#1(*|9@S(z2-jsa_WC-Z)s`gXk^NG@07Kk+aFt}tx&*aCCzSn72?JZz z&%J8BP+2M>G3SiOwMU+v5P>Ak^L2?hTyh=$id}Tji6%xl#aVClK~JU+TzHSm#M=?% z(<1u>)n--@e!NL}5xj3-g_dGWheHvQVy>P)4_6I>+!mr z>BATznjH*WQ|$hV1K}(Q=`Mqtb+(R${feuxES)F)5IBWTDMfO5KU ztY!_9VgB;vN{Kp&lHItykYEQh<(@GTJv*cSwF3R>#X?TmBeFyGB@Lu&8)Nmi zosi;@0LRfcnX`j}jLSj!cia617tEj{A&t;fsbprWuXucO9O@gK#ME6$^xciaZm9MO z5cMDIfSB`V2?-$9Q#mXwl7s;N5O{qY{yTQ#jSB)JixA{!R})>!5hc_wBe!=$7U!D? zN^oD#Xm&$_FF(A{W*_B`1-10U8@L}+1KmA@4|cYU5Z0pCJfb@u!Eybv5>B8wLZKRcxYDHmNHg#?>gj6WzpTNm=`y`O~#Z+U|h^0{S*SG%wYxptbX-v%(Q46#; zl3n`teukx|0USvP{4GC!2*m|UU2b6`b%yp2Mu=|Kng*mfp%ra;!J-kx?yM%vcVEdo zhI6K`$0idsMd7z!3MQ~`$=`brk35G*`p}Fix|*(wbFbIg4xere^%vWe`-jIoRjb@& z;tG-{v3T|D^FiQ!sx*AaJ$s!TofZn_oV`uD!5myfqw)k8CSr+e1-tqDL08Mi-%|KJ z$i+yTxCAc2a?EACs=>~#RlzEo?9SvNx-^A;4Fo6;42CDY*ZZHf-WoEy-YnbI9S$>cYl*fltsrR0)Esi9M+4!eJ)4Rt{+wbtOP?^W99+&0L1Qwv6_DMI;erY17fTCezn(Je5ialduss zLF-7I6WBjNzJ#GNl5md5CdcX#+cZsK+(o4^H4t_tRCW+>iJKQDoMg^9_zd5m(_*{k zDT_M?>?0+xrGK4>OqjrFrX5W4+|F|Gr&c(E)j{0}m8kxbzSooq9eC~S^)8sFy67wn zRa&le4l!LBe|6>Jd&s_yky9R8>eb*aZ_amAu_7(8+^GYKsdJBgT`{jxy9i16sRUqg zd;Vz>oNxD23?jf|2ke|kO`H^?Vbaf5o7&8Qwz*P)z`)-7Z0Go8UR~7$W&Cz_-@~&J zjX7yuu@~j~v6L(07B!)*?4l2cI!2M?awiZ;RsbGKMX6=yi$3XaVfLT4ZQgv&*;&ll6>QF53O{Yn^elE&!9{WS zdB_i=*4PDG2>ssLd>o-^2y!T?qKws0tfLfiS=cqK!oBL!*VSyC+EA9c&k`Wz`+|&1Key)}N5~Td%Y^YPWo^@aj!%>S_w48N#q->0*SS7fQ za2UmhK-VwTkRzX{f4~Y4>>;0!< zzXr`(y0q`N;J%(dEa3M-ptKi!C5J3*02@Eb6%MW2n-Livn(a*Vr5}HtZskmi*_Up; ze56ABdu+*vs`?56)lzPCg$=*ph%8zoR2~VTc!9VDj`_IvmApJ@u>FySr7=AE%I{K+ zcooGbB}yx$^ih_QC6|3~9!vs|RKuIQzt(EeAY#`Q#hupRv54d-R*hg7;Vt3_q zJ`bk~V1DP)93rclT61X@%}S@Q`_t61r5<|z8yfouDiQtD%v{+1A?c$hOb#AMPxmG`~cbxeuGcMU(UCJT64<6N+X1Yx;=~!{}08PE$^r^;?xy z3)yaIo|qz>I9S(sVnWBhvSN^jv(IK?3l&c^2x@HKwIpuTGtWoW`Uow61qC2UiuOmB zG<7396OeK{hH>E=I_0MW*JY&({HGJea8MPSCU@VJ<0XhdKjVo3JD=@c^IvO&zs*fC zMhus|?Fh*C2oC%TkQV%x4*T)gra58hVycuY8~!~xMdJqIzWwG`r39(| zzf~T7GnD0x51n;kSNX}D&hf3bz1lWJf+-^%;^OR%NeF^2Kaqg}{wBQ!9Tdu0IQYu~ z@ORSoKhD{_^7{VDhz*ZdTT~kd6t!W69|v#Ke#K1dz0lh}4Aan-xrD@|lxkUwD5s3= zv+0417-6gzndwq-{ffsOMK|9f4pb+uLK4c8L|-8(Ep6kU6-ekMv;_%%0M3Y%B`G)s zO3#W^fq-SH>qJf?(VpsU84Kt<@K8B*CmVd4#QQE5k%{Z)(F>MZqQRcAj>kR zMAH-+cRhC)Ab_wx7aXJUvGUl_@u<`AWD#4JwK^*xmQbnpXjH~Hl|kCjbj5Jx#*v1H zArjP!g744C^GmGNa&w~c4FUT67g=3u5wILt=hc2_DQxe*xiqipaG6DeC*7vqFrX;jHTA1K70uZI4^XPPW9+Uy*`c9m(L$}n1bBjp)eG^Ki{WrQTR=X2g%#~g>d}EcGV$Ykp3AH>VM(k6w42-W z*@3_+R&F;kgKN&empSvKZ|2~|^fvhqV9D}aslKItm%;GY#%`20BvQc_hvW3y?LX^i z9OYH4pw&8(3B8t~OIC~DOL0E0r4S^pKnk$STki8XkMEowE`zj>6GMC!fE`$|*(H*7 z>A>aU6JZc};5MtN1WH3D;u$@OESLib%+W-1fs)iLCdI?}h?;~-&Q;VrF1sLNxXA6@ z>yLcFJ)I*~u42o}2@9H{bXa$$Woc7Ry)~c|uiX^$xSlCi!*x0<=t0cs6RGyJ<(*E# zZ!iVY@O$t2tuW7zF@s3b65wCM9?#KzrdRsRrN~Kg9{f0lJYqVu)mZlMBCq& z+;r>sCUyG-s58r8m%#8RDiJiwQ|eLqh9=<`iz#1L`U>=i>!fDPo0K*cSQu6?y$LY& z`hGdJsUQ_iHxl=_b>!?|SJzx`JSf=N98F0-MA3!IQV4k}DS2av>enAs5jL>9-^|#; zK0|%rO53vR+#Vg~&3=(0eF}A}SGNk6AFM+35n!gC2}PAz5vP|VC5DLLUD&iq?Vnc3 zdbK&fN?GcTBI|z1V#91VeS45w(6{mH%^GCi^m#UR>YZ<%-~M_2?g)5d{N$kG70O?i z{htgjpWO$joh&Sjld36H-rffK$z;-BY(svH#MS{S%o_sd(roNZ3a{+U zbIjp#5VOVBIG?lfL;K(ef@S?aQuvEGmV*&m*Y&AxH7XQZ3u|E*0IBd~>?v#jeb-D~ z0gy&?AtY~!UKrBt&FC>Xx`ArMTooslu5yUG7EF~JuhL*x49DI@6%b&t(X98t0>l*W z)#p_~WLuX}!nz3l@}{! ze}OPL2OZ>wmOg-yb)e(-iL!~%gh@kS65BLro#J*1zd?vLI$a+;h$VHmmE8J|C+4Ce zJ2KFTCinFFM{z7-y-C8F*`*Kv3+ON=y7jwyyvTjV2m|>K*RQp+X^E}rtn$T)o7?6I z(G}40;A%KlOmv++`J(9ayfj2`EmGK6HCr?u%Qz3FjG45|%RBM9PW+CFRsLjHp@(J} z8+K4^!RTlS&w+~Xj1%gQ8a_k~gTHI~mY45OgW%10ep;B4R4X9UlD<iR`C4PN2bj0TTRx|C)J3}DX9y!b*IZ3i@@b9Bki5GZe&J_rI?&nsLZg4`a@`<&%p64KM=x!qCbp) zMh7rM_o6?4{97~dZW}|y-z2Z{w7~e({4-S$Cii@TTJ{Ferv~^J7|cJu|Fe$=82Lno z?tef=6$;QEIJfm5DE!sop9Sv+JP`nho$(2SrXYYl7F-l^0sxQ|%nZ^3bbZo%3$nO; zUIGPx+7fNbn-C?w;Tg}bS1m&85YST3i;v!f%eKwNJjSENCjn$m>hynC$prM#$?M&{ zZX6>pFe8o*?oxr&dOKKVZVq9+=(<*skflKc-Gj{EIZx`={lqG_Nz2P}R`tIkD9B+Q zH)p6@1F#EN?gk zMh#MiXiF4M#18rRNs}N+zKeN0dJCc}n1;p?4zqf7Qr?Ni?cx&WxQ>97piikgKBbQR z|0Olhcm0#&h)gvQIElrz68kCkbG4HwXE2j?0i@!m$e>ONM1Ljc3j~i8uqS^$a$SQ^ zPodF50qL9hJ(Ap5*^VJejvKagld-FA$4f92{ju4w1O!la)I$$Fj4GkRRBC=zeV+{B zly9WS#roovjz7?Cifp}K8coH>msT>)PL?MKpfUXHRXCrr|Hst&FT~1J-3I_g=Fh(g zb9a~}%j>^kpDfHIh%122AP$cuBAhX?`V5tWJ0Qi=qqF|?RBoaFAY_yQs zmntU7{eXd=A>6ASeK|Yn!dV08yJ$0l>p&mHR;H0Kkl^JR#k_;!NN# zGFDBn1I?{2FY6;LAVt;r7}tI5mU+gB;ooQOV9!Tb1pxq?H{iOQWS3a3F{(7m9U9mW zhWGaOeG%a@k(&XgbQW-ZRU#X z6jqknFXcE#L2)FSWNNY_G=LDLd8S}v0thCsHb|_#y@b$b1~uYN{&)bS-sjsv@) zS$F(hc>I5@JMj1jG(Lp{{Upw67sM|3d-UH*I=(g_-hjHKM7Wfm=P_|}T6YV4;Idls zgV-(*z+e&xK$kHDAYwCJ#Zn%tQ&+j!o%+<~y+CqHDZr2_UK;e2)|1!?pcg2dnm z69|ncRxmJqaOyfXV%!PFj!u!dZ0&w|`K^8B#`0AM5-R`as=K&a0^7aK`X9fRGA-Wd z#?WN7ntV^?^b;v``_Lb7?}+s$w3h9{ze!-NR8+)N&e;?#-qD3A%SX786R6f~VXZ|i zj3k-JzGF+09n$8AbxvYS6kA?qYM|==q_LiN-z@Lc2B4{2XrTL0_AbloNN8B7-loQqMfu*TkaN1uXPYIT z5H(^nC9id$FDK2W&6_~Cnj<|S5a7$Aap-+Cv8N^p-6 zCw~2Lp51pI=TNOG2f#tW63RaC8>OBhw`-E4FdQyHzj1YB&#q}#nOL3(2heeQq-4=N zEvc?6)y$FIl#+IROGAjfsey)N5ZGclhm`6@`BHl1gK)@>Fvq5d7qK@v#W(Rrh~u&kzUXIOT&=@-xZN)W?8VDN@JXaPLlr^- zu3YARH7+-UIyb@ztsa3swU{rzRHEzyHLbaNBfJ!_KFJ9j=&IdT=`5LYt^&r4H9oj)-A1^2s>lb zQ$S{^(jkP}tJVX^!meQ!RQ+Y#v|jV+9gfgMUsujKlVQ7FqeW5icL==O-Ebd;2@|eh z_!#22W+1&EY4=-Lz<3=)zlay=p!#Y3epI=WXquvo+lrHb7R}Y=Y4-__B@25}=*6ew zX)*UJu|e7Z#$*@rn8o{g#5d#E-8>M2nIr*!+c+D8RfohmJQMRc(NR@wDZV-9oewE5 zF0E~bn69BmZhCK=KRas?GOr>TZ6N}ao+fYscJAeY?ByfvP~RpX7jm(Yll%+6Djsx4`_n|D2?L z>T_T^NPxCNAdvXe8QBv+Oa%GADEkVis@{F|EWoXM8{`@;Y?Ad^I2of zMk=ik$laJIp^8ccJ)__2MZRlx2a&{{A5XfI%N^Qb1;D02-g6-D-zDhZS_bg1n-s7C zlKjBrS+FMtCQik#eC6BF+fEM3DO4Jt|+W|8TT&c2+nR6b62K_AE zA6z7N$z9sM**x1`KbKB6-!-ixM>!NvOEN8`*2| z=iLOzy8y%#7G*(w%Z%uhJK^**@OWVIfp1Ah2o=ks7Ui=kuATmT-%j`N1r-ey$yO4a z_lm*V8U&9F2;wKGw+c7z_&+9HSbAY_34D0#R;Vq>t#6Y4+2-y2fh_VgT>*3K^iUsO zz1YpHdwJ4dC_fDQKfrx~YErx;z%oU?rMsMYxR@C~f>u9*G>L~-#7^)@Aiym%r9<&U z%x2y(9)D7tu;tzZlECx6)v$#X9dxHhreBB&J#?Th_W;1O7XY^`22 zHQe{w9F0sZNQYxsIOq`|Y|zKg>3^x+|57pkLHoxoZ13}HR9dD~{kBml01$66wABxa z8q%x*#JA8OZ*zZ@PVGjvudPo)**q5sX0gi!f(Aa)u5264ou(1a>{_97PqE9Etchf9 zncLxhpQa>=B8QVMYS!pCrs@5B%KL&%+O)^qgAAKMStONVmL6fr;gg`^RvJ`j$i~J) zq#{om!lfSi;F?ChHU2+9rCtg<>{zaK;kh6J40HL(HBp zR^Q)i%7P{bJ=OKU^E!P3(Ge`kWFYz9#4NIv6o3pB^-O>g-|OzB0l+k|e*t8q_5 z75Xn)#$(4bx0xkc2A-iIM3`Dt5N)Za{%Ay0_IVkkY2Oh$M3Xf9==uE=dD%@MGg^SF zEgHb|!SndpkBkWbpv=^0N)jf8Ja$;*Njii!-WyyAJ>Ov`;}YPg{F%oZTW^tB?R>NE zZ{~;Zc~EpHRE=St_!LG-Efqzs$Da z7hA>pet)aw=`%ryFoW!Db!X4!8DnHfmd8(-QchciD3nNErkjTOH&Y?|W80!`=%H#yP%BR&*pVW!D^qQ&ZB; z12NIq0WeiDjv$2m5JJG=REp>m_(cbzd+ff=pG%n zJ;MNkePshhY#OI2whe6mg(e zF178W3hZ`GCz;wWnq5gCQW|cS<0PR2>jpM}7tK)V+gM-op%jPL0KJ1%nVF2$_=s@&`aoY2Q3OI6VrYg#f4ePu#E zv)eM##h7Id2-sD;BS9UoHRDBA^EXIq!ZlrdBDfO zAOL@6rw2gZTrqZ%OhoQUDbhlTiEC>Sx8tO$uKO8#pOq43MXvocX$;-a_kjOP`h?*9 zjHfXyxIvjckkG3%v)j#nVLTf_S847}P*2-JhFa}g z_f~*EzFIu1^T$Jy(++&;I;Llnv`V8m)1H-`mRtdHOJCxim_MWss;Ee_%~@6{R(jqO zcj5MScxa!~uYr?0c6SI-fa%MFA8Vh6%lQ2ysYP|ZTH}REY|ZX|w?}c7Xh*-yz94xP z&G}~CkEsIOXusOwQ3$D-5=M?o3z5mFFx;kP0q1x7aC6U9TZwqt6vROV}r(4Nvdk#Eikq?kj?KHJ2vz?GbV^&_3 z+T?!X3nw>5ujQsR#O0ZUFm3rI_%o!FH7FS%^QkDmp^69+@0CeIgB@E<0`%$C@kG$? z-slpQAhULm+3%VV*%^cb;Uon7Rc>+p!?DbIdlf>1M-AZc^Gv_*fj$nwuD~HMxC1Eq zB;(xPWFMypl@h)U;S%mA>)pwDLym68fNA}Ce~;Taib}9@ zOqaF_#lY{5Oj{Qb65oN6<-P;nrI$fGM!Gr!S052d+%ZaE;hj$(1ByHsg`F}U-jVIk zzwF+CCHDwJdWsgrYt8mtkvktr0T3z>>=g+1H$8^zN`Cu7gqwsv-wXcv`YQp!%TOGt ze_j4|pBuoWM?g6NfNV^A5tn@bfG4Uphd-=0uNh|JoO8KlcfpuY;?*7iz!v>hF%{iZMy31L)So*Za5@-vGiA314_>Y`*%@*}3P{4>i! z9m~m|kQx}~yFJ$%n5j(3FlN*Rj$s(ow*ZDANPiNf|IfOPKP9w8 zHX^WvSsTm%Y%M_hBKMX#7(y9CgbRVJU_e)SkSn7*+&uq<)?q}(SfGPrIiGxH7)5i> zNcbt|W0TuB870|Lx4%@lsWJp~&2+MC^b4}oj2?E@^_1vQN$PLCl2REgF7A$RRORp9 z&``l!)#tZ%5Z>4%m8qx+N~n3@$cE9>WOwD)yAC_@6DH!iWw}_ESE(UBz)g|ndJt@} zR}rR%gD0<3aM!{N7z_jlAd00kkpCE$0~N{kAKQ_m{I-A7zt#i%dt4602MQAK{I|oF z&f%s;j$M-iuFQ_1V?tOFsz0B1bU}t|fs#m;8G=cJFvh%VHd4<8ymbM_916w&KqauK zUb6o~k6+x$*q4D3%a{08s_*$keV@_AHSU#fzVVw2Q&>D$`1Pj95pKY|h2Kt&?4F5C zArOHTX=A)kqPc-HmF;tWeY$PmQ_B+|V$nxYC=Rv66d^Fb7{2%EHCOc4$R&cWJ$Ew| z$DONVd`nOzoot+1SGHN6lPaZe(C?&QHlP~RuqERJ&_^=%4fs8JOOd8sJmLN2E2F=v zY0XIUwyi3B=@eQ{Zym&3cDJSMqeUYDC$gKdQk(6>2N#H)YHvSsP)|rt=plpL@-2t||5#=aF9RDb`-@U|dI zRx<+X6@gHl!I8G@t$HkghnR);iPivGrE45CSB%|@Z8ZUc6+ zX>dU9+K@ON=jkaLGZKSuj7LjWzM?7>!hjjsuF9k|8`SdL)>4d;M9EQ4J>#chf#AG2 zzru?<=Uc}V)ZH^TjeOxh#+wW%Gtq)($D<_-}U#?DT7F+wMPT zA*dr|XJv9KUHrh+E8N4~s*D-SKJh7%hnX5-n;LTRwr_w~+AAfxSzCWHwFe$3RuI$a z2c3N}Q!SnoUunkCd0tL_me_84Y_QdWY~BO`(F+xr8*&Znucc4~xFv4?S! zUQRkaXWRp*sVhiWh${&aMo)T3=NuMQI#Yzi8d3?g*`!ohFmsTIEEW@M!F6D-mDsgT zfKJXXAMTwq#iy=8#cL!^%WcvpJ6}(|)UDoqTTlxrA>sa71g{Jno2EeE%Bo@FwS4|) z@L8m=SxUa;MJqEN@|hC4f!|`mSP-V}mt=I8b~JiX6@heGG&8!b&@Teryjt1GvMrCT zpD(nOG`ER-7aK|n8*&fD#$6Z_XYYJ;clsK%#>6gh z;4hI4SB?Cg_#&KV+YA6&6br@UU(BgK`F<0=X!#h+%|o-g^p?5j*uNRs#p(Uk=OZgD|*Y7yvC z_*xfbKDW6rTM7*>S8%_B3?i{F37}vkiImu?UkTf%bgKZa_(A#t(1g8F&&c$^EblzY zm0bS;qmOxJ)LIDd`OxJQf%C^awBnZ)s4-%ph+C#urqj3uFDdBsi8R$z_zqrl65`4v zHB&X-{W*3+fFtd18j*3d4GEaAAICyqRHgx7pf7Zw7Nq~Xu=_Xme+VFUA^nFN_AJtO zaB35A811M*`uTli#nl^KUaf!KN9@l_$>gk!BaA6?F*VM&COwu%jPR8!jWfYU!k_`< zOid);kq!`c(Kb{f9AcGs7x&XX$DDN%IsVclq^2OJb@EfvDk(WX{%r_GP2N_HG+Jmh z_0)O|fVmBVt^`5<&vNe1thl9vlLV#t>Iw%Klga*Q?*6=q#y@5fZ}vWe&7Otrc|n&i z9`AZKgZ=`ouzl)@7-5u2{#Q=RZgXOW&jlA;n3c0l{??8z{)J48B`*S>a*13k`NztY za+&Smk<9i!X$em-l9ex7Am9ZM@NbgtAJXjWAeBKk4FxP8SE(gS0Q$NHpr zUr~BT1@-dqb&`SU;6<^fRuDhsh_Nk&!*uGyOTWuT^~k+u)Q_=iNkWP$xM|Yjk3SA% ztLl{2`xYB6(LfX!X_CcE8Sc9n)fP@2SYa0U;#O9~7i&>pKIGSeD1+R zG@7Fn^qd($p*DkK=3cSGZ`X5-J-_p-c<{r35?pjU=o9`A6z53PFavFzrOq^DY(9}e z{QHO-=r*$ut%GN793oQ14hVvN;T5b&s3i0yjpmiX#O0H39GrWH$DPZmCr{(BRH(0<0Hhu_t*LGaTuX3} z38d>+Qb>73N}osqi54Dc4)zm5y$fC65-%L!D_l9Vei{jy6>7_dgx4kFcw^?tYYOyJ%8Z9*^$pujl`&#zFl`75U?j$nNDyYBA{$dPB!szm2pYLoPIkC%e-+CNJ3fkt#DJawR?0U}O zDZ))KmYxF6fy?(41z+ZrPqFY#9wb4FUhkMJB-%J2p3bcNs2tv}D}E!x7|*o&Six#4 z=B)-rAF6$t{17!qZ>TDRLVS0vc1y3EW|X=RQxQpp3Pnvg^ik9eAgL`-t_u>{`BJ*BE$D*0|Uc) zM0nwz0u4$c2NAEBuThrb9W&&lm&WKHetqu|JU5K{$FC zftIH5P4X8p?3MVu9HR;mLtBi)@fd+s8A%W5?)aLd91>?cIUUE>?H!rzU1&~CVs${4 z^Zce(Lc@E+7RKjMj^FFxeqe=RA;wZjRLCb!91C$5f0r8wLmv*EyR&X9!7WmXy!u*} zgd_hoCPG8)S%987@0e(Age1K*^-xba85K$Ud*Bxar9$!M8BB6 zZ7AOx6b^VmiCI)A0 zgZ^u)i(Bgl&e)QtqQJVJkSHgmX;dIil{&?4BVtl-^$OHXi4ZLk8!1TvFkJ-s<86NW z6P(+RQVBcLlS5yLj@=Vkrwo((m&9Sm*76(GbzGh9kmnII4}fIo zEHWzdgf55Yo$@&-h2G}1ChS39wM^Y>+UR>qiE*CuP)6cW6~TB5AVM9SoR|23gHg~U zr%czd+91hbxFl@B-N2~57dcuA`P%5@HOCo_aHF;lhKiHUz#dB~^~P7uPK{a5r|Pmp z_a3o`Ws28ESgdRlyesxTabauFQRMhELuSQ-17GPu+B@!a++|QF*T3-S1NmXqMNgn%kSz!nXKahBm(r(Oo~ec}m!0{SJ#%7G*V5 zPz{=Ye1d|QLHjI`23%y$iuhiZxt+Zs7%T#ekZkJTmD%n5Yv#GwS8hN+3S8QDPto54 z$Ro-C?XC#*tBSM4UuKHMvI`KV2FNsfzoA3`&Q zws%U$E@2N)4IRIF+pjIJBzy{lOZ4`IdijSYlMU&vu#xZM zlT-+x{q*Sk4xmif=7!1eSWeu1$=pFRHFl#JFIa_#q$y*$&_K_?*|4#1gh{>*V|fqc|{>vVv5@i#uVcHo~5N!f&Cb#O-=YC7M@8*^U~!!CS1_i<>b{RSN;=@uWZx+=sN zr?KZhSP?#k)xay}*igh|N1WageT(<_UGn&iwH%0XiZMeI2(@jd;8SW$Wv7WuE*mc(C zwx#hU%JU1qBtYom5;SF!;EgsA#B$A489N`W3M16v+H?zu(DWd;b>UI8BgTqyt+gtkRD0V~bzAfA+`|a+#tDD#-9AiXOe^qlE|4udK>eJf*BpjRHEtCEM)cbUUzM}W>B+XmJ36+O#o9=x% z>ntx!+qGVR1B9-oCfXRa%2e)8v5}O*D=QZw;*hae-Md`#hM1QXIoF*g9o_j9p zLg7sIlmhb^HGP?_7TdkNHR(s%A4!|e&5b_fDw6T{p!k4NEm}H*#^zs+M2(IACDpk8 z?j8jO(7$vcthfdF*MlUTW%lM@R}itm@?H*<_B{u;2{@8LXkAir4yXRmd-c;=Q=~K+ zF+&q^=*0k28ib09v$0T})P`|5h^*uMDhwLd|6~pz9ipsAQ8I{cAJin4e-9Tn;{VR# zWEj-%?{QptUj~StE?t2N<$HyWE6GOc)YLp@M^wc`P~Y_CSg#7FbmPkmIc|?!HW)*m z0LRUFc<{DapH?rS9-?H6Qr1;{=N*B&w+_8~UyP4WtU+q2DW_{foS-W>)Q@FY;J6X~ zR)Kf3>tzL$$X+N&oP|uLZrXz~M#Kw~R9yH+_4yS=N&G>nd5OtJHskbAFlEF$Xu(T(|F#V@L+GOfuVt zx0%>$xsV4y+jt8EuDon1Z6T$va%kXgXp?#FC(RlsU1Lo5I)kwAMLse6iKlJ)h@!2Q zT*S1$+b@K6Oc$`1VJ3@C*7TNKPj-IJCdzCKsnnoH?wUgi#yWU?FD}31peiSC_l}?) z7sYE_m%Fi5emqnkO_MhVs+1n>#G$R0#m8udSPZ}XVxZuiXQ!ZY+H+IBc$dm3UU);G z$7NfaHMczTy9RPw{349VK48&Tc;Xc+W$GoPTkN|JCHdYu#p|9JJp36xUUr=+BzNQE zbsMsgv>Ef}gu`bJKAmiKJivO$wv@&3AedWetiv|sDZ47dzUHO|!#j=x-?x)(kMOHa z#a{ZAfbHc&q%ob%>G$4)t+B9lHVgaTzRpFKS-mY|xT~iz zJ;FZ`<~l9-#K;g0dPxb4O!T z$gn9n8}&x1)!QjaU{u%3?MEz5NkUN$t-#24LyVBNP-l&B1S);pK5esYM(eA|T^~RV zBj>5$+){09??nVvYzkIToQ)!7mLhYodvuc38+V%95lO~q_vwnI?_q!gHuaKRcIgxSxkW^_g$i-bVV9D0OYm& zmuu!FTw39>jtgl!2+Qk>IE-rmxDX1G&GWmG`DrMKpt!bZwi`I#DpTnY8b5A|zEiPB;j z81%2Vt99pzqCO2^BRmS;z`n_bE`b#xl*y`3A0pRNHrYfQ4I1>`&)yH3pmuue?s5)*V;EvT^ z162*E0RUt#h9=7JFC<_9US&6(c=q&N5$Tjmd*$SJ#0)7WdIOYU)+kniQmpK$lf9BZ zcr*g*-k9eQf2OCF2)NRmYz^c5P!(MhAdn*Hz*f)j(Gc^l@lqPiOx{B{=w%qRo(<9& zykUR0o=iXg%loT7{kF>LFF34~p8jO}!U{(7~bn(nq_#j;4m|7a@ZBYNEX{- zs=>5!`q?4b_1=ipo<1vHPfp}s(c3YTZr`wFn*L+SDGEodf&sg|f;2rI>sq<*9$5=! zU%%0lQNzY)SMp&|rwlw}ZtO=EW{0`+=F~Q#u{J0}!EB#n(Mh@1KZ>eoBS$zV$61%! zqGV~+97YZS0g3%ij`TMO^1|EPsH(WcKcC$@wsjVjsR|YK{>HUww`QmyEYw>;8rN+X zPW+Dk(PkZ=t~BE1$^7fEi%`y26K_0qxlhV^4)Fb1C)K@=IveBN3_IR4l9b8BGCe@_ znA0sdfh)Pk6R4CLQoA?4YsKb%AZa?_vclhmgM|!v)Ba5$MrE46>5TfTq_O);tnZ@M z#={E4RIFWNLFULPs80)0-)?zh4|jfcY&~V`@XX@SH;DO>Ghf{wBX?s-^AoIteOQ2aix|4sr%Y*UhV5Wenry9Z-nEzkwiTXs^K~2wsnF<&ZOKFN53W z+9uoJBQK#G=hVgxSf7t6#?*f70ia(4x;U*+)UxRT6lMUB^33+E6N1Oy3&KbE;a&LH z&gA%$ejR*M22Z%hAL`0iH*~r)B8yVxJzAVRiBqsz3!px1;hcmeID1cA!rC#Q!nGmC z_#NF?FFtHfxlYm)4+Pv{voF}@i?RaEvAf&nwhv%sfnL}XtXT0pzLLCrs@-Mxse;f{ z*|SBZCxyX^2X_Che@%GV=R28n{`E~P*c1o32Sw$bhc4~S(uL0W1^H`cJkz9M0G1!i zqC?Y~8AGhX3N$a|B1E3dcKg^3wyFm`{NcWtF?-7%Yh#f5S`mI|YWw@BVGay0&d*Qu z5$JmgusH7`J+D{!)Yzc1mPkxUb~b{U#^oU#h6#+`&5o(h6Mc(nu~+qdf{Wc*`1Dx{ zosM4Lcptdb140MMmX7(YH*-6M0Wi^1^(fHU7KrKVogt#_0mz8+3SPGjBJ5iRr`+M6QdcXI^g1Iq=oh-Eg<)`cp!Ea5=BauDJ|Z1cl5KOTkZ%FoF#) zo-;olt|ac{_)2>*t;^?!YDHqX6nbRmbT8wHfiU;+tj_($o0sry+!~iD88YQX+7MIB zXAi>zQPI3saVp5%?V;5BWeAEKBO(>!XW^fR+xA}{!lFC2 z*L>MHa64Bq-k)PMd>UKTu=@5odZ0fKN`Dy?GDc?tMQFHm6AQWLRC$$D5qF}N=8*v^YE!!P5Z=c!K z0wyhWb{dd~@huW{C`u#7(^V|OrFBAZV5^Jmvq+4Gq zGIL>l`g)86LHu`A2%C6ewlg5|95Ql>I$;?N%e;6Q?A!b$pL}zBCsgm-1gEISToBFB z6L?*8z);4g_Q2ZDXPFNnM0fDfU+~6M=F|3&znzbWQRCo_m8|NS8<-8Rt2S;!Lb6gn zL|q*p!t9+4!6n;JVSA$a?P6XN_HFou1=$qUR9{c}75?3xvzdbqks-~A0Aiw78?Y?( zM{MfxnCQspqo^%<_NQ%2yxBRSGU-9l7y$AZ000?~Y#EIIRe<~52};C&!R=LRq?Ky-y5I`;p6bTC&thz(frlgm=* zrURg*ef{2ZWztR>@IMjCG)VDy)_yQEVjT zCDk*W8A!DVi^30<35>JNPxX|4AwPUbTXIv4&g3Mr>1Jc!JUIc--RjXE5a>VXI0QE{ z0GL;Rw4d|<5ZDbwmLc~R0`d$1LjZus9%cX{JIZk=aM<1#vOw+v^g0e2QbzfrD=V&p z4QVT7A0+_LFPU=RK7`o6F3V#U}3OM zFNUuoz=Wsw#4T1HowApy_ubU-EV_Uh^7=L=ctCIh!r9)d4Pp;I-)`k!cD2r(a^4Lf_COoRFPDYCYl;L=S8X;7`&OJ~S3{ts&P7o0yp{nt5B>a}Ny7%2@|t4^Qp zYB~kd$84Q>y}32Fo$FX{EQVEZE*(H2pV1`3vXhjrG3$CA;hO3>QjUPg`!Lq!zzrd0 zRiJelC?R5-EK$*(l;3@|TWo8<=}l@QZLcawDM5PtoT+X>9~nJ^PW1I+@Q9SU-3!wn zo$m}r9czf6#|5~nzf_n#7cZ|Oj{m$CRl}jt^gtj`T#g#LJ&f?6fUY6d;vBjZ9%`?b zTOwlqE_JtU*;X;#*{hVf!pG_ZZBu9i!o32iS6oYbL0II@;!D&!_8$_^I8pJU}E2E}NC_!_GQ_^+=`6IinSx%nB|V}kMhQisVMV$F;@d*k+Jz8b5d zKCYa@#X@YxN@>L2MZ(Z}@`>loht9$GPV99ArM4OVLxZd#EBi9UPM7tVDcxJ$Hrcdovku1wOs|>lL!1vIQQ4ct4uz$`bV!;8( zrd94mhTr)78Ga8r1{?@;Y54Ncd8JorOv%u}!$G#Xo^VBsi(S)PvDhMKKIW(0WS(ir zfD|=zBC%AX9pXT19AxHcnI5W=a>Rv9$OEIBelprGg}s7=Nb;^BpWAdD2xd7GFkDP< ztx&3z=%RaW5kXiBP68RTd6D94DF?5OWC&->R3z-jbq-CP&`lSHh<_@a2{X^3Kj^S$ z$S+bUbg=Hk_E_a#wV}Wu_(I9rSVL@VS&J;|lkzCqDyMV+yUY0eOF{02jEkKOc7mTB z^T8Xrkghf+K{1{9J{`&MLGB;?ChsJwcgxi$s})CG98V>6dQj6Dl8*mK#j%V)LVBlBl?ecNeQq zeYp3tU}+{qxAjP@3Cly%YS-;vEcA8y8{U@?a#^@FSnDAjkZkSW6%Vo-a=?AMaBdj2 z)xufL&Z9om=87&8Gpl&Kjl7K#xCH=^Id~VvFy`=Wm;hbu`-rwr0d7+C%|VO2b@959 zE+i>+Xr73N5i$ zz)Icvrn`H0(`c9vk;HO7(w23ru{}j$hSJXKU{NQJy4zSgp0k=bE;1jU_LQEZw1}5y zh&|LPBMO&NQx+Xp-j{I5_)yTu@`%AckE^l7AgIjoaWC5|%PnU&#vAdgwTJ*0N=cOd zX*$t$ZQUzE}EOYzUy&EYv~2ykL2DTV#vK4XZ5naarYtQU+Se8 zzFzJa63J=2WH7`HBhh+kUnmdll=y6M3Lv^^Y$KdfVp)v{PLCI$i=q>p1djA`E46O` z2Z3M{^a{+s{eNhJ{wh5FF?_2=6gl}z;-Pkym^rAE4l5b^|E`PBvLUn^c#tfu$TO{P ze8WGg8Lz_bU+W5IETcaX@2j3+;>aPnxTab_A#WnBkmiG+wsbTzFCa9~GeW7?$>9^t z>wFRfeP$laII9pZ5M?VQTLD3RSr;D5Xg8iS+PK+Q}S==Tu30NH@L!w;oyZ_!c% zBp^m&YKRO93f|sq2qGaaBUd0hfPUC=e}!-`Ub!JhI0^?tFdB@$rgi%WGCd*dc1B9B zv#zFtSk?Nz9O9=LI;H#!4(%l!LsS~d!;evCYi`PK##cM#@wLM3#Vu9Z3%ywNDMyZ; zo={O`&CD%0xU^@@*tr3lZ^rv)&PSO9^F!Iz){6XvQXXGbG1a`@7Xj6<` z$fatLq8|3;p2tTl32nr!6=zhWb*R^AJ0c#I-U@R=#VcL52{9sco-7gu&~xeo6ZVkk zCG*`U=x=?EyIIskXRPfuIjcyBR%FMQZ2c=_&TyqQw`z{_86qcXBb%CK1~M==)^74t z5Y$ArNt+h*qcx||$?2!!<~gx81=j?}^yi6vr1%aTMS1v9LM@{wQpM8M>l-Ko&(@qB!Zi6SsKK7=kgc`JfyRpP$i(2DRtDXTyPfZFQyV zB^MRXhCz?_JH{!)xDuk(EK^Tgfyi^@>8nqk>}(eb9mF%|bFR!=phxUXM22QyahG4i zK5%lcxv{FUpmM2}(fiR6QN0?$>|jg#V=Uw0*?Rr{Jsj^fYOw}t zAJ4oDec>M)e)v9WGy>B1!>I&s&=MDKI)5fa*1cAH#Alm0t1)9b^m}YLyMK7u>m7@+ zIafsF9=c;AW^75i?WxeFnT)gtn$(Iy{QBeEcWhRAv64yEu@Z?_7#;bnR(k!n8Dz#N z;;APsm!O$8O-w%I#6am`eq15iXWw^D*)sMW!XnX_men;#O5WkAw1RYJA%p6Sb%sPj z_*bVEtTMTul5}$!7+BHPuYBmVY1MA{54xsBk@D$gEl28%(5IvXvJyR9`v}qNC+j|~ z68VSibv_qhhS zY_CaByWd1 z$eldS)EzKRz1Q?|yomo1vh@-FvJHHg^2`z`Oi+$J(<31{UWBSzw$L1hF(YUY z9LN@@<=bjePilCM+9gp>l&aCoJ75vDB|(eH3IMENWdwJSVF>FSC!hEuh+52Lq=f~4zMp@l^3=>OV(X2F{;Q^ z+?^hf=B;4T?4^M|=LW?!kKEgDH0jZfdw<3wEHUV!av}SrMK&{FyOjJ6zz2u=RVnE~{r9CywCy)UwJ^OY&@Q3`ejEKJj)ZAqFcwoa?GwfLW|rc zL{w|$5H_OWRTaBJF`^-;Vg2xV4}baPuZ;|WYA_{Y{@Qwg#o+&XAcoX{H=$~F0Mc_& z6oAtVfIQ)*32nNWWpZcf4fCTwMoa^M+qMQgU;`X?7kWJ@r^bS44Vo~+L)01$aR|+M zyT+`J5)0~tp1mwe-Op!qvk63-P5jQ$ndWM4q#XhbCm&*#ru`23bz;= zo?!k$n>N!WbMQ6nEOoy4oQ*;ktKdp%5)+d_sCj6nG1iSOJ)Si6Ccbkfo ztmOdrskMMmG=fUZUMC`|JWup`(}_r8AT_r zaJ`4Z$%o3EyJ%5|&+)`Ano%-+g@?8G5_Kx?GI#XfufTQ+F5+$Ry0&zbe%XTJNOniO za5qE80Q?}<`%0`&`73HGRe`nH56l-gDGj`$xT-Na^ZSB@y}ev1I2S5ir3h2dD1LqpRkoNIVI05{ZT*L_KNYDJV%C8ejskY zD&EIQLIHxnOGSKvyCuls?$0vx4~WEvDMjxpDaI#%(9*1ZVNuq3!q+UuO7|#gv)KCO zdNTI|-tH0gL@A>>8Fr?$9pS@+OQD3Wz}=JOfVjs3-v_<8$(6~j)A_p~XkzqsW=YST zh#CT531Jm)67Z!Wcas7lPEs1508T87(ew$hXFfipYpU(hFSOrz&edi;JFk`ud!}fi zk>#)Kjwjv5>1+8yw`9*~DxkqQLHKP(>2O{5V0>Y)xPh99y{p1!si?4kUeM&ENM}1@ z{5kOdXB|U9KlxQIyNH4qN(m@|^oQRw1IIS^tz=3lq5$B>1Mw+53!`WhQdWSjCIJT^ z^m4Z=M}uR};9$svm{=g8Nq8(S8FJwncWO*@Fe053*W(pzR=&q(8E1gbWG9TuOh5?l zjr%OSy@YUhyrfPYx^MGl%3;CWfTo7{z8U~Qq`#Nz7DHx&^VgNWPX3px-yU zae-zz_o79*h^9}up{wT&RoJW_ZCpIV>pxJT`OI;aOG|1^D=;dqyqp$t*&XD1+($|v ziEa3EHu>w9zRDBRMNxVKc8mCIclH!Jf_~TtM(T%$5|a99MprR4Vd&IxpAZjGuk=2# z86S{9YK1=>8hLt)v66@unkbKzOWj#s1vmBsfDK6Ylivql(O9AEQsKW01404BS^vU? zTZ%jwj)>C&KynccwC;f_8nlECXQHp??F}t1jauOVG>XSwd63QMn zf#YWi2b}Js(rWhrVJZNCb#QBRBEN^rk<1KU<*2F0jIW9jqGWyZo2sA0GO1%%VnChU zm@UzzJ9N+UW#AyEt+0^hvcB`6xH+O&DcZJn0qaU1vHh}9^mRzDA)ZZ@Zz&Ptw7tgj zyPKqn)dp_TN@i*fdM23FA-M@&J|8&=)v=DoW_SSv3Xmt*oq4kV|7i4nS?*uN|16^5 z=XbHcE+97m-9yaW^6k+nin%i89zEg+Y1sYw6mSg zaQ;&&q=4DsTlhJCtr>krv-RP`_cL5Ar^J{l8;?f?&x4zkvc-vB0}yNwWjzGU&A&EC zXap}RPNe>L@9j9{FJR!JgWCWp<$Ihcs@pj#0P7st?-`s6{5EO!k2sJ!%Wvo#=h$)V z1y%S8`QZR^YYzZnZvZ!biL$5qRIQ^~dS$QQJTCa@%+7z~9Z5UMSwX^ewIsqR?BYA^ zytI9be}w8eb^cXrnaVKc6TIB{Tu3ELmh8HZmYj^EM3#f!{y@=q((<~H*uST$Z^9ur` zAn`MsBmu8)Vg6d=3hK1jLdO9ontv0&*Q7JQu|0V}@{yjMSe>L!l$}WSCdZ7oUQZ#d z1oq^Nd8>+|PVYD3KUnp5{21E_0#5|%#UJXKyj zOoOF;+v9Cc4G*h-_K5MD-NU8XN>BN<-DbLAmm^G18=eD)Z9_B6>5AoZK+p{24h}cF zJN_g0zkSh(n!qTY0FZNo#2{Kht~%`rL~AkN$I{7F01Z4Q1dX`|>N`#wkg*cA{I$*! z2Rf9Fhww*6gGq;|Md6#fyXto#H!r^CusE2&#ZzXo8WP8(J!Qdh<2P)`G?=PsW-Nf< zV1e6v&ImjRfXdvc|MLyfVocFUjOy%C;_-~_mzC!`!`-3Psok9Oj5LjM#9H8@=cjt3 zM+1!0%AO~ql)|e*%bDh+z(mk!P-dB~KQ)pQV;iAl*1}`BGG8Mj6E^X90KyK2!j`b) zH@N{b9uI1g8BBrLOmrhny+$_mC4^UiOND12e+$I{@O9J_+3~)81|lhC=&9pgYiCyv_nFq8o1|M9WTbbkoX7)5o($iW)ll`oAyjdT*eq_h4#?m1e zD>n~Rk$+?m5%|8VfAG#?&=Vt_X})f5g^+(L>D`a17<`r}Q%I~W+muAJX_x*o#(A_L z6YTYuWzr6O>N*1F2XIQMx~Ce(h6>^O-&JY}X!xZZ;t0pH#n75kDHcxZbx84tMXouYK( zwLl-Pzf1fYN+qP}nwr$(CdA4oi zp6@0z$=o|hC*40*(n+V@TD3ZF)dP-Axz3@L4*GzW}$LmWh4hKXrYO7b{5=G_JLsc(b8 zzNkK7Trv~9pqZuN0^>2^2v`%9B-}V4>I9R(PFXZJSlLNLngXOndU?cR$9qO7LKKC= zfMAHB3*t?t{nJ&&tF>voN1#C#2>dS0lY~qefMTkwVFpItzq47P<9Om~zrObzbOO5! zZ;TnT%K#t|P??Uq{QRc%)ljLv=UPpheud=A)bw4Q76KgzVGuztV!H4de~R8RX)Hs* zt1`f_ZDpi5Kv}3)FfojeM=#d9lD0>>hHoqc#vWT5&KU;3E~VMOg3w;sIG&s3uk** zj8OvUVkN`z%A)lkRr!NThga()hjdEKi@#2v6{+CT*eX-ledt))Hu_M?LK2%#CVI^! zWreyF)8ELVY?JJlpYvIY?MZ z08T*vfQ}_&{z!+)mV5>vsZN>;jRWu*?*!DCD)nhxq|PXOa^sGAG!WNfaUaByZycXh z@5q6^PRvs8sgEzU`9(CVUTwh2jzluHdW!Wc56ItZJWy+T@;YEO)VH9Hr=$Hx@jqLc z1uf9tLClMgPQbwo4D5!Q2Wl5R&Cv4{sS7PZv7*<>3~3x~%|UiTF6R2taA2}pX*)eH zYVcAx?3WT9<*gWICb9v;g8eA!Qi47ir8u|h;ge?A&CXkh1m?yzc@h=pG$2aF#mX--DO0A>H3SAct{7xeXG=vYh2xljs-+s;57rws^&#}{zpc9rwlb-DE~ZnMWrY=N5>~`D|A6y-ujfu zJL#|)rpv0OL{lU_3<}$;d}M?c`Rv0%_RJ)mX6@k_Aw({pN9+CPqL^5U`gq zE5=!vhr5J;eaalPOk$G1A5d4zX!O6%sNnCTUbKF`&)hK(+l7KgJP~R2S63jaIT^lK zaZebQ&In{pNqSI}BHWH%`@%T(W+F(~h}kgIY>nYVS|?(*Mpo_bW(>^rs1C#v4h+)_ z6cOn--CizX+8>p?R7;k+8AHb7`@_O}K5cOlClxaLVCiorgn*6^&q2^BXg()hL;~M! zMSsQ5?8W3ZBza-fRcOpD=4goC_{ZT-Zx+7t^BI{t>i3a2G(offSv`hij}LB&MXhri zF;ZmR02uu4Q;niE!JS5fqER77i;eP7mdN@dMqD-wTBh-vbfrs8IrTY+Q;ykmQ8ke0V<=*7KR`*QB&j5(o<7Dk=zRV6#^3wA{VKmaDzpG>U#oUY zjUo*Vg|5W=aTR1L_6f_kv^C!JeR(CkcA2Wf3IBkj5??phbEhjnsbe7SGF>tr%;;bF zTj_P##|Fw%=hfn-c+SKYm=GX=G#pz*`LzA&-u?(+h<_$nxbmhim|rK#ZWp8`t3kK~ z+(DyrS>{80y^QOZ?Clq-^)zfAEYJ!SiJ!lLTBj_N@K8uSCXqefa@j=3*LDj35MJis zQm{ZUDv97rS_>+n>Xx2B6eCgqDsI<0ZsJ|9zhB_S;g@4cdlKK&b4~kkz?#fJ z!KkBjV5)9y{?+l_Pa89iMFMn7*8gf}2aaz=(hP0+W$XIFReimK$P9=G1pP9PMyzo> zfsb-c=}VX9bg>ah+I!YQU$SXE@<0E!S?q%XXS?e@rsfm>MTUGU^A%!t&4z{<@kw|v zKMeWo^ax_kpQK?Caq=S#6~m@civE*H1>u_ZY8z##xD_+zsjme-V&PQQYujU;Yv@Gh z|NQ6urL*%N6%d#`_h_fVXP^Z={?3U#4JITn$K-MXR^+YOz!#Zc?g!hF2NEg-P|voC z$$d3d=S~VWYgO>D;hmlF!WSk*_KzUe`u2~1piKTWIW(EeU;5uE3>X^faJqbW( zMItDaD-8*!QiCfTKeO5daM)a*Vw?f2hk1vIe)8lp@)d9nb9@2D;FWJY>Ul;%SW6^~ zFbqT;g8xA$1<;L?uTDnWT`;nO)B0o^$2#FBNbkQok&;>|<0;3YVO)QnS{KJj)X{De zL*uSp%%-17olE_CcD`yn1mqlougPMZLGrV+rIRY^2$A<{&41>Q>we7|o3Y=+q_X%_ z@kx%6o7?47q;Loqt6GcUQ3I6atzku9M;euIbN#K<4ofc_+X*IB@2M-FjYicRXU${Y z!PPLt=MCVdo?bJSJKRr5hW~gZ_oc(ZZ39pXA2cHxc7H=SC{=FT>ZO`kGeU|Slvclglkg`cJ{$S z#;Y3>V_`~NlaU6|t(er-PjEe9`SOBnXYlN7_4zQubQJtbYN%2Wk+6g2vA4?4QTAFj z1Tz|Zr{JNhZCAN*q{&yC>3w=G!gjQoA5OaDVMvBbVlS+wXL%M+fjRIGJu!VA!!tv0 zs(E~b2;g68)4&hK?CK-h1}f+#-jBveVy))e{^wP@5u*eBc5XUg<96r06VkFpN+lzC z5+?}JBq$d*t!o>Ni+yR;jQ0RGi*Z=sYP99*mUM z>kOy|T%J>lYvRFXy{KxWcWnrw#tq;Z_X&!!b0&Nax&WEt1-jzKI*#uXKc7&q3?dh# zcixyY6xtbZ_#aw#IV`j0=i1W0PFR#@k3MLi22(VcZ`**%0hNMPMtixUCEohvQqnls zX3OhnAViRnO-*onHxYpB*x*e9=|sG#6cx41M(h{Ubun&*ugTsQD@{w zvU{|R2;9Nezf?L8C``89B8X8%X+(TS>QxkWd?2c}Dji9~Td7O@VEg@cbT#ybh{v8~ zJ4$G(n@4hGS;^t75&Oz0s3jhxBF!I4ZFwk%SilvX-UU2`xVz;z;g#m2rfLyAR)InbAed?o+bc%E5YTJk_ z%?~M)Xc$}w{zw-V%a`1)Z6)JSSgqC_2{EqTI|B`3Tn0inXJTE0r7gg{njK4mFPfA$+4CY}Etw}@x%XlFNe@x9fScXI< zYI1zS7`|8!V(n4q&>qb+ast;D|C&eON{}ZR+mmamdnTzTI$YbGmW1-_!K&z>u|+GT1Q7`Tnouu|dO1nwdr8Rr+;}VS* z+a!tinak9-yYVjmo=`W?Ij8fi(vwC4fr4yUSLpYTSd{5+T8zt>uO0h2o$| z+n)%!`5E9KNyvvpv|B-_b*HSaN!)^`u(YsvMu8t^05gSh%dHg}+o=Xx;+`wFip+g?=w3_US}I*&%payL#RQ%0NH6 zI$f?VqbdS^Wmfv4GTvUT&n(w5Rrn}rgqs6A7~tNU2vC$67)1FQIRkc|0Wdst4%jXT z7(hET0l0z}Ih)9E&mP?+r3K;sfU$G z^q$mN+sg({=sC}2zs4rOE)Uc1l_{bGb)0NR=g)-30A7{glnvxe>b?niP67p3P&!r~ zk21AW#m?uj!5M0f-vcn1*UGu~(OCJoDFdFCc9gpbtP%f{ydoA+^Ijg@EDH1289z9d zKBA{W4!@Dsv?@8aEfxs%s;v}=lA6wCgp4E2*J2|TX8$(CnGY|4J1BYJN+**Y-0SFh zL(eYXDBz)gak9F+TOh%`gXYZI`$hwMhxQE~^}FUp-{jS=a4G?rZgqYZa%&?HRcs%> zX!WDuvH$=i7LrtPZ*c-TD_(Fc{g9;P*lTE_u9ePC+eWcee3w;pYS)Cuy(CwqnYPU} zBM6ldZ<`tLM0J*Zdql*dSV=0E6is~A+8 z34>&hs0tv~;crxM$7L&1yrWNdxPd2Al%{=62D9a<4Gob=EwI&G=Z3d|@$QK;rUH3n zcubJBZDmeM$vuXiF-656X4~7jipo^o8JUrh_Ec1s)SeP!J^$LJ{vn7|+_%L>_AQ*K zB%RW~M=5l5B`-1R?NL?6K#@kgI!7htEA;2wOM0R3d}464_Z-95#^-_#gngkzy~cG6 zvU5a8%M2oBWzQ%q>_u>`9RDKJqkCI4adcX`i!$_lC& zL$>(=&8Y$Td*flEqD0T2BeONiDl8rd4Lg6f|&BYAM3qmxyd{lzdJIkc;%BmRKKzjmp=nN zZK~L`24>NLQarx@W81npgI_2~UKwx#veqC;Yk*&`ao*zv0Nd+iwiG%)x-}LLk6oVu zK5+%e1I%OulV@yn^)c5_ZF2s%O4yo}zN7p@N@zO>xpnda)x>fKBb z{u#c%fR{i)YfZkyw4}7L^6J)o$l|1?ibWycLdz4#Ls~8ON#l~BYt%m5U)@7y-$u^6 z{>$>w8C_sqwFwqLqAbdi3u*F1oMTi;^KX&0^J(}8S`>7)*+PkY&=q+NG~cF z(rxtQhbV#8u&4haDk8^6Z6Amy4q=(5VY*Z-T=ur}l( zofsZ(I~y;4>zYLW?N3ssg8mn0W%F<}Ak|I3vlhH7dub#w)E^-pE-XDA)~^paCRn(M!VF59EF8lO&FDc9%wjdeQ}-1w{84rF-aglPGSm4*rAmY zfwmp?{!xj&X3&>I!;r$1HLD0OwuWR|n7M7#cZ66|M^d#>HPtHVR~_e-a|C`n0pBSR zRq43@2<)-;V0XDNX`bPxgK;qdL?@`OAti2zX^>zOX)gu0`lTSOGkVey?C-%7BcT{B zwyG*4z%AMmLAK{4<=v!u#%n`2Yx30v+@#B}#EMLBTuNU9=kolUsOpmKtL=wh^|^86 z(+W;DQhhOfMYNtWP4NBTM!(NgE%QzV>c1H_vk%sUesas)RD9id5(pqy@d?F zr<2Uj(=l)k{4_@jH^twp!cTi7ZqFTcvtP&acix$Qh?jN~bn;W&K_sE-a^E(zE`i@h zTUNY7GLAP7uM0YGb6ZOro4pYytZBgyF~NGTr5b%b?YM%C>|{UmYK|Z3`!Q5kah2Bo z9Qc-;C#arfS-%MH886W8Ih88TLcczf48YR*ql!!>A+?rCIxeW}UVsT*@c38ojiUw9 zGaB;CHZWOT@cA4VIKn518ai}tfZb2mf!mPE{MM<#xx zS5?a5%k`u_sfeAyIdaJsN|bYG^lp>9_Wf&6{Ci?L2Nz<{CJHlJZYuKA2CFpg_7e=VOhRQyP_P@eI6?^A?}s*?a&#cgjJ_8P z_3fuFp8eJlvC9LRG5x7_P1-@Z@`~jmjW>dwTc`dU8t*s&Ewt}AU^w^)D^%_s@?Y)O zeJAm9>P`mzj{s`D#9*p4z+M(6F={5B)>Y1e8bvO|^7yudtN+po+x?{^(anKuL{cH! z?fDKTBHN6j7`rNtiG1(3fJ-Ykc zhis;t@RYWeiJj=88D}hM4f6Ez#|*K(XYYP%PsjAiJV2cc!#&in#f58o7T_B#FVb}`}*d!bb( zKv_X=>Cc*~vWjZgs9M_onj_8JB=&H+!YHiM5b&0t5Fw|no^xyciv`U6BZ0e7Y}Y}Oo2TS3h1+z*YQ_8_LFMP2ZlessYu{bUVNZdbtJ{YYKW01YwD9t^yC*i zlL-ERme}b2M^wRT@I6$-@xE*f5=bp1a%X6T>I=l08^7EXJ8H$;G!O4L7kdIR`HTOH zznzM#ql!OM85R!i<8LH^627ggmv}{MuB^mv?`ZTO!KjH$hTRW!i8PVCpo|km zp!}BV^d8h32Ia*H(=j_AF?4QCg8`?w7nXk;?^alp!C-A1$gR3`K%3w}EX`h+?2eyq z9@lWExwgcI??=_Oep1W_?uZO0xf`%SC%IN(!17RkC;06abp^C~H*ES{vtcAP2)9Ax zTEym-Ok+nnWw-C3Fz^^^|3;9itg8N0Msh^&sg*dVpEfyoi9+@ANY=y8*s&hN7Q%OMSv$Y$RaCC%QZcAC+Dn0jmkP6pX)VbB#Ln;sH|^ z9b`%4OH=|*z>M?5T!ZR<^6pfo_*&b@F0o?%+KV#p3~uE#FXOhvszUu?nLyEmjtke1 zc&D$dM+_g#`@cPkuxu(S%1Q@f9O$BmI^Co{%M6I20LZCCYyJK6!XYcZNWWPIoczh- zH|CJoQy!xa_Pj4J z3l|En^;ZuyzSEG2P^~vc+r(+NN{1W98wRzSAPb|3tIf`}*R& zU|Rwk7{IS?A*Vz)97NMZ{Kc-Y0#D#d>hL(OF{)w&bdtv*{6S{M@=ROuD829h)?YS1 zkR)AZ{D9u8vMMU@?DOxS9NtY=+w?%<&jVS#hy!;ThzOiYGjaE6F4mOjU2+L5k?j@x zqlzrTYlWCrP(2AVdo_lX7RVdgB?lmK^1_?zZFpo=hI8C=d@)J4Qlw5h zEbazpyQH3=vajR!(Wpj?FN3u0UV5oU+Hyq({B#ZT4tBM0%DV~c!tVS6|2edPCQ#`> z(BLR`dx2-l&38}RpA2*D-J5jI;`ITar-}#R!8$oVJp}ol|6%(;?Hk_pR1OaHT1U?f zr7C#`(0Yx(ES%;CF@eEUu_6-q=QVhP6>aU`5YPm+`x0i(TP~CC)MACS-bI##9#1p^ zH#NzR`-p4{d6$aCO649FLQw{vdI)wbRYBdFmKgi_39IdBV#VM7qQ}>S>}`oiFrfvRxBiA4>6f$Uv zcau^W-k;Z&ls?Lc3FRtH=8oDt9O&&J^u1T=-DgHgH4}Iyy$_!_OSInJ&~Rk3q@dS%yJ)Zc9CEL2ZzZhQ0u>GD)ZkBD5uKVpnu zqK$f*abPtF)K$d{r95GmZD*2!(|Kj-Jl1FOSaJ!vyMJ2x;S4y`1BuXg;pErsg>xuy zG@w#{EynNcSiHc3k)IX@Few1aScA8H)Gcx>)Vat>=l@E4+O6dBjS}F+j^ll9Q+Qj2 z6nbt0esyKcF5jUj1LeNo?wfPXv4$cVIgsrxqCY-(oN!a+>DQ7T3fj(&t5c)4%_3z^ zk7gaSbxtXm;D-DY8sz{Q@U&Gae(0lV+2?nXt?E*$JSCQBCDr{<7HJOZ|V)mlMW-V|NFI@3?k7*X+X1H?}U_xOZA;DhRyp4Nsg^7iiuU_cH)I+q0c=?0GXR=csf(J&TB zX=nRDDYHe;6uwS-o?YF<8qe3lV;EWCc?ZC-=vAX42;sI@AVXPSI{@rV!!l>3cVjOAM80UG%^GqRH z_I>5$u4TJ(ocJC_d+Kk^!{Sb6!v+EPV|j0)9Sa7(*nqXP6UfbCI=+4cFma(zv?%%q zjt4;FKvVNon?BO-p|x+qRq`*w8ehW2yVpubVBOkg~ zoh>y`DN)&r>ul4ZxsWw`;;iy^>&b!UU5>G#CpX=h_+IiHqqs{3PTf`<_<#_OM!8Z4 zE1_brcSFevo-HU34ig%y1XpAYoBaLIG@K3c>R|3sv<${WD#NW`1y0{VeBiQ^JC;*T z;6YCabmbIx>lG@0W_la&% z9LVafV?AdYk;ouYrZ>?TT9%N!SQu$hF%Y#AqECBNLU((7N-in24^N*JRVV0&W(Ji^ zWv1UY0YiS?M66R7XJ`rVH(X8L+1|2|3V!pW4^HI^OfZNKYqZ$cz( zroc4F;K$=qYcFWzI2ow@aa4mV;)56eMpl*I_%9 z`+=)%xF23^bzr#6Ho+M|GQV`^PWTO7@eo{*>Ada^dQ4sHY|i9(Zu3Q|vuZ6I3Wr(k znJ4E*<@auYgmCbxAmNO+hnLOPClKS$F2VKs2ZNWnqkNE&Vh$(2>+D>iNvRs76BKQ? z!Atz_E$Cxkh4vqj^>L&x9UBT_o5*4EUL4aQJb+`E68NBiEuLBJ7Jp9M{ePY5?!l|H zevs~7-{!0m?6Dln@bAUyYlpMu1xkP`WRd2yu^BqIdEZpvA@_xHvbc;PK$oFn#y7!D zqb5K>s&o_6BAhyQP`Wgis*`ny0w^KfhFj=(I`>z)4ookjV~O(cBSCae=*@VEx@BWb z!Dz0yn#sBr3Pt2%D%ZWQX;Ju6yMCfdxOdJtV+Zxrj{RytDRs^IEv1zordo$%Z8Sf$ z7Gh4GLR69}3YgXI$F{d!@IilY;($9Mm&E>$bsXPjBEeV^l z9v7E7&KlGPI2R=yMiX=d$e2n@{l4^qqhT4TYoiI^>uAs#Nf)}OuK}f4nw6d*~GnK-OTo z;>+Gvc5Y~lu9g0#QJGt35!81bBfuA>k)U~z9S@Ewq0O0TJ0UqU@?) zG++DNW=`(*JB;O9*^ZS@(<-YsnkdgWhmTyjFIL1VrR=~FIBURuM4rA6>7xK)=O697 z{zy{Z`aHe0Nb})~&coK?=Hnz)`E;Zn(EAlidI`0aKGWbQirh2lRSoy{Frc=I)g8$Z zZ!)?EbohLXRSVtCGh9_gNp@(HA_mowmusKp{SFL1&hk$4Q~vSLmjW9-Jfyvgsg+PD%*)Z=*w|LI$3q6my(f|tY7Y-xuQ)kC;QYNAr6i1T>2Jkf|MO*6CynXJpTj>P%0*k z0h(LrFvOBJRVW>zw%R_q<`XsOUEMhOnZh1H+?BUzY|> zY2WP5wNPA;I;g64NzBuqTXEkZ;TV`+)!wctbc09#J6*h3@}md!=)xlOH>iv8T+}e& zzsM|aR(5@@w2_D4c!-t2saibaOPXgc&WJh0$QPYwl^k5QNTLv!iR?qs<#bUmpFcQ{ z0N^DMvh->Lq0L?0)bTw2N;q#U){4O*J?91R05rTS{(y*qPN3^6(0H{)_{SR5)E51sk730UrJd_8TxfgSepnxYF+)S&caSi>+p($7P8;B?==e)uouazzNYTZ z)h^@6j<~)A!Zky^ET%^SMa+eME}dk>OLQ$8Xh9PEQ#iSOQ|S)}jX|+QdsY4?L$-We zEJ^w%n8QSkBcgM->P8L**kO%TzS$nF^)Y>xTwJJFkRh%RBQ zUcW~^3&kLXdjXH@>$-oXl{V`a?Q4=0sGvrX61|IoD>I3I#5AVcQ-4abXNeqQA=AVG z;>gytn1xeC`+>oI)F2A6SeUSlR`?X2&;qmLJIHZ!aiS2`$8_1&c|NFkV@re;xh4-9`h*`QoOOU2m

OHot~Wn9A8vWx}8xZp(}addB8`OZX=B~guYo9w8H zQFA8=S+P`meiXaYAlE;CMCd3GKo(!rPgjZ&o;Dt&BULAaBP?nw*sqXs#df&x;w2&l zB)C8~E5eLs-ApyAF1DrUwU1Sn%WnBNbrqeigh{F;FDx(74o>SsyhA8{ z^V>NmS6CN;V&^K-E)Qv0@<3$xwVh+O8>?eIN9H-D!@2{DLs<}l_d_nJ@;Su>jq2|n z6vF2^{MFpyERshvjlNO+`!!WkYysW}`pyRlYupwbLya`?7J8O~jx3fwb638-W1mXt zt_0jmY=PS_7Gm@vr*D{7 zf2TXQi@iA{wbUdb!U%EGn+QG0NkmBr;E&gQE!_xP8Z4?VxCM5(C|xpG&50F5&>#%+ z;GxibSm%~){c5vHpJgUK(F$a@vHu_Q1M;aV6wmWxmczFNqMLJgIudw_H3u_w*nDjfIiaN3 zrvtqHSK2l>q5G=V&y`dASD;o8T0>Fdg{Sx63X>k}(*^MTu7Hh8UCS!anJAfi;=COh z*v9QUzKJ$g@8Pri+YWqQ3ly(5XL9tDT=wd2a#A+yHdC5YKc|8vQKGP+_2?CY1y5|( z(up0s9qYTDgfKUgvcDdQZ7uaV_$m`PT`!a~C;<6dmunpc*vNS*Z{DoP{79}@x)Hf2fgW)zA+71) zx8PcJj_||f{~)WPzbHWMH&|U6Hvp5&ffM5riwbRiidp__`qf`k`K%Tc&~0GJx+rm| zy4Jeji(pPvue~2 zPu;D7dqe)d&URD8w}7kuufJ@fmOwRMs(DhGWEN`RZ*L&(uqM&y*Z5EmfDETi+neH- z3^d!-J_n0I6j;leSV8&OuP_CXd^=DEpzi0Y$==3l?3dHCSsrA8#gL_|`oRV;e?!;@$f*MT@w=S3{Fp4qHBzj#Vm|G*f#1Dm zUX4}hle-x16LtlEX&=ScAgC>j+A-^cUs{m#5*2{fgOiqFp({CV*KLu-+JF})raM=^ zVzDtqboGLM?bD%cKn$(*a0#^A5|v9|cYB(MaFBKP6vZ<=We0crWBGXDO3O?O+qYr3lMen;RtAVGs@>sMb1Z9sYu!17fVeyK5E}TBvDP{G`iLGRJwRk z8PhK@%sc+^MBuCPjw8H9OLwH-hdyJvB6nq(WrS}<0P=1Ncd!&zr8g_2%V^=)uAszolVDr|iAwif8&69HMw0OH_ zEUdhi4w#zP58AIAjw|l{0*O05@sq5#z@E4jTSfv zk5;LH@qtSRZFn1lB>TG6Uyoc*A4sm_xSgZ>J~3T`gOKgqXBN11h#9R*@SlSsg#K;%bE z6hFA547_mL)Svt=3i}dot#TzGV;R6AN&mqsQ>ACeFSY6m#oNAm9>u2O>?J4FpyH%Y zZ6__FDbu+!`W~17mlGB`K~HKd3|ykTI3U(PwKD)=ilkhMS}9OL75q~QVhznzXdJ0I z9yw2zZ5r@7rhJgjszy!hPqoUBPIX-0C*pLt$yyvfak*58D2V={uc)7jJ-Xyf1X2Go z3~a5qLfmgG#h&fej=+N^f(UVxX{>%i>V8j_P?P46QiKu9Si66^?yV*;63}?6g2vrR zoZH-w=VldI$ZGd{hb}2<24P=*io(qLK(wD7KFn3S37Sx)`?S>a!Dz!9Bx`Es@bOppTk|)Q7NnqP;f@9dri5 zdR6fq_2_TaI)_W@)SMrTP{UCXP_rb|!2a`xF~1-50yO3|itjyO{*_89^7rSrlC=}< zu!`)Z$jCe+`dn0Rp8%Sr5$ES}0Nf)%A%2c=zts-2D93vt1pU2k1E9F{MERK=7XLyl z*o!e?DKVk?);CU7qDiJ=>NoLil3S+G|{-t1DU^(Q6aY{#1S5b@&XuKHa2PfftzlF9(l5KsBsBmhAz zmd?b7JXLMf{3RqApQsm>!(Hf7U5WDf!ph+hw9{{o-6+a7#_s|4H9&O@_^S3uB56qU z&jw%Xe7Ah=QY+hNc#|@)H)mLV7j%Psz`t*NU8EYtsZ8r2)uP=n2brqB zflJVo$_-Q$7F^oBoa=)Kp=ORBA%{c`3=+27q??vA5b-;aUtl_4ZNwGQY^GG9?lnS- zloAb|sWLhgIcbJYgOW2m_Tswqa@E5 zD-hZyK;2#OIZLeBW>|;}6pR+qHJb%Lk4fL598S*f;8v+sZI<ly z)_idf?ngoXeCYZ?i9|>{+$^OQm7j}cU-O57X1w`yo*d+ByfoQ)8y%Rm(nA5`*>|~h zGhO#2h%^!n!YaOOB!xO~!5|?JZ_aoyKH_StQP@8c90Jpmo!>3(@=w6Hu6bv$wq`yTzwTm$ZxV(7Vpsy=|cgN}+wGBr~m@{}w zznI)J&ukGw>Rhn5pcZ$~fcRoPVID;voK+_j5^Q`RV7e;J?R4u~5bm z*NDTLL`h`Q!BGP01kR1n2C06q5YeptzW@#4GKw!+>8}p>0zNVG>Jbi#D27bXg5Gtlj2qu8J5561Qn!XFVl~cJ5exCR+oCxLI((a^#2h$Z@Mku_hG*?7Wn zbML(gyk=T+CgxuKe5(P7mEZULUlmF zQqTSOy*@cWj>w}E2$*5G)XwWfAvo-6n*k0w+{>47rIuL|ulEL@3e2+|Np4oh%s8CAkAH-i{ zG1^#a=H^eZq5%Nc#NLu4WHOp-b?o;$MYh_pd0wPet{3i61sJ>cL}zd!q#I&_iRx0E zKNMpl@D3YpI8fdtNvpHS+~$pFd|%G~&(iVBmyDShF}XT})M^376oE zpR5vN;c+Zqjs62!(MfSYQZ*a)DIaAqo%}6W&L${0imNxNnWJG&E;=gq#i|wCN@Ca! zhs&L&mM&u{_lCC+5)U1N3Lbc5A!M^sa_>As_`b+@d2?O-B4Ldq!q$qrRd&M@sYhL; zRFo)9AR#n5%sJZcv*Nb#x@z|3e#Q3jKtgw}c3icDK^mlav2e^kqWH<9a8Ix{81%{Z zT=2aD4ee3?}-dlD4=(GEruKitmty6pLeR_Q^anBD` z2et%xBRN&bEuy;<$RY6bK7Ngc!f{=vwdl!b#NM~uLUl`}jn3zPm4y(scwU`8F>C2Y zoVNcmm?`nRY{b%Xi{H-1Q7JFo3!7V;Eg19YJZFQH)4??1JpF0*F&F3%sK8>sHFUi< zjrIGF#T!|iUp`j9C1jie^&ZPtXiT+mnk2${tD~L+gcpE+7F*y>}+@K3AKz)72spPLX^+;`38gBt; zMTHG12|TzbG*?CbAj4Qj+F&i|o49!FxcDDDi~88A`=?4}%S1O+>8ueFS+Wm-yr{V- zuH&)kQZCr#&Hy3l><`^y?`GP)R&i?gzOxoj`=$@CPPfw50M!&E6X?$?zp2*2-8IjA zosYEw+@DI%5T*#g2?s&$wxF*6Eoa%=-e`8H)SFE~G zpnjle(H1%4c5<93qIMr5XJquBQdFz}+hkp|!yUg!8rfq%{vhjKwaW%7n#R)}e-@JU z_}bn*w9>4+N|)qe5at*IZ&dQ2-ax_;g3i^v{(!$65f132!^=52ezK+Ovo6TKOELU3)F?ot&EX7}q?8DImvJ-o;jboKZcj87%ai=L=O~CnX+~%rjR7I#5sU`v%NyA-S8% zuQX34#$QC0{V+{!%Nl>t7mjGEAMxogDiJt;P;uYV2CEegd+Zs)^sm*&us@1|+(GsA z_LjCFkJ3iff|Uare;C;_ph@J=y>y?)U`^&~X-13x@N4(l?o9}W27Yd}=AoP5OjnVP z9$BoGXJGx#?9^e3*k#L%CrRY^w6GYgZ4@!>S8Qj{yP<-bc4Nk%Ko0&+^Z87a32C))if}WX~3rM9bjrJ5=ZYgT&ukQq} zfnd|F4cp~S{CR1@zjD_Ctw_+4G@;6AP~@ek-bW{lH@#_MGnMily)k(st$3xv{JIYK zGe^8kotDFu*$@dD-7FYVRPtVv3qr+dBF?+=e$93Nk-{J;ZV%$~F8y-VQL+$`9ku#$ zOt;URX>i1HG`g%m9YiHO3l$lS*Gz-`{THv-w(GuIpF`M{HjU&S@B`ohOTqlyA;eGh z;$=GbuFGm@U#DsDIz zuv1|^?VV>Ty!%$I*GDjtsOzjbI{zsBnfiQQ%+{kTr_basMz&9DzPrORyxt); zlV?P*cb9hSu88>XD)g+BMJK3wmsGB$nh!u#D+rF@W z5OoJQ$QvQ6<#YBAmBY_)1D1gvWUV4__&H-clA?bPm^=gTd#l}2=T(LUVyap%Av4W; zn8i4S`|%&82rEI$GH&O;7&55<%skS-ejXDw=P4laO7L3HEQf6S@6KAp9L{vsl|StU zkgj2WK&)WXrMy(+L94ST?o?7D7mN+}H>T@~Ot#fi)9^F38_%!EjH`%S+S!cprufpf z;Thg$XM>h;m7|W$g7RZr!rXah5B~D~7|=~4*AlJxidHn&+Q8lxuJ=fB2mg?=>Y*7! zW{PJ!R~?wE7>SQZB^HxgPdN4tL40y#=3psSxExmL%8g&h%3BY={(10aZC8*p7+U1+ zL>zcHDfi&0bv`&OC=L>4|BK>*DPFu`H}LP`WUump5|39w5=kn$bp_7#jdeZ@nB6=w zJ~BTWHVF~N;{0HkO&OMgWSp1V_~dB4?ayIwbk&5NWCti1s9rT;C0{q&M8&Q}iJAOK zEIOcOo39*E41~3a8(|6TeMf(T{L?p~l-3=`jmb3Yp{gyLh8TQ#X?8Hyt>WVyT*ayo z^hoZNE6=ib&jpCEOV`;*?ovDtU7zF#fdZH%*6A>8q(6%)@50YqFC~zQ_;ry@MX#R+ z@49{Zvm!@(5$MjVR?=E?zkKb8R)Nf~q>NjiMavGw>@ZHzUSe9vt=rCxksAC7G)^7X zsadH}V8x5F9BHW9FS$rl>3NF#gzjOSUx&-*?tcjZ4cTJw7XmS#m|8g!U8J3`5TD_@ z%^c^aCf9>#n1@rfA@Yl%XW*nuU0NgBZ5q0uaHzhWKldsEJjbmno(hqH6JVwDeB66y z*4{hKNpOV#>m5Dd!pqE^JviMaqMO-b*leE8+#h>I_G(X(+S-Ie>&hW9EG#$_S%Z6P zLdV@a(?3^o_WlJ@EoWHtdT1-|zG0Oly7jO}f4KMwju(CmD(ec;ki5b;33IURKo}1! z(j>nt6V@*3C&@A&wA`A(`rK4h)KbRqZm!f^kq<%zQUjBC=4=<6WS^iS^aeD zk^6=6A&F|cs{E9aVl&5LtJY-&n{LCLFvMjDBJiA2yn?k6+QFygl;F)~4hhJdf9s}+ z-W1Ad{rPGY_6`&3%~3Ni61F<21rm;EweSWwNI`3gTX!yfHX(Cxcm)6bRqDh*;o0>p zvt|~!b0{8Xh1JtA)FWvV^RvxnsX|c@gRs(hlo@yJw*hVX@${)B?Z=-vTY{TBlu{_& zb8CP>U4qjmUeoN$A@j8r=|K#Vl$Vtowk;&|@{Q+WtXd6Y?*m(O{Qw&|*#lybf>Dxg zmsuOKDXV=;55*-Bux z-}xZJm))N;K>^0ne;vQ(lg2U)!>Ta7yPn!i;vmb3?ir8UFWQd<|!E(a+~NLZqJX@802 zN0R$)Ss{>ou-&F zOKl*5UOD$-;CW>WHUv^xOYT)I=~U0!gJ*YdT7-o16{x&iexa*I4$Yf6h_q&6h~#7+ zbjb!qQgI9C^u@uPOj~-20&>R>*#~@hJV6(~8PnK7`eq892Wly6>B%i9Gj|?GTI69S zLzb+Q#h18i*kF6`U0zg_u=w;@0ybHS{)_9Up5Nnhv4L zr)Ui0Lw4it)ykU=42D3tJ(W1GF0+xXt#zEpVo6^?z&dZRoJX%U5Ws>;SHAQv<>4u` z9&Q8p2BPe)j~kqf`qY>>8`n5MO!b#ob!@=mwn3})8)G7Qbun)bMT7PFp0t)s`csfLG`imgwJ@^~p+@|G5h^r4AMIQ6vm zrlwPspp;VS$XzRn?lNxQa)ccT@QBd##QqAuEv#52EKv5?3|9pqtxXeS)zZcF_EQjkKhAh{a6a*W4or+TWwmNIQmeh~LZA>FwL z(}Nt;Os@Td@c8jf0FBF~UFH2DDc+mc!_EoC%iLtH|2{LER93vu(dBKxo|O=Qyu$M0 zpK2fpl_g5P(J&?^nSQ0%V81zmY4yVdbgr>XmQ3 zZC^Dp>8L{<4kTLU#);z_0tCt4ZZK=_u3L-Ox4febloe?;_DEBz=?r=+(j#fGbv@yA zCt}^0(^W7*zpmOXLSNrbCY{_ zESY)!$P%5BZZ!3O2qC(NUAU1&7j`DwRu`!zyr^HL%bYg*B`F%7B4s~{Klc_kkWbh= zT+ZVKd*J!=bHlml!Z4gq2#y~Q>ka*lL+aOR3*sUzCyF7$)a|sP@uJfibr-q zH6o<+H=^n3fx`!q33R7O@{uxjpe4@ANIF(b3F; z9!iYv$08nNS=!+L)KzGsbyyB z>EPq2$IK?du|TIk#R~A!)?T^4X=Kf~278S;wlO1TzoZ&8MjLgMyHpLJ>r8^Q=-5>`Z*LHXKD1}uIE zf+*eEFvnn1vYrxTzyX^jf1*B7k%c_*Dc<54R{p z-C(5H0%jR%+;AXgh?PMdhpn3T*;@8u02b7s6g2ZMrIzU({(_YN3%!q!HxXpXT~L4; zA1+sc2?dhq%m|RW*yho?Jwoy6L-osGW*y~8_^>1CqYFD5j(dw!B~e+EB8YI6%aUWO zEe9q}s^Ah9#>RkaWM3g`k;@K#m{w18*WE3czRmtD<^n&1B*NGe^?r|k)UcD05Znb> zk<2c`kO}NH);iM3oKupC8Z`=m()7ulxwY(v1bGfoGgy7oCnd=<*h2Y6%H_A-rAyCy zNT_wi3|I;@7N)~c7t?%><-!mBmOgx-M*i^0HethMd3>n}tM{gWrppQbqO@P^yP*NM z-H|6HAR`rgjr8n$mxnExhMh9v})*>loiNGnGty-*kdz`=G zpz2c4sKo?AHTf4S1t+}AMie2CxaEHOo5S=ZJZ(<1-415|@a)569D%g@I*t;5!AE>b zc%-^{4qm+I3&O=qKrO4(p&gAQQ-*{T{bE=8F6y9ZT|Je`sm+rUs{F`Q^G|QjS;a=E zUe|=oscDB2i*US!Bqa%Knn`jzV5T zmfox@p5Ce(0#~v@Uidl2Cw4`mfSw2n3OTPMWRUOaecVbkN%VEXf2LARZr-MMj+uac z&?zgQuI=@TyK2-|&I2|Ow8)#l%D&ogHo1O4K?_U8eNszbNbX%}LB`b8c`wj4rQqs9 zi-UHH*G@%GGLvoS}%c8g!f{{4kSnUnom33e(mV`NI^0NK!- z3A>Wx#k)Uz&LrWc@DRtUVDF!naMD8%(VZCy;sAJz2QD7%6~MC*?;{`)ovyQ9p(Q_=6Kh zzcmwh>ue(D!iE!Cp!3;0yWWPe##!e;%-oy7{8Emj}m5ZM>UT@i-3t<+9-k zG5<-xx@UNp-~RVExy$D0U;VRGDB0zoRF5~(I+0U}kYJKJbhuO;wN7*ha!j!U^-2Z$bR#dSIN-&};G>mWQ!E(c$D9B5@JhK2-&pmZf)uHleHKCTg@F^&d z>9Z1qITS)FV)gPv#@6T0yU4I!-H%|R3h+DCX#R28rDlDJZF+P2w_nV|unEUsw^9T| ze-RIh9p5%R!r+~;QKO1Ic-CLA}4mdYRWas9&t5-W1nKKcL`SjL?yIB5J3l4gH+6SmlmS|v(SuE`EG-4{l zCqXmk|0BOLo@>FCqoh4NIqJ&HMa7^DQV1VC+DB~A#KFpF$*`Mt-)W#u7E|zV9tug_vBn&r z&%uwdxnGb-I${KzFD2}?E_sj(ObF94I9e_kAtneEW0sewx>Z<^`Hw~kY%;BaKNfVU z`t#)F^b>(QE@xoZ96HuN-RP0M`DozEk#mO&-iE*f3iT@ z#6_c^RE}P6_*hh<(4^3333ewQi4yzG)rHffzkBpP)D}^_*DE1M>mPLEEKD&jnzB$A z5+l~EEY%mU@kE4N^w2*wC^JqW-cGtZ#ye~DryCDJUCL$YInNfevZHBs{k%Y-&eK19 z$zWRMp|RyHn2UkzYLKF2@$PXHckVf{t2<&;10E zvaH3u5!Bar)0*asX)+XyeVvDeYGCIna2j;Q6MR9`U}Jqla@gD1V9+!Dvlq3(_O}(d zDSN4UjqeODcIkGzjDLjuM9C@sRiS-bT%|Bjp5X(g- zt_2lfQ!2s1rdHVYGhkjw#ZftRwAD;pog^@hu9Nl9zpHh%rcM|6vb_8d`6sQ&<~Oc_ z_C*g_NwGenVB+E*CWD(LT6S>uS~qQ84ucAl^S`Tl)>j@%kP$iD3=C@1^*9!9?%0r# zkz`|~Np<`zfFW^R8vZxH4ih}+>r1y(=hFt?IbzydQqUVff~6(3Q|haZkLH}a zB30v8$1Iw)15R9@7C79Nn>QTE;U7BTucudp)*5VKrB{q?Nr-hl(E1z6A1v44xhk`l zYVK~$z;=sXvLA7PLs_hT<)FyO{C)xw!-rQ0^(_fw;s6|JmtX2c;c%qUXzv#MqaDrQ zl!Uzd2{E>dltjToz}&OiF~i2r^!6)iHZD{2mpZ3PmN7hZBpYUM*WkvkwY{VM?^~8j z%Yqa0>v;B<>Ix*YCuUZ|jd*BbgHPC;?qrMeBmxzW!3adw9YtRd0G>yN&1{-_*K1l| zT$sr5sSNcnt?deD5Vn7(6j5E4i=2q7vRY0m&!K1O!mp{K4xq>?r%}2{Z4`ITEq>fP z7V!QlW3l+(_ojECD1(rO?ov*1%`Fko_8~CZ8mB-XXA@174qUM$`J3AWW3>4|s)m8B} z3f4~Lak^H4=#iqB&O2%MvtgxiOm_ZN_Wmm-)7F#?Iv%&{141o}-KDtTW>1?4MG|kJgtI zNxv@U2o8gc|BP4PSzf5wR;B#lY=y!HLogbqsCAsEq+XqlWY-J1eTPXWK~vKZUgK*} zK!aIpKW2hF@fJ4>Wa686%RY>6r07Q09lNHl3t^-bn~R@2$dvM>MDtny@Olv=D`=1v z{)eL&j>gzqdVMoFa9IR9C+uZMLQULx&H5@ea$M zb1*DVj0WcA?2OItHQpTW4t?y4OBx2tao7C$-fd;d$&s=t4Ur1vs;e(FwB40Ek`tO6 z(}T1d0Ask)A?)<0!W1?B9${s7J2rGY9RAs4P>F2=q+vvXvzC&Qy(16Kt6ACtS#TeB ztB?O;OmBPn;8*mq-B;B!H)qT49=nf7_a+ZjOJzJH8HTCdjuUoHDyaEL}Qt&(t`$D8J7@h%g}!)(g!=4^WJb0 zjpKIn)<0rbT6W}Od^9GTdgd36V?{|MaDfiWjy8NSQR zN4~TZ4{ zLv>K-i|oVt3=C2QAOjbF1Cxq^6$p0->}Qi3e)02D#BLXgkeQ$L8$Os_#QRjJc_+ukn%1| z&g*z>R4q1+WR<*{SlO@D4U{i>_Vbb1e&E`!37u#}q|0paoY&dp@t~0|e`#v!RgL-V z4@@442q$LYhlr_!IQXo#0Q&+*XkZKmMg^Cbd3D`KMoj;4!Y6_NpCbU=zclgxLeNsCb4v-Jm z-?@{SnsI?YZssdm`U5EP$iZ#R>v|XqSkjrs670eRD@qDTSj8}3)r8X=pyH!?Q$^8E ztA2@r`6aZouGT8j&eb>4@2CBd!2gnw)$iO#{-=)~YuZMtXiv`2bZ~!Ipz6>%C(wEj z+^a+D%=y^Nh^w_K2HpjU3F#CAUabkF#6tUt6!ohW{w5|$;KUfe;gKvShDH;fS~(=>FwIuH0Ks^m=;!yuaHIuHQJ#dEnRI4GSU}g7@&4fuO90XP zTSkrME*ui1=@LLl(wqOJela&qL9<+354|5d5JMb(0#hTJOJ)b z5g6W9+qCuVEwCyNf%aX0vl-juy|`4fs;{2Ml#4+nf%XlC+>b4^5`B4;zMySG1Hr-m z+(`#3i$CY`PlD9xlxyEZD1HUs(DN;)A(ly?vp<6c_Lm6L2*~NQkx2CCY``!XSM``4 zhnBDE0No_RB*JNCjHX9-Hly4WQOsr_GY3Kj&jc9>G2R2{B60RG$j zAOxNIeK2F-0$vDX+3c@=TdY_z8SvoEw&0@RB$A{001&gw^f$*{-q|&yHmcM3hs~kf zWWg(&wNw_Z%4mysEB))_-7)^63n}_6R|R2_5UKHDu?25NbCEJ8-04jWbbGs0JZI;x$s zxwShJgo9*ySe7f};)&?TE82G7B!a;|`|o%2o?sL}-m~ZIN0lKyHU6d@Lm0Y*XwAX# zNKrC~b&`R^(|_Y=+J$nmC;per$F@e=FexeDAt~Pig#_prw@RJ|LYUA!t3pqbRzi{X zdvp*O3cJh1WvGYF$)vhmhj~It=XP{hf%L_adSD!npi}&1lFF#3!a9+5nWw|ZBdqdo z;RU9EL7bJB+eI z+^9Y8V03M*SV6S)2xw0{rvV!)Cou}p z*k7{s(CthBn%ucE;ICCtgBi*<4$}AMeGD)+=-<}ZEfRb-lIN#Xm5o8|LXFc!l4-&$ zD1{?2oBcrw(5#^^7!396A%&_PYjFrV%+8MZEF#WT1?9Ic(3BVcc*S2~iPHK_$Yi(} za&f?-zbAHMJ9JF?-o{`g-zxwUkaa^P#GPtfr~T4Mk79L2Q6=q~;8lD`?+pR;f6^JU zB^na+@?fH*X(RV;+*@Xk7fnn$1ud%Xo8i$c@vBFRv~4p~eQ>S^48_LrQ0y!(ccX5Z zyd!sd;ix@0s{~PGQ~VI|7sd z0Q^xq5KQW7)8L#o2|d+satQF4-d555GPi3kNy52m5h9q<1@@yTPw^*QzpKtQ<|m#5Tl$<}``BNi&`QOYb|RCHVN*VR4bSY)y#pri<#asJNj zgu)ew@`JI7R=HxH5kW57?=!Ik`t_dVX~ja9#&%+7V%;Q$fjsY}7B&z0(Q$J2A`9l7 zt!QT^pwppAhW@Ba=b7nK{)}znSye}-9u&F#-%ylgU{0~^{{!`dSA-X^U|ho^GA`}AArb&t=K(-P`u+--wR^G~04d;)-);g>9@7LYhVZ$71S2YDZ{`7_ z>jQ^{87h9fE%^36=?nb>`_FIvr(%?UB(!xWX*mFFIa9IHRGimAM{tVlgJoyF@Xv@c zkSlk%UG2(UyV~r&X~X~l6Q0|I+FAZJQNSLgI(sevBqx^YZzzL(4XlT;PJg(#l8gxC zORh`L!0g@roeZoePs(C7fMkg=U7b$|jo};30$BW(7XAN`_T88N9>9nH`2Y?Dz>EKH z6VS!nAmJIHvTQ|VV(bR^3jmOZf0G)&FZZ3)VY`X+UGik8oxn_Gj+dt-!E^bao5bQd zZvZ6wSrOm{0I&>>&EO1(L@hK-F#DPc#+Jx*PwAt3o|(SiXcN)(db?M9+1fd_)=6lb zj2Kp##QWe6j{nXoHiO9PH37j%*_3AxsHfui5H*L=X-*bFk~no_Z6QqFt}`zK*0dOFxVxF=9T$Gp=R z)TlNC=55ce3&W$;CXa<*$FRBwCgjqQ(Ja<_?E*n!tt*yp;eN0+5`G{SeAxUxILvP_K;VR+)ff|i`h?w^He{5#T67o zL(c0{+Q4wVMT=qjSA&iEo2YlI!@#~x2?F*#92ftgpmA|tDMXorUjt+zyF3f5{AcqU z|2}X630PO^S5;w4j?2QB9=~oKc+U# zBE>WXn=}>7YY|nil0RTlJV+w(QLa>}7vu;@@L=AU1DnWgHULk9Z6xZwhGqw)F7*44 z92lNsDY*`bhE@Zo*q2=H`M-2Vb@wO(1`#zQ4we(?7iSHUp(TPZi53Chv)y zuJAN=(Cu=tMd1=EYOe(qklia$(2>TxQ@D0z@K8D!X5`Y#NMNT&Mt*H($^n<4Z&b0z zA7aw^$R7wZTlJ*qjlx~p#0}PXKm_p<@y}6@o?D&%h3+ey_5V05o}EUc6fWVh8URh7 z@Fq%e%0f_heg?N|0Qp6s>Yx~!`UrQnh0SB*)CaK;m(Ri3Hba(Ij#a}NSPo@3_r#bZ zf7M{NLO}@uK#fZp(y!}<$W0hZQh0ecK%V@P<`&}w;XPSSr$7=dX>6WM%d4!`c>9@= z;3Y;p7Hnrl&;IAn28mHbbsPA=w;vDyb4uX;;|CmzvH3pkf672?wURbZTuJBZm|9XS z0WurrKd|~dZ6yEVao&{?XI3hI48AMP||u7L88BlL~P@E1FUvDZeWNJYARZ zl~N#b(PgODqIRQt7HTL1vE>s+3M@@KWExXeNK`c)w|gly^13GcwO6BOz# zIp(;*rz!Qe=r>`KxR-X3xtCHxg1WGP$ho>I(}D-nzWO1f{Ej_u{&AyVbiwC#=sFla za2A*slQ^iPSlq`iD~{sNLSzs%^QOXO%qBXGGd~mNwF*9G{g>`jR2qX|c%N-?9r`yk z;N3K1Cwz)3tUxt%yiw)J`fmQ=7@d=CYX{hNY# zC_)oY?P}mfq-c=2d&F_=4bEP)1JIepFb$B0xr1nM(MtpF83l2enZ4=s!|;?auTeQV zygB3$nPZ5?#>Fc$FAK4;&++#mRRhaw_jhe!@DWuv_eBh<8!aYV{09TRJp}XHL;iLx;i|)WM^pB3TLllIL@!pxBo;G zLP9jBFHSF&;8GE-pnU$X06_dYiG}#S&W4<`pHbll{-$``W95(`Zgb-xv-Fbw<8rVG>N89IHZD z08m;PNavGCadr%K)_oLtcadp$W&O82ikzZT#wI)$oad14v?3P#EY8f%0?1%J6kK1o zLjw|FAI6G@i(<_(u$d9z&Pn>^7}>L^MFU+SanyIV5ih}DGBwekrgEdO4>Fj)_%H*t zx9^wx`NEwB;e~X>22;nMY{i>b*py{~aM-!LH5gTwr(0hr)2v6n(qocLoM0#_4tgFE zn2rE|7!|i>2_%vH77=iDWO)8~PO1f%@tAf-_b-jUl~pru>#@LvS;Mj7T>dVPeLkM} zsBgsC5y|P>?BzlkCI5f?Sf2m#V>u>mWt&O}89|E)Q_C~m;36SA&i^R_be--3$U}=& z>Hu6yj{7#nX+JG^U30;zZ@rI! zKO5_Vq&VeY?V4XvGeH5t#nbf_zd;Dmz1C;vUj>tuH#DYWgvC5cgUe3x6~S!}qL;?d zKWX6z?ddjJl?%+9FmPS9J-c>jJ^MZ8ev-<#e+bMkMnB3KbNPez(De(#B$F3US>3yM=-x7ZM+C8rlnsbyZ& z>xhW&h1O}p{>ty98Eh)!A8K%pg)827E{_~}1`+iXx_8hrN^JIg?A7t?$}hyj#{~j+ z));?J21#M|vS;iw!~$`nKBB=#dZsHSX*+i&Qh?Z(d2F{1^} z?V44_U%#=>@TyDSIfPjv=^!o$lMzy*qFvLfA@Vq~5jB>uDVa~#l16F*LRB%Pj970S z%((cpLYdpto%YO{R^Dp*^%o6)1SCEbu9e0o}W9I_V zNxw)#`D-b-`i#E~D&Z5h2{;G{h|*bUW`eyQC;u>v9{qeM<-s>WY}n?8aNN1l(6}N? z5{5c)xJL%8$>h0cmZm7i8vi7dfK;=EkNdH9o|)TvU1*}I+`6=KD~bb+S~JrA&~pC5 z&S?7SwnM3@o0K(>V&=4Ad7iA9omw0O82{3|@sBFPi&SyR_t0hY+Wm~-SAkg|c$y~!T zgQQSZnJi))4%)+boVD7H3gCeyIGNeRvxXZ{ssTBg#;Jr?P>g-^J-3E+61SlsD%N+K z0E2|WiqA5Q9y-DF)&v}CUmFEtn4?Gz3Dvk@vMT(C^q;hvEiA7#02irGL@cumPa#Sehb1H>*>2$0MytKtmusBF&B_=`zSD^{Lo zXRusbAN9#xf+BY3r3OE#AoH7n0H9@>v=r&N-2qUUS=zEMq@6LDOhyPcO=OPLs7jnV z7LtkaREbn%D0IAN_wRn;ghO|M3$QJ5EnGM<;aGnn<~SL~cT`B=np$V}qjEP;69o*| zyg#p(;GUg##5tSRc#wWnN{1J~7R(r^k->!=%TqM(`{R#lD zOas1chPsShf}4xI*^bQj^!j<1mMIcJ`_gIGz85(N49QG}oLeBCq1laqVt$V+J}{@{ zf0JQ4h$%(TmV>$|Mf7Lqkw<|wL%^mYL>c4>%@=b4`E{Z(0HF3=wVH(y1vNA&5yu{`kBQoaF`t})M8jE{OaYfcc zrX!PitXoKru=fM*xbY+tihb1qQWew( zg1B}o@ze*vt;5bBWL;L3tZ=zJqrgaPl_3EScs?fR3H%4rX(!ToY8_+n#}``036N?I zXHZjU5DyFQw2r$Q*3@K_^l;WcjKj6I>DRAabKR=8IxjAByE}7{wtr*rTkjCGzY5Dy zo?}dp)+vKDLvr3DD1vVQzJamd2CDim@R=6ee_Vic^bao& zh+cIx(hG1~d|=&IODN>(M0MO%)L+uhZ}HLR<%bNU&x|VAr3?lN`DeeI5OpEIf3)6-pn!e zk3!kn;v80wS`c1_VR7yY&9cS@X^_jT&lX^Hb7gk0_$W@}{C%$T@%UHF?1?wwX*g1z zTCPyiAgZ8+^=)Z(vKLY6+qE@?GFmDAU(9T9Ft-1bBK$vs{wwPnCX7G-`aj6v|2BLV z#N_K_M;xNrXi)5~`FRMXu6zoz+ot(HW=M?vzS6+b3$Z>%rsL8+o@ywlBJuYdF@W1-w)K;A?8 z$aPP<#qCPFN6q`TEh8|e=YJAEPynrb9`w7P4eU(p4!-_?hM;&g7$@N8oTwof&b78b zqT-c57^Q~U5G3Gx(Fx&%oJa)|8UO&Z_xN9w6$0dPf&fDYhib}?>=0AP~ifisnb zH4MD|tZYEt56zSB#|d=lZ%BzecSb`{TY@D9=QQAS6^)Nh4up2zOU#p%(vzvlQi6maoES5t27Q`JA`6pZ4YXn=8=OB`KwF(mNCg%{(w?jgySV^) znmMkuG*2a3xC3L@9B$uHkBI-;eXQdCVZb#(_(3}+LboR;B>EJyLb6TD2QJsY=#Lv% z_>bTE%fIG{MFmlY*yc2M&g4{#O}n&KW%2V!lB7+Y@x*xMBDQ9V5f|%d^z7wHNg2_7&U7%y1cqqTEOhvYS(mokYnLb(>)>}EQk15$ zP}NB4^t4FeG!f&6lBKhL3AhN^=6IW!EX_xh9OZVr5xg|?GIhprB=~=)zQ}hXt_MHG zu814jyxqEH4hog>%U)NzpaMRA8)Lzz%mE&_e2N95_j14yu+eBn13HxP+9OU{tjVd! zL_|+LDF%*fO`g+Ab~R3A;TwAb9=SrcBVNw=#RM$;V;`d#L-8v4b%kyEE7Z7v9W_Di zSofrud0p^}yAZ#pU^sSmE#M;se}^I$`{G%5$96kHt@mh{Dui2-OphizKL^F&B0F`* z7m`J_ng3P$9gfa+K9xdnrSC3Dg>2|ypx1#mRL%`-Rv7e{NBp&`?%KNO| z0ea+iHr^_mMVd|nfkh5x@8_5nFD8@AF*RTKcsHqIO}X7wHQr()Vj1mF<7%PExn{+8 z6JQ8RuqrYHB=KRL;xO$aQAYkQ*RbG~cj31N8Z?f&+yqXBRQvAPBkTNl;C`hDV|M7l zT-`i@`nquIDqvtCPoiZkn=^<_#@`+8ixYqbLMNd_-q$@~e9I6=o_muN`m!9ICKU^P z)tuNPXbfA`18H-UT9U3!Y_HjiqfijB$V2UoSU>MRD>j=9IvyKluIrL|$9aX-z;0~z zB%vduEP)(YpIy9M2qC~xF!ADi4~;6q#6yGNl9po#tg!8eI|{9)j`>XX6g~hVSHayTCKxw z)6XdR6l3SxvWU`vGf7^(w>jD*3*4rzW05ND-_z5nmKhbSzcC{1SdkGav0;|%?}W*3 z#T$%*QC7zUni2Ile-K#y(%|tIzfimhF+OVGX%k}cT4tQK%c|(3F8?=5mUU1mVIV1#nr zhPOCwN0G{y5*|aw^L&CzW`l{JrwP5p1M#Qk9ji1Qx4;az3ZXTya61LQ*W|ng^D+J` zA0h4_{(k{xK$*YktA6XvN1pwVl!N+CPR=w9Lw;FBjNU!rj=cj?R=P8SYn-B^erOpB z$|Oygw9M0uJLNHQ!^-Hh5rCNUGFAWNR1->(EGkU#BGN)N+>m)5Pl;5B>eH<=Rtis4 zZY$ax|DY%0 zYe^>eRaACFqd@)6Z|-(6NvZK@!D6ozzltl_#J!W#o|3CG=_96z=!Mr9)4nXoCWrEF zWfS`8zW+fK@}1&1^{Cw$r*rFVoG)*w^vxdw;}#q)bueu|Z-uB;0A8|s`>Mu+*3GkH zVh;H%UkJnf#F#F&`6VO7qPx@9+biHi@g4ETUk+Odx%Vc{2qc!!NdI;tBBAf-GTGC) z=tcr&60?Xe3i!A`9H)WKAsGwDff<2lRqpF!WPrejDB>Q)+Lr9`RLf;Bv%DN|?7G7qs;Zo)w#? zYF~X{RwCE2hbB^H1(&BE{*+m5_U{Djw0~v#3&$Y6*4J8A{RZ(4?U6)bY2#!_V)RTD zNgHr9fPVJeKRPoN| zto>j!8c586#$4<|b{2km}5vpeAUhH7{mm0yG z+4L;tU+vCo3KHm}`dW^nD}4IeT>UB315vFn(7nytto|9q;Au$V2I?hayGC2GI7Gd+ z5`(oKK{ZkwVSQ@r_ishK`LT)HUkn-AF*1ninid|#A0mO!^F;@Y8;MUDo^t{PU0uta z9>|ChssA&|-`-;nxS42cq-akZA0+5MI3)0Qdm>&s8DmiO_hrh6hfi+4use;{qQ|Br3~ z`_DKsq1+LUuYxJgQ$A8L|NNNfO#Cz7r?duI1m zsqlMwp)nwaVHv#jNFacXrf=OeAEMxQ_my`$1siXea06&PIz#M|LRjM&c~?-LU2~m4 z$Jt0GJnyS9jbR4Z%2)%j{3!IZ&_D@Aozf%M=IObs`M~xK+gFRvVv$r{ z#Npo)E6QUD>2=M$O|X5t02&08!YuuO+}xA4=mls4wwd=VZDmqN4WW)J;#$zIkW7r} zcZG9K%-^1~vJ*Q_bVC07ZJ}EmQTU-Omj#o;8pF*u+?WOexp7&az>R8MJH%nmum?-( zVXnR(y_Tm`?-xi4;zk9~`(N$8p6?(VHjhh_j~S(>v@4bu@ZS7&hI!msRRZF`t>Yul z=dZ<6RCOmsGX>vgWi4GYW%{~!i`|*qUDi@=zb<2^TPJprVsF49QD~lS7T+UlKym8+ zAL}1#DL8ayV*8o^HBBX)2sy-|mn~IkjqZ*nZTqpG0VQ;_#71*d_^by%dbJFWo7?VlHMZGBKlq~ge@>r z^s*-YE#d^CU3}|dueyJJoB{Yk12^HZhm%u2KS_>xf&-JDi{zwTK)NRToZK(5;r7fM z&guE>Fbkb_AUsW|aVw(b%w68TH9WAxlfk-bj7a#xk1}~7i(@iQ`%v*?4;I0 zoyPU!vE=d5GbF4%KNm9MWIvMFeu$Wn2sCL+XE0`Ya+e0lq6}>yD^r@7*sHvxc7m3t zXmk!>)?{A@00{Z5i`$Y)2{Cc?mkSz#ei0BdK;Q{jg)o#63`inXii3zLG+Fl)!TK_+ zQpst1j*H@5r}GewKJpXulhD7DWLI%eCAT8|MePi)@JcDy=v!%a#;~vzY=pG^!36I9 z8Up%s$xUKnP}?ZLp?hiQxCIP%Ni|8&j|=Wq(Re-2$RnNCV?yaj&mUZtZUt4YX^C+l zj+FVaIQ~cgN|CvU@{sgv4X&oFi5e_WOuIM2fFYCa- z$Caqm7YPi8C!WE!p`1j}S=JavASP$jU4xF4GjF@dZ!rl!d|^j5^`ZeC(LgQx`VLyVkUZg zDV#8sNeF3SGY9b_z%Oiwm%M;Xrw8nwyxOgSm<{5Uwu8ac=)b_7*V%-*COm zgLv7Ho@{C%;Odx_G>aGo$LsDO8a?R&gkw_q)qnsgU$5r%T~5C>%^FzL6!fZEe57-+ z)J^=F)RFw6|B+hHnPF811-FDr60Qcc=LIhg7E1Y&^Isz0(+TGLOJ(g7#D&hylFYvSk~jS{W?_4P8$w+B)@%r<4PlddbR)--$e zTYgWFSW|jBFkDBmtzGnFtUWofhReS7Vq8?~@L7*P5hcOw&Bc6C#*^PmQ6V^gl0U~% z22^hZnySP>s4gK$@nZr13?#O*nlC?X&M3aQxn7`}8qtB`N)@s(^8!2Q3yC)UY-M*b{oI~s1L^Dijj?2sV9uAA1X9)9Top9F zVrRA7mxAFH{z(yn%ayL9P8bmnpw5>erk%hJ*+ zm7$PyB$e1IRra7kn7duV?&gV5i>pjp3ABuM%-mgLJ%}9p2u114(XK24_>v$ZrgF^P z@;GZAkpHSs(})rje|4Gg3;@$;FaWHQC+0rFFVU;4!4>oXCr$}{xVnUJ7e4Tm#KUtw zA-B6&UVQ8Wm(l~4p{Ga2O9Ps`Usmqso<>L<3f2XGOCNKRLg6oNCW#hOQe1Kv`c`_G zRb-f_Cz%8eU{5ruF_+&W>KyIRIuH)C%0_y(r>g>E@riacdv=V97w&t^*{%^`7n-kt zLE5+eY5CK~C_fUTIND!HoGJB~bEzb&!}hJo`4fsg0y`|QuK)W1L#i?~mL}+n^8Ckk z(4W72whX;8xO2S@rE%P62(orxo{zz`N($OQyQwomh<6sJ=$=eC=aL)qjX;~T9z9Ja=AYwy)x#$GdrzR zC2tb0`1X)jHuUsz6Rq^gMRrpUJfrCG5mMgmn8dR=b?Do;z1xL^;^i(E<=Ve)u%Q;x zft#*JD?adYStTjP%7`0F%S=VRI`?+E_56gnEFu;(JjrTr2iB&DTC_a6-X(pq!|A2h ze!u}W6Q=K{D&Z^=fK|H{a$<;_?tAx-qiPntvj)v&zt}y&nKe8lpl`PL94}{6-2w@} z(4p@w*lk@-4MI2legFe=PGU;SDLuO2yDBhGKwPG5Y@0wG z`qt%JFERtjn~q{8D8F(*Pr^{@Lpg&Q+>2WVd|v4m`}6fTz=Z0e8f2_a3rEO$dss$9 z`W$C{9VQf3rlt5yPCP5Q_Xfu?X<@T~iGn}kcLUg)o)JN_+qql)odGr4BbLtJw3kG7 zdWi_k#85252MQFwM)HG!4I3yf|4?}Z-DHBj*IC>LaRdD6 zx*O?_59$+a9@rSN@N`m5AARfANJ8f#J8$%x3rhK%=em*uO&~j_bl;Zqxsx_c5}viX z`0!@Ak|Qi$t*c5HV+JKmOikbxLh0Y)?s16Vj027eo{oEkXng=aP|D{Z_Fa!FviQs& zq$rXcIsC8EiPRax4y7H|tmkM9A}or7x*|0%&*u|)u)MOZ>k!ZwqQ8K$V0_-D1^|;P zk}R5x*SU{G#L+s>Zl1_H|B1&J5I`d#veF8_xOv-C0UGXZSyT`!J=O=gI3!?M#$^m` zn*rGtdfQ!IMM6MiSK^pB1z%%P1yiZEs)90Nj$FbTIR*oPfj$X@y4K}xqst!{mHkA# zR8ijFl&v@Z!%wUWqyGc$MgyU{($H`+74B!Oaq#wbr|1FMS_a zA~7$F)dRNL#`6gR;wTY)+?ewJJyQE~qD#d&34hO?m>vT=zBDrWf$~jX`P6|VFHVS>F%d0AuPh51K<9u9cx3Ch6N=naqB6?DE((e|=vixbg5VQ2( zMkB3euIM%XKOyi>XrcNeCF{N0P--{J1m21)8(DqmG&FBI4z?SLdpF3&NZ-x#vT?sm z8$Cd8gF~rRIeKDpZJ8f1lRr037VTWZ)3UFl(PGFaiHQ{0g|v)G6ajE`T_qBln^(Z_ z74~BY3(TLtwaHBxauziTIe+H0bK^d|TM_2+8pN~*e9&^uaki@gAb8A*(-tUZ6KaMK zwzM88jA*|{m3`K_sLYt9|1eweS8HoKwWc;S6>s*~FiALU^wX+;^vItPO)fUGh@6g) z&Hk;*#i}>nZSA+-qn?+20NGWW)bFY1y_1s43`9^e_i&%~FR4R|+9v_Fn#*F|Ec$8v z36wGX<6B&|hB$tzgBri9$otsJXK9lH5UjrbC=`45SL`B5{x!DyTv?Sn0x*FWmmJ7c z!(8O_AxAj~BZ7@d>*fwsxXL8gd@2v!h7EsH1}a$)6OCJ5`CsCgw|Sj8x7iiE9D{J| zJ|sIUf+2myeSqP8vn;xuh+}`s0MvX|itVE%0AnNn{|Nvn|Hhb1BlX}?w=-LM==nE; z7rLp~-n)4Xu0v775_S@25(XaWOFCB>*Zpog&@{6NkZou|9k9O(j;l+j&Jush%!sEjMO7f%Eo~$Qlm5%c!oa z!d^=p5`2YzxQfrWagDBx86UP9+ybJnVH@F4{W?jx!R9%GSJH)lAoYggfXxs!tg02i zJ+yI@mTrPv8{uXd>>jK+CS76Vgy*(dokgmVVP!=cAgRwa@P(Y2!9bXF@koOm|8+s< zA}Tb!Z5^{ue|qm1Zct1s($xgUJxMUu&GuNxDkG08Nb_Hk+6Q|534@DPbwma`-g1{v zi@u9bCg1P`vAs{Q`gWYN_nRs+#ix!pVL{RKMO2@TxG6CISVrTT^0-)npRqLEwchzy z@RhV<_p)dsE#m|cuuynsHs~)i#h`O*WKesZweK;?19>j>z@SmGsU9(+s@v#rX)st)YO{7-)mI8}u{ol-o!2 zYq*MyW6wUwm@vw*T{=MigZgl~xddCUbD@hg4t0POkNxeXIp`1a-YN~O0Ktas%3<`3 zeSw$RJ{6d@^cFZcbpoaHJd^w0p`5S9Bt>rtFkr?evyLTo$J(blcG4FeDnu z$ng6R))-WeR1O+1|J&%>-hLkT0WCD=v$A>@N76dTXz3fZ?-LQe^8afqc7VFobE8Zu zxi*{oKcN)#jAVD#CLQ(XtwmVB7$a3efGb4j2j+LWt+0-XZw+y&ue=Z875)vXvr*_L1x)KB3PI2sVnut$_LMnymSVhaoOFnlDw%1}ZZ0s-`N<<{G_ZAZKs|m+?u1i{F zoCv=jU}3o&1b?V@o5aum37DhQ)vvt^Zyk!ohj26wnBaJkjk*4UhzMDD2li%(jHP<{8)c>2=QZ8J%rh#dGw<5?;w*A2GLK);~~uV8@V7LUbz>f{xI zr6-OJIYkj6!Lrh%(r0|OI7VhWn7Hy~%(l)<_2R=SJ$qyI`ao%|(HXoIYKcYn-4gj# zCWBjPVv&mmvuXb9caKtULoO;;2~_{*bXjA@K*XWYc0_oJ^F6lC5;eeQC-(m6@jR;ao3c*8aI!8R93On=gWg?dx!m;UvE! zp};$I-G+saL9GT43|vAbli?v`Btv13wEKMcqk%8OR4oQ7gD=q&UaN=Ce+Q%vD_@@g z*%aF4uk6%BWjW7Z?{9MB7f=w_a~l4zY0X&gFwJ^M315okO);0-u^ep2EKiD%io})_ zb#)b-yXT1RdjP%&<;XtP5ZSp$=q>%tE$kv_rD}C6Iy*x~*ffguL*&C>jk}GhlD+fM zbVSOXWob)Wmt>={wAM>knd@Xm1I;&@^3hPOFh8c#8EtUk7zXDjw5_=G{8m<69N7{g zA&o7iuh_JE3qaonsS}0)WVxj%%>SGNjcNkokWX?ru*yFRTyVSekneH_v931tV}j81 zmuAZei%;i1q+;N?G>I;Mhtn;GJNrlu90ubv4^c= zCoS1Muwy-)nnv97nCR-i((kKO^X8UADi$4won@~+FoEEv*;reiR)%$+CXuJ? zcAqY8CGXU43Mgoaf`}0M^Bk6~ktJ;h$^n3heT})ip0Xzj(FxhpEfUI`9x=x_K-h=< z5|1ejL51S)E(8dwmsnwwWH-7ZHo$5;Ln0?Q2TE2>Vpo-oy`!HSHZ!V!(fQ|ach>6} zW6>!q)APcrY{`kEyYyW-Oz2IKLmhaswDqxA3(IG!lme401Eb3IIoypIyMOl(o7;Hn zroe<1XRji5vFSt>RAU|c3`f-IJxOJP`p%YmB93m1{5gToG|MO!=Vfco!KC>n)y*|O z`cm84DccuY9;gMnAgh0e-%DLihhvQwzGrGfPZy8d1NA)l9 z=L&o1byz*fK%~AE(UZAb3;ZUlrOIsXpMsifQZ~a2;B79WOk%m8A<(5fc%dno{zMn~ z4{|q>`-j*8Fm&}82E)dxCy#sdO1d@NGTZ#J`MEr46NnljOX6-`6RlFc?SyRN*$)zB zg;`W}wneHl3RMBt=XT@hx=cJ)+$79e(Zys;2|7A8yyJviflLtlRss38l#SoI*9>rf z+ogP3oV~|tYo)Jumf8A&q!*+8Q(fFV98hR2;}WEAA?Ha|H8PTQ12+iCvhoLsZIRAV zJuU0VoItS9?e7GIa89m6GSaYOP`d2)=m%HpdwEpatl*QYvhf5|L7__>i@9V;MiaJu z--$Ji`C1)giE{0^_SrMXW!C4zIDa^UQK-vo+>LW}Jlqm3TnuOYCo0^6_RSMegbN5b ztc7Phk5~N6;wy)Li{_zjj$+m9#W_tZHH`pCR~qEf45_y^KuN1vMMPBUWJ&NwAcU3& z(oS==moOoP@1v-gTh(p#NgO%^Z9Hbod0tiRO32SSXFIvr-|2l!6VBu8E4B-%3sO^n zdJcw5rEoq51WiZ}8rPLpM+d+b*kKW)*%n&HPY5WXwN8M_=bKF8BU!Q>wu28xX3dD! zMwmCZaAmJVa!GhDgYgXHfJx%`E@J5C*32kl_TV0w!?K8S9`!(K0|=T%ktn~0e1N5k zGZUE4c0zvlO0KL|JcG$TQPg$wIZ|NVy|mu76pL^&!Myw$rP4o{{giro$jguMj^gC! zb;(OBv}6ZH+2hJ&d~_O!Fbm79OHq2p4a|)5=N5q2ca>0!wCD6qoQK&`>nCfEaFfNd zGy!yqn0j&}39H0g@;#B8trF6EgM#6N?h~rLMW_%w@*UA(op@qgd^*ncLvx-LVQzWz z_978v)QwYR2cGCpcpNuu$j1gbZ`Wra=HIkBh`zyPD1BL-ENVV!Ng&2FPE& zhIZ^uV`2I7n%w55i(`G^R82B0i%#sTk$jZuz=oCn_nS)evm|3_+xWptOWgwJb7YP| zRjUuHBruA4X4|wW7GS$EGt*xznOiV8NycelG0#kLElIU@La(zBMG-gVX9D$n7ITgs+!r5At2m5O+lo9}hgP~tb zbsrXz#CVnlPv=olZh1HEe0YwFjzPYs!FIa^q98l^0R&l>WwGC)yAS?u2w( z@cxCdaEVBqoKZ19F54~Iom#TPw#28vqK&LyQF%q-+O9z%r!g%h)AgN)M_jRNNge2TU?%^LddEb_Y(7u(R z+sq`}FU5Vz@xaaTkdP^)5>0g;ZS{@jbZj;nQQV;|xpiW%GQ*;4=f#@4i0rK0(?Ik* z5Rh}ow(KwhLB{1_@|(I$PQ%(b+Lbet)3$)JtkIE5?mt%7f+tC|AG8KyN1fq$n~^OvW)PRj<6*~WV9LR^WjNg|KpwGWu$HL_tHl5K9T|c7ABo5w4)i^18t{9 zWxK=98o#<{J%@1bGbMezl00ehLK51<_=Hw#lrY;$8#5zCg$xtbovgyFGQ-4I>s&;I z9>Rj?!${pnU+W9TIpxwPy@eWolS7UEjXI$EMR)eY4W0Ld|MgV6pZ#vO&ucpI<}`ka znw)s_Tcd|gyOWBBw*3f2~zwbb=rYi>2Q~uxzkzgrH!W8u;rgUR5l7)aV8k?@}=gsTh z!5;~{G|0N?bQ%01fvv|caotP};JJ5j+xxVjo_GAOzk?90E%PRyx1Y zre3GdXOq}^i^I*nDA=tp{0_>2liyH|=l?$XhfSriES@sQ7MO7Dm+Mq?FvhFQWhlndrWvLZW9Qs5LC+y}q;CM`z zq(H->8^Uw8^`W@_J`KRIO7xg;-8j4 zHPr(2jlHn35cfhW?q~=H{iG^-*ZYuZ<1 z1bC8iThIZL3r|U%AA|H>c$c- zcbN6PZ!C4cu-DD(yn-(U@t28Hy0ivb2q(PtV;Hw(4qQU+J}8efk+kXfm96YukZn(^ zZn%0w<0~d5bvX0MF|sBUPsY-ZUwEuvR2L_7Gu8rZ`-nTC!$!=)oVQ8xf`)~lV&voH z1Pw;LNvL)KHXL3%KLe}=R>w9!`JL^LTjY z7}aKeN-C>*gIzP5_N-y-q?&Pl)m3{&^mP7>ilR_GTK&bW=2cu8r8AN1D{XQrpnTPD zhkXn)$%^*MS&>;J_}y+ge4N(q!8|8vBFNG#CvI^n1Xd^oz_}4hR32Oa00RI#S)d+L z6Wt54?C7^sJ68o{-X5eWR56og_^xbu2_?qOQwA%isPy|BYBlNhKY}N!0Wln>AaLnY zyX#15SL_|`Fk$lYV2?4_Hb(?et5IM4oWF(pJ$I5>*Gw^5umXw2r5UINIDhbF5 zj6+ArkC7J#o7Z!f071FI29lo0#uFNly@>vXmAPHRtj?}hWv>GJ*-FU?mS7*zW_1C6 zMB{eL(1&;QnsW^UPn=H46n+*B>UG)FDU+63?{p#<;y#<7>C-$R>OZ?He8+;W%l4A& zojhSz!nb@Ur4l_Jgp9#K8$}>?X=bPZ06I0XI{B3B;FfoS75;xtP?L+f!2wT&6!0M? z+drRsT_GqUw2Q~UOlAc{JxxT4ZZMC4zg9;c32FJqT0?%pE8ZXo9W9{dUm^2Q6eA;OuTvH`@* zvB@@>oz4-!qO05D-a3e*t88*!_!r(2sD*Vxxe{CO{eDv8aw!!~8#qpw)t3_;OW^Vu z*|4ermp+IyaWXL}VC!tR#AC&4QnFoXOOjV;;sR*3Jo;`)HbN!jvgZYHgoLem)h)5L zs;gf-!znH6WB7CQQi(Kpu_AfRwS5Rwc_QO65$uAutADzs^@t{MgSGC}xUON;zh&G? zl0V;Uxa)T!Tex!6np+0x+in+?$w?bMMioKIepRUq-UGF5SCc9DB{nuS9 zu-WH?n}HEc(Ol~lW!Jd6f>cp%%?IP%j6KHa#Y#}4Hn_Q_;K8rkRtxDLoz7!dBGZZ3 zmFz~l%r3wLYr~H_m)*HBj|vzRLE;>G6A4RSu`-29S+S)r^x6#SX_i(ka%gyFpG}Jn zu~t@)_;8|jG{bfo?yF~*kL8`o%Ag`U z1avdoZk=ZkBZUm6VcXtbu2y*jlBeaHfcIfMg^fk?^N1|>mda;$$9aT85I?4UdI7BJJ5H;Fyib3-lT*Wg{=-L9<~P7F$y zp)^CyyGLkD-n@f^XrrzW`#UFtK-_9IXAm1A4_$zKRxg(lp0#7iKrsUxAq_OcJKUbE zBG$d5aCIrrN~}+Y4XD~u8H}kEmZL<)maiy>-89kH9{h$?lPX&eWUo2=xdHw57-AXR zZlp>P&P^DPLDvTZ(<(#e(Qu!{c*F|oA!AcIzXNN+6x)uy+|ng)QZ3;%>%{n8cV#+-n@ey58ETcD9888@njC zBz^NzMY?`B<3MLnY;hE#e;W{QKGzICFLIgU4jJO^c-Z?4w4(f<9k9Ku4CQ&dp2Np-hu5%<8YgA$ydSFtP4boj!Q;44?1gCTe?LCM2?!^wlc_qIItCS17R4O8YguPML4srlqjIk^q# z=bFougP^ULu&^CTU68AAxg4X0l4G0uAT)&DkOTK&Ha2^+9lm`Q}5Rj1x$r zUD{Nx0k}S=Ocy}m(KXB z-txFMmKkE&=Lu^xZl~f(7R+P)&)3xR(Brt2PyWW1uJP~nPO6dS>Q}2&+0Uv)Z_CmH zRVC_NuH->LAdEY7M^)otOE8WyxtBKe=>X3Cn$vY_Jq`{}dWsuUDG`A`DO1mBy{Hs~ z3y+cU)iQTuRnxedg!Kky%{{?=aTi1rwT)JQRIkRntdG4Qfb0q!ns0H|zScXQ_tpdK zSid9}4uuht>TvF(iLTn|O^PiAeZc09z;nr2hT|5sDZ9i&_b<(|%GEzRfkfzZbovQU zn4@qdh9mMOX0fNK@94k7nc4f#LWmE+cVaYgLViPnozPsO~>;( z4;tn$B<$ZApU#SOi_0=#NRh-`rG%P>|F(_AUn4Ic8lS@CzwKdkim(RLKl5Dc+{R{slU zm;6kO^(g)H>#G&aJzxQB)aLz5qall@nB=B|T;uHSv1;qFMTL6jY)l%8mz z#i2!@3-PVzYw2{%NKS6%S3|=fW3^YhJo2YT=qWBh(7sOHrFRA)kQmc1ALJteYy$^Qh8WjgBvkdX#XwkCiaSbB}e+U zThuezi|}GOpj{oZ)ln8l79x`V%TKup4R_vBzhUJ324ExO%(e%xXZ)~F zie%^>l>Hl~X2kmaZ4izAe)w8SKFTDn=y(yFcvUy*$7BrKTeMM~a~r+huUaSnn>7WR4yCT$tZi!aO zmPCo~Fmhcay%rT%ay?kQQBacwtA`)<=uRBMK~g$a$6VZ0m8IU0`kUsg)L00HW7th` zZmj-s(x#UV9?olyZiap}CX7{m^etV=_v=3@D#2cPfB*m`e-%F-MD`DB!1Przf{0YP zC&!KB5qr&xV-fktTuVov1iQAx@9$&du34#Tw;md-))4|DHA65GqT=LR%BWf%J}a6{ zkRrIpJPrHYrdf?m@7e0=c_W{AReMCl3RyU|aoOwD-~U{E$uT)&PmCWU2_~K2AdgCJdO_m)c_t!>v2}dp?17=jmNSAkkoe*f{tTY1@hKy&| zcxMXX%7cNRBJ^*MkXMWy=|(3JCc&k#;-fvfjCqWn$bPua(a7D1!Rec|H!K5M$_TIk z0IYvtvq|}Yk?@ThkT0Z*Kd4P+FiYFH%sU($&c-~BgovYC@tK}?V z2bcTqD>{$PY6>xBv-@y@jEp3_+sf^Ynd~7cG|x1w6P)j^s~dJ8XH6B!ZeQ(G0^+{v zuyBQiBxf`NVN)<0GROxezW%fwT+2fYPgTXs1l}+ztK_BTr5j?8`ea*M?`IcRXjYvhm#+Vl2V(ZzOj6! zx}~!gXB^c(P6-#HxrXRRN-Lk2yptETk9+8RnB$C^@P#I(IXi?4-Qh#bxkC*Y8PCY~ z;ojbW@Y3fS(W!T$hDNMxx3#d3dFb{M-VmKDfGh~uZAH>T2w2P93qcR$NP_TrlW0(e zgvdPKT=WCFthAs3Dg9C0p}f$EG zRYmQU1ahGCk7X36|6K~-OUd|=A4{pf3`F}DshC-GwVr*<x{=Eo1|HTFvOX%(Isd6#J~= zE3SXYJx;WmuOT|}#DGO{M%-1p*8}(!s)`moqs3FCNNZ`ZICb4@Lp~gCx0zsLbWo+0 zYSfxLH}z``w=TnJA(-s}R1I+aInhyGF<^Kuz7KMajPwhbdXjp+(7oElA8wpl=WCn} z#NtLk+RkHXx*-zzlzfcfDND_|!3hf8)2lu%{=>%rLf#kV?vS(!Dow}QmB>qW;48Sw z^ga;NwsI|tfc9Dzfw#Gr{|hYVU{!6nuqR3l&nTf;$h>h~t8{R;*OoFP_!zo|H7*t# zb~kXerGb)Ya-A^tF5?A`o0ps+t<$vL@>HxUu*(&|a#Ent8^i z+=1b(2Rqd%Q^1)6CIW?QgBYnOIlX|)pM7(G)$FN<2SPAyP3}7NREK}D^Z_Hc-taAfqwm|r>IiaV@P z%(t2Yah-b!a5L82dW?T(2Ozl1VJx>O8)mHhSb{8D;C?BhH=Fvyq*RWr7 zM;Rtgsi${xguJNLzRnrteW&bjTWn4Nl+zN)J%8Ma7vxxEsoqn;goxriaYu*Uvo&j2 z{oOy!&_ptY=6o%hZ=SYqmo7riE?P|7N{x@(g8zc-D)tj9e}GpsqfZv8>jwv^od=zq ze(4-Gbl*9F?OWVE>3Xz?FjVEGn5(o#Eh5w}YxM?X3;BAYo3?6W^iwoyh@iSI8pBmt zyx4mF{9T=HGcIpqxV`kEhhrnL1O7QmqiL)l31pA~auop5#?#JNjxH|VYlmSG`pF~C zXQ@@1*>KY@P(T0Ur^Wu_p|dkS5o3Nxs zBnD9DaXieVbb|H4s|vW|Iqvd)I6Ym6f#CI~0_bhoPy_YF1cb9TTg6M-`fM^M*AwHQ zyw81I{t3h20!4cix~jD46R_lm&9pca;*E4rhg>|#vcLcA2R|ypTmu`bP@~*)ut;^p z@Vl8^2!|Rz`_%PFOm>AkyU(dIv>GYZ7M5jNi zBX3f@%W1m1HWLI-F87TdPg)aQi|REKM}Y)Wm$O1JQ3k$ z@FKud&*KJf4=ZpxYRp;-w9&=Qy_*E9{rkM%%%_w5i~-1w@MXReQZ11mE|t|{5qo#M z4SdcCE>|r`3pKPDu@$Te_rOh>1c!9=a$cqttcd=|bI{3ZaKX(!n%IK+t-{LNdQ1lf z5lMHRTC|lKJ_N7qJVN!VwZSUx1Q_;+;|%h`B_j0+Wq}m#IPvL8y_iNlv`e>H{WLJOw@hj=Prozu&f$S?T2#qdD)8n zz*zz&Er|#g+zn{+WulX3ttbeP%#3;2<(dz~$ev>^xjWs>S>I;>!3!b#dQz-kum$xb-`E)4BG+H5`Q}N|8vCP&qq1> z(@RV%An4xyvx3-#l|5?)@~zZ;QlT7W;1cI5#j&%!6f~o^?IxKUBiymeJ$2R$*N8;B zQZ{Wt7!96hhCLe=LO%R9ED+=O4kwxDC#FEJXKNSG)vw(O@M*fjXp5U7-cnmkGTqXC zWB(NyudYYeb12$RQaDfcAJO0LtzcIsG*RatG{Xg0@l9b@?Rj>ib=1PL4o^+UQ&`p_ zUa*Z&&KIz_$OTCDY_a@FB#%?qc?wGuS7o+LI=7bgu8{sbhQUg3gf1akh(;-xHZRI3Fv*D^^Nvgmx<-Ht;O=LkwK!eW_(= zN&p@*8iyHt1dJjELd;eG`oz;1P|sBQ8{Tv)``?h0q!pviof7+=#gdK=Y%4-9NGQ^fI_k>ZziH|+ZU*u6d4EUO!KvzyoW-`l~ zD+UQN6)?~SDNmj3Ki#j5T?%1|Zam=F>N8gd-cMz_e-qWm5Aa~w5SaWnMD{P#EJs<1 zEm^B*xQBAgCsKcK%3ekHlrl}=@sg`cP()D@0O%_cL+<~20?=s(X0Cs}#C;E=L47cL zzT#tBB8LmT%nguaF8nqGVQvKwvLNqNrwSI)YEy-t z9E^w~C*Yb|ZuchBomsf=qJ0skcym(?4+DV>y88q8m|;*9kpGgA&|0SJ zk>VUVO?-+56dh%;IMh@tIT3}0))Nzw8l4fvGW@1_K%=A?T4u+2I{920oL60yd#J`o zl4C~#wRD-gw@(3Gnt?Dy<#CPCkBh+KOx1YNYi+1=UjIR}RGez{Ho|YeXlvB)UQnxV zNA(iq(I-Xt21`-LLC3oaFd(iIrvA~>VAF}JZZxvU(jC@4`zgFw)G&n-+2qe-2xyKSqlzuudLB+D5(y1qv=U2`O%r?yrlQvFQ-Rr@Qmh%hKa;ttw|je zYW4;KsMvoH+Xoz>o;Ij^6<>aZ*F#tb$L(eSMNHZa^QZh+n-sT|fZu`{fYTVK#xfAb zQ=kXZ34yF9in&%ubPiQr4cmkFZ4hOtv?C#(vu&(M#`wtu6m2kMUM1R|AY9Cz4 zHc&a#UwxWEW&}hFwOUVtsKnQgztpw^kh)9tV3N`zr8TvdHD5XenA`f6;yGI&+OP7q z1dZYZd~`!F-=sL}CGqKn4J6NivRP?D3TGsWe4W%1rPupb)W>=A-^)A{`KImj2i_V? z*yG6Vbj$Te(>*a`xRW>M-3fPOjOqcIem`2Xa`3(K0Og)nV9Li&23v2Dd1rVRH#VVE z>!O~Cks# z-g91#LFD2cIuu1RZm~1QSaA}CjEi+T^<>SN<%YJMR+o-a&Q=jhB0Y+LDr@4qB==33 zcH>->Q4YTz>_&U44PxA6CBNqi56x;;d$7KF>IGt*XNn}rtXShr1uNZwAR@HsS@he3 z{M}RtIJklR|7gE&8UQIk*1xJxWS}^VSrnNDzEkhXNsWd7CGhsc9`mo%9AP0PwjK49 zf*Qfw{d0Vkg+_zt$EB4m9lQ+30hwjY*g zx9*;2)JSL*IiwExR>pN;?kfny=5$=GM%c4;Km0hr05SZ{3Fij>%WWt6;|g`&T5;rY z>mfZ~BR9IN&ns6>QNdY0ypypX>8)%K?7|ls#|F)DhellqBg8p6?Oop_DmCpwSS9)C zTievt|5BisiwQkutDDj4H25jJAX+?UZ?fZ(BwVRd zJ~~xuGM4ejvF^6)s?aZ{DQ7TO8S3f$s-9In1-hU?QRF9Ng-dS1gWi|il87r@dZ%krk~f=(SI0mjC1d4I;Hatg<*-h<w$Aa(v|W!-vsT-=CnNMklX zHFx}f#oAaAP`lp?J=EJ4sOFsmo?V_oaJWz?DthY6xj^IxlKvLFCuRC#Iy@4~60N}x zbLrQ$7@z3MpQULkjNy>ON1r)~YQFR7Y`f1|u;O0G$Bc0c6%_Cg0)gj$x!5p@T z^tQt!YeH@y3T}x(UYjd*oZ^pM;m~eNvcuQ$x8KI7Ywi*2-F(rJdnY`OR>?LThk^hq zy!V$~4(^R9Hoo@&;D7mS9wAC8Jn=BCI0nUaKorBIX|(RT`HmoqIM-rZkCHTpjUhRJL&9QcxbfCM&x#L9PA(Q7NezjDNY)9I z*skh9-UtxHBaOxl6^jr&=JuPhH5Bi4Jqx{UwR4YB>hj9fLlklTtP_8LettN*u1Fk- z+NA9n=JfAp;F*2AZmg?^@nBBI3*Eiu;W3Fdu;kn@INZP>JTm6fPd-oeAsPU%9C} zC+xyJFPcW{2`n)7By}wC$eM7wXNg(<(80}pR-mTOS~Xe@ zGK_)H+B*-T4q)-RGrW}SSg&bt6KE<2AAJF(0cZpFYI@h<|N=qk|V1U!`9U z2!SysOt`@U25JYEcj437BK?qU67ytmHv!pi-0+PsV2>X(&;J;p%+p|j*oUK_?-BV; z18~KLX2nunrjU*&Evbh5yUa2sQ1Fqp1k8J{roFX6~y6k%#!%hKA7 zk%gabNm43kaN^4VPIbz2R=mQWpzc;e5x~ov6iiU=k~TSck8i*0rZIGVJ_)0i;qX@JH8bm|SCOQQEcr}!uo@vzMCq~7?K7MITl#7DJ@osXs!+Al zqWhd^Q=I!F$StN2D_ej9%o?C>8TJ|6Y*>EfZ#!?!;jo%k^C~6Wza?;Zd}v7tAR|t> zvV3SF`mttD_S+f(F9Z*yUUGf2vcL3I#qmAhgWPl&44__W5Xud_#;&tLVgYez4{}K1 zwYJ7z^3RKHPj?FKE`O6F?zkI61+A`FAVh8H58o<6X%ShPns_wD7bwrb3=hAj*6G8{ zQJ=Lvj{6ocngz9fG(_PX^tH7$Ky9VpbIzf`ixQfTq>K4 z3q_G4#LSw&Y-(owoTo~1W1zSKA-dM4Uu$eHj`MLiKOtC|_et|+3baO**y|oX6B(oO zR%;054ON+$niG5>GiJ^A8SfgmBRL08Qz>80J7&JEbwt3ZB#(7N!V!#SFZxNkfpn4; zhK)UwdH#nOv7NRKqM0zsE$GHN=IAG8)dPDcl!DtBy$C`faSWQlV(mgm$Vo)1t30EY zz1wiA==&bYkj?2;b@)<~nOsV+`_c=M=5F&T-D`YIQxM07EE}lj|0${4A0^NgDCjuk z&Dj|tbw;;qkh9;%L&)Ktt#Di=fhjZSkav?&p_1s$#)EJQzaOvh6}vv*`szY=8b^RZ zD(US*bhd=z3Sh|71>Ygq>2NH$^S?xPOv+zSjR>C*WW|OQvNDG zy+z~d>GOlI0{V6W&ue$a8Wa42EL6G@RC^Q2`=w-OA&sOHb#>=K9`t`m0sk_PdVT_T z(a6i)Nn6DwT3}597_U;(%`Dj_>#MkNLzgE{mo0<^CL!Cmqkf~M4A?3Dc&iGxVYBz? zp=M_UR0)Eu_jA}nZ#5=&J-=OlGm1dUZdjo}VPUEBO!k6j=$+!TVm|{sO?SG$(k}A^ zf+;tzmr$y`HtXdQb2?Z5v|Ra*o2QM^8{6_TONEj4o*+46N%FvR{Q#ADk^l>-eun0; z&`|0V$qX;7sVD*D8?q2`EZ6p^ud7}NJu z`+AcxqN`W@?WC6jQ?<4jk};6xb4UPhE~6Kwp8J#=ubxif-BIqZH@iEOZTu%ED-p;U z9J9KUDLqaz;q4bu{b)qA+94uMZg7o1jEdfQBO8gPQ_s9 zI@R}+bJO3iFvv}ErxW_^dbcuYN>lu(Pe?4DOrm?JO)4Say!l+T%9gkr(6%CW-yZ4? zi@|#?X#3H-OQBUDN8~Ai?$@vxlg!qmuD9K}&N|{ce5iUSL4dVAApNJkRg6|W+0OY9 zml2&XPVi}5EdpoQ_>G%n@$>v`ZM8RD3PZ(@b&G9~MBjroOO>wTgEehRx7j?4uev|^ z<5RJ+r@qN0rN1^s>~SN+i5!ibCm5~ws`TjV-Gb17g7ck$+7BgJ%76WPpG5a@#WaNL zm2Ny&Yel0}nb+JcO)HpZu<*OCG$86BtTY(|2KS8N&BPTr7IzaAOTeH5ro1pp=aRy$ z-Fd*J1aVJHv`JEg9$2dgzPorXd$kG&|4yUdV~*(w;$HplAuJ?*u!1{KX`0_}spX3!|7kS@V@*ox2-4q#J-n=qNh)m3i|1{E=2l z4uz>UT6a#>MdWce!`!9!b!~@^BTci1KL!X|0f`;wJ?P;%J)mvBoX}lYc2s|AatW+4 z+ggTA==K2&p2+>&WTtn8Lt93On2vlKG#cPq86+ zC7wV&%Fa?ymX{kQ@WQmE>xmHvnQNLWL1q}4mGSS0#}(u8+$0Ws!r)D*DBQ?TjK<&o z#`geQvbxJCQer584Y~jR0%K>o&eIw?P8?y){#MknlVPQbT=X`D;1fqukH5? z;p^&NB#K*O-#MvTkR)(bxGj;Y6==}ixit|-I}TBj=wo1eQ+(tVT)!Hw>^(H^_X1*W z#@@BlIb>d+xCcr>q!@Zs)5c_Li2vxHhb%+mI^Z0U25pBSo$Zz2J9*ZwFjo zXXFkir)JzL>vgQJS1=(Bc~fq=bDab~t)Z!lDC!lTwSfRlbODf;I|Xd~Y>PYFMPtGF zO%UX|2}2}&Fu>7SWOnT0G?5BTt!zhgzYUw_K)FpQa6vhT8oByT;9_+~xy?pmz%E^l zgYD{6i@{-YBBTAQ+`p~$d%T>vKDKK#?c%+!qXxffSC{v}CLQ-X9gC}^Po?p9acf!f%P_1 zsjvCgW0gPFRdv3?6#YrtQ(fImIqGbh3})FcHlV%>dc(r;Q2#H`A1K5%x7-C&ds!>x z>hVa{FEtmdG<|~m?Trlr;WhiRL)yE~+yuHV=xjc>z+=oR>Os4hYVENUj60gd$^^L0 z+s!>FXr37``*X)^ON;;mxpu$Ly<$P$2Wi`wx*g=Mq$d9iq!ghiE{_S@hR33N(>xL1 z7~+OL4jy(_F;+PMRV|Q2MXG!r0Dffuc`&ceGEP?0k@#$Q`4PvWAy6EA#ZOK0_juMr{{Z``;8h}6 zEUQbNlc7g->K0i}QQU!4#6=Zy1^Z>LjL=VRa#8&%Pm8QFG(?E4aE1 zoy#t$q7#~wAINkG%8&TAJ3-5|F?rXB>pseVG%fl6KXF?Jh<8_xM?-Vh#Ym5A1dfB+)Y(=z}%S@O)@%u!C;;@oN3Y64qp)!IOyhgGf8OJ3& z=o_*#ZkAL$-&nw%NoCaB&;&Kwc(~F7?{V{1zGXDeRfNwVaT@%-jokbT-C~iqXXA(D z=S6{YUOk7Y?`6nqxcgHz2ev8s0pB{r(f-Qh!JrxiY}C|0%IYoTP$|AuO{(aums98b zC5qBQDO6!QZ|@U1Lvp1e4_QcLHJs1tM4$gtoEas>b<-tq>LafhTPan8EL)x+PZ^^7 zCZ3T8nYA=SbokEy8`tKzV9Mi9oOLu!f<}9RDg>9+m%E>8QrxUk?DOFv3hvOc6U&ok z^3wq+33ZSC_S_|F#N_AlK zy2b?GKY7vF!X&7D2Y`8Y3*k4j)M`MYyD$qEvy!Zc;CD=ph4x zkuyrZ-&G422ps||&ju*xJEB(>`8QVSpl%!aFQT1zGkr_nkP0$HPGJFi>G;9qz-Gwp z{BoV&hQ!oO8C4M_JJuc<6CfD^y^d5Lu;`e1(($;H4h`eoA7*jZ>@2rkO;hcYCwRuh zQI1s6FnJrK;C7~l5ZzB~NgMsm-|+3~g5&|79>IKkf?K<0UBq2AR9+6V5tG=_#T>`X zR+23)#{mUq%24+vaG7wG-B5TalWr_zjPeG;jZa0>jyoiQZy&+S)z=OlUFlO9*Rpo0 zpy?Y4TmrAt0jg~=dVNTz0;PxwwU=^hNBAHXLfiZ+=7!m*g5_J^`K=pLOM(YSYmC_N z!#KiLC+Ul2`(4FAp>Yj80)0&TtY%c@EJ=b^_9iCy(FLQ=`-mt52sD|)XA6i~+6=RM z`NaZC6&YtJ-lxU(VcUp+kRLh$88(gOG#9b$bFB_6V38=qzVwn8hDyrx^x3Vr7r+SD ztsLe1q~2DgU@~+3t7=-Vr`iE_plgqExIIhOCl@DLUSmr&@qY5=u&$7rp9gTbRQF*O zL!FaH45J7CvG~KZy!E%-7U7^;1$(&fv)^Y{_~}T9sX>LUX*LxTl44LYcrU2DT`5ZL z9;oKuPDU4B#j=<9$7cR#2jcU&|2)*jiVuGeW|x<`ROC1G{BKnX60>s8Oo5Fa&&z%w zaLDmSI=U31MhMUFiRhHj;*PHe6C!zPg0v{XzXRv>NbhJAiysideU0G3ShhMWElA|Y zGHK;t^pY_6-t1t~sv={a_IzsRTc`7!)ktm1fo!O7zwcMzIy@xUuf&v z10wz?kw@w;W3$P@A~!SZC-rQl0WlK ztDRS@bnSTB?jAFc=0DQ%FXAuaFo;XhbmS;R9WI93eoS|Xzi+IIU8ehShe;uQv?OMa zDYbm*oJuQky#hUL7s1-tPA4_xP$sCUO2u16lORNFBDqG$-vysl*34bX;IeiXL@9uA zCcEhT*if)AFWxPRwkdP?hLxqt zd7hkGDiYUe|CEhWmgIYy>P|{(txp)U*FSj%CXD99r|#^H=xq>;1ugHsFhsE?rV)e9|7KLD5z4c~cX^qUfE7 zL9!$WQ(wXX74?VTeHUQos99{5V7B~2(>~AiM1dRbB7AYED{L9TqDIl_atbdMBgC$= zsn6#jf5^M#8!$+*sBs`IUz)LwNfZ{jDorZ&^b+Un_c#ecKoz3$l)fsan)e?hyLj|} zs<#*8?qox4FOk1|x1Q?g%`-WXp><{_^tt;_MJONVb>N9jC%WilxJkS!YKg~N>Ipzy&>OJ%@go*B-Z`Pq$fEGH~%>Kw#3$43{ql?48iTr-j+|^4#872qTgw&J~4-MeP?@uqjYv zY}qDVW{HowFVSYO+4}uoN=BMSM!e(ERFGA?q)Ow5(DaGNFjEuE#it96@^c3B!CXgo z-9yQUR}5_XPv41lZ-;LJ8Hf3bg42M%uf0?bS&-O$nOjN7RkSGx)M&J(PG#N0c}YHjcNobjHGT)w zGuP*vAjNqAH!gZi!e3pYKZ)x>!8?%qtTVGU(W+QTBDeR;SfFA>(X#GE|!eOEKb>b{Tq7p4NBwQm}q~f5HP%tLj ztk$npHQe%`14kE|xZ3<;WxyZ5hajloZFi>JH0Rr$Y~ zxfK8O!Y)lz-6iw>;cVPq91~SRytciLSN7(io}t4mm}@ofS_V9I5Cc0~`EbD1SMb_o z-Nyif4UiQsBj2*o`jGw0$+D+`Y^RTCfvWx@KhrS(+7u-;hZ%w1v7JRbvn_R1-5AX` z$@%+Rjmu|VPr9fb62#M)hN{`i`UK1yKoJB^&hn;yduA;a-Uw~)@yz6+Fv7;_oY7vQ z8DI+;o8tu$DES~@F~ncVTUs1%N#XdxnA zu+4A4l66BV194%QZ#o7Fy;&(61WHGkl@G^7N473lMzvabH&=4L&&Fv`07RfELb-$}v={z+6pfn+eLzI~)ovVPO&|f{7rIqV9iM^$o#UaQW;BUO`}oG6qRM-YnXUgJ z?q8G{mKU79x$z*L8MI=mkZ0dgWW?aSxZkE_kNTaCig)c(9CH_#YRfKu={g#FZK~Bd zkknmM3_1>aqd85u`_V>i$Dx&xR+6zsCO)3E#kCHkJMSIB z!Lg(d-~Mp#?>8;zL!=8aNyZSL&;*r$2^ueNP&S+UrMYPMNfc{>*W1c6XfQVBdmm4L zZj_C2U?)IXQhKXsu9SC_QoXz0v_~|Z>6!&-$MaI*Rv9QU=Z(cePcn&SLd9iPA(WuP zpKFA?kqE_SWyMo?S0okiE#pl+PaJ)`AffgZx0r_2)>S8om7#JHd;reGYFxL(%!Lgd z^NaP`_6df-1$->?p3ylBKmkteMmgBSd)7lJ+B~W}?ncZ%*E-5exj?>9A`^g4O(*TBP6l9+E2d~7o%MxnS#A?!Fdaj8DwjgUIr_{nja0_MJtK&r6 z{-+NA52k9W<^9u>t+%p1t}R?74D{1-ApjdcQ& zb0B&74dR=$WiJ}TtMA)WDlTqFgm<6SLf1Blh0i?93g2OxaNOdSfv-n@F8edc7iYOX z0h=zDdEW5*+N2({5y*UF)-O4J`?SlC!(6@7#Flu0y?JIF)!@IF`2;Vg>CniD1hEvM z`eJr(rtlI6-lfwe6zP~iE~h1i$bD>qsB+5spW&66U1Ncwt8P#9mwE`?XFv6qpt?M6 zE8KF~GOR-uR&7n=t#amQ%#_0`q^8&Zd)l(ZGtP=HX|gE%${5;6K`7IwB8Id8pWzfY z(*+{lY`7c-i-~YXOm>R>Q3Q142S}@$VCkI6%i29<-6l3IJ!^-!d3jT8 zcrcrVHIDBHaTfzT9(NNCUb+U=y%D@~PV0Rgd4Ha_-jgm|s|}0x zD8)2Mt<+ZWP_>iT!(pEE1(FiBCNb@H4+h$2yJozHeKsS~jxC zRz|F)y46iF7#3Ho(L&8uY%)f)Y17?B#rnH2F6q)`xAGrnI*vj>1SfYgoIu@L4q=KU z!bC&(*!-Qn!xP;jJOKu6kovK2<=05=^0m@ZfPv6Tt`#lM=Kv|JxtN{9|Lqr6GJJ*q zq<10~6sf#dLKvEQ*+o3r!al!LDr2te#>Kh8aXXQj#JN zerb?hCTUJ6P@O?3-My}A*I8Q#1_0ZMe)YryMAF}EuFI$r%#DC;>Q2lQbWVjYk4>+^}1 z8Bq0zd6;X(Oxg||?*53v{x|LuK`s-cTkQjVqt-GI4g-<|0hotQz^pVP%=c!2JYi#IPQ{U;~$4EEt z9Rk|gT9QBe$xPMo*~C)rpi5R^Cyq-aI`uQq#VgM;_A0fnf^**fXBI8SePdDJi~nuT zzVKESfoEZIT;6OSri7bK=lZN4R0wZCwC|_6q?ffiAkFtcS<$uev)=qD#Rbi}AzLMy z?T>}0ab2GxavK3kyvW}nOdG`hkur>_laQUyhrSZ4z|~4wyv^y?GWGfo%sm(V3=F;g3Wwb*>sXD1G_;zC zh2n43&tC%jMwFyod_V~;^PNM9kwT^#sZ+z#pT$`Gko|lw6b2d4gU8{pbeyvxDI3XY z=8~88rS#5YC0?~ZFaqEFKf2fX^D8xjgt0!9mhMzn`SSz8?%9Z%-?yj}PypVE(_SA0 zFP6Dx3e{N%>D$Ki+K}&LW3qk$upMlt)N%cG58v!#*3XlW<6F&CJXI=B8xG(D+Sr>X ze{<=ohiScm^J`qrChK#?@hQhUv|9h${qBXd^xb)WHCMnRI?nP4(NXhrh@U^kl>L3( z3TU)^5!(jPbSzcQ*4$j4C}i1=6|c*^bv@$3Unk0I?A4E&uxRwu&HCejGGmU@BF-djG0X@9Q~Z>X9|am zp2Q~xPL(P9ilhGO`&*=*ijDfNUun?IZ{JEnWF9rS1%E-aSCvt4GZ z{yrfMREuZ$*L;iZ_l^~Gg*|RmnfZ;W%$`*?UiNe`cW8Dh4I`p4U{~!lZG$#G;2=Ba zYOZ_CCL=e3(VV(Ea$bAB01%UnLc|phG$-O4DWBE~rwOaMlzbEf)d|R=i{fH97wC!q zA4z8iTZk00BJ9}|HGI1XbZi#=lq~StLK4=7FoND4+o0egA;;ggwER9swoMOc7izH@ zaXaqw)PaqB35B9IS3KLM@?V1Qev@0+HI8xTs~BxJMPD=hqD=u}hQn|vP-&|?C}BTX z+>#*eGuM-Tgis}~@GC*2wo~1uCX)<{2D9^MR_VRHeh%WINCVKAXpH0ltCf{YP-rkMxa;|?!V0CL4G{vJwcFNtKnIb?wUNj4v$ z_i~qRR{&NhJuPV-5L+j55%0i+S)ANq3cN`P3 z@&N#d*8`_Ld(W{K8Qih*hnP3i7#t)R6u86f0{ZC%-C>%n(nuX%;7ZFkFbUsg=1M}*q*kibnvo^92#Y22CgLxX#Syuu7d=0q>Zp0;s}(LY$m%v zt~4Kl$2*JzK8{W5hQzWbdu}I6A$@lM$}yoj&(3GQP!;*MUR3qMmA`HW zl${B<#p_mhNkFfe>hZjL3VZFrD7XYaJxDIyxxwLRxq)cJ<|(}*Z?{S zsZam}+MrAkA6EoBA~`7m;GQd|8o1ZGT?o(#gZS-YANlexAf0D+1B1h%i%FIyq3-Yu z2LI>>eSQ9F=kgS@f`B%Y%jwjnb8r;75yFeP(2^@v1oO>2ZnT<@Q+PEkv%aY|8%-Ua z0>&*Gw>CxePr$EO+Z#cMd2!IuZz!LLf)}Nzgkl{q*=MvfE|!xiz>N3Oqi3~~;@sd^ zppma|-uC{v$uiqpx&YWHg>Od>LN|ry$(wi?y`0AG6agG*nRWgEtk}x{Sl!9|gtV{e zK$2E$2d!igBRzk?bN=Y0H-+CBEEhoaudn`H zOs1_Ci_4dYN{~4gvj6iKafp#`HeKns1LhR0fgab{(g=pXq|z^Exh*pW=?UqZ69g-J$10mmj%o=c_AVQ%X#$%snMC*s9}_ zVHny7N}24BcO~{!AX0nt^Ba+IUY@vDr|F(8#3^u1>{_$$_=KR+C~Hb` z4}!1Wa09edJ;XsygiUn@WI7)mH=Ra_`Z+5?5wXXF7aivxk32FaE&oS*ReVbTV!~qR zyl^}6;i?*;4CCqE9bQ$C+YrtoW}23~i!=z?c78j+x7(Y<2HRg+Iwmh+T13$b_!>EA z?qjQv11FUFoCaMpgRX*)+mZ<^Bmc|2g!uiHlM{#C5#*SUhjy zoEL2+QDy{H0EKCW$m#T`YV81k~7< zBJ4T@eP;|T&yDMs`Xfn8W^-d)?E=Rx1C}&j7Y@%BN3(j;NiaOG-kwn9yRrld8ygl zE&M{qT3D>c#r?E}Pn}P$`cTJUI_E-)KDjR}5G`&iXb0p2f&x^tG!RwO#781e? zH8M*i;B{p@_JVn$3J(WFEg8@UrW8`4mq>#sML+V#u}wY~QgKc+VFgx*8U2Md_OuF; z$8oa6U0&>^MyojCXPM^_!a02W2*|+tk;EcFBHTKDo6r&ms|= zOFZyDF!WwnY8TqP0sPd_hNE`n!8_U#O{O$vIA@Q{_0Y{fe5jNk3xU93)$dHc{`VTJ z$dA#+}G$no4xKNgCjc5M`c3Xo&ZGmm& zm_l1+^NFQy4_-hxTtclAi%73U8+B)q1OLq*ZT>*+z|GE_Ci9>KvHUZ+>KsZBscwn~ z*)IbNuCLY?(}&;<0XRSi_q(d^#kJJ~n#Gos(j5g8WhHY`ZNa!y#&10|O?z*=@{3}z zTU=uH7mSVsm$#Z{uUtu%xy2yT9RJ+CGhABl^w7C!O-Rn6-IUL!1s&@pW{^TNh?LuV z?Xkqjed<#YAQPU%cvWfc5i6lTnDG#5Yw93Emg*Jhp*qt)oJ?(HOXcZl`|fe=vG12q6sHoT-=^0 zN6h3PtoQ5tme{%~h{SKQWG_?S>Z{LXyXV$_#&^;aWxx3t2BFH>%x(?T3cqa27cFT# z%=1IeN(xQWc< zRkHK@TqC@BcnRH#7spy$lh}Q>zsDd+?qS7TV{Z+5C)WZ=L!S(zRV19wzekt3xK@26 zMg_HmcMPI$p?o23=Nr4%*bc~jndmMu%7*s5Ek3I8s`^fz~_Io?CF+v;$Fb;+LKlmY*gWIP<(+8|^G!HzA{hRd1)PrmKCa?sRHpD`m5lyNV^?&#Bq@nQY%rpaR@oFUt zoPE2D(KFQ}%5VF88muaIJ;Po#5t7pf^37UHS=qT%-ChWYGr4#O-K;M!CW2;LVp*aI zB3&wGUi{&&=9n8E)gqdK$4n!+R}bSZh;XJ=!3M}z(qbnE4p4F40eg`74c}n7SGkq9 zz;$X~i}mou7MHeW*_qgDXk(mG)*^HIjDngP1e!#MN&|Zrg^e7$o|?m&y?X8N^}LUh#k(D>19$=tq&( znZEU^8qU)21hRB^)E(q*br{`prX4CTTou42I<8XG5As+%P#{wUi64qj#iy%uoib8@ zE8&iw*mVZC{-fgWie7#+smW*KtNB-4ec(s7c# zlNOC#1fUf~rLjOX3rSvPW2z7kz+V@u4{{ zzjn*8k604fn}kjHpJNkY!e~tCB|;XgXf{D$9K^C}7CGExPh>ZMlhD!haSp@e7$s<0 zLY1S~w@fQjb_-O1y_p_`kXykb_WG5+3~7fyxzR6Ai~nq{lfarIvTo9=&85Ufy19IZ zri-ciS~( zsBGpVO#@l?f;3EwYXFuzEW}0rG$AH~^P*R#2Tq}fb^rztG0B!Fi=O@)gnR)K!tq(G zme^jbm_=fObKypSjF>3myqqe^FZ z(uqf>{D1+|JWo2_-h& z0r@LV=^`2k9Qv+2Q@_Jkr&@2edmPq0043#?6TV?Hyif83< zpYD}2Ucef*X`7VYcM1fp0>cZ}R@=~jhpKeH@HmIu7PQA0vow0SR!doG;DGZSK-40sSl?-QEd*T#9Fs9hGUu_>&ID$c|VFX=@ z98|qJ8V>*CSd9;kVD3`tHO!i|H@pG&V7Ug&Ne%rX?S$lTWf`*4Tk>*119 zNxI^Aq&U~E9lOv2WJ442zCCKsQCI8jnP4dFEUkI^R07N{)7R%5Yn8)25f@)?+Z7Kh z>v08tt>v7$rlM9k`UBZvE1i=;e}v=nDzmRR+8xvm;mLv=GmD%dw+nEMVx-K}jvy@d z5C*lv%u_I<8|5;>PZZErRG|cg@6qAAu!k9D6f&(lBbI`p)Yx-T!5f<6r-X6pm>i2h z%4t(~q1?9kQ9vY+B)j?tw#p1<>$Mwet_s;$yj_%#W7zA&{P zn60(SqCWa)igp=ey{XMe0?LW8EOsBUB^S?UBZgJc4L}Jme+q(ybV^X?GDVBa{?6vI zk#1RDe=MCTSPGq}Id!PiFa78gpL4k=c%;YPS;#E+EOR!mX+Zc!;y=}r1 zm~L8+xTA3FAkHn1^yIj&DkfmHKshjY!2=1(obqcQxh)M1PlW;sF%9mS=Vx9U|G@aMTaT`R%c!fUJ1TVSi!J&K{5-)dS$`LOa0KJK^Y+=ZSI((e8O)>he&#K36p!I>&T6a1GbK+mm+DzqQQ!Z$}IfteE=yi&0$ zhh4mNaw%~?p?uU#&VWwI9VTM3%{)%xwT#%Ea%^^{eHSt`aN1C;-4!a)^>dZO$gHPp z@~!uKAmU6mCRrgdqNn(x^6l0u%4X~_weZp0&ZPgkALq)evE5`;kHWJ=onHeW|SXW45Lf^`SQ^GXSlC10o8@Q1siETYh#g z7|_)xBg2+sXCQ#8yP78pR?#frSs>D;PCZjQ$)#^LQS3qWIST@Rxn-8qP&V%e01#HXd4Q5 zT8=3P4G)tQ8Zn6Vz^VMnSEkg$$a@n52lrbxz_&tUg_3N*5fOf;4QqitTUs&+wPpO4 zrl?oCj|Npv)gyiX8w77ex(vG;?!B?qpL`QU{;YPfJ?GI63CNXgvKuHCAL?Lgntcns zk2U@zStw7_-h(i?WmS3^>*<9;Us{AsW;C$6XZONCZrPOV*hE2IMhxCXBC7J1UFfY8 z3pCI+Za-Abcg^E1V2!L4(Nm5%od9;9SK{Mou*Xq*Lf(?eXty%Xb91DT<|#vEa1PD^ zD}v?unXI*B6&QL2dHRb>^XI$fF>Ox)q1`>$o=vPExsQ}Ieid)s?CyP8$+_EYoV>nA zsi+@LN9P#vHc-V}GG;o7E*gRZ;)obFL+RGaAK(M|PL%L$9@CyT@5c~4hVOT7>&B(! zJhr+o1Ai3tF0gGsk!eT^)6Lr904L0~2YX#bDb{~($+*$e6%QP(e|~RX`^EslZt>1z zj2`3`IkNb}Sr&4od~0G3Xl!$DjI7JCGX}ANEw>*ba<9Ph3+-Bn?c9duRj~nsooB&3 zQ0Ck23DvB?XBl_F^`Lp|XJKV2aRGyX~YS?$nPjGM_~8vt-!!zbO6vMiIZ zOrA||-uE>xMdxO9&O8S1HFX-wg)JFuJ9e z2q#{lAg;xoaR)N7uI>d1VGcpKR%RV}?bfFu=MqA9 zuPz{Jc9}PfDzW51de(ti?mNTe4UA3F8I`(ukN|=|)-4L71Qy)cDCt0-U0q0!2zZ5P zl|sH6NsLzuHU}_m1d=O8v>4{35D8m|)SJ-=&$ueCv8Z{MbM zXzjDL%Y~Q@US1CqPJ*99V4NsRUm_0n5w%R&2Jg5Gp0a**;S~G+Q7U~FtV}W^*}2}> z(l;K@=Y4^|5ekReeE<4SpyvFSk=Yi}p0h_I8$4?is^&{|J-+&yJgQGtpoUpzW$E0^ zM$q?g;d*K?q#JH*)|f4b?#npf*WY80PwV=j;TL9h><(0tk^YZw`xP2IX8l`$s;v?G z4_x?|hj)&R!rWXbTj&$bIyn6i$NSFy^a09Id1#DpWtHiXFy_ZKFXkw^Z))3sUeqnP z-Sel~BARArv=fhFAUJsEGW4(_o6se0IKb9Z>ml1i?xT3lLf-4_x2zXqIcQQ1bbQlG8CR>b48NBGyU0VKQsU5aUzt43QW_d{YF1-aZ9X`sU|W z{c<;^>yA1$QS~IGe1H=LEny|7haK4y_(zV9uq)`E5n2XX$@P+F@r84-f8|wG>d_SJ^NvEECMEL1@Ne&N}W^aK|Jw{7uWEg z$SGBJT>L$q#jYjI^@(n|yyHj&@Hl(4dqwgK7rc#(ol_p3_XE?)bqwA@OT9(~ znzcCLg6GW(3q;l)GFgQqI_z}!`&7>al+%M`Xu_60UQfQB3b%{r<7D=}bpf4!;atPX zIaT^66+eOhV^)wQUUhfCJ->*NLBeCAqEV&d9KfgFH#o)6Ppd;#Kl-u)Ux5^SqBrBJ zqP*e`S3$p0v;1f6>;4Yy%$WR!QQR@41TSPg&M!?y;1Qur42caHq0+iEAw5%qL_R#3vY-GNA#R@%$`i0t^h) z<}6B(PdgSzYvvGkbd9f1)DO+PIj;7?5(<}CodpMfzx2}asx15XLi-*%4W)^S&xV33 zE{OhV(E4%y9MKL8DT+p%D6I(F+u(-Xnhl5?O_tItqXFpx!JEay9WEJjxw%;#2dwAF zTAeqH3uiXJ-S9F8vOrn<%>`)W0A60}{etr#S$KAQeqn!#moGJ*{_Y9RN9Qn~u9IY+ zk=M@88eN`>HVpzGK|zk`*T2+R_2%qfGtl>0Zw5ixutN7lN?ID-awSIvge(zpbYC${ zpGYV1Ib#$kl5d6^y9;)7#;LZcOZ=3JMqc(gRq=YUUd)Uec2V39>wWm*OlU zy(2e?Un9RtZByGKF;O#0objOzgz-_tx51B(C6j0L741*+NLig`?sTVqi}EAc_JB1? z-HIv!QuXh{ntwu35On))tBEC~@+97f%ai9Q->Tv_t>i%sd%<|ls$0~9tGg?Xwg=j% zfG&OZL@`^9$5DW8CS3$+0zr<(_R*$DfU5ueFz=0>o^o9GaLa}atT%uA-S{CVel!d) zZDxm<%e`D8Aa!6GNFZV~>gT^R)}$itu6R8E`h!KL%G^=r=JtkASzxmNeY6Z>>#xi9 z0nc&K37#hl+v!`BbYTW;g;P8q9X5w6Gn)NK=<uz$IUFMUH1wf6Z! z9Q@kzgF?Kz|Dv*YU3HyHrY48KSOWgGVCv;?`KM|NWzNH79J@}h-8d{n-Z%OU%6710 zb1ee(F84Ly>R;KwL6a>tVI1Bwq+<-m zX$@^N7Y|KnuOiW4a@sq6roE9VK*dOa;fbn|{if z5WUivl;37$zADaZ6-;yXwXOTFJF+fs0Vn%UZPMh|5aA> z`bCQ_`u(wIaQB)=EQLe%_MYiN=?{LeyNAFZCCrRH%3?Y!{y3_rV|ZdHY82o~&F zC0|Z_uKL}s*1s?`ZUG``GNf>We2MK<#Xo)qM$O5y4&Zz;6eZV(gcPu2gOAg{;qpFh9tUst^=RU#vn64w z^CpW4b<=QaRI0^?*Nm9XjSKuF2q+o`!p>+Bzaite7%6$8_sWFFzD~C<(7pHZq#-s; z=(a10=|m?G7`8vk`e(9J#2YlWqQb`|%)M7NOQ>L(c|olu?jdTDz}hFhg?!P;X8%cL z-f?3+>(=t-B&_91irihjxiB#PF!;4f_qy>$e{cPSf{p z?~;YyZd&&5!W{t_d0W{zTiC-o5jX0riHWmNLBCAogkNC^sEvFETZVt z4pWLnQR1*GrFZ~|4YG;Vq!lY(!7lzrbvbLK%YZ>GIw59+wDA+Jw-8RrpejvZJVpfA z8s_!AJuQ5-C&^wO#=r*3!(HdC)~0iN3~LwC-M zyQQ&{JJ<`IcbG1`ZmL=|8YD>;0iuQg*aoh8V!K4t0|E#Y zTC4y$PU{%}saT;U1?)w*{k@xD(tdL=#xbH&n}_$;)S+H#@n=fV1>i-I1<5%09l z$A!6cM!|(&lmgvG@cLojEk^Ey>{vO(TkF=#qJ--6*I(QFum7bRUqBCyDpB+d-tIWQ zms3898z1NZ$Zn8-r~DKHoO{nxue& z;JjX{uo8IKIueZ^eWm#v>s4D>`FkGh)rYwDyMBdAS_%3gMA?XzKUb)LP_Xq{LV;N6 ztxYn!1Nb*Eb%GD!0*>X}@slz|s#JlgOnblz$tc)u>E`p(~#-*@G5q7QEC;G;D71RTlpM4^ZdrSLb~_`x zM@rCJd|tfFBU7!pgY?%_q-Ow^o+t12m{Rrzk3uwpu+cc;7^~gIRotvyx4-o=nsg_7 zBmT=5&l}bb#|nTR5kRXO;KvV0<09X)K@(KDX1Zhd02{idv>S~6(PrS9vPWO)C?6ph z=)-*_C82Un^BaJHl_4RAuOmd%^R@i^s&u)|{dFWp@fl7mziMKkBG16KF)el+L(Qfmrd;@F8|%61H{=`g?W!gQrKTSCqmhzP8r$V#EzOB;0nkvs z9-=K9qU(<=P*J0<&`ys??eR%mwe@Q1S$>E@n&7UjksFG@0MS=6$E;h=_N>GH-$>nv z{VHdrN+=-_&8h}IG!kfFL9(+XmqE&1VB}41vjR?|J6YRL#Na|2ZD5WEqJYm=Cy1-t<=HUc^IU$A+wUQ+^%oM)KBmpcTFPK>`NGJVHKbat7Y&xSp?w6% zT%4I@;qFRKgYR@d!Ww&OsJJo}w7+)UYNaBdAgf*~pIfS+bUDi-h*gv%ymv8VU#KE2 z7Zr6`%RsVXSsHm@1x}KNy}0ED{3Z1TxlpjdpRz8?qVurpxhNCs`y_t|qc@!O(z3QF zU+d5`UfzcQw`ce|HTFWQ@RUb4U>Q2#PT})ML})nO#4A)m^kb5_jtXWASf$t|cY{|5 zblfiW(huXSC>W8zM78t9vF;x1DTVsn04y||CX@gI{=#8Fs6)w}mR&i(t-|B98ZDX3 zlF!iua}_S(i#U6@QtBBDL0xcl?|gIAa(w%dyjhRwU)u&C&lJAV4Crq;?)-R7e?gVM zw?b}oV8H)5w9(_j1itY@)civhecrgbJ5XP(lfdTh=WCgaDa2L<3{b#q zqztdqSZ&vQu8giGf?1P^;g_A$U~TCLv_%$|Y%x9*8Sb-b~Vo#VL{-laszZ`smoMfI1?7pXKvw{NuUTlMD_BUt=B_lH{L)Kv|dEl^qC8h{Z`YZM2gXOqRcH*sFkddQ%j za`FH&1xm3bEF?`W_;!;U!GoAe64RgYFh9UaKLePqx8VYSKoQEa&1X~fNN|s^mBb~z zBr4;LDV3Te4S2@GJk)OaL0)*QMkcU@XoUS+JM5(Sz<1l3J|!>IQPtRm`Qvgi>e|Do zGI1*{63@QsQ3HDhY?1e7Xk$MyA?sUw4um3ETDJ|BNX=H{4bz536b53sMBAsiC?QIoG-te>21NLy|I zJxq*t2Q)G;fy@kWa18Dmu+DX@73lZA-{;RanT%QKfx4$?+ttu(au7TPk!L$!+?oFb*k6Z zwCNTuPDKfwkHYEhg_8-758AbWIxIP^VHR|%q&?lG@Y$vlDof(h_(KU4$f@3Tim$-@ zUWWD1P;;JYJ$0hX$7(pa#ehEehhpsg_yXF3@r`SM0;bc2&lw8kN!8=gGAUT3Rv5X{ z-|Je?cn?Rf zW;1!$p4&VU4PO;;D3N*IeznWQ*Am3?!YJKH&W6%dJWQWD3y77FNA}F1IJv2kC3eYN zeM3TdPCvVViPI@i$z;&|D~Stx97=?_h0l!tL&s+|BW`8bCXcxO(Iq^MM-t0EXU?1x z&pV+Pb4P2L6LCL@h1^$~$4z7-Aj7qH0%ic7JU4WB9;dtzngEj+QL(S)IPeu}xNWQ0b)d;Kgj8VfchELJ-o?<;%?09RN1hl6k;&xX2NaiN zCl)1F!w!V71h|a((YxE%yTJh}#flxay1`z_6+Px?rnbwmX)Dy>zuJ^GGNh7d&jED_ zM#C^bsmq_#gU0Z(0>+OtO%DSRzaL*POC3N`rq5XXw1seHLC`>g24_|$GP-I|T{=CH zf7iog_9RL7kFCWKMfaOcVTl(g&!3`s=BrE_Fn3Vt0N!^mrjM=?IGawx|Kg8ux7b>D z=!6vCZm$QAEb~H1^u?`hs8MYGP0Bz&4X5Myve>XtI<Pkq)|>*iFc8>8ynr=1kj zea#9h2M`JOMVK0KJP#jZXtrZl^s2GziBQgJu*rknd#yM`}9y)V&s zv~!xZpX2fW=^n+)p}|Vr zCNaKH4~5Ue=`vooXbEHksefXh|Ek_($$dYQe0-zTbmITf)wK`7&hSCD>5CH@)WL;B z;4Ya`NIZwW%fVGf;QX{_lhU*NBY7|4Gy?mBh=8yRV?$|eSzs*zsv67%vy>w}AS@-b z5|PpR)Bc#F^!!+s)z&d0XC)^uJ*Bc{op_oAe!QX44?6PsSGXlRVa2~j6}~HR_L+QFp+&YDVnH#%Uh0)g9pGaB!_T-x zfMKRt2vL^bXrNezMd_-{(sY>AQu>`xE$k1=96B0eK>rgm&IfZ~gdEx7vN2I!lb$@2 z61a*4KeAs{kJ!Uw-O%4VR@YIpFg3SPKcME|)_a(WJ6SL%YsBtG4;t7nNY`NL8ItUo z)Q}vLek(j9YUEuid|q)E%#oy$8;5w`p)j=)GO4Ehmlf=yFxyk z<-mi**3Tqcpbcm&By&fWBz#ST?n7wql45+$_NVc+jJLQbdsPzY;`6SYrcS=_@MPaj z9%HVD90*q#kRmkRjKJ+*Br7(fm-*BI36!bPAP1g2q`!`QTOl!Vwy)ZUE3U*bN64GT z9L8yz8rl1)(PbRJ88nCx zQ#c!&%!5*{#0}~9K^1^vO!chgF$SLHZ_qf9?q<2+Lagx=xT7-a2%x-2dYkn;qP_}f zjiDIO%S>8*_(o^xK z>l~x&_p@bMB_!#OVHScU=m=Ke{i7~QG^XAga zYP*TaXy+y|oacg0<`fYv1;85o$)rh1>zr2MNIZaG<83+m!!(b6hwwf2>5jdflTV70 zJJ1~8bg7nzfbcya2)VFk<>jMGy$Y7JHki;h7WM zit=477eeqt}TPaJ&<}oroPzTL_{P&m?sq zu~jP{^RTnkYvoDg+rQ3ikRA9&O$wp#XHmfejTrPG?Bz0j8^T_YN&uh+(MqVA5n_}> zD;^imdS|CzDMVu_AB}#>1-&6I=VY+iGE2N~(JA%LgfTP0rB_jX;O@~$-8-Ycx%cL` z+?pN=s~xcCmR#5D6+yP`$x}v-jPcP+HaLk;S&?P z?H&c1426Y`Z!A`fLaPoT#0O#Fd^dhRDswH$!9oFMnhzY@i=p7?<0{g4nhKPnfszm! zN4+vFMrWA~(Ni4X;%i6WU`dYi&$23|#7@yq(k#Wm!oICa4iL=M+gVGFd*o(mMFWX6 zkP>tG9k#KpJ8T;Gkw+c^=~>M29h*CD@|U!IADuOo(BBI7Z%qd|O~swjC5iw&xnWc8 zQ>ihQ4TCo6&JP-XT)i;$FuZwkgt^`@gZ+0Q*SSWprBMvop1t!2QeXW14)*jC=TXwO z)%F{pynYhP`LUBuhf-j>{nC>sOvPlvmlwGM=7mPKu0ku4_GU&ZXohoqpDrdzNSIyU z`k3JkH4?b?LOpA~EO$f=k!=@>Qr4Dv(x^%6LN}JV#A5430**xKlat{xQ?qS$Gq%ro zz97QL@&LzeZ9?|3-9aV89&jH zoo*^i<)rPjdHc|Qw=6zV>#~i{scCK4bSdVZ*(wHl6E^UbiL3)L591dWj4<0OddDhc zPtXdkeVvDJmbwD|M~l0d=$t=)yyJ#;o&=i964mPC@~G^$RN*^Ns`3{T zc2H~r2rBlIhsomz?yZ(Kz0Mt;oEP;vRQI6)v--dki)mHDD_M19bc88m6d6edcO?5B zx6Van8-#6kZ58d3gu}!|OB_whe>V8aD3&sPCdVDY z-BTogG||voqxlcFjlp`Plw0HBS=bbV0Oz&Q%xthBFos|4HI(1LF^Q9`kX{x81-x=qrF_4LK$axI`*K1@BMgh`ia_cnWHg>@3KAsVrMya z<;B1nGTzuPkD%WcE8CilE2M$iua6~;)c3I&s&W7nDx0TD?^K%e!J2ht-{czN;tn7^ znBwg0Goqw6&P#BC5$puC;{xOi^lGDP9bHk*wPC>NVB3#yeP~a}QA8kc1ZueI*=_&& zVG*#b8w}z=SIXJm+p(tJFaV9p>+=&jef6&P3oOpenN)Q5ZZT4DEJWXCrdz(L!1P^y zx{oPsN|_y!$G;eHe#wcFJ223P;6yKTg zEq!B8!9=DaKyV<(8XeTVpVLfi9{nDp@gjw%1z+^80XpcNEyrR>GcUaQQRVQYkr97y zw;!8JC8k0WDidA}a7x&bwa{M-a($_h1!XuuR{`|Lq)m{ClzoKnhjZo; z>sEQj{@?Bp-=mnEyAmN-sNh9`Chw|D}^{jxYIU#OvRw8GnI@f>^IMus>g{j~kp4 z?<43<3yQ*I-sHIe;$oLJ%2BrSIwEwyDtW+5cA8}9ek=TMud3vlriGpb!~1#?xVIFH z58WV2#M%a04l9c*HZyMb@6a5zaiVZBvi2fZ3r{RIL4&mLuH#Cm zDrpm&EQVz+HjV=(`V%UNQU7l#hem{iiZtWP#tsOoAbvj3x~{-k^(y zWVcF9G8ArW;$P?kv}>khff)Fe_Ab9gnF1IJs*Dbk@>3`9YyeXEO~ic+Ig!UL9N9}RCdv~5~r zX#$b_$?LeiaGFF z#={~e3tZ-KR07*7mS>g^AhAI@r#xRq)Dy?Qsimg4|9AC|rBoi* z8l}x!nJed^rOsYTL$}{ky~DMiMz29?l6)PpfBO&`f2@(OFrdzQiimyGZWkyF183;> z$KKv>j!RcVE*xBvzJyfml3U!OD7h9#PrRB43YgSGl3r!8KI~1F(VbCqkABtqqUIoH z7mK4GiO@fVIXjn~?()~rDL?VQ4JQ_pd5m~2`mN>8olS_ZXw!l(zl8GDF&=a?ERA;l zJ~3PzIq*Sbt@>|kjBA6L;*nuZ&dWu*#h0O9P3u#~eur3*1D#A8YlsbEJH<||$$k7M z?JYw-WGed05y+x$=W_=Ui_)jN&ML9cZ6)FcP$RE4^dNL=OqWn1{G?7ghs)5RTOP~L zgb4c)mENcl3feUh!5^(}ZTx+MfQ`~dW!OytYUOcjABvp-{ zpd~#69qcP<@0Z0RJ6NnK=_|{TU&iwQQ^0Q-huggugH0o-YnMp5)#-tLBvGH%5yZS> z?qZfX-fNzdd$#T_lWn&3XyS46_e0N1=GJFQZrjAEHj$Q zY1w;ccr5U(bf3cqB8I>LJ7poh%)4G#szaagQ>!&kI@at1fc$>*x**+L? z7-z)5pb7Zl)Mg8|G?lbGIcHL*Qgo^VK{^{n-3>lK^LS})@w(A;#)&8X|w;v85q-E z9KaE*JjpYL%>}ek;RM1tvg61417VTxDK8{MqRr3*`-`73*#a6X1kwTsRUP#mKn%`Rjz&K&w^UoCy+D>OKa;6S9JM%27}4 zxTP$0%^?A8R)9=%mRW8m4f@Nq{#fwyJ9p6A4_5r*1r-Q%BCj(JSoO@5LnzhnFPG*a zMx!rdb`VIq^0n|FdO)74g~xaX(`ECJSut-MXMnSxD(72{93p%|D$w!4t$g6Q1Z~5L z28}&Dv0!yxQE^(<;S|I>8c^bk?$ag1i8tWrm;|qc%=Y>pC2zCz&-9z_Q2Iz{fMq@hKK=QCa$Zv8{^w!290<@Q}C(A!)9#`m=% z?7eGlYw6=r`&*K8OUD!-$pu3)=Cvw5o3bBaS%_7!VfE#TDt@_JIS@jcS8>Ww({%qB{w%0b1s)89FBeZpOA!dROBbFIkd z2??0W)LbXV9c-sYrBuCiHOo}RkT4$SbULoRxBP8QLv4k$yQhDMWKwlY!#@l2hlFP0 zg9%BRah}v_&ad^E0>49ydO*rHt;C|Ez_KS)h;QF8a<%BN$gg(~V^^fky;? z8MEOv@r!?cANc*N$oe_s4$_!6s=$fCM8DDin_5C(`9z)5a>(y>t*B;`t1#GP0!3b{ z=+%9eD?bAOw*mqifFo3TIxGjO-BdP}%rx!~`a+?DzK$s$!&=?!V8wV2?02lJRjXrq4xeU9s^17|Kc#uRT`CVW@&y&p==HQ!`k zPb3K4<3NGuO+)uSz<5K-)8o1bv~Lz}6y;W)T3)GZxDzBG`fQQdG!q*AnaV*panIeX zR9t|cKCi~{+E)uxiT$WD62@V$&VxUa&K3o}#s@=7_% z{O`y46I)<&1{Iar+R`LvH=1e$R9X`~Wrk<;4#JW*B#BH*x?4Xq)OsoW&e%h3qruS- zwVYn`7y8ZG`d|ud?xT0NklM`h(Y<~a69VMKYK)1p z)eii=A~<|k_Rql5!qe#?skxc`@Kc&0)isVzDjLjGFJevxc6X7DLjr77FNa6)J$7*UZeQqLf)gyr^d<@> z93t}%Vl4pE8)UsH2}c^sd#+mZ+3l~$JE$dXH|(oEW-iZ3Bte5wdAQx$%UDmQBLsZF zq}b>NapN*eYxrgFiWQxg$6z$OCAoqBk)TNs*qH#jQRuW9NNc>f;I5~74x0<${R8w* z+uPo7cT!IYCB%mW`a7w>gq9a`IbGbYSL#Qrhf9d?S?#9zb%FC<<}llEGjLm;wgRqB z|8;j9hyR4*DMFC`0|D#Octj-XST0i5QVQj1o0ebRySj9RCN5^)`GK~waxyBa`XCG3h%m>Cm5&cUVUr#&Szi{Lm+gEiE5&;E{se!$8mO|On^`g=; zZL}-AT_2GWi~}8zAHl&jf>-%pYop|X*w0g{e+|&*_hA z)x>ZY)Q0ZiajLXJEkW+wlB+c6$@B-_k^wfvXeiX0{*yZw(=4ahOooG-G5iKotlyWL znQY5cQsEPULw+O(#1!y;sFA#sfjSlTK`E%I3|CxA;rCka8r@^p!j0g>PVW>*1LSheIeBAK#@y017C#wm)Ui25xF{A)!8&lHRzn2R zh)HpV*cD2Tfz7ep6q5&d&iQAVIF2BkPfgU;`;~ovw+Bn+FM=cv)X&EaXri56T)*8C z#|||))n)7u)ZbX_UOBs#d@`y)S_Fqq-Xa%x4;;g)qB?@vWmXO4AOJrcF6}dl2i2j6 zlQmKmRCGDdJqg`Ujw0@j0si8BxYj2cUT~i&JoQV{76afa{wlmk4XL$J9f7m7+|cP) z3~jldxK#iG(YPhyOa%@_WAL~>0@(u0P<+G>&sNDbw zJnDN%phr|@tGj-%ASrMSSex)ry1ZF-A|iB0|Li8I6OAXZZqq9yud<)2QU^)@=X-aa zfgefJ&=w7QZik9vAdei>mYv+R}Siq21dxU51&MDk=tRnwB)kMhd1R6tfRN|e> z0gMgTD1lq%ttC~b6WM>?xy=;=#-`8qY~zB*XqX1&*Q2bv67>5LlUt&VPy+eoOg>Z3 zT`f?>$>=eHoLU5!B|;J>t~t_lhHV?w{=WTkILMNY?j3ba@{#BES4)K@Fy2_d8ne5e z?&R+0!JSDU&o^^=WPT4eI1F=Rlhzh8J@Y-}NUG1_QXt-H8gd9P`nMu&rl-tGsi?V2 zwk$OY4RLmL-Xa3)q#{=9qVeV!3+IC5{@lCVAbqwbC2RS0zaXnJe|g5N7eDGI)#>P2 zOEXHlXpQ(O)z2pyiB0z*c#^-ib~bjUGqXt)1db@+X^dzg5kgU>f=46T+OksJnaR-< z?=2I#&9@9|1W6#dRK=oTV$Fu@NsWyE*>u-O|D{t)c-Qy0zUyayWUF;B+=aw}Sfa}K zs8<$prj$x=r;po9uht$gQ~esI9OpNV435(Vb%maNA2#vT6{nNsS4sp(F&bVzQR4&k zLm+rX&Xy+mt|ro$fuetY+1KXTj2#^DGH<)&=hu2sZkHhsl}Ge*xv1N9GgM)g7vaT| zyulQQjd6;=XjU4RM|=#Up=Vjc9TM}yJGQ`Ijp3c@M;3pzp2hOrT4Y$79FY5ww56oh%Yx`I<$HAh-Aq|VpUFGR7&q|hu3{TR#+bCVW%{1wn_gl zNN&T3R%U)FNnEcS0Ygn^4|)|I*)6*WD%k>2$?v~d8IMOhH8&vz=iA$F-Ww9J0uBp* zqXu#!d%_dnE8`)O0mRcxN<%l{{4XOls6OX_{P$xkpy~%5_wpv)yGFc;Proc*!RnPKvWADR z`}MR$C^xGiWgN{~i}x|P!;IE0wNjdCO_8tKl7H=0xk2O1taJJc{Ic7X!I4-x1Ut02wVU6?A-{&!%-!t2F(zKzV(xI>WA! zjmfdXF@`Y(C)jZq!;0MTslEwU)h2Y%Si@fA`7nQ<8NlC&^&u~LI^{9_c3AWB)uNGD ze6%EBzO_HPS-Hk+#mux)%RmV&8h8Z{9kDZWgpC#ht`u%Ii#5S}}ET%c_xC&YM#`?Vk|M zbjPk#%zU;SEkGMlN&gU7<%QpgqVb-#(;LWwLkmcp?v^WfAJ?wM zDHO;PcmAwvexbpYqu};k($(lv>$m*Lt?eh|kRw^9bsFW52{hQ4fGiQRy-4Y=uDAjm zbrvW5p@0&HU7Q~CkNKxAp2z};{qtkfz@F9j4np^(b7e9U9l#bS>~IS7en?y=CL)`nqyf#3vKolQXZ$y6(cqQXA~vzRsiydi3v-S&kImWpUd=S3 zbsa_koUq|tdGW!Cim8K%Hr9>Nj1)pXwsJQ(BgxJAyaDO8PP2f&F}N+)Da?Y6(^Wrj z%h7Lh^x}pHKP=pLI$mYt1z@ua)on-yylC!oO@=I;8*LdpMp*hBR1`?~-$j6c3#2COi=h#-`ELwG$3+faiZ3 zS8O-k@f+$0NT`g7*<`k&#!vuaegELeSdA09)^_PmOrQi+h2oXpLA4s=xqee|UsCB3 zUuLBX^?mSh@+Fi1h$nY1Sji8)D9l<2~n+UsN|QDBm3IX@@FUT zQ~<*pYl69A?Qv`NJ4nMcZLC-@M92)lpERb2acPRBREjEncV7 z7TmIMTeyzF6uNEevXNrnbG`ORwI(^>qA_-vky#l<$(JGr_6Wo2*^?cryJ>{Qu|aug z5fUk;WF7`I@)gRpjK(1&t&@{dW+}!z)sYtM!}v4;@w4;)vBQp1zPnX_&wd0h8Nh-M zKOtV%vstC`BzKZ@m2)Rn*<-olr2tbHNw|c{SQb2&pA#6PG2=N9a>b>68VkxwYSG?4^QPCf=8yz{}kh?Hzt5aBPA+?Gc zPAvG;XwNxb-KJ0dis}>Rx{-Tv;8%LX__aTZ^p7o3LjsLDpg@_PLtxp(cKLi*iTUX4 zv_jy+g-1YUCJi1I22)jUI`7lUfS0@k{}kWYDlAu^ff)|XTZ%E@uJDt_k$tTv))v{Q z4=zG@?`!vKOy&!*gbXBawpw`}wn`w5TCB!kVxoJJsjJ!X^rEceU3qm7SYj>J8Hhc< z18^_@@piJXRc8f7y6F;|_C29S-?*w%&&R6o$U)g5I+IoyN+Q+1NYKlM^mwtw?&o>} z+jzj^haR!CpU%(B`oVw^@wzMyk24r7fR(@rY!6-<96FJI+ne{HOOEB8auY#gVgh&B{#qDueJf|F>Fj=P37f8N2I!>nuvY zo7hg{%?afEXc@zL%6xcOW~&r2dQJP$N+rhR^3F2yHY1;~Tsf%yVx;}Zsha}SAgP#u z0(Dmi?hV{Ona?3AgRy$Ri8Bz}^XRc(-CYDGCqTi6<3=V)T00J@)CW1}U{QsWVAP8N zC?4s9x{3A&nxPoacNwZ+gG^bO zfQl7VLCTcTPa25N6bB+69p!RLVxq9LJ}QTqa+a4g4Hx2jFMHhK-rCXXrE$>tK-MGW zYRWE<=b7jlLR-IFnuqX&BRb<0k=JiuX95+oyz&G9&rPQZbl+)BLc!4u--f+GL*By~ z+R7EC#G#PzNA3@v*50??FM+<_Ax@XOjVU=Z9uYRwdJ)e(0qRit3S?tz7{T>VMQ-~H zZ3@9!TV15Tq{aA#4K?q>Aa296SBDa4ZPCyktyh?;;^1xXY4XrV3^&L6r^MDP&@Xf% za^ouf=IE%-w?xji!u4LzYD-VDXrRv(FV2gE8w>e+DD7%c2G~o%GPD4~b`^ z8{K8^Zcy?(Nz*Sm9P(GTLMs4{u4W`B8h(7Acd+|LrtWbw12)-3*&jK;c*Q1;(@6uy zxWX<@uY%&VhgB$dqbM-sdd_nCfIIsT;Y6<@{YD{b@mNa<^nE=AQTMnFL1v@_#o9MwVKfet@G)Av z@NMVzkO@i-@1bw>jL}v)kxz(O*9U|o!syMDjr=}0`Y8WGsKaY54E-%Iv-07Eel?EA z4qJ)S(CD0(YD!iTidsP{_@q!Ocj;0a9WG(SY6)l^wRb1+`FwC ztUB7GK#)_*|Jf=7r4zE-#EXu;VyCno z&fn_G&oLz38{^HTkXVCDa@xeM@({TV{{N!*Qzv@{lTk$6+>-bm5iL4=Z`C z5U9Zihv3=#bYq7a9(`JMY_@@C$75FzJI=6C=k%#p>e44p2y4o{_}tr%vPE?sVj`Og zykO&KeUr(CR94z1HRhdPBv?F>xLsm$r|LI>JIUaRCa$usP`LU0-kn3dfFZf1=wqfI zSi~-$)aw{fcN^U82acae!AYk5zBipoG9aq{OBnjc=84^$}=&9f{Kp@ zqu*C=GClP~1@Cwt0Tg64Wcw$q|1%qF@hge!5aQj| z$`vv9M8_H7y~{L_P<}Y~o%I4zn2I#zU6(M@C!#h;BHm>|4{<@_pz2~#8V%QqS9h3DrZ9aUn5?%Io4 zk54`#lseI_tbd$Js*VY(dTNcY~DxXrL) zR|Qsge|3z{HN&7mSy4;i8h`^+MPz^{;6%@E;0eNO>D+NdNB5XvrW!8~k8{{H;pq?y zvTv9mGe?RV*wJ5Q8R_ZdHIR`3Kl`XeouZY&5Ogi+0|ILg^wh)6Qk9nmF1Q}8X5rs1 zfGsCt8tsN+{R^CG5^C?=A5|@1e4o{B{%e*9X@?LjgVD#A2G5pZX~?y-kHcuK(>qx( z8&<1KS1tR>IK9pp^$7Hzyi!t6=_F1&cEj)m3?+Bf-=*bJ*)mOEy#epw)dPYw;o+y9 zd64k%CjpKYSJStlrSFZQw8f2}i!D_eaP-bVDs4$h={2WVwa$3jS6YLI zaehgIKS9S10+WhDnj@FDfiE!~;lD$cK61anqesX1&4%f%s&=+P6Z8;I1?vZUz0wx| z+Jadwd4XJV2#9DPJ#Fte)F*i<0(3#;d5H0shm$m^GP}~B+NWo|NkK_u%E~cZ6kcwS zYfm4m>oB^n+E}qKDgWk;Npb#gHOL_;=R|BYzl93ac{;jK)e-QjtK55GEuSQ(MJ@01 z2CSn#u=J;fK8dI_?AAOX7y(nuP(m#}YI9KqNT&!wO8R@b;abH)d?)U*?r=lsbaLU3 z`kg#S5u8c5tSq1@Q8Zgpo|<}2uy#D>80F+Cji!RXJDhH)h;MAl5m7{09N3cXiR4Jj z{qh}^#tZDja}l#Kf&tPtE=J_F(I(_a3FVG>W(Osz@A6+5A@?D*u<%&jUrO{Z|A9xq zF*Yv(QX@T)nLOTTbpVLNj^D5DADJx0ef_4eG>5C=RJ#fAy+pG03bU+pvB`RZC6(9f zlwq8)=XXa;OoqWN7+OycG@bFKc3J9qHu%eyv6WK|R)ja&{4`zQ?<0OiFfn;i&9`fR zgIW=Ni-j!zXj};oHsh6B$@Z_t*u)x@Mcqsh9N%ukXoWy+DN-_t?} zR_cQO4P^U^%A0pa@jX@x3wte2RS}2{K~|6F>uyz?bs)RJjw4j^YY;}ause^7+b8Bx zRm;exgl=eud!Yb@%|>dSp{Z%bK&XJ6D((M*$lSe7b@hNh_gau-G0%$Xm1aR08x3Kr zu5{t|$;K}pN!@=)D4(<1`}{~6;LS7AJ zTd$oDHbKX#IDK_*fJ5?&<9$XCqW%Mq4#CL#Vbu!4k)vRoH?s+wwjs!!%$x(;=B+)z ze0`f+q<=1}A0W3xH-X8#*lQvy;Ak!`a1H_qnnb|(<)rtF5ESkxEe#Itv1JSAV}U^t zRL!Zipw|~uS$V?&Y)VD!SqvG0*dcV5TroYHbuqQ2Dxg@fw}Rfz@LfQL1gAt_SL|-l zuz~b=HjZ;<7U<49H^p1fT*;``<*1suQ&vUi#tg@SM{yeN(*Bc?_OAyL1(4*8VPZHR z)cR}05!SD{83dtU84I!@fcR+zYsmg3ul!jttHoL1O73>-PKT`*KkCk4b-GTp2q6f3 ztas%fS_s3zf5;S9H&FW=eHQ>nq}$3kZ*;5IEazG2E6!<>_cWJ?QnMh8fobUn zo}=gy6tqpfE1$tf7gPaWe>~|KYi|aLXHV(S$-9+0fTm1E9SBCvJyaD zx8WlXInT0@jJ2&!FI@f80QWz1L1ciQz$B)I=&)FCLI$o#CuY&uV`3Q`Ejl zP(Hyz45r?FUXw%V8ahlF)v)VnrdVlOi51{|T-k|(y;I(+iV2sshKk(t^V2GrKi8V{ zyf*R$lB#a~QS`UlqS$&lI{m@!^!-5|b-|WI`ikwPE)volh?mz!cwH+oFCWGg!1|*@ zEoCcWISRs@5cD>(#SEcP2V6|VxOYbdd>QbZx=U9`+F$z(O(5JDwZ#-#Koz2}%eUD) zbUGA+sX{3`W-XIWfYZapy<29=rF%7c9G;=|hV9BT_DPoCrNgw@f6;`3BsYvK9u|cs zk1B=-DcCNvZu!QcSvh5ht6-L%tEvl^y(NHOT2jWWL6??1=gtbid6xT#YrKx?i}+@b zi)ic9-1DDimG6|~0CVbChK^_JlTsFMOf^4J@faaTgxDKKBLLsp*Wy_&!fVeAa-Foa z+vDmZ_+WY=>qY-n>s4l&t)Ha$mrHh?BA4ok?|umcjLW>M4nxsfLI z1>PpBNr0c9Gau#jF9y;xz1|Mm6s0QD7RouV=$cmOhA&1z;nbv`?8i@Rt)bv^)hB% z0IIp{XnVG0L#9=DqW3NCg)nW=YuzAE4-=*ODI|a4GYay0$Kl5kV!A@RTPCCGc4}3? z4dA{2>{HC}Cn&emRFO$WHu=|d3eJ5vs!p6ZYy0=w{qb7bk5>uRn!owq#FrfWTDTys zj~LM@*)Yl;JM4W@no)%vs1}GXl`&G!-BcgiF(*?SocsfHW+uDMCc2U^t?`Zs59x2DOX{P|{J`FTm8j~yPu)YLOe_u8L#<0vQ+ z#}r31@?oK5w&pR{HOy!y(U9yXHa`!72REiL5B;_t3BX0$`~V--*%9o3d44iDWsXR| zkpOjWW%E`SqeHw?cdFc}%5ZQL^iOSwBfs6gFciNecxgC`C+#oHZ*|6 z8K%@*SkK?bXvoHx^<_x2%XL{;Uzo%@x^_Fjv=;SBNe%Vo;*m{^&!t-d3wedp%FQB= z4_YSk%!EKQ{=t>@8W#sw=-^%AI>jXOSx(LoS7vMT8k0CJfz{cbu`L}pz4F4n{yE$} zkP2}6)D&JJrAk|T-uJAHJ+=S`2>fZIUl=RD#els(%*%i1#=t&V`9Mc-T!T!$5qPx* zwPgJno=41{k(R)n@!TP{^OpFM9puJfhWmOl7|G`@h;R;`<}U>al!1|iSF@g*Ch~KI zF~LodFjgNMk_~?K;QWj6e$#aQL|SpX_L6f4J${9O&5=Ng=?1fQY6f(+zN4+eel5Za zFoys5^bEBY;?YBf$=+9OyqNh&w{T17OSVu$JGS$yo6b6}iUG)!>kiA}J>{a@eG(JK z0>{_G<)>rwW?b8y@O|->=yTczc1l?B#(e{FTOdXnsngOC9jTZ?b??K1Nw6a&o*?32a`z?ny$~Wz<&0Xw>Z!gBFP-4bR6?s$A>pqj& ze}LfbcK8?LDLI|CQ|LX&Gqa$Jm=y{Up()8>3IYTKg)c-fIZD8Zp-Zg8?Nzkp+-C** zHyqJGc;2s^yGuNY)x7^~8!o?qhex4q6dXWs4AK{XGUHdR^SUC}coDsE!d7It;}r=P z(9ilNlkXx|&l6VUVb;&(QAz8CH?$!(`x(HE_22af58e!={1=26-@FpH(4ql4NLwzuzwUNeWDk2_v#`76LRLM*Pf$2k| z))8mp5;?hfqBstwiXahtK;W1nhS~~Byloc>Je+(N!n}z{Oihu0aB+J&B3tB<=(JED zRiGL;9{|_SwMN|;wgtJ>dzeb1nORNMcQY?62SyuQ>DV8qn%H4FM?;c%B-<=ikJbXA zoiK|Ot>Q$_seD_GC}f6WKCA7%f2K{jhU@<$KK4os^@1@f@|p$t0H~Lc@1(Sf7}(Xg z(0A%hRs*Y-z%kNLnL|+7sOMQmGwsrm3P=1gbIeJJ0ki@9QTAQ24E81MT|jLNgu7i? zIA^vLHK52OZlaWy;2W{c)rIY3-gm!(^20?%*-FQ!?;5vbs^>F<2;Z2HD@ z?PJ$cU#KStVqt;{dX@3aI>H{;+RV=XCE=-#I9aR$eNhVS)GT6SmR4x$&r$WV7;>_S z=0P53c0>|7g$ZRr=XQJ7ipsCzMUEYK51Izt2+D=qvI1B!`Sk__B9hz3HtMwg`0O8` zWot61&)<|N5iEv`cHSZcG$NQVZmi8@@-^amrC!{oWyGEtgq%_E#g5x8i?sXl8-GF& z7yk1cK)3fsXi6C&-yYB6okm76e|ZyLDz7yFKGNEip|6iQ`adf7E5o}%vZp0ZL#t9| zdjQl#_^8=OFosjt>nhyol8Pj}5_wZAp8_GhDdqpAqR@kc)3+*_-LqVx;PS{G=>75j zi1ZseDEh#3)g)O#p@K_ic7c&>^_bSMuTy-zOzh2JH+LA6_(kM4FHI{|W+(MiIvAf4 zxi{M!Zgc1W*inYWsZiIi9aYUB7^mH_Fci@;f&{WijmO+ynCHLdhB-(JC`M}6TA?8A zbPDP3Q8#mi1tg^|o@w^_R}=3pUAB)pe6wwwUx?&8>#5MOctzSaRuzPHHF2#|IVa;n zoWKyl7W%6+iESEqBG+3M1f0z`{0>X*Air@8 zkKcrCZS4wh8@4)28t~yZ$Jj10M8D!b+>|K6ak7847ou6Z4s(uR>CX09Z04R#zsN4e z@W5@rQTv?EuN@te=_M=xH=O0sUtkp~3z(8cMFAUtq{5Jcyl)v(ndNCEyVIAdrb_z+ znA5tmK|;_%<*1Yev0K^tpaGMEfcCDkSU)1a&l9|7&bh94ZBvS}1qXQ1WTa0$p_VNM zoo&_Ns8eeYSYhSHg=KMA+{!5yfKYQrv}YofIu)11_g`6|7Cv(ZRB15t!v9vp0tpR6v zsgXRc)UjPNB9(Fxzr|acplUBQq z+|j)mY|2WS*z-dm$jmeMTxK-vX9D@nb zs>0jmacn893J9=OZC&SyV}B60ZGpuZhh%V@F(Fv%1Vr&89NzAo8qs-Xm*o{^JkZg3 zxWO7=_Z7ptVHp7!E-n;vejFl!U@bTtgoEw1`JSS5opauY&klZ|Jo?HmFlZimN~X|^ z{%@nAC_(@bES5teClD!kl5d8yW5TEd zRF-)I{QjfCvi=bHf|9AZe7HxrKbuRjv=}!PcNYNQYbVv$Bv74IVOO_jxLWvJ07Bzd zGhmgpF2R|!xz;iPg`Et2?lEnK{0?h>KXoHAR_9dDCr}zTg>DCZI)5+o!EUuY2WZB? z)agBGenlY=ov94gTp>-gR%9JR)>IIva{* z?Y1F-JEsTKr+0e&j!$?+7cw!DyTQIxIzggwS&BzU(u%edlfn{h~> zMrmf>7j2v(V6TE0HAn$qsvO8>KVWT@wQ6||d}+)SIc5AnTa+F>wFjrKu13e$6UYdM zjVMfD)!c(7{DyGK_M4VJRZo|jXgK46BhN1RBet@P;&Y{DP|nv-^cL%|4>iF{1EFIv z8$(zSnxw+O>j-%8;@e=US?uX3}t$ zRFitjUpH;7wr}Yh8DQgrmSVKTn<%|<8yr`Gw>Ag#yHmeS@$VXk!jN@#JdViO+$eYf zXdrxuu355zH6;mnIc`3;yAV^M2;y=sXVIooh{<4558ut0X$OiQJhM=|0xM`Ho!_>Y zp`*s%aCunX(ZP>~V{%99$X;wrb4?A(w5HYK+9W&E2ofP7)$q$;8q9R-fcy>8P^a~< zP-ylkr&MF85AM2NP%f?9*ACDxO(u>@ZCovah$*4t26AFp!9#&v`ZD*&lgOSQ4ab2` z`&43T1CkuK?TSNHazQX5MI~?I><#^F+K2$I`dpep)Fd@V3s5jSf4kHP{?=(>4%44t z)ggVbysfn;ksa{8-`g{1oP#h|a8K2)(Kj+j6)|L+Cs^$~fuqub10?+a2snQho_9e& zSS`<#|KsLato$LtsR#y?sgDdZdw&0zT}n2_UMnWQTu9|*XGSBjzE+EI`a#lW={N%y z0l<`H0<}+CcyS?LksCxxr>tx}!&$r3vhgrE)cf;y2I=tD@vB!K(G{-L(JFt^!62^!CF@PZi z?=i*5X)2s+nU))_Mw9d>MjfcLL{!J{9XqtjCd?_2)?UQ zcm64itU*ki=zm1SBrMIlZ?NP+Zm{TP$^9?cl^@xv2z$wxMa`G)#hHCddctBw4!01@ zfXoblq-tk1L~ouEC!gmRhHXx*t5n&_qmA^Uid6p#vVrS|)iTV> zOVD2R5Ws3u43zRb&bKsUqsqDT|B1ZuTyibiD@-xnavTzVS^5*z-jxfre&an`V83^w zH8+jk-xQ&~!ZT(V4L1SQ{C2|0+}Wo4`ru4O-1fHj3Zpril~8v;=iXRs#q`T#a8xt{9Qu;_ z1HWI)=$d+q)OJo}>GWT8LEF_{to*0FT58tQx!DhX4)6e6X8kZp2Tzex;lSu&>f*7Y z$?1Hgbv6}Oyg%Q>&l41_Op226uoD&pvfny>>Aq}Qic+1siVVZGQ&w*fo2KE!Y`m#u zM|355{st3K3Wb(C6^80R3Z5hkmi#B|er`>QnT86!Y$&%TWmY8$m>=lp@Dy%VDW(WJ zurTq4B354UOZ3E?q(o5k&@kCk^ z`dH~SnlFwht@}J1(3t6alYUA*+*mlzkY11k;cmuM8unHamtOo;VoukXdcQ2`W(k#p z9Km}-@z%eBsq*iX0l;T8UfNWJPDeHn109JgKgEi3q`Tvrv(725M1Z_)bnR>oOf?Xj zsDVT@;oP*Z7$`3iDCHppZOijZH_xTd)Ca>Cm_rTVW+gg5TVil^e;UC`!`-rWWfjuD z^MT?6#a{%r$$f8S#T9%2Ue*+v^36)w(k@qol+S4hZ|Ua8!Y?Y#xH<0dc__;_bCEeApVXOO1Jh@CyL48 zZ_nU1n`xU8rqqC7662S=GVaii=``%_c7SQ(nWr`Olai2d;mQRmkC`rKJZ@;R;SISh zZbWZExdw{%-yd$|bl$E(SrvaX%3I>{!Fr5jM`a_wLxdztT!T$oYng+l)lgh=pINz8 z5Or+E;O#<}%-3MU&MwaQi!BST^o_?v@zE6puwij$N@d;wfJ)pe6G&^tJ7d2gil~&9 z@&V~l{>`X@#R;WOF<{=1taOpGXfrce{(R?m1J$5Oore7#e@;x5C?qIKep31rOHyEy ze)RcbF{M?uYBG>J&US~Jy=Ig&GB{~yqwMotx@WwWYOKj_7tdfMR zTx0x9464{eWcRB{5lL=3sI`8!$R|mWYBlXgb7&t(cxkR{vOz!M&03%a`950!Yd|#g zujJj9`k9L$jAspjUS!xSPG-YB@LzBdYkGpq&LY+i?07utvPCq!R_%?pXH8Z0-u<^A zUM!n?X?g9DH1P)*iHRu@n>l<$WZ@mF&1XtTIL(QGbxXkA77A0_QUi7=aiYr%U9wiK4Foqvn(w$WW}Z^)*n!g)+AxT)lr@$KV5lD;r6WtEkq)AbhU(o0;S|CLv5eMw zwjic*S{K@4V-gj`o1efLa|-+{-K9Lx?8mqcDDDQB*u&I6oXL0)f!po z^G>aPO>pVmY#;LhGxkpoVlE&rIc92=m_^nH3%(>4-vsjmC?u45CvLEHvR<@F`tJaG zk9521J{9eM299=+fM$~_H3x(f!c)cJh{ zg$eesT9n?$Oo!s1zJv6kQj@g37bhvVF#ir!p#bHVz`99RZjxMp_EO9c=ln|=_W~Zj z+0FWI{xXU_zp`3WmEUww{pc^1Q@-O*;Qw=ewt4#{uwX15wyJ2)#5dW)iePpbF8ZB^33Uh&@!`I9kDRus~Oc%v*4TLS6JyU3< z7>Ta!cXH!`dddsUa0b+z@q95MKmY&(00093O;l1l&p!q)q&l&qKr&*XyAQv(AmI*( z#{sghtwPKZ&k-ppn~vKqhh3RUB|U`0 z%RZHu0US8$cRma|`tqdo+VUlI7(YVqD&-RCvbflFN;3&t^L{O8UZllz~e(K?Usc8^1X1(2$MUULA=k~ z#&o!hGEQK7JtH90J|0|5M?QN<(&|wVCjX!E1MT9OpFhzfqJ2{(pYgD#HC!sj59Zn^ zr3xWPdKOCzaeFMBVl2vrYC0J_K-SZ&aJF!)FoB|bJ-#e44!@Y^kH;Axnj#ovI zG3Q=#XyYI4%)+tyDJoQry8!W!H9@<7iU>Ud4?@hT{K+{_3EkkbSJcA+SiKqDTS zRe|kIurnF(rH%cF)E2}UWsrUEhLwqUl`Eoa{cF^!!i8naN@XvO*pW&tJaQj?RG}`> zlU(nI8-gZHCN!B-6Vh*e|Gy7laM{2u0dY;g^))4tBFlZS3&CU#4cz*nocdnS$U{2K zrSj5sDd4-5L2zZUy}9g}ddd7t@6?s-n$KC_g4+E3=?oBW5mI^V0nOKJ+_a~g5syZD za)hz>4k9-&D-~i#lOjzleAfy~%=B_9BG;+0Q3)#{g1#&Y24Sbqb3oo^}nCR&S==;VoDH}AroU&yk70H-=m;~;aEWz zMMxtMn>%>gDH3iFg^bS-$f{&(o9Z+g?^qS@kpdU8DU}kr@nnK`jjXz~X%2kj79Jt9 zTce=`q(_m)d#pt;C%y&(Y~7GnCO-sqoK-S-F?Z_$`|Tfw)^J+<*o?DO@(2D$3L@t_ z!u!&`1DMdr7MXk+>HxU3`mUELc~a--0||6d*89l2;s}kyb*|hAS-y&zV*i@rCSUl8 zcZ9qiic|}=?df$k=L$o&(cw~j`aFkp9|WYTM75MDwVvgHCrx*75A)l5S4PbP%_#F} zlbT7$WWKuJRfkkfO>w`&Hxh#c;HZ7fO^Nx{pgyFy;^_1d;17d+GthA-Gd)-uWwE%r z$HZ~*=|IAM!9rvG0W?PmewaNGvP`n-c}(833J}g96WrdGYxeo04Lk~@U3z&ux}&;( zx=C9)CH1iH)bkSq7*I<5e-C-;j7ly+aU0xg(NQhktx^|L5LRJONqotc@9LxlC4`)# z|EPIzh4`AEa^Oxd)Tvsd_RB{>gNt-t9<9; z;481Vs#qfd4cH-v*zw)@08{>S3ik(Ly7ixt-hDo91;<=aqK|huwG{2^C?u`7jQvF? zta|V7LU*+yTg(8`EGKUT`g2j(U}>cl>_wtO!@c>}ur2agblBXJcd%=O zNiX(y|GP32F2hlPycSH)YmtT_46N~pw>XX&-+z71h%GP$S)!TMopKKFD2E?H!8C|+ zu}u5W92|65*B7BKknlEUF=o}c-xA@*V2Bf<$bj^`tDN@#Yf1~90zRP3=$uChCvCB? z77c!KVH1pyeLMMZf?(D)aj|G`L~C55a6Uq{0U>=xP;WA|PqAv7Hn7=!O~=~`@cA6& zP)=vF@#)G?oGs>rLJp9!-08&A$6rYm(5s)$z8#RwJl8x!&;DtFcsIzMiFV&@qWPNM z+kC+K_6NJEe-O;5Mes+mYLD?qIKcKvUFAJL-K+7820;vp2_!V6>o!BU8fLjLx_LwI zNs&aNnemjHH*i&=L9YwSOJTw7T{e}uj})P5BkBtm`M*k@a+h2h_WZ?@700AxEj(9| zHRL^isjcILg`+T}SP2JLc;6%;O*hHQ_mSbG(EsbqayXcH*D8>sJ{}>gQ9WLfm}kSB zIm`##^?4z{yQ=swE-;ZeB|Z+KI`9RV-BJIb4r+EqFoM3pDs9bh`udK|^wwZ~ShoEa z`x#nVpzLpsxY?CY+8XP@)fLbZDt(B-ybj2R6?VY8lG_fN2)5NBSA}6gug~l0RK7Xr z4-WhYgQqAMcA8U2s{2bf>5Ts)POQA>-frF*h{u4a>Jpc%0?n_oXR0;uKBQoqoY|8~ zTKHePuTc?ZuV_@yN^C~oE&uw~H^KS;jW(f%6d7TVOkm&j3)P>T#w4 zlAk`%iY-aS*f-#QYzT}?_k%Y_Skg^2*DIpksi_dL8%P;`va=TFSim7XcKdLbF)h%^ zQ(_ID=16x-hXSvL#4WIbi}eV!91Z}r1WY=nm>_tE$Kt$xk|KE~Jvb)YL*lo=jSWmg zctWXJ(eH&Fs}{iLlzD{6w++X^fx1fcqM{y6MaADZp6=;q@=hSCg*?OVp8hgmYPXa$ z^x-9&_{)o+r^;bpIaA<7M=U=3PWQG`QuyvS;-=Wsw>4A207hN!= zu2LviB_SM5k_&`d_fSkW5k9SG%Oip7mC|5i*dKnW46)4UKMnFMZuIlOTJN3X*#k~} zak+CDqoWJ7uKi%|OSfo*Z*ex&VvmM`giCwXA2lD(HKOWrC&^T*sW&roj7U03$PYmq z;IwKUcLcc>yu5yTC3VXm9*BoR1T$CpLnov}_g-Q?EkXV^q&80cIj>wxdfTf?wrDG z>C4WpW%!K}j4BN{Io9V8Z-cd^_bCbly~i(SUp{hDl$HuBAj`@)PNQ}Yz z@6av4&fz#fsj05~I)AZ6p=;Pn$h<5BL2ABBSyM4bBi}!v$Rn%>Rd*z5lj?Z4NEOtRpd`1GgheTu&8hPA&1_aVWQ=TCm(j*P zb~=||0l=|t^ia)Nix%QKevvsHAvOR3-B%%==IR2Pe>{})U10+RD#LmTX>?Lq+18e9 z+2tBlED;kx=mF;9V2o+jHWcf+svH=D@vFVBu(wc9muU)w%P5m}4oj?P9YQ9#HxbO< zgJ*O*+_-c-J;ZIB@9c)bAI%OM&|il?pj}1REof#zP4K{Cn|C$K0-YrL`3h>RZ?2Y^ z7C;FlcKOiqaKI_5pVdYHt16ugFdP^TEv_$91dFFZfZ3_Y#9O7^@9}CH zWeq*#E`B$m{sfI%PNqKxV$_14CzCm4$d|i{Kt{WUyslm(Eyk`%P8Xz8Nti2P+JTVC zFF)~=iaqdZqW0y2yQ+~Y$08FBxFqw^@u69T47~2(*{#kwS#=}JCF6~>C>1+Mc)t&( zL$mR|CnU9)gaA`?Q9SZR3C#hgrWk-%kt_|vXv^iURHoQ1T3yaKIqPxomI9@J@nUSy zr8-ntYXH7f^Ud->KouA}y9Ym7`2~RiC($v%%`c4X`@D+f5N);$!}Z{8UmgkHfcHsc zsOTAQi{t8wJnq!wAm)D2aklTBG+bBU1(C&(<2whbTx*#*&YG3t&wz0o566Vyb1R9W z)u{@WPZ-+5*1{X+H(s58c3Nw6@Y6l^nT4ZX+FVWSk4T(+} zERpBM-_YqbG~BGr`rq#E@A_#gsK8iM#fT3}Y3`84xOGLkrvUe4@ttaUtABk&d)oPa zIiQn4^u=)x_8LsR$ckcr*u^%0$XknVg?G!&n9vRj6kiShfiOUWJLXsFcI;O>Sa1Ba zAna}zNiEMHy#^(;i*DYY(#Ijsz)-6X0k&%83JeZC@B%`kab#yV5@@fv@4pclST+HD zN%HR5%u66bz4qz==ZIQn3(^FU+A}+l{J{i4UuQe4zU0Zn7w$fnA1J&78<6MYw|=Sc z{9TVnwdGg>6sR;rDhJwIhc8s_tdWc@DS)Mv@D% zhlc(t87)U?T?I?l6$eMh`P@Mx!$6yyihOd+?+v?%eByllSd6rc9DVuQQs%;|1ue`H zv#qUAl{DKwZK_S!{3wP81&Q>bPL3?fqBv@cIT6c!KCpX+Q#=ychOCeNFmTvHyICc= zs)YL@4RL1&As0gaDYO*MH&2TA>-15v=tZ@f93>OfZh6TlIHO?e^Z(G-x18=M{e|+Kn=M?k z5MF(jIk{>ed<}Z;!{{POcjbuv46{auHeJUf@!O$eXOQv>*WpFX^jzNk9VJi9ZQ=7X zpThSPr&(U*ArrgacKRFX&6&_Rh`ghN|0AmKW`=w!Km5vRFM_C~y#>9OD8vhrpYiSpPqO!tQsNjg~Hr)_ZR!DL({Tn&i z5HbqlrLDEKgsz`v;-016$w&QHU>GZO&1G$7OL5|ciS z2;s?wL97G0=UHyE0-O{&=+~avh+4~DC^{VANijoZDh~n~=1FC0mz0S1&QhOo=a3|$ zoKOcuX2o@bNm7bCooA%Yp^>WG>y#UgQ? zcU$MQbZ9-cN^ct{V+j`Rir-{iO{ zxL1RK#$Sa3Tn?}Z&^uHaW9bvSS6;${Ct~c+)16Jtr_g_F#iMgh>{|az5h@Yq>*gq>#E_5%fn7H1Nq*Oxk*TvqK){Q-djI zIB1rr*Z?qo+W5Hj~$cvMZ>$U-&*ryfrM2}#-}8g7xBqH6au8+*i;iqAH8 zFH4m@Tz)&@M>jr5JbTekQ7zKCUb%=SSprvcTZ3se<6LCrU@V6`oLF+uo9rX|wE_zQm!45tgJWU|Q0nIUB|B=9!*Mj=GW6zuVN~UQX z!6#{sMqi+(7U8jGP9I=h)a5K4ApV?o=@4~7B zC?ZkpZkF6Gc7OMh{A@w^sICXnV~p)H2n>+FoUx*FrjK9|6i9miwmYy!ja1xY)$fz9 z+ZI%qlNmav?z$`PZPCR=A3jKVn3V}B7*n?kVDdn15m;+W0;$<*^?KYxJ|rkVIgV@M z+^$QRKyHrJmlzN|(RLCOV<=W8_=1)(55`gGIwwI{ZY+eLOYU$m)Q5YG?lYOY`pyw~_L()g}0&e6`vvfhy1?;ZEPlgBRBa~0^&g$(JMhVJ*ksOAf)J%7GDhKiaqo_1PlFx{WaXpTpoZiM z^pZ8IF!#Z*NJpd-Li8QORGO;Slqt6cqv1HOoV@fxdm?K~6$_m2D1G~`DG%Hs2(EY% z;Z_!Mm6GMCC|PRQ=lM))PykdkehDd!TRgbR+j~Y`O+Q_b>U&e188AAn$p&;Pb;!Y;)54mw8Mg6SiDhb7l-caLMtG1- zCxvM5_;8ItE|?niv(b2{ynYlErh@>mjgMc$R9?{Mi@J#GnCIXEH$*Bw5m)M2)p^t} z`=Ogfek!p!%`dMKf|7~qs}$Tv6bfPr#}^ZO1a2may=w>HdUn`{Rh+G@uWTbTrd0#F z>Ece`b02qJVKI}zvGLItwA|KH5VT;nTdY74r|5sY;?Tz+ET84n4FNamX34gU2LdDX zCTB4T+vKt|w|NQ?P%?b*ZO(K0@0rGv@cvA(J-JRg0{*o(^(lB7&$y%^8f&i7`rBB_ zjVN`=T%+D@99wyawFDe2a5Aal*ts``5Nmy%YqwG58j&NBjx19=d=vrU-OjU9WMPmZ z+UQtMAD1x-r#nVs3t{rC%9UMK)gq)QE{k@-nJ{h4SJ*SR|6c*4{HJQuZbb#ep59Kk!9{$kcJLNi@D9KGw{FUBHp~?IOa>Y&ZhcZ$zy~)uq~XOhs8^uK4MEvS{&LDKNYQ zPyhe(J#SKIZzDs~nu7j6vJYkslA>?|(O-LNshkdBM&ydZjWZIDho#PhKuY6Lu{q}f zz@N4jrD*?9ff@y!F={)}OO?f{a2~L;uG_rV3!kc6NwLMDh7}yM)7Jd!?FDJ!xCLhS z|LZZm8bF1yiQ{fKW9l(k!-Gl|^Z;!pqWjL=#A51<(g}=fh{gKabg=d30fYl`H^S{chjfT&o z%$g%DqtV%wb7_*m3>AdLbpS2sipAqwS5}U$WL*O(fJ1F3Fd*$1x~EG3gqUzEtXByh9;OQXsJp? z&GIH)@$?>5&6{KYF0XY*Wc8m#SlW{zDH_fqxf*jZlXPNZG16_~zGtLA+_M!-kfM*N zeVH=Br;hPJn3#%|;G6Td@AH2Mr4yiC~WdSoWJ!pu;q1tmSbD>8xl9@lPU>PW-RG^s_3V} zKkZ)Ft8o)U5zSi^sK*SoY(!m*6{gP<6-Nu+)|6+^$xEjg#~mMyTP6NDL*M+on~Qz- zd)k8G`L1mFFNdQ&8CGQ9Xgd|=9CpUoC-5>Xbq}v#HjSEaf&UQn2QNa&93{lH?Q!|( z2?F~Y@|xkwpdc03KKhXvLNNE`GR3rrk2F#EVRnvw^(^Ju4@#ZI!3JVNjVoA116cn& zKS3=>R1B-2#^d(L*vc_d>@0JuHFX_nF}YM!phx|pbRis{M|YHEm69_mKQ(uicB&g_ zQJIWA$;9G)n3iYws|?jt?O=5+s0`h|LB7xFmSp?C7L!HbVpm(W;qUX%1U=u6vCo?r z{ya2UyvDV_FM{q@^v})77kC^ODX(wDMt$NfBkt$B5L-AR;~yG{FIJ5|S9n?KKf8-)VM)Fk53k&10J4<{7g{rAoK7D~~Ct9#< znV9iKJEb7hPN!mmWza9Sa$4yj0Rdxrqu^^$xslc6ByF7Y>k(3?+^b zQ5qoQLL>D(K7@X7^;kDsy&iOpN%!FPhM?co1;AjL2xfWE=Cry51L!E}og4Feb0xt! zLG(niUlq~jmPM{?!!&FnA{61Sx-~$1zbTiAODeWGsl#_^W_0DAHL}((w;LOIf&R@l zvev5t$5SfkL*f|adsiFNWXGktfWCh3(cu5LZ7R@N}%&|RMgKOa&nF$P#`_}h?WXpv_8EHK|e8? zX@is(y2CcbHjZRT=y)30r=OxTLncdpl-bvNHE03!8hM0l@ke&AMngXgAhzgiBe?r4 zAz>(V#Z^McFU%!Dw=p<5?m1b60Nv_pg*)13Bh0u+IXBv7(Jg;2Qptg|bp3S9znkt7 zIFq{-@1wv@)DTwrL9vRqEB79^MKzd< z8_BYKE#dADI4c=IGeB|mhu(!t1+K+NM&PLUJZ_=YGp%H@vEw9S zgu4JAY?>+1$c!_^Yu%}}gH>`)<>_}1hq70nv^HLvgeOZj?aCnm;$;yykVR`(lLam{ zU0*He*kkLq1CtOKN_MLN6!wWEufSLN0+GRpR)O13Ro*IM0XD9}YU(fQX)@eP&-D@& z@f?Dg9n@S%^WiB}4h9uJ+k-+rw2EB!;cxCo8H_Jei8zUtRs7Nm*u1Y~t@705lWQ+-ciw>_hj#}B zEIPH4;-IWC-PXJnm;+_(0&-R44OOBCF*Gbud-e$CeTo$Y?IF3*azQ8Z$3t5 zEA6aQP=FiS-3iM^#CI3%Bx3u4FAK(~!Y@^%{r}3mrrbf16#JF$A{lkjBJRt|=6K~} zkEoYVO3zgQG(gM0T|lmFWJ-g?&NWbe5ERf?$iI;eXy&m8 z>yrUJkM)z{Xw`&@)|3})`7sV;FIfYbLoxH;QB>EygCz#eVC<_jvrxi5u!n^iR73x( zMNS*usM#!Kj{KS95gnhAh{P{Zxcg|E2xKu+I8;>C>guNZl&16%(xpO71P-u#(~8Ow zhVx=!FxwuZ2*TaF-{yKtujFG0pUiLTju;d>HZr4*2Apr}xU4etV9P>SFw#tilQ~TB z#&~eul3$0M=e4#`qne#bEH%KM*fqZEesJfxpJfmFohslhK-i)MbPmnJpOa2>TWbG` zjPh||fBwvi2T?8k%EuluWtiJ$Y`^y-PMEb7b5J}h>kb2G6`^{6F5jfeXa#tLus3x4 zA+e*^`zr2ItS~4{cK1tH;aTC7&tH{nwf}5D`z$ntW2;_?7!!{-HQ;gCoIDlbu8|oi z=pUZ2i!lQgL%OmwaBU`6Wr^Q2J$#sh-z}vvEC&`78!@Kv`&Q4z$b%qHl6g-5Y2h-C ztC}pfglgSW_x8q@g?P4e=tdR(>Nwr+J~G88C;*s;#CtO_XS*^XyG1Z5*5;0FIfj)< z@N$BqI#aLRjt{=kOXd6U7t<+ZR$1lm`PZ3ctYnG}9gk4fbP5-Y-?yo5q@Y@_y z0uS>vq%*nLpY^JsoYWM3Wy=^9s1W4>U;2Ok87*P0ssbmgBNf(bLZ+q`AALt=)nz{Z zRE3hn3rbDbx?D?;pGK$K>xZ$dIWBsR!ez!VgKg)$YzNrpGwVO{bF+(-3MgxTI>ezd zz#@er&9rM(e{hkuI`D1@4|$VfdJ{r=H@x{Cb&J;6Y{C`b2{Z#D{+F=;hpyn;j7-QF zrD9vjjOU|M5$X>LHVksa$pabTanIpKT3jFj;%4>-lIjLY|H75Iv)fYnNl6;CvV6HY z83`GrpGbuA{Sx|PARXZKVM4*>q8U}@SLG7aO%`W00ZV)EKHO}SVk;C^nGlEch4~4$ zBt~AjJO__Hz91e_iD64>xBfem4inSNtV&Ume#mqd;mm0lS>rh>itHSsU)cPtJ?|w( zmTC|S#G5ktIOCVRcVeCse*tsXNV5>gg5vnyyC}7j!Rj8!Q0x%ha-QsB-lL~G%PmGw zxXSJS!%tqdd<9ExuXYrT^&`dscUSs(l4iUC$F^yGJ2G-VC>!_n+@<+tRK(Sp9c{8( zAU*o}NRq;_NxmOvC7=+SphI{+>ABzjdR>8W*ebf<7meod$gJ;U>*8YSZwL$Hj-R`b z=X0}tIoj4If3b5&`Lh~w!Y^aByy1amVkPx0e1fMp9%q6L>PBL`VE_FX9>GG?s4Hp& z$6J1roVZFWzya}sdax4{#qh&}&A%a#uL-!sOq~)_vj+Bi@HG@{uY)gk7r zumKmb0g*kteV!&|h)u2%_oADeD>F$fC#qV4kLv+>wNUB0yk+YKjsP|84*-0VJ+cSf zX+X*3l&P;1T)B?>Fj7n*<7|9!fcfc(;hO@XTTw%bL@l4Afj8f6N3li`>e*y7-xU0n zlY(V;R*}3Ye4ibCTsW!WEDEY^!~TAh^V8$D9}C-;Qe499FVIvXahDrUho4D>E%Cqg z1Sn&Qam^WtK%rwt-~LHxa9^s!^MJXPxbVoQd35t-FSt+pd&~T^i|Ro&X(iob9W#g` zaBySBb9JwKqd+?blDLl+ZIef`cPT!ZD}aZ}pZ+u!d_4p-HfAdth5{u9ZQeyYBPdnf zzYh(~9Tdtt2fd1_Vn}oO>}C9O8f5L-Rlw|aKlaLrlc~jz*P;1|Qq&}3_mECgY%fCT zG@A4S82Nx3#5E+E%{H3+(Z!#6I0W3UCa(1I=l_tBLN>sM#(?n`yRQ4Cuh^xmx+ zkXo4=v4LvTuUMf87FaT`0O4@1^$TR?mg-yQF!P(P&Rqv|R=IKW73*udCw3~Ym~EgW z{eG@Axen983E!qv{u@grJ_l@5>F)d<_4(U<_zfYt=DHD4l#Mt-8V8&E9-nwS8jZBS z10~b+Qd&&3#bVMIoT$azY>-A&13EDF5TKi8e`cxev;w(Io$0t#U7ut#W8!vbGGYZV-M0!7ZaQ4Tq&ogl zH0ecd??MOt=jisJv$o8WCX!d?u1(dcN587d<2KBE)o-XMBxjt&7Q!-M!TkOP3b_lMYmw@CfRXbUSDV?aZ|ZZ^ zCl{O@3dnqV%G$A(UzI}-d(c?w841L9^U~&jC>FDrhS1B;F|Nc|!jil@ZQ*UzoV=>U zlA9TaRy+>(KqfEQ_TubQjwBp_3YcDp8P)g%h@V-ndPUiGQonvZVl?k^_l^vwb&7$L z@9;rJCvRC&!71iUT^4a?8g*)@9v!82s=hdlHs%(=6#b>2m`@{bSevQjrrnu-U4v1v z_dh4^htN4*P2{J)E&M>usvnd;6$v@STFNY>9q_fNJ+70-DdD zGdF({qxxOaZFWhOXIx9;Kr#SkUYJ9|#al`xIpOsBnQLKeD)zUff5ZV6SZZ=3I$w?i z7*tBJO=MCl2+mOxi;NGB^X0sYhI-V+`dnkQe(B3|j#*~!2t%~@3UJ5fBoqB9iKUJ` zeT-4@Y3w`;j?_b-=7$xf*OWg2CRkUHM$x0DfgabG2p0|8y*=CxY(pq%k z!+fOcyX$OZb7G?jzgVt{yZym7*JI!v3Cq5sNQ+wfVL5RHP*0V8s4(<9f{_0c=hJ^EjDKFlId%R5fo zE$g)I$eJy&NClf`2}CWyw=>It;gNs`_|v_TyX=(8ZXZRdQ1syXZrKyH zyNsQ15l{pJZ}#@H%r}bE36G=dHQob(%czHmZ6Orb6jPdW!9w){4D|)Q$)R{{bBuey z23<`RIJO;>TAo=RNl*qF(4GvKZf!mXSIcH6mJvao@m)*{t+p|#yPJ_T9`z0l8a&{t zw#Nw#DMB!EUO6_zgCIhLD)+>d5lE29`Ns_giVpc%aqy(y-}&5OZd`&*XZ&eWmCE3i z{Pe+*BQs!WxDpWnb3fx!j?NCDR>wZuUH5lnv3D_6YFmPSd2!)JjgDPzD97W;Vv4_& zfli*I<^&r8!3(DXt*QUnC<|)^&YpxKSA_`Jdbs{FVN$az2ey$awMLANcfRl!>cqCr zC-sf3jDiTx@?4M#HoL&l+?dhEi(49wZcjR@0W!zW(nP;$R=m~QKjAb&{mY2w zltPL4U&;H8b@^IH1wJ%?#q+Sj$6d9k5B3bPbBkC+lT&vTkbK##pJ)kl$ttCVDO`7n zm!=n%I&9&>sR=Wl=biJC^haW^n2g?qEVDMUFNkL;xVU&D=s8V7(DNtwaS;(`ZR^}Y zp2A=ZI+pNGB~h{`C-5>z{-+o0)4amSDtwuv zST?(B?+p-pg3A=R=l6|v8U-9=EIkDzM*}tiWhg2|&`)bRE5kx!_2{1yT~@ek)adMO zSP~0h0yp_geZWv>__7PWWP45`{!qWHh%=AD*U0hD$56TN6Q!tyd-)r-|E<+; znmIYQ@!ake&cI$1SI1Gnb2HX-NugZ-K5^+AP``B0bA#Bvp(QaH(`_jro^I`eC5P%} zyumHA`ww!w(C#F*?nBm|x>$WuwH$kc%ntjSV4VyJq@8WNaR(%GFhcqN@UMUbU%Q`T z_*bJI$Px5*hpUqIJx71LGb${Tl)S31zo4Q!Dd z_6Tm67zHT3f9QP)Q?v<;7yrYqXud)$=?f%qvn-avY7GY}7e;jRc}=s?wTe_rX&Ko` z0el0M%|A||`@Tdh?XHjy2B>FJot%)U11ejPy?`sHG|w+u2yghBU}Ph82fC(=+cfAO zzx2Z__1zloCj?Mblap$E&KuzPjh~N%dxYBqxU^CZ%c| zuM8eE-BbKREI!u8iUu2kBNEOn`{wzQSY&25WueH%+lvj_UfR*k3nHBzgmV-|_^dpt z;4{DL$N*+pV-XM)%X^T`shp%;urr{w;dy@rmIJj1miRc*MP_3u#+XnK#Y{Rp8sPO5 ziWvJ|1db(Cr9!5pW{&M{p`vFPJAl)hPuf&7*F1p?eKk`#{d|#=@djb5*?a1P;D69c z^D@|B8r8Bki4(-q(e|X7>dkvxyorJNoA2CobX9m&7qE1NoWEp;48eFftyc2mK&i)K zu$`cSAli_3ZN;%CuSPDG5pWsi+i+C(``)o6M=eol6rvdRx~XK}=-1&E=BYOEbPoGQ8X$)V=s{fgas7AFL@()6e0U0z<8nf{jp=4WD*7sGm5QM?Wr0k&7h0=YH|@2I3} z62b0=Q%~)acF7#i8q9X8zp-np3jD;r9l%@zSW2;$-P&l+Nv=s|o(KmrePlhaIeS69 zafAK^R$cC=Cp#a;yAUotC~YcJzYESfWczHVSi@ zgUKCUY>xj;dxLk$vdpm5zts@eI1i&apQYe^Fu_%GoroW%ASQ4@lH^aj%gP2&OC!ry*9NbD2fYS#(WVP{d8o>jiSad45=~S za=nNfzZKtI#BsEp9N!dz+p?T8>X~iUq$+*_wN`T`*5lzl*SvDx#x(Zg(Q0V`XwxK9 z{WX7v1gU(HMDwJ{=;e|y+Q^`U$IY?xEj!t2)d2yo87Lm|(skI(j8Dr5Py=;x&~hB_ zqK=^U#3?}`D%~}&vRrWTHrY%XaE5}ptAVB;(jG)z{&Y7T z=AeJ$xPuR-42A18M*;7$5|4kg-1vwxqf#@g%^uHc#%>L&t*UCVN;~LDJwOH~)&2o+ zZw?5-4F5roz*#m$ccDddjb@R1Dv$|PswYpB{b+lXCf&`cY!MT;6oF+gb;YE2^ou<% zZRpkl@LI$Ok0RqBsw7p!hty^}ecvaX!I6t5Jy?XDCuH|&PQ0--qi<7*2FbC=p;JA{ zlGUVnxh(1*$hicn$Z$r>VjKxT$MPrkQ?A?7lA7G33IETkqFlgoNsBU8RqLs7r}yCJ zwUw+->!IT30I|&U4RDXoLPbRO*TDDOXHhh!C(Fo9eK9=QuP+YvWt{s3qn7AeHnDe3 zn8B%rQ1))AA>ZJ~$o+o2qXetN^gA>7>GqeJJN`S-!)r`0qB{4)_S*)Vbyqf}-o~>C zjE%RN*cU>CBh6Q~`$`n|-!69D}O4fj67O{PP|VSpLr&vTIZ;SWHfx)D@V zXP*R=6(JH>uS>GaO6Qasy005`q7Xf+h|5&n-!|QCW^9tdc#*z6$nLM4KiprvVW&#Y zw$loVW4M@s%w%8YlMrzB+6xU(q%8-&CSU*n5fcu##{s+W@M|es(@VLX6XZK>F}Q>C z3GSTi4lnf-fJbBDa5bqB69#?stYC4-Mdh2UO@0G*U_7oYFFZ&>RE0C24-5}CQ$m92jkvzgVtue6fwiQPNc4G*$L7cUzy z_LW?^lq@rsAVAXU^+G@o=|^21^5^K=dJXTI@Bjb<0GL1v?$E44AX)eauLZ*n>mQ4( zdbF7%aKzeAPyiw@e`5Mv)$7!4|7q@t!0iACf)_ActaX4VEtOnv zYE)a9i$pbeyZtOJ|3n#z4Ob2M``9a+>dNQHwer|FvUE)T3CoyKX{-otuyL^N*aywwH_)Y${u9NxQ!jy>Srkb zn*Us_UN(J8Vz9ijU6M_ZqD%4v-$?AF3hL2jp8Vz41!V7m9U+%f0DkJx((L5E)?O_I zX-c(rPO&-SLz&h=hc4Y1Tr!FD^D;9a>Y>n%S^o*DI&Fe^Oc7&}-{ki5YwlZd*a2;A zeg6A)2(PHMI2%O$_mzq!nx}wcELF~Q?ly)WP6+aQlL%$FsZxx|>pQi*mc>nS@^WQr z?1%3>ZPeL#xjK}01Evvllv;+o;EZ0JA6@tv%GIAy8u2*eM!TBY8$2C@U(>%WmpB^y zt*hrlDirazZ8phH(B!XTEN~F$5qdWCQn1QM&IU}4Mu3KZEuOCagP~yfy9$|e>i#bX zRYtyo109Qm_1#sP*iS6D?TnWb2Aw=9vHoT{C6vy;q-{S^Wnsx^%QdBrGbG^NZNI8T z(xzR<2e+_q37qD)hjp%Rqj1CzcUEn)EMvw4u#^ptx*Xawfo;3w)o3j^tbZydA3uq@ z1D}VVPoCX5#M0Di9w2CA-oV+L66$fAbW+O+9PGo8);0coQXorU`)8p8@mx^?aNwoc zj*E$KqdBlI5EjAZ2{T~6Oq-#+H@B)Aa;jw>A9*l*%?6}Yz`?W(TH;p_|1-vHfBeTl9X46} zf~y8-D?BZ=k#1|(jP`}D!cz-Yh{V|HMHIi1HPvC+G?cm;OmDJX7qg{lNwH0B;dV%k zR>k@M;uLfee}cg@M(FDEs0_yn0#3A#B?F+HP^3)b2{5!GAaUJYhG)A}NbW2*#n4-o zEI=90vwyw{MLx(M-fKZC-T6iR6HUr3HBeW2cF3HF(8#T0V;%f*K~8G31X1sgu31pU zGNXkHxu5_x)XL0>!`uo3mj{rW)It9oE{r`kCTRiRE69jb+9lOpxtZ`9=j2RyU|>0+ zn`lbu(YC!*A@`=pW4*~N+ATjOvD)cyJV(=FtnYEy1kJtrv|Ui>=FQ78ONeMwNNuWN z)A;Po*A9q{oN9+sD<%p`s}Xu@z&i`PQY0rQMqzoZ)Z!`jdEmKHMUtW84B&uhk`htC zs)gN!xB+V`fticB=k4Yk&L^=dUuQwgMy9eIRtI2()tHo`c(Tb6q6Vgjl#JYl4c7lq zO6Pt~5&ZGE&opHKy%6B6o8<9(MhNT?jo3j$&nN1IclpkL;}d}EiaNcEs2t&^$A_GR z1NZR@*-%2mc;OAer>Vowx4&_U9a`&JFg=-gq9&G%g!h5QvT)g-wv?Z#E-S6Q-I!X- z56Rn}Ud?2Wbiits(aiY+j^~B37i>IAS|{mg#&TM%GpR5eo$4XaQTQ=W0*m>%ALidK z&|KJ;H1`3zP^zHM_y}YMiAU4PmIn!roM#E+w5^YrCr{fkBahK>9oSo9uayqfsEmdQ zKjiTSMOhs4uTBuC$xqr5bC}ibw2sw>_hsAU00qt$Ioasn_`|BnTt+9BoIaN<7cGva zVzo_|hsqFT*bZ?@&9Mtk`SMtDSxW}8JP)8W)*Wq16g!qv=A>eMdHR<);RJGoC=3jUDwP_9TW__{uQbr?EBz;Z1~@)*`D(CdK?^KUbuWR zgkhbL%s ze0nuqJErLj{)`(?5aSV1wPgz@$o4W45q;H~ddJ+MgY^p0uk3n0@-f8#4mCc4jOi^^ znsly~ct$@I1Np@Gd%)f~BPGuVr9@W01*sXk0oMAiRw%WuvM+s1h-414wGJj8GLEq) zmzBQ}+KiP_`pR?6DnfZyB1hSZVTF;51j*4erXR3x8bNbEL8t zinG(O_(QFavXX`PgmA}Is7ov7I6kdlG*?R%^H@e{Gy){4^O510q|6QT^i8!i^6KC3 zdM`1dxc0ec9350S>|C_zCCZhJmqCK!^f3Y?HNLSX;)tdx8J8h zbm|lR@UuTTHb=9N$_<03)(mzWtpBlNZ^1-l6|c#47f1^3QV>^VNTg22D|WRUnNk%n z2bZ&*_}uE;eq5IJdp>mC({<2A30E<3eDwRB=KZ!7Tg@c#8y9xD&ezZd#dc5b!TeMN z_rK?*Zfl3vL{N+iW%c$2%v#HTPuCmHd#t5NKyB#KaS+E|&ZarYv7LoCF38l6 zJRz)uV%|T%9{!pbXlmVH4H+di(qAim=>n0v7SvqLcg!}34)r3q#e<6zcTpNUlG`_u zVND>eL|T={CGp*C6y0%-SxPQL7i8#WWP`jjOPxNOJHM`bq-NJ&O${4ZRf=u_*hQKiu150j%(+fBzYo?sDrwx-DHdbN|4XO+Hkv)IaNX8QgGVK$4ZBy>dc zGhjWM`mT zhjHHlHir~%2%4SQ|L;!ZN%^>0QeG={0A{!5pDowxC3xHy;rbq7oyXPC*#}hi8rQJ1 zNl5d=7uRuXw5xyR&hxkbpks0yVM%PH5114rBKcekHJ!Wwe1!GQhA4o3N7*nfZ)58! zX3cyAq3Jb}8XD{L)Ed5Y>LK`-(c0ysw*@l9f8n<%s{n79_SmKK$1`rw0Xb{^5wgIn z%3XTB>bpjM87CtMvnkeor|_lEMV@bq8z41nwk@J~N8YBCVM|X9g25UTNaHFg#5|EM z!c}D zyTK21Tf=|hEIp2dx5bc=YJu28jCo>jS44s4+#Tttxu6*rQ&UkFtUWkQ`@i2W9eCj` zKyUCGBG`HV|IhIR+gu_ZVw$+f2fRRxVx{|-DXS!33$!RtCMDY%{tUF(qS*yQ2Qb## zSi!u(ZcIbK3WsOV=#jYFs`qsuGy2lFkRQQ9)VifVtUlR$?mjN(TG(M)y%HKxJLqy9OkvDFkVg04y&a}Lg6x9 zJ@M|_rPegUf_c^v&E=Zo<%&_sI`|22o~?KQZy~jvb}mt<%y_@HQXPe~4RQ;C$4Ed3 zr2^Wh@zK<35AG8y<8C#ml4R*#ogkvM8tuF`@JZmv5w7i3>n?>^>+tvKmRm&zZss_k z5*TkiESHp9K5E)>U+1I!LiVq6wR~rKP)dBjdNrf#%S;H@Av(#LU+jfy#C`1xaaJAC z!^QJb#W*h8&XkW^!DaR)fMyMYAWYA(`0uH&gM?#Mqf5YIm5-PT5}BQOIAr*Tot5N? z9UfS-s!GPE^vXOoaah(ZSVa$lkVb;=Na)@JoVUn8-zi5W?S`gg+!(nXGqoB8!mfGp zWbTsmM2Eo859E)U!Ua4?W{f+ZZ{T2kBCs}(pVdgd9$I$mrjMtRixFGljXs9*H*XYw z>klSGwn+~n9t*DUFO)r7sdVZGh>;Q*_tvXC<;hVw!e?-=t5{G)%@*MzBx3y9CaiJ$ z+ct)H%&YtI(I9*7hRGP+bhLZqHG%`?cQnILZ-<{c78PPsha@44zcq+ApeFf>`_)QD z1=9`f|5?%-w}eRzYW7G;%ll|$&qXJ`1XPtWouhV+sr?i2-HBua`zeXY)PxkW6`?pm zch^k*Qs9X-Htaoh8%~qN_KYG6eXt2UmeNdqhk~rWXafhl9Kstv0xWgSLRPNbV2aHT z=ju4=Q@}i37Eo&lB^=0Lb~GIGi9;om$?7%7dPD)zyaE3r;L@|$d&9EyPG z>>`GQg@LOcC98j7SEcP@>4fvcqTOPvEB>Ue0Qi;gsqJoml!j0at&1#N2B3p&Y)v*l zANWJ)BxKziB~&bz$r*!PWa=e;-5-k+^KN`>gDkNmF-+Z(LvAmMO$7DBH}-MLTfoMM zT0WaQ>Jdo-c)rTYU?Bu%rPf@cW|O5>NXVqQ&Ig7`o~{6Rm3w=UqG!n*RnnOVB@@~V!65xo z4~>6M@G!+M2`=I5W4vBaV3yL6CP)Q;1bAwyj!-VLs=ntPwJs=UCbE;(dgwTS+z(T= zkN73r{d#zS#SMEIV%sUw{B+elKUDS^I9)1QWluB8i&Us@c0vQE(4~9LTifCx-Io}Bn5z_Q zwQ{|2wJ5Q-`M`A!-(o_2!rI5~4#gK-sNOlL`1s4(V)6U-Dt{TKvGj>* zoBlTE=h&^HxF2?XN?vk7NP5*e>D%`wPWq#I^V7yUtWAr@AQF9x=eypYuBv8OxZvHFml$Po3O49G&1HBp+7_xLA;+t%jUk@Er~C zxJh-QI=sdp4kai#N6W)7<6*Qq(|P%H;d-Nh#ocp*j_48)iB-)W8sMqMQ+D{Y>*9TS zDX^8&QFgwS#kGUsN|!l)=6%{xhms+o)ik)O%^sf4pV<}U#mnXbJG*a_g&f}e*c+VV zv5@J8;$qgKZJQWr2L)5I$V%?w5uRZrW{rR1Un?fgt@K4^IG43eSt8K9=IGd1xb4%I z__8ILt3Vs$iOigYhv4f{A6poQri}C?b-VYM(YF_2cv|Qg($5pa2YfngNrZcoIA+Is z-ZTD_Jfb8$v`yFMJGG>5E5t7^07;gaiU~S8`Ehl2?xIXbxnjO z&!J%JT&22ZPjTDH@O$BH1Gp_8!Ld@w)yr{9BmDnW;QvM1HxaJHzYs`ipXW~T+8))R zBg1&krOlwnk;yHwo`?7Zcwc_4LnJYd4oLa=uE#nu2zxI*92A3OjoP1+gtIa}_od#& z3D@6?skLjGf*fpYmoa@Lt<*BM!79(Ws0w%v;=v>M>j1E*2*r#hA{X|k$k)E-z8lGC z&Mt=?V8>fZTbdkw9LJdyURgAkdZg*h=p~d92U1iT8=lq23BYb6M``LiJjeVT=dyLw zaq69=HJ%L1#ZW6?9N1Rx_gTz%THaWjJk6`48%``wLO2xVAdCG;_&p?re82NdwqJ<{ ziOnyRE58W-k_kZe6WVm|d5HL%AyHL7hmyC}!TQ$Aw*4il^sfo_c)OYq!s9cI|BoT0 zACLbqHtZ`x07BJX5;ro(bG^~HBAz4PalC9Hf;q&6gy91S{jE96bnHXgd0(;*T38~V zFcY-STgB-cc@QMO5uX^rOGeS0>YF0ff+FRjZ1SMLcTsv$LV{?xEw@Ll4MeVs15GL) z{@_~Gvu_Vo4!R;aUhAmPh5TVD1lj;n$zqGIUV4V>ozq+Y?&7|4g8*(0yxmOMrtSeeaNlv^Ipy{0^J z>C8Ma1oobvjPK`E0Na4EoQY(;@=V0Njt8X%Ma*Dch#DN2ohkH4Cgezef%(h;02=Bv za`4B0wrux6E^aJ=8D6b!8x^nb+&Ov7q=)Q@yN0=lf!x;iSDK}dhg3iJMZsn+ zI(F1T$%=)EoGyDFEBqTT4|1$}U6|V4pep@u)jA%9bLadE6BRuT@#ecTS-rnWFz=Jc zE`UKlq8X4AF75*AS|?ur+u#XNd=9=s1!AE?L@`w~YT^2$4EIlupt z_0WdFD_-^l2;7#GlEaD5wD68=_6+5Z-m(*4B3^&p4o7W=gs+BylDq=`XT@uP8I|6@ zYPL#JUAF49^oYd5NJ&r8a7@*x zsrX~(VxpuRRh}5+$)Q|S}&X-+PEK|yMvlt3`G|kf25ss6E7QCur zBk0NvpXyPH7`F5Q6D7zvL~3AosJ@giw-AAKTe08uDvCwb81=@}J4uj=rU0eDY18|- zAVW@T?=_U?hd4R1LK=WBO-d903@6F^TL4-SqD_`Zpg&pAD7&+fHf*~Qx7;;uDj?MD zz37uJj)bp9N#g6WL)Qp&pdH)|*Jd~1jS>TmvB*H4ugd}b;Jqwb(R1e~^-%M}_hi%TF701JSa)_@c&HE<*)_( zD}dbWDH%9M9oVt-NWxzbP2?{%Kzzzc(7`LN=_3Jns4raChVcX)=Nxyu&|_>~t1J zKXhuKUXz{bUc@%8Vrot2A6mWS8GaQfS2Z8GhCb&fiLWURaAbT)qW*g}+XV~BC`IeCFh;NfwzQ!;-KcSh)0pl2o@ zW!axiTsB#~EoFX+RWFHC(3lK~6D26;A?3g&!)-f;fd?oGzAaJ~2gjNl1*`}{l zPkq?nE=STW`5B$z`F-jyEPInh_k*8sh^@()FmKORnsyP$MLY?rD^s z_eQSGgCulI!ub9~T1f2D$_mhckv%9;=_#dnpWPc2qza~d`^?#^xnE4z%WD@iDx#kY zQe`EJ>sStIWa-RuWCCr54ubK1%81R5+tZoxdOO`b7z;tex}y41LO-G*Ig1qsiKbG_ z2vCZ5(GoG1x&DM)R7(#NXxJt}@V7b5*0t9`N7?7DZS+mb5O(YA2>VLra?y0Q=)xKw z?q7E>kRmBx6$gPzvL)Lh|1XO2Z_jvESEY^DhVsIP6()k6u zXq8k#Moa&TBXG>10|hC7r?D&_BRwvsq43Tsb7*~I?WtZZ;+m;$0I2HRfq&mswkDYp zygHFK6^Z3AKY|e`pgWsv(v^d6srp0u;(9SD*%F&BLHty?*FP~qm%iM}N0|sNO0ika zRNr+9R_Cc_+@dSvT7KEu5rWC!Alyc*s5y~48^;+0Mio_S+Ol)Y$2$|HVroXi+i~`t zg}1>ub!#UdoE2KPr9rw1R!DJm;XMvj>Wo7E9{WY(>;V*sks`Etun_AVN3oy$UREay zKxl+{qJ}IM=G$vfZc&VParX&v!P1{`KVZ(IdPO~8@$lmw5fR${qyqF4u-$0R8BdiY z5n+D34*0JkOA5$b$75nYkHQu(a?2j8wS)Dl0L@*cy z(5;gea}V-mw2OpXkkA!@V_dnSrbB5WBV>@b~96Kfh$IQ_9TkA4)+#wpW9 z^%Iq?5%wLnEV)7w?eAb1upbqC833m8!z4WBt?{DpD~F6cbf>F?R^dw+5idJz(WYX+ zDJs|ixPoW+KAZUG-TH@T!hP@TwbQi5hMj2gg)=4eeOOMb_e8V-tUNQw}Ij}!h zmW`3AbfQ8DR_ez1wp>DafS3BSG&_Ol)s9Dw1ae{w_P@OBqBV0ap$QI z8VzIQkI&3pgq}z}wNqWSg0*8Bq*umou_g4sfUj`PJbetm1gGmmPZ5LKf4U*^nWoPz z|8)}l#;(ucTMvcFHIjH-F8tU|@CAxJZLTn|HtBlAIKhT zp6Gf#c1g@~ovip6Nl?7FTaacWReuOXyzG|)Km6!!^TbfS3m+y`?9m6r@o!Jknsq^dL< zXWaF5p?l+jRZl&akx@6&z5=MhOc%RA3siI~|G`(*`4|MTOC8&T`(i+q&YEu`_C6Cf z6A%813f^vi-L$9p6Dp0e_rH!YErjE}uix5bz%dH!fj97#C6|a&x5L5uaT(_atEHdo z`7zu%?LbVFf6lbO8f9QRF7x`f`m>^Eb}Tk~vX6?;&F~}8P97(Wo#@8CEETW2uQ)Sl z6+u?sBQ>yH|2Ij8^JpG%WO0x2O_p9jR8WIhI|9-CEe5@geTUa3wrlh3%Il7yU6}r> z^2?q1La}CV3a&XD0rH6T^`n@mQXM@#N;I}pJ1vG@!(q1Gqvbszp)Db2Uv62M4s=cW zW%NTs(ArzqU}F{jn&+;Ov;SIA$k4SypDr84HDpgtEzgh-WF9QyVmm6vJ;w-bGHKN3 zvC5lu5$vZH_$4OuX-WpeK2RgjRtO2bCX{ybj;GVKG)C&V2PTBuDF_ zS#+g4`taP2^Doz2|HmPgCj#?R!K0eH+h73>7JWPO+0Po9F4*S8qZ_9n5Y7&}wAE^r z90jj6hyei`eoD^EH~r6DO&v{J9T!qSolR4%gvL`x z>qGxJRBH#Exz9PbHX9a?q^{0GbuW@Q?f~P!zY2kyS%RqoUNVT;xli3VUY_15&ly-V zn;T=xG`=T{W-O3!?pVURe%)QW6=ed1^kOWpWFuob&Sga@G- z3oFKg>dk3U&J`y1@tG2^z7E@$Nnof*ZAS?H+|VGb(%>zUFMMdxFpQjbo43Vk-N{ig zQ0j-_n)|we1MN^a+#Y2}cjGp94;@d!OTU8+%!i|EBbvNeD5=BgzfMzE(YjyhPxod)emqGis0LOZqX7+H zXI+MK_t*PR3msWysLN0Q!YK=};)9Pq@>1xG4*s)YLB3JMmqKJRQRvdV^t=FR^Au?* zF7BuQ*L<+uFT77&-FP}P&V=8z!16gJx6g{6?m|RjPy?cuWglpqUzlI+?a=_B=i+lG zS={b)j&ChesFHh2FuiiX{NR_dhnOnBvxA7TEE)N{R3hY?tgsA*^DYmwQZ`&~)GgG6k zL5+jhMLr2%q*YVaghGY^wlw>xi}3trlq%C2bQd$yUD+C0D+Q;GX?b8~@8SOXK>|PH ztlXE-63K%txG`A?b{==jv@7TAIH}WSGX+$bN@(g^;W0_djEq?W%0E9~0v7ANb4?}$ z-X`A(3sjPEj%OqK4)5+o075{$zXRVUhBxto0RPT=$zQ4dl*yR%S~o!Lz3O5EzkPGt zm4dd}bNp}i6SzmDP?qml#XS{*g7-pVhk}pKGdsSin&NqMzMr4|O8C8uN=T@Og@=vK zU&$eXsbxaUFc&qYI^7{QvrKWTbCnWxxJg!KlZ*}&QujNbUTV$kTu#A_?CU>~o%Zoh z-wbb@yKVOodQp>WL6< z3=vR=zn!*6HqHi6AO@sNL+&)fuzLQtnOwHeDO@Cxxir_18j>s=NNwFt(@5!xR3kIy zEfKeQ2(dD9qR*ic({|))-L7}|GqE;J#}{oT@nZOAyh7WW3jRXGK-23c&GUu;)unSZC=c@jEHth_Pf-S^)qSsnqLo0@ESh zCm`}Hf^%*`3qZcrb&Y*|Q&L3X%@1u1IbKuK$7tBhgAiy!$v>mXSW?wQ8D`1oaKV=4*|B^;yH$h?1^F^E=S`9F36jls8apc>4W z-PNCI8bxUNzKvb3Z?h>(f2O+Fu1)}JX1z=;q)av${Dj`s-~oN&_dvT@E!5fS#HsmN>GEd)Mcs?$axZq#?WWtoUaz>Eq-wg6=9M9Fr67n6hW(6Q5$2QrE z@UG7P5U|S>KO#cl2q`1z3}>36PVZM3|2j9Q+_;L4o_{a#K{|JfEznT+fb-=P4$n3w~e02Zw} zjv$bSwnoIP#*?c2ky34r!pGcCcIk~$7$3=-G{fyZtX-MLAL!kB+NQ2NJ!mXfv@Ce~ z=bhH}Fa**O{8fJUf1Ijzmh=Mog*rN)(He1o;1WN#`Pu(&%;5OX{E>+8xi9EBprNeR z7QRw@CI`?2-J#7RgT(*=O0UtcL;KZU`%jfgAEdKl4PzOJKUbwZId?JeneUCR30dvm%LNEo(;)ChZ>jF{_#8ADJ49$9mSCt zDq^<|%gWDDao0GaL&F(Q@{rG365>U|;oj!-?e^Cse^|sQmGna>1PEcK!};y5858`@ zL@B^C{CXXW0+tsM&N75P20hZP6AgO&8Y+W2V%hTlc=&1eyF_st5AofwxFT&Y7E<2# z^6mExSSwx-j~=&3o&rogiP8cqJe~3kOw@W|M*li^=`_eZE;D|Y%hTXkD+cUX0P zKwdD*61-dCg7uA<)Qr+OC%(c^sRqC{bWg}NGcpEn0m``jeU^FzH!lnsj9>jtCVLR2 zz%FE1X+k8dnv09lG}XPIc83K)?u`po4_xk4ow8qFpu;rc@=g>2>ua%DsXw+=F;b)+=BmLQ?;y6^hHP1~*Q2yjKa(2wQ%M zhBt@u{=lcmw=9Hog=QCgLNl7Mx~Ux8$M_4}<#w^6%BP2Zy$F)9?6H!Q`=tUHRMDwM z5$Qtf+UwS#z^nW=#gUhA9TF;1ai0Z~xmF90AKScly4&}HcZv4{<|46^8l;=kgSn~wG{Rbv{{mvgHw;&v{)wkWjw?$V_r(Ka^sqAp2tRk!TXWqY`fGF+KBf(dFF$JajQ%qeBjMKh z$y?H65v)(;yr^3db0;1q9<40|y9Ya~)pYed2@aKBtI)#K{|-na)>WiGXm# zD*F5qmCpBCA!+xDV^lRK(2?mpOQ)B9eHjNa@jd8r9c3k>^`PIiVX}ZFQJ8D7+%R@q zaZ!y>UQ&+&C#ORK;KzSoyfg2s>rX@juM;>e)#Sm-L`G9AkZ`;nLKYr$O}fM&Y{vZ} z4@sq*;Vbn7q6bWMk$X!GLzU}U!||Y&-N{xr#(239jZM+vNGl{eGZzOf_7|UzkNiF% z?bp{9{bit#Hh9}q3d3Vc2cl?qPOjLt2cK)dDRz+!fN=WY1~a-&yv5cs6nC5C4661a{8rQaO`e9J-68VzSeYPB{=`;{Q? zcUhtPiCad2&-EKk^ae%2Dk&qkUE0$*)?*kED3J7;c{N3rfzl-+4l{eAdenHo1J$lM zp`p(9do5sAg_tU6SJz^R1fo3QHUKk%Cag z2SK5I%kb`S^zkBAjC*2z-VlzqB8B&eb|WT=rY*)|Hl@~;jhpY^gtMLo%>2p^$H+(_ z-^#%2ZX8)Ptmm5eK~57SBr)_Nb|__r?_Fa1?V(FmVWBFbU>D#p=y&<9(JPjwUMH|9 z@;O}uHw5iO}_;6QuD%9a&<7p_rbliT#U zMXQ=^vz&LCso=d-fLMA!Q~-y&AHx1by#{>mz*OP9=b{U_jz4UWWRPJl9p-S}5Y)YT zy7)G8{d;B|eOiga;53ILUt#&`feusIWy$akh6*byGlsSw8C^NkAxKWrc6u8;{~_=W zL^xrLn9((g%v#o{e$C_(cEcwrr$uKg))Jt~L%8W|wyf{Wm!Vbdl7}b2D_RAmLR)J+ z|4X)lZF=AKU8;V*Pp2jCajem+Ho+_c-KepxK&0w134g+3aR_8U?zb`&{9uQ_w78{e zFm21}IqFR)Bjr)~1Facvy~N$LvqTcpT?QPi_r;U|C`+CjiR>rqK;s~5f=xL=252O4 zGS`~>6ILV)SehXilJbvG2CWN|_Ea?N2eKkzmuv8IF$Yq-AB~~Bm|wNifgAtkS>Jxl zWU^(BtXV4?;6$ry2T}33{bU$-qMr<|Izm$vT+9x7U68V)wEM)w5V^MtkXn=hw#GJj@0jG@KW8GQGnJa#F zx?&9#zbp4^%(_f&)lL-mLkH#gOJg2Sc5=Py_IuCXj!2vOTJqS4EFJ^ELpp6Az%|D2 zc$TBg&F5u~J>-i^AL~IpM)&5P@`ke4*^(%lTnZpZUy)8z8tQ(VpobYvC?P_l?kH-F zvP2gbk|vS$aYOd|)XjPx`Z!#Lg|8n2cXTqm`Q~rltS9pt_Ho@uwJHg9gXT+s6Lb9s zXScc+h~N0ma=0U~>f#{sfRnungMC{-zdxgo`;*K1UKYT)A?0O;KA$p@dL+x zICx~lh|I19Xa-1HL-Di^A&yUWLk!&W*A(hZmX6TNPCXv`ag0id2=K#&fbH8tnOP`gyj5F4n>}&< z8yw>=4ac?S8}L8!m1B!HBLFE^(RNzj?=tPqoSJp@!lU;=xNIV7|Fcy!9;b9-x(Y6h zAkXOa$bppVEM*~WM2$}zoPJOrOYLIK$qa_qPieg|uT^0=f(SOw`o$lA`dhM)UVfam z5kBm8jB92<7%cZv+A$*DSrD1|cQdERrMW*QQKVyX8yLRQ283MU;#uh^?LW#wPfxVE zn~=w(m8iRC4{f@0^S2JXDdD0i5E{cvITIJ?8$~W9nWt|Nj9lyNy^|GyWpKK^iX5z=x42#6!5+7#ssnqyc9A=S9~sII|t$ zQR^O+p)$4MT7NB*9~bYf7!io;wk{8*f%h?;Tb=q<%tG#t?=sU645ADLA{9>-?|?Wa z93uSD70TX`J$&_Enp`aX1o*0}xn$gLbBFrc%${uJuUw51RY1DT0#D(6%~R*z&ew{^ zLf^RW+uwKxGE!FVZ87-sHWF|%K0$mw;i*v@3c$RW33KMG`-tdtmysfG`;IgK9#VE} z60h0|qreMN1;E9ydS2)fP@W51_fTK&UJ6un1#vl3MIZamJ|NV(R7*9-2}+bARtDTg zYs1kp;jEJZ=BVh`#hu?SMil4UkwvtJ_V?=f-*5ht5QhwR@UU?nUTwh-_)>zNU;jXYXz(_fDCz~8&qpUtpYfJ)-Lk)*lgxuw!--gwZ_Tg=E*t@`83^C{ z1WjbmJDEPd8KPr)2VzXPXJ!$L{kf;w=($kr%jSj+9a6h1Fa)}&)T+xqT81|CPNwA# z2*T|Gav)uQXGz7BWU}^i&jyCuvrbiQ=UbJIbo0tU)&g51r03;s{8IGvdk6uSnkZTxV4{Ji!aC5NJx56!4QO8gDQ5py##&w@c!NvaY4;&bvQCepGje>ew+m37)4W-uayWoM6u(wc5O}^oZP?(+Ni;D zt1Mi078Q7ZSWw4GXFisMBjj>7!nujjGoGlfGLv}w6yi&b@)iY&Dp$j*=1){t-xAuG zi{MnrT$3?SJ77G;dT zh`qpvV38@l`Vwes=PQ@dm|vXCo86j-sO3ZY2RSg?eMB_&nsT0ii@oL9gC9SH?k5}o zF@SxjPM+=9=Enkyqh=c4eXS4%i|FpEu_4T0?yfw-!Dhf^o=Gs7K5kaaG6z(s50*SM?*(q?CEt zA)gE+x{-(cmRc4I%)e?D(Y+peJ$ zGXwmUDv;s@xP}d)3_`#!0OWb$zSiTxW?|HJC$1=LHvwu zG5fO5?t{NMpS#LDw@uPan158!=>kDG!hf8zXXd*>R#41Ndaj*2Y3%QHUUiGRTO`lJ zyl;bAaWvGfgg19zin!s~_UwlS)p3PGdi>m)I6pgy7SXpK&(v$Z$|f>sL1`d~C9??4 z62G(;Pm*@kz`^o3TZS4KKWot4XQ%=E)Mc=77`cHw4*lkY-g8OP7tju_8qnkjO!|{S zGqQ%tdp4r)E)e3FEau*E945W%FuLFDbADkmgRKSyYIvkjJaz!R_69qq#w8_#*NET`OL5*Uzd%^-~`ChX-AjblT=4i-cKbQL8 zuC zny@I*?a`$$vQ*Z`rV=6auu9p)^W0uVp0ZFz{`Wh)3<@d@R_IZpl4lZbHNa6p&!1EJB7w?A5?v1e8MRyeXT4 z7QDsp+w#s5x^fD`qpM|weU@Y3>rh@h(AaIRdiWn2;Ov@pBuy4TEmVGn1&h1aQnnTK z9avd*t}$9Vjd{r-J7iCdossgx8FhL^-9i^d!+7WAJCRnFpbNoY`G#&ZA{Lr3^r7SL zs6Y9yR4iHo<%TKjs7On))lpsW#y+7Zo1bT04JPZNpevf_=-}4ek|B1 z=LdZLM<^W{70Updr5{6iJtBz=xZpqk zMTCH$JsLrPknmsl$dM0)b}hPGKe5D`cd(tO0a_1=NFG=~O4=f}j4xX)@aHY-NHB<1Ly61iHI1%$%V!Y ze-y=ih(6Tj4`o$-Jo%OZ|v3YQZl**s-?2b0XbGuoTE4Ph1J1`9x& z$5-Vo5$PDj!ME5RSxR{qgaOd$^3Zo+GRxHwSSheNT;%eER+WAki#jE5XzDBuNkE?Y z+aek5Iaht~m9YW|h+Ux@TDuak=4`9b#uXdQVe9`zNJuT#j~j&X_sTHQN-G^}ARLAt+`T$M*t(1BJMRZ^v2pN{vOy2x zu0{h9Dke+fsV91Zx^5|@OC}F-)gzTipz<*1L3D*?Ej<@LBH)yD9l1TVUTT59S4qb$ z<(*TfLU&;FWEt8ozhInkQLF^~3N5z;9&|bvEX1)l`BAy6K&EO;$XfExPd)|GIZ}o0 zL{4*u0V;lwyHwn&%jL-0^Km7?ViVvcr29N(fkEyckOMY#S$-3ZsqG+Cv*-V-$cR>$ zwXdXlM22D0v97iA4~?b!UfGUUIPW8v?)jdH^G?A9FmOI zuKzYhRO@B7X;BKF>=uzeI(*(!AYc{qikqf^9(EHI#`)x)y_H72saTJ?s-ahk_w|Ai zZ=@h5Lv;f7#abtk?|VODNdAMwHa@n!?{jTCTjvi13HvD}Of2YT_Gq#(gG`6%j~B4F z>nT#NTU4Eo+ShmvQ^I+xe}+5?EJeHPYC+`F_Yv*Hg|P|9Ttu7N2u+igqaJc(*!=v? zDNM|js7k>{`Q!rz`q2#vg*=HY^|aom`0#l-+-*mPnV={q_KB866`Dy4A``jln-|%D zFJuD$U)&l(>Loft$+oAgj2HrWM><$z3r5P4A)^a41Qb~&&!(tdb_ToQu)Ck8Nr8y> z+Ur#2*0ge5>k;``1&Jqg*5~vFcA@Y@0rS{-&48RjuN-l)`@pc276&^H0j%wAlN8k? z8Q%RMegt(T(xx3_J&DOTgmaVqFpwvrORs#(YDaX*Oe=zUF_W;`IC*25f`x^@{15#+ z4h%VvSi)npcxz5V^rKfT!Ya-Zn*ojqp`WHo#d*wHb9I9{LIH2$2{=_pBrHgG(L(Wo zW0bke$g?z$n7`rP@LrZK#Y1zJ^LlvU6MXD=s&@9vwWIq0?2}$8Kix>LAz)%mQXne9u6sC@S>rsLrI~@B%RL%5Bino1_`he)$Xc#4oF))hNCP&N^>@jY(x*rz`Lp*pZ zt+XK%a&GCXYaZbV2-3+H@ztOv8qdSIV8W-itd8lm>qQxr{X$~Mhcqd%0sD?+c2qd8 z$pVFksM9BshPG_Raf*=a7Pj>mn)K}`Fb<>bxBIQL03Wnqfh0sIWo56~@+4dkgh`DyysTIk zp6-ox?+cz(kH}wpw`GhvNHa$|;&zj91ta2nS{)>{w&~f~8V3P={c-KXB735*DjIicsozNb9?+rzo} z=bNx4v;xO#j1Dkfrhx4Js_X>QL^C*X6jmD);G&w}{v4uhx88&N`h=sn6UpBs*D$^b zyz)*h>_R~&nXrjVZDTd6bF=C;GobJy=O(bI#f<(b=Js8SgkwWR9X~KZ#w@0@lD%I@$Og2l=@s zZa+7JXRmQ+aq_!*0bAS*=_04`uLfYx?&Of?ARPxrpg2{sCoo~)vM?oS!KvRE*-Ytu zGpuedM;Yo;m2T^QSC}ScGs^V>wiLnp?YpZ_^1Eex4w=;U&La`ygE}G8q{D{sp$fIT z5C?aRSju#8Zxt+|q&L)3f_H!U+ncxyvC%j*E`o!95`A$LZ)qWOf5E&kQaplGh4f0= z2OPy69Isr?B&2M1^XXzK#!?rzW}qeMybW}0k=Lus4%W|@&TJFhAbk2lPhbP#+Gb8E zRPbpl*iK@C*R)21LK*Sq1M+J(BgqI#Jlax+fh3vHX{~kD?p!<#kV#tD04Z#WC2u#= zk}%hurbP^fKeBhGO_}itv7tu$e2i7~)vyVh5qzswnOI5WN3y*ZMumrQfmpJ7#{zuc zyoR|39p;-$dDg-+-_v-urz(xr3C>9A-fo_6dlDvF<1tL8wW6 z;=bLBj=d2ywcTTFGT4+$!>1DOgo^2=sBU%^`s6mh-O7Xmb zfaq>`ikez11K;aHAqCmQAa!@wdz~`9GPxnG6z1xrq!O+GUDUXql*&$$=oC}>s z&uY)Pley;5j#u~|X`0VX$N)m@L=W8tZ*i#`K9U|BM0#PDPno%#!yCM2H9x+!|I)@R zGYEN}rq*)Bh0^z7O)%3$3ofQNl0T&xNB4cYF;DS|&_Kg=6#b^*}&XdT0huKuF(h5;S?>KZ( zC#gipN8Jx^v(g7BiYe;_O17Yv(?AOD-F)oB;ekM+L|YHqR6x`bo3S~2K!k{_ULIIx z?Ai1)NUpKm7N762DeLWB;_29oi146h9rs2~osJ%NIq1ElyTWJpYr)B*Il~qCE0$Q7 zGlUwk=SbYbRv~C53A5gCJ1i79sT#JVyR$Lf0?j6d^~|gI=W2i)N~Xpdt%@K&U8Lpk zz0rmwgqfB#;0W4$An*&E_yj_xwM3BEku3}d_cDd<4o*3gg= zJu+&_!mc7rZ8qPBIPPfr0d|Edpqgvg9OuR@To3~y|@?hz4R^7LH(v4|@D2WJo} z(9Mww;qz~<@R7804Z>s{STlg*25nlyGEHMwBtU*qA_GcXCjLu1sPQ^v`Kk8(Ufw|; zw>Q90@>nKNyXa^Q{1CH;s4AdKn|FSTU%Wbr>l#OI{@2vQgLm=>ddk*kk7l|)-Amk@ zfb~cb@!7@jm}!5Nyoshq#IT->(}1G~@=6FsqbI$Pm6{56uSLEVm$yHE^#x~(J07av zoorOBmAi2}*N9N76W*vPrPKxfE$=G(uRoP7mVnmC%S&6P#&X|fbk0@}ZBa?XH9uN) zAm`}*N_XanzO(o>@J612q}>OaKd2K1S8LL{wWIc*h0w|M%aC8(M(evA(;1HUfj= zA})Se`T^dd>qU39JIUX+fqT72a}*opteX@llS4WhgY%_fO}v5_8F(FA(|Z>v zut`#`+*2-<*Tyd%JT>VX?1e|e>G-cUvj2xt3zL&%tZESp9)hj!A&dfjqMnEQZ7vCh%N> z)-p`X=^KR%7N&jY_293>y8y?Ud34f-AP&)HFl;41jr92i5!^pYso!WnwIYpDgdfdc ztlImz9D_z>wG1tuvXI*zZuU2>)>JdTA{2>{Nx&Z?58(qhK|7VC!34G@U}wOgb6d%1 zKmSLX-C@w!V0dK>!9%aax=+ofyjk!$pJs?RNr5&*`!R zfq>9;g+evV^0JkWC66A5K;w0a2y10Np;-FgSdoB z$+Wx)3c%Z0?R1)*q`dJ!pCz~83EZ*sH%Z-!%0e3(|J)Xd`)@g7 zyer4Iu2W`>pJlRh1fFR0P@x_OHnRg>+0kXqZI~wx`}CXMhfp`}Rab7E|A(dd-WAE% z466>~a~{>kGoRg&SI$FsDr9`M&P;Qi7%fZ4X$$oX^7y3$!EvHm?bn#`6|YP;S1V`> zBoSv2DG)Cv3Z#d7RDL!die`B!J*`*b0J#M#97(Sr|IM{5JhGqhUIlHj@1aPirjB%z z5I5nI%A=Q-9Fne%`WJ#On5qx;UAY&yg~qrX@1w#l)K92O(Ez2YZos_c5%eYa?rVOo zfn5iL5{C?-heT==LiH&7Btt*=Q70fS6N_+=1H%I3d*vQ2R{m9m#GRrMIsM6C2AHi9 zL0YC+^f8Jk=#DQ5PaEcOwwMy3WbBCR7HDvomCOTxFJJtXrtP@9@3aFh?t091k@CHy zr$#@TNIq4hrl^w|7Q&c-ev%K^htis8+nsp?;&dB50LHL;!e5P)HF>NzP<>}qE}rOL zWQJgVRNjkWF68kIPfs39cO3OVRSC5 z3E#wPdFE(k_W@*9*3D4-{UDZM`C<%wvLPL?QI!I#y3ZnQlOi`r2?lcIk@rOy97kHm zJ9X9iMlYMe%@7ZM&u|D+QyoiDzB6ObH2{Eo2Q-yTN2*#np{TA+kI3n(_?k*E&^t#A zPW=j*E0Cf`4oPRPvI8OD()xjJWMa)TN?F384~bn#Euc%dD(Wkt#Wg5W}CJC!M-j+|Dgm!-rQ+~><`$_=11~%NP z(t|A3#ZcB-GBeN>l*xW!AysM^EQV^Al47-X$*}EM+gop-xP}C!y1}K-M|n2&wwg(XT!cd0>l-WSpOBFiAsSHe6)z=ronTHlwoM&dAdZ?a_q|tLIFI*zXHocSB4tAfo=hK2qB}0hz}DauhBozR z`U^Un)ezVB1FhY|t9KA~pRmjmhYH`9eOl)5X?s~7DfY1<9k4jmM*XPkG&_ITX>HWR zdy2d&xUZ6CCeSF(YF-Gb%KQLBQEOQa(a70swB>5ah$8s5 zAL7PjCC%1k#)xnWf6Y`LunyQ`$b{?tl>|HTyz9PM7vMP7EDqmI(w*)GH5#rl0(?uFcTyH)wBGy_PwUVAVE~Y#Kz8YFk-Rd z(6|zff9EkMK}(y-iThrJ-zCY`TQGe#O?!UKhaWJ&bd$^MLd!biS<&;RN7@kot1mb& za59>nZevmzhu(+5?_PiBMorZVZU!CkBG@$c6qU-PoIQGcE>tC7{x}j0!w~ebb*ZI9 zNWRv}6a)C6=J`1Bufv}$>OO5ph$HBoJK%2dA5MyA|Yjr|iC;vCTRd~m@{dT5z} z#iOV`AfJs?igsfA0V}buYo(E7Rjfsz1bavO6I%*DTA({%ive?RNU3}AGiplOoiH{> zm@1?w3|Dn)3D!_3UBP}w#?8vBPvCg5aqV4BXAZPMyuuf5VF?0o#_o_AVe2tRm^Y7( z-qTIxI;NBsVEIV^9YFa$0?1}Edi#2Kd2!)u2pg*H8N455Z8OI2idg_^L&RQJYK&a^ zXr~S1@IO2WD>Ol27fCOkww{0hELg-V%C)8Ip`Cj7?dB=ZeOeSTLhIBEu+{Zc&mvkv zQ)Q+hF+4he>HX4e1~3e5Ut~|Y)p8$ry_zxLx=J(808!gQi_BnuZjT7_}sr2 z&nzM=FoJs&6r5yaT_co)x<(yV8d?tH){-hcCzZ7AciqUt8L)f2KE3j3IB zEJfEY%oaKUP>HKKEZ`jEve;#MrOW*afCs&++VMzh>aJ%D8JvRY7S(2V za%hX*s@V40`(ad?psZif%jVIhSvNn>@1sOiFg# z3%BvOS2VD;TgiT40RYh5QFVIa8JBB#1Gg0sbmW;Rgs!!My$I2+@_C=$6iZb^7?{f4 zy-esfcfj_Tkc!colJ?SqESIeH$hAo+v)uN6vYA7Mxv9;nOVTkY~ zzu(=2a_Lf!;+4ImjBsS86py08 zxd(gY2Z4&X@2+Mxb|;L9!K44OLm@w41{4JKhrz)?gGqb%C+Ga zzQlWVPihkEOs?9`{oQn(Lw;IgpCA;Q4{^6;?8w%S@4wVVIX^m5gNSkX*)+yPu*1^w zliL0En6+nx{!WGi6wHU7U4;QNYTUUq-832J@T^xdL|0p&q^obeWDLyf|BgIS^hYX* z?@@g=Vh`lrE4Md?k$2r!k(jDIYqi_@N>$w?*cxv*LpX0vz?K^eNW<3#FG3V73xoF1pauz_cct`+3^Tyz}s}PB+p}g7K~Yg z3K!fMy|Qys01n|+1Ri~o-vkRYGW6s~7DC)nvU9jspxLE}rr7b+@5@Av53WJnd>A_O zCQ~+eKaw5P(artegfx#+l+ezsAU>abk49u*lV(#j-4Au+NkPcNNzFuw#Jy%c1y6lI zyg~amZw`d`T9lTC;jw058<9cenJRzc4E$RzOIjw0Z}@JQN7n(j10T9HL7ACn6yVt6YpQ!A{|RwA(8L`;^JQdM33sjkmVMqAo{i@4>g$S^Ixw)j9@U_ zbO>K&$W)NV!hj@Gh3Lvbp(wdFba$=x#ljM;Khf(u^yQTJMbt9PF8L0qf~;BH-bIP) z2t67q27wTj?9VMofNt;E`N0E>&le#B&Pqhp?SzoMy8w8?q!0>K00&0o-IFRq7&5Mm zjeQ@QsBHll!dd=&`-2>AHi>^{-uW1&7TfYygr-nrD0S%Nptaq$2lBmEqRn%ax#bW9 zQ-4r6o5$C9tYlU%h2(Z8?3*Q3c_Jg-YbmL_wwUVD)s2~gcOqQF{y(r*f5fcIEO+$LJ!3Oaecaz7h09kS2xcQ5`h7b@_j{(0)5(xGC za5Hi>tjm0+Z&OR9DIi*v7q_;Ui2a{x-+1s?VpaHEn1qf}@+^%e@g()Tbo_S$I7i|8 zr{0=uAsa0>Y0}=<FEVpF%#vtSC z%x-9ISUeEa$`$%ZM9rbL8}vUgS{jj>@uGD3EG>5$yvnPjq4gJ>w>|n4G#M1Aprxm6 zWOc&xlfg$`j;Jk)p5m6?Fzsg1_?>%W=GhO3=67tZcq&w>YY?bvLPG!nFEbkCXU)(Ex%v*=# zp7Yye6#62LYTETUn}a7(T=4~^CnUHPNjQZ*mdOf5fs~>4n()&RRKVk#J-<3A?M12g zkl`3Fyp>BTXa{Y#e=#dV8;HHY&$@<*F&PC{p99b2bf|3z0>Djf%z;tbo$A)gtMg{Xe!7radFoyFu%2ffr=&Zz&H9O zVk+=eo}aT$O2Qhtg_M?xd1x1!Cs}|x$0au^W{0!5Uwv4^gFGdIYDKd^ru@*em++z= zkPL<|lI*AqGJS=Oo?6b>>SyGF7|H@?0 z2@cKcof+>W4*?a{@n8`f6bPvdFO=DbN$UqU^Im7j9 zPTcc>4BJZGvMC^Jo!1kC@cSvEv#)WUmAe{|*!`1h8uV*G{iH*Y(n-IXOGlnVIo%`0 zU-s-;sXKlk+%PKuko70hpFCGi!lMo3c*fNEPWVC}B&WXFbXBSS^XMZE}w z6hbj`0=e-FE56nQnR)0YvL`bXV-D{E5((zA(|H_$HSAxS^uIQ}C!L_$QX64M!Hm!e$`bv`~QfBE^GAHGuwd`?BA>KXfgu&o?l*`> zS77J-M`!qKjusrF9@oa@!x(`FwO17#_|c}T!k?ofU=}1K$YCF)L+h#fo}jjd(PBjY z`q96srKUii6AN-QraU9QeIQSn6&XFWg30W={%3^>9{|=jgc5QP?tpKY0S`|G85KcH zST!IH+BvW(B~IR0b<&W+{XhrtmD7)tiI(|Urq)~3S5_|{qn(c0E1! zXIneV0G<(+$~i_(&7_9Dl{iH&#e{AJ0vv-*(;Q*||0Xw79-ybzdiED>@B_bY3wZGZ z693=dHy;@Nx(EcZ5^AyjzwFWPBsx`-Ue7S>?0XPxdh_d2B7aNd?H}D3zSR!(g=!aBoGqM6R}~k@7@mG}NCA*BRe1%oDH^F#;9W8<)h*kk-@o#Bm3A zR+lTM)B%>uGG0AVJTw$dgDL$8i;&GDS9%yOMzdS_?8Hcq3}u*U)F8@j1FVLd)?KrF zoL+MchhRql_Ab;ZVj$=rJD`2A)y8Gold~^b5c{_IRoh%K7O>d$i7t@u1Ql&x@Q9?} zY>n(r3j4;e3DU625@px4{2ogMdVbzM%H76&#iru_Ve!m0xaib?WZYnbPfwxPzrxFQ zl@mSfY>~SJ!tjoOAcYMiQcXwQ+pEfAjI{s?V0jB$5E*&YnNo;0(UR@6tMkfj$XGW( zprmotkwAv{2X`o7#AYWjjHVP#r+6W-T|cuRASinWoR+F}k0_Zzx3$8T3X>k%YT)iW@IaWeIAR0C^ z_9(BF*PKEgHf(5c(X)keN-G%4%eU`d0s<8Dtq|Ws`vNlbSUDil>&=RL#V zn(Rtv#V-lg99C;+zZeO50dd39Rl~s5_6TG9gf87+DO259YN!=L(AdLUT_Y)oDM9)!dzN!?lhnUjZo#Ue5hvQ;4fqZ59DL z_PwV8=^&K28kM~cL?8=?P4lomZMqA_pDgo{Dkg|i8DTQ}*TT)<@1{q#X5#Ho?U_Yx&Jj8Tc8G=A%R#-x9q9(}Bn4404FuA!`>?Cs<$er#R>x43zxi)N*dd z?7y^mqw@o+j7#{G);*Oe@_w`QVS^ruNJG|6P0Zvf8YLv77=b(GbOzY`SFfsSKhNB% z_}~~T zIgiv5k1HiypF0j?OmF4Ot7`Z+g$&SfboJyLWw#cZwiw};p<~oIXBuN9ENyb_Zf}_ovs#vS^6B+^ zXT5B`h&&xN{FI93Ag5cN!6xmGeE{r$GiJB8*ggYPd1zz@tPS_ zVn~63Y-Y*CYO)Db@2=~VFv_3CijET$j&&F0-VGnAk8)bo-*$Jz;OT3VA88jtr9(P> zg1=DhzUd=aH?K-J*FA+I_UM2jnn0f{h=t#$Da#)!$N5vb^$Ivi9+CiXM2bjd2EA0W zsLVI~RG@Mm91rvEk*w2UL0K?%vlTuuofDT*WM#c?YP+)(m63sUFFTbhWK3=I81clb z(SqxjAu%`$i61WqUwcx}t#I|co*JlW*rrwjJ9iM(8S{s z*rKH!AD~p!LOid3*AqXeBGpmd?PGj#SQ=A)`Qep%o35RMVU34QPb%~9Rf=153>vpM zxbQevD8bb@SLVwH{6!>8*oT%=w3#j9(O^4dmHr9t%7f!#EZ!<%qc;H2D#qn3oP#`y zyghY@SUsxxcv%x#kE-{L-uVut23xF#nwLVhk&T;w18*98^3jFBEk&9TL0tNcI-r4I zBa|3gQ6V7PRdjz!*=R?rmpAU%s+SVrbb)@mdDjYzD%Fai;$sqr+M1|Ypg5P{V`-g~ z5?`;qxd>r2R<^Cqie>y0jls^Ud*slLxNB2^*36wUUza(*Q8#(DLY|!iy!OsI^o9%A7cpK?3%1^ zt&avso#({-V@GNl39YQ+Qu-I`>RZl6Mhl;rY*B9T9KsHRW`+XZrX9R+^G_%Nu7n&! z_EiEL{{z$H314OTw1-IQSmtRig_|OB@vR#RAD74-GSA(MdEk!kxhaV8 znwkT}P^JdOzJq5aWPuU67a>U#jh8VZybNKf{T1JC5p0jb<^tB1)w*b#Q9eZ4<9eRa z81DF~&3Oz&S|Nh#UHb|N#wNOwjlfRgZcLjZQ^8YnqFV-|KNLA7=9XTIZ6AY^_E_dB z=ANy$U=9Ri<&a-cc`ePXk|s zLY_!?3qAg})4~?&X>!iBsjtP}D20^yO$lmoRTI2`h~9-!DwCSU)9#+c9}7e0!Ycwt z29q9JT$|e#lf8pBu_4|T;)wU%O7@>tg7(Pn>8`{N!)jbN@Vi$^;C;LZ7>@fIN6({o zH~5LAZRFufC^_ke$iYTggRT*jhBp<7>i_@~o?tBTwLs+=Eu<({JIXl7dln&I4qW_3 zKo~;@b!=Ly&_EyVpht3G4-fZR(61(Cpa1{^00ADdb+O6%Qeh}d@@FFO@IiXJPv<)_ zLJBhsxgvo;RncrU#-+WfC&QJ_!Kx;Cub~{9N8hCR0veek-b&@*?paf!NJ@Mmzp{8T zSu3XvwqC1VR_;hgn;(VddOb!ay=g%|oxD@u!xAYTnGwL17905>hJ&IZ@?elbI26nT znT9$6O^O)ene*MKQmWF-7M%u&zJVPN4Ae_&jVt{F78Z?3e4Tuo-Tj@*=EnIJdWQ|a z86{k#$_OGl*0_cXFx%Hb5l=~&B^jEjjOR=UHXWv!-OVla~u zWRH_YLKtmgr)F=pc^du8+{ zydm5v{i8!Sn3{&0+zIg~+m(UEk$l?1z*wX1@SU0KDf*%*xX@n|@I)}1wE%w-NjzYI zt0w{&Qn?^h1C#NOSM5$UP|S;Q3vqREL(6FoTro$`1BCDH-Y z;qoUiZ~QDPbxyPZG=;{2Xxzo=fQX;I9_4j`0I9laAm&Pxn4-^WVM`9?kQB!TZK@O?qF({WSpUUcn)^a_^{LC1W*NcY4QTFz&t36$GjqORGVax& z%`=qAf#t7k?iq-6YdFtD6>5Y9GR@qJN10q9Ha{u?cc49y)^T6AnN1|K=vfB?$D$nNnoxXK^+b~E@oj_cE|wHNNNK9A zXdq+E6bw8(BK8*Elmm2juHu}`D?WzY*Wmb{FI7O7H>|V9kmTP8rYqD<{9`&pn#GBb zvDqz%*6_1tjW->OloFg)l7E`5=G+}iB`n=~E1cZ-5R|t9Fq`Xwh~=&I3Q=u*f11hg zT|(GCFdtxj;U9o0yrmrvkO-zyXgDW^lN8H(n^tI=g6TsVO9<22G?_oeFr6GgapRe5 zl01zV24Yak>4XWGf5xGvP6fv)VaJ%%PQwT1%Bu!FH=qyMw^E|Sv|P1ZsgMI3sSZPe zqT|;u=O$O_DrK9SNRD+BXgXelQi-B)y)n7mH+qn5c_~QAzZ!g9<=p6mUZgRr1X3zo`Q*vd%iWuk|`t0GyS zb5A@^E%^->eUoGX+gySuWRr&QUBZiv)i&<5gy2=atBBgX_(I-yzvP`|e|j@j^kW&= z2(0qqDEhTXg{qSE(A}1tO+Smog8V{jnj@MH11NZ&_Pd!Y<$+K;;;qPL!JOBF3z3o* zk_H-f4IJKS9(Ue8L+39(5ZRLSjIdf^k*NA&v4hKB%5MIINWGQrHKUh@X81iPPO%C< zMFn3h?wVJ5zBRD%*clu{Ny|R_P-;xxEOu&@)yFhY=@dUp^q|2{JYREbgrit+^J#G- z(lm3J7eJPzCYtt-r(4`=@NOjQpJNO=$lSC^wl3U6lOndgpf(uWT>(tBkgBe|T#17q zt_WaZ`vUk<-Lv<^+Bm~R`}DUH=?gk%&Ht;dw^?p}OKbn?D*o=99cTs0ULtqRq0WQ7 z%AcB3O?2C#Bt!nY^{xU)WpAgC_9FihM3L9i8qFFq-1=)$xEKIny@wNhl)>tr?u+Ch zkybF_Hufs0l&R~JE-bh9fH--kQ>n+B%PR9#r!cNLiVcCm#Qj{TK!|!Fy087YcE%NH zxI9lE%h;cM9G}jYBG#>5D#j-Q?$Eg3d2$T_(BQ@XwNDA4?!6*NG~#FOD5^f$@phiW z>`y0ZIDUV(C;k!SaA@ie%{$-WD@ruFKat&o7cw1<08t4(N^?fnu< zQ=H_a&Poo-U}77P0zMuToqaM9<5B2NI#p5QnECz)N{6UV%{LliNRe9xFyN~3ubL-Tr)%JbGzm(9!t;60Nm7 zqxgIcCE@vGYTcQZ9bc8gGC@%b}(@tvAAUX);^RfvAw z3+*%1s@HtN9G;~*J%;fSGg}QMX0;v}92k8ph^~Cy)>VQk6l-j~B>S#i^Aqf*OQZH$ zp+2DPE?_Lo;kaPbMk{*0$`X3|Cw)oOi{cGgVD*WoMFoTg9!Z@=pP(pl8F$(O9)Pll z{EaoU6wo(FV^WP$5_b3T7j(kB+WPRAncdbqSPe;HaL1?s0S%FTyix8j!txP9 zIbK2QM1SX@{#fZ`L7j|D&IL8TrJKKGnhZFRyPz1ly@n=s>kjdNG8!NB5l%mjqFyX0 z`1Igc3&Y=g3gvzE)`}U`$a1Eg4B`7{1Gx~E*B|b{NvrhuRPlzjM-5H4|TQ%0Nn7S_)#L$Q^=XBy|fidgf_2GXQsB`Y0V4Iy(?FZ6xHE zl(vK`P;;6UJ^a(L_Iuj}WX0QVwr@5~9b6;A1{%j6LkItr9`P0Z1zh&W%fOC2c->-V zm!X9jjbBKbc?^$6DdG>GQs z`aPU*{g~YLdHFOqmo&M)Go%B%`u^S=&8KJlIAA3|*9%Z0$Dc-4qiKLJ6^yd`RZLs{ zU2@i=!m8%Y)=@z5(BUS5f&6#Z#jjbRfWK#r=^itBlDgFAK{`T|AvVfQi$^R2=W`eTx(ub+)o|v3Kq?oatH{>tdt5a!3MoCTJ#d@UZKT zon8M;L^P?xeT9{vwV-(B$Mi^;cFO_i+c}#wX%C|re%l*+LD78hI=g2iT$Ln*j6975$b-g_2Y~)3+>44t6K91_F`fIK63%q zK)S+UNDW@+L{hx$rUpnc2!_$-CC2w8j5Nkrajjx4JgTb;9L1%PyIx$ud+kpTB*|B{ z2j2X-9KAPE*PLxPTWTx3+_sN-VlW9~DJJM8ys{sRzmw*F#MOr^&EBR1*_Bx`wJ6$g zY81!^?qD#mTW`GGXT6;CY3S=*-I_X2CO$c@m@Iw&hk)oqwUk)ivgL%W|E9`C6)Hv>*=AuwDh%Q3ARa)F#i$slY6$5r>-;a2}*@Ks|5 zknnt)n|7&H=TUJozPQM&(sZEs)_7~Uieb1<32cV&m~yS=QjQcj@rVVF=XVdWGDXs? zS&NGWR~0GJiI?de&eln^j^xF1vSaDYobLFZF4@hwP(s++@@#-|fq}ohz~zT8YnhdB z^lK!GCUzEfs;>YQg?npZdmM@LlgCF&E8U%=gL@QFu-%boycecBA?(2504?ZdUb?NA z2oMen5~`kvrHLcVWHs^p8#&G-&XP|Q8MvdyJ@2JdPP8G}h@x!K(TD&nLlb?Gn>(KT zwJqS^uhw``|My*I`+w$2dWv{nQ*C^>?#0#z&(_GP0+4|wHK&Mk79KCu&Wd+%oG>Y8 zt+swQ=>WBtN@-tdkS{B{{mVRN{!(i3Y9<_K+ajsuZ;$r$aMw%Wa)gClqqO@X^#HNuJ@n_M$G|Yk+`FtB}V)pj5 zKFIByh#h7vqg%z702-yU_zpVEP=EzeyZ-!imkaBc|3@dwnPnl-Rwuby%rc5}k1lVp zzOTGqrDQ^fj5Hi#;&xAdEt&$n)zAJjxbV7c@2bLX-C!%mo z#H0Jdm=1#tmzjfkr`DBQ>7M;915zKV>_w^DhZ*!ziF1VzGN@gC1y2M>aXdPS)NGPE z!H{t12HCd8GD}&x{St|Ml!3F@>*fDJOItAC&kN_M-1gKYROjd!v~dAzYOY4m#fI4! zu_5+CS@~=B?A8y%@48|!V02%B6)j851@s%5^X349^qUio?F?gXBE_)IrZUYaCYMK9 zHa|bJykAe7TYp=W4*fTmwk{g{`_`eewOx10ttfSm>9$-5H%cL|IEg%$jGX}a8e|dn z=BUmn6l&|X%Yvp>xD7EkD`Ydszl$>yVhDNF5LD($FzisHc$DhF>_Un8BLBa0ye
u9``u+=XWW1Z7?7ynbfi@QLZ2Q>mAwi(3S{N?3AlDs2)i6439DuZt%e_u%o>$DOnl)4)}10IdXu8a8)8(Ih5OXE`E zqg57A_Ty&;C88F}GclBSJ#Mx*;iIdZ-K|qSod-#f^*3W?qPnWeWw%lw{VfeOQm1r4 z+Wc^~P8OCm`}O7?Ek`xkI+usb8^&tNlZW((aTD372e0MOOhski&GC8?GU`L)%58hD z4Umw0euGWqF^&b`NKKddNpOW;j&wEf8bTXixBkV4pAG%UtI;Aei6KWg7suYI5!C(W zjQ{s0S{q~Qd5WSKmoOLpR`eYO)@wwMCv7Qn z^QWuWt5380{_&pe8|J2#GLWb2jX~!=fODNE`&0v9g7bI>#bfcWHzOTT=xBZk>$uz? zYN*vzp35YU+*hRMb(`H;9C-TfNQg$u^58<*kN>2d)yb&xAap2_raPO~BoR*gFE*y_ z!fqIF&@VXkhh}n;1=64s+3#`)`x9RGAg~oF(*j0JEC1n*OPCuT1zXI=K>N{w=4?qO z!xv(>gDe&40oMi(;hUAoboTVOt-*DB3in=nDkfa8hiD6^)jtThHvWIRe`u@7Ee4O$geqtS`a)=6F)5s@uhtY8<~!UaHfpjxra~ChtZIc<)a+0SP^w} zyuEqP3+>6xIh- z8<{G)#h~^A*&2PjMc;~NHs?GlD&9pB&%oU@#h-wL#D7?jL&%T z^(8E~=2WJj2+qz*crpt2>Z-c~MUj0*aGO$a0>s~ZINGiZQO>Fy`dD+&WkP$k9ATl6 zT}o~=S3tIeY*L(ile#Em(#CF7_{sl%piJ~e@o`Lf9Z@@y7)-<=wFD)Ya#+d=X37wM zSMVuk$0y6r(MPWzibeTM&e2;MtvtWeh`nvT)0FZj^mfMqBOMWreGK7yr+p1>p3BKB zomGuVgYubNl8T`L0Om7RVM@0U}rNLOx>_WHqw`1J&B&Mf=&kSco6S*g|^qu)c#~$8ldoT545_X z$yxqMYnXq4hxZDi>ZuxKasRL|WSV<}g&{?@f)^Zm>@b=i z17x&HTmikYG0)H}mXGyE+tA}5UN|UyS>WXuX+4mmU4!ig=bO}4c=gllnvQJGG&`b6 zO2SN~0K|y?#PDo(0wU1;49wnyq+|Ol>g@#?-p6dpoXaan-!a>_6*8c3Ul6#%Lrcu~ zX|XsCT$->DPSj6>VdPWMcq>L9XyN}!xDQq^qvfkSUCwUSr4|ej00eaQAqx0_fiv+A zbd%n8Ax|xH= zPIKq3#-xSMmXD5+o|AWaeqV?>Yk;|<3)2OV3(r!18y~}g)1Y^XKBVW8ip*A}^HZpI4eWR;K0>O?o{1_A%!tP;Foh&_?1v*Y$#`a+Su--w&nz*md^b=1B>(F1u zKS@9C2d(*yAG`_}y|+XR!Zp6B2w4~PoGry#IWk+d zm{E9$IAes=a;T;7Ilcypc`8gfU1cU3brgKlIdTO2M?M6Y?3HYF&ujgUvM074@1U;6JHtxi zy+t@>pQ;Q1mrOEKf1ky(8Qrc-mmY=i^xbUABk5=$n)+3?tcDkE7&%K>eQ=_6{*c4N zeMGc(vN@Bg4z}6|n34RsU`TH1>*4=)000v~#ly}+XehJ+F;z=srwMgg2d3%Kkp3X5 zV@+>XU=ur1NJe$u_<7{(O})?G3=#J+$49U{9Ofz5DJ=cqm=((lK`XxA-s}217_RSR z@ui#2yz_`|@Z`&W&Z!#PR4?LO)($4wXQ(iHQDuLBiJI> zUpGd|AtCiXYG=pFBF9^zuwWVcG!uCMAkemwq4DDbgsWglmN&#ZjYDpnVt_w}F5g%ZB=+gR?A@*Uwr_*b(5u@?D^y($?<|r^4rmsDKrmSKm_#p zWI^3`va)tNT6}YBhcLu=i_OTd6{k}k31B18`TR`@A%kU`)LGfwLkLPt7Ljn3V7Q=c zeQ@o(pHC{;;upX!SpnNRq^%a6odAP&W;)5j#I4di?_>?eyu9DHi_-sBM&;lD=Oa{L zkAof1J`00?v7kv=afrLSEa02hGZTq(2f8t1yO~(Dbt#qP0*!q@FZgaw zL69B>Tkr^wxll+=3k{8Z$=a zIKQL?$q?WG1LELc
UNt=`(erhqDA=O3ZX@aJ)sijF$f0W{{Vu|Vq4U#D5I^VBE9#jw< zFxHM=fnNXg&8gB*Uj<8aG?hqOtkO>si3z5+%m^0$3neM@XX+2CUS->p@&d`{!;=1T zM>Re@jUNu_*1oz_@v)jn0))MR*ap+sQDPR;H%K1@vK_QOO^t24&} zsyQM*XXn`b)0JN$6EwK-L`?uTEf|fMWpH)}n16;jmZ1#8gI7vd_|)18B6pVP-VP4| z$_Sw@_>y$;&!_%elcEI4`y^n6m*AofIBM@NIK5R&IZ#=&cS@p4jZzF3XvEG^|HU89 zR-QRO)Pu!szp{4GR4Z=zxVYRrK*Bcno|1^P)?wOBo$9onG_RvI;d>Bc&RO73jAzPB z$q5cnAtwx?Hqc>p?zLt{5@QS(sb;UvqbJd5sRx4CG%Qdnk^l~>9Q_f|D=Fu0y;>Oz z!dhtRLtd|MBO_Hp*uMh9v!k{sf9kbjMb0@W4ySyC{N%S6hkMKj9J%XT0Uzc9ylghH zVe4*69b!TU)qm4$Mg&>}figGv5VOLb$tMN)o259Ms=K`|KR!-k#~dOEy&?zbEW6JA zihvSgf6)M8Tr{z~B7-N<5KuxKegQ>dZogopr2 z1+ncaiU7ngiJTh^mB!ph+gt72L>nYU@ zitANQdl0O`j0RP7__y8g5uUfib*4Tt+0KYj`GQV^rJ4MnTB>MW9$5^^`_~+&eB~WJ zuutNyFVawTFjVkLor8@ycc*0i+Q`pI_6`UfTiT6EOiUwe{JxlpaC9&;Z-E{oP!>aT zW_`@EBs+~%5{<;~s6^zL@U3X$uhQZSuUzQLu@?Ij~8crh-`@ASLLLgyCIDD00+OscOAJptzA#O#NoyP(LGXuCEn z4aZN;A2uzneBcS#m>!E(cMEm|8c-v%QOnIpdK3-?G@uov#8;{Pk}TXrX_hJlC#|lq z2B_+mdxguFumMbt^0_lPN1_z)V#00$whQPhMNkfOhUGC&g$8?C)JwX0$--es49Nj zgeq(B1wSZ3z9M?ZUm^%pX)AvIee84OLX*F9k}N0QdaJ~T4-!lXVUChDK15Xj&5lLV zCZSAO@%VYs7Q=cb_4<=hU(yc{Ce2d@27|4;VsQKgN+bCXI$COlgNW2x%Q;ndn2AA` zJS-49=#x>cy#S9-3bXyhfbW&A@OAOSk9;PHe?ZYoC-?L^tC$p5Hgqaj&zoYs00ZNc zkgRcqzSrYXcy|2swdl@iQ%8)qs=MdP2S}t54$lG6N0XgEn|>$Y19yzUc!z$vA~wAb z1o|Hn*gkTGAAi;m^klW%Iad4FwKSXztK8c$B^n>a^)G%3$z)wA==7J@!zT;WusV&< z2T*JsHJFS#GkmU61eJAdT_J?{amm`l^Ya|IUwe*q~lw?yaGwpe-k%(vK-!b7%i zVf!zNd&+H;5}K00m(}uTJ|H;V7YX{a5Bh(lE~lu)Nc3oA<+`M5b27Y6TtakWY7GR! z@3Mt#^vP>jbpA-qa!P4fByyPi$@;dgpngx0MD%Q72x)VPUFL1CvQDm{&YdX3> zSy8zv{VKv^cd%JH2O4rAmr7(%*Ku^c!u?orlC^pIo%3M2DJ?D{*FVmxPm0(# zEUCWJu;zW9lfmj+G1B~$12;~$=Oe1YpX@oJ0(SY;C4leA={Osl9Rb~Su4UBk2;HF&j zPWCzNB;%R&c^G;^${}jXSBO^3`F=23rcb^E3pE75)g{ammTaTzrm%L)Fc=XA9?Tw= zYYsYPCe60yD=aNJNSVhHfU(GzUO*%BP=o4wH;k^a)?}M@5#Y|Bjx1Wgz=K_Ict13>y$y z`X!PA{YO%bZcs>S9dx~X;rRwv3W;z-^%E-O*NMqK;(l)9IW^SQIb7;~^fn>`iNKjy z$~GMFxkcUxaTM}+|6sDW;uQG zaNwdB;VJg(jgX0H$`kmh)@Bmz6bg)o%%Qln0I@miKH%8?i%0(3i1Ceo<&b1Dfpv|O?s)&uNF>dQ?z*9uX{!8>3X>ZN{QF3!i;Xtc z$3fs|zXi|UCHexajmm{X;IM-vfCa0O5HHZ(O|gqCD<{#XOMVcXNdrT`&}TPOX2!`k zP8pNfLQ48s4RLRFWIUDP@RxkOp)gxHQs|TEn6RS{bMR+3XOkVAL-DDGzYOSOg3)=S zGpXIqp9LP8mo~a-+S{O1-;xO~7`@%RHqTGA_<++re!0owt#Ku-sp$aKLAH+k@6>_O zoq#OMuHv9ZIPYygW>8Eqd7h9WaC$9)Ku*)=$~ z-0?40u1>E165C`UQoJf9>=>mzINgpqV(U)Z=K5!Hv2f28#FE1AI+ib{i<>3YS) zAZ_@e?Cf7|$kt7Dwd&U4I+eOus?v)%<}FviAymWc{|-ffJRsF20C`gexvF@ac&Kvf z_xqi2j)}7J+h44Qp{SsH=Quur6Z)VNrqZ$XbTIHY0m6uc_6%+*bM!H3Ks^!kZEiXM zoVl|AXWHWxuLndCAwo$0y`oJ+kS<{9?dUrn9?@5t2uPsxo|K?12A^czQB&8v#uPm; zgR^|`X|i|p45XH3s|OlVF&O&1vtkVpC4Btec}gBl(QV6fcXhCcKd0LXc!lyX5x~%Rp^IiE30FW8pkb~LWWy!^E@QvLL~1m9^qwC~ zK$(S$k~aQljC%a+tQ!3&Xw`p+AjgXkK=PXjBlOj?H7uEi+xbo-2fLbHPK3_xPx(z1 zu_j_%n8KZQvezj z=`v75e)g|~M2!weC-x3p3*B5QZ{nz%g&UX3_`{HtXwY1}`}GZkbiL#!&%wC(C|4lg zeg>I!pm5U9*-(0=dFoiTgStGFTUd;8=mOMBsSpI`c}vsUmF+-bLRf914~|Sc#N!`w z7|IB8W3;)Q9f_?{n6CC>_8)>_T@U<5W{Uuy?Jn4`n}6=%$WCPb=02&PIVfMeYm^JuZ6liB4kw85O38giy1OQPoQP!3m8N6X-qi00HM5iHu5|~T+n07 z9nimyKu@HzE-qHu@VCiHhGC|yX^@5mk=&9T?fqWC5;-mkfcPzvF$;D{7dlxBw+aAj zI6Bh0j!SZIZ`BLuxyu#vVS0L zzaIf4ms{Xcsjh1W9&w|O!9Du=fMFt+&R*Bt6JRe}XyD6;<+}+pWeRQu5)|pTc9tar zK2Jv$b=zYX{xDX`*Yng=R(XrQ{!|7oKpO5CQ~G_V&{%SO5Ty;PJGZY2&RHCUnx(MtAuau(n069OSx6zABN>PqD4JWD7LO zId%WVJ2kV_F+^ggezN@Tuzh+l2jPpGf!gL}O8E5xjTKrzdWMLZI1wA_omzuSCRvE3 zPY9b7v7G7rAw73@JK3$~J^v_?%fwq9ai>Kqm1?FDmfTvZXRGHcLYQt}WNnq?iZ;Y< znGOI#4CTHL7=*7k{4BZxTP#G91)824ZKT<@%WIIykTqJqzAHku&`FE4{6X_OYNQUG zE~C-(l;Ro>tdds40wVW;J>2a)0Fm5*jlvs5NYF?a54zP8s|iGpzuAh-4`lesKGv%> zqO>%Kkj-$5!MvwUUNz>+ITPfjP<>9z!&Y3mcL8WVy%r;MeXZ!<7Sov+SFc^?V}K5?u;fyw^HXThOU7LDE}h zY3>k<>RbTqgf8W+Q@xt{C4VyEm{RDw+KQv~Sa*AqIq0>oQtslAkeFp3+5siAc{t=& z#%6D7*7dxA8T4K9Oy~3bJYqCCW7##H_XEi4sIE!MibNX*?A!h0TU(hmsCmGM{s*yC zQvUs@CW}PdXjau-@}ThLQE$J|Hh^G$Kyq_WRkf zWP=mEGE;U~@qO)4>d{9o!$j6ztE&7$R5)(liKJmuGeJ~9^3xAM-Xce22pI3iH#X&{ zL{k<|s=$a_=D=2SMe6b;i8ILFtJ1#nx^kypx8-1@1mJ1EP7bnL?LH)kz0c~vRodIR zz*qs-`zcSpZ-v_!naVRJY8*ErA0wWY`TSG{W&Mr)U}b7AvPqUuqu^|m)biKzMf^b| zE`x5L7nnj?F^cg-dw?WxU!28+?>x{}w;{j4q5iYS9aAPX*7n+BJ$G^+yOYnP<1XV@ zPASf^;I)p{7Sdj((q2bp`=DVkISPD^qM*CB5=Fj-$PDrgAy55m8?XS~u7qrLKyJp3 znOHC*xLR1t`@H8Y-UnI?rd2-CK|^i;S;re z-xVEx?9be#v6-!o{y$e~$U0S2{k1Cb%PHo@YP6N-%JaQPTFKK-sA=vIu1K?Lf}Tl* zY;G85@f-^zBixy`MbyOlP!-ry(WX$^bHgz{@CR##q{C~B@4k#xts%dn^jDVzjH(Vr zhRV&klJ#fBX|Dc9Ry4e+pDI<6fRppGn64q$uu*@rX_jFAzvJ(bsSk#tYao~uDsRH! z=`4Cl_jR9iPmb)eK_>h~%P7zS6kI1xd!5aEU_+ahnIS6b&H|(Gg^r>Y;oAGOcZgnk zZ7aHL8yu9PIhq1M(su}x{V8A+Fr(Z~mF2vd#Ff?eT)IzYxNr>yc*R2qKx)Y)^ruKz zIr2hi<7>5r3GYl67#V64(g_ajU5PJ(+FxJo{*}E=wJZ*sU$Z73D`!nFj|#o$Lke7N z3H6fJsy$1b6Lu_vAEK}IwRWat46bzyyg5tS8@Qm%wtIILB${L=4G#X^8U-Da}q|}E5?-)6a#$&W9^4j|m z23YYSMJm*U;vC|{emJEYG2u0S4ZwNn8ihL|5`u!jI(67I;emNFMw#%f;WijCwc4R< z1jreD6-eu~5ui5IV@CMgr9Cd)^B>Rp^8s#%xEXl@7Sd=5bpR6O5(=6!A;3T!5hqkT z2#EIAZB%%Ma+XYBl+6avIE)E4O+jeKI3JPOUu?1?kw4KPk6wIln-#I^7|mM}D2@@X z)F0BG__LVD47vwHIQaa|7Jn2|t=#B;NO0xGChCg1`#PNdq9D+lRjWe1L`Nz8%CcU` zKezwURtP9)*lufO2%2%gQP0c{%X#{PINorn8yQsGl_syX--(Ic$EFO=VcvA1OU4~ynifK>$shwpaS_(ZlGPdbbBO%GoV-qooA6f@Gu1{F1YjAf6G7x zD2IJs&E-VaF0;G|`}e{rj>*|cJg%f&@n{zu#C1p8fA0*E${>_Dr-r~k?dcnv3h=$0 z1Yih($dW8YjcxD@R(d;|aY3lRRb=kM4FRu^o@f|7ZJYJZcWX1DRkazcuJey!%5zRqRUhJbL(r&A_Am5YbvkIhOKWeUOB7U zr4Fgqo8Ab#hGi&^ke7?Sn*9$-bY*@Vd7U-#YU}w3RMfrl!#*}xiEugL6`6^Nbd##Q zOpT)D+o6GHJh3<*Hk?Z-s94>Z&_06HqLWi7_~FW0FagV$1eFkZNs4_!XDHvKv)0iQ1%ahfnn<=S`2~&9?{q^P#+PdXNcu)wCe3=g zTUFqch9S7j>?kVhX+T{j@NorsK{ZIPit&7e+ZD&PDsCu zxLB~^udo?Y^Z$FOPbW|S>@aU{P_ikBrSFIIciQUwbt(B!Yw3mvZg5I5@G!3Z^OPW6 zR7tSJ>9?~SIB0>jp$?FrFVkU8;LwLIl`q7`nopWhpzXtpHyy@AL^i9H3AE53Z_;5h z&Y@0SY;qi1z|3k<9A4jGw`SOEkOc6O70YT?dK(4V;!O>AOgf~n>5I-AUs^MvoHJV$ zK>n6aW#&C4FmDTj#umYj2sbgVKlm5hU0Rsy1Ag!FntnCL21{Ep)t_FLhpz1?-kC}_ zEvzp<5GlcC8W;GAu{K5TD?{bZsh{bs{?&yB(5DJZ2y2G$h|ngk|sO1tvu>dpa7TmOq_G#5Fw z($_QYV@W=aoFRTnkT1IJP6lUYf=Q<~h(ii*l`xpzled7~`f4(S1>G}xTY#YX^tKQV zJJ$zh;hdVWviNAi%8@SuCNn?IO;_5=d3#RSb#f{-ccW<9xI7mo#@+(3)-!AS9;J4; z=u$2&>XPy7KVbuHA02rbI|iz`KO5`{Iu7DH^AMFZoI&s1=TT(xpbl9<#ki8R3@XVF zYE8+5ZpOTOBA07|NVS(2;dzE%KD-jpPKdryYw!(WeW8v;cxh;?ySk5);>=5JGD|@U-&3(vqCt; zHl`nosP1I&00{N;HhlUuAy<>bsaI|3CvzzpkzRllExL&O!vhg?7HHR~kE%wub%`in zTar?)OHW*EY_2=S9e>-1aBersq#5}=qOQC*W!~XIoMzBpE_7wXFKl3KQG3h6K&}=w zvs52=E2qq9|C|>NmE^ke#XE}}4I@TV{qC$xb6eWOB8Gd@3xZvwh3_-P|M$X;dvp|- zjbVlZ2*CzTkf9~!H-eNa;V2SH3muv1wQaP{4G64TpUNw0_M+wqG^0O3H|%an-_)zK z&8nLsjyI+$5Zm)~b1pUST_v((EG~W>7hJa)G{uYXV`4?kIy>8xd@2WOK zFyoVXg}rlTTcF9G<5KS}I>yx?(?-xFC>6Fr%eoLk;E#GnFBKH637{bXHTXa{dz)7S zlgqmKEqiR)-e$WdGeVgKz+?PCqSW+IUB?j2VvM)7dd+A~LS$i{!(N{TZ%qwq&uKe! z>n7*NM6!)2lQ3Y~EZDtZ$s*Nm5(+@yp^Ao_)q#7*;}E(#{zAb=4QB%J#RZS)R}#-f zD21re53W8y2s@_{EL~aYD;O^fw_Au3m769xFKi4x_j;3*l>7_|C?x*Y1#?$@k2}Wu z#fppqgGw8ns=#)i)92=4$TuG;Y`#_P*b&uqudxH!c?}ap6c2YROEKn83ytT~ZCACC zeElhv=Lz8^J$Auf@@R!;p)t7cyDr?Q7^iBgAJhH@h_ghg?5| zR-iIhJVMP}L_pqRk^vsOv9R<&;RP9+U`d+>ZzaC7YckIUzfPD{K9YXwH%yk1;sS#% z{X7n~`dU?ucZ6S`<@mSGO>SfPZDb6@=$s+WRrgx0U*Z~9)>a?3% zpQhBart}9M62)F@#gr5U_zwU4Y<{48h+<6=jLuP#3eRrQxfe(~Hq@R682oZIMSoF4 zE79~)8ul2G5LwN}dYS=Gl<1MHuv71bH}|XI(Vyo6K#XX!R_X4*edx4hvd8cVL;=M z1XAr>cKQd}RPP>mhl_vJ(FbCxs4pmLPs}G42STWotv7u5%m3(#C=M_1L61(!Znvfa zatRcnRXF+v{=@yd@Fh35_jI8yC=b+W1M~Rz? zr6k4wJ8>bpM`G6+-Md%rA>g&L==T|hgS}jTldKdGuzV}vX8`9498$Oxx9yFX^9s;j z$_zp0TuL-}X6}gd2i3am3HodJKY5r_Vb9A%Xt;vsEs3{kK1`E)lEzOs zBM|q2>BYvO8qANy0D>+oZm`X)1{|Jnn;5DN)mi3NV}kXqZk#fsQL1J#&-eb=DK{G) z@-atri!G%u-Yl-d*lBT#S9A#60AeHn00RMh2#NUb1#1pg+8RmNKIcv>O!+x-;E&mv zKM#?knGS{rWtQtr6?)&@)vay{64JmTL9U!C^%3rlc!^4&f3b^GekUq)Qee8F4)*du z#w4|o&iJwizXL+gR%T0hs&p_yuj+M6Y4ORh4x7>%Hoc}u;_+jw1)|FuI+{@hH!U_# zW1{rKlq#>n@XpN^^$9mKWaR`bZ1QF^g3NNAZ0ivkx8B-D*SC$Mb>R+}PFIB2*N;!T z1>-x_g&8yQ2PiDA-zbS6bj*lSjF?uUBi9SR^Jl*r)qmi};i)8d#y-Zwf;I1(J5$o9 zaYXlXR?w9t@sBC+?u!YFL*b#kI3!Z%(5OCuVtsLU;#-{r_u{n83Cj^wx3QY;8ivPg zel(8`K;C}|0KK6qYaydwzW4{$kMpBriXWYLIP_7GniP`8l2*;S3SzPoyXz4$YZ*O3 z!1j?ZFHaYjC3S%b)^mT{edCv3l!tnYuRa}^PgngQH<+o`U+XMA-^t9y@PAwksNc3m zWXwEqr=SolTwQ$5B_<}nr-E^>)MAvVzlqVN@T8Q|J3J8Df36Rz6`EL;6Trd6WBQ-opSeyLQ zi4_up7$|<`(KEBIq_y5*s)26>5!asSSeK^|Ur9Z^Lkqc}xLYkH4gUP+>;;z+wrT*x zb=T`k>KBGIj&KcSW+?wam={=YCBbUxayLS;L7rm!)UV&~MUn)6z2O891AbxV7v1Yq zwla(UNrpWe|3JEzSb*W=4d-h5xM$1VI_+5e%~DPya28ni+$3*zES> zI|ry+$RPZ48oE)-*C}Nn_X0-r*g#d}eP@(O0NQ@`6Bh3vGShi&xc1S0#3&jGyhGzInh<%(M!6x;qPUupFSsJDRMZx9@ z=5D>X`sz66BfT))zu0WbnUt|hy1AvIOqdB|bGrcL79@6+H4R|n&2wjlN=<6V$ zLo%hFM~W~%i(8}OR^D+CDo8C#V(SHeJd+g2YJO*B!iPky>N?l!XyY9FrK|3HEP8GU z<#B96w|WcvaC;?xC4evVPkRei2@F3mQ}U-vh~a6Gt+SZx~cz^-qf#n-ZCQ z*n{UJ?biLu6&$?goG5|viPrW$-8cmOZa!bui%d;Lj$<&)HTq;!MFV{Z7`8PyLbq$)A zvK3hF1t{XsH8!`5z^<#z>BjHCp!@ycfYoQdkG%VMUd`_Yh!ib#E)m;iqEX9avh>H9 zWrRj|MH)Uy-4QQN`5hfn>$`dHsTmJfpw--eYb+q-c*+Byruv^|+3EZT0R<*qKjWcH z>T<^c!C-$P!b71g_XuadyyY z#4j$T!xJ$)@`G%|z_i6$oWNpm#cxcLs>g5}G-r`hmN4qEi%={(s=fU*qp;NeFQ~1~ ze&Yht1jVpg8~n($9rWduoRDK`wzR5*5}$F|a)jk+f6!^q(zZO4-@R2l)PU$C$)Bq# zqaZIIySLj{wIgXU1IjI(K=yri87j+kgrOq>!)ZhG;7*n%Cquz<+3^{0UVfpp#AkMU ztf6w`B(?t-FAun?w0@dCYF+2tUqWWfq1P`njFF$Jd%1s)`E8rN;$3Lmo)t~Ff&+yH zS71oH7I*&wx~pAw>X9C~$U^^G9j|~V$D3b`?PQib3xJPfBkt2d@bOLW%SMiPALh~F zf=3`;xrR+10hX{5eUbN2iNIP$;WO}52g2Wi&D#N!#}A8H*WmpUU*{RR>8RG*i`^ z*#U`>MSl+$H1e`0S`w+jy>kE#aVK$V7p9o6QHY4QWhEZp zc|yO`Ed?zauRc+z7ah(SuKU<-ppOWl1rXojc1o;Yr41Pa$5J0@QxN~UM>BbDitG8N zaJTn-SdXn)oP{68w`jl_{is*TCxgEs@`cCu!BknFHF1VDI6-V};K`=SG^Gl6#1 zDK&$RUeI8!>C|?w<0^izF!hU`vMOK!&u{^9todci2fpieuY20{g4GZ9_obk*hL%xt zMo^R<2lZA_z1hGLsJBRGhj8Sm9+2g-I;PwWAD43oLK!F28A*wmpco8?ooiJjMF0OZ z1YR~>nt+CbL-Ngh3)H#Ef3|G$=|X;LUJ73m6hbq%ha><10{{RNvT~Flycz`v9GunY z#A6c3KfUG_N(}=0K+qPErQZ8J+R4lG{2^jyG zgWqZEd}NhF9|7JF>LSUF){&^$Nu}o3c6{khzD_G@{D1B?2v<7*a1lHIi~gA(u9sL2 z%(ybX0dQ=QIz-QDk=Q-i>&*}a@*f-5a0EIkJ=7a>?{{yl7=zO#a%7=pBF#?j6S%St z)d0AeBhEjy$qX9)0(0ZoNmXNzZXBH2=h;bQGr{!KM#IthA9Z!LF_b{Ct@@$o-){*H zH3RM$smA20sU+&|tM$YCsQwNygNg;AsDwhXJg_XHzoct=*+qmgmU)O0*keK$fLvmd zxN6&Af@WqW;+bDrwuqOacpoY7)jL={8JbPaD0*O~gl)zMq60u^8DEQlSh?kQ;L5Gr z#NIkq#teFy(*v%El)oyB^6LLw+;P9P&D-$^P$Cu$1U2+PiPBGQ&tGs$+o{S`wR%J& z7hl|#14P3@z1XCn;}=e3pZ~`UXZe9a8Cv*i2e5oC;Bh?;wa6>QJ_DH1G-W|SmJOk< z_&`TZJKUV9d*61OibfJO+1G~9hz{b_Z$LYsy;Dg)qn|U1nThkKfI_O|`&g$XJIO$* zSr=@VuV#{)aS#ikExR5SSP8@0KCKv5{4zsO>;LBC%yX zEsa76j`VA~KrM+-eZ=6_F_6&no(ZeCn9D;eZ&<|6+t%WFC5?F6?Nz0#*V3 z1I2KBaYzgw%qz=l>v(!dVQgTn2V=EO!~lbgE780*h{Q9q3!Xj`-E}{{e6(^*!k;DS zkbydh*^jL1>Xv=+z=_d~!#u8(wf!?JokH@%lk=X!glWi6+8C47q~kbH#VcwFfD+7K z3zvnf>n9*H)uZ`@C|>>ENRRtGFHyC|I=SczcQkUs*tO%34?WpB(%h&EXCu^Lemtugcy*${JUjzo0vKL-Yrj#ENk2^ex5vLjt z79EELYewT?T0Ij=Wj9}@e~$v9m(jX&dDCT=vc^9Arbz0@bUkouJsRg8sWA!)1mGsP?3nEW3c3Bd(Q^P1Z2b@Gm#F4Hx#NP)*Hij7wH#(q@@o4{N2 zLluK~7f;fe&UJTIGQRKxsE?A}=NthGM(}m(jTd)gTSV}N78v`>;Y#rad6|)tV!Vvm7Wa54exWmc@+t(ciBd8 zN*}hp4C*KUJ(NisxTK_Qu-QzzxVXh(Wh;im=`OYq85RpMv#z@oT8tLMh|zipaC-Q_ zYG@H8L})<6Bm?An;%yJAPDAARw7SY&bugbm8_HXGwuh!B_Sg+`CnPsZowsgqMUId% zjLJuRB+Z&^6$h95`CJcR&=Zui4EOw&9p|ik?ZvwQT}=k*i^#NI05hgg#cMN2pcH| zwmX6XsUKbY&LoC9rY)H4Bl_R3sL2BlWPnBe;%99($P`{S>$Gu%g&ZczS{Zg*CFJGo zm=L{%gqmZK`yu=|ave?Q8!446*r_}%fB5%5r<6!Bd(Y8JHG|PA?Xu@!c+szpK>I^; z?v|daK?Gt2#qHEVTb}c;y$Q;aM?}Wm3Xj<*a6m7 z7MctSgqpL>Xmk2nZAnDse#cj01<~T7>Y|_ZV)Z4=-!=&ZhOXpEs9Pm33iP5 z>n5DHJ7|F_PW&K-5iUfXPHfPFuF!asIr+c!^T|e&G@u}$(0j$k5<++;0Yv`YJw;5O zzYp~kRrim9ndBM=w5$uI)3WgxR2YX~l%sHG^m(ti&|tTH;tnw7)9n|R>vIlG`lZd}1yLAvJW6iZM#f&)d;kCi zvT@FvXUgi%{=T!fu-@ji-qfv-%h6`YYu$uAs%#GmE zG#+~$NW6$R%`?+G13NHrPqLZeZESSlUba86!AB7j&9{sZ)~MQwP{ky7s{Cc^K7IZAfUV?@#B}yS?xD0X|5)jCqi=z@CSx{ zLeS*OGOiJ-LO`2phZFlYa+{~43i=2gIPz?w^7U|@50z|~2l^zYQajLyAEUN?0lSFS zgPPCjL(kJ{tl8LzWh9v=iIb7ks#C_H94HHSO0SaA)ITD5erufEUbY5sm_P?KLqjD} zkXg2eflr0NBAOub6}45QQ1{hTfO9 z!@_DN7du0ioaZV_?Ha2gZa zZZ=#sOrk8kW%<@Lj*oeV8F>}6aYQto%*kzv_KrWUp~)l$KHADG3T7xToeOundc{^3eAD)ktb7nugn}4 zx3t#knG%mcq163F=PU%It~ymiczbxy3(b@Uhscjit`oE#smMD)IwnibVF{`3^#eIf zSfd&#{3PTN@mewP_xU*VMbRB*TgT=gA8|tZj?tk}PrgL>-J+R2Plvs{5+W9+xAD!E z*3PRt_CzjH45iy&wf#DzOb8QVAB%GGO5Pd2U!KuUw$eo$%+!d7QQFTebgI7gK)lW} z5<9S31Yp%`$b+t2x9kdCLKld#@7a~XK|W(Y-*iPp4*EI>p-2Dw!+L#`6Ev!FN*glB ziYW9~rID)^#_nEW8r!U0cLxy~C9VG(a-~|v(=TtxVARypvg$8@=tMdWCN?rLHg)u( zP__vWuEK^*-RE=O?xuZ@!q`ptiMYSXrzoFAVgAxRCs*3h+{PrHW z#zI+93-y+*6RhZBbNvEVo`G6J9Ka5!rDQZ^92h}XI~TYP($M22uNe{Y<8P2t&>kW( z9Nr`~1N7OJQo1;L2KLM0O%9b561*Mo4J7!`6gGQo3Bq3WC@?8mOl*~0Q2DghfFfNC zu@58knn|1z?=)<=*zK=(w}JV0U`FaVZpv!8dW}TYz20cs@EBwlCq(;C+ijN^yV$xw z8UI54tD6R@OLW=s54wA6)YR?6B9xSNL&bxq#BIzf5jN<(I9OZ^5W{7T!~lX8&q**1 zmv-Y;=TJUKwwxOy1$dr;Za}+^3f?u76b3RA_)NwT>QgEBAUFsIF!r$&!s&z*Yk-pY z(qz1Z*~)+;qr%j-dM3_^GzVGasoUFjDF>s4B9xF!pt+eYqqPpo7XoG$>dDUmITO5? zAJQ$tpM6L->4TAZ`07$Wf(5Aa!&Ma>KUL<#ZcMch?k5_-qQ#NOo<$eFWU#YIkY7hA zcwfu=4P?)INbdp#SgGd6<9dsvm7@h_S|%`=apQrr5JH4r;r!)HQ*0*~9v>47Hbr3J z-Uy<-Ri%3eLJEy%rUhqsURy!Y3K2gk$^6=mK#~_3AK{c9L0n>u|S5=SNoBF73 zxpnYCax!=|Tz?D5R2G%T-Tj`G+yhu&9%$AUYCn6O!KAtnQP|nOV%B$Qdl}fNerfv4 z%RH^=r=&Z&A~J_+XEpYmrXv~(cln%}IQjBJ{PxfM|Gha1%WY`XAZm}E!_{|gbvORc z-ZQ8py*IV38l2af-2Sq}h^YP=Vbd8Nwsq1n&7?VE(X=AaF4Bp{qVELtl~gAmc%#Ep zPk92odSps;xb+L8F(NyLiWRm=lJn*lrgnvy4|^1&Yoc(%ggnJs)d04)}ad zxO7PL5T>$1Xc5Xax*U*Rk_ET{^YBw)iVsS0OOoXMG6&uq|NV^bc|-4|c%UnIZZ_4$ zK2S3$=9BXi08{w&iv!@I1)X#lgmR2Ln`Z+RDkfX;8=t;tRH%s>Gk3gj?-_aa&%(Z+sZ`ryM|UbWAckB;O31v~s()H*X+)3Zb&YnYT3qZ}tKe${v-%0oXGR73eQ2+o4Q!8nD zQr2K0BR*POSMFp6&Ck44*s_npZ>ZgqWb)v%`BifNnp(4#6;XaWcvL{bNp?IX-KM`! zlx>yv08epCAv(QnxS_;qVzZ|1G|`<~S&$jSrkN5M$saLc?CS8hPVi zI!T@0Crl|q_F;3TWH5oqfrF)FtG(nu6-|oOvN@EzIgklJH`Z^9+ic>t=Z#Ec`0=h? z3lpV_q&`0?N9XXN%BmqUwZNl5r@A7|o10a8H<(*E6gfdp?uLUh}&_VIx@H(hfgoq-vZ_8rjBwnO(4 zU;#_<$dM+8BP}ntw0ySoje?{HuE8_yxB_bZ8}Z6<$2aO3%Qd_k*ow93srR)2+B!09 z_L=2WjRK9H=&k2l2Xz9FdFQoRG3}(V9UL-Q{x=qdy1T?lI5_(7s3pd6jg1z)RBO!C zQF)n3_mLs13IrZP8WoBPcWZBYJBcXhL@sDARX-TU&tNpR`B@y|NX}h(&Uqf|8L&C;~b32Iv5X@-;LlD>%Dk24n|E+;&7s>+hkuh-Uu} z#&z2ijl6=Kkc@3@Bb@7MuWDWy_QC*IWklut%)*u$K$_H*KN6X6e-#}_*z(lwf3}AN zyGyzaq>;i(u)H-y(9W!^js!3T9Q54ywzntxUiBT{zys2KkC1+8|%+(*wGW@C;> z=jk=;L9aalrj7G%TK`F8=*!AHBkG%e!jBY}6kid?YGXv0>981I!}o=K)>aK_T_VXE z+rxLyc?w^m4zyIW;tr2=-3Jc5kj zI0o+bJf!sWPZPzax)Ys&?Q++=qc1c&c*GMmerp^^RwEIOP|yxThGsT6Sn+Hp12c-n zKxE3%%S+GjSECo6Rc(N37!LIWo5Giqdb^=jYe!dO@p5W}!)9KMlteA07@7`k@FE3- zCQ$ud%1y^#RhE%7ca*mm3R{EDpfL!vY8V&ycXeQiJvJWzu@>kU=P9599c(I}jk>>U zoyCG`Z;a$?pQ5?H{fh|?=ta&);=T%&yv(tcX!3|KDF>j?7(j|SGWjfX+p1niRrf|l zqjnbAeAku*K`C7&@QO6;ZvWy`Ujr(g-U@n;cdQ=^{0b)K(F_RKFGG%MkM}6cu>o20 zl0QlrViYaUrWklQbsG_`&^c*(_k=bM1dtSb1)q{>>Bj2Aj4rWoM>ap6m14fE?dYf-{$HAjEUo6PSBR_V-q z(U(hfSygXsFn?`LGwl*9=NUqyWNsdBWch}jqHUmbN5;UH8%X;~!3fId)$0%7lTDd; zUUAM$ou{b1nE7e?dUZB}7f+ol>5lhTNUPBO@t{zjh&a3ERfcv;H)zI-Um-m zSla!ZS|V;OJzQA7ke3SY+-IcS@|Ees7~~$bI?iU{xKSG+6?)ktC!>C}d%s6%6lB&A zzHvu)%ke7G>ckBwxmm)9pjX%&{EM4r_LX8B73oF{S+5As>$SRIt{OQ3CiV6W>O*Iw zj1X_vKj%H85k~JV;CMweKFp}^;}A$IsZkemIMK3L$Hr8IZ1Oy$j$2ON>i8vfZ@PZm z_JE(p^6hg4%S25c{pU9ob{I)X5zGq%iU_GECag|%KLt{|kYO7QSdE#}Z2fnr0N3Ie z=)(JVXxjh4#{umwX0u`-Qd=LDojF2;MCf!VWr1B*?+aqoY9LSMez^$d!=^i2xBt=? z!aj!Ld9UU}Su2^gk|Wi|EkhmY;6sOvbGSQHfq|?pHi7HkJ)mVgc8x^Dw7tY|7PEF( zjU_7qztKHoj4i1zvb8|8L2;QmK!q*>QnS6GaDc??>{S;d+^REa zoa2jSh?OLMO+>n|IfA!C!)AXD+=vga_k0^(9)K>AQ7NPWH_5hlbV7j6;>3a^_-P>2 zS`LyOy|n-tOkBdq{b^5vgq%V@nnDu+HHYu^2vcu?@22-W{^CJUEO;q}nuL0mJ&_$D zIK)4=5E8QOOz?b{&8$XsH_#v49(^kGjFW{-#E0}nP!}sF??uBA#z;q)1o3V;fI(k<#14W@bH*VArp}{#*#PaJNVU~{| zUK~o;P~Zg~Ll9r@1GI$GR3P+4TdZQ#HQn}1AO^|bEFyu`)?GrZcCzdp2$mn3-yr1K z`HiO)p)b2a>{D;yKj@g2>*SAcrgxMoNUz(qtT3DJI$=&g2V1@oGx9v;KpfC07$ry0 zGs?v$WNBe$tT24{=Zsj~pW<&GXJk3uY*9R@4!_EfVO=G-Z7VcJ<&U}QpJ-J*>y)iv zr|1~{ZIK5kA6Qr_vFqcyX{30poN9Wzt8AOxk!u;%;@LrItipiWXOQ@(NjP=5Xt6-t z&K#tCBJ@9hIEMJHw1}DmbCtg_?P7+<9ffeH>L`^Up`m8CjDLCzqk8ht%@?W$>pvzC zd$(pFn{l$AWWrLn$}#Sd9rb!gW3rbbdyN?m2ME^*W7&Z}WG$?m{Gt=vu6$TZpG2=^uY&#w%Qe<*xH9*VArpH3Y7sa7zzti@soCvvz9zQEip9k{UXi%({Q|e^6pNfT zh%}#DPOg!}ucaSfxW(N^mrf|^o@|1o=w*N^flozr=soyH) zO%h!qr`itxcZG@N>f6QT3R{NBlQ3NM{e}|)j<$`-oM@15635I+28=PXxUO;?AP65*9-6EdJo_osT8Dsg^SNFk(xc5j^Txcm3G)oPK7j+bQfYw+wSO4E+ zJ!7=)TI`hAqc|=0VkINs!gp2t+_6N(&tap(oZ5mh+?gG-%M@IpYVLHPS~YH zJG))Pw0n)QY=TOQx^Z`s8qv8!g~-diE2RFeyo@*3!U&$izm&M?x)N0G2@8g)mOOD3 zL7xCB8dGgy1cSM>qIc{)MZjCJj!KhF4=JIxqOXF1H{O9=JWNB&sjQ@U`1GEslsDnFPcmoKoQ>9jC_2aN>a(-hW!P6KO03N#4wAP}lPmfjJCnv^2s%~9K(3i1V#JJCxWFC`Bw%>Zwi0h62ABM~u->gQEv^l|0u z0H*=TM{ngw(xQiN{y6|fe{Qb~Yd)x44+-3PHy+sH-zUI>7d3%3el@W{=uEmdlztXcc=u5rBC*RhKGpECvQ!LD&LLt?xff|&tl z<}>QfZJUb-$ps5~&sp(^#CouRN9!xMd9vN9Ri|$1o6`$&vtR(=Z%hl7^F@9-pNA*8 zr{J(mAvmv9D3OeRQ@&>Q`*n?afk~+xl447qqY0Q5s8G~gOvXizsTLw?aYz5@*+^dh zT@jpm4i|Sec(53iC`ZHK>ISKWLud)>VV@Hv?nITuHYtSUO@B<4h1&+HYh#T0`rbB- z%4h==HXd5f$lPm~gIY8Por9WzYxi>&+|3yaCuKoPkLIP)TW2B52A2oEWtzLubrT4{ zDa^=wH_@Lq{qz#r`DEs^gBX0?SnoJ`ywgROlAOzWI4Zh}B6FCFp+^?}_O!k&h!AAb zCEk|>eRT)W_=4C+7Mzjr$aOHJ@W9x%6Ez!VAtN8#Od31hyq@8%D8I83t6#tk%q<+u zFRRS+;f#RGRN~+xA;VTDMm}N~eLLZqTa^0QZwx&PyT*Z-;Cgieh&R@HsF>}qbheMb zx&Vw*BSp@3>o)<{kKE^Km4hJY2>H?2mqn65#;Z7YqC-aI6*;rzy0GP>RrXODehQTh zxRUPXp-&@L`7nl|7+$Xt0s#0$bxU;6x&f$?VghWE2rCC2o@oZY+~NKE069akV>L<) ze5zyn2B8{TpylCe9@wDK4XM5J$J9)uW7%&RaH&i=XleVncctXn+7$3(h0Wv0D@eCa zPJP37i4J5)B~0m!hwzV!r7l!`Dt2#E_d|)}d-Wde>{7o9NkGzllmK9c#RBnpZtWcDJCIVvTDvW4^eQ+Zq@ak9M5e)g*V zTLjG6MRjUC({Uh*MSgK#qsI6SPrCzj2*&0@;8R|D4D#Cj87;cJB9Xm8dXH$#nTc1y zhn-r14N-ZNa-4u4iJ|lcvJWOS#t{!2fi(T}v|U81y)YP2nXC{%?7vE>;)5Si&`3(D zV~`C=mJ4IRFP#&7)p033)do7Uu#Tq|baioVQu`4z+*2U(Xz~rJ6?Qrh4HdjJ81T)> zw?tlL((2F{H~lhubSXHD$jlIdJ7c#$oWjYm#$x_&HxbLqOp#wA6_@4=klTy>&eUp>Nk2gFA zo881TRQuNAtrbB;CYQy>CJBQmu>=sXwV&uibY___&}?zHzU+gy4)dy03tu8V=K-cC z@C`)PqB0D(^Blh?U|Sp93Y5^I0QIF_Gw_0&mj6u)fDih7-0wx`Q9pajPV+i=%tY3F zI3RskRnSR#w7x&_+V!kRu~aIXDKwgt2^n00O_L~aQ#?*V593e90<;H!^lu;u{D#!} zPhQ}hNA>$!qzi#ii4M)Ugv(vgzO*jI-k1QiMScT44fp5^@rxWcrX;gAQ5t@W>a_jU zTt&UHZnn&`R$5^J*ZLIFdwKmp%hn5aZloWTpcW|9rR-XdLNhB!+6iGSB(qLs^= z45Ym!`l#u+Gdqj3K2@{8yOuXiddZ$~{?Z?o8!UE1R17=29L?5n{Em2)U3P>6F^=7u zhJiV2Au1D*9YD z0e<)8WO@_wGv67s*yUUV@V!P5c@hm+1vT-P85IYBp1H_h;vcWH%AVKk(O4mzg{%M* z551);ntigNhy|%pm5;VmBkygzy=@@Y)IlnXNB^TG=evYe=g~KNE+%S^Pjx>_?lbl@Zjo{gZCk{5O= zD};A#$x0nE(j^igkVk#>!5Oi59;_vVQMXJg_!>p->Qbu~`Bd9=CKfOPDSM}VNOSZ9 zadl%gmS!uO^b7f#4pyigdXW$qpD|e8w&OMs;g7I__=6goI+mt_P9=lo>(z1M#s>xU zfSYS;Ld>eVBQ(hE=|XIxgHtHO;PRcDyicA!!{I^pr(P-^EorB%E=wOsn7fyAC$ugB zijC5VdbJNj4eMjY8F4oWK%L-8s3ZXpw^rioERFoNwBjAclx>TLH;W^c8hI z5Vy{t!GTD#5e)W3n-NjS7@N#7K}AW0XBpZUj3)x2X0UQ8EJvopI_ULd!x7!REBOV= zd4sT9{f+0=@gc%=?(H<1fq<3z)&D86xq-zN-iz;#o;s&RbH>N3<{aK+rO%+_%#?CD zswXklDu4+<(^1v0&#o_45@qZfwI$daN`hQC9_MY~*s|4z3G=)N5`pLX2MCqY+c%xi zVJQ#$`VXQzOnd!t{o(Cv5f}q^EDSn7MOHr1+FlJ4TYZh`7*1d0ku7H=#69&-&?NDtzZE7dW z-4+28)9@n{`AiCxPW39nSxzqb3Wp9v1`TUbxc9w&DY=O*CeBz^H>}&3_hE>J$ksCO z;_~#FNBO?;gBL*-+^fCH>0YMzkLr94bjP|5=Z@s(OpzE&e;;W(kj8X1roZ;cE6ar_ zav7F%0y!iS5}NJBmQ?>f*X;P2@)zVCKY_V|-hJDCuqT^QohBR@0M?`5H_Ms4bL>Zm z(Ic2|TQs?@df;p`Ksuj!zd=TwZTWKQnHuhIq9XzzJEXqHGn30SC{K}|1OpT%Wme<| z-HJcuu46ffoStXW1wN>wRuGOxU(iA9sGFlmBhm;M!dy@<4wG#@}8Z+2#!6az$kDkZTpbSD>hz zLN19LPDGf_pvNQApJ?A&Ha0N14fC=H=o{|yYcoZrPl77QjkC~HAf7(7vmptuGCb?p ztB9vhDbu)cAG-vVc2KW+fz9FK!%WUYjl&}8qfP0Bzt*uDIWJ&@R^bN?+Gmaf-45M{ z8__77UI(f`rSv>7jhON13=%t@kq7hU?Utq7z(+dl9l10gL5RHbMM#JqJqzwRlHM8m zVAakPBreV4nu!1HAgbf1a;OD@_%m78CXd<0)Bw|OCpx*7*2XFg0wx}v@6cU_O?mlh z7Uk-rU=%QWhTX5RAEu*tm57BugJG*;0Rnq0iyGnfqe$)kE=2y1S^wUiAOsSiNAU&g zQ>`FVsp{u=mC%3C&OJ!GZEw^hj}HK39@T~r8;PH-fP23Vz+6ecmQbm9358iI>s>i@DNazUY@Go^D_P_|d*6KzVBz4hAb(ID;5A*&l4eMq zIN?al`eQyu??gI#m)tha!W0dTh#KyI9Xk?^k)Wee8VkC~wFP%GUVm!Hepomw2@=iq zE(^Zo({vK33mbJEHhIV9Rw4}KXjYqpQDXj1XqUBq)lMH+;0)=um$a|Yu*J9u5dcwG@vru| zGdvs+$lW~wP1ewiLQ9F^T`7psN8HTdm2N2$id~%FyI|MGwkpcunTyG|NT|G^0Rt@Z zCFMb`*_@S2=?oeoI6Jut0x)if8-Fo7%ANNP(Fdq`7TgtEnP7OIK-@o#-YMGK^!@ z0|%i?9^QjMSnb{gvs6KCYV2Zo5`&>*17O&uJ=s8zg1-vjJ*X=98DKCI=i^Ly9Nsm!QFyG zfZ!5BaCdhP?(XjH?gWPb0fH0U2~N11_p|@6y0_|9ZS~IdOwT+|_vv%GduGnD6b={_ zbA?vCa^Js%42ddxt}45TWmw@So*ZY9-VO%xjHq^d&CQ@t?xG% zJi^kZXCFIrn#=E|5;FX_cV=JL8*tQgk^P}reWgg;&iPXzu$(w-}{`y(7 zt(Jn$ZCdE-2X;n|>(N+AtUttRQk77%ML*YxUOmVE_>+b$+&1u6HeFVdx8sU^4Qn~m zZ>}v#8M_IT$|l_!5|Wdr%-oxATN1IY!{uQ=#js)=h00#VbW6tG@d`~Q zg@Hz3i&0y*phdB}-VDbPJ3e6E{df{c7oN&xJeETE6{`L7`c25Ed<^HWFJr{`j&43k zXzqKHm2}i7c0>q1g)*m4#Lcz#KKcTnG51bFWXnBc)53;Iu8(*RdbheA2Srxms&pDp zu^91xaz6+!XDH9APgT^Q+CK;}1uxN{MLS+6V)`4AToP6jeAY=~%g~+_)HXL;@N_Xq zeF@#D3aDklmBWmfQXjLS6Zp0q%R|BC?813T~UVx*!kn&7+L9=(O_YrA@$whV;Pub+hK6QA zg+^HHW!f`L{}~Qu&mLzFs79xD;~)Cl*zPb`_s(0p!SNBX)n6#WFmh}MROCx?*|0!Y z$AM{dwTxa?H-Q?|u*R%6R%fwDO-G2Jc~Xy4%|q&iVq{c_U$NRX0jPG)JNMH zB6xrmDoL%^0*YtGhWNQ3%bXJNp<|ziLfL<261QNWVcTl82OaHpw@+m8+xfnwP;}I7 zof)w&WA{Xe!0tucd1DfHk!bKG%9Xs^b84p2V$>mVcV3kU$`U(~{6?N|!!+TeBPseH?)qnfYHLFP{p{&}w|yM>!WO^v1WKK07P*JychhNQ&qCV|;VS$V zk!l8gR-Kj?emMag12kqOWDI@Uw|=0@@E%ID_k=?4jC-EmsRwgNo*p$F%hF~zM;zX~ z!EJ%HuyDdt(4!&GMBYaB>T%@^P-wB;#NzGfq$q_s@c8FD3W=hEA5SUr3E|LcXfE#J z;4iVpDb}I{)svt!DE%x)-x2ORv1h7n*0A~!a>It#9M_+F!YRyYL!|Kpom)gdJxg8b ztC942!`06W`%{Q}=00+dqU`9-Fj?18zxXHi*}V=-dg%9A5I0f?DbM~=l%R8gwjaK_ zzE}~w`GUwLWd^I$d@d_VcLUUn9#~AAs^vR?9XN3*Jcd&;OO9B}J{7b9GYa&Uc|IFI z68D~xBC#hR$qckHmAjlV9yiHqz@+K?s18b3KrXWm&2^KU)0t$)@~i3(36 zZ4$14LRGtJ;X^z>w^90$zjKhwazy#FkIAa2Fm7RinC^(PbFtMdxVL2XT zl`nz#{KJ0**9z|JoSp>f`E#VrXOdI>YvXp-u;{%&UtQ~-V@=%oyJF_LAYN ze=9O-jW*+}98=SsfnIji`(n=j>?bB4g zpYPy@*eWKm-;G_Ng-RIIAzWWO%NR~2p{4xm3VnyXALKk#*jw)67-!!5jv|DR*`IBQ z!|`-=Y-*Zf`0)}(i{m=w`wR2)4^!{{q%kckzb2ojx$=C6yWg#_PPr6VNZFx(1 z^AYme|C$nYd+g+?gSm!N*56ZT`+4uzUMe1Ij3+XD zLY_VyfnA|sxSRWRE%YxdHM7=V31^|@O+B70tjBHT^I8{^q8!fZDUyS zSk+|Af!V)K4nnMx<7>JgR^1Q=`2P@ZHP{BC_MW>1AWVIJ&DM+4tWy(qj%s#ovWfB4kn4GC1kc}vT+axcirzQITFjTL5ysQRK)dqm|s z|C8b8@F))~b@HF)w>Hn_AH2CYkh0g0Pjsxt3~I^wSr4>7qcK^an2}UG)$iUfobmn#%dr*=B`UF%#D#9NUI z)Q%{83hWUCAqrk@hd=n&Tff`0~1YM3`WO7TcIpTw0-R&@7Zo zK2?Mm8I;TpmxD@^6g$4|$I(#87G~c@dVSl_`cC#+p=0f{wH(AFfzk&07Th%FJ%vc_ z@5YVMWAQlz+HtSX4l7ZvG^*L1&24RE1wSB!tbEG@4;bHCQ>SqW}Xk?(O_xWO^qf2AkN*HkzPUq~7 z{eh8_mNQS>%1d=pKrxwou^pjO_rjW!bN&|R-_!ST*G}5cDJrHp~3M<3|rn~zx773MB5vs zyt|-KDvs_Eg1?sAQbH^T^sI}oh`mLXi%?O;bL4xuYTVbIE`rpa{RXRyP*m@JyYNZS zBib#gcwE<-cztIr?e%JttVtbrUH39w(lGoCUS8bXj0)Gg*m_}Y@k%2b7{Sg7Tv14g zdx}Vk9U(Dnt-d(5kgC-7 z^1`3LzYTGcWS23=dR++(Q+ZsdDuCiWJd+KFrQ@SN{ULa^_I=P2^ZxSCzxRzn%xV;R zj$`~D@MHBDgL=Ev@9s6JJj3RT{7!rh%}#DP3~{@Sb(qW!GK3JQAan2QZKunK zT1~oUgq10xZ71Q6EqiPg)%z^-Ws47a(}j~cw#86Pn!1>}egIqwV}qzZJ2Bb@o8Ilh zCW5@$5lf{<*U8Wqn6N23!kI@#%C>u-u}bvR$pQ;0SQSMhqcW0N@rQ<5dkrP|D7PbQ z3qOEJi$x8fb}ZsW$rmGeAM5+BXudp?QXy-GgKIY7P@FOHrGfq`##p44B=;?yLlx-E zDd~9bEAcq7FxMY?Yu4v3Mnx0`!r>=tpy^wa3#?}SXtv+qwt-eqleYXI{iOQm4MliT z>o)hqj-v^Qr{_nHvyZC2@Hw`n)SnXO==iKPN>P4s9j-Ko$@=@8tCD)WM;DxF%b%k# zZr!>gd?KYLij1-h{pz&P(M2;CGxq!C!w%N$w78Knycn^Ue$}G@g2N~P&HkW+lM4ea z=3TRDXjc03Pg5<#Gfty8E?!Tn|E(xx6De#{7SbA8;@by;iEY)x;HTJf+ukYWZgqbE zfGrSBhmQ)&K_m`xdX7-m>HdmxM=>7aw{?r$YAMrKPY0m`#UbOpofjJ9z$obK*DCBS zc<{REC8mRb>Ty4LodRmlNvIi7UD3+Ykyl(?yt2ktEK3Gc&0t$s5l_v9FCQ~H$N;`u{w;AUvgULgj|}hX z_}mr;8s$jD39Yt87hRPrsBStyxMZO1Re=4o@J47Y+BX=~tAujv(1$E4T3wCYUZ~s;O)a+xDd~@lM zF>K`aj2pI!;ix}^(G~=0VyF6S=tqEly*k@kI&Js$C$Xfp~ z$x~*KHAXDV;<7!5TNo*w66_|%z&lHgyt2eCM5t!mCUnD*4!ti!n_`05r#~U&;P3j_ zp>;DTV%{*wbJwYSq2~W1tGg^@`jiM2e>G*kWw4s5E zx~I|o9o3UI!pg@tt|InLo_Wyb*Kf|{tzUthTYFhrGemCX@bz0!F_Jv@OaWFxtCgKy zTr>uU!P+oPu_r<(df^iLX{gmx%W*+OW3yMxQq=(OG<2ggCgC=~<%yoNGCTES=?kZeC6dvH32?lU8CS%4DCN>UWX-kG}stjwos3FS65@sYLvgtiQ*?2)kTI8fBb{! z^Sc*C8U4?&GKm!N!7+#WUedgs1@jM{H>~XKpM`|{eqg@s`#3;b7wKE^0P`Czqy@Lf z93k;bQ#QMu=rPrl`r|i5YyvgOdP)a2w*CvyRCD!eO#pk|m_NQ^fHCxgv+0qWqT{fG zCt0#{aL4Jr^qknesl%5m4Wk(1ftQTw#Q9?_MBkD`#iU5bFAO1DsNv9-Ng*_B6~Kl$ zJ{NPOA;7Gp06=xlq#zZ4nzz50ZZpqt^2ivp;!p!KA5(2gOFPm~t5Z9;jCB$z2hW74hwK!ki1i>LD!DKXY;)Pk0&__z!6&E$ z(=}ChsWd#D3w7?OdANp)GKEy5chsaQ@y=qf+O{7p+{~ibSuCQ(Q1V=QFyah!9=If@ zZ@046zMGlbZvz&IlU-=HuVRpJ%TI4EmK#c%X)aS>&c!OFecVzdQUUbXelUCR3W038rKzqlZj+H8)vn6Yi5OC!&AWEb%<@U1$5CMnP*<8F6*ol zaYe+rS!ry!V-FBPE=pyks8JYg-uNfmgHdFkjwb7?wKU?#0yzo4jMIXYdU_}{^LUZR z&p&PtvjT63dravN=A|7y*s5=nZOYnBSwLi`rm+1<-|MDbZZV-Y@abH51{vU>?qXuhE4!_slglR-0+bqT#TTs~vD*?xaz9e!b2z0071p%|=%uQ|rx~ z9GUrRVWIAe@|psS{@I4?qNS*ox|j9$)?jxHn5X@|##e9nd)9w{7^(l;{#PaeJ<$UI zyi+>h`p04e1bhoeX@&qE_;fe+fQbd&*AJ6I0yWr6iijGNqM^WKqJ-aT9~A!4o<{+d zLv75BR+f;>1LE8jxozJPVf`$-F6ao_5V_D!!4wBq(VPKE1q1QfKZ5)xjUv^s)NT~G zYs-K^{!!2B#j{^*D3zWs+z-i9v=<0>`jhhbe%C63d2z{lSU0gl6T>aW`JMPUSWWiR zt#292Ez5C@!mltc@p{SW^Xr~r&uZA-pzq@(_jWi^3-EK5@=xYP36_zt*h7WSjVWgi~e{PY_9K7 z)2G>7Pe6UxJE>4b^#Zyme7IBM^T^${qI+VnFJ zlJEYyCXM=`JGYchckF#Xg&)jYIe1ANLb=4$ZC_>(5e@*L8c;SqbHuAAEEV}btqfa= zLeuGS?+3-yZi<@AoMbyiv+x!j2ShgOxzs9RZG~kAKvjg(WUo2b1d%0)1G!Loy(aY7}|}CBs5-tJUTk% z+m_<>Qd+!}wFYq`;d#mStz#JiiCS~qns7#y5c#R9SBqUd4N7R5aSluIR1O$gm%f%R z(lQI!QWEF~{*bL$)2w!k#vEY-^>WsLP9`Ff0jOxOBkA~8m+n?0v>)CEah{Eaw+z?< z=*^PxSJ(FaiIhfyl-BS8T1Mu5nw!tV(N>LLijuQabqCBU>Ej^*vFpl<1Q6rGSM}0b zK1-DSnO)=V(}31so)WX+!Ei~gcYH3{(o-YP@OVL7S)bonCk~==c_%G8F8i)?b40$_ zKr&9s)?a&qThE_DM2WJQ#<_Ke#{wq$2@3Lc3r?_$qHgt6;*1x`))?EXxm{UbDPb%C z0R50AvzC4RKRYEjTbms~garN&&JcNiX3tfc%5Th~p+`a?aHPe0IEC87PU5^6BJu-Z z1psU*a*hyV1>y)w;3bO4$9lZ5zZbm^g&=e)?c@0=&JM~UhV98Gt{Jg~4Pw72ljhhg z7mTE{g=ZQRNwHq!X>s%D^Pm}MHrCMkpKFFw?w+Nb$IaLZ`nX7sIw2_7FxNGuo5*|w zSZ90~y6CZBHCDp?n_ZaLAC(qsuCMR?EVz3C%u5J%H_>$bLoP6QmOT|i7!cCwf!8I7 zL%9F-AnK9M)YW1LS4mryc&)j9@YyXadF4_)@VDb`FiXN7kH7n3-EQ8xfTiQ9v7?*? zYo|)Z%uyZz9lxikQ=N9Piz7}L!A zl}r{#<$Fc*(v!{h^l}mwn#apvDpn&kA!+ohQrH|S-qx^JMiM886}x>rE%pVp5aquJ zGXo;2-2}MT0q}CECJzJp$^QAQT0_fUe=E zYMIbA*|l~pzVCMhv2yhd^zUB%s(RaZzOu_ES=USloJ2=MVq2-Y-f~sgDnXZ38KI** zjC))O-5xe|dsC?I?wGB-KRb|$!)VStbV?8T#!e3VvXmt_LD*ue&-*Z=LqNJ!zRv-R zz^xI0`PeQ3D6|o!htfWRi`xy&FxK|H2eNOoW8difXtbpAsQC~|)O49lkC*4QbX}`+ zi-y&EO*@&~SaMW_Z5FLima@HFe|cNZL_q3WNMfszLPT{Sv`cTqpCB=V^^pX-Ki3ns z(0{67hs>y+fYHWLKRgVIn5K1hl7@+fqc~TT`m?;4w)uMli%!L~80Y}^S7!=OxG#%Q zmS?2*X#K6s4XT9g&&o}?1xdwLpTzC+u)JZ;K0Am@S~K*k;(O0yi8o>@(^q3>v^1lq z&ih@ISZC4}C@W-E1!#KQ@M>UfwKzyvWI+BJ8vYaRDcgSZH-Y-5EwZ!Zi}J zkqlOq@Zu}61!@xd1SUtR7Tj6#B28{QdPdf~7JRe|Ppr?N2@{EKpP*6n$S`rK#`BF( z?>XVB4`RfYpq`bxOicNQ)gPpaVx&8fnOUN4v|F;wCZ0a<6+z~$U^LNe@~V-4YY@m+ z(u{Kuz49N6FFI2CjokR>S6R`2@@z9x&7aA^7MqrTN=}eS{iyL`6=p!NLb9D@!#=+? zS6}jBax+!ZYhg0KL?PGycmo(2&J*&%M=I_I(s4-z?;@_|rf6DNU?SIo1d9qxnsx@F zD0b}RNopF1M*FNqbQHV3gg=!Z(3bf{aEdljWbOW5ltRcdAmZClCjA}^^q547o`Q%k z$s@_FSR7zce=CeaJ~*&V!*V+bH~+F~M}dQB3U#j|ZSKRCt-9Ph*!rE@@fTa4(t(Gm zxWPEaBAUklapW^u|7s$tNl*|%&YL&zCSH>3(XnHN+-!NeRckX;pEi*SJ->5$*JbmE zr$}(T5m2AcV9Ay*_;x}iE=c-X;7rlhl2uJLy9&SKM7tYOu8EL{!n(KZaSdErls%g( zEyE6d*aUb0NleZ$8oU}JGOeHQ(~$ec0+}OOgo5U2_$Yk7Rom%2<@e!GQ?^%+)`xn! zymjHU#kZZW6hx_K$#9OoM)YLTp~TN7+(eYhU_x9(J}Ab<^VJ+OSsB8TlUx|veBwXu zH?f0xdAj;zV>mC(LWbXvhpDZBA8VN)(+bq08wfKGk`oHHkU96D(147g?62!PQ)4SPZ&&Hztdy%2#sDa7Xs@6?TfHpLF0avJl;>*HW*VJ z=3XRHNtzjMPPoe7z{Yln57{_iE@PQi*0+X|@Z(;$zhI~*az;dG)Pnyq((3~NXkF2C zdh;eQcm-l{KzI=0=Vw)VCOlJEztH~~pczs=Lb%t3qwu9-0W3YgBvQE{PhA#Jr6$jZr*cid!x>QLaU6TfJY$(y;piAd0KMw0WRW_ zL_9&`(Y@~h-)@tK5~LxhaSE^?tKD^re6Il$0D$v@YbO?bpY5{`V|42|cvO}{E?7N8 z>(Eg)E3X1t^FAhBDd-e$$Mqi%TLPcFop~|t5=c21BfeVLiIAg|thcB7Nlx;F8L?VQ zUtEUEOGF8MQOJNkSRYX=D#p?j14VGLVj`;2v`6Feg4&e@R#$4n8>d#>$$d+`Skh)) zWlqEsY~ItzClP4DuumSMRwd<4-S1HC+ zg)dv;%7PN_GOL%|`wR0DB@mH&a=O1VDF22ZfZ=>|veVRhW z>|`l6uI5edCG!|s@EiFIw#-OEXoHjX*Zt@(Ldo%v6ct&i_kU=8ms-6}Jmg|cV3?YB zqpUTJN?FNvekzFghsr?@HNIKnWG4GyEeYj3wruDA?4r5Dr3)J7qrZ7dJA~^q`B|YW z&`wF5T^I3i%pN#D~3VK`>^M86IpHD(W>Nd z6zJvLy*;sHOc$pKFU$HQkZ)5!V8nj*y8We~HQLw<=JzhRl00P6nZ+SXyv+J@CtP36 z#uW0?w>V3hEFw{^$_t0ppBc5une!7+0zI)Tp1=h*4eN0o0NpkEbw!ox>6dn0=okXR zr`J%1ocK{YF8WB#B?2`u@U~fJ)fH_SwnF)}L8wvb9fG>;;l6KX62ds8T5M#Y4nBO$ z4uNgb&E1(-e4FN?Ub+IuJ2i2s>{=>n>%vEY&D!J@{1TjO9R=?4IJtzw1eu&knjP2o z{1@o_k=oxOuHKt+Ck+F5LOCCP3nSg;R@yyY*}G7w#;BLVhkcSjcDh9`dl5rh*x)@>8m6xw3sS^Lq!eJ!VEb|^aJu=(V zf?yK?f>jTYI^mnr|<(phNU~ zc55m$jdJ*wIOLOc9SufwPGBEsk0gH(cVnyC5HC7W9pNQ8$M+!v> zG4CU-+|6HLXub|b{Vn5i)C1hERE=>dYvVAn{YD|ioKP{d1_vJ=o?q1v>?;=Sg@&eL z5JN%YUjwh8Y+mHjn!k0+ee+KZE1`~}P*VdS$eIOmExCiE>LIwfV8FsW82>*lX6pxl z-LC5jh;I9a^Wn<~{YBWu$LP(Ra{-vNw%==%hBV|**Jt(pGB-tDZtA#}SP9-#;C`i2 zgm`5%8tE~&cnc7HfMysVI4Y|K?hgatltH#FyWuQSlNl$@n=NWT3wfG%hYJB=vsmmEua9e_T1;AnK|g0Y34fzlwh@^Ckq5t&xA6Az9*!J!{p{X{qzR_YK1`YComIMX74jN@P^zzLqD2A zWR(ePrUX(LY>qDw6c)k3CDT#TVB&FW`02n$!gLOc56TQ*{$k`q)N|w;4X4iYijvOZ zmHl0k#WDIknAM<1yFFz$mR8*2dl5IxKp&C?7juPZF1fmI(CqIlwFdCyr|2z0(QUP7 z*xtZQJD2+5)I#nhESk<27A4}>+}tQ%3_vRZAnc6eY%6(?@qtofg1zw2h2(LSI_h@j z+|aIbudxWk?kkT$phAJfZ55`dx64hmaWk^pP}o7d!RU_*K6!nKlMYLLFI16gPM>JZ zXs9vqJHnbR*>|!Jq)+}Vz&8(`V}a=VB(X(!;vBQ9>PW%Juf zp@!w8Rg-D#F#&(>Q8b=Kp(8Hsz$dvx3TKmqOr0~*qMF3=GuXPf2Cihq<3{QH#Ji5& zrmxkJ4>yF8=D|guLI;2LVOS6ykH3cs2E*BoZw7J|sO|OwKXIOH+b8QJcrngnBR($k z%X)MJfUoBmjH2D`)`*-gU_=(mi48| zy)1~M8EK2uIT6kXtg&?Hn)(K*sPfaXU*^xq%osLE1feV#`gnpY6|*Z`MeutVN(Lfg zf^yI3#KwrVxIRQr8Mrue|Huok(e``KvpJ}3%_Mn!O%~Su*`tVO`;>5q+wrqO4{XVo z;<`0-KFodA%;SCq(JvGXINBPFKjm;AoYsxGvTu<>kKkA1Uk|aK;$bHA0%f1;2To*i z?E@&z6G$E2jVGg6f~ybrX5_k5yvZT)ABem@*p19&S1yDZ{*jY16Zss>XE%;yMI@6H z>VI*c_b64ei#I?{fDvRY>~O80(ccsK&9Y2{ztwP$*c;r+3gDoC4&D+yY*l%Ad!|!= z8No3yO35KTz}NHP{XUqq{_}!F`rR+7wbN?sx$Om)E43P~v3^qvUtD55SFA5EFIYlk z)Fm-=Jf7CeOQclS_~LYz2i=231mOXu<^6v=JNUiJ0u8xO;01CIg>Z9 zJv{Pk(K}_Nd3OxbixwC#B>9b8%Ee8|WFM3&&4X-ay8*@oB|% z=n;EH6plv0({n#qcmQ`~6QWRcj8zuG#7E2L?v0AS|Lt7oI$*&~xZJP_{=o$pC&HE2 zQRwGYbJ&nEXsI0Jw-wZ*-6y^@!YB!5g(D3Q#5-+MrFs0bAEH!|N%i)LhER^@pURW` znT6jdpC-w8bMSmX`|1O<{a}u`?1A%XvBl&klLv6K<>YbS?P2=KivUdV8xDL>~* zl7Bj4`Vp|^m$eAB$Uou5X5EipC%zK7bbfWePqBd`wS-yTwzOui`x3%@71KDFQ5{W#DiO$b^`;QUTxQB)zWboTc zhpilWU%!Y{2^b;d#u4q>HhBeTxRgrkTGWK=B9;sse*V1o@%A`4x3AV;4Z*e$BIBU! z_m%%Qk$+1n=<8ot@iF`ZsrFNNhhz|EqW?Yu05*~UtR*?|GZrl)aqr)JaAqbbS>k~; zlK~zYi#MbcK>cP2P>};9B5=@va9f!1kJ%NM`Z*(&DBz8e0N2!sXit-=<}x}yJJn^v z%W>GyXWr+sX?qGE`iW@t#QS@Z3cInK@wu`l3G8hW)5)8xzI&t>p+{{+ z2w-5=Tooci1Oii20r*x3{w7eiEV9IZ#YzowThPY;kp8a${%HvmI&z4UFna#+f4O*v z$RY73L$8C7;7uG603`X3Sp6+R;PM2>a>#uZ!!Wk8FgjA-lS=jAfm4rD7wSf!@B;1f zO#Sgf$raG-ad-UMcJ)gfN1M>bK=r)YiSEa*m;Q3%>{~a%SWO+30oq$@=F+?yG`_ov zBjaYc1mB57WgyEB0=yRjoaz5Ra4l>uOMIXcfW?4Xq>%r)xq#D{ z7@qY8cl@hhwegaac|5)3Vd;sr=hKNCk%NL3pYdpGIZdMrT%<=~H*Tgi{_C%ZmI&lj z>JLE|06qqU17z`ER{p;n{?EGR(139K2grX@(i&q_?ax4GiJKpCkH9)J7SHA1{sQ7c z25{LUo+$lb-r^YkEkq=OGHD1UR0@E-M_%WU^wm1pYW&Mr$%lr=Vo#6|-(aaJa>Aed zTCqcLB_eH2YLH?>TMhW?@S_BMB}8JYd`jE^%9-^K>pMRD$H;2(C|<{HKBAgF_8_^e zdj_0Q0>%){tOpoO4YY(cfIk<)ViLl_>OU;N1pYI%Ve_v^&VX{_JD+wD}w$cO#$C+gk zBi2StGSEkj&|v(K{f1c+R+*>#N9fJNVa_7C2j~8N)zR@sZ_3D7E*9-NOCguy$@Yl} z&@ic2G?tt7va9}kCt_)I1U$o8W;;Becj$CNM^!a#OQ_Lzw3?|R7JYvB&w#E79Pk^f5)Z&3`_xuf98P@L}xZ52OF15%i)2jbC4AG69M1uumDLY6d}J4>2u9XIZJ9{m>rM_C z?cyUIrBJHXrc@k;LzQi{hUGrV(kG^C_7gH0J>qgH*PG6&5$*07?n%;s2TRN--6tC@ zT^SeJcFVqHZfXQ|L=kW!&BY%mDt)OdOvX-pSSn(93;Sf|_iT=Le7O!=pYmXot47yt z6eY3!OVpMQ#y`v*$s?CHnDrSOTmwI#E2DG#bQYF3@Vty2w&SRi83S&$^BPyStN9kC zb$_GuZK&BcCyb{)5Zt=(gn#boPEw8R(2e6GS%lwThgF<3w>G$HEvgunE}!%!>GxiK zkB#p3`rr>D$YHk>5mPkyMxcVYYv*7O8rV>vmN!1FuMVW@trxS zz0Qmjs6j5Mg^igR)#Ztqgs9S?4Gbhm2r43o{yA@ymej91_zou*>a*`(AHkj!?D;zj zQE6vgAmshHGv-g$g~p%LGzv}a&|3B*s*EBi_NTv+dlgh3hUPxvmt0iXiL^g%&@I%d zecU=rgXNt2>~vDC;zHmD5AvJ+>5A0r7rE3UF7naFn13-n@QrwUd0zx-Sf%e%C}yL! z%VE(Q?sSezvOft(ky4u) z&{E%Z`A^sFRSZVEeC*^Q@Ai&V2%vZ?XOpMH;Z2BaP)CyRlrFN#XPEJRcK(w=Ic`sb zJEgbS*V89=($}|t(!*{YiViiV;U-&_JaR{*VFYN6~E6N_pRZiShs2 z(*;mm7d3_Ler!^Wo8ICTdlk(8gdTA1h3tUq)*vYeinoVyLHIt9o+N;-M*XJ+bZGRS zwa9V}xO0($lO@PPN$ziO5OOYvJEZIm8J+bolhV_h)jpS5nkkfc39#mX*x8N*x(YoIafBNon~F4KJL<>k^2W28WqZ zoVk_9a0Xe|rr{~~;}Cb9)LdMv)9{h1OrsM)B48r*%bFzgF&m&G;Ji<9M8e||1&^QPL+lDH1F#GjPfl<$v; zK1%fX=&6l5Co-7wby`m$g^1ei+=QED3bK!e>Mj#Wzt+xi8U5$${30Pr5flZ=)}B!N zkLmrZ8M*>KlDE(uKaZ9tgDmu#1_~_(5lb2$XZ5H5QHVMfK%f{v5;MFiaEqDDHOuo- z-CBV6w{qq4Jw@uElVnmdhQ6v2p!?+(KL0G_)+&?q{l@a?hcN3noy@+#J26I!p75J( zJiHGcce+yI5yNb1GkpddN2-rq=mqm=gT27MRJ`At2D3Mq;PjO`8 zSNdupG~PtsOJ({;io|Iz#ZQv8r5iGQi@>$CnXX$5tk=b|zK zGcRG7>{mPn6nYxzqSqa0CO{wb>6Ufo-=_jL-~XlN|Ehi{Zdc&Kdz03vmy0RE3$p@A z+CFTY+701|?RNgNv1TPn;c+Ectlac+Lsc~|QcC?zY@Y!)2K%vuB=+vd(i}626Mpp1PiRO!{g`e{@0(n(< zw$)jp5gh}9_1sYR&=mdOsEmE}Q4i>It;x+e+gtQx*jT(=Jq)GO#b`*{!F6*xX$P=)$eeNuzFY&+IC->CfMxFSOx+#bTP-B-9jd^D}z4Xz~bpG6ALH5S6 zA?`XGGEgoYUnW0q?xhN-*12BB$bA@;asSRj)?O^5xHBQy^a0BBMH$~Yvc+Pk8*$rV zi(;YS3gZto6(UV{%i-@CuW9mKW^j|Mj2WTzisgp$o@UA0gi-pd7prbw{1$a&hLXX- z2^)BoH2ebRpU<~lWkZY2u$mkn5+fB}%$@txZ{Ny$h9M}`U+7EmbySV^-QJhCBj=Eg z6rSfHW-m%b_)%*0Pvd%`Fxa0R=3@O&jzs((CM(t^>bBVZ#kDxHVoYC?gV;o2ju3X7zTL=VD5#p~$K3aAG7-`@m~x>nQO2^_9T6a7M}c!2iX z=AQw$T~oU}N7}yNc2zc1r1Ol9R+dr)zkm0Wp!84p{2IEUw;ogzPU_<=jo!BUfxIM{ zgU{3@C99=51JCYjMF-sMue`{x*NnD0Yt{{PH5md9zG@rn++JE(clVFudR-=hmT0$t zEu>2Wji78xWNpU(3<6F?jUi-`BgV0J~pvg2#({c zz}riSf*fl0*21>F=p6H?%pvZm5{=EFr^Lg4GaWm<4MemL@meIGVv9s<|<8IebtYIEMM53 zA1x%b=ntjljl+$5#Syx}5?w1YJOped1gzEn4fcOP{)_P68!+AB1dv7H8z)ftzfS_? zLMOsGK^Z`%wh&s>B>=3XG5|&0Al0_I;Jm~_04;h$xQD$7hWY(&p;E*PWphU~LnGF* z>t_Sr_bE>>QI$7B@KVL7wcs}T5XRL04VaS8!BMuWGai#0YdZIh-#$X!NxpB3fC2Q- zAWj|R-VmE%1%LW4oAEEB0R>3@M?}U>uktvHi}4xcXsWGrdj;tu%I-zlj-5f6UYY&l z^c1B?(dzr}i6tF`&R&qr$-aGCOz3yZf1(HlT21X#uSpjwdBc#PY_3$}Tnj`Z`)&3Q|I2;UTzT;@mXk^rn%6h= zG(P7GP2LYWQc+40l9xslHdkLd>!n=Fn9?Tlb3Nyv`*H-iEPk@RDPx%V>C%88Ok&<} zm-T7J@9kdMvlI?Bmoyk3ar}U{%g}4AmEDc*l?5yPcz3~gZK@#vjAnuA{*qJc^QK7r zgAIbyqO$y~A7#ks>N+8cSld)wj1|^xf?Mz%BJaekaWP`2Xf3%e&a9X>pnLa%+;tze zAi^B?$jtvn@)YBO7*&`u;vM6UuONaQ5kHD)%OBux0>N-TZJT!m66VL)@Qcy#y-pg+ zY|Ov(`$TP|u&44{9%jp02GHenT3D2SBUOdCuGD~!8i&X4IrQ1UMV^^f=cIb$m6j{p zoCC&>1xIi#GMDTy=COg*i!tUkJU(%Ztjs%-xjEpkv+28P-uOr%i@6K$3JCU0!{L3UNpTf$81+WFg0P?-d&#TI@y~e()+tBK!$Rj>7)HVH$mc)Wf%Y_pWWH=tm~xJ;CoZyS5d5 zXr6gztQKA>of4!^yT%odc1JRV2O?4E6S58>tK52U<6Z*jFCi|{5-P2$mgP=gbG19Z z|4|JO)5Lv=yNybRJWzfGI)O7O|>t3C=9^Zq@r3z%Wr zLz6eyasoN}x;kjSEA&aLq@fyg*HATdNi2~|Ec<3&ZX|)VT3e=CVJ{~olB+nY8R$wU z5SMuW4`Xiu71y$@3$I2ScXxMp0-zk% zf-Svpry0HYxEbuyxUGBGF{Ztk-k>s!ZTbo6>d~6P;4LD(_zAymSgc?Ei*u zP#&|d@2~pg;E5&JG4r&<P!>D&lADYJi`>j$11AcZ+IAL;bTOao7bThZ zb4h-*=;l(n=zvTjFbaRMW6P7|Ku&#z!;zsXA<<4nD%Q@tQ=+}Ktcb5PeV~+sEo*@Q z2W%;opUtIfLad!r{wUnA+}QUk=pBp#9};F%Bf8Q75>E1vtN0gRKjw?Fj(Cx!xJ9*_ zdT$!EM@d@oe-s>%#fs}s2!xq8P>5u{*O>GF&+zZJou#TT`1pe7k6%D=!v+xiK)6OR z7<6Tc5CFD0QBlh5w=*^)InIXhqZ#S?KI#PHrg&m$f@3#Da`u5|G9zk0Fs(0Ck&M2KlL0GAZ`)_qb z#%+vhm0nz7r5w+NX~A|La-l`0wt^@7@(*_g^K4~n z7t2`ksq=H*iceoPX!msvCNPHAw@76Bbmo|Jmm*5Cwxz~e#l#xcc7|Smh1Xd zyw4Y^XcivLUL|q6cN}N=2EoXJ`NTF*{)-yNe-aP4JnsM9FQU4~8YKfD<==N4fPpdn zLqH0%hjqMo?ua{1gDAC7e3=^d#jsEuJu~PQ|2r)GpOHJ)7;}%W!klMtE_bS#%-j|} znl|Tt;qqDi)rPOTMkFtAZP$R=ApMrj)9m8)8+fzcSF}^f`?q2*xNoAtMay#Q!I#8?P<_UF%tQTw-Sa7>T?p4E=o z9IzG}casY2(Zde0Vug7#%w zSfVM-fio{Diwf8yL$)zK|2#Sv3dvk|Ie9(`9#T-QQx&u!#v>Hw!3Nu#Er! zj=nAD3iZ5UzT=Xe`?#|(oe{3p*XDN0){|833gu>>3~Rw~J2=e1sMdFr8-_=n3qoxr z>Cx^kCic!+Pnm6y*D`;Mm*lJ`rytxjg_;Hz`;{Es3^&`bRsF&&Pk}scc^#0H6cZ|w zY%|5Xu(D_FjE{DxbaN`_-2W;z(GA;%_6SU8{h^SM9u^t=HvrUzSkI4pIpuPtpU z*G`W4Q!*{jl*_{HKyJgPJwy5%OzZSYYx89P5DtGfnK`sGCq`L>Ngb8ta)IxRk}U8U zwWoK79?d^KE+DnmmC3MVNvB|l_OQvT^WhKO1^h?~9^G84PcnC#Bs%n@42EBuwVYnJ z8K7)l&bC3c-n-?jevZ?^0axd&brgkQ-u**n7r9blo9Q?X0Rw>(5vy&iYWz8|wfBgx zmD+LMQm_rzX5<`p<$g}*N$J*JIX~q^QLV zfHBmTWZRyBW9@qQr3EEO`-^!DpC;wkslW=Z7g{l!`~@*ffgJENC7RGltAUQg?gN_z z8a=b+GJdr$Q$kl-BzlP)J!X5$b2#d~Y6u~7Y=Iqf0>$yj$mIcHVaj7`%-x3{h_T1s zn7K83OKS@?vVo0;VZUhM=qOEcFyLS!T~Y$^-VoH7L;47g++WT07B_@=K*^K8u3CpwEqV zk0NK0>XNDZuB6-X?2z%^b&RFzwUgpkq#DzzNJICq#>iQhXiWMe>`})))L2{9M=p2o z6pZar(cda<(d4dudKbudjT4Y@Yj~#h=q})MdL(|N@P?^mf^Iw@0>yIvCZ><}EYqd_ znJ$RFrtFKf2b<<56x5to|w@ADPvsnN*adTPuiv8Pk0*y1#|K@}cj4J{-N($?-zl9~RJ| zmdp>24=fC&$b9_w3_03N>hjmJjtBGK-4k|!6tg?25mM&0UR!Ic?EXyM5XjMH#~Tn3 z62`E+3{A>kgxv&J%q09(k?F<(1p=UuW(g0nCoP$QdR&eWKxuy0JaE$FSX_IOIfaCz z%TH|19e=GBt|^ns1^fzYOb^kvI4i|>BR;%Y3BAA)z3i=L6!Jw4<@V%~W9s99dBuiqVb*+i-Zj6FzpiGS-5n?WQ7J*x<7xkdd zuV3_Kkhc(gxf*pqS)WEDtU$UGGhQdPWs%XZoc?jiVu8>Zt54{wVN?n>t?ka0fIqIJ z$AGVi*q2RuSC^t&DA0_C!KR!R?zQR|+u4@-gp^5h?%F=`akJA^Pki4oy#-}8Msbbb z{MwZLvQ7%!Gj?@itgSmEyders=$Xyv*G3Ph7IROdPZG`89L9@`@2cdVgYM&oj_njk zQMJksko;)$3U*%52?MxXr5Wt|_;`t1$RYZBXVn$=#>bpIJy;a^BIz1dVE*y=?g^ZA}WMAc*lh5GRcM&Vpu`!-ynW08; z_4$SMiF*p?`1AD6>pcmu05>oK%8zINAI|kp(?C)9tA+flo&0{qOVx;k%%td$CxeoQ z0fZQp7|%6OH-ML{5qVp02fbzvAR#M&Ex>N-C&%xN$yz=(hZw3PM)d$lAIQZLW!VKE zvT-zaFEq0nEAl4)ctG4O-f#sXYIiAjT)rqsPYJ;=IqUS78nyH}xHMds1O2LD;lRM^ zLB+|=4~THGgJD@*!FQ-~4!&%z#m59%t`I`TaK|(;_#S{V879kTm@F#)lx5S>+bkv9DQJqjv_0g;y`6}lD7ApsA!*e zbqtLnRII_qI){n01QW^mpCYxBPVQ&HnZ_?sAY-rf005@t8i1r^305ief=Vm;3)TPt z4Yg8FD-CrY^P76Ll_s{$h`jZZhAJ_R3%p9vT@qg2OFzXBl-SS+?^qVj7(L20FY;v$ z)O8Z$fOqTI$CI+jNgWsgv^q?q;8M%`V_bBrfCF^P6n!)>4mbi|W{n^9Z1f16sJH0J z4A4`<*AiKc*?+<&itRO*T%lUCm$Y2n=)Fuvycue2}YuJTX`Z=dT9_z!L+24=}b(F;jS)Lyp~G z1q;gofaVGRp$7hTPcroPolB|(8Ps=Q^nZeXr2VcVF!b*bGmZ7?Ax1+e%&{uCHl)T8 zkTi0*WHt!41sK}D)AyfYQzQgT(*-ihqhFgmqafZK8arXO?J#S@e&T5%gbO8yH6dUY z26gNoL~hg47Ye{f{0R*G1+km__fH0^fY=U%&w;e6R8Mp0#8{}hMk?p-?G~tC4z?Iw zYgnvHOp=4{6X6zYD@Kzt4!&4TXo3e88fP zdP^vk*-x}FvoI#G3a0+5s?majwH`dPYt)~TX%@MtQY9P;H(QMy=0AJ*CRU+9j4!eC zkd3}>Kg=E=rdIsICm?^2^2K-JUZ2T3V}g*@%00YTS(Y-r1GbLhfU^gZyt5C#`K&T&XUR=%EDM#xts0G z0#G6V?k~>D!)>T_49>b|h^DVU3W{>)zS2b0l@}hc7DcT*`koL;cg5^=1}q|x0tsQ^ z4>%)Ux_HW9KI@Cr969cz~At>Z# zhywuGwOFN7JvXdz_dz)pwkt35`5?MW+uboc7XC(!B!;c09f=3s!uKL_oPF5Hkq2a@Qj?6BmGv)gUeD*Y4R;+Wa`UOuR1QMj);70e(w zKM(?IQujGuZTV@vQ7G(R{+|6|=3R}sJJT2ksUHK@o*mxQh3o^BZMAC2op@!hmdYg@ z&@!Jq`4i!EWnyhSPi&D=jE+Za=~rZZzv?gKV(QPeaE9k|YmVeOVxR;G$i58<==pw# z5yuNg@Cf~6MhceY(3G$HOujM-bl)JH7+lyI80ex)V00lZjx3zGiWbrBu_y2(wZ1IY zVl831kX?>{i1dUY$%4}M-hX_Mz5D?ULggP`vifysO!^2QJNr6kf&aB#&0UB^iKG8# zo+m8^YKSa0ev-))=dKd8a!6;Q5!J8P$1Qd!Xah;trq>wpq5nwL!8@L6@5-CfA^hHC zAYhux%l2KQRJIRAec?&V$5E+RChe2)kk5qQlJVU1ekQVL7wnwbXz+7uCi$G_t_i-2 ze1^kJL`5htHP_C%gm`@gQZqjsdwX>`-Xt;168(7^HnxXno&dPSD_2oA8dzD zRiAwrb}cz8qY34*Q=CN>DK+diDh{Ql_M)g!@kmmBuzBg87 z*veA!^r+UiJ;$h(WHNNVb%qmWvr}Vu@4w>nDddD<&6QK_3jbaM!TlqAjyHE%uja?ER3c2p!vJk0f6A-(kSVl(jQZSte?-6VZtM*C!;T zcI{J^unHWaONbGf`PzX<)?5`cz1mF$1hY`H()iFZ8X6lFE-Juktj=o6nrp{U1rJ9) zZOA;_xPK!ufiZ_N?Nyec#fJ@JeR|xBmdXee%t(hF)|DY8T%eUOU)P zefk7%yL{mg{7*uox*^A9#;7*+hgB)6j6+4E!6*{3c@+AvkMsG~$s@ zPO0z&Aun)TS3r`^a(4cc4b&8qFtqtFwDEttkpF52{|)BfZ!!+`-7xdKmw`_Oszc}j z_&fkO)0pk4hkuYU0p19hcOh(_qBgP^I&;CD3!;7KE2S(90tWKy&99YmlaX#5b%a~$ zPrxrWVDqKRD62G z&HJS{Tfh=Po;Hgx36Cr@Zs{9}0T(TfDF$kU!E%$#$+!JK{n)<%gE053p$)J5k-ee7 z(C25fZqB5Q2`7a&%T)Kq>jWBIg`oE@X(e`1{BhoeU=!-GJQt+MLc(OgUla$rVcI{bdr4yEjVqq{>f*@#KJm{Pl=Z!^DGfzkd*9x@F^!YzO zL$7Y!Z(~(fdaPl8cY1~zLfp?9_(BJkAwz@Qj`-E(glrI#96JSXmhzM=WvIa4p(@xY zXI=4)bJ%t|e;p%-K#AF-UNzI`lB!s^ui;hND`OEsOghR8zq2i!1Hzn!Kpb>0wOdN58@qx+c@}J+$G>N@#Y#Qws1oBp$B()CS*&p9D z(7t;wNY;9Vn0>0dW^ksudMd@4+)iIR{W|cS^3fL#VF`RH^%V(Q8G(uJDpRha!cAZP z*hl(bouT-8Zu>b)CQmMs05NfUbs{!NhmbJqsNkYkOTF#4ota}OGSzIvQw4Ro2YxKH zn?En9_reT7Cb*1=@SD7mO~k``=5+Jwj!F_YNRHxnd=2-%2t=S@@o+t^D04+{A{eT+ zD~7{{v)0o`CG)-X)mANLN@Ju^-U zcJVZ0L+D7%V7wnhDw$t~{>P{N>1D`ksk?=42LELu1hh!j|Es1}2{V=O0G=|Y$nNiD zQn0bM%8%7`zNZHf+O)5W=Hl13;f10K)B+AcLS}cH?+k<}@G~UpR!42#E2KBn1Go6v z$+YNmNl@eg_2Zfl1gSTY^oz53j75I2L+M(scZNB3vH5CM&Szr8XwmkgseaD{J?7Vc zxwr>!VMX?c^h(u+FCB!xLZF`BSI+S@KQi(s%5SY-B;jW5@UTZ+d1W!w$>1W-jSH@D zNjx82A|zC&@+UI5z5YA^5GG@21SZ?kc2GzY&C&o$0Em|Rj&)#kCM#z2QA>!Sx8vT0s>0NkC#}U!hvw>&xw9P6NO}C{=UpHM-nEBS?k~{ zqt9*+`$f^?l34u0h+0>E< ztg7Vv4Wx-VH?=s1id1(cwu1)cz3Ok_sii2Wh_4WC=xe{&mIb`Y6zaW+C>d85wT(4b zp5fI+z~?B=PsVy>&OSSebntm36#<=IxSjHg3Rft7ot4`>Pbx>VF3JS{(z2NXbFGnA zR&m3uWs@r5w~>|MZ)R_JWA9DTWt#4DTYtnfUzP43;UdkjV>-0Lv;2r4~C7!|0CxI*~xm%l>~nv({u7YqQz(r(?lWc`XBgvR<6aZFWg`D zvM`Zo9tDoIQl0yp&4W`l8rR_l!bIG178P(^9ezX@hg?teSuML{KqZ!Z^Vj= z6VVQmq#<@v#g4gwEA+mm0v4EvUvBYpLli1oB?C0+s=aV6GUWya6jyHulWx^Hnr-`2#`e=mI~?1IKbBJabHKL+xAmZ|9aL-KJWtQ}k&!uJ{vLa5x1ezMstKI@t3}_= z+>FkE`kj`ChQrq0eNxYBCp~p*QhY4Gw`+kL2+r^&=W8izS;e#g)vF&D3oo5G(!87; z>V96o{sIhzhaluu=*sd>Q4;Pu5xX(;p&H5{z9f5W|NQC-&wE^&!5z7+t9GPAN;iK%dlVLNvp($qK{ zQy#C}a^Cxyv}X#gqYph8rEaAlU)$a*9>i{HMFxER+AKs(OYHxwjd+3&o?TEWFZ+kj zHw@U4nbXsp;wBCrrXZ#&kHF97(PwFzU(teBrm8AF=o=sth`5emo}8>+b{siZ0++s9 z2G@umNY_|ZY*tm{s5an>SDNvH7Ba&#FumK}sZko5!yMmR$^4d@-;VFE{{MeV>V~bk zurH~ZmF_+>mv<0leW!CA^dra&=J+rzl;m0fBM6An<1xfzvc+){+^fA2M5_P+5TDSD zO;!1Fu51wDXrKIo`X+GN_Qb#KkUKVo7JpCBb0UrgXM7)&jrwNyqVu#L@xv%^QdNvL zR`nt}M{}*;s<#vFK5-R?l^J#_p-I8`lpcmo$fuWnjh}PPn(VVJX`1KLkHv(R${8en z&CMXa`f-k%{qcR z%N(EY4raAnANep7%K5xSCfRzFj}v>SJlD%?odM`4c;Y) zeEf2Q!F zziku`sJ<>CPquR6c3|S6Q0JD?01!rxVuC3Ra`Dy`-jOKfP$}*4Oci0g-)B48t_|C% zQFi=Uu#fG@D0h(sD0*qL&wOAY!(wdC`K0h?HAaScaZ#>$24`^g#4zLPow|fg?85mzUvmhklEWd!yvms*T zNa^}DG|iMfiLmLc5k2$c^X~WRD!kDjIA2dKi?-ZmZk662?bj6yA74d{tCd?q( zsVHPO#xBw-r+XN_rGcg~R&2AG(q{5C;p!nID!6a%9voL+Vo+AR@MTQqwny2+$d+F* z#rme!13Xz5Xplx3(z5WDDq3q3i@t*$?gDcqwzV-mEJHkP&~~K{C^Ictfcr8x|EM5C z2W_1|!M+AS4{NZ$ceCjp`-gLFpWsH|!Tv4y?~6DE@>h`}gYb?)uDIZn!amaQArIAw z8W;fe6+0lo659*R;*cMRep_7-oIn3wwqlIC%vRfk=pFWZj zcr-^ZMSeI49)(MAYS|A~WSG{DARjHuo=w5a^#Z2?*|B9u=|Fza$VnMFFy}!>{ zT8UEb%d|t>`VYJBPph`2V);5;D$#|B32qG=o{?Zs?dw4WnH7T>5M(9GZF$Qt>0|ak zeHMD&=C;0{CW@gOF2$2Tg)T@(IpwM29)2Lwa!agGf$6LvHs8jTed3g>7wzq|DxSL? zkcc+km67TJTln0grnw7SPJJ>fis}s$rE{}xEZ6%}qOm#irL2I6Wsa8-Uu!LW6zJLt zt%IF>XaBtgT^oYp+$cBJ<Mw(iiqu|+25iJk-R zUO|C0D!}@fB0SSMx;Cgn$*}|JlF8^Kd>(EbF%uJe!kw}2_^KIe*_U_?!td3(gf(}V z?aawOK2MWxcu#0tEZc`EQ6ma+ddJA*CBFoz+#95!vMHEK9(sCB6r-n@Hh=g!tgmUh z(C{T36#q%ytIM;)A5kHKyr*mqENzVCLMS^RTs%@mq+P>XOu26eghZd)3H)Y_XB$_U zu6s%OmlK=f36UM`g79$SS@T{};Kwv9SHk~f0u4GAa+C-ZwGh1q%bV^bp+mTbS{u2h zN3%8)r4I9b(Oec+kdmcM6elj5#+**X&B^`gTufATsx9+8V{$Zm993p-eSC# zK0WIY@jGehU~LA53&Lk^E}i)k@rQc0VH_>bD*dBj6^3Kv`ivk1eeohzpQ%eLY$mCX zIN=G+-APyc%!=KP4=e~q;b?0vM&Ao0j&cRi%@OSCY1qyhr1gqID z8!A8nfNYIu%3B2X2`B@r0n>Y^WQ-Hy)ENMf`13 zi<`^ob;J{tWWiAQp}O8mJ7iM9sNE&qcP}5G1O<23ahZk?np{Hk#lIF|=pG7o^x4cN z#7@38lC6cw z6@&vdC~hUoaag#=Pn4EbKpBElFXjY16(*{jq{@<7sM5~S27vWv{7Z`yJlK*=;|3*j z;WmzP%{Ll`YO^!@1L&1f2S&|+v3Y@Vz%iAeTr?`^DOKJxP5L(|KoU&FKrbl&Gx|SW zQ!DI!*z@?;P9(^Gjp1O!BvEUSJr>bWkCYE0J^SN(8xQza1vuF=+q59NCrY3g6|Nug z1QB1lpCLOrE9#yjbLE{H%avUr5q#HrY8ChSv#sq~!K-}PQMtuawkBmi*CX4i%F8H0 z(T&0sR!||w5Oy>N)ea&);tu9Y8>Y>K+7Msn;$IB|;R$Tmf*tPzfP@AeOLqXkt1%fs z1M{Rh14uzIA>PA;VE?BOe>JGTzTofn1)%T@pYy2<{%R_m6gBqL_O?Rr?m;5c*I}S$ zne7q!^!XF?OQ^`#KygDmH6-GWv|Z28imsm3)fE!TciofulXQT23@``CJ6^h}KVNY$j;Q3kp&KfO&XB9jurh2V@}9m&BFeFh*f zMlY-gAgkTZ_iH{47-)%(NL^mNFT+Q;Kl`8h`;wB#83kny{>{t#)`D)2HyyJue*TUJ%;aW6uX0z(c>s)F-&67pa3R@ zFYJS!Rt%F=*%!>+yq%1jxPhJH0E=$G1DH&IL!+lh!~nodJpjB}H6lS6Z0Wit3|Srw zS4fPxepa!%-XM~NqU@y_V!ODAj(sq_epyhd0p z(p)05zeI~}FJ7~TW;~I4OU*ufTN0{6E-an(J=-V%J%!2qH#WF{zYrpxbppU0EaKpe zfA^pS0T9Sx_+VQAef}pU`rkB{dUTvJCHFb_UesL~Z)nuZ2R26y#iDvCeRw1KI?F}_ zfTg*ZFUv}KRyv!!j|*Mok;(@?*v1c-0EBTJCPrR$!6u6pBy-vz6{r3$3?F@ygCqO9 zHF4a5?nP989))W4s-QJyHwwegNjAZxD>V5}>jJ(R0)?fpB#b|h5dSn@v>qf9v;8vw zIT4EGVTYQA(*yv*YcN4Rzyvw^Thae>E;{Z37TkwrXu;YFK6=mZ;xRhuvt2H+EHA_t zrFfK3{CX1-j#{-zfK>a63JOn=L(VeRL|0QXasglQGO-k4&OVxryq-D^c1}Rw{-&~e zG~dK~vdXYbPKKVhcL&&C_)QfuRQ2g>r+K!KnGC6Y&{tD2eus%lLqh=`>PuMYM1XdS zH0uiDWyy2`a6<6mXZh9?6Hd`9-K6B59x_7h?F5A7%wwii`+BDTbE4||Vp99%(9 znTR|XXaKvwHGjHnYuYq7^}HHToTAU?BJ_243#ng=#dTrl@zr4?&n?BMoQG_zPws?C z-EvpTKZfHM6Yw4|o{P=I`Or{r{= zgH?9bQBW21w%YEAqm*{Bi3xoq+f1lsMr4GM7e0&J%rX6J(nx30-UU+(+#9#_5##14 zW$?1QdP{e&{5;CtG2T-B=r+neAkv6I6UE)rp@y!?T{+vz+(Bpn zJ{@1TCE{L0z4;YJOC2q#G;{w&MyetzwyJwBGX`?!8b#R)LGnPXJngcV2_tRoB!@~8 zCC0itIsHONEZAG7X1Hg=@q?&isV)cRXGp&3q^h}%MEc*(Kajb3ckD5Jlb>-Qb+LYl zAM}DoEdYW>wb%azt?f{4u7c-F{}z%0GH^pNM`dkicFrsxL=86 z{$%{`pvC`#`#lRWsU-$=jzhl#)lWYH;G#7ai%9kA2T=ZTE^1c~0JlN`d6Hb}80j2+ z%*QbL-kmlf<$m@+G+}X@PBF$e!LRR%j(y)wa)&BSn*(kD{Wkn8h4d3HML|_blK8Td zB5s1v^X}6})6EBPoyg)>-=Kk94PvJ+@ujFz2zbx0h(U55eHoyQ3x6l+>i(jr?4rY( zA~vg4W1VguW-I98>DoU1tF%_Yc;o6WTbvaMF9$d3=!33S$ zMSr=h#NdOkLehBo!KMvKEG}HY&*UJAR|^g$A{kabxJwJ-xV_Ii0{TB~|G1S=q5}&u zo%|H0N5W?hsmmm`v(#m7njPXM5^^C_cl95>HwMu1-f4Zi7xrGXo@w8IHm37NjdyOU9IyzI&k$X0nzI;apwEwsSSqG+nZzXAaSbFTyH|!mJ;Z%NK_g0dsX$^5w7^^d z&;pa>Kjc+ZF8OaqNEm8VF}p~(!$^k1 z!2mOW#dzBTDE7iY!W{qNf5fm*42m$n?M;z>ui20pkZf?Xyc3Ijm&O5(!M;oGn2k{p zV;IiDrWDSi4(rjg2yXkOQ9ooucvFw$tGrWSZ55Egd|G1A5ugyk2{Z-QytyU7EIA6G zHJ|PwWkVAZ;U+P6gCfz*dt4{`S^j`mj*>CU`cBg)7X=$7{F_mA7}@vyT_pv)K4byF z>kya-qc9QvBNFyc5q<{7;+-V#*7nzH)50T=yK7crV7{$e6j5xME75n@4e=Fg?6~Kvicy`g42#cCiIpCOJf)yyh52TWRc*hIxXn-g@uLijflggb; z-Yt|Q9+X0HPRS>9m(U^eqxI$ac_fQ7H64Pc^Hg(Ek$z4UUQaf8pv}Qk_!$u1c9t89 z^#=1A0G>8=ona09h5(AB_TR(!t$p}z0Btc(W}mGiMgt0hu#@Is%MIC_IGN(?6kK4MVs z0sx4rsr4)it>F9Vk3LCYIl3quf@%f3b9R{$HmJ=LC7OP@D7t<~7dM)3fx?$qR5hAc z+P;r|S5|5s^DGQWw{d~OYWM=maEZUiOrr~>1 zp=`4{b7S|Psh%C|HMzV-bbLQjzOpVjw!oh`GS?+j9PnNvRDarA4r_T~u%77qm75== zo}eT79>Mo`Qzze8i2Ms&`I7GVi}wJ71;?7_@uhRg0b6bI#-7vI^KHx`+?c4&=@|VY zoKoa{(xNYG0Vm3E)}eQ=PG`@1{Ob*Csw26sb?2BaR`R9L=FPk5qe5()n_3j^Y_-U5 zKX6t>df1)Hd(x<>%)Lk{{bmCZYH87Xi!(>W>P(IEF5L*#fLBhC{CW0SlNnjc*V);( z$pv10vMOja4EQP6+A)*t4=akT1Stkr_LXlXxNI`ZI;!TMU?w|YYrAtAz0}1$*W_~z z9TPCpn?-!NQuT5#176Tpe>XLzHSo6CnwMGsxXJs~H-gtOxz?6_QI3a{Kkr{id>VX@ zZH%p3avndT6YHU{LiM_0yDCh{%*15fgJT-3N?oqbuO-vLzf9jM? z1BGrB_1w-FqXt~dtNnO97er16`8#)o>)oGA&FQzTpTBcS)eVJ*^VQ^h@uxZ%BCm`o zU}ub^X8TUc@9Z!Lu^Nm+PyRYpslS6e;zJzm5`#ZaO?@bJ!lnS{BM^S7i50db}OUMWhDb z-I))uP3B*sC%s-}L1&F08X5p9^#l`mu65 z`gw24YJ>KoBLuD_v37$Mhvp=Nq7)s^atVZDWIlBg>PrPAFV8%&NjN{P$J<9^n2lN`G5Y`n2Cw z64=&fzg-PNq>->&^I5um7d8oHL7^(_-6v}Za^|W(%`D~oy_kZzxaC}#Xc(rN7XrQ^?6=;}KcTtvbQRIs43)6U zL(w^oyjjD(g_3;}JbWJVWvQ&_b0UeP88%g1xnmcB1IhPMtxLSVALwc$CnPmLlYw8Q z{vu$nAcVU%7ZJUyO49zyuPf=g;m7Rl$3IAdDFF-5Albg1NA5sV@tm4X#t!_6^x7pl zO8U6-uW};G6*xDWOA0S?qQ6tS3>Lf=zTsEmcX~KPX>yEDBgjlw>U59%HIzXdYS7ha zr6<_5yP_a+_cIHO*U=j;zG+f?pM0)m*ZHw}I_zEOfI>J^#iwaw=dsUu)_lIQXyOPp z-_L;mQUI2jA{M%xZ$6|%nE^I{`voV`WXDL9jpFoBnl8vD(&wUL)x-J0@8Ev zQb}^9mk+iwYRoiuV-#)TjzP3FPKW+^DNZ~{sR ziv#`6;JuCiPiQwB1!e(&;(+i%v>mIg36{4d__Z_ zg9J5$Lzr~Bpe-LlAyY}{_X9YtIho?LT3vZgxXc*(4^Rju*fZ=23Pqv)9qru7rcT^5 zzGSWj0GwFZ*&5Lg?7w@d-xlBr>*nzA2jFM`LHe-aM5kmklf|frmfN*)lnsfevoEuvOUBhM# zfKTTnVV>kE76i!%T|Qewt67Tu@WS+gtd6ng`{6FsV5bykbKY0AM!OK5%1%8GtxdhJ zG8~`5`JG>>Wcny#xcMXALt3`!ctkBx*(K!c?(B3<-!i+y?h`UrFM4UXj*gh8uqn1o zvrN_#un@(_I7C&MC9U4@fj4HWQjopK*HmH@aq0PkCavOq33tnT9rCrl*iT2lr~-Zo zAkEI=4H04v$RB?iO|*-c;%|}KJqpx#+Mnq=N3S2`(yUp3fc$!hAb&r9Iq929`#RC< z;8E1sWlFZ2X=2;A5oIVB!gh?^4J~B%)2C!+Ec2lJ1`1tUDMfuq!Fv_h=F5j>1 zf|*n3?qx{Vg2IR8)6vb)(UiWFf@K$8T<)uR2TrC;hIS42o5crih!uCVGurJNQ9aF3 zXd$03o(HJ7_>>#iOvS(+y_H0 z6DyNu&~En7me+#lmh_3D(?LAbEkPivZDvGO45zpQ3FTh7Ws@uqv2PK~(pO0q!2Kul zt!81_6L1DML_I_kuzpQi_#IRYJAC_Bi(v(<n*Ymw40RrzeGu`XX6!0)S8+UYT33uQlvjp{rN`gmq_Pw=F01r zI&tdlQx+ry1yh`vt5yXqs{H$o(pM4o6K(WD7p_Xw~Y#XZGO@lfJ=OAxDlz zZ@s&#v}ZtK=2PeJAO9Hrbu{=) z&Hi*ZXfg{iRJSv^nix^WXc>`>h6WZjyMh_?c2EH-`aj*zdsvj>-z*K$`>zT}A!LQ> z2Uu&l8t)4YzX~^ZdOVPY(0L1gV?E|;VL)ybvh4Sh8Up;p9zzZ5-d=}@w4MqH z;Ne(az$DBO4@4?qO?9|~J}mK+t-%gD zBJ$~i8EiQrz<7ED5GM&Oge9OI?|$Zfu<&4}m*@rnHVYW|B^Y@2e}exv@P8EG@Uc^T zb&f?7D;Jo>trpN%Vt!SVd8HW^W}Bn70mk_bt36n$#L-YN1}G1Z(rnQf^}kKLFnSb3 z)lk~qmVUzKL6&xpF}L+I!1`?7AGP)>%G4>TuaV*=~Ju|qw zyIXKb2n2U`cXzj-g9UeYCwPzqhv06(T@x&50)!Bf{KGlto_Fv4?_2M#)vLR@r@QOh zRXtT(Yd@C1LBVs6M?SX8Z7WthwMjwpk&_+3s24`vYZ!Hk{}pvO7Yn(4MU_Hdj71kviK$*5;dLdMsbWMDoBzhQjy)83_cc4Spf z8mnx*4UV0d3bg1XI7uef0eH~IX_nbXWbopD1pC0408#io%L&*e5ZY2*?oK7Ykkg|$ z@EC{!B*CD@{YP;H_J)7jz%K}>x;Aa$BcUL$b3gjKQ2@|DMEJnsfg~!RB|S=e?KujV zmK9@Cskori4B^dSVCcGi&VVwU+g>n(8}y-!3N$D>IM3lus~=;U|LN5w3L~WpM#_K1b@B9AzyZ7nHOGDjRnJ zRdo3mFE@%MwzjwsOAnT10R<}@>Y6D4NJwB>!|=gr=^0z2A*SNbUP4Ylfrje6Xjr@4 zB4O%XrT{hUe+sr0%SHV^RBkvFgfvoc@LItwUkI(-i~~3*B*;g?#TU@1EVzBbBd77B z1NBFPCyGE+K}CQteTw?P*n;6?Vxh2B5vH=ZA>QbI>oj8P54izsYBk@s*+K8v+!yd+ z99LKbgDSBWOa@hO&RxM@&VHU0t+Qb1SQ<{EZr#Z84M&|;WPKjqVc=9xiC2#s=8wt} zvEY4%`P zR=a8Lvgt`Od?{+SyJCZ|12{0p0-JKFNE! zM9bDoLpHsG{)D_xcli{io>2B|^Pz=Yp#$%gKX0Fdg$R@X^lUAOoT=rA^dg} zM5JS&LMQjcfv)3Z-`R@U)E4v|$GDL>3}xFimtaUCk-yOdq2!qC^-kNaUg-5XJefNy zKQD@4`3R5r@|ns{y=Psd%(LtgZyQPTvq<}La-6Gvg_8>sWmnZvAoNn{vE0ZiMNRPo zY;{g2{3XLC{te?TWBft?ShJwp%AZKTS<>DAe>uRhl@^9r=x4jPNq7xZVkh%y5iT(~9>Ixr(Bp4~Rnr2jVk|7Cdl zpTQMuqxm>Ko!A&&;Loy74rF$gph45Yh4;H$ppDr@00)b$RbNWld{rrv>V>GbZHZW6 zUJ)&fVs5!;|CH}GG02JU`U~hzMN#FoXD@SG%&G77Uzmy>yoFV?yoJqLN}JR=M%X1Q za*%Do^IQMR@bi_{Q#^qVOrz~9ex~S5=QZoro>KzCFdJlu+0SV_YIx#?XcVtPsf!Mz zC9%V@)N(kf;;tmCYi(8ROy??uw-*A1h&2+guy4j26GNCVcrz-0^C|b-OGugsNB*c9 zkJEdJ%-vVyk<;VX2pS9Q=Q|GHL>VB%vZaS7$rc_j$z9aW>&kI=G=w2W2A0?I!lvD8Eh~Sp=K-HJV6PCxH4~c#4r!=`e1$DwA%10J&n2&hB*lG8O)!!b# zIqKE0{)$|A28t^e>XzVXVln=ZS#_ko%Y+wD>}s*am{-ewq{Hm>8KN3Iwv84NKAj@= zyA0&fY{~pF+zs(lePvRd)nLrmyi%t~^WEcnnyP?ArpT7OZ11|?f$Vl91mdCIGa+J~ z)JpWwWmHU)jvp2zBkvLk*cVdeIIfwixE=i!)LQAdW%I|BiE6mHP2PBXfRpxfm(j{r zr>!I4b$F+MB0rU5Ye`5?K$G5S!QYV{x*IV|o5^u7{P7Yeo`pZ;U@C8K3yUS9$g4n+7Ah)Th1Wi-s877kQ?4pn9Yx4 zwtK`!eLhg~D_UFrS@mJxdscKOISrX`(SBc}aXv2c2h<1r=pV z5Doe$sYHpeM=_i{PQ7QN`Ea+Vb}O#zg!GM&<%QWq)y2K$+j++)Px9u=m+ueb#u5fR z5Zk~88#q@-&MGGUFK?bpS=qh+@*1NRPiM24Lh1J`?kCjKRY{&TSW4jIpU-xv4O1ir z=EVd0(HzZ0%;^M_3V|fS3zDb@CXVnY8-sf8T^hphs)n2W_m&>nR~Qa1e7NA;pAvoZ zekCQuGQYdE0s;Fz*w`K+R!AH7f7>Q5ZJ)kd-N7hh{0N=BoQ3^OaE(7uu$J@^0a)YS z5atB|)i-ftF!{&9L@R*V!jhOV?ae;LD9h6j-jBK?-VqR2WzVMd?$4eGCGYKi*OUrc zNic{NWl4O?eOZamZDAAYoJB2c?#5ymwEUZmsw)+fjjmPnEaij_I$(ZB zk>HNJAvupNi-x@?{jVCeq_Oz-R!K!VuuPsJadLKB<|twsNRi$|7`jLgGC2@3vW1AS zk-R*D43c2D5Vvh%6^OeE~cT!S~iK% zsOh*;J@#di#n?iPsx2zZQq6GbW)sZT3h&wlA&QQAtOk4b33DEr?qkvyn7|_a^lS7_ zn8W8C?2JMzm+e0(1s}2fxe*ZYgddT&v}c>Ikw`IP+5%-lzq+X&e|6N@Pk?2z7^)z~ z!K8TboAoe)0+1qsdw7J4vD1#Qfgs1={ktM-NI?(bWwYZu*B%m6(0k;DB5s!n{pA3uw_&^~*; zlf_ix9T3V(C)V4n37y?67yW2kZiPLqBB|P)eG+PXa`{YZC@)DtB*9tAmT7tXvqP3n zQ*sU4NiRjR>dIARPLuF6M+Vd(1AY3gK?pC{K($&4tX4mU43D#A{ev&+g4gL8U5V5@Ij_z!JllwpteM8_njv|&uI{B;7 zW2^fddi#BXr1U&TTXZXqff$L0+F!CbdZ{FK)L*59Yl|=QbUUw6jkA~VM9k{;D`z)q zHRBE>ASZvT%j&^^#tBma-=`>QARDRJo&tRt4Ja3Ub5JVLGuM5q!EK$jK%wm<7L&D2 zr|AlK`-%i^92=86u%-@#ZxcC87SNV>vTO1S!k~LegK| zAnrNHUfdw_)SFAEK(T%)O+ap+O}m@HhwDiv&(GO|1(>%?W0uWRLS^v-y|+g3%W!Cc zpdnQ*mT(Gwk(O%AhgV~YsLMOZj!oK=#atKu9v7l+i-YrFjab}tAr1~?LS39dLl+F?f`Q%n^vt}9Y+muZJ6jtl(3-v#0_74 zyHpKoSJeE(^=q=B;fGAUIA4Iwnvag4REb8ggk614xk;zQwB00IxtfTH7-tTP z^Xd}x;;&FXu%Hkh-nnWDqwz*;5N8_W2RkL?s-|m+YhCWg@M%wMU@N z)PAXHp2F1)BkJcqz)iqM-|(z@tljFSIKj9KEMo;;X_BrBGwH3T zSy<;2?z&UP(b-7}aRD!j))DgZ=yAK7O?SF3$L*?0Yf*^KK7uT6ce7Cal_L-ah$X0M}T$NatgJ#^p{Frw?q1@ND@q~d1fa)MC zBx2`|g$eS*84{GKTsyd(TbFkzwvRpTYG2K5} z8a4N^#08t<5|1D{2q>h>E6lo;n(@6%xUjE)5Y|`uFzVR;wXgn}sK3j81zqrwh!k|# zI9gV0h@@}^Cwk++Q;-XU2HF7Li>7zyr{qMez9tej(mD`U^H>PEc<*w15D$DD3HKMz z4}F1xK8xU(m(?$b)o~p9A?S6{KOp9H!OZuv09AF;hdwAb@%yD?TLn9}fvDH@069$S z1Z2YiI{x3HR8YO+!0wH?<=1o{WpyNQB>?C_*PtO>c`~B_YyFQnkhn9ny_wBf#+%c% ziQ!1d3K@?8=mQ`7Em}k7Y`XycWk>3sXHJT1gY46}(@2>+a3B9b=q3(x@kgu#V1APT zSrMW{US9cEBvzW9Jorr*xFQ(1xc>s&8>UTmKFIunWP6I9xilpW6)+5`)iym4m8xtb zW}2^BjDW^+SjHj6&U(}!=?Ae?NL{C`%ok<^JeSm;w!*>L?>i}r}qho~muUm{gt8U_#mr1XAA+@poN3EldF z7v83N9+FLNFQ^j(lp*-{BJ7=Q`+apCA{)iPn0Gsu<-DwT*-`E)EE~N$dnqaLz=?v| z1i!c(jon+E#iXoI_Z9ggrAPRA1l#7OVrFCIECBvRZT@G|!_d)Dp%lRkswl6Z^Jx*{ zQ8`?8fHoFMGK{K07*&)1X!-v?vf{B>;4J^>K?vaGt@pCnj{*r>BK45A%={$Mk2+*} zofgX68=4A48Q8+IIe28oVk{1bPLEsuMzmlKlFSR5nPSn_GbQ#tpbhNXv_N zWzrs;t1DcwFTslOo9jU~$9bY5o5h!5RBZ%tsejRqyf#tR3y{9)6@mhU&?KPI#Fdb) z|8n8>2%yoM1T=}s)S+@u@V0CH2*z4f&0(Sfq+Kjm7~$Wg@85p`hYEAW4J>`I;d2 zYm`P31@ncuRPEi7}AKx@EUNzfhkK}1m7*@LuSGxdp z87=c!M4=fOH_iv&qsX;(t>`Kw@i3GV5ESS37d zCQ4*+t7I`k0<_zyDi=!KZ)yDO3ui}MJ027|P`P--PP#+agx4`i@fvq)3_*z|EcApW z-$J_j_A^p@wb66R*wSboCka_;XlYc<@D@v@JlxCuAf-PFMvb5!vpO^d~S>b&$C zS$$yYx2bPC`3*P?GbGce#Gm)x_(XGnis}$en3fZAyquIpLW%IYQ|6nKyha6boYJa{Z;&xye%*v!`P~Vc(4!K&ikq%o zMHJu-PwSxScKV8QF(;gKgC32gy18eNN`_%p!Xk|+rZCSJTxy=^+m(Ts$D+yjYd_I3 zxcPFVd)i0o;vYS)+ zn99}mNyZolC%2nh!Cq?ayyAyi`L;Jzuj0;BI`Y4$@8X^lQoZ_iJMybB{(2uj1Z_WZ z2*Ld2tVV_`B!f2La^@ueqMmLUH4ht)fFL* zWd~44X+4r*k33ZDEk_wA%>;MZe|(eL_rVmHWZ?J=^Ckx~h!sjX{uex{{qmu(@!R$; zR6dOE`xfVBi4*6H7&>i_rJbiVDDz2xeH|yDYugiXU7)fA_H&9t0+<3v5n%d&6$>Kn z@#(&w=fZk3`=w|b@2OhhnNL4vae!(NXgbh^QZpnG&CxhcsSAs2kSJ(>*v~R^iX=g* zcPKH%JM=kiEIuq1+5S|9O3}XCuJWx`)#u4M>$*!YAn_Fg%LxlFP}UyiI#cRo|)#mXQi+B}OmsKR-eD2x0Cp1s^LK$Sg0 zd_dK|I0FaxA%a`Ffm--8H+95)-A`f7hGXQ=1=&Pu1xq&p8GF^uTAGz!G9|w6Ij&;3 zJ+*`gvYcrRZnLmt?D3O%J7jzb{ab2Zlj-Jt0|N4pWID%5TiA3p04h}ak4)sBGdS=> z^v@w5yt78|)hrafBl;mAh3TO-&J>g-J3b6SDJcw9Q%gz%&`Ui@i$jV8&j)bH7_I@h z#=sBbx)UN;gKzTavxeDxIvtwgz8|M1l_!rJ18_}F@Se1pm=g6zT*3+F$(CAoMddf0 z>5J~AhA*n~nV9&5@GYTjVk)uZRFCz8alr1qBgar91i&1egg#M@2cR9h@8iUwM(#9) zz{uE#k@4Sfi-Ga(Xh8SS%w$pJ*Ve4^Pt(<|*hvtZw2v5w3HU>%vH(2VtT@gO05J(u zr;;97T&~O=;Yo^p=KB*GKkaAJ&QVW|Skf5YG#qFi5E!dUEO4)fc;!BrRL(qfQ&fKw z5umOYL)|IZaggD_KXeFhFAMC|BABg&po^|$t%|?lqmeeaw3B0@dT_6Zs@)1?A$yM) zg~DKh1ZG$S+4Os(J!)J4f+Dnt$0Hokk5{-^8s9Yz(UglNDU)Di!dNCH#eZdri~sDO z|JkD$j>7npx?K;#^GlaQ~2fQvYq$n9j)dgCk-0G~x&1SF)i7DG$qxJ2E4 zO6Fu2n-xKD(Fx`81V7rOys#XgwJ_TM;rr@=rs_cPyLT5>=nE_OH%Z()jW0MqYb}zL zK-Z|O^!fm11aU$BkW(e(e$tv35yZt;Kh4EA#6ONt+EEDjvWaK?4=fzx2H2_`27Nj? zDXpP#tY#iZD89n@#bPk39>2kVXI7EvdjIEH6IxamqC%KwpzzSfK`xZ`ChR%J#pGd` zvC?@$h$SG!{e(oEmKSS=V=%!@rbih-Y3IDJvNmJ?4u3Njm-}(<0ND?N%E;NncDY zR$#su<2{k_R|$iVFHs8N?u4-ol%FyAP<((aw1%av-<0CP$(*r8Yvo4;dBu|?>!CxHZXn=#0aDAZ@%`AuIVY|J2$0C zE24s}NYyh4fVjZ?06r8z^fM`z&>N=YmO;{YHI%~HG@s12|i1NrK?XX5wF5mtfIg5FZ_P@bg+j%1%FqllxxI3gJ}(&s^cTAye#88_B@* z4!#pbzt$3P*q$Onzyj1SDaTQ8R3y>7x5(0^#7v1-yB{TEh^knw3d6sP4k9qwfjq-M zKoFacvlli%8C-vjWB;lWwi33 z{v_T<1V;eA<<}vjF4r2$zpLQ7E_gVSXF7SaFO$H{v0Gi_ziMyxsgb?glqJKx1Yt}d zsH!iQE}o9))?;9er*+4PXPRR!a`*G3aNGM8vn;Rusb8bwy{Dfuc4%1T?A)?A`uThi zhMaYa{iR<`NoM!6I$mE!V%^KwlMl5!xgcE(;&I)R@cTppjc~KHKzztw-y$2l)E@1R{TgAke2zRp3yj`*nB6E3_54E zY}ni;7H_1izL9yZ%b9@k)Qq^7Phk}_zDSCdQS%CpbF(R}?1tO)gIQctn{8I$YyzBZ?0-dM9q zPur%E< zMnir-{-@+Wx;lqT`s<3SQ9gJMnKUdo26^=@4|S8;r&eOP({1q?JeL)){NnTb)xK3- zw9^AFE3qxb%UaowI-iOfXWbM8^FL;c=BNvi%W>tDng5ot*88x6_pDOwr+?^57{^ewU}q3s*bdy>xF8Au+}Kbw+%_ z91B3OQ1FlR6(7O*@y+OEV)u)F=M9%3fygMfE6qi3_R9;Lq6g|dW~wH}(Ru-jn8D4u zZhQ^(5{2xH+%FfGI*rx#_wdZpg?j-OuQQzjkh%7yLtTA(5pq|_z>eA~S?te8cq9xC zwypAM6B;d=+^8FUORCOU^m9zJ%=vRkZbQ*@v;?J&LN0mBd2JOLvAvHD9r!jud9*cz zczntsJy zvMy*}=oSde5ma`WnDHEzuNYR*kUboYz~eWCb9D+ouhWkCk!_<2vYk^Kx5}@ta+Iaj z)UYplC;f&OKcP8}@0Ta%(|SqLPI`gt(XcAkyx)2lGj>4vdKLot@|XO?TcYgYP*~3J zcOduZZr|09*`M&(7<;1toj0`zY)>5K>%`zYp-cmF~J>M4-*IlwLuBId~I=iC6F^znngo ztR7jb#zy1TVY-;8b!j8T3+ec;(X{oRalq>*+jz%8{4hwPhF#Ncjdr%bGEe!;Byc9G zjSZx=-sKuzA4Np^(BRBZ^s_9Js4NGkxc0)zbrirQS{B(B__q?3^LoIQqzOCF$; z8fpQ3(zoPH-j~&~zlKYy@Q%r2_uoUv0^n;?Tj1xQmmZ=l@kXN`WxI}^?QIru(%zXy zqnTnQP=UN+T6H^}S){MM4W?M=vI1#vqn(Ns8?QAi&1(^$e?kQyP07#uU`#iKuQe33 z;aotPH%gS3b4mkMH?QFZ??D$}H^Nc`78*PLD?|P_>97K_(OT6XuS3`BQ)8ab=F2a_ z((gyLAg`%eEssMHh4ni+C3p+(k`)TUelF%@M?&{DydfWT=x6mqZF1~wDcQ$9Z$4U? zJ)};2lO;h}TtUt!yA^v0A2D@%@$7e47%Z)Px~5lo5fBXO&S@T1!GF{a;xIgT0(0?A zfYTxoc%khIeu(4jJ4}S{HHlXS#$XC)ZkW^nTfwN%_+Rxh^%c)9+HVRzDO`k*f{VZ7`{XP7RZ10|17= zgck^amR!REfDGGn_?<(NpHqqUVtJ*qFk7+!3LthW81(lr=>N)${tX>gfZzE8IefJz zA=XFIt5EMAn-UF++*$9C=`}n)Hz@@;%f&)!%5hPMq@?L5bRxpxrZ4WLg|0~OP1rTX z1zCJg5fp1d1j|Cqkw@sViu9$$6l=3w@vqHSe!T$BfcUMM6_C^`dS8yr29i}fwRv-1 zR5xnVsH1hY?LTWq8UcG326Smb) zOR`9p{M;YmK6Md*na}yyc<~>)ERyykPkB>w33@7$?VWG#Yu5YdLpvO#3d`T~aiagq z6P$eUa>fgh{##3SFC^HFt2VZ-3mm$zy`Yg{z<5FlX(-CaeX%MWD1`S#XIq0pJTK`@ z^Z}YFh3{Ei!P-X_K)8L+sTvp4blTPwc-m)U9gmJoDY&Y|);xF8ZmaCkZl6943DF{X@liu=jRtIyMCi>%&vu36zwU{h_X|Z5xi=wnQPT!{LQ|bK6_z9w0vQMap z!DuSfCi}^^hZ|A(^5XLX#=TMJoutb3#aPWy(07qXP#~(TUapFlh3Y3;F>bp!310C`ty~3Iel)6 zH`exee(!}6TcR2mC!md??p#IdR&gAg%xd@>04{0okd2io-kLwye;|hWd{}@#h4t! zFDOPo`m3ypDRb(UZJi(ZrPAJC!3BS0Fm1u8;kzn~Iq6co8FQ@AxdxiWM&6Y2FoT%) z1@Dq!Z>&?Tizd;_w&TwC|3Xgh%HHgnzWSXfG@mqE?ak8V(J~#))kb^va2CuLWGASS zvn?c7BN$F=@I?1SEtl1RKDX2K)3a&*?|E1hs+k?lw7}9`y!d*fsr-%V8wa&7P9|Kv zAGEddZ*K?7GzwS8v0Vhm$9Py0k6+xEj#_!FZVB)Dxv9(=RIESq9`QBRsn#y2p?v)_ zwnmAQ0B3sqAW&`zG?C;=wq}t*{zFs>smp?f{p_7q3KOXN{LQ*0yQ!kH3k~V2$ij8i znY&W;B9-Yos3&#Xw%p#k-$xc5VPW=C%AwtdwJSFzo};Tu8{kgHIMwd=H`3S=fwLZQ zUFpMH(#(4(GuBAP3< zbe*;f_`j2S+f!pgQEMgBw$UnqZ^yVaG@p7y^9F@BH(1G>acZ7dKfoj|LJsW)A%MJ+{=D#Yzak$! za6?!3;fT%S1AaURT>P>-BKvEk>mC*ZmRap*4&Sbj?<1YaL@&k0v?OuaH(J%uiM-wa)g#rsEz^X z14J-$ZZ%Qx4_>q4vT5LjC_q|+Exdt_kg^5oD;E8F;IxVe<^JNwohwf$70-rSe-;-) zbwi10Hs>ZK`run(wXAEr@RsDj>i?VfW#Q*}bq=hrcmq3%}#k*Wpg z^|VA(I<5}Zn&?r_i!{S*(vev)Wr$`q63ZTrUyHqw*Qe_IDcrm=SjMMqTSfh%ng!DZ zK=tnpe7>;6mGp`idG+0C_$M*e_t=Rm7Qy#}tZU>DN_ExE0aNJ$>50&T$rut*whY2w zMQMzP3$hAmJ9YHr3S0`Vi!$IK4$aEpX^NM_fl)Y@hrDB>o8dA5h_?_P9G~$cgm(eL z^n{&@!lp}z%1Y3l*IR0O_4vL|R?tt{nj)2tIdPaHkX6E@$N|2V0QXlYvwC{x&;9m# z)F088uCsW3?YXprZXy6EdXud3ndpIDh4|EeOu~6 zHU0hwJrEu)#-$HFIeB=Z=LM!XptxFE^v3fPx*a+R5cEM}s9wL=Iy*9P9j2`3B7D-! zF-3`STj)?m5b06ziGIG&oEP9p{R}r>l^#znJzc+n$?XoZ{webLnR3(J_2qn!L+A*> zl?fAeN~TX{Zk;c3`Qu-Q`#l&A2Zb-G{J8D|2Fc>nXGC9GZ9@+W!5MC3KTjK!1K?X52ITh zd9GHorK$jU5-F4$>+o9+!ZCx_nz$`EldI|!r!p)BnL=FxxbXtCUbP5PtBqx z(RDm8o?&}IJITdeP*`hUlwmG|n)tSWVWO?_6XscQM)(+#OM-KH zKSgKu&K)z}VCywYln+j3fO4GGI+}|K^hNJmb0`Kq=I?2YkypR_2T>?pel2wB1b5gy zH9_*)=m~K=i(*&n$ymLF~3Y|k7B`Wdjkok1|TV=p5m%ysY%`N67j@v#k*v2>glm+oriXHWztfR=8!>`F($m|Lc+AL zel2fxsbyv*3heWRr~G_btw4lzlbO5HQjx{F zWPRh0zn#HJ)_d-+-jZ`o;1SBw)vAwFIo)_@X?c(^b*2GE?_+F9bZ%3?ltQ%g;lnec zZ*ni+BsAVAHL|)-<cT^295`sI)U6Mv zlXnRxKYi_f#@Xi9SzeG!sAw` zDHRPfHDQ^0FxueP?r767#>acD_fR4meEB*)T3Fv8TG6n-*lObiy2l-xCOXq#*S=F zOJd2}C@5a6UTAXPgV*_KEO`#U43uY|{wqi_gs!OO-R8OMkh!7-9M0 z6}ybvZ@-eA^USlJX3X#lU<};s>kU3cX{xX)p~Obb7D;)}IC`cC5kNgM z!y1bOu20pHM{r**nv$OACVA?_N6IWmk)Xi=5Lp0-+Uk8CClrc1bA^l*2tP!@K?O4I zm5?1X@2*Rx!%+mBXTpsJK3=ArmY*vFxx#TxKFt|-l7&DCa0fAp98D$9ma2+Y^fw(>%)03_b^*rbq00ApYM==sJM^EL#ZSd zx{e-q+rcn)pRe~QaTwY(E1HuAZ-FwJH!B0`GswK`200hMWGy%OCiA#IoB3ZD$rXP_K59UfQ0_>hl zJHDn)v>Hxt=;iI*dXypSVPv2FFJ%AIR7EaFxMPP&&5mX0^g{j83tu&@K@HmY^<^k? zdC@qrG7`<_6G@GrP9C#76h`D(t-bP*F)4;wG7-e{U?eBnM){p(zeJl#Jn7edMP@G~ zkS&#+eN97S)Ai{qKb)i~&GW9R(wP4Fz5cO>xi_hXhohS+B0XUyySI)aKpMf--`fVK zz!1Zn=6u=y)2#Yv8T$h=JTELLmLUg<01Gx6%?3c&0DPZde-MC(E()q4h9Jm(t)r?C z6{CBuhK|&-{uUkS@j0Z|PBk85#mx{{gQ-G+Qn8co$cMv*X57zr$>82T-cf7{B@wL% zc}spdHeMn{15dKk7pNp57|duxJwLF@^|Y# zI!KYSR~q5t82|#oBJfRw;39ef>aZf%10Xtp8=v$FONk($b%Z9H38qPd1Q1FyI-u|3 zN}j};FZ}sZ(9PqKV;D;A3Ls;2rRce)r;k(uqP?)oirediaFs%!{aMd#?M0;O^RNF5k=FZVQ2&6IKyndcT zYtqXzBORC(DkG$`evK#hV;Z4*@ji*QBN!JwOTHz;AwHCSl~2hFv7Zj9a9{>?#%~94 zuJ85S`&VW^z6knW4zALOvpiI%Ki_AH7+kJ=A3sg;AU^CqEZGi~Q>=SKJ@7_R#eF8G zCCAsNG&sNAe#JR1quwYt398hDqnF@*%fyL``qfk?wg?}?W?aP+DQ>xyP?W1TmgD&+ zd6Pw1X}-&p*XKRMy*jgb-O*85%3}svKuw-8;et4E{=y6d|kxK zLMagJ*Ihd94sLAYz)L^8WHIGGJ)D;5k*lFnO2T+a;Ui)>+D0SWZo5(0_Zxpcs?z7@ zH@J*-kN%D6a#}Btz@oUCXZ~CcgOAPpmWd$dHR9cTude~6*P-J96NdxXqB)PpIL+B7 zWuPcz$jRecI>CXDzB3-RqQ5dr0ihgIFDqI2MwI-i&%w%FKVy*C!kHHyTDVemq6z9( zgb{c7IzU1nFrt=HNzm$hA%v}H%ZYU8uk_5PN~gSI)rU!V6W!#l^O$&!?R$vTboPnd zDemSC|La}TS~C}&C3$n60G|CFte{2H*cj7W z8+s8^=BJl4+Yl(Kf+!(yFFDkWX~jFVV^O;9z5MD=5`yuw zL`^R}*;Ui}L8tAFi@mqzGFwue(?P^`%FYwDmX>ApSznqS38E*tm+-&!Vue>7aLZm4 z=hJ<^?(ET=`JGB$ei+=E&Zk6+=fVjc~`9a*LRnb|q( zX@sJ>c9x4Ddsnm{NuE^SG8hTl>AkW90ec8+adLFX&1$a4<=BBipf_741ii(C%P|0P zmYTf8#y9e9efy!z@aUvDG#4QdRMvNcx2kDqBF z5iF##3WX2)wJg~i-lCqBrRUDk=zXF5##HHEAmD`G)Vjy2ugK`yfHVkw`DxA-@fnzZ z^9qOSV3rhBF7@7XZHdH>l=Z&vQt{ameZjYz+Sr#A#@$^kZteP5&U#r~hHBBK!;W1> zCNbZe3!*&513vd+>zg^6>#t-Iqg;?xyz_#ur~sgpHWuCnN%9nq|Mkn6Adg%}wMo-6bN0vj{q~a)(*HOuqET4P1lJtE; zInCm%1+^@s#IjzP7rArdriuvT00eedyTe?j@EKi@`6W4=9f#OTc&6m*+dwt}@gU-f z9$WVMxM%*VOvNDUo#mP)M~zI{?q$T!=;-(Xc6#%tE-_(gcVh0KDZnu~W3hO?C=ktq z+0q~#Jd4KaK>J)joWMggHiv<%jp}3Lz3UNxomM3PIU7^?jO{Bc^gx4&LweTeTk3a_ zte9vKA_^g^mv&VWp1A-i1H@ObrbLA`W$oWh`S?#lM7U#ug+TuTXL3HC9z5>eFw-IJ zYlbf15kdh3bHFGKr{T!Rv3q`lr?Yf}*vb+i0)$At2BehBMi)rLx zQ>Iwje)ZQF)=BcJ{S%5PDs??65gTivXw2FkKPoO1{k{ruJ%OdAK9FB%B{My#G+kqK zs4jM6jJ=IgY$JfrJ9Ntjt5Xr9P-6xc zDu)mL3MUTZMA(@SG&r>82XU@~-?vVMqWW&B1483G9&whObBuJ>EvatFAMtfM#V#k^ zhY|bup0sijBGjVfS!Xa}oK zYfO5q!ki7-|va0ojSx!p(8*|H!QF7PDsC0n9F3sjJ#FmyidOc6?fVP}Z$3c$m` z$byA>ME`9Rc%%Zh{po%vF8bFg?22@JAp#}G^iQ%7$g}X4L3z)a#=7{st3B5Ms0EEj z2W|rc704YDIt~SpqjU-5Wb4CTh$TonjYz#l%)d~C7t{px`SDmTjkPs@CtG@s+!5}6kug3eTFvEE&=y4~P=_b8b~SC1@3t%)1>uI{ zHefG3n3{^;Wg#KaW&xG}B0m)NIiU=SSpz&_OUD#a5t5^bbuj!e2fOIM8Cy`>A0yH~ z)B9&RB}Xm;TktrPeC~!IK2`!H-3N0`X-~gS?ak!!n3baQlrr}-*{I)e+pY1^y$T{ z1p2+${{06{>$zlnT;qNyyj-dU0A(1RW`y}(#X zPE>8!2tV|>mXm~4OlW=NI{-ms0%L5pjT2FHH5OGhilMG51oTm8i{@H1eTXXTN0q%W z{XZR)JtTNHq9C<}x2JDg^tuoRtRhgYwv1M>Edh97OMP6y4RHsb?q6KGZ4aCIeti}Z z+Deim$+?6_X_==o(${PZ=JFF&H+P{b;Bv-)D|%5^R0h-3ELgBWoe!Z&yyzzGZ2X4b zIFzyO;IN2 z>VJtuHZA8A4YXj?gVXB+DhSYcLTQPKjJHL1{U!!16lX}hErtYFMYxb zdHp39daNQ)jC>X+(SQ){8KIu?CJqB{wl~_kqpl4Zx4)He@5tyDW%1$(O( zy#M~c6tn78MR25>ZY&kvaIrH$A}R?)V!$3GU*2Q2`8Sy%d&-oEfwEP7!;JeKVENjc zSE7POlmjdLEr#jel<3cHZ9wga6oq^fp)8X1r8G+gG7 zQ=fCDG&7`H&Sw73v2zTUy9=R6$a^0h#u18B~$WUT$#BALX4%26Q-&3sc=XAK~>fA7|O3RH}+kn`zpoSx_)eCa)}9g!`3XHZdCD-w@z_8W`Y5M z$revohpU6Jc>wlc=w6dzXj+r;m$&JJ)8G4^ez3cFD9 z;&QUx(oJ{pkay5pTb?S&X){{cPiyz|ds9*{d{hD#+I6^d1gIi3oCp{O+lM3QmP2$l z)y1{6IYm(^B;s^8r!R5qti!SBjwe%-BX$oTK~3qO#=Mjyk1Yh`Ci;e_ik#M9@Qy<3{q zFw%n70`~VlqS-x+&wrDQ;y+P)BXMSi>e~<4Y2O{^*9|AqYzF6r@uMfZQ)C?y&}8DT zC)bnzjDznHljGB*7HD4C{MlFOMEIusZc)aH=;?}CuyW9mpV=^53NOH8_UGDjEXM4C zwZH_0SZPfn%f+lKIywJ$?-H4``X{G76?iLesYEcelI0r#FWWT6#|2=kg}x zS64o#i$d2GAT|c zMXBi8MLfw~u;&EV4CJtXWeG>Gobgkc&Wd#jw+85!O%zVO*#%nCah!=c3r313h+rgns|0J&IT} zp18F5sAFKr$U^pXdu^bLZ`wLAs#~k$Xx7=^I=F<8PmkJjaLlf4fk9s`#usp$LZBN& zL%CsBC5rD3a-(R=-49svP6(2u7XSqTc0nDNB8+{JLxTtg<@7=Yb2WDm4})el3UExp zE05D5ZEYQhhq0c!<1&P{8jZLrK0(-Px6)|cN&`XVKKWnyhje-kAP4<}wf=f7%63fI z??VTx6W2wd(%gPD@x=J}WGyPAJI{7ddcI4DXc_C6e;|=Cf(sgnXzQso3W#|6m(%(^ z<^p_d=gkmfd}+8=GiJceK}*4Wt>%{1@gNfH!5#s6-kbFXzF?NM6cRALb(|RG*W0$} zz4_Zd7P|M+1NE7S0DhhX|BxzS3i#vA0021uAjv)y_DR=|h_h(+cqu6%K_!}YdfS?^ zXY_BHz*y#=sQM2Hn++b;7tO+B?Y8-mO&36v3&$=RUGJ>gS260;MG75qAV<@uFDME`fbb%a3SPSAaw$x%u)lW%``cWfi^I zXY(vy;e~FDmdg`e?1s)^S2DZ3%RU_p4CWv`G|RkmSKHV;);7U>PP1S+A8h(BL@ez9 zfh5DFi=3rF#WB}Xg)hDX?aQw$;)Ww;J5MLW3<%b=lf9%W5l&6o%zsI~vS5`JGuubE zUiBpAY$tCj_0kgrW4WG2SR&YH9O-Jiy7y>5lfpDN}UdvFFM!=~!x5a3B zOYnSB-ggJGLsYZu=*;4kDKDH3F1mJ4LkMi}?Hpw?=%+KqYrO^L?jqzppp^k!ql|BuoX&=mQas!5cML92Xfz6l~MnGl=OGDMG-mN9J5=<6VJt03}t6` zSeCEghwDQ>J(CnpMU^x-}Wiprlwn+GG9M7P_&* zx;<;EgI?tWt1=*@;nTs_hT(%xSlT~-JuO0OB+sXTLavg1!y}%?j{_{4RKxTNN&2^Q zUuC-$bBq=4FkHw$gON*y=i0W39|v`8sR0|Qu8sP*>!12aX~#Y?FoS?w>}%zWK%*qT z`E4Q?G%8c487--sf)qfSFEo_g4o0g0`2gZUKtj6bhnhC924kjY>_+-9tTEse^U3^# zMWLNWj^JBek2hErYN+Uz;R8)-GdG#TfCjk2wbb{J54^Sp_BVJtSD2PfSSGU&`b&ao zHz48^DzpxH0D2THxjkkU*I^&bSs?{7;;>wB`5zZ7YDIqeL#|W^10fM}{DjctCzehW z7j!eF_ilFea9JRPL2AJ^Ps6uwyBm!eY+W{`A|7u;$vJ#Rgif$;cq+%M6BhX<`IVO- zz$oNXC3u?WGx7UD{{JBq4!Rd0JkjSp1+-1`2i3_Ayz#9YJdBTV@pP&O1mzDS)ZiTS zQW_Z4=%2JhKYcj0Q*e#DEH=tbOQ6R^C*@-C^7+j|sv^VQZZ4ZYi7LW#{^>ywp?f&n zmv6+aJ$sJ|#xRFs#%)^)qdBsATH~cNK&p_0<0tx9@kKkY3SYvaEr}ngr#+-5EIEKz zP(zXNyOWe=6v$LB4sSVaTCFPKVUOrm86MAUjdJWz@&m1bJc`Z&{A1VhCHciX&ses$ zgUchkjWV#Iz5jZ0vUtgjHz%##KrRE*l;Wln3s^28IJpa8RF)zy07 zIGH@;Nq*yd=9$8Mh)KqL3tRqzFL$CnyH^Lt_jnEV_M|d~7dXaX z{xPCe7l5bD_@2C*PIClqgn%?cKk9G*i(dFN~!=u+iZiJr>`G%xwC#?E&Xsubq zlplL4@$sI?FTPOl(y%h}StF1oTt84%I7F60%K>WyR#*SRU*gN8g;yAEXxFX{&kPpu z=j|-4B5Im558-5^RZ|&6P`)D{!>&=;3&Bt4c%cl*Bs$M_fZ-V-AanLFbOHU3_L=R` z81M07Kayv~oowAiQj!pi4mfK_gcXCQ#R5}?lx*__M8$L21d zvpG3cSFG+3uM9|D#W0zMSfk5IqWC?Whms({O~W- z7o{_4!PXQ>^~MOF2ShBc?13DOrm@gHcK7xy*p=SK6)Gzw0F}n8I|hywol58(@UfWM$P*uQeeHIQd*@Y0#sOu*0D_9e>=q5mlJ>6OW&sLgHcAVl>K3Da#k z(Z>fK1sX`uL}Fkg!nIz0df?Niw&e-9!-B5u&LHR)s{EijiVa9fhZBBm@vXg8!HSxZn3g5vu1Bg98W*&n0dkp0=iFzZGo@5t z&KM{?bAQyC8dBl}*f||>_{I>qeL~-s^fkw5w~|Uy+7Ju2&f`ftBo6p; zZ(1alsCK6Xrk&=$gL5HzC}6ZqS^Yt3{|v3(3+P-k;YN%gd0(J zMpdTvVQfxu%CN>wk+NbrCCy@9$S@MBc>?BiPa>0${sdj(tx$$F3T#UY!hcWgM4b;) z-7zlcz8rd`HaJv2#gH*qWG`af3*s#P$nD@Ipt=G1;Y;4(9=(Qs;Y9sh@n5q%fp}Jl zEI(_`h9%7eLz?F_sh9VU`b2GS(ZYmOda%y@XeA%>WA_N+U?IL%$_K^3eo+U8c^dxz zjTjP_ejUL*Ni4f6xK(?+HudC+96uO|ixJK#Tbb)TP6ERp|B*PqgVjj2)Sr5S(7c+$ zY;9%dFFF>-m2IGy<%#dM6z~@Zshw(X71FFRV519AIq5Kjxlhz@w($25?6Z?ze__pkCH`}Y~gsCzx5OMe_AJGNt zwN^>D_T{~;aFha{8GOtH?vO6Lux6!-Dn@rt%{G0(NFV79oorjK>W>_QB1*g}j$GVt zVK>oRl4a({s~?KbAL7L_)@IYrIE;DCAa?tgO4-|CJne1f5G`M`9+a*ChzN9fpGI5QejorREx?NAm<(otz#|^lBWsvO zCaNPRF?#v^fnf^hcKAu5KJFiI8aN^5MLa@&H9Jr{jpACS9qR6b$maR_7FO5ZEJ!ES zbhXA|S1OA+jPgKU2`0QlO+x@4rZYF~K!U7+??|0vi+I>y7pZ(n&Z%R#266)M+cU@m z7MKieRE=E>r9AuA!f*r?){?NAXZVkXUa1xms@23bRL{L#yO!z3J%A6kn_vY@9=t@e zupO?ohNmm26o?$D`^L*`@EdW%)Axl#BT*&l3MM%rI+@aeB)C)#s zZFWSIL!$pB=YM}=*JHt;5^C=KE@=CejSUkb&!0Z%qk0}T18>yM?&?r*8jo}lBZ?%5 zn!?(tJSi^e%UW`Kk8N@b@5NX@mW3}zD>FRlSNNRTwRO8fyS|jF4q(Q`T$>}@@BqqU z><$=njGRNaaEA zQ}EXlA>}y76l;gCR;*%^qy^n7K>i0OLDNc@Vh4fsj~$2MZ6m~#O8y=Y_&^v#wCtjw zEiU0Z;G$(y37-a}V3_5#6;h|c__eWeBtWBLpR>h?I%>i1?Pv+7zx z^ULN#ue7klnE&un`VLUmOl)Cein8*_XpH}G2O^zUuh|2HIkj%Q z#x}9_82$V15%8j)FI9@mieE8&O_yo{2(l5Ao^m*YCZPVWX(d>6#Bs%9kq*zKAyD7-)vHcOd z$oV9I*oZ-=UX==ds;Cjmk-*f=tX$aFcT=+O=iSGXKAUyhNw~^Qr<00?0`mB3?x9 z^52mEk6wQRwLMhQ*GFp~<)q|9d5Ip}TgzntK4O9Zp)&{rP5MBbrQkAC(s~35LWay< zeO=jNtyv#~3Es$5l8WQCYp%GJHn~Ope_2jA2y|G^2vUi%#{9-E2-1pGKv=*pQ3QnJ z3qIe=FroN8rQK5JE;?r1NnFI+pSUmG`0sngrpAW6A-bO{2|h~=p+4VMM;3H9nX_b5 zbEx~1$ z%AT{{8i$-JQEpmvuSXStyR$|-ysJBf>e9P(YO_Hbj?zcNg2UGrr6L}8kv3#{Av4M5 zxUiqPp+QwD6Xphf=T)y%4pz@;jiSm6v_U7oRb$6wY8Il0X)vJ21F;zGI3KuNW`&0P zE>FnWGbB25?<00~&5=k~R`t+9La2wl=sQ|ZH^o|}U-`Vt90&)Fj6s5&yN z=uG!pd5cP{9s>p7J?Rb=J73Yxy?Uxn&niD5vWiW*57}Ficm}_sp$>;b+kVYqRha~t zrsGpTUBIWym0zAFvjKABfpx{}-#GClV<|8TrD~bu1^W(($P@Fw{iVWOT2SuO!rBhH zvJ6ZyY#=kJqkY2rbTzu@`{2&gP#6Wzc8RqSKyd)4T_cp??1avXxovXcTSJl*?s4iO zp*0J;qrbsOgDI6rZZ_0_-3=?I)RYA0fDOs=pmb;L%PoC^dn!+WGGY-|oQ}_E$e~7# zc+a?QRxpkH_H&arw4!+@Vdp#w>JL89$N+VR$?YpB9qjWYEB$IFno%nA)02*!8F$f? zkFGKF3ouo#LToAt9LHMJz=aa+wZymO>eLn9dAAq`<%81%bRb&{x&oY^Eq@$&5_v_o z%8Z#F)Y%$wk7_v$5De-s8|v0d+w4}NUO%nqc*TNf`{!l_CM+b{Z;jW&-6+8mG-r9) zz+Xsn1XGbxiFQj9%J{<8l=*B%>Sk?PaQJk`6=BiZ9*lxPV2j$3TjwxC>^OaYtPD@w zk||m6Sc0L#5enw_6KW#=v*IA?-asRCzu*>o@V&3B>TJgk>GXFuq?Z#F9bozm2-Q|& z@ol=B3q5D0k+&;|Li}Z(``)fBM0?TT(G=C>4G)a=BGI}O=U2*UGuA_t{`Bi^Ufw*_ zj=M%cesjquUqU9r9RSP|vu+K~Xw_p8nNxpVnoI+Csyqe-N=p-K(Bo6dsX6B3+kger z&F-h{>-=7bH^Zu;OTWJev$>2G!9nzmL?X4t= zu_QOaz(HuPGF6~jrxMDcEE(|{yr2}s0?Odx+PC?Be%92oh$&?Q#Z0&GpFi=$=bF%k zy6mo4XV4~wO(U$E51A@B(OfitHH`!je?*qQNQ)O2D6BJNOl}{HdAS5=fc+MU7FA6* zn+9&v{*zOG#Fc6WtO9J(i$*uGn4Z5g@eA(0^3IRb&DEaQ+ERpk$F3?RW=D)G6WKhL z5;OnKq4}G}2P=sE1w3EQ*3GE+7$MHc$w%SWYVNqFGmI~1r|D7 zYN5?Ktw?lWq34t5t!=j=4-*S|s1wtn@pYE2h=ejj9FY!)xTlhqY*ei|2_g8ne?Z777ALus0=x8sYm( z(5-GAMdpF1-Oyx*@{%7+7h1$^cdM&(^`vXuCmINo>96@WB4cVfIW4Nh(QO^DShZKf z5ckfVUy%!i@GlTEr-(=V5s3q|-*VvB6p;4nk2!*v6+^=~LF zjtacqAGqM({A%+(s@ime?aO(_4?37!N+#>|2e>JelIp+KALLI;)#0f}L&T3#yeKZ0 zQ(!5bN_Zil#TdZB;lEAsS&JTguy253Y5cJQ?9-#fyPH<|mGUF*(*WmL!q{j!g4T;& zdby-ugoP=rh8gr{?<$??>&u*#bn6EkdJ`L6gH2k#Ob-b;}&@>YzLjY^t(Ne0#dy15S@^t zTSv#gj=z5gQNd6(b28uzHOv$g)K*D8@p2+@zB?+Jk6F}0>E6Kv3>ZJ!v?7l#N+;wk z&G5mH;Dw5PRl$2?dWHfYt)!@X*{=dNw+hgqjcfZ&^eqfzOr)CC2A6nqNQwpzAzq)5$5Z({F-QRAsPSx-O?EScmhUA zNZRp$E?%Bmc3n&QOG-IlMpYyWw?Yxow4rg0B@cu>ZZ}7zs=f%IjLw!(4 zzJL(lK8w2egHn@7a%C`Bvu_w=9QPYk}rW5;v~6)yeBtSLwTg)e13OPIaRKaSa@)}oNS*Xsz0PVm-|$EWIPJZC!E-(sC`yV=Ivhq z9QpqTM+EAp7HcZ?7RGhejuGjN%Ka?I2o#*PtCE-puU~bxt%ISpZ6{g+`iVW(*L~To zuvgOtD-?VZFh1tLpQ-H7($kM^d9qx^s~{KV)@~rO(#Xn!E>fC*}pZq_81f!znOc}>%LpyGB}2U5bD4`}u$c}?(NVL_SWVK!De z(sEhfL>h^_>Tcv*V=L9j+GhCI(vI<|B{-9~JxVPkEpDJmiS(&%BeJZ?>u~2&(za+2 z0ZLo=3nUos`1~T`Z*5`l=p|oiA-zQ$07+m-*f%^R(G($|IAl09!=;9&`w0`KH&z{B z+&-+E8k(DV^98T>Skhr8G~X_%>$lkS3zU>MJN9nx(>b|!%}a5MZoF+>asI}k&o4kl z%Ch8M93<07Mn~@1E099uC(uh&JSjY{MCpX08FBW|vsmEPYT|*mN}%Bm?(jx^fO6*{ zdvl!R0K)A5oA3EMXbR>H_P4JhBwYN??{J?WoF(5An0}x90#RVXn#2Y5M;q4J^y>Q8 zj~sc#J^j1QOe%sbi#3$c&K>>3;v*|fAkI%8Gz#d&mf4CRE*D3zG`>#65n0O#jZxMW z3^hD6PYXekYInIEF4+&Cs4U=4~g3T?fWtkDAMBwIlEq(6=h%5!!6Sj(K?x zP3`%Cu&RTlbO4SqZy&|E3~}}tWHqrkS;au@y)e;8ML_*$TGtEbrzL`1PXe3yJNyNc zQs9s0GH+)1r=UH z3n%E0X;98D90y5R0m)e~LEy)qa&YUOMDHx70!JDsop+=F3T8As$vjU16C;JY6MPP; z4~p|s%5kujPCm_AqgsOKYqC;Sm^ZF_m=0)=9WSl2UM?LVKxr;+r!lQ}1JGV8$$zid zQY@UW|1tp*fdJ=R%>RI}%HBjbG0SeL5(7-US|7Iv%iKK~tFfMFNBk0E1&_HYAQ0hy ztBXeQHo`adsJD6e9&E25qJT$e2{K86gV%=}Ff~W%6e@eJiKxe;E2HX}0^815trT_z z7Hsc~p=cHwy9SXZ;#yQ$ccoVIm#L0Yjl##b!wKZ&8Sm z+JnFU4@Q=hR^M}=uiURF5B+tv%3c6fl##`L4Z4f@;6nND-D3RruDGq-(Uf_=2Z;ru zF~-EzOdLgzhmuz}E6w=Rp196O=ZG_x~@;Ls|?kmhjmM}2#q zl3f)p#8)XZQ}uhuNuu(Y=|~yThS&4|I+{ISl`>DlN|@C)B$&kAT{g9>kPq>s8VbC| zG%;oeus1I+N)~`&;~etBUtoNs6I^<&IFbJcWgelvHGqcDcILCfs}kY5h}hK3o)!%F zauFz2GYFcJ>u@b|&+w32Gsf#2bi?`IvNSC+ukar#`xG4#ZrOL$99SkkxLzj~>`X{b zwfnD1RT=XB^{9(uKL)k!^iM)#y7O`GD#spC(jS~6CPYvj;~u6_fD1YSqRF}y;na88 zXJ$$)E*ZA8FV9wPi`~H!*!m0>N$TEr{@MPcP8)#E^DvCOVw3N6)zRCpQfl4tH=!Ov z`Iws1Ko?!-^xCUEa})dWk*n4lT=u7T>7g|a5)WzTPox(3uA`$v8Dq52@L`s>)wB7s zFAb<{i6cHApWK@I4`4!^$~0-LLIg5DFG@xSRFg=;_$_Sj*_6Fg3T40H2+t{zX$}X; z$kqm0@eIjEhHauQ@roup^a$0Az(HArARc(OW$P}tD9DYjc7Y%v974=lv zMcJ=C9vVuFg z-!J&M5PcIGp4@l2#Bb2y4%~Sj#cb0MHvWvK*Zb#tZDs z(Z*BgygePRzM+iSsKxBVNY0k~E||rC{~B3OA518_U3T=+&Qt{`$IjvY2zMT&BORd4H1Aa zc9LS~OJp0ck2srB2yb<;cmSYwX5qIz5-d6yRE}oz^Nj8gF2zI@a_gYsNopkUl6+j^ zqaiIEu;%}*Br{uo96@N~|F|lWWRvsns~dNlAPIE!1W|Qz^TVXv3$pkiG+|u+OYK{r z=0!T)440x>_AtpPi!5_bU80vfCbqyrqNBr9*Kc@38)xDstz$kuU^BomuOG^{&BQg* zBl9U?6CX5MU=bWM!_97MiwDRY9rJsbip?K)>DTcF?gUuwS~Y`~ z^&YbRubCae6H~9oQYtoS9ynDt5k?TtR*l~@5=P&YfuGKkohiOE0ITb4FuaQ~{~(Ki zokxa7R(xw;CcNcX?(TOM4F8B21p;;CXO8xWI7+cYI?DTj^0_Xi&}$0o*&EVFKHF`| zR$+2O#fX*HRMfrvyF~nI>_^QiZMc}qr$Zz(48)u$1^V>f%*XE-WS2(E@OT$&KB+r!b(s&s`Fstk~o zPGN*t*D{fbX2)$`SB{A^OKu(z-SiF(B;qhiHp}?(Z2|bD>jiY0h-&k3D1S>@slH;u zE6Fyn#VC9J0{kj5|L8BXmqXYqy-#>mI|D&@$lbvR$;(;cl7B|4M^iqqzs1=!E^p5} zRCrqW;;Bdi7A-7`uvAc<;>^5tXM-pHrKkDrsmll;#-c6&3{yZjsXW75rKd&X3y`zO?>l;Qn3@xb^2Y(eZntBf|0&!^yI`sCXEf|VOceAO7jX59d-E~0ADo+ljg zB@S+BEhUr1SV oIL%MYcu?U=k$n)hQ#FOtk9i-Of1r}roKF-X+^33d>W0g9(=-U z)vBDmQs^DB@(X3KHf0XbMMwWO+0SBYif}qXU@jvQpY6|^#(SQ(vgrQ`UM_#u(U!`* zB>p?zut+i9^6r>`@Bx3ukxxq@w6yhh3En}-O+}0!gRp&%zS*t>RC`OQgJZ|bTfw`UX#H}6o#gZ*E zoYzTgD3)|33NQSnxp3n9Ab{JYDZq`te{d1-D3Y*B*hTGUYZ@ zCZ*np$i|LBu>1MrFkY9E{K?nYnQ`sf4Wq^DjxuN#{@+meCm;p6&hS~hl+DenA}M4^ z(;Hi&USoQE8)KO=*Q&|ypB_umfkHTDak;w#Z1`sW)2?3p=!&wSY$Ty(xG2`cexgoF zeHX_2ssDL}RUst#pOmeh$#9rX*sJQHq1*sr{e1DdJipiW$~GY6YQ#=+^Iy1%5*SWk zZLu1Hmp-UPq(wXOn|lT9tm(7%pyr~{?<`K#=R=urOD1n=l~(ju-WbrlBADTJ{}3Zg zLG|dn$RbsDSZ0_R)Vup@U6#dJVJflds0mRuT>Og}0w_r7P{)J{1Y@ZO+JliJ`oN-X zW&3q8)iMxTE+baXhAZ1VQlR9`)>5kV?b`W;ez(<;#*xvt{27dnq9pD(C~Si@J1ktd|noNXVD`DjW%y|=)1aZfkqQn)6qaAUsO+B^5i6KUzw2Rj|L-t9vi z$2aa;OQL$^StAm?Yqfd9o{)x)s^mS37U%0yAvg2GlQ z>T^SP65f9njHOJ|*nAlLN^D%@c?W)EIqvmc%PRSBt+34<>cirC#|ZIQPD=b1z*l#T z=i&cs6$Xa{&p@$INC^zDaZ0=pgrfUk5=RG$)~SszQIt$D8xsG`xNPvEMxj$0 zmZmL@>-YNW1ffmg*+1SeS~|t{!iDeNJdZ8F2H*-7Nq3a)lITcT4M=&zqE4E-;G&IR+^$mtK8FWuY4S4ihT2q`xf^pEn)kMIrQmSl3H_z!Y zhWk4eKAtZqz}xr@;=R!c9H5ZcuLEe{C57p#Grjl?xoxZQ&G8ilJC*g`RXWOehK9K; z?81&pCz(1-29qt7lbrQ7K9BD$1S}W4lrrx@F)(TOnD#zy`aKrnpt(tKwSfuIO8Tvz zc!Uj^VOI!{7pL7;-3nE}_bs%=(r^r2$8j4jK_UYZ#{F>uG%$Dn1IDic8|4)x6)Wc= z?9V#;?Q8{!rxEd>9(Y1tz%R-Edh`yt*0bk7EyaIZ;2iX=1!Mnk*>zhmDh3eAq6YUI zS5DDEk>Zf^YO{?-=v2N-4XUw1Sb*`#dy;38^My4ka!ILuSd0e`>@1+UTD1q{7oiS~ z25MI+MGdSAFt|}$l|sp9W*j70cTA37FFXRS?>=Ojc$a%?$*CNI`Nlr0K^NqU9q(%H70{3?(Dit)*;my!Ixe%#_i)0} z!9~I@JATsyYk&!pNE0&&lBq6)UGn0PQVKg3#D(0#pvmyNssGABN-#KnM3VybcHDBay;tVdT8sp0fq=27RM=?R@9_*~zUb>2 z4ql2r27kIk=HWi>8zT44Ly7tm09ajZP7C%?DK`O-A+!UIZC%M+n(X!IuXl2 zf*>-G?VvBgpSJ-Vr85N9&Y|$YzqF$3iL|M)M2JLN<(~C?jF@1Uw3}4#wTdPg! zAB){(QU*T!FdE-;u=Ai8lMV2I0oZaVX#du1u-$H;kX1(q55O^|5<|+f&}Nos~Op}G@vhDI3Sd-3&8%+55m&jd|_?Z~5*s z&Y+-Bsy*^nLzgT36Q_|$h52J4O$bBtF!lEKdWrqdgx$?zG#?Ay+{?1yYo7(E-`M;n z0R=CQBg&z`ELla=xt1FH5hkCqG=!Y=ez#N;P$p4r8~I0;<=DNZ9oI(*WFFr$O%K`K zY;(p2bmOkfwittPOHEYi$VP(ZnC0&9Tnb%XBK6g_l-az5xn1LV;YzRa-r)m^r>|o# z0HU;-;mH%EjEYAeQoqPt?JmS|k0ypA4?Eh&ZqN~vX_#Q}FN&ff%W?*&=hb$)Wf6UN9w8|B5COY&~CLPm8C?+}pS^iG9bJwnO zD}dVNmrY%IU5ZK>^kcCcVMJFgk>m;n8)iBp!!{vcdgAf1V4$981({A1U*Dkte)mkq zAMFbDCoF^t_ozzrCHU+Td&{E?*cqd?&Z>zUttsm@tiZ^ri-S*j3NPNdUqXx zIK{vxp{wChuzq^H1Y}1Y}s{GRr`6jqcx` zxxZ+1tNKbviY;Fe6a6%|<_^d=NJvv|Lt7P=nhc|&x41Jt{#86JMOq8lw8)%?RQpFx zquYpd`CDNuZ?7(EBUO827~XGhW{mWZG(uP!tF2+z+S@$vtOZYJcD}cl&)*u_(8+Nb zE@~o#R0N|%mpnw=i<|4z+Y4cfLW|6(M-{;H9yZyxeMiAWm@Cvi&qz4tQ?pLNiV9+7 zs_m@3KCaG6JU9Y53{Lm{i3(!28gsUmw9T4E#6j3jC9S{kVgH!Vau@|1?goc;L@bHKHQr4OVFhol?+dAr91&?V+_8C|MK%^?s4!u?J zgxEAhf8z`_#ifaS7)ltS#dpMH0k8iR)+UWx!CtH(8m3Lj)H6jUh$ z@n`ik$ePc@yo)BBn!UxQ8%EldTp06f@|f>q9N*?@a;i%=xOT3rTtj=2INFiKl4?F< zKV+m{GPOIIuLeQ8-I{GE)$)fcxn|5KWkKREi5J-7>M~so?Sfc#r@X_rvQEg`)~Nzk z<^m=5s1-6!Ws?Sta7M62Up{|j&w9?7MU>3j63+XXprfRkeBZ3AXc-!D;BOwbw_70&BvQ&u{L%t$1-IJQ3?IBF`A@ zheGeHo+{yQUuZ0~`%_++i#E$nbWNXb35HV${{M|xxQ*wJADsw&G7*g$BPJMDg-yJi z=U3XFD@f6pn#4H$Ifq%7CzKCqoSE*ruuGyv6L_g%@sL1D5DmOaJ1CAhzA;2ep3pS2 z+V)e;#Pq3NE+SZ4T*+}9jD$p03u+lG9_tdWiAeFujnbK>ae zk!iK~mpGLjC=EgBO(8k zu|<(XK;pIjB!_N1gMR=_buF%wL79D>B9F{{z7O}l?6cM4d2LxT>HB3gt4>0X* z&#cXmD%5fxL8wF*?t;}^j%{U20}$WYjQ6+ccSJZDo(dhMh7POgu@7i%nI3J5oa5ih z^SXjA$ksOptoZ^jtQn>`Ayscaoet3;h)SC3-A6)Gq*Q{ch1KWK-;i3xHL&%J ze(KZT`Xv9kl@G+6EU+bO_-AGANUj0rsP-&RY*R^}u{qMM;Z`W=iHUK1zbzzT%M!-^ zsPGfrU<*M&=R+WUK=xK~4#hXD8#D`1ktM@9uV=rIOdjO&ogQ_a+|d0GVL%J0a!X24 zKY3)VgUP+7i+HUfv)f8s*sjOYs1aQHYd=taqS(3(D#6ZJ#L9_R2>W{vGqtsQ35?vk z#wI7^n|Vvk=Cf&p1;XL^1d~>98BLjh`4e;H^ty&}lyF+v`ti1mg_}eTb&hz~ITr&9 zHgCg!W|j;E2<)$Vb+SN6DG{%4_pw#BR1M3j+|EI8 zIb(H$nuKqhm;JXM?)-3zGI9nB`!!HA{nl86j&8%zD#@vuS%l^l_Gp73MG0^!31uTv zTjYFgvV$hZ)b9YgH`(|tCm-TDU@^{cZ1`PUxO2B*M5wkH?P5wg z%C+!qkMrfa+Xunf$q-=P$H#zgWH>MPzL7bUP2hG{E8h}D`c0mIrZF=EvvsIf)C+1= zm<{9pdflBo17{Jmx~rsc_22b3m8Qgle6fKhTiv_gf`YZxp`#}%1M`D89$aBptPM>X zs{sXiJ{s`d^95_fwln3wB8^Woh{fIl9;gs-3Gp{l46Zn?z>x~jR0g43b@xwH)+>ngYaw9zy5{2063oDUgkE5Hc# zaJS6+;NASDJq1acDE_4o>em9BHKeA#B+NgGpEj=ocxOzzQjeG$jAlgFZA@3t$-c zPRo62C|#Wu;hi@+zE(-#3+bju)3Hf?D)ERFxLx$bF zZd=FqoCNe`qQ%wUAx&ZR4?ev6Hfs0jL|5lCelDCj4@SvW4X;dIR9@v+e`p^Y!ipQY z1eGfqB7$P^mc?yw`J4pD_Pv^cpNzu7C1*7(u8X6ss_Ex1l^|pv>{UXKd|6Ij>b|?b ze7M4!))PaGt9ftl#lm#Ea{4GAKkG09B*&bsybLtqJ@l{FyB>Qs4EM@-w1R5$mEz8L ztVIiX)2ebp;@!nNe{kk8xw+aSPT!4Loh^|Quw)Mc32@vr<|Je`Mwr%GBV~olQ>La{=Ty>ku9PAL?3NV?V7!q$U_sbz9T&SnvQR+zszfvx-_2&1#kEY6iFa zPZb*erUX=em`vFRrmcO6EYZru4}*%unptgPrg5S;I%CLe`bXRwQQ`)0awQ!du-5s7 zr8ohadHCib%c5Exm{g|?GWp2AJtT)ANB`!VKNWe{S;l)Ae>XI>$5|0Rxm{QXoS;}? z$u+cYz`za(^siBYfH3fdq>;T+1#MnbPJ75hh(2Vt17EK9nLD^eTF;yg#{&^O_bf2e3Ys68XH!Fnt>M7V;Qc{fNVAlE~8$&Y$_9w<8T!_;MXS(>Mt zLinCq2m-O~8ogd+I#btGH_}@2yF8YCT8jNmeGgg`Y_K`A=YzUEId z`R?zi{4l}qm1W{8JCG+4IA`uQ9>Belz{JPD^GD2j|M_H?CO&13q!M}i5uUot`x0J% zG;$M;vn7HU`kPN1F1{X{T(*x74gCdFPPMf9Dk$zZ>Im%lrf<&AqbW7HMZI8betaz> ziULkpC_z;}HRGlm(9;47uK`sYZLYTPSGBeU3DYy^8J6qHct4{Z4;B)8c|KO52pkEH z8@eTCM$#~n%5MlsSX(9V=kVZS9h<@Xdo>+}OyNu=+u*Pnu-ILQo-qI;N2_)Fr74Dhj$%fS3c}9bE*QTL*XEA+_2x4Yp+n!8;Ztb@$MmQnHp-1tUnoY2Y z4`UwoFe<&W14Wa-OICZelG+BUPK)ME)p^gw++s7i)HOWflmMf>_$0&9*HkU8eWko8!z^dqDzLgL1iKZvcA*G-)Cx`s@qlwA3-1NU2JX zY8bAQ_O6JZnO+!rdJW1ww;ouq3DYbqi3gPu4NumM$sTwrN+5E#t2u&>6(}uSg8LFZ z73cmgb}&URsCd5?V>1g;7A}X9Iqd|cb5d9fe0||xrVV~EK#4$pu!eT7S`?P2ZybSD zF#_YJ#lxXdJU6MBOuU>Wc<-Wt|4(k(U3L*9ab#*(B;LJ-j>{-5&H65(&acHeL&Q08 z!35S40Vcd#lD|oiJd|h)$AKArqsHo_rNQ-Dx%Xj)EwsResI`K(Rw)SLGQ%8z$C+x- zyfUxd#{v=7NmG3x&EpP3vTQmdd9%cLa2mN>+D_wr#Wu!dA_VBS*kT0Q$5ttR|E7t?UdA%v z_ykp9{;VowMCPdQyv|etmfIH`l3ul2>n|9QdA45J4d+LauSsEr?BD|1i*>JY0vAYd z(}>gCo!huaQ&L_U)hDW$*rYY5kqZ)(_SWtN5T02_SYYwX>ST%Nmm@UBla%q>*D(ASMOGB=WDURP>Uw<9?@dWYSROpGLO$_WM031oY z%JuIt7$c51it1FUPq6}>|A^e(2+HPQF1rn5as^+(my%Ee-*O0&vX?n8?ALz*QgsTx z8MlhuO1Ca;iRz{CZHD7)^TG?V$h1Aa2Oe2TT5IRNV+pz|2Fh1QV87gk{bC~|G@P)a zI4D#Y)9WdRuI#sGs`IKpAm!{C!< zhzON#-Oc?q%mVKKuUT8m<$;Vdc$a_3)I}27NC(si|EZkM=rNO*n?zA=N93Q z2npMMr8K#n;ooxWb>+o7~2%THy9q3(pfXws%aW_}Bf z|9sM^;e~H2V4K9l5DLC8gl5VyNg54Xsc7mcXk=Vwic1d^|xI6T) zVpRvoylbTJeB5~c|LX}(j2E#e`7gWNoR+_yWOgID)}$`O&-%Y>7Y}D* z`75~Q-@)CL8BBq;?Yy~OB7N7r1C^gce-X?A6!~I_8=N6@UsF#|r#xh(77&8@Jk+ag zWcB*!@Q!JvvbrAOQsGZK(h2F6{JiSV)I4O3i+4yZ`I)mvTel=YbhK!UPKeI-6;oPe zwrHphTHVR$v$Q9pj)wi?FC!$a-{0j26H%1}Y2;q7PVYMBce(!eGjU*Xvua^vBHP>^ zKM2)R9nOL?`8X$( zjC*#5dI8uX#x$+@?OeOt9=9ygF`Xq{eeo9}h!9rYFX-=5zZ3$y2&pKtqk}}SF78*5 z?#uwX7B5<^>e}8uRZuJ$_^pTYBO7#z3%4EEJA791q14Cz;iSfE_CPn-c}{u>YrThk zk@<|eDUe$pp*Rhzox-IUY=Z|34`{d`Y?cBw83GN!r<=FOUip^YRN;mKh-8mgo#iSy z@Eh0%v%|(0yew{p6^HGi$tL`*(k#OnzgY%%bGMqSC2wj4e|(A4qb{LA&f{=4dHE+n zRosT&Cx{qIVy9+E&7)|}10oqAD);FeRBZ~G$=48GYs&=oLTvZXICR`DB_HX;$N$h_ z1H#=+46G&zeb*w3_#k4&h$?*1=@CXcgf)W5fnU_5JQp%5Tp93j_BCkZf(C^GHZ3=E zGgO+B6qhv~$k=TQPfQ^u_+zddxM)W`KklUG>Zf74_WK6&C;3oL=y8nCJYZA4X*j4S zsezbeOKv8WU=KKq6>upWA|1QISMIIR%!olykx93Zdy?2pFN1QBlh5AuKER&9*yDFm z5;ninw#OtS#blGH^q^|8Us~-Y@o^yAr6gOQ$ndabVMv?R*HSntdDhTkUOB5~1aPH$ zAqM`#ZWEMLx?VNV30%|(%IoG_ZbET4W32DSufc;vlr|5vbt2ioh?)(-Qz6ieS?--o z1KULD0a>Qr329`;tX1!E!1c#0>%g)udPjYWtw+D1Av{y5gDx|bjn!Mj%Psr5Dys)R ze#doyWrO5=JrYw&HDF%&?~1$tFSW9lg6Q*AwQH!fE|I_LYXlpv5wJzP)UcC)*i|C` zxCYI4s|Ou9X!X*2{!X;t5)!T#&i6pww1^2&VIg&;`ekj2?K)ESM;0jYiLOKlvOqqB zTE#^g2U*_IQL#$p7)BJd%L%!O%O0b?`%zj570TKI-hXE~JAwtFoDVYc!#^QS+Y}ZR zV^8JOzlq>awZk&Vl)xQpJZVg)^5W-qYmgE-K}qO9!0gGt#M!dsaMIH2kKNQYpp0d- z$icUl;I0cYZalQFqF*Xzs1+FXftm;QA&?wyB_M*>*88qqDTP{eQC1vPxxP2>@uxFZ zq_%{d@2sm1G`wr~p7r52HRA{N!qB{nr+>N5iS;erfPjWhI6^vNbu zE>75vNay<=1i{F~pqetp2U>ZalC_Ozzu7!CK>MiUz(Y8JBT6d!BaQmM>Dw-`iDe>#FO$Ccm>({ejW0U_wX~>C6UPY62iW)|gb%9o%vz<;0;^DW zcuuCDGJyn(a!T>9sm6MO<;tPz=v+wQ!Af$$8I-Hgm85>%aD4oDV!Q) zw$saMO)@_<*;cTYp&hDQECsTcdmWPD2#?WQyn=6t z*t+4D2RCbIvx{+Al+P5v_!-GAN;0mb{&S1%)cU7RI&CxI@QHM#zABr3d*@jncn`8R za58OE$AI}3P}D$3Rw;TzoGmm5ja`lXEPSvS2J$%XESsclZR6j7e9vn=qK#;TL_4`f z#=PWa$mjo}V~<*7=hTih^d$!kf>6)F)JPBMEAa4u1~@u4^au8W28MOfQO3mLgasWN zfCtd~0JBGDm<;Js%;Z6x7d!CtZM7RCH<>o)0yBM_uJrYG>zvfx=Q^8*KhTEJ2{yjZ z9jShUqPQPv?`CtsspXVE{)SKW=HD+tnGGV4rHPAk=27JbS^}_qyg4F7W1_+N=PCrfO(?=(TcQx#7er67nj*4U! zjq)1)uTcZa!1PAyF(lnapf`;=qj;4sso2gC@K9>_9w&c^Pw3HU;RZDrz#K7CVVT+*A&RaA*jkSXTtXalxj^#q!2y6auGcw+~nSjSnLQ|;uCqC#e8 znLx`poj~dyi3<`XsF)L!_Xf;9Dt2Vnuy{#sxY}d5!EP3=B5x#Qk#Rc1i`zOy)LG-1 z{IZwMha&^-R0{WGftm=gX(&2ZBtY%FsqpZ!Hz;LJ1}!X5QL%PE+tcShv~?YU0zWYW z*AHE>x<{$ZXglBhc=#LNsDHQ`kkJ_ToJq!RPzIy&rDJrM6EV!>d;5qKOuu}kKI`Ws z6`zn=-vUP0q9>dJSuWucV2>YK4+hzO06QS{_;6S>xSrVp+WO7E37tbdZl25NTp9^e z@f+XvMRv;6#+iN71_@vjlo|b^nrBml74$&{`^$-Awz<0MT$6#h zO`+52UFp(*3_!rQQ=|?Mq~F88eup!i}e>;CiG2EH6Uf>1Ts2 z%G@V;O2Wx!n?X&E3mMQYoMB^}9SGG62!?JTj@6b}0-brO=D>AexJ?X7e6=g` zyjTte>yJXg1$81X7~co_qjBD4NU@QJwU%FbHOFF#8YimGD3Ft*7G#ymJdwbd4d^Fe5^QfrY;S!ngxw_!k?+QaZe;0vvugSv@Witv zPCmFVtz2~tIb52;i8v60JYGT+y#ht=^}G*%aTbv(z;b52IlYSMnndMgjMh6Np-BSe zpGis(tH&H(mwoLvsHUAUSO6O>aPf>3)eaR4gJ+%;D_Q10e&}uOvEg?CR3#a{ zU%>?An2$9r+H46pcRS^K9uKckXw_neX^EpxG7yz;`(v9iI@?G3MwsS?f|M$pD132E zqxY6BEUN)~ZaPcfh-Gwv1>jei7erY1qKmRNm>e}zso-0y-^`A8O4bw5GOR<%O-Le_ zZr-!!ayi>h7xT=WVKBv7K9XWeU@BgkqRu4wVUp`bHjZtN`fo?!(HZg2RoQ@j*O0B}P~ zWw=hX4!T0@|EdiHvol6uZeNQO166DbY>8xa=fKAj{Q|qLkHhaS_ERb(+A6uD=jYm+ z12YZ3;1oJy{eg!A+#{CeBmDQ+KM(F=+C5$_!IUOka(nDq3LDo4=Ab<66TTpQ%M-M% z=eToP7S*2*Y4Cd_UW|Gao?JaK68M;>Ry-guOJ8&_)5V$ zDeq7NqM}^fgnr5(EUNR_|9TJqlF=@84AaS*ea5Jh$Q2JXTFwM2QR5y6n3T0S#pq%q z$B~=UCzMyE{6_%sB#Ua~pKThg~50E^xN2c z>wt0MIqD&FfdekA&$B+GqG2$%ghB7J*8uqG0__6}#Z3tFGii$}FrcxC!xpAb_Mzml zl+H93W*D#T#dqr0dc@tg(Qn}TXbG9GPcK{ds^o=(m&kx>qHu60Nx8}2Nz(gLrzM53 zllxz=e*J6?ro9@mS4!Q=0t@dBoOg!w%B)zC!QMCbK6G_Byv`k_!WE3Plu@N4l6L8V zuxTq&MTTTn<*7IFE#fG1tQzEvR`$>oL!l#Dl&?M^B=ed7UjjRb5Dv#?328>bNjV!L z+mYs^q({$dGs!dtssgIrIrT1{_4B%9sTjt8`9*#zg^M31gud(*!Q-xP%JzLNAoL-; z_|X1hv9|Znt(aV9^2F;>83Lo1Y86HH?D9J|r(Y|c;Y8-jUYMkp3Yx}gDILnuhY;5jj7ytJZrGY~x{G{a#n zy>jK8paiCNvNn=l-SkY*TRII+tEGpM02e5Q+xWX!(4Oi{jG%3>R)UDrZ-B%1?f2(C zo)_r9Yec`a8hisxhao;Jg!kUuvCU26RI`8R53-XPb=0`X#7)!l)}+K8GfbS1e9u>_)acV(DKgFHZEU9$XVIu6t2ziDsa=f+oQ_fvIYsVfvPswjfSWdp8)Id zywg-^#rp95=Sh#lCDlGwsUm(i15l-eHoya7s_tun8sbv1A|z&w$_5oI7Y5HGP%y;x zeuRzmjhESa;}I(Ci7YcDO*Yq-w#-dpZ(HeQLD^%$Gcz?B%=#FoK4~R5%279il4JA# z92T67rMuAFn;I(qdKS;Q=jx3_>K11Ci6BGjx*K<#iztA>zv0#62-mCxxpCW$EuvbO zc0Av7Ub!)~x&qS_28QL*S$_kf)MXC_OwMHywt*i%)Qw8f(KRCH?^@_anarh;8jpA| zKt*aFuvg5I)0TJ?LgXg6R2u=GY>O&at00thSg(;U z>>^qPQLY2|{V|33&V5JTWngQMsBo4sds&Cs6-G<7#CAB*)oa<8{}eDwFik^0>amBF z;1>BZE^zYd9ke(Zqd9Q~PsTO+2o%D!u=7}rw1bFLv7d_9T(E7Pl1A!$KQjLubSmKx zvr%M=-W08l}h88P~4XW-tjDmcuLKC2DBxV_#{;Jt@U=U`5FLkSrdj{B*9q8s}4n_Ot^2jjuUCV2$Y;b zj(>-Lo^RkAgR}#FGI)9@9>DNz$-#F_C2ZVNyXtUh9RMEbLk&FFL~w!J-Ad%m=KT`E!I`vp$@z&Co z=+KUs$(N#{AfHt-P4cKks|lHZzQqU_1a@8Z*I+Y@153HqrK2ks3-)pttkG}{+vU_5 z6N{Jg*?;Hr9vlwoYZnL~op1zQM$2Vw+4LS@;0 zVP%>iL!Q9-v0XxOwR=}9Fz$5ZG;yCv5TzRR99D93L@!SPKVVN0n7&iY^`?LSCbP!+-<;tan<9Oa5(WvB^D{*^zRefLKcxFc9e ziJD=IU}^3Gl`ClUW<-(K44n%OjjMEXqju%---6P5FGpKI1K9`!2uXF3A45oo!h25d zs3btp#JjdR+0{qjdVAEi^}uWb;p85wM8-;CNsJhtPc=O-9$;Bq0&8zzk=d&f%J7;U z6ob_#VJ5d*A&B7VRtfJ}<5bU5lqrGk{V_y9nE5J?4JEWSd42U09siqFbS*7dhv2?{ZK~H6&57-aBfJ zpL2xQOxqi-@N9C}_AytxH|ZcFxXaKDx53_@aqM@u0X=FyLe1cqt+mq~;)B5If5(}X z-ISi1S?D zL*kKt0>b#}Ko=JvR_3j~SdvS+Ojc!!mmBLue30Zru9KCf#tu`SD2CAci-0UFdnxil$#nxdYDr_nphqdbUpih2DGw@(KYxITMJwvP{^u$G<*G~b#2DzmMeHy8KE<0Y;@B3M=Nkjw&CbsW zBNTGPyd;r0!Xh6;Cge4KmWma}4JX?lx(P~Fnp;@i;AHKViBz(+dY1$v16R%@CS|8B zorJzyONcPo8DmhY7e<(6YZ9M~m5yJ`0D)O_BpB`h)a}kLS)HEQw=w7rDv;mOsUJ$Z z4GVv0ESz=cbqHRK!@LaQG(k~Ts~qXxneilt{>?FgyXUKN6k9BtDrkMQFSrIP{jD1Q z8II3Wl>|zOln9M`%Fo$SiDykbLb-54!uO_j+;5j%X6Hwy+l(Vjx2H~?vi@%l)6x2; zRvQ93Fs1ql+=u%RV5zFFm z%LB<`o$%Fzv?vb4GFMk7xsA}@NTpmV5BzIlw zDxAHI<;D8;hmAdi!b@f1kP~QG$30UKwTN{&Klo|AcJj>fVpt8d3eTklQqGfsk@#Au zPWx;D=0xRs%A|mm`BrG>M+k$EBKb@?0aXawA2ThM^2d`c>gQvk-D^oPi>gn3Cvt`^ z8Rfh0=!?4`Vg!sq ze~K)<(rOCgyzy1#3W5zDsi!4B10|!VU3dckBDZ)r)mn4>GX3!1DC-=$ly3Ln=QBUY zr{dZVxsI86FR3l9I$xXr1whzmCUTBTVCNNYKzpNdF;1D&XD<&3NLxQFjvPmP%X9Dh zSL%01m)waMIBoJY(574z?$&M7l-qBU=(zeq!5n>OE|#os5Ox9a5s>GYYRec3=9J#O)4&2#5;`^ttXrKhY)k=%nK2T`)i#Y);Uu8fRdI?m@6lT<_~w2;h_G zjt`vt3AgAqQT6Y4W1ReW9j7B;UX9@YU6?eBdIk;pX{VlOaho4HUnP&tQU5B>`c920 zVxSbH;xy(q$=7I7aSP3+T+h$JO4iWf?A|hM&~m=K!;4thF!#SUp2jZ;N5E}Edlqrr zBI0_&^(N^bn@HCA6WI=_W>7iG)1C)^ z2iA1Jz!5IEF01Ksrf>qifwjHa=DL4ybOv&z$x(6|F!KCd;-Kj~nNX|Ko%S?Nl!zF; zS+^zWsWJ35P_T+5>z0-yJzpVet_`ny#kCYF<|?YLzzAuD82TBf?kD@m7LbQpRna@| zEr(Hc5qj$ouZfWf`X_;DW^;@_>}Cv!AGc5>f>M~hROx>8MT^=f#T?bw2`T&x^7hhi z7~Zx{K>X#cyusleR^FSm=ATgNA=HMwLb}m63T34Ac!q?Th`!H(`%0q%b>83g*G%rS zMWGo<`RffhQl~5OzAl{ABIA1?mJCKA*zXaT1j0~zxnJh%oD^c;+9u-CQk%g9FzbJ3 z2w>oaG)`$-*vV|$JY_`5-D5(@IT&|z3i`Jx@o#LcKo5euZ|mI zsug{ejgK_b7<6Y~+Dfxq{#Sa;CQT6u03?lbwBZ~+S_MI+M^Ty@td4|EHgDCMx~0mI zBvK>CjJk|CiY~Hl2x|__DVFwv*ABUz$MOCc$=keqqLLxG}YGOyk`M3Zqt^&u=Pt z0D^7#fy)hfMM3M^#d&kQ&C>t#^a+=k5VZvIXAq5h0#n z>V`IFNWV_Qo}}ThhQrS;8{5ZkG_$zuJeLN1tQC5;B*H6%0ah;44yhaSl{XJ^-_v67 zy=<)+a~+GBj;CYb<=w~%9#w5#8MF?_u-=Bl2zU(?JHtGb#jKzK(vyRwXQm7wbV_je zW&W2lhMbT3V%_iX?$>RWR=T-N7rP{`j;a0bpj>#cdM+rh8(L^cn*`GEz^OR2d%-!q7vU=4D#FZXOlw4uQ)MpsluGrww&GoUCglbkg zJP_xVHyQ9W-HAJ{vfuoHHS=iB?YX>g?5l8E8uQ09KrTrIt}zz$42CNwPjTY!u8})=2gDh;bB+;GmzmbJRS;w?5_DVgmQgw&d;mL1s5 z=7m|CbWwCO{bnG@XB=y;T7@WlWH zAJ?SJwspU-9IM3WddQkgbqLS`A&r;+8b7xY!6 zMOjd(r6Mdq+eFxT=GHyVB8ksYqjAIT zRtq#R;9&cWBx>-dR?ID~QX;MGOZ+?hw%CLrIdsR(kCn)iPuAOAt#xQvJx`q8rNv$V zWfIPukq_iC-ptld4XmF2%CgO6 zDjJ-b8eu-*ul0G#g?qpfscG8ODz8hZohha ze@>V=9bCa@hkwZOzW_hf`^yv0Ug(`6-cD5Dtg@o0N;&)NRRE*J`|fHunFdK6AVic% zah|ONNYv;tU-uxQ7VyF)l-7Yho{O9`DZz7f5o@GI@jwYI$*^-QquLg`0xT{DQR;7}s@0j|8H-7sB@A|v1a!w{9QJMb##tSPvqsf0u-_N@U4c`IL(Xs6LF{pYUXa@4| zwwc`dwSZh?TJ6XZS?@tiMj4Ip%}L1Ss94udSvUECb<3^6ehxq(CNw7Xl0!hOjzOE< zcrZJi0MQZ(p}6tSvj+Uu|G8dT-flA(IrieAR(6vu;wWmGF8IXxzPYoL2DshW@1^Zw ziPsor#MMxj+}Uh;2;dJ>|(v#P+64xm15eWE#o1eMtHwI|t9Xo#qIZxZ_R(@%|AX-3X( z*0$l?rIQyM*GAqF$?wpEs=H8=MWuQk>yPG}B$4cXZwMWwHCg<);)ojZe7!9#in6@c ze7D9n5FFL?F(XtBH4I?_1HTy?gB+~XL5U$7K9lW4twh6WUX^p5UYOmrq$e>S^|2a< zs{rnh$Z_cQgGpJdvHewT#N_NMuHkfQ$YIJVu@BW~R12Po(81*{fuE5hS7KU!;Y@IK zV5Gz|q3$j=>!qHH4I`}(X!BJri7F(?U}^lfI$qe+~3Cc8=!6{KCnbs3&fx|PB2 zMGGs*tcb-82ER90HknkFDYTd`fgN(rJTuK! z(9||Oi^VUgOLco$;H3|m(%4QaGVpA{f?FS)BOKKtJQGxWgnz3ypJGmicwCJ9Qoz+F@vqo;%ARonb4zuTM%B6ucC4=6LrSXFnKO$#q ziwrw!tRaYQsk>ojE=aiIC~*iObB`S_53B4So0q%CzA zzf(~BuqnyD;^47M-ztlFUFUv7x~1lp?^&21=-Ixs7Ip;|hz}!2W%jCpf7duC4!^6D zIr==wf~$q=7!a*ThdsZfQv>m)hP2I;LL~9%eVLZwnFbNk%B8xrtd@%-m*jx{I|)sB z2IL~Py_eAnhc*oOSf$E4ZeJqB52n^5%gCVSB~xO@BnQ+ORn+huXdooH#BsP8PTD@% zK_Y|2b?`|Mf#}(#cR+4m6OaNa1HJ_q;x;c%@+|2*AgMBNK*-)Ax}7_L0qn$#(93y4 zXggslLs%fVmG9IIp~~3OO`{-VB>FMqdB$n>*6V}Lowr6D?XHp8 zx;0^m{&!^?JtNMOZ%Y+^%jd9y7ZWSc&J3kV?bjkMi!}Tu{$rn>pT;ID%%q02|3@D; zat++^>#1ssG>_i1FE2YxS2J*)ULzwy*|TSy=ldjHRz4|xjgv})1xzsFZ@}7j79bLZ zEy*8sU*%xN3cJD>J~2qf{<#|?81pnZ1jeoYJV_bzx~iL2zlF75`hghFwmpbLrQ|&q z9=Ua-2BPjPt!riW$x|pdJS!{?J;gcHTguQYB%m;6UIL2|i_W5Fuj)$!9v5+SE>2e5 zZaQ}pEnfd(@Z4e_IfcVo$aKQ4%eVCEgx(_-T-8sjLuG?o)@|{hI%JgnvrfL8&}Np{ zkR>M#EBXUypPjGXunX?taWhS!kR8X>w0z!2kSy$fbwt{{h7*`>Z^La&Ku|HVf(=%O%Nv zAP{wvo9jIAPtk1_Bb_fP)&J9ox?zt9cbaDibaSaMkHQ?!Og#qRp>eM|w8`uDHFslh?yD@}RXurMyCGo+ovrSV=3lV0A)o z=_eS0H)ZCahtr$+)`d1a3uzfSEQ?`eW!jgQJT;DPOV=_t2fcRClI=LuQA+Vp$E<3C-#itX zQea0{v1P|yTvE0C$PaABHxPkwObhOQYRmUqHKSiA%c-iI4y}F&QavR!A4lQ^=}(SW zAQJoFi^7e!I3=PJDo2VeODXya^nMCGFKqcN#RtO9Kw*@)^2;Gu)}fkX?YwG$!x!-&gNz`eE2(nNN|tHyY)} zZPqL$c@mxcwD(f`R=52j(f99v10pCwxN-tr9JdPd*Go74s6q;%bvC9LHr{9By+H@c zTBwCsSL}IP^FLI#Mz(MVfm|2d7|i8b=aqhq{yu^m4cA~36H?MC_As%Z2xRr~T>pX~ zzNf>5)AnHJjs9#{lRlH_mnVGz-Y5Y9$7(&AfN~1tHB!`J{xm4)=cRHKc}7qVhr8&( z$408o5u+2;zl>AylA?mJb{yqSD_IN3EZT+oibNNK+Ey-y#~|0thtvy*X}$0ZHv@14 zHPH=gVH!Y$D?G{?KWJ*W)R|vl)T*i}syi-AO^~+*I0k2&w&R9lulU&Yo7d?Kgw2gW zLS{%~bIlR#DzU3$0!!P(miuDQhB#(G*2o(is zeeuU~wir{eO{%fw;xXaowXZAW{o1G{L0A9f{^kOXfm%4IYh`{l`ezz*dZ`}Xs7T@Z zV*vFUCGSce4H`i|M&8VCEY*YYu9tw!f(5qyCbR3vDWqz{cZy_fV~%_vH5>dKOCKEt zkH34>%WN1&u&g8L#T@uE{4D2Z0v+?%aDjFCY1GL|@fXu(<)t(za5TZp(}{vEXvXc$ zIPNBz{V{^(E6se4xp031OxJsR)cexvDW_ijQQ@2AGyrQWAE0!y=RA;dvvh)mRSZe4 zS|hYNcOE#h8DQrIOE;t{Md}HB-vHsnw_+z+!^X9*NbJv~%VoK%|L5bDYsc(VQvFwT zD^LXAv>}&jHS#N=DT$!)pS%HYP$$`XW?YLQS%YZu~q&5_a_sOC(yYzbXxYG3u`Na%M6ffcWIEdx0Gu2f)85 zfCn1lpR;zkwGYhtRbA1p5BIb=oRvss5T_h$Ji7m3l87)Q;6ODTw?jHHHPM*i$g2i< zmlt5Mxp=IY;6TFcUQ~}2oHOAWrV=X=a1G#aGlnp*HQj^!AnvFcED79Yjbb>(yfcl<7dNUy5}jMm!TZsbIFwldV{MsLPFhr10z9gUHih98d_X z8PdmcCA%9=$Xi|Q36rp__F!L3+%lr2X+yu)?f3)`6$4%puQRfj*wr@mQ9NZF!_{*j zY$9i5Cf0O5Zu5W2b$U1tBUf?P3s-UXlR+!A2y-Fqp(zHmpN)6g7!SL_wc4 zeig3K?Gw}>9-l54FTRVcUu+vLlN2*Dv`>ZDREkAwErTBS96-2l$}hjf)BEJZx<%*y z&U5{CvwC(~L>^U+-9D`dHC6mLz_hy9Im<%1yV&u+x(=J2n{l z0ra`x)=z0{XL`y3xQ?mR%;$3_4ekxo4MM+6$d@BB*}$pp(F_it)gidSgIf|XOUki9 z1_j^k*~#i~6^3svCzI6PmtF7i2<%f>-273f}g8lj_#j-obcg@5>|C_s)fkovzP=_SzT5V301UURmf zcrLgtMExl4rMI0ZmxE<<3cG>HL~!`A9B#IuUQ|%EKRQu+uikixA^|z`O6KLq*W>vW zIC)ufvYG)j0nCu%v;^j`kDug|eh);SW0b3sJ0$zuJQZjJCPP_cVRA#slI1VhtS?IJ)yfuG--sg5i~QJH9DRd@ZJ9LJi#8_+Y_t zA9GXLSNI$FVJ#I5iPNznU_Ut|RKEV=D56fEPq>DtrQnfid8Z-~zT$+d_3=VDdu)by z?f;|%>v2Ep`1GrZm&L^gt_Rh8%(XoM9Dp_{I?GH<<=F?1OUq}cm^^*;8Eht(0ww!B z*w#;`%NMfS7&_ikqQf%bc=(^OK;2C6h=Te`&PZ_2YWB5JU41fNa1}i>9nd;DP^?W(T}9PVU3o zqy%KDi$kweD6_{|mYJaMN_bL9N^@`;$mYygzyvd@ln&7#F^ev(Ih#@iTA}gz4z9Qv za~uV>)|02(wA0X>ir+HMnI-HI=k7L&RB$ydt%x}mxlqm|DZ{)%a}oN5HVBG&Q<`2D zZAd%PLBSS;N=Q)s$=@{kVh#{^w8JEKx*1-8xl++P(Y=&d+|`dhEk-hMNGMP=zwR7s zr*m}&eCvz1FB}LfO`3z`QBojW`im)8F(=R&<(sS9y~%&lTH?R-AVKsKl77o|h3i`O zYtXd`Lg5=qO(x5gJ&65lt$NE^e16n@Pva95ss| zlHVLWaq%jk*aPp&yjXO>zKk%ua|>IE#By7^0gI?me*co@>&Ao-Go>cGoNP((6Tr91^0Pb2ATJV!#MFAqayluV)sOryZ3>_9idMIGWVT){_7 zruT~JP4h&tR!b^9Hq5&JpI~nq>kPf*61V$V0EGOej{NTdz9B$X>wAr;at%*Civ@0 zv+fbZmGxF~`os^|JH~Lv_+z-j7>q4j-uUILoAFVZoB@XYszG-v(!4NU>9Rit{)my+ zJu+g?z7wLC-da3d`le7z%M5!O<9P-jxA+PO*_`UE9!0C3_a=O+*jy{Y zV1lL!y-kavQ#mc;qQ*ZHJD&p5^q@8z%%%3>$z%`?KEEWgX4W0e7Q6Ers9k@?3Es{UVJSgxo4GMy=YwrbiY zB)`hTth-tZ=!G*oWEa5zXYwF_HP&F*dh#sSt(2#H+w&EtI4kTPg`$C#KD&?P6FedG z*exsEld%@mq>(=v`L2jHqb1lYa7Fp=;}1)h7N9z&i8}!lIt?4b&3IQi`$J7{S8@{L zwWQx-pq^=%j+4LbUvH);T0+xJAhpZ<$Nu%Tuo;Oi&`E0OKdHzaXRTPpw_Z?^7=l{Y zgfFhV9Vo^eh^zQoV`YhFbWj2Bks^B!ww7QAsbg{-yXTd_ep?I?m3PI!L1jYVf0WR+ zv1|+jcFVeyrQGBc%m^j2L$%ph{k-F%22?CBS61`e;Wo1zdhaCkHjhi?Af6*@*6n+T zrdN-%`x@V`x9>yBWh@#_ zcFm4fhvzfy^w-i%HljeC#7)yE!l6_lFbyb#7%zB>Me$9d0hy8Q-gvNxIVP`U^Xkmf zUAI9G#wdB#aRfup|Jqn!hOuV^Eg@mR;UbHG^>5z@LP*HN290CLC8XqOyVH@q06I;L z4miO#^uJQXPYxu@l2m8-lwG_fyi{uOU1!`w3GKN$;JpwNEF`Wfss9-5kA0N)o(gq1 zg|l23+yZ1#c<@8qAH86q1Oh~1DV^dL4U*`VgV2ATCVHbpaXqWrt>PoW{jdd&TJM(+m5#O+ed<4-5D(j--J>NVGkQjHj13iZUCF;Lj8RSoA zhJ;Lc0R@Xr7QCfbAgpE1X2X0A+89|tq;R0fk3x@gsio;UWy6JWm-4#SV#SYCoq~?t z@E9l5Na{1j;fRZ8EAW?S($aPR3bU>()mJACz9je@jn)H;aGK_aG=*%p1UR13g$-!k zSEs?*2|C;n5BY-*Zt3-nTd*)BdZpD0g)f8LtSMn@Q6 zWCzjtsan&uJr?b>25+|iVUTMY2x!n>eix3E027!qb)d)<1&UU4vsTo{Y^sL;0ghIU zv|*p?^}j$y7)tG%of$Nt|7&`8{isDYpk+xNM0Wr;^z=#8{^F-rf4<!b-aS9G7X$`sFCbm zRtM6D;``DTVVh)O4FrYh0A@9%Id3D6T3$6+qlde=UW7Uk)4Smm-X3VPqp(UPY42kp zXg%v?Azq~ufM)CW$3771ihyrHB7SL(7%rI;P4JRqjvoEd64hl-Pao2Rz8t=y6~l!F z8lOM*^SUk=yCkvF50kjP^DANVuf`vpJ50>LZ+`!9(sv)+N@0N8npa$%66hXBg@FMI zCY&%GYYW#=((|AXhIR%WQ8x*t&B|f_2_y)5?MItqrj5>g<}DqN5(|?_Kq5-yF<;lk z4WxKUqF*jhs{y=G}lu?V2=k7s1&zyOK^_#| zM3ps4pJBSVDK|Ht)?nxxyCYX3*j+2@aN{ zTq3`?=sbN~1E4hNjTAa{aIK^#BV!jNOh{QzuSsp_UygZX<*l9$cfS%Q$-Q0Ltf*l? zjnCp&v=Q8}U*KV{V1iygru$CoEk{A{0E3GpYrV~RPXRm!Rp90qw(zb&X1FhGxnkD=m;M?NtuiKy$T#m$hD56T=NX3tgv*bQO z&P^cRa4OD^*Px9#h{R6DCsTs7Qf#r#UvB+e6DkgNU_+qLzx4KIuv~l=u_lp1o+kk0 z2MdI!KK-5cu&7lL2j0Cvm*U3BKH;Jpk4K4LkRzg*F7^w-)P-43DA%B;Rw^xIq2g(9 zL%9_>TRUPyeS{wk^f*r;;9Vd>omFp#7$Ak!K9EuTESd$1IDI1gNa3>ba~kF#kn5@& zP3C;rz)a0!Frq_7c7Iz3d-+`n_5kq)ol)=zK|^kSfp*!>-HJ?j z2fwQNxoZROc!0cTA#IF~%A^lYbF9Nx8prxzFGLJ7&|rOa%q3OJ%TEb)A8kM=>ccIj z7VwbI5EAoI$xMljFFL&tcpuKa%dG*fmlhEbK`lo%*2ZL{K@uMw&u2q6vNaW+dLq^% zS~(?@sb&*-K1$iN|GTm;)=wF|6wTC>u0b(kf#K=sVPBe|j~u7XQ1?P7;-UzHLCx$E z<%Ta6ic^|O>P2y%1i^&cS3Lq+o)98XYh1Fp;9~bSsHR(v@&|*5u-%E_cmT)-^x#o#ElWd1yM{6odo$&m>KvUI%ZJ!j~sKjr4^O?A#}L-5FLi<`D2R$ozfGyq<@Q zS1ZIloGkmvmt8@}bC}EOF$YAD2%TmIEcu}{z_#vDg>2G5Fk_M0FOz3rT1bCjRg*=| zvX242kf>h~EXBy--H&@zAQi;Yz`_g=pEHC!IA^D+&ZQ~=9EWjiKSdrQu0YUP$`VaX zU5+Ustlgf@V@S*$2Y^pX=zVt_Niw?g+F%LqZl7m$<;LNE{&%eoL`YLKKdletscT!GyYGTJY4rSnoHky>LdwNwwbCmhojE4bJxRZ`lfhJam5f0aZNje zu2q&RTyy)CKp!`W6Fn!Y2M}7TTWn(_lZ&21h#aoAuH`@!(?weSrNI!uFj=#m`%l zftN=YcW}~>C@!*K-loh21N5*JCFmiE3;<+aobYf*OWZ*(VY&o${wb z8i3!2eFMQ8Tui_4Bez8uW7Tu8H}mmh0)w;}$6uIfcGlU->~wTOi*_+{lJM!QHK z3O-P$-Y?CHBREB3$A^0Pk2q6=mdcqxaZv1Ddktrr>LUCqcyK@DQIK@B9ca}beuxPA za;c)k-v!P$uPPOyQlO5#EXdPN;(jZ~a()z0%Vr_7A1KvJ%LCm8>_%4*n{D_Mk()pt zomZ;DWl9Qb6}3oQc6%pa3~&Q25b^}{_6xp*_*@-m?tfFI?h8e>ET9mibK-HEJCk-UZXq8Vb!4 z46ruS5$h9AaW?Qk`?VN%9#)dWR?#_%&s1Z7N zC>cgo`sMOk#B!dK-qrwNbQz`rh39eo^;>vEBgt@}2EK255Wgqu7{Yp#&S%8E zZ$55!AIaCJk{}X(V+<16CzGY&&5n6kLH#C7!vSQgDfg9z+ctxB?Jo((-~k)2XNHlJ zJ;n(JZrA>IT=x=Cxg)}YY$j>#v4~aV?xeYTC1!r9!G#9!1qM^wqa?u2aqI30 z^8U+lZu{r}MUad{wZvxi3`K%^Q&jjjN%0QVOzW){^bpy!zl`qdrq#qum#F68XJV9g zLSd3jkgyZ)(`CSbrQ0@bH?vahbHd8TDp-s|6D*Ap%%1p#X^vPhNQK@Qr^o{q`plj& zuGMV8&_{}-OX11OO;QrCWmBVx8?p~GpD8B9ngr)lspBlg0EQO`KCIMbJ)q`H4vnGB zfe8pxbB1YRZvw1PXq;1%`Gj6PVZA<@IgXASGC^)Zd2H8m%s^WXmSkl4DMA>36HejVS<&#UR4;1m5&SAE|^lUsu_ zBb9}9S&Q^ts{;@!)i*5mFzz<*+2~ZnZPv_#vKKZ`;ju}O4OAc9+Q8~y9Ji2KpB-40 zEP0*H6Q)&!hqY^DYKXMgiy=%yc55Hm8;zv~uY0i@tbV6=)ax@{m6Y9sy&4(O^(FL+l??{KK_94@v1%{ZNcv{83%C#q+ zkZ$*|FIE!wquqJ0Pf;n}zzk-)a7LCN8NpudgrGCbkg&IS3y=b# z#mTv8A=Raw;Rrn6puA{I>`@2&d}0gOoctbHkD5Dg)!jI2`=H5M zI=-?}Ec9-2zJFbRljmPWnEL>Y#Z@E)_ogT>Ba!|zJ$@)#9!}TQQ6f{BrwhJ@kzJaE z_bK`=6xb|&_(zsINsHs0=L%#U0kS;S%?rlRT7_wwxbzxQqK!be*hynG0@JTp+oSR)%-E-h#NY@7}9wCzRlhoEA7oj#V zow8aaCpPndVMjcNv*`&x>4}xAr@wrTP7S^eb@cS*e3F}LpoXDpVO*F>8ErR2Y$us*RtsHD`#>5(WLzSx;l@9`MX{IZkXQ%fG z@sCBCJ7;G(@eyt%XwspN$4UU&0%+<2VwAl#_efouV6aU&pzNcI#FDKWD7}G3K?Pm= z5rb5<73e3>P#|K!Wx4!Za1O`G&iyk4iZ>Vpy@b5DQDmN)cxQZ}nOm|RF@|Z>up8rz zUC)H8j3gJQ5QT=G@u7KHs+d;U3y!u&C;iv`gw9Z+Ui;y{))+2kQF;*JSZKjBn`;V$ zilKA!bPyn=TsA9o?!&kU6|&Dm;Pk=fnywlDhe;}nks0>%(ex)G?ACAHE;NebBldzx z%BhI{k>^E$0NvRmwXxZdK0&E_W%#iG1F{+crwRGa*-%5sN&OS~Cx~ID-J%5+d_G`R z8n!}Hkezm~Y|z}W66~O=$5C;Pr43EQXfQ*MlW@cz08_ICTR`Db>9+4wIqpWmsTK7t zJJX!c<5;5&*kF{X*~E`?oynLT^Wjme$2RTSWNGT++2jX_<_0tPJbF-i#-@&<5mzEg zSflW5l{nl=4y(QX(=(Cwa5O5Y+UB7e;_}+9A`8He5@$n@Pa-=QkMrgs@$s(DQ*;XJ z5gPi3Aw99ToJ0wn?bsxQre`u9bWL&1ESF+;7hAetNQMx2EhNu6!Dec(JXGz##SI!j zE>BKml6K>t5E2be87}Hh|I;w>jXv{f-c!uD&Pbq2B^ z1ID`@PV~i=yoY5S5UkEGZX*YULcXlWvZQ|yNYXA(+S-4CQ6((TbO-m`gOz{lvPTXD`dgu17__folR4h?c}42I^XNp|HU+(l8& zA z{cF!Zl9m~>*s5}SW>G@0%)j+IWug`_oF$j6cwB;JyaqY}kd6jOBEcXz;klN`S~vNI zkW`!XWhp#`l4@A5;&IJ3Ui!(g$OxVhh7hyyOU+zkL-o@M!X4P3U3qyKbk(4{Q_lSn zUA6Ual|CUU;-wM7L=cW_01F2}3DJEvRPaQ%oXDp+dm6HUZx5}dd_sz}_`X*rn8{=W zVnIc&P_@4k;V5C1h`lyO1q8TV>C0Iz6YT@*ppy>li>%LWD+8n#X_X&C;8`ke3zS~B z{#lc+U+#+JO2HZ_vC*6>)xiJ6Y^9n^i=}H63(Y8|9Rb%DYl9krw2USz-a_ zho51T3>yT5P6n-@XNl#c-a%52`f_%^azbSl;W8o@mxdwIM3a=o2i z(fr?u`;_L&0R}fBF;3UC14sv#o!y%SI%3C*X{BX&xze^5E1_ysb7T`_`FpSq2n;5x z1h~uSM9qMA4RUMz$=J*+O|M|v{Ea75BmaA~@fjimo>+2`9xXKN+WaY#L6byCQTANH zsF#`MFVn=I3O#G+-8pLMs3y+`>&T2&r-nV9aU1l7Gr?l1g2p~_YOKT(7nMzVE~ddWPNBz=^R8+)(q-v^-?-cKK$3E~#+pc8@y z3jJr+9D>_%v zKDi(YFRr-yr5>*3%GasI9Qr_;gWo^3k8LaWSkv`_fiZ?6LxaxYRN$)2*54zMCSbDy%8 z1@^#9&AJtw=}mQzi-1o*YCj(VsJ*!j3FM~Xme43XjntSELgk3d;RNG+-oAj7V7+aVegJl|NKqC3@b8L;-NS0-{LEMV{1qlIcv5j z$6B|@d(C)F1WFr?-Ble;B+W$qOX)B4E7!gmOB#wJpIIV?yV5QfIo`#9_Lv6F_Yqe1 zIwLBt4?BKCfB)zNAZ%Oc-45oyRUU!39lg$jw$YMUN(PG8)}B$9h5R6djah>yx`|?| z>G4UtsY;!6K`f!$f2XEOD{C9D8K;e4UpiE0iZlzMi0%f}@X|RVts(_^#bO7*WUx{o z=Z+uZgmRXRbYOd^PKLEuX2#@&;LB-|U%SAea>ce!Oz<7l3-47R-q$b~G!PG?ho+Lk zrwbO0^6XXiiJ*oQze*4oIlA>hKmur9(}Xq1Lt!54Pe2UuF5cFddxKXa+U!zf zQa()IVff^3k3CoqFrF;#+oli6FL`TGA?Af=Bc9?okGO8RZ5jgxto0nWa1F&Z8=W0n}n;_$SO?NuVONQsh-7So@ zflI^@iKsmLWu&{NvmNAIYe7CTfdQ5vF46%Oi%YTCvYK=4F!)qpy*zrG)2ZS-g3ZR= zA*YhjyI&;ZATpxL&v&H?w``>7+XHkbNoOTFYJwW62N)dgQznN(+=lUH;ud@{9^Tf4 z%P8e!`fmS0Qmss$0FIh}aC0wj`CK*n;5}R3^bxFoWjN=PLW?reGOlEf>2|%JNK8vz z%#!&=t-rnWm@R<$X(}5ji#Ct~5Avvd)Wg|&bfl%M8bPM_?mUPm?XxDv)J(duDvtdN z05h=DF4Fe%9rPD?koItwK#<>}d=XG)vEGC}L<0dbT}$S}7fBwX9zU*f3hOKjAUhsh z`$eGSmP?~+Cr2cHFCQ~TQMMJ}b`Op-IoYKN7>-m5-PSXiT=)dq%|0336nk7y0)Xmo z3ch?;;02J}P{N-kxhQBnE$Vr-U`|F?JVUd%O*S&+Fi+|u$L{>#lKO_%`3--Qr+66` z5s}*%92DZ5`AJaloKh49gOra~2&pe)K6rSKWiW}CHo|=S#@2Npg7m`t9yKflYwRQT z<~eP_y5gkx9Rm3F+Q{N+Ui5(tu|QhL6|$_`8&MoQRfQ{PGa=HkA~AMHwif^C?m{Se z*|qEL%?g+!Fi8BqvqZD7p2`Wc`Thqa&V;CvmQbNYIJy=>e(Vd7%OOR>_zyqt5!0p< zY99Y}cg-C5+yhlyQ#}w_Jov7)nFaK+ z!ny~VNs%i9cJSZqpk(CTptBH-AfQc!H^ihh{Q8}~N3HiF#Z_yb%I)IPlG~nO1ffCk zw&uJ^DrY;EMrzV``rQ00mfZaI@~*52ozW7%RS`8He|q@>zxming&Fw4h;iL@Bho;S zi#E2Sw5)vZd+C2HW0WpM@y7vUU;u%&jQSIPtpe5p(PtZ843+;J1g{6$ zH&NMhdFEXtICC8v?;$Y6&VF0TcHxq;h&>Vi*ISwJtfx{Q=<=}PB4=dtC=_^}Y;;W= zwH+!VJq9!Pmh{4&h>J*lv@L&08Dzclx1b8x4{A?R*2 zOxm(F=9+nEP$$UzYSSqQ1n<%wUetlJ@V9D-m1P(y3uw&>8{1n+5Wxa9bAzO zqnFK{r)|W7?sP+qM)v)UUkbr~1yS1`B?Y>!*hC(prf+uLc3`N1%5NN&K6?8zI2!K8l^e06Nq= z!kypBlE<_#XR!mMm*@U><;(#Rk3O-R3F%lr^W2)_n(+nrB<$kOaK%cMLp}|2F_vb_ zVg*0|Fof@@js)z@kO^@%0%Uo4v=dhB2C3|1129NnQsG*|O1PuZwxZjF?;p1SqfkZP zv5TJ%I9=kN>ErEPZJd$1RcbiBksOfPTt{Ii`$H#;ApGQ#gyY*Vbd_*}{XxsYaz*?F zFGwCv0mLjRYoO2gE@(Giu3cG$&9+@l;uGiz09BUZ=j4=|*2Frhy#z>ITTc2=nTF3nYDVj7Pu2rbk>SI(7&3 zbbj4Q)7~c5IJHP98V*+KBVWbjMdaZ8ol@D2skXe(NOinbdJKdKYH9Xt@=LK>$&5{S zZ;X5YeuDV8n1|de!_?E1?!B*@8wG)QcnN6;C7mw{L7J&RWl_t! zvU#bT;^uVOi~DIq0!vPIjrwhK*pBjBWo`{~_%3%KvRtu5W*Iwc`hZGKGV{h}`wf zFdc50N83W@!u0-%GFvKAjY?#SddfLfs1GsCR8bjbvi_Tt--%sU_?E_8A zd=l%>$D>#6in#!?fc-uL^g8O@MS`0`y6I#2Zqg$@u*UTzz>P!Ak*eoJ7WeS{6h#aQ z#ZES(emd;F!2z%b2+Ghg00@kP>4S(n@Vnvbh%ZpB5>mUo0SnAcF(10q=#v9=ap+$i zAW&bQF!H~F_Zw&xpg9A)8}DmIYb+f(T=JnAHRbEcbglUFkghDl1wQaafmDuzz8im} z&&yySz6;5$6fasUmbSEJV8rE z`w1__x}N5M?K#_D3#a#DJFEwr$YKE}JVs`m-5fh@sLN21zJgU3QM=%L7*SXdL$cHF zx{i)!W()y;gR65Av0!VODiJ;r*_@{GicU@B3WQ-fritmy3K+Eb~9DE}QkBiHQW z54SCA9&3Fh^tDD>556;7p1h|WL(Y$XMQaz+?ebs-z#v2D!yHrCkwR1xdEa1qgpI0D z0X?#LJp_5|13Tnf3v3+n%rX-fxn>g<9UhH1jeMu~iHS*myfXR&{1DMR8P5q3W492K0}VjC|Bp&s3$8qZp=ja?s-zRr z3B#Yn)labbNoIU5UsKPY;tSdc3Q$6s&Hcq~kg~uczkb#YB zEH63omC3zYbg!)MAq~OZ_u_6R_zbRfT`IPdK?fl2ta?Ym^B!0Yk-{rExjqZy z{1Q!0gydwS4_17*MbhM-d>XwrDb(OV zAx`Zut7G$wrlFuA%;xjDY~ZE@9Sp5rS1eJ8T@8oz1NHid%}VvbgWShDIvD|ICCBCsT}A@h}w&RA;Z ztPi*1wmi4Nv^$4z!aRR>(EnV?BoKUKSQ!4ALY$_DL}0U^Be8Q$!i@>ZP9ZXO7hoRl z{OC3@K6TyH)6oJ?G{%k4|*vn)gt4urmY+Hnzh+OUGC$BTy}Imr^6e-_W>_*Enm>!;cH> z2oajZtdOWx)aXrZIhFZZfk8Lkv@<|K*Kri|LeQ)JbZes@Dq#>!u;(1w4^0fF!kWbX zkVd*YAH0OqV_G4on~QP;;@lz8* zUOQ#vdtB{Z$v6~^mwN{;E-7-jY9bh!Ed`gqYBeWxe(V zd6x3a)|!g&Lzyz9R0A*Ub1;d<+GL1-aX z9BhG^12B=(ktH!aC=ryfnmaRlLsWXPz+Ay-=c)Y9w`RA4WAo$BY}cISTv?~#e|oZtklP;EroJPrw)Y53a^>s-a{~@0 zXfsJvnUU=R%`@TjHGRfqARIR9t+9T+UyCZ^Zgp*|D_rYq-wGF%AkP^Mr^Xs4sx%)5 zeD(JfpE;WJu1zn5n5L9RpBDFwg{O#J0MV~&OEhC~Mw)u$f++qDNOG-1&eLg6D62ip@uR-!C%`)ZNaQLk7a<@InVF3T#`lFZJE0dX|uxibd0_ zsh#$WRPr%Ju9fG{6ZK!^4Op&|wOnRH`%dUi#Gi;fZYYjVC=amolf`X`3rHc55*;$` zJ**}7MWRIuu#Q)BO}hs4^AYoPIwmifS$5~!9KMQRjT(%2){*74EZlGRmzabll2PFF zELwBpPI&eHjC^FuLY4Yg2rO{7b{_ND)a2E=DM*?Ps6VNXu(P_;<+wFN7aG$&DDw8x zWop>7txsXi8K&NkA*A`w78I@-ufzqHqm#(uraScvttRaH+Z+KsiT+C}X!d;9{R>M! z8T;(|EY8XAMytrj9oV2#t_q1;pg5tvTW|;cYfm^6jH?93_^uP#AuTc1Y7+FuhB$IPnbY0Sj z@-ye(%gFhljWdo86fyNQy_yFO+7tyecBYQne#tKfK9pZ`%~_=D}l(6b9HrL}$@8vW0<%yD}=TA6cpZyIoAe3;}x zl<=I$CO6xgm3v1$$v9d+kZ)vRQPy_n1{5Z1;YuQR$F4sqfCq+t*o+@X0Knppu@?hM zhfo1IDSdhADMkUaJaP3-N^KM_4K^PP0~vA>6|4(N2INIQ=tKmg+on#RPJ&J=58D;%^@P+K4BC`V89 zsn+=368kd_)w0vlJ1#$)?wT&a|2~TTjTA67Rg_g-c|>TDbhQr{b;X>l<~hq)>0G1J zAgSi%+r;))b`3OkN7Kf+)NvyvKm~rr>9RSvn1$gU&z1GUO=V;CYG-A|^ zMCtUf{;_Nrb;fxJkCi!$Ow;svaA|4nv>bGbIQ><*J&bPrZU(3{8r@KI!IQ>_^xd+s zHUKk`K@jH@^d^2(A&7AMpd=+E)W^la9C2PKmDRz} z0G0$B011b4Sn0=x^bap8{mX9RZ9Uc#5;j8i`C!#L2$}`L35LawhocSQ+}|;MyVCVXg>+JOU91^c8i zw3*tD!Y_U9l2w+c(qt>Xmzo*ZNAI+tlFKm!!xYWi;!vgJ8m$Ym?H;xravzpzNVO`CWqKHIdZil zB6%KL$E_R1V-8nimM+{j|9X|gS!N|or8TMCg&^?oQjaib3>NUpKzNmMr1>sO2khj z+QBZhtaqkwqiK>LG~H3bqyM)ql?!NWw1Xi(p3%XL4w~FL008-p86gHg53U zI8JrjDy7#vuvnB;{GBREV#WoxBpTvUD8Tkx*ug+VIt>RGEEoFG%VuY0zsaHEPcd`; z#6WDU&XRJNeZWP!ku6k2rj|P6>Vc#DAVX5Y002-y0002t0iT(SYAgQ$00RI30{{R6 z006gu00093Du4h0?|=XSa{vGX00GMrljz2fv8GTpa4}TF)TdO)sFBEVuo0<~7%>l) zssM{yGcyqZ2Wu=cih?YG7#~0u5Ws(0+}QKEkk8F1Qt$}8*ytWDaI@#g#&c)mL){go zfP1fo=L}Q{R|8QPHjJo?GaQb^DSsGGsyQN#0n9`I00RI30{{R604c*ABme<>7+7r- zut0Tph)(;%uHY8Y0002b0iT)dbguvaJc?-p@r2ZC&>#Q-jea5h2?l^WOClg_LJd<) zTd=PTX8yny=$P*Ea@GP_00;;&8C$r5pLsO`W$s7^>W*cm?Q*jQG#nf!)_M(Z<^sj$?(G! z>KTHn;NtwDnf@u-XMI4)6Acou?WAr1os7|Zg5w||0n?nAIxr?Zk_S3Ig(O+M(}=Mx ziTXPa5?5I$bj4`DKmm3+P;Wg{#%mv=O^aT00kU>@dEHPBsdM1yEXrX23u!+%84od3 zl2B|hQs(9*8|fi(P6UX#=z4F%DWk?PVED!@A<__DMAOSKJG&TSrv7|E1&=|K;Se$ZSdj8OnV?s0W zAU&EuSSUWK|2OrFYjQQ^K{BRK#wh2Qj*Z)?ZJ~}Ju})n%A`szZ%>s=eM$m8+WQ@+` z)KPE5b*exhlE{;IobX*drkg!)40T#UYwwpklaE1NL#f#?{sNG7o<>{a~U-Pomu#}bpZA31~N&>CW{Q^4RL4XRDO?z7D z$ACXMf%GnBbA14q$*?9uvGS-R+k`VBlNcn$%A?*n0)5+K9DRhrJ@O2Df@1cjp1frC z1X4YM7O6#b)oHtUTTk&O2K7d1)#3<-x+ObBAj@p;11XEQYJ51+@E1s7HQUQPs z7V^M`g6$2nL-gZP%2+n4GtUZ|7~in}UQW#jj+ligISNwjjvl$nI0T#sYO?mV@+JFJ z;df`}@@&RN@os;9tfEd$Y2#xQ9gbV8G!@-YcV8}QKV5Pu2c~EtyT>(@szcO{`Zfds zX%s2aYXu14A**h7mnrvaseK+jrge`k;anl-IyP;=DN)Mo&hiWODQAXk1`LoqY!LYC zq}PT5{vi;*6E;g@5laSsFx1+$kCSd=%3R*u{91X)meoVOCTJpRGVkM#_NvS|F=BRQ z+h6}7CLiQcZaoY%OmZ`1K&CDl$OF&MMa^mpi()-WW7w_{mwpnpW1(8mI5OX_lU~gC z>(XEf@VVNxY|$LQC<48}0w%O%q?tk}W6VWFD;@Tc-(vSSW`|weo(<&sDimn-$FgX` zElbc{U#CHu)OD{^NUpzEUrFrL{4tytge1wBb^@)=aGxagk0_H6a-$D-wcx~%DbX)BXRUGS`9+Hst)ZTi zU;x;Ry#-Jm(Y7txd*klz!QI`R;O=h0-6d??HMm=FcXtaAAS4ii1^3_~NCI!?oO|v$ z@7?$7{i?3oR9Dk$j@iBD9CIw`2-e@>=NT?*p9NT?lja1|Y9BSg5OUdMcy4U@vO>pf zF&Jl~IdA<_+;vJl;*U*pni=ha8|@pGiu#QT>rUaT$rZKe6G#Ws%pB&Yx5&Pt-!&>K zrGB6Z%O*&7{fJ%@=dh?$sgFaG&URIiJu2&4KY3{5ntN~-^AudRuoSUkp3vj&TWnIs z`uu`>xMS$jiyFV;|M=@tEpgjLfRnbXPy(-%b#h5(5{a+an{@O(5USxIGnaQ~v~YbxqktNgKXQ;CaCt2o0E zQcL8m0Etuo5QRIbM08ZML^Z$!M%|&F8Gn6~75ZTutL)?3FqH?@{)xN??pfF>OR{J= z*&o(ozHYeZ!3BBxQ)excHGCtOu+jRcUG!pS6|z5$9RCynVS9!wl1eH$v(T^1ha}r1 zwFaJIu2pUo_v*&i)L+-UxWN`={8C1q4d4@lSY7AR3CwY2{lMHwiUBMwFrM`;+?;vP zuuIiF%OEE0=dSYWmwEv|cjo&j(zLu*#r6K|Nk5Uz>yJjZetw8g^ay|<5AhvrxK+A5 zV;HVY_MkJc4CqH6C)zLHW6c-hThXu86T;Pht%P3tNfXSk_e zs9jdBCg`K04}(P(VLozpR$a#=)@~jGp%=eIgGbnOZ_-=aNlI_&5=W*NguCQcs+#tO z%hw$7<@l*j?I&eBH>+c?C04ZWS&tY+o7h#q*GOkN-OC)DxX}{5lyQqwH;GPyQ%IXM zR*-LF>{4#r;Qh>QF&B`8x#xuoUz>nFu<#Z)dr)pLUo~SR7WwHp&s1Pg?@+2QNyJ@g zA*ZFh<&m*n+t)P`=OrwA^Z5HNm`hGEbdhRJ+FXj^ygUxY`p#W-+!WeGLPPcW_X3S~1f4Jo%oTevGD$0I#^UhZ6xenH(8hw#?Ya(Tw|E(?-~DZ58za} zdu|z2r9`HERyfBlN~=k#tXBPEI_dA~G1|Bquc}Q5KAuXcyk)AdFEqHzK64n)>Rs0n zB$5*J@rjSVH~&jGB#TPx{uVrg0D#JTpwk3UB^VgsoCm8-)jKNl_WD8o<`)1iaffM| z)S+cKAnZfb_wZRDE|DaJm|L4cq5%DPTdYQKT)#$NU*XxKp5(n@0VV#T7_k5reluXpsx_ew`G+Or*R)BTKFp45J zfHfkWGwa*wq<sWToZ=-c$a8(@5~?RDr@|)oHNXf~(> z*5mNKW>ON5Hm_XJVu`vuZHf3ER)5z@aoekiz=bPn@yV5%9FS4*FTRG z=1ZK}|H#0v3UVUEv+P(G9aDbV@+Z+r$xOV*Kd2KTpW1f7g+yEJOyR7}dJLQuHhYR! zQg9p{YyUzf{}?`z!oX*iVzCC~fhr7U6}aRZ(IUij z#Pxd`D8r8N*z`E_NQs(grs;ftT$F812`X>uH z67DciQH|3-$|E#&fD=Lr_tOwOo4L;*rJoAY(csbq^#ed-6romQ!nb2^cj1p@JW4kV z31m#41*uH{eKlqjD59qtyaX5s88!JT2RM}1zeg>Cs z6fBOCQle<=gt4>pns|$oZd30lSxOlNovKD0Uq&#r#Ct&DHFnNZAJq)GODQuvgy*%3 z-PnJhJwnXwZJ4BU%?kqN`SfC9L#2oVuH^4;=$PWp*+OjSX)x;+i1!{9>CL~Z9kw5a zrTdMwD17)lE`+JfJ-bSrD24A`Ji?aQYE9%fm?3qXxumyPB_o%*Fprn2K-jb54*~oG z6GkmOdNmKU;c?l}_dXYD5N4b|IBR=;M&hpN1A%(IRxb;5hE4X>zic_t;u*Pfzgcz~ z;LSxVNr3S=)!2n+fY{#A*CG6C==fY2=g0r~w6K+v-2Zxq^s z{y@)zWj=~Yq~9c12vU_;=12VLu*LIEctmDc3PWclPjMtg#t-`*i87w$ay5j&*LbQG zYOBu~h#0@tsZUANmhh$r;JQ1X-uDCSgp#rMOs++jC&l(>kPXekIVFQd`+ut#z z^>ZNaaI<;VE{mHhFaH#?X^m;62FWk5BOO-^6*eSp@OW{0UeZR0iK`POYE@|}F|Mk@ zqu3$-G_Gy)Qc@`)>vQymq75AQ_wN16SzU0A_8^F?B8++szKzofgUaakcGc+rN$S4 zxEM*{?`eTSVVnin8x#Oo+697Ks?&En(C)6yu{rtV@@Q$ZY3CrfDfcVB^W3=>mlWD( z*DGo(>TvyLKTdi5=-MIq)-iM)!z)2UV&9C_BekR3$F}+jO{1{4NY0ENl)@u(C?6lBk&P7Md|&ft?_V}FUhvEY?@@_WRx>p0!ABWXl;i5raU($tAN_SDNIWU3 zIbMV3>+gfj;E5G3;FKy7%>^{egRKko)gKcvq`#eM#J0%-fZkBj)50bemK#JY_2QQA zN@lgx$wnG?7h#TZ{a$vcu>2eiG!RBcM)Hm|ErpoafvrpA5Mh{hHGf5hz_VAL zEeZk<^^Rc2jOOnKwUcy=h)yX|=b6uHbX=-=;oG}9f8NFUd~VYs?MJ;!>5uEAN^o4( zvI15EQc*6^Z5xYkP zAWNhM5^w7wW|bCKjO@yjT~7%n)QzcSedzpZX-$G8$8MrAUb`TMw`N<3^eAhMRY%Q` z52Fw9zRQkD1Ar@Nw}lat%&VRFzt*FffvyZ)&=@Q3xC}o;M~*8$wm4;sSv<##@lhim zLiV-N=jP{(PYj|vJGTPF=8<@ArU?l9wJBTiJM!WrBEw|u@w%AS(`t4@nwEX7jY)FG zZ?@5n^dPp8;0fFAY$TAepEg>yO-z_@V2&aN&Ov|?GWGc#Vi`}VnP)eOc`)ksG@bRv zkuLswqkHbaKHrdgnvpC@dhW-X^!%8~j)#2VcRgAzFC}oAOxmrg-G^4!dn6`l&7Ta{ z0b4Ta;rY-<6&TSSZQuUjZw&(PXfTCrHlJ;s`E*m$4)aEK6_$iTY3SOL+uh&Ol=u$k z3$;3w$aIY0vR{=LWaxVGzBx!;VSCRZ+;%Yd!iO_%FqLjlMG0%oe;pLV>UPBQ*?VgG za2=@VK+Pie#-Z6i-N=j!tZ!>B~J$XJ2)xiT2maYOaEO2;uteEz|)zxQtOK;2ADN9ujOnSA(N#ph7b z4>TiL)avwK92{wj?(K>Xq4cf5+Pe-uBK*G*{vQX}h>gv*fu9M~Vz|Mf-xJuWh|a^hh4Hf}i@osJwfEb(n&jRc%stsyxLabcaFMRg0Xtkp@Wem*|^LiLv=>2A1%Kh(?CTk=vhkA-jWD%spmrRpUU@j9Brc`?x#5emoer?1O( zj#LSy^GV_}?BENwkxJ5NWiJ;!Q#4IBcO?7(S>x=P0qf)=4+eFOu933B=fW+@qObO$ z^Q(v~dWNL??I-MgXA7(!F-{6<_Z?K**davLjGIJxS&=8_&w25o+X}Z%M6a&uxA&q> z-_c++N5X$Oq2X1@geC3+scESgScfPxBA^^+S`Fs17DPs`uvv2;A{v1ruu9TJDfB(a zM_a@pDHvJIt|DOXetArmJ+onbP2W7PZF$317kK)c-f!3IN3_X(c?zv701GsGe=_%xGe)MG*J%oXMjaxv(#+o_Hc=t{(Q z3tx58;|;JqO0q*WM>Q8u-bbzP^>yUG2F)8b`B0tX?63kDuc40<9#quJ@?TXsjV zIZ-NeL5X9~Bq1q|V#EVOl)^6r0sPviN$ALY=HRRGNU1$+4$b4>e#i4s!FxR4BRxzL znWrKMM~-Go^CV||XHA?M6d*k@)f?E3!ct!#%EKgq%iU*X6ChTGixHHXfMFp@9{$Br z5b#6UGzNZw7y8{w^SQ~r@3zegg04t%@#W=mb}Xw+8_@L@U_6g<2}{YIohJw=nia~C zftyK?D`(+-6CRGQ{t!S3q0v5go`>*%qSeKB{xOFsIRpSe8PpTX|KSNBL`>Hl0F))5 z`a6pHf4|xQKsU!$O=++Z)&(G>lQ4!Po&;e2cL?YJYG%SeIaaPRSu((^K`{lr2!>(^keB!`E5UkI z0Du!0-YbQ23EN;K=YPKV4zZe`1{GlSpll-H0MDV@q#U#-;HJU1_fUchF29c5I$`)K z@?Z?L{aR(DB<*u?8BDzn{aK;MgSHVkcRF~A)Y>^2vyQ}fqJoQd($y>jF)K3&Q;y8$ zbsIuZho6YmocU=g!7R#|olKb)=25K5r3&)5fJqagBux9U8N@L2>aE>hD{G6D-2%5I z;Jj0v^&rDAZBd zpag)4Nk$2+hui>g6S<_vCG^%H)H}y2IXg_bxo-F#;AVkVuS#u=P#71S``lUO*R1`F zOKIAM%<3Vs{%fEi(jeZI%{( zb?i)6;_dbF!j790&WO{Zn^G+|$~ntDsRWF0?OVEte!a*xaq?Z5p>7sh^u(xWp|HhF zn=8}sj^7VM)ZJ>{Byp^E=Mr`*MC5QtKq_?`KNO3SXYN{n;iq4MA_{**^I^DEC2oo+slG_#Lf;lg{h=TCs-ar z)bMM2-Z{Iccj+CuD^DkbQ6X(#sZv{HW*I^s=xsQ%y{U#OlN5~_nsed3=I8Cd883fU zfz|Z*;FT*Qtmb!>>blre`i&^2w~b!pvuWLj7NJEGxjkW~9K*SuLj_4@2#m<&sJ@bO zq=^`Hy2wz;!c+;%1z~;dKC)r4c|da(2*y2Xx|WR)4Q4d_V7J`Zi;j~7W}@m-&rMQMeF=kf zw-I+hp(3wtxJHl-SD9h6LeJl7S+#H<0;}dp5*2}Sl-TSnJS;NccS}}ZOuH5B z_8kDggpx&LEdNDTV1RggX@U+c`b|RyfrGKXUFe?&#gy-7jn25bXd3MB7VJj2)^QaUZ`y9(*h6k2~in z{9)lh*2`eoFYdiP0R5MLlVWfsem1HAM7mQS0 zaWTsCvG+YEks-#9`vEy+oKH^lqju`RPqa?4Oe=pcSiPhzPYI)pVPi!zL3p}>*DNWv zn;3`GuUBox26na2MvP~&q=a7-tgy5j!yo8z_bg=x2&cQ^EL?xy%oLKUHi<_0&^#R` z;dHw27ym9ro21W>wq_62j|+YH#EL`p^nPs!EpehuDS6hkxI9~TBQ|Kfthy_O@M)o* zKOf%NxXIzj zq@i6r_66oUl|-UV#A7f=EHZOF%(>H$WJ960B0ZMfZ^c(t<2*Y`W)b<*I*cu4!<{@e ziN8+o(+jJt`Am(bDDv63)L~5+`XZxhy4J0!q4S#II^ON4Xts}5BT?a?hh&5wjJl!a zw!YMC+!Mca-UQ7VOMOYUiyLQdQ$u$wNiBw(=NT<(h~8UfGADYag;=>uz4%*Db3PA- z;LynL1#r@@%vc!$)BiKQ%$)s4zW>X7s&Hl2fjDReh6)ycNr4Ciz|jzdz9*n?z?zr3 zQPR-N7)E!=v{L*rey&D2u~*RaEyY!4gv$xJ)bv&4wm+7c*lE_`Gz1`z5M#PePWu>m zpX2lKXf=D@irT46Uq9w{n=_gl6z5DdhTu|26{PH6E7)-U=7Mwpm8IBDUqfCfU9@L} zLmnA!P`U)2VI?8LLlE5a)ykKWj>-(hL2UK@Ahln`x@jjx=2zDW!pe4fCLI~dN(JH{ z0Db|0;mOB_8Vj>82A~87zcXG=$NPL^b0!2vhh2EymY>JX_WA@ENkGAW0Ts=n{s(v< z7Eg){726K&>8A{2{NXbTzmLxdl3ojNrz03PLyF#Z`(?spKuOeF?Kg@!Yl?5 z-3qaOqH0X!rNL8gef-QK?lPse9+36eWvTsRDZj4ld(Ugoo7&%d;xNwdhLXNCprqtj zvExiozpXcah5+8E_b|pxXKCz(lsJH;N5n$)P-^ZbRerxV{B+*)en0_JrWPxv2*|SH zFVXqO!C_nc_ZL)F2Y4eEVP=933t~|Hp|}d5xRn3R833kx2!KfSuYdbjk0)6{QGBQI z)&!Hf34?;x(Q-HjAV7jA+5&(9QFu3>*PiIs`Guv=5!$pL%0_RJqDts7WeU->n?2go zAaH^>7cAQ9atZm7RLu$i9^QzjFRiVtO$XXV`wqd=5U}vKHE;nX0O+W%0|4wEP#P)I z{V|pR>;g4#6>6Z5Zy@&|e5xF_AgJU*f`IMAi7 z3T^qSa=@ovI+QF2!O{gd@+u`Afl|9yNF^#+?A1q6wGL#+Kd#_rr<|K*^wok=W)q$ zvJByJLQU?K%=;+!e`78G@;u7vDr6>!Y_Vd~09e*b6i^!t{gbUxmTFJyfM0|4b(4}p z%B`BK;Rn`+L9-aQ3guN~M>KNw&Su>#4lffWK&HmahjfaN_RISG+Cg<|ok70{N84LG zTZ(zg*YKdWmCuVz_ot@=sMQkHL;sbh?dC=RuOQzR2Nyb>=AGg+1*6sPWO7DrkQT-H)!=%BYfNgDQEgJJWp|0qA{ERsDu z#x@3-Vh+ugWl#?d4S2xzFjK#;HM%kuV;gqW(G0oj9z=a z1{e8i(`;eQ5^n_lP*@oysB7P|wjY|^6!6bjcePqt%;xhUFo2mox9+aQDd!mleG%`@ zg6&+j<1*J0xPCrpcaMn~k#TH4N@mPMxu{yFcu|QE!8_9t>yX~P%aQR>z+H!8%I^Nm#8*grv zm?>uV#j!x}3zdgSKr3Z1kjL-y!h{`KE1CvOl?(Ti#E~M3&Pu2~;iO!^yTw*s6@Gbx zZ4?)gr2<|h$B^^Xf0!Nd!TG3b*oIbfyA*H=!g1nP$yjX^a;&d7x+$$?x>hq)(_lsD zmUng!XRsw{=$>H0c_kv+;YWmch%JF1q|M9rGp$o$-Wz?}s_bJd%oqO%kl{v9mofYl%+A1!3Ki|HgKjLKeh)af!IqAYg8fsaVPU1B~=wm` z5fOP2Rr26Z+?i@$;4L4?j5$&vxsB659p*Cu6ryDof~C0BUA>B4!A3TbsKrlC_=xYa zIkmw9x&Rqe3}}=r`f~RFhc2-um0}X})@Q*nhoDeVh7B%&kOudFLJyQBKs6XLizy=k z9#I8em8jmf*O6M?2}#xKbU2ZVjh#{}B%iZMmLa;nE>{#Pxht<8u<1L#+c`LE?}-0e zgMrvgL+VQgbeu6a>)>LI%2{f> zoh%E=y59|IW<=%#OZtUsV;|`jrn!_vcZc6k5-hH;U?bh4@JbCS^;8Lu90w#tZp!3s}YZxX2iPmwS_D5|`_Q_zp-lH#1b6$mvhHj#GAH`hX>tiU3#~noll4MeB9{ zk;wnDm?QTtl_7*G2J!$1KmZXNLK*t2fncXV12pLE`gHJ@s+e)@uC7WO$lksYla0#K z>mbID@PX=NG-JNVAZ`YNE)7jqbza~HF~v;fsLyY>-cs*t6Ed+eeJ%5I?VNoYzKJ%R ziq2yJE))N`=tNzMOuVT&4d@PMiY$K;;^;|{*p4+yJma|IOh?0;YeLZD8Afsp`!*AlwWd;BZefaD}m89o&p;X|4w zNKl+?iGnelIN7vDDKOjJ*oQ#y?S%?$RxLCkm%X#TeA4Ko0? zgXeS&;sD?ypqAc&iZ)RHo$Uc;b#nl0NTUD&>nr@1otV(af|T(NUV4k2#6s7#3KhG4 zbr_{f?zO~4m@*GJf;ybFXWela>Ov1H0N_dRRkBLF(b60{4lWhNXzC9SqOPyEKpp!k z9PwGmqkg{8c80mY2j|gxuhy2tao+jgsYlMg;Z$Cpzo(wn=$XsnSvGgs!syk&Cj9nd+CDV@^p^raN`S1J9n&i-x{ zO8-R#g)-cCbR^DocagXGT6m`|)k59o{2ya(Uqx1U?C*He?bK z>k=wR#LKtGq^-y_pu*7tfSC>eAjIV1xdEUP>nX|*%pYwAuPyT-7O`%_pILMQbOQD~ z03)bI2U8%KxA{M45dRBQI?P(+`0GgMULcfs>Bo`GqYV;AdEbxp?5VXx*RH?d$UfP$ z9J&2<3JjgRbpR73sCNiNTE^NnM8=VR-0bx$(2%23R`0%e?-<)~ix^V(Tc3Um&e<}+ zN7Z%Bz;sTLP|4W0lb=Jam7^q5?b~m)A(gh>=;U9WSf^1_E!2yGMzDx`E;bU!DA{q91YoP`Sh$ zb-e8FeZN_J-1#~-TgiVtbB$fb>piD;eO!i9)KP;Aa>PwOgo^3)X$iP z+d+n)xm85AcYsc03+Z#bkCl7Yn-%gX$u?FkoOYCg^f}d<-<0A!mK8lm{*+p_I{w&n zJjHcr_F)3QpkHa=WTRyel5&XxTjbcivc=ByoC~dgOf7}e@ee1uYFqfW_l11reQw>8 zLKe<>>1MPQDHiwVx`7Vlbp4gjXT&oNIQbCb4IIdpl(kL&>lGv3{KWd8Z!ac;@gtd|xgIs^53*E^rXX%2qQ)W^P9Xi!8m1eNzkX1EUM##i$fH+{AmWxt3G# z-cp2Ez3PKRZ|;Ht{erF-z&+o`rz15F4`2WKTGkD!`7jby*~ zy}uUM5rFNxaTc>bin6Py>R(6y@#-i8;v>l+_Uc9%Pcgdw%>bfWgX74$1TBuJV!n#o zx^e_NLfMozQbTHdkIU*g3!(CcWAl!&HMcgCZi8vgTkZ`u;i}!MXTy?$z3_Hsx)`0F zZv4%AdlXd69J_=p(po+mDDOCs(J#WHM^oj}o$Je6o z;(q*|G+cMYnP85TnG$@U1^uE2lC0S)@z>k)X--?-#y&dLvW@m~@)&P&PlrGr-=6r$G%3OK{(U}{zh%HNTkaUvN-;SWtowY4=DKd~ zYBSEhgXT{SMf6C?o5p4V^~Z8#-%kzsj402-eifaN>f+VfK(26)y60 z*OajNfjU^@(V7#-(T*g51FSk(mGT~pE4mm>sikJgMKrWA7SX5sVJiydY1R+310K7$kcc>9=5@ryL^yBfbYlLF@#<8dGyWd0r$(Q7Uoat!yvG|-L z^P}Y)apBX0AC%|VjqfanIdD_@7z?reSmR3xCem{?o%vDsxg28_r^5WUaMnFky^LPC4j$5a;a`cefV<>pVYJOmQg4I_=;R&nFym4xD2 zo&0jm2pJkRGuybww|oreJqTne*g2I=TBd5`;JrqZOoFpDW6Si>^g_gYclKp80fa+z z=7O%H3P$$fU?>{QiVyW-V;=@%_^#f1Rvg@hx^mwmL$~hfkoHH`8&7O+(}OkE86}1n zRH0`ksNI=b%DFY#Ss`;ai%Gb11GwA0+x*uj?e$L;HEy)%HK-QZ+(Jq#&teX%0{{kj zx~K2L-0l{ml7*w%O#pc+)a^`Awikn!>jQkct9;gp88e zu*8?r1@Koge#OLPYymugi%nLAg{%de>rh0h_tmea7J`EE=8(@nb*ZP1WXE?;SqqW; z0;wAoiil+OX#?c_#o#(XX42fP)zr4ZR^c3_q>`El22ZwCw50+`u`gRvM_;X1kA4#s z8+&r6;ZrDJ{C55v_-iOa{u)~8kL8eXE1urO)J(B#IsT+((f&#Go^9Ybtk42aGdh}H zIyDpxWQFeKDc*uiKh#T`cc02`Y&MQLBKuw`VDM?!l+DRp8J;qs+GoA%5hv3$I`s@8 zh=l6BUCzGk)yfVH&-ZW!&!kmCJF)~iAiG{sYzWA8ZnjQ*<@9;${&jiNQxE_Oh0;2x zeD&i$%Z-2OhA15W4x3Q_@zf8%Lb*-R?|Kf;j^y}5WEplWg2S%?b7hi3^7-n<&jM_t{jO`|{8AVPB; zw|P)*57XT8*TQwhZG^9MoF`E%0K9@5?1XaP_7YJ!l-!D1K+!Ei(VhL1wEoxpHGp># z^1mS?ZLZYl(7J5szEnkvNIh|MOKyTA)0R}1!yj`S0<_G!3d~=F{PXW`6hYe?U0f|R z;gy2^df0nY3>orz5;fdUno~bX`eHH&2txE+iQ;n@)lG*r?~aAe&K1?>Q=VW0Fw}9B zQ$TW3`71}ZF_2h?{ViNHTLEMWCea)HMWtc-yO45Ob_Hxtr%8Lb&y;X83wXg$-8XFr z5NrdGJ-5K%v^r@ASdGK7>%m%w(7%h2PC-TI|6POtpz;I&;G~BDs0+paK!#BTU4ll& zdohl83m`9;ivtMDzefr29UR^)l2Z~&pvY9AdogQ{BQq<$0*Fx<-o?#!{)9{T(L}q* z#1lssnz{kuE4w4csUj=-U2e|iCX8`9`+SI(Xr<&zsryly?^)p6$(PSV>kV4cm5Z86 z(`c7UWoz;C@TW{Ccep287?f5kM%jHH)cy9K5YB|jehFD&R3X#uJ2o+iz&v_}BvS%h z$wU{xsG-%z;!TjjBy zuJNT4=w~vAr6Jh?13;cDVvHLhC4iz6ItIWf@M~28c&Lx>k$4d+#YA2`}%7n`3`rPsQC3lg3CG z<%g>H8|>(cEc+v$lPkcZvmk{)c(AScqIMLe6F7pG3jrzS8%m;Re z3({O8wA%bcM?pu(p^RorbU+{WCda{qYt)l=tIzWebqE5eN~k)U1Nh@E0N4-Sd4I^d zmk+=Lk7v6kV<6*Nw-Y1Pfz77bAb)43f(In?&i}_0x4*^5zi15xBPr17Ykg5kuel&R zUd*pe`biCt{tbOqpjWU-GN3E~_^87eVs9(H(U)$oY`{5$OCtpzbW(EgRt9Iu4gxeV zejIZsI50!ZcqJd??9}x%C!<>**g5PWM+7>~SuY;-KIJZX$;^{-VW`~t?bOCcA3Pan z(xNG{3R84B^F45C$Eof_SI`6XJ>OzyhIQ5Z!g&=k)3kmPG0nl2{p^D&Uqi6m3SA*( zqY>5GPe@Joy8Z?C&m5q*WV+>3y6mAXol9X$oP^mjQGFCeT>g_a6Wha<0^ayI1^r^y zt2Ae^dPsgl^v$jWA~k$xT=?gxEB-%;^Qy{0*f};UjvbyRBi@8#-=sHDZoJzGB}JAQ zB)=+vb&giWPbeK(Yz5rYa{x-Kg-!hhIAzWFg5TWQSONWX7- zN%}A?V>V>UY_BjUYmPIY;~Hnvy009|RV)~*dBkbzxHx~tTk%VwvPV0+Iet(@l{AyA z#$VYFjRnJeC>7uV(R+HF_&>Sb;PD)#r|3uM3e5O%CLesg>w}BE#aC5($7x@g6n_tKuHe&fXN!VGhFVK`cAX#*m@RyzcXDg`HAiAA4pnXB6!i-9?D60v7;&Z?Bq z9|OBxeQijilJo`bXlo7#G1B@Kb`>}r_j4{-XUCo==UOhDR7>-sV{LzmQ_y#_WBU#` zx!u!+w@SvBDf+)}dyVpooiR?DEQ9_Wo;08-2BY56L!c?J13G)J?80(@4xT=gi9SE! zFn@4WX}`;=Jf0&%;;q;4#F`?4%X!EsjJidlY6(}q`spWdCZVp^+ip`<18G%UuJ>#eu%Pr1tCn$TJ#z`}uO zBwvE6b4euLZo-7A;y81*f`||bnFA8-X7YB7_^0oic6j_l4{JP6uU#-McCpQEjv47y zJJMwUP$c9p1OlkS3KR4XFsmeVQlvr=2bMu=UjRA_DE%Cc3&^m6QbP|75$>u8al!)B zGv4V4zmwcqtfS2ZBkWM(MYQ>46G-bv)L00j+|f*pxS^DI`d7yDs;5XP=@VeR38JtJ zqzibfNfC$-zdV{=Bw?Ki3PG}Gfybos1BQA28UpSCz)}E^Aw7h#KSOr6@quO=9zwwR zOlW_B8U+43pA%Oy@5T229MSuq*@QOpb0mphBb{JyBuVvZfMF|a_1@nGKzvKys~o^b z;*GIrO%>YDCt*9Hs%yOUA~3VRVtlNX4zT8bd6}F#gtGW;y^@bs+KycUthJeKB!Zx1P2}EK;ess)r{BPs&wR(Ut*=w}>l<^( z?3fpu*XCrvJ;Ri$E_o`yh9L@_L}XeuZqzLz5tkj|;zO96agArX+qE0|o}_jlqK@c+ zAX6vP_uoOQ#&3E8OW|-39;5HTEmq%`Z}5H;vDD5Tpd}y`alg_Xi|-!DK#ZC@%Fn=) zaQhXhFE}QMT64N<_kLX-eo4_wa$~unDbwZULHf*Ng*kDbJB5|`K#qx|CF@F6Fs>bTv;@jxrjsS#);1`H7_DP%o56(Pg%l z7>>mb;rD-Eh)sWdeDR*=TSzBrJXQN-I;9j&Ge39qfSuTAO-RiPAW<~1s^x`)lG7zw zoZ=wU)Ch@;d)J;tO0~@>aYZx3@7d8gT5 zbXtgv>C^AGlk6p5a?OYHFnMCcK6m14N%09^U zEAjJZGX%%zII2Hu$A4OOY2dG8J((8(lR5BS=ygn+v9W+XeNY}bS;lq>w=peLdL5el z3O*fbvy2;68~2j1GY3Y$P2?k5YwS7r#BgA6D(x$}HFGs|rApG5>P{R2ITzdE!TY$$ zbP=b5?s(FaGF2t(|IRw3^)fmkT)<~nxrxFOu=Dv`X+NtqypG21iF4ls4;`)teUL0f zK>dFWm33J@<#cOwt79nMSBH}I=#u*@9;|gVq0r{N?n2@V#2t1^?I#Gpz67a4go@wP z&N_ixxDl~`@>!c6n#8i5JF}D(&AN@KCaWOD9E1S*9TvA*@HQS;T{a}yk444NZ|7d*x%&qHvV_TcZeblNk*`}-P5K2kb??4M&S21qeF z16KXDO^kJ~=tizx^5fW4;1reIiy{UM*LLAL#d;eFG$T0F@v^YUmx8m(v*75v-I=s- zbMg#_eJ!7!)O24@SU+lg_xM)5SUTYrX$4*Ewt!HsVADkYk~PZl=88e6wRY3zUWKg{ zqc6pUSvg2^DB9>-r#|oNaR@yRB@m=+#na+zNn`F>p?*Jw^2E}1JIhSnXgu8CZ^A`qYRXQhj{FK z>}C0;H=}7hd2cAlK~Ne#uQjW`JGv*;$680~QX@EIMZ{D8o_5>1Cx=HsPTmrO9cRR8n??@rK%85w_86VZ!O7L#E{b`pWR ztt#5snt7iq9W9Q>LIr8?p*@d7Kzw$Vk_0l&XT^$Y8A{a03C7L!E)B!98dYGUfgXztY{%Ysk^O(d>joFvkCA${8RcR0oJOppM^$TBZDdj1py18T{ii+y%{`O;vmZ?g7#s9=vAsFsgIz8p z68}bz)Zb~8GY0F|LZJESixaKHd*mr*S)Z}aTlfznd`N^AdRDozXi4U6K~ivZI<2X3nLfEqLfGId?YbE}g``BbLr{V#sG=!FlHAi8smJjNuH?Dk zucaUxLcsqvvugmQVS_FN0w%q31whz^%@2I|- zZljZ^rjtV*5l)$u;yR$lcVxcrM*Z<9EG8@@vAHz_y(bK<$Zt^}?y7|DDu7huDRNN^ zGcv3y_7Hq7?7mL zj9dn|@ixWYfx)z!arR}p+N`3Az+!poMedJryjcBh=p2CuN9Q4@a;6VmVhXCu#2KEw z5RuY1-TV!MoTxU`^#drV*tzI)orsnJ*$7>|xDLwSFbF>HjgWL>Adkbmo`{OBk};^} z-k9z@cM~z+#9ehXbE4ibEg&R96qTaOZfphmz6R$?Kf5I*YNXa^Kex8M(^;v+z%FhA zwi0(3WzpcM_u2+GyG;iF_1>I`CnT)8)31>8KYp*;Q%1zaT1we}?X* zRM>LCY2oL9wmYR@8*?esoE0S$?47M5zj72m7qY%lja{gmb9ks>I=;n$^<^bVaeygJ zE+`kdCZ))|HO9Vw3Zu72K46>WT~o9;S9FVO4QQhNQv`+Iu?&s7k?Ax+W`g0?!0UTts8LSldB zaU8;N$KaoAs;%x;uYZo~R(^1AAe+Jx+1$Oz#QXlv6V7qF!jhnQD*q|x8pe8nn>0sErx^IZQ z^QVCfW3Y)2b>q&DT-5PraF<}8!h)kW)7{#;9=gdD@$=u8S2&~L@pQ(|cABmn9!F|z zCTs3Nf?RTA`6fTK1Xy(<{ye9?(KG_j)At*ACwTQnzjo-C)N<8mOCvIi`qi`%mU^DZ zJ?Mu-GHsI6laHafwSM^KU6tLpRtUr-xNP4R z^u5#!?y@}9e#g{4zFkA%tg17EGC4sQtGfJ60dMd`EWbXYNRF!|3k){ZnsEWIM@8*d zNogjiP@ZXrz-{#^K_6G~5FI9Cs$s8nHJEu-Sxwr$a`s&EQ-cY?bINFgC;aCZwDBv{ZC?(QzZEoiU=32wn50fIwt zhd=`4R@UD8taabLr=9m+wfaF7e67tfm~)Ok#_Y3?HfEjAT)JdZ_l#B5A5^U9{O2)7 zSf7>`t0oWcNXfZ*!N3%ueO8;HC|J+FZ4aM>;#mA^$)PyneslIs6Av3=1^ zvxg21hki!_e!p!=J;jWnLq%hq3=S~a!t}@?R_g8MwV*EvpZe>I4(1&9qNl?py^F5ez6H=Lid2ui`xQmlw=CvaJjo zpv1LXfs_Y0b7Lpft07}MVuF_I)8)?9T~OE=gF|pX*T(D0vtUIXby14OqSGD3C5?AT zPHeoZ5!|q*SHx5c!A*T4)O>M{_oF8Rh>Ndmyg54DU`T%?xy#f-)ZctY6td_MKVH<5 zKr>$EB+2BldxDg4#o4ZVe5@IX?($eu%=DR$Q6~RVUX_B5+KW}Vv6F+%}A*<=UR z%Y@x~BPzX-&j+kM>*(o%JJ%#sx<0(OH8NVAHa~HvR`_%=AIv`8=Aq}jME)FBra$S9 z#O{$7TH0juCP^lxQ| zX+LgDRY38#DULm&Hk`AMtc(6p{GCpdpXHR!xd3;J1!|vK81_D;9;l!7;f5}-UdKXI zVDZIooJncjsqil;li2nH!vfV!Ay-NTiWAsau+)-ID%;LgGdkjO{@hC;ob5s*vqL6}lbbn0MnAKR5H=n4 z$PvMH-|apwkDL;g8Lh?rP!BYt4@StSd_xYLJ{6&GnHd_CAQDw5m+kl-8y|nHoLd&; z5{Q961BBorUqE4}!UZ949+)^_<}wh39|pbrnlBHKCm_Ho7-7uV-(mJIR_x>31ZLTN zT=um74?cE?2n~UBVq^er1msfN_?_i%TtyRYbj$EibHs_`CaT8ds;74a2(E^pr-{O( zAWF~;2PNrMe2?#QyXQq`hHJSmVX(#0w`-XqW?9LY5+0JjpA572t|XCKzL~yc!qHvp z6#eAahU#M1;e0d{U3qegbJpe4nRK>CgY@C?CGXai77lJBo^ohISokPXw#Wx&3zF+6 zr=tZ1Y%7M-$!Sc@ov#=ozIovoXwV1N(I%ReB;xJGA&pU|(aSrGR-bp6RuGt7$pj(~`i!iwG|WAiQw+w-^4R-mVvk(gM``9Fo0iTen15 zeVE%UrvOUeI18Z2l%;Ila;sT4&-dv2A<_Jm8RlzuD%w?no{4YvY{I@Lp1H=I^-|%u zxadA`bUA6ywJfK$5t2?yV@hoDJCYu|1%4~rqbApy(?F&Adi8^Cqogu|+j_PQvZ zmPL|Fb8KC)es-yd((v-s(H*jfye(6oFJ6h@M?3`Us!t{IIocIIF~o$9Fr`WMbX$qM zEwAjbJaY$a_Zg$lyGFp~g;J%y>O@N9zY|_#f2FE;zmt#txn@nb_D7x9P@jWwFn%w% zRgYSJ=(v6rJ|DeUWEu=MJ3!^3fFa3}H%S-~yXe{rCDJD>iu%c+ez*L7xr6uYt1j;E z2#i7GbNbsl_LR0Q0D>qABMQn{q+$Ofe({Jc!Fm4R5TQ!F75?~V7%}7MpGgIXM)Y&( z0X(~In+4G2NCWLDd;o+M%7>)Qrxw>UglS2}%)FvXuAw%*qKJWvUKq zMW0CazAdv}bDR_X%4pDU9%t!E(Y~|SP~aH#J1Ucog=(M5NI1u-6hq)%(pXsKsS>)r z*HXIs%m#yKm`L{V=(BFCtmU7 zUYk~-D>>>f_UsX1uzz$J*G{CVH?*V@QmWhpSqW+0E?FcRyluTk3XK;{g~E;LUEM8- z!dpGA(eqQ=+v4V#6w&vIS3)o)*+8!S+rt-bPeH4|ZRv#y4b}GBZj95{%9M6yZ{|%M zb`!ihh5LPbGj}i21SHz|)pX4b=`@%l>KcwF+mv=4e z4p17?awPjur2H1I%P^MfH*Y88msN1crl6vF!k7OId0Xvx!<*PgAo2B~XlK;uixh}R zYj1>LHbD@Bag!aYgY4HBcgWND&OYaigDdVDO!YnB22&IxpZodefY_iUI-O$|<5VG~ znpU3A@bJj5(vMtpGk&W$yC0DTC8~;$UNSxeXq{9xKN0>kKwNejj%#yjWa9Ddn=+{V z6)p|k)&&~Ys?_%k_JxEvW|$g=*Et%P4*u-7eKgAGW& z#WmB-=lZb=bn9lECt7j1*^4LPGkCL!){owjef!4R3qf@*Sp%$hYC}kgI|wkg>ueTh zo5aL_CMCLh;cv<(3c-5~viH3OHY={q3a=t*6Bjo|L%YZJXA;Cblb^10XC%HA6I-K& zd8g264@q*N;N5da;vC`>AkR{8%+L3#QHprKKZ49LTHYXJa`qb^{A9H6zu-*AKV zS<a#_4#YO zmIVcx--H>mQP6MoUlE{H8Y&ph4ZYEIIT0d<&?oQqD6y4O+S`iE2P{uE{}`576=&l| zDX`KYuQg`Itf_3r#K(zwa-YeRA&WI2$|~pm=3*eBwu6+RZF-U+ZxT&dnr} zyc9-(IkcbJUWYw5HycjFr3r(*KYBzOcb;wiJf{-gLP_?0n!4;Z^myiER7rV zTST<57<@5?te|WDdZY1-E(^fRaYjPR@%5AJy2S!|)yJBRx4Wuwo@^`TibO$zXCg6( zX2*r_xNRNI8?%0?MUcB}y3DuOW^aUe<{;}!^k5iIT(U%3mA5~0`~e{3{R14ZQzNTp zDE*1*JLQ61;zHYh3Ix+f&yMv{7+pNK)9mnX{;^ru4T(X_De+oX6iE~CVK>;vIS~{z zhGDH}P0`+j>NbM=7k=nQ80z@1VDrb$e^r1nc%+`WVMP@D2S6al_vUhSqn`q*`r++K zpJ6E*6+T+%l@v!PE-gWt1z#hPX$jKAeJG?lHHy7PGq{(TczUCCb8?KvC}uvfM{svO zIQGr231A_5`Dqy)RbI8mX8FRV?M6?gp}0bAeNhF}Xj1!>P>ZZJ9^0e>=z5wtTE3WK zAkFK4I~$COkarP;0b&V-J($Z(wlg%iaqYN2gU|pB1ThngE|tYH@c-EOk&$@+ag_My zItSOP33dMT$>fcm+eiimDc7$z*0knZZ&Dtk zef!$ph$jTwHxtn&34T~@KWko}ozh}xazc6RRBPOnpttW;hiq!nyM-#|rK(vw6i+Qu zkisL#r)Zp;Mws%F+Ny_xV5;ep7!nx?u`kV+J`V!cxpI+p8l%)wH`EK|*87ARO!``e zRL^d@S~vhH^lilyuxVCzMpWZk|afUFnnP~{& zN0}}K^H5VPdK&UrnZXlFqlUH`Q&?M{14qiMhI1+rSN zoVHx}d~4_!(`0nvd1qDLus@>&O$9d>hSPe-jDHh0!wRf%lt}<6UQ00mfN>Av_c2mg zyx#-CY4d+xvzf|&9zpx(Lf8fAACC0qTukt8mmtlt$F^|?4aW&%6l$ZWYtu~Ti2Qkg zIUY~_Gr=zai@xR&tqAQtN?;LP2-vi*<aTB zw%4iWO?iSljQq1S#iabS!e8*I$XvWBL9W}o5j`aWavrbmTL(CXF{pKY3i%I`OIpK< zhr}7CtF?PE^p5)eQX2P?+zpQ;{VBP%EjB}6qUXPrZ;C#GegS$lOOs&-_t)bKj*yq(&K9A`GVj*<==IeK}CWAmU~`#AU;JyLA&j%EFxF;0bTgHv6oDBw*htsMvw7DU~im65(OVnzQ`IrdqC zgYNCRP_04c1+JJnp+FyA&?joshNms)O@uatOxsCoQPKE@kUl5M=zTbWed zS)1g$yUuRLz|tW+Kw!*z{WV6vl2Qpo7!BgRrQeKTzciKpLQR^8 z6zCN)eb8=kD?~Q<-jAgC9H)ESv|lhAu3ns9D0+-u08>dMIxTJTPyH=cFa z6$R!pO@3^l;zhnJA=+pgHmkm4YQ@KUxv-}M)5P`3&MRuUBz#&uv6HNwhG?;Hkuqqe z%q2SY3KuG9S;ERkhX_q+QhB1veucYqe+az9$;>O)xYTB~SY6}p@x}-e(0^*$&nHs! z*fD)k!mC7Kbn+5mnEjLIWK!F96t%E+McVlq?y8Qy2I3?e$x5fC0mEt!I-^URDi9V-GgYW?YX6NnJHTZF{d>q(Sofd)B5QmM@NE4(0fZQ3|bv z{mraZmak?iJR`f0(&&g3KN!!8jY@%qPSXE2Pr_7XjYs?c3z^pgG zLEKAms(Zvbb@p~or|Ujy3qN#U5bM{tHqQFg*|!u!{#QL#uAM{!Qk-RAnN73an$FWq zZM%E4^NG8%=j%Q(JH(uI)Uyqp1#7X17%%HrcWj2ju-G}{4fF(b+!!wNEGUkklv66L z4SI%X_L$SNzNS(-pZ&JZuPG-)-^+uUbU2c$=%35azksO_Kv%Fq)L^Quss(#?d|6cP zu~La~Wa&*=qxj9OWN7A!>|r|j-m}^G4R(DYwP)*gcK6T!DZ zKS`WDabR}Yx<9{bGM0(8&OvQc#7$`%Aqk3k3GuD$VO!7Y4D>Qp9>`Ze07~$)0S}5I zIb^DcmAI{VW33=DO_KiM6sQY^d_8e3ZQ+7Lj#0_t4@v=;0vL&j<@&e4#Jus{wKM8b zndyd12>hJEnNQK&F_Z!H=$vVv{i!J{@cgYO=a+}$?a{JOLW2?$yI*%r4Z=hd8quSG zeEa%Yic}KoSH~PzjjFjA8@zLg&}?l6B4PHYG+K9#0|A_`+eXcb?_}R{>tmp`B61Bf zP#)~>vm}I|&Od0pNF!mBfLdTBGC)`+iv$RE;R4t+}|pCz2k&0_IL_zW)F zppvNmB63w3EXRh1xREEkyC?IK;XOiV=4p)&pR2@J6j7Hk?&qf4NV)3k+&JsW1$6cy zjT+?owM{R1>z;(8>FPT9@1t+QZ5*m~fdABeEy-~JRAZA@_KZr#IrWt217U=8aK^*Q zsg{;`!<9O#lPv8El! zdX51A2_u}t0?Lzu{(aE)Z?Y`_;NcRP5#u5n7$8gt zx$(948LishbhpOH9P@Wh7UWNDe9DV1rrejL#tAL4<<#BzFtj1;3@5I4CK3De#d}~& zB4`r3{FPw*wgppVL{_LI_w@H1gN0034rBF*n~~z>-4T(7nZ@0DVrZr4px*e`Na6XP z9<;wWTuXR6Tl9V^(sK83{1CDg_+W(JndL@&DJffqyq$BAx77S}%^}WpnFsom{Q!us zzXZQ&xW0Ei4R%T?xVD~}2vCtgh1ko=*R8nBXT{UWPpq~=z3kM1U5rAt7;j90oN`I7@{@T@I-~d7z z=ReyUfLehxii-Lk6V8yk$OdXc&TAfzEQ7(omIRY&`I#`IJ?NBHF^2tZDoLz zD5)M5Wl{;B81@PUN1Q8+c+pjsK`rFVEkKZz-~vE+kRIQ=E?%q)e0B7=7`VaF;IE?a zwCP&^-S!30wL6){z+f}hid*ak?IDcnM;P^YTJ*;dGECS%3_?L$YKA&sf^KX9E1bEzG5N_&}+(NFHI-lhVTKNb-Ej0}dR+Pw$vFA)X5{7zGyZ)wUSvnR+_}$G4 zshLWhkJYKx@`O}CFk?H|tpeHh8mgIqbqAQ`Citp<9E^sr?&8f15be@cbtu%5> z+yMboek6+2bNWFYg+Be2{NHc^T;e>jpD_;xk0J|H(4<}jbV8UxVwm@W`EZD;*fA7Ik%dRfI)^ws;W^U+yp=c z3Y@F(b8q?SrNZ{EXDm#OkcWUzDO7Yf`uzRwSU)Na->b7kFFiQw;-q|#JnqIh`?ur9 z{+=hO-+{XuBr}Asz&-y^T6T#xZtLey7tA1itJVLY~U^)cBOrFKXCC&U4 zI4`f`80Q|N40O}NcHZ1&8JI4vq)3GlQq(o-61%V(JhDI>tJTwoete9Oubb;u)x4U_ zcLE&=dU6K+;U!yUi=8j~t5X}JgP&;8ck?B_)n-HF2ku6Smm7R*OpNwa zmE<|rMp%lM1K*eakHlKaf-V+*mp+rio6>Eslv(Hn0)CJWg!ANvwKqf%>r`)j(t-+c zKCX&uXc*4jQdb4oM#hs=Y6ucYITjW?ryXNnh&`V$jEboPnzH2-=1 zqjSW6Hb2ZiDc7*B=HwB@_EMRFWF%>`Mi8YTLC^C}BL!U610A-rl<9_@eo+3|vYIBh z9DoLQ7i9&v=_N&}C>iIyui}qLjc^CC1iZ5n<$TeDm4y=;HE27cd}mwu8^>W+baIWR zcDS(YY%KbI{oGc>$#Hk&$hGR;$_8zX{=Eh1Kp)+YJK`aXZw>w?<`kWonXVd5p9@7I zNw1MRUfMVND-)2S&emj<*HjtiwtvANi9IuDg#7 zm6^Cm_z1OKd8T_tp0^0~9&vfSA276Gb*$P9#Tc6 z^XcZjL&nzkVaSw!PJir>ZTeO|f(`>W^nTu5O)nVCWS0^M})wKQrpl0RA*VUlH!j^@q@kL zYU|KcfT85~R|+FL{m8`oGz|csGpYWo{bW!iW1G)Sb+$-7zB-BcVh7QY?w9@TItBGr z*%GS$6Yey(3+L%hEUM~nu*iR@9$ar6JZcfDsbQ}bkQotb* z-kkNp-J$LED99dtf>2IQIj!Ot2>k9E$-2J|5;WF|y_t#eadLOjfW$5KW6)MtXHerp z*imdwK+T65AC+?rfvE~fnH8)js7|n5v>|Z!UmqY4TcB`RHV1R)idxj|l170U06k%2 zM7sD8zWxF98am;YBPBv&$y7j1bdD+89l;CZgQtZHA6Tb@?OHV?YFfTirBHqs3;qcu zl$j#a`A%ejewT_9M~`=>QaV{IDeXhN@r1()GdQERlkU(<#Q(jPg&S}0=!8Zw<&HS6 z_#3r_MlRC=4o0MXH*%Q_rjel=xwJR54UuYccI{jlzAQ73ITtTuN1J9eeieN9X_m*G zTrT)z@r6wImqNXuEqzrp0Dq|amjbH46taI;m(RyDsEZ;DHEc)&Yd8_5N5C4*PCv-EL?Lw#b zEVf-?-7)_FUw-V|q5m!GCND@F6n`mGUCi6TDLdf#oT{M!=Bg>Y!1VIb5&t5tV3{%s zdp{sAFIn(e+&S>zHW+8KdQ%73&A5fuBk11fUtbLA`fOQFL!3ay{#p{z&kH{&KEJ_M zX8tAOMv))$@*6#)nij$g5Ie$F$G>g;Tf6}(KSc|>Vmp&IQ3Jq;3Grk^28FT}4ezF& zca#mi5IzZ@MJO4SmWkZli2ly05)QrVwUlk_(R|;a)_-;VPN$jQvyrbLRXwQ0fUW<@ z#+G%JwA6)SbiT5d6GYSEGaUcPI`+U?A&Z6Dr7k1P;peEV==7ErZRR zZI&IT)GFz!2hXy(0J`jUDI{TM6V+IyiB}7AJf)lYyrREWknIP|%ZNLEq@(4lmQp(3i>zwQz>p$Sqrir{5(EG`M@JzBrTGE>)Nb>xr zYxmQ@U`6|<$0vkHjEpsOEMYqXTx50+a|x^UtfB9>yqC;eypo2%9Afv;N@NAE&gAuq zw6ufp=e=T*Jai~}TY^sRtIMO`clM8-2}=}xIe!)?GG_0({#zzxRoJkA)QIq^{kM@a zvQH>YN9}eJL)&Q3X)Ow~p{Z1|>!rts;q0{n;LOi>FlV2dc=Oq@yxlbME3WaVM?=Wy z+qurWw{G#fF&Smfi(0ks-(;0i?B|*K{b(8L;fFi^RP}iO?42g>OF*ThRHUm?GQo;R zE%SJ+tFQHTyFEv0jW@x!JaV7;IF3p$A-r42QA6QJL>1`7BXBd1y(|=i?9UspIXi?%bufjWF z9NO!{i*>4-ev#g~c=7HI1HO06WyA1PZR$X=>aaRLO1`Irw$xr+2B%pZ%a`!7 z_mh#AQLft>SR`)M_l1Vc>mneH?C`09wv4N}jUUz-7enhUq}d6M$8yk_@vL>*ZqtWp z%q70k91o;lZwH2;Z>yQqXq}z&w99lVWjA&hOKxfJ%uWq6SQ2)n%@q(!{YWa$;P8I} z34atah3gr8#pytA4M%7dyfv0n(JOc&qcn7yjbwQDGS z3G#D)VMm>Q6)dn@N#mxS#@Ay*YxJo`*P=W1=?ID>@w7%^Zc-7s?!tnM{e2;3 z$r*Q4j(X0?y|o&d!+O-sQ&Okd0FYA4Ida!=dT${n!B6sQ)~WlC>{2^qWo8bR{x*Y8 z3=%+z#{A*5Q$c*E)k$`)`u7l&=u_fCOH$+R^pi@{uB=S zO81Xocf00t1+KF$PLzRZg1q3@HfiY+7+`sHd(-BeGrum7s4gDC2`WDg1A9}WTKSyca5 z3GQEl-~Tt+OErMl$#O-U($y9~h)8j0S>TtWq4F7SXDUvqNdDr}PZML7mUbhGJN$l*q}RPeo5+O$A1z zy+t|8yF*nK=*0&(X7_$zt&0v{<4f$r-4 zLy69J#*d=i?n;4z&pifTIq^kytWVJd1>_7F2+WkSjunn&(+U|BmGUC{z6lz#$G#;_nRiFYR`bp@^o8r#vlD zt-yFO9J_$KR1=ri*{hsXYGmudlcq;uP8Grsl;SVnws*snuqxuxLLcv-P|1C$Ve1K39lljHAU{!Pt8sAmF)fnfko_n%7u9NlQYn~~0GfeHGmV6F&oFL3*-5sPNciqJc1h~_keZWM`4uOB7m}9GfC%fPzF{!e z>xe6)h?5unn`1r5b9)$gD4}H^d4m`2D;MKX(Wk?BX#t=*+)j??BAuh*!SFZdRMG?~ zBP}+CZvJy}$UbBirDefF3qUPF_?<&4%Zm9Aui`Jj@Nc~Ezul>0T(>w;V%UCof#x@z zww})C5UGXaY`rj+-WV#WETN59k`UlA{6ec)7NInI5RMA@qA4Xjwm)%!?i4$kt4QdL zX6Ce5LpLN{yMrV36WdU}3;XaT$t_t!Pg>y^>7$I~_@0S{@L3WfSa(;$45F2W;Dk2> zeR9iVXw~$~-r*{L276cL#URtEWWoF+gGX=XnFg7~Wc8y@Ygc1CTQFpWpsR%SXK1C& z+Ow5<5$uB_i;U4Kw?88MWz{dfL#e_-VoA7i>}}MxX?W+`o1Tnd@SEv(=b}jp30A6W zyRJL9%LxUAG>T{OFtk6x4IBKq?}g_KuJSq7C8>1U3bU2Y&2|u8aM!0ca!1mz)@{vp zN?EIQ082E;|~9{<|;eG%fko6l%;6gz%f zE~3)qB#qblf#Qhi{(wCOuPF(-lzvS4Rky;%H?^$Wl})nVWE|tmlUO^-{jW_kx+oeF z1v}nly)S3##+s+^%uG52RG3sT^Q#ARe=2}TC57CGn@UrE$*sQ&Q^ZBa9Q-xJcbOwI z`b4ULv*Bd^a<{J6jMJU`%P_UPuU-9TioG&c~nfQ#H2PJ~y1B)dnMGFh_huutWGGmJ~ z6puJ4Bdvz^O~-H+jpj&pr#GU_mOZ_}bz$s+C+t(Pr)LsKWPT+bx4Pq4FpRm_9&~4& zL9Zx@v>NsdY7%-Ev@N;w5wsRVl95Q1!$jt6 zvK>xqiu|Sv$g6X&|8tq&_q2mIs!v+q8uCxI?S}2-ny}@kS@xkwcbgk>@i4LbV{5~v z#seoMG*nJ8SRfF~0i4+%{)y{f`qZ6T#>E8OiO>q_STfcVViw8yoGveoN#w&r<#!20 zX;bGs*fRQZS?yK~z?E&oONB_9Vl2xa1MxK8d>1}B=Yg7B)Q!)<5%?NID$k+%KZm{l zgIbgNtTY(v6KJ;afqh9!aG?*gOlW{&sI9#0mHaP90t?~jdF%VZB@ls@-_NVCt-N=hu&q0C8rz#6-RYv=gNF9d>z+6v~ zZb}6F?p^v@kxVm-qat@@x^P-s?%BX2dGxTo@ei2Y0fzHjWk{QEPBcj8iyw-KCy>Hn z8r;7vD)%On7p*;Y%H1*HrE6io3s(CQj!iVB6-OpW5b$z357cy661}* zGdHA&uc>q7CeyMk;4qU4({w`sqCL&X1<4S(aJj3&$bupjDP>gOqzvMMn6jUuCxki@ z%PaCBU*ddt7%2cc{veq)P@Y@NKm75x8m3}QEaF7^U-fdIiIFnggr@F4pEbIf(<_6d z-g{R91TY1LCvNKFm_xNogX!I<8YkZ~sp2tw&qdUQQB5}re@$_tv79?R9=mTL6IzV(iXNr>(0X<$efE0@TllW8$rAE7O^a9PddGweymBK0rm@2Bt0XGA40h!H=X-k zne7IYJ)sRNGiywp!|Td8l}b1j>X4M-LTXAa&l@F9CqtU(XNfZPYck$PcKf7+G$-OY z_wC6!+8O{z7Hmc9tZSJ7Or>zbI<#R%SEnZDD;LD6_c0tXYef)-9{va60H8ASKZfQ; z05ORo1%HXQ|1k~8GQH{Yne5SuXO!OufCRG%K&sX`x4->d&ab`)UqQa-(OWd|b|_Bx zp7$tl%#6t58Hp#aY>WyI4?(MD6Bw!%liOu-^sBqHlP8)ES{SwFAf&W8Xcu)sK$5GE zXI~fR#@v{E+n!~fs3_?gp)+aC?#u}{BGhZ)OXm4{P3gb}O>?`Avq)w$pOUtmGvHcl z@OmJ|yeGWwtv7!cQzt8X}yZWh+|?#7{>>WKb`qA8!f;DyEc+o>Zk$&|c$ zO_D@^LIj~%Mg3Mcw(M=+hPy;d%oIchk|L zK5!Me2+^}!Ss8{8(gL#1vM_)f2qHJXeZ;mta6?a+!RI{&Kl6T=_;qb;jQ(xkld#&^ zO&Ob3nyo$gSFqx)fS{R~mqbl%D350@1~&{m_2cn(vG1Fe^gIL}Eo9Yr(v5m=hhI!g}wnV)TK0M1r@(=qhTA8-D4|&=h#)IDE8x;sNd~Rr6d$Q-%x? zQPir+%9=B^SNy?7V|@~pgES#Wk0^ajOulCzdNLtTHJk$m_2p{&a=ge$jSS-W=n8=R zQ1 z&!0`;R}dRWH)2jgS|@x%NqGRqi-4yY6nM5LX@Paf8Nx3P$}Gsi@@rQR(g^*)E<~?o zFg0sZA5Q$BM1NYOY1CFszQBvG`YX_&CBfY^3ZvKZTSfQ`zO#CP#YcLF10g%>UxSU` zdsV)Gjkdj_fDzyBeGYJZK7@~g`&G@H7{g`V+#)0Hr6sV|zD^8j;4Y`}&x^AsjfZhQ zZSH9N{C;31QJG7oqZ-?xF5Y)FrK*l&pm&b;q&H|X)9&3TVZvN_!(sdvfvrq|Xn|zo z=$G=kg1ZI@&Z_H<$@&y*#qY&oni_^hDn0vH2j88F+2tXNIEa=@t`=H2_mOsQUGqlL zc=wa77f4b&zRV>>peH*r#N?s7^<&hW;IJlz*J%0_5beuZ$Dn+04Od`7@{-!!Nq*IqHR;&eSS;t{bcbjx=Qxt`MUycRuy*|y3gY&0mKx3 zC=t5Ij^5q2F4|`p>f@h>g1XAUCGJOTuHt7**D{1Zw+o(QVcXAcXgzdLw0<^mQ#bBl zVtq%ayY1)vB(2geY;2$D`QAetF~f>f?Aadq$JXBS^k;nP(>%7aWyvZ@uO#TO*qf{@ zc@ng7S)|{p#H^#*TtULc%!>U2f8Y_mxhUFt??wMUL3}o}x9tm|!_>9s&)U6YS`M2& zaQ$-{9rf8%hQ|=u3U%}0gr0m0FN;QuUA0GgyS;aKT!;tsBE`vyijC{QKS#JBxMt`HYmg z;segNUV^)H3l<}3c$6vN|}F?uR_bj`(0jOK@}-giQk zeIBS1wQ6%S!C~~Wd8z6omG0jmL4ErqTuYJqXz&IF;FFsBV)c#m$&Zt2!;uWX$8gHg z4GvYF*N};GQxrODtQPxy3db!BW@HZWoP0k~v(n}@3!zU-a%#_;c$W*4$z#9BMJRNy z((+^`5_#22G-^DNx`jf1nSW$GvL}`$Q=4;nr(-+#GKo?b^GE7C^jwLMeyWe@c{4*5 z{uX*bj7&ih#&aUhOu~vzQ)D#pDFvhMRtyn?#BexZ4Fmq7o`)#^1L6Fiom!wg|57+d zYQ6X^yie>h`6s$MSg@G!2F=>z2n$X=*p_U;$Q|0iI?rM)XfZN9t+zaPm5XUp?$c~< zg|ys+(22{}>fyz{xQrF-0*Q@A2DN+-^mQ6bi{vlignNcTRH1nyYUO*^E{j-LvN|u& zosB<;Y!S6Y3+2P^DKu3}Wrbx>RH}1*+U&|6BW8$*kdHR}RET6INy&JfD{YwP6DD8Vi<7We0(w%ENY+U4UOXM90h>Dd zk9`g3H%5z8;yCNAsJ;n>BOZ+fQH+;J_mm;-(*^`^ynL2~OGs^X>5_P*qaH|7L|yEM z`;0$bHZN`L4cbeDO%er_L6raxX?uBe8m@k#Mr56=MiLwH5NI6?KoAG(AXS86{|2pp zTJZf{t)kHYQ)auURZfsUH2_8c#sZ)Wqss-@O2oCuum1Q-Eq$d@cg8d*ri??n15f&o zxu1wR#!a;*e)?qmyi=F0C+*uB1>=KZoNi=Y-ANR(8>H{gF`gZhlFz~D#HfX6JwWw* zB4+Lc!0T{Q>GJMhUtMN0V-BUIO6SZ|30r1c&##S2PhXp2?}w6*)-69ycUjcmB}v(AxwZEs_fiAmzS zoA?!LAJQaz;jBW4N^$Turnoy6eAqabbYbQ`>_jcHJvECX-5OJCZ*F6ULvg7x1%zOL zOb-I5$Vz2}BG^8Lh!+B={5Lq|o6zFk^m4iT@R;EAPf7yayta-vt#l(7)!&<^?vSo7D-$b*UR zXTH7GNSO8!Q_FJM8Z&%PDVj9G6hd+73Y~P3wXuFp!p5aScVG1Di=qaT#{Vp5S^?i1FDJdO2N#3uT zPePS9axG$|%(Kmboh*->!LZY$V~iY9VGb@p0M*{e?&^~`H#1fMX`{L9us{AI%v6m<>(-^nO{TkXb*Zr%lt9CG#Q zig*{L6Np*62o*#R2A#&O5%yIyeP|lEA8p*AJPWdqk%_95+nf)-(s#n*8TK%hPy)_` z*r2pm?>Vfx3!F$Y$Q5k&#Cis9X|vuDDkKwc&pV80j)iFSOmG^%b@Yf=xY|@sRW?PQ zjrF>h?Y51)#JgAzT~46*jTNiYI&1#*R__<7kLmkMwpTnA?M31ejQzuirCA`A7t8TK zL52UF^D=#d`tER#xqaXqWhe>&Og!;iKuBNnUQPPxZ^vf6ry_74t1fq`#&e|o2y*b0 zl$AFYzimE0-s^7u7;X()1BO_X^p9Og7*vBs5j3e_q(C#V=IO_l1VRY)5^R@ zwNXQztQ<{gickb0NKz%wtWh$O&!Bpbf5!cYvmX##=xJWJ3zEnZbUlg#=7khG@TQJV55hC-3pg*X1>< zh5;{iH1YUqEjz0gf6A%G`M9DthaDQKGvkAkKwI>vBBbbv;POJA;lk$c0;MrTOwG>A zqjg14Ohn}x7zO2}LjNnA1OH@}{8`d}-pJtsDTwq10>%o}g%NEs2tc$jcqD5{L0!d% z0<+kUdf+HO+p+qPo`P*mvt90JGrP4?zNOcQIptoY-5Fdxy6xkU=gfyt)Dxjjf?UEQ z2N_5(N1A}b%PwI$SR6sFj#g&T`munrn|`gtO(G82+m$Ig?Z)ScuwC^FqSyd z)6>#|L$KO3UrxHLJcg411vdRZ3txLf_IaxU!6*^(N?p|?{B{Lpp?E~}i3mQpvTQLU zl)g_Pf`b;EZAMDFEf)b7fCG4w5EzKh762mzbpJ>#r8@pS%>UwaKnk(|VE!<}1pqK! z1E3o~w}0wroImu67ZrGfGCly2vP3R<-Aaa8pm@{a!<`an5Fk4p@OTXwSt2aJV(aE9 zNl>Kbj9?ia+KHoAsN`;wJFz7zASaBImyGG(T4w1rO3}4i4v@xq56c5L7OxrL3p=LC zA1(Av1UIi6E5^HQc=SLUvY}B7o0xIij{`%)ql|DS{}*5H9OOyVbPfL6n6@=-+qP}n zwlQtnwrx$@w(Xv_?cRQ#_x*PN*w~GzsHhupqvB>%p1N6CndkJux{819TW2}ZH%Nx> zQKy5C5FHEg0z^zjDny|*q$O)X=fP(I6vilT{>mVZG`z$BDEA-u(+FfF|Ig>{fA*38 zS0%>RVI2>t8!WxdSJKVD>E<}XkpDYB_FumP_FZD>h|SZl#ZR8Z2$hu$3*}%iuWA8c z=rkFDnPsHI3NK$ z-x9!iPd&R+CWy+^{uUlY&Zh;7h_o0`{KqY5L*0lK+Vf;JLnT_2I0?b)r8_Fn7P>Jv zx*~5H?0N3(AOHC;B#6TDLz;nDPN6|P{DZGu22ix=`fC6q^Z9|f@BRlIx!ZXFWynM@ z*{sT$*PxYN_n@OmZc{il+WsYzd<{;|LS4&tYOOUUb{PAr&+P?w(QZ&67JAC5 zC_t?Lk5^m^dwlBzMRK+g6a3$YK7Jwg9Ljp@dLR2fk$kbugr=Rci8!5#3u;#Dg;|P0UQ5a@{-t`Z+DTqaOIMl&_a#MSQ{2-A3@eHq{ z$+uoh!#VXC13-WOm>dU`Q~bZt+m8)s`v0{A1ZX&5FBxN^_kTwJJzG0m0pOkGF#Q1O z58%A|6#tzG_XU#<9-VzW4ZK}~a)Xiw6!2eRCFGw#8-m)8aP{^y$aW$M3ula}0P0uj#MK_#EZHkG^uKpgsqB#Tdx+QJQB=e+z`Wy)b~A?(kx zk*clxQ~L4{Xq=}Cd|ZJ&k}&{amHHq~HsxD&y5w5wK)cn45gV#02B-NIQOi81I%SOr z;!1CZc+c$%qDYdeWmdXSgM&!9X8j_sy3>e0rfXsP6RS7Q*dS_%*rJ)>T6};)s_3Lg z`5q%@IkvvS)eFm;+})5}u;6Rs{PB3oC|1T7=#GCKds3pGG3x5u%`Qd?MRGtA3DZUK zRo`Rr0dP2Bml_PQ$6Td5y6`W@7R1!3&x1L=P=~LL2?3Sb`ydnNX@|qXl)>+0``0!d zawp~I*lmPL?w=5D?DR*AX&obLz`&z+kr4h|MOtT5Qsr!f#IuZ&FIVz5xzr2Dd|8pX zU_P}}Ne-7*4u1TO^)R+qQ6$Eb*i>8?B)xl^A~eL>nuTP$o#NM)t=+t^)|dg576|uo zOIO6_vTwVs#M+Kj1afP1-(|t+B~`+$CwU`mMK&4Kf91RRgGm!AEnXk=i?Dly?bY4i z(KPP7`&QB1rMT~zLqX_h1Ijn+;G1J>$|!_5n#~h#{~5t_{c`%=f1fY$>@w$*a6H_)3jCliSMvDKtTvINH*P|f~Zo^2JR1M_gpnFwoND9cSk z^Ex8B`0r8hfcptr65EYD5YqX!mHH5mJJaoe^k-Q~0j>N&8>?oKIvZ0k`(;}4GM`x; z>|1s9s>MZZ)O~1-Cij{LPS?9KG^O0C&hd9nlzZjp;){1tq&a_urMAs9`Eow5Olinb zqjJX=8FtfXzzY$;@8_lOEs#?~{U$vZeOk-Z~C zl^vl4-ksnO!CiY-haQOQP^MhFMfDQ%u zpap0_U)AAn0|H`dME&sG+B2OvtbWnevFkqxWqf{Q?9wk}-7(=JE*m%B+; z;7`CrTnM<}1qW^9+oCQV!2^YuoOj)r@S%!=JFDuyOhb^;>Pmi->Iq3v!hKKTbh#v6 zv*I!h-5Xq(#a9p_$6un}7Z%MRcFS!k6EJ|U`E&YjirFqQsO9hERl?%w*o9Mm+7qH4s6B4BCyG?7r;ISSSUR))9#O!oM?T0 zGsGV>3fB%@exC?%Qa`~`_6aR!W~*n3le2X|%F>he>l8R+3<^@xMrR(q#tpikD^4`3 z(|X$5;1alngM|K%RKSxlJ}>~l=~>0Ay|5?&jt_VQ*g{f6S_uEBQjX=qx;sN=q5%MK z(*hZ-r2l8n(fZ##r{`zIAUKcreXuw^PN?*fgJg|xDOp3xr|F$_|L6nFb7J(ZDpvZH z_j;TrD2=LIUorjFt>DXkcU0fFf2R60V3atJ=b^tX_x3#RMvUwSSd1u^g~KTzC0jgN zAqk%`{r@=CM_&Dv4vLF)`m^;ermR@{p#8oJ7Ntk(F`$!@9*uI8F7oQ2!gXB$;%S0}Gaj1h!R^#%C zuwVPl9zXETif>{#sB&gCxQXgl3Fs%5>E)ge8Us2$7bRR6Z_o9`Tc8d(geYLJC)?gW zltDo5Z|v3Hjcd1#pT&!Sc^{51{>r*XTIwP*B zdAel1z>Z7PBHvmBJ4ylt?QqjtUGUMiT+GlL_gD;mRe2Ls*{Z6z{_bnnMm`R}xS66) znwJP_TcufGQ?eeEea%6K^>W7*J!SC(6+W$E9s^7-LB$>Fn0}bXF`Q>&)tvs(d9X8w z$N~|oX6(mVPaBvPEK?1OZiN%-G@oYr8-uvnPAARD5E!ZY##3jAFGB9}cHZ^ph$JK( zR72_9jvt0nkBxol4jX$2@S~_z9%~E$c@wAW%_}X5l}@KjgL`lgk|?_whrpmWBY}DT zw6TwW(q#6QH6<^rr%dn8_9gdCbVtdu9?JCVIz}ZF5AcF6df!KteoxrMw45^0Ads$X zr7F%wiw+C0pX;Qg(5?8o?zxZ3O#~zS%}RBq^gS&~YnltoK)yA!YN5eA!L{P}CghcX z335{y_Bd4qB2;)kM(&JhB9CNY%P>O^j4!U9_eSWD+uj-JznhHmi!@7mB`wl38VL=f zRMf*wGHc4uzAbB-=RZDE;4= zD3Fw|l**kxupgh_{6dBH++$=3yqbb?33&6CP@tJhCj9_W#YUag zqjX)&#=*uq(rI~~G5ZRlw{AB6eE{``bRNC9awGL3fia%?%Obt$)fzJZF$NXErso+1 z+#*{NYmuPg>an=)l3ISQYa|iN+2@n1&y}yRwt*2+gIm#^BRy^y&SuIQ22U#eMWGuY z7~uhT0zT**)?`}`olJ(mLNnSGyIjxcLvAR7oKJqlh_sU;b2;_r*KX(gdRC{j`PD=h z?XH$F&yojZn2s=|kB9Z|(jWa*okqy-6Q0$dhVUhXslXF-QTUA%$Y??Z4rO6~*)B|- z!f=k=Y0Q8+eAHB|#ICkUu5`q|sL*?9J>@>YaagDMZpQCxc*1c@HHRrs#C!lxqQHo+ z^ms3r1x|eVD&C?b9X*@o0KJRSqNjE$h7;}ZXlFFwCb&7?KoE9@OP zIa)eteU6nI_2n9H54XbvJWF{{ouCwWTy&HnGyc!w6{kp%GpOtq`=s=tE(z)fX{ktE zgDG<~;L&@v6m}|Z>+8P2mVlgELhzK9DeqG_Fz3 zKcUY%unv+neCjr&7nyb|Z#^!p=Rm6o=f(z9l(b;2hxdaoP1X;2{Lf*HH9l zZlk3)J-l4v;vX{o=e^v0)LfG2TV=wPUy>ItHB8%5mE#r^LrLq<0G8tt6nU3=2DE40!&*9zw`MlEJnQkl;n(Y zyL6RR{!KhPZ98@S-gjro&3K{u4n*UBh=3%MqZZ*<>~I1Bj+wtu(fBG1g5#I0yD1$d z+(J$oHZZN+8@!=nW{EK6sf`K7Ujs(qYoIvDFAdXbj#293zUM)j`NW^!%LKfCG4Jr{ zHY{3%?o&oX3%Hg zaqkK0JB?D3@JWHFabcFZb)f3GFxe+tGCfr8(j4p`Uzo{b=s%lol680*?g-Hkiu7=Q zM^(}qBXa@m`)UkT=ey=k03I~3VcVlx3t1Dc>hANKowAL?!Bdu%^|imdwC*bV8W z)&vks@>)X`0M7$!H5VL;#Z?(|E+Z5n*HgOw1vUd@C}~?C*fbSFaJJaLqB~E0ak7@eJk$Dnmk&hyU}Ih8}hAs zo67yjPy&A@JqZJ~1xV#k^=l{fS-!-RN`I7?6~n|FW$AJWOhssQ;w%e3hE))MvGq4P9MIiE1_JX;GKrN=SS~UjpXrW(?;$-t6HbQtM@TOb*#4&!70QgG5dR8XNe1XZ zH19JWEjm@_!{NP@kOySo^qe7$2l^Ng%r-ys){~>&Xl410qx>WyC};G}3I(Ej`z7Jh z9td;q%t(5HZIRxLe&pJL?LuFiG8M3Mcz0F$zPaTN{b^7{KDYzce)ncOz_>{ z6ytM`2^LhQ-Z?a|qf)F<^Z zjIMo^bXeT$Gl0B-gCkKPXx${^5#lSTov}wN8$=%4H~r;w5}!GV&L|3vu!aU_?RXB| zHx=_{AKjl5U`daj)(Elmebb1FuMv#~i>)t8f*cCN@)8gi)M0eR-Pof#xw_K^Rdba( ze{)>!jue*{N@7>ivoP1}`IYLo`aJ(gOP}3&2DDc)jmGnA;|$xH3AZfr?G}qQZVD3s zKZ+B`(AEZ;w|Y!uaia>-f|S-L@Ag-GrVcT5OM;N|uchHg4=ENWRar5D5V=Yr8k1nD z>TXz&hPFOCpJDY83Qh_4ibmZA1PTT2|90PI`BDADZ;uoBv=Fr8K*kLde@I9Oa(jix z+FYPU>-#qXKVb{cqVQ7G1KPA9MlrPZgml^erD4l_58VMbZ)TDVTS-LE0R%pODc5wM9F}ZThS;qb9{Xw{VCoNfgtolJpb{` zhNU$F*d?rrjH938oQV}RqZ0q{3;9=8RL)jPRAc&^U3zsbH%L3)i$dmV!H#BT_p%sK zI+n(IIXHM9Q&za>usdKxTukVL-GJJ!RYs^jw6z#u)|<+aZ5|Yez%rsn{b5KW8le}1+McsdxrS4+0O3KL_bk1oL=B)C zWxboEq8o>aW~?bB=;a<#JjOPz{u8l&;TGoap471O7uzc8w>N{!gga42cZbg}Mhh&J z{5nlbURg?}K!hphZg75*5K5{$tn)CU*qdH&oBW9esD28e;=p@kog}b^Un^l{O`ftc z3s#L8-)IBE4H|YNU(ZMJDp7SqrJZFr`8-&+eZALQA`Dru|Cn({wy>TEY18jE+KctN z*{e=;Rnvv_ZB zvxY(;dIHP#pm6aZ{C85XI%&|`EJw9*M?Hg%?&B#80b)sdhBqlx%sUoDR;4!m)w>Kd zWBR^h%5U$EHI@g?XYwTzrsL2Lj42fhu9ulZL>kN%F1xL6p@PpYF+|K8c&U=vx>0%( z4PnonA{VG)Zi%LIK!t!A@wZ=&_iD{M7?g#}s=WiLJQ7x~1))W6dRcy|{7*98yv;U; zEjXTLR%!er-Rj{06vid)HqK)OvBtkqPBCa{2zZAux{CPbEE5mLG4WC-hB+PGXDmHs zI}38Bb6S40vd`(*0DfLrdEj$ID4Qpk@-tcwkXpMRf)Qy2%Ryxz#6Pcp=cyogzqohC zaupOhp6fOtpk$#od5plIcMM+`FE{hoW?k>85@f`2s-_kL1pk@+LlW5O*NBL382 z3_p%Op=y3!$D>p*hq*)@4klOW{Ya5|N*_M-+SjJ5y+Rb5t%yrHDXA34q_k>SRI>v! zr^Bc)wIq>cVK(G8+Z`eeNi_>|jCy&tCtH9oD(LMbR78B(Mf_e7)A7o~Qg-QrEc*2u z!*wQ@M8qj~M)C2eIpYn!E(NSt>5}0!GfzisqI~wt&5oQ^0?f}clj&E`V^hljcl1Sm z%({;t5rR$F+^Zmg!bEqOSbyiETp3c452KUsfzN&Bv+>8qaXr2XNL(@hcjNH$elRC| z?&<}?G)h8o3Vg1pFk)eiQnm4)Fk24 z;_h&5Xt}PhS4CM#g|_oeHm7)wdRe}$WI{4sCD?#-PLot*ICOU$8D-&BXzUt*Jgx@} z^I}~=$*V@q4T9{=Dvs8P3Y1k0z+H#t9{%a3TtD`I+Njz!#@HZAdcS%*pW4qIy+%gR z=_3(4gB{*4a()tduUb++C=>|q{>?e4PTV6pd{O?BwtLc)^6G5gc;kLhMGQMz`O+Ew zfLbfX_xCJfrW8;Csy$z#l(4n%)s`V0ZGEDdA7~*({8)NT;8x1r{h^v*MI?0yp6c;C zl7|$(NkzXFXdgW{9q-5L*|Z;qLb0Y{F@pZhA@WIjQPZwlw5jo$K)tQ)P~x<<2txi- zGEgcz`(a<0=^4g7*>@8Wn+HOJIOV9J^HEMq9N;-IUoVO^8e*d2boxoiqO zt;S6JPar*ZA6DT^^-We3Ih_3VeZylr*?@#^zRKV^e3wpiQZyw9(1Djz%gtY1EvQoe zG6yfm8a6Mg3O6I}CLOC3-Y@+xE_t2%SIU8?z@UknwbdLqL+YjpT+i~yD5jtA+2{Sy#c3D>J&*$)eOE z$?ON`#kAN%7Fbovay*B2D>3O5>^Mr2#K5MsJ$#0b{;uY*5*!^>xf9HY7w?Uxh-yn) zjV0=qCBEhUbLgxAfoozJ9|Vf!V-Y8CoGZ{nhLko(VU|p)W%}u@B!bw`2Phqtm3G43 zAXk4Aq_jEBz@d2B{4XVU1at6KnGRv~K@bFItSpAsRt-oqo77YjB-;*3c4<5>4)?UA z&-xR#0zK}n+QIOyf#&1drSC#9jvKYAcKWj6UhC|t3GBZcHkBe^+j<*Hoi?tUNYO{} z(>(UbHO-6om+(UY%GzTcZ}yzEvOOQX9-9J}_R8;-RE1I~|*(9}2CgsCfrm>4i zfY8jZb=FZGj_rq?0+;0n0exdfyn#f3Feg~b{%-N5e6w2VfpK3yf{J2qepyTGe>bW5 z^BP-_@HDOOuCFzzX4Dq^_6#M*)+{>!M@Q$4!0?I%8oL?Rt!{fm!0Nyg<*J6STp)a{ z5$5+nYr>7o&}P%Mk6P?xLG2u3?qnfU7yYBsJ*t=Zn()V7zR|h=MYQYD@gDPvKgxm2 zs@0Cf@n)YCA@%o!8=V}hH%yibB>WlydGU-v%j2iPUgu!!c9hr%NnUUwx0cafK8s7K zOrMr>o=#$k+}t!C5GN4BTj(JdW{n|IS4l`xZ#rEK`*Y5lgBc}!NZ(qXU`*7qPjuJB(0Re4VOZ=UpRE`xL$B)$ zRD&tNQ;xi(kWjPhNK_%e$nc@!zT0|C%>(=?vR;*zf2KJe@cQ@;5N4sKHH~BpCj5Hm zAEdi5Faj?dPb5Le?>zX(`QF9=fC?}98sJdsY@aX-rr#LvnU|O$XMy{ma?mz%n-fxZ)ANBOTS8WErTwFe+pn}$h z%&!=!;`Q19?K+l|A#ys!ckC~jMMWMR9b!@~svP}e^DOG^eOrQ1hdXbSXqz}5L}}F> zIklVV(-^4y9>x%SY762v9M=W9NStzVr9vgQmU79H%NF|$1zH0+Qh*T+fK3meDKC~r z0@;w_G2yL1YsIqnr7lm=!i({V)*k|o(!%ej09-&c z4G#@si%d#09NdWP{sx)iY#-x_3`aW$))vF!%vctX{6ROqIM=i>G9r`p;w_9IZKZPE zD=`&m@Gce}sa2QEh?b6X%-l4xe^6G0%HV!2N8BhT8sDKCGeflJwH zsOy$z8!Y*DifmUlbksa>Gt>O^#7x=m>84$&%0dK5;Kx)(rlK#WUxeaT`O8}p@f$ZO zQS&oj#tK9B$nB9DGpnFBpnJ9fO4{BM|L%+Ouk^Sc*1UuCo6^;(tToZNb$7GAMj*5` zS$wRgtSc=|L&&YxO}7bqnFlx55R4q5kyz znQe6}eU!w|Y){S5zv}eh3Cm|kCmY)7sdB-9oc|sk=WpRak)*svfLX)bt()IOfUe8U z!)*X<^(BW=IVJWgU8Kz8W%sBsQWvZOGSRmRz&B#!0ig|*se1v3ydohC<$B?IiLvjA zj8lu7ORV*vePWlZKwuY$G=;LRc=%c%7L%Au{1D2hs;bT_#^yZ#_NwR%9%Huxj3Joh z!qO2{ikWK+Q52E4xQe?pcK=NABo?0#;*Q+|!`nkinMbPL+ziX|yxY%?D0DVwa$GnB zVqK9U`znx#(Av+$Fp(}85^`(hK2yDs-DY101z#A{{zDdLmnM47KqKdehLY;z--;pf z)jz5;o5>AW*@}afi7JDhUBI8Cw!)FgI4Jz#HudGVp}4vCOYy}BM2!!L0p0vnkC=k) zvB2bHuu7vqWo!_ZXH`G*8LASqBHXZ*e?&O`?Eg+ANe$gqQd`i|*lP{3D3K>_Ra>&( zfZuu+3=dcea2{sb#$iBGC2TM7m*G+ z$$;W0iBif6A5CrVG{sYub9!wpTY%upEXoP+%ep!!q$iB(-6{%hoi7&)?gaqhk;L!l zP6EKXbsuow>wse2TLZye9H8P}e1PewCeWWL%=!I!86%Lg#e*Z_pl>)TM{d^hKBQG- z6s_zVE7|n@;9^+E;*@02ck(iozdVI7Yv+whK70G^d0!PZzSHp$?**6(S&B!?00;@& ziBg$=KMLEaAV?V-(7B2NbG*8*;Y3dHh+>P)@z|XxT9+-O^m$mq>Y^q;Os$S%pCreo z=5&SY*Sk>tPqrqZn<|m$IwL1M-Nl}-S_h*6zwDgHKYlymV2{tZ0n5=t&zv}bvZl+NzTRe#JYiua`eCATwl+iU~}`*h&wh?@3fF1+q;JP*bYo; z6*!8_4bO!vDH1r96PW&VFrQ&mCf@$(33VTMqp_8GR%(Wr2FB2aHPF*MzI2Wb87EN*p-x;PJr!@m2!@Ry3wbvITqT zPkIJzH5(FnL7q4_^-C|!8&hoOL&YxEjcBc~q05~8yzExE38W*dok_mF2ovoCk`UMf zZJ=K$4N1WxsfSzfce*vs38)-CJVSHgE&`^20j8oqO)Z{zz#p}d^;&qTv@a;1!b<|Y zJ!sKPs3#5-YaJ|QoGnJc2 z?ERstN5v{f&ANc+#N3!r>V`%*gg3R?nrNrvt?CIQPr^!}=+WZ(eHt;tT&`uj0!^!> zp{LqygZU}zst%Qqtb_fpL0qxTpY;5ndLm*&?8aN9qvY(yWsi36DKJkPDM2)E4I|zy zRIv(AsDk8Z_m1MseijR>1ZGUAXjcx`NFssY`X$8yUm_Eb(X&PVm^IHsM2)(zSet(2w8rxoL`uepBR9qhzWrfTD}tFjUSK-jTq$_Rt1Julor0;Pe?|!lWMhudkkkWn zLOYAoYP5mHr8_-o)|#905Cu1wbEq>nDoi9@R57pS7Nbw6FgL*JHmtK7l^m8VB$Ps~ zFY9jTXRkVg`D!f*{Q4GiEQM)x!*tCbR{8zhSz+oskJ~-EG%Otx-R!BOFYn3s=dCEk zm2D#n9H}95c&c?|qt>Muh!do56kYsG@VCd%R0`hmkDKQE(Lt`thk9Hm)}<3CveG|v z6{~NqMGta(KKJ*qq|E(8#X0iaGv8PR>M9VaM55>&UYWVC)#*51d>s=vgn#)|+}Ch+ zXY`8Ja60pAcGw=YOnPR2?M%kQ!$8rOu?4vf75IiRSC?KF`BT+KN`g;CHvm%vc^c5a zIxPl>B?_1&i@Zss<5BLPqYcx!Hp5Z&E!D%ajWLa7a2xtpR+#XZ8Qc+I&7Ku_sd;yB zTa}vHw#RwGeW$G>X1yCe_c<3-4`=u^h|2YR)4J(CeuXk++>$373S{|~F!QDh9YFnt zd-Fxj)FPe%m=JVK49m!P{IejgLjQ{SHWZW2z*T|&qveu3z^qzA>?X>rOO*z~H(;>JL^dmWq2L136#8%GNOfRZ0oWlTi3S;& zmhe$J_B&+{*|n7iN%20rmn1u<+AB>Za7b2G7>15S120;zwZQ583mGBB@3=54)_@!Ng{6PYo~~5_rUbBpQD!EF+DAQ}_5ds_Z$o#o(iq7^eusLTl;$ z1x=7@C#nJ$-XCLQf_$&gKLdl?#th2i)8e7U@Qe|tp%2;(wxWo9(|X?wvEbypA?ZJP z@M8X)f^AI*B}_~NmmgylSV5p=>^G6Y)yPvkJILfoL2x{C!6HT+1uHaU{LDdvPF1F_ z5}Qqe)Ho@o!soVYRXSxjDOIqI*=ujBeJaAkg>}h)uU?&^Lwy zB){Tp%jGzi2LMvZZ)v@3$8ilP)_5Cv>hs8MW=XFaB$308&wLVz|vb)%aC3CaRaAXAvxhULXD!!eFgkAl{?+U4Moo zUZHEGN4c!axi(?m9#wx1>UJ^VbSrd&P7@Vf4|#`!+9#YBMoq5vvV7M~ z{JDnLrOAF3br|nvC=O@N;{>0H&F)|&*YqDUd4O}?PvYx{$1_Vrm5-s@zZXKD z5Pz2W_r$v;pF=;X$#9LU@QmAc{4OxCFLiJ1p}saGJ%Wpw6g!Ce?rSMa!(+;3ed%D8 zlU3>r*ojjfzQVe*=E7WwDshSwF>6R^HY-Q&dRqf1yZUBeKfl5`U1|kw{^P3cy;=6F zF#sA`qNZoT`HestWClUIe$Y_$zi5Cl1YPQk5q=G}pA?h^zMV!8m2-sBgFq68)}~tRb_^T` ztqnib03H2%{K# zi;*Rvb_mN{Q-})0g_<6SgEkQd*SQ=jaCgUuQ5-v;v;UR?v; z4HOS>V+ZojqFwXTLU81W(OU_jAefd&o%avTQL>$cM@x6uip}2u)U332Vp2zS7ytegBGKa zDFdnkjL6n)%+n+&RT8Wd7xB|JVI5!+m7P|;JIkf4k9?)qWDpg;Sw3&`Qn3-pFJncM zHA|078qe>4n0bH+#ZKB=36xeK7$X6>h=8H_6CW1z=>y?NI6&TIg{|uLPG;vWEfBzG zUdjXficJrl6P{)@D%)z+zm<=w8knJ!lC9 z1WLSP$be7z2XD_ zcR=$s7H4=|(=!DA03$tcL+y6qPWCL|KhlCAK0oli_@4$R=IqMpK8Chgi$~0aF)xYQ zATUeM1Yqagv49!f$MGum62N1`m@$2N`slZ8+1;nk+?!@sBACkggNmag5DKK1OZkS# zjOnfxDy23G22Mdg)-1|aeBm2MRU9JO@~eva%?uopvNPh0#V(Ce5F0)mu^z;ZUMmGv zb40hLhmFhCh5G`i2#J0VW!1o)Ws;s5tT{mQ!xv-0M&XO%LkI<+&t&C?Oow45sHPzB zBs7WU4Fg zdTOSR4wBog>=k`)0)IFa)QX+=uv2$(T@5U=l3Md7%?Mi1$7yMVCo@laHIB$<1!d~F z6f)8H`aI4yd_PsQ1rcUOXe5iOQWmVUrF8NV9i}kzL4;$#Qt``!+14TyRs7^{b#2Mi7e;O_0}NQTX}5qj9Mn*VnrNA^bB>}X`%|Gm?)dIF{ZNVfs)7bG z|FZ~#8exOH@Yat*+kU?)BIMc zKA*b|>FYy~s<)(qE!YTYV^GRd?-znkxG|Fp7nu>cr54*Sui%M)3eB3wP+!j^M6`Jn zpj_zcV+f)yKAl^vH0~Uc?Z(pe;x4wZmwrgPPf2N`|KhbWT3N8>a{HnOYRI2piVpc;ul}zKl%c| zNl;Swec>Y^ih%}nLf7~u#`B0@v$sM4#31JS&6;=aSf9Hx7C=9Js))70H~qn+{Gyb( zHz{SL;p@GDm&6)*GxaZle9OJqH!}ETr#Qb`iKWAovO^xz&&ti-Q3{YYnEL9gU5sr_ zM;eLQFQ+U*A#^2UHDJAFALtKW48_|1GJe~(#)1fg-X}oWhX5#Z#5pZx4qGs80~-? zt^-&IlvWBhv~PFN`Ey^Nq}@OluJMjk82u5n(xbO?kp1_EVC|V;1P%Vlt}zfx8bm;U zNR$z}yqU57nL~|p*qj;&Hs&1zbwKV!~~Z4DXNoQOIbHl6W=Zw?Ijz_B2thX%K#M^GEwQ>JZ_&5GlblRz|9vL=hH+>i1uBiO>VF zLZ5Y|nE}NH#muOt+()xaDB9;+kV42}0cYTcvQF|MHj}esT4lUS+rP77ihLR*$`O|1 zs%6v%AXQAqGn=VLoN^4ofgU{Jv~$RCEv_ynz&(s0&#z){x>euq_@ zd*l@wk(CMv`_W3BV9>`k2)A;H6P19&Ai!(KdJFC>MKsaiO`^T1s3whux%)v@%Vv2$ zEK?LSozBkff`BqoUoA|G@q1dUkEsU~RO@I2cnik-#ej>opRuogBT1Eq)(Gm_aV67I z%A-DI6(vyncH@zUdVZs18MLPHE?=SS63r9~^I(^*=TG|j`B9pBG@MtsJ9+yU0xb;ozE$dUcDqvj{ah2(AT#-n5yV~kufu{$@^3#=jC%~&jZQEPV}5b(@|0!hv94sMjRIAVxkQ{1akZmTQ+;1d`Mo05|>F3eF#6toexZrdgg=Z+VSp3czUiFwa*+N9WTV;$zcXO3^hI* zm8%*zgsrp~h1XiWOj>?^SmU+dv;>|6NVT&HhBW2K^U3S1TfhL>N@%`w>eijEIvMcfF$nA~_ci}@ zG9)On(TzO$W+HkN^3CVd^_ctHN$UMxZfI{s6Vym;M$G}Jg+jZWEsGGpYkGtf-3+i1 zvJGk-7Q!tAaCm#g!?mP1J+F-#xEYY{6e|ZLfi(zqAYql|z*GeCHA5oZJ%Fj{qqk!I z*rPWK#c?9h&_30Xcf^|dTdN#1Z|DwlxPO_1poao$a+`OH1q{tO-j9mz%HyKsziYCh z;Aw-PiUAEq{lWRbt{#{*Ty3WL)-9d|Tp~y4{^~!D#U$p+JjWzR)`x9@LTXOU;J2aq zO{6HTz?XYcrc4c@a82Jub&=x?h zkgmhMKsSpjuM*46(aMsj41|0clsA%6i)h1KrUK#^l2Lev{y|iZ53|`k5Tfb0JB5Gl zq&toOCobuQNMaVJY8!VdK4|62B?5)P}NOwa4r)Z6^7yK48~|E9b?x*35+2({NXE)ZwD zS;TFA9S1utM|YQy)q_gB%?cl)NM^jo!Tn5L7!rn#y@W!-T*#A~aOgo7hQDB&>0`oPC?sYO zLKoUD_9+-yONC!BID>3S1Iwn2zcpn)G?yQR95K=6i7Awee5V5Cgq*1P=qsi&3Ds#g z6veswQz4sT{Y^jt<{C@s!cDEE^sM?1zDr@3bU!<_fJ1I(+^t%LYkpC1I;Wo8ysM(O z>)>CtaC{HcOvs)}u#t#zbIzpmBi*AT=W&PU>nXsTiGMk)%XE$$XEF(@tABw@D0V z8LwO2klO-*Lh!3ps`>@9mT*C5z0=1Fa{VTV2_J;I-2i}TH)}_Ij4c$6(gvn$VBg*T zSf?$O1OJVPXl_Rf9rSOWu4Jx#)eL5&Cve-()vp?xRElZruhp2FGtngUCIF}sAt_?* zDXyqHFP*vN@s`ns5^o4)Klv>D)Hivdo>lO=kG)Bs=?vN)56jX=j22u&QzPY`Q-sm6 ze2Hf9EsB?RXAUeYFUphLrMX^-yqZf-kq+jxM}&MirwSKCD!}6s$DT1|Q&7A4l$PQHQzJ!|&2J!qKP?C05Oh2~94a|*1(o%k!zd&<6h6K%Xh1e_X zn5(1ukb`bsgy9{C_YI6I()|>N%{(fXq-~T$i+Aql9_|yi=IsupE_D21g&)5?c75_= ziMr?;#ArOT6sK~AgE1WWn!Z{u?X&oru0cWp*o?!HI+F)oc6SZ&{{>V)tG{k-ITHGB zKfjqOhECI~%Cq%*W+s(&5$Jh?PX0G*<&1Ha5m%~V0CC{H-7++JjiGyW6R@Jk^lpL>ATeb<AA1{Z>Kd@!AlMQaUpq1l0Zj>@8`sLDKV5 z+@v?T2HIr)^HPELLp&S(x+#RIPv5C(Zqr5@Z=YqCVd!8GpcG{!*=Luh7HW~j@#=E~ z2&e)(Ub<rN$H$1My82Egw`8RS_UX z;Y#RdRNm|7CuOM~Rp-ZRuQ3x=S$$qY8<%!F%L@%uwsBI$&azW^CGm9bOgAhzQq@l< zS9py7-#;fIAv?Ak;HG3~G?6+y={|815Dx_AhJya7eu3qeXG?-W;JZ9Lr_suUk?oFT zok0PYHsU+v0AN4Cvc+8}*t9D7)|eTrE>zu1nVF4JEi_18i>)6-M^P*cJ1eL8BNQ^6?l{R5n@mZ z+O*51CQMZY=g!B(@TLujXi(emk=k!_XMq7HZuo7PNaaz3R|AtK-3+k=Y{ zt^&!~DVA|{pI-rM@$vrjUBCmh~L z5C!snh9fX2>PLu3JKv+67FD@xTX9%#f&#>sOFU&DZfDHAN2!B@^Wy_ZTHGC?M$VR zIS07qX+q}^qPF;wm{x6)h1N-;#h!Dc(^^naXAh7)(-w-9)Oh-7geR3FZjFJW&1OvV zzE0JNSYVE^*y2b&&{R?_NB(LB>kbOQ2TR#ruYALbR{meC>VxwMJba}EGtn&9KM!QT zY9Yz1h?Pf5Ck|Fycm=G0D!dk@CVqN@+MbdTm1wP^I?6kxB)L2=QpdYS8Kg;RR*a^p(NE$`2RU~uDR(DUhUB!GdJccUqH zil;I5E)kasSb7FhWT7b%25aPgKCJWSTytP!@}6U!cc+n)}sw7jETiguJqy zYwER&S9-ZBQ0b;r}h;J0OfNY^qD$!!Z}AhZ1R zS_o${j!M7?$_%SyI}sgavA5_8jhQ5ap1VpCLo^@~I2}R3I7miqH&es=m;x3xlL~xb z1S|vfI)-snMWWCh;>$`&SL(5YDncW0Xz5v@D6}EI-LbORPfY{HfEd{MgjuB9T+N=K zJ?uJvU3)RNB1O-;nOW2PrnVsCM0Us0J_ruY19wi6D{@*=c^2+2H`PLaVQpX@Z; zjrs-+89AtgVR<~r$*fUi=;mCt{PCZfmQ zWNpxgeEvdT4Nf(pm}O#@zy>i&S;HaU%t>3b&TdIWY<>Gc^NJAHm`T?>B_3YlGR3E? zNh1zXgNUv)m6G3_)lYh~KsF$f3zUmI#7Msv8%*>g<1G0+>P}PzFsq6xR8gHBR7+wv z+e$xxese0OO3fMd8m;T}W$0lGX6IJrw}rltyq8*!GxIW7YmcIEa{q?RKoN4QHc$?2gr5*nzLmMakk{J1`8gp@wH5m%-%pu*T`mTUxh_?g$<1`_AGcZk7fR`_)}oN zUw4wZY7Hx0dKh34P^)8VC;oayPcfEz03|h(xl>K{#+)(}ZxDigr-OAtbS5k`MCf6Y zezGDw`L5T&)Gm^`@gv$6R+xSwzO#I&%F1zSai06`>jk#n6q3t$W}bh(#+;|E|7~Z_ zpeO?211!+MTI~wZcio4_go41Yc(c1H-uE`Ipl0+-O@eew%w?$JkoWH#XjAWMszN8> zX-MNx?8aRIhP8w@xE+kO=$UY~#;%QnMGwIb@-uGQ;^ts(GWfx5>W(g*#>GtzQMDAy zVU{WjYdp^^gg1<6O&zXe&)}?Bl|QAkJYeP{bg^~BK~^w9>2h|ZfKJ(&`kFlEsNEI6 zEom=#_`W~{wu>gA8dVh!uv$g}w7x&=q1G$y0j#%8XW7?@e~P*Cc^bR0!jCe74N=+) z44Hp${{ZPdz76oIa3`a7l@n2tqg<^M{&>t7}9#_&JD$kKZk0|uFgJ} zb6Zw-YU=xUE!9P>7wL_6R?}tF@@g0mW^BE&#|+TW(4~Q>NPG#RnUPu=?~T5dxbuHa z-KDE~a^3Rm@j;Yj*L+#;tvr4`mG@+QGFIn5&N*(u;hp=)x-lCYF4rr}iX<8$J_0CP z6i1)s)&tw)#RL5gyYa|OG`keib@SXlL#sQd>%*Nj8xd!SpnNXe5R-`yU}3COVds#} zZ#We+oQT%rme?+52xQQTEe08kgp-H_mP=0n;Pt&W;H1b*_#b-73Fx;*#X*InBzagRw6Bd(=9WaU(GetJe1 zj_&JPWiRSgicm46KzAW}33W87N$-J0zR+Za50%3{W=R5V%sAsg&5)DOfhK~5vcWzY zS~p@wJWRl-8NNy~+%P_%78k@&w?N2+cWYIYg#mPQ+(z&n;91LDryqQGFTxUjZ%EyJ z-_Jp6p$<&Rl#=_x@k(_C*Y?4YvhPD?Z0$#jMS$pZPoB(Axa>=0DtlH(&y8y7XnMy4 z`9MciZWE6e@fJt(#gaj)nV9mhNWbg9(iIP7@5_@)!)doPW0}<79TzpjHfwDv@VGY_tYo8(0>vP!GJ3=ki|6SPl&?x4$s zFRcJa`K)UQx_KL-Y5>cY1xy|EhEUz>-3mv5|KZ3TlGpPjNpZ1>w#*Y=kx8Ga{K0jL z7=8kZTF$^6HD6<82jF*Z!k7bDJB`{?;`Tl%vsHtO2f==74#+(&MQD};!W5Tc4J{6%_WWICYM*yUZgf{fba9X*XJ$$gS{ z#48PC`|UA?G2pszOrh!eno6ssjlm6CO1bs$!Fgc>ei>u5c(b*SCiy z>5rHgNsPx5gQ6^|>$Z9hoiU_zIdhyNvQ3|w*U0ec+m|G! z>*>G}pZ0QRe$jps6&3pLxA!ALEqZsmc^ z%7bFOB2aW!u@cnPWzziA#WhFmjBl0^Nz0)uU`J_*6gcc7D+Jt_&?&1%NkV^dhiXbI z`WF(JRR!6@P#?Fj;&~y!z}Mu|F3oeA?_Jn=u{PM@`WjfHK6O-s+#N;mZYU)bXcy=2vGf%0Uz{&3uC# z7UO-rxQ7<@YRH1W1mhBQCX2<-8|}~QoD7J1kF~HrnY=@$2AXiy0OU{@mtWu$R%gmy z%hpnJArVY6=x$tLVpvkOiNk-r%jp3dcDqiyI_o5wTx4vXOBts4bt&OZmh zHTRT4K4%&e;E<67)e^nnQlevwzs+>df0Ess$9~QGeW zO=_Con3TJu1N9EYU%7!$feV$rXzPd=wqIzN3?cZEwG+NK2LdHsF`+!YiU#KMxhEHP zrzbRRCOoYhP?~C}<{Vbb98~$tud4_=&h*V+4R+5ZNiqv!O0l+Cfzt=V{qR!CZ@`gy zBK3S1cXq_|IIutC`#?FaHmjnNNobebwN=$7;gD9e;Ncq*`e{fmo|`8}RV+tFnzx%L zn{(@k!fPT!`)?T_bf9_5_k)02G}# z`;xx2WHX)_gMR+QiCGTW?AJ^!f-(WtHks{|{v$>Wpo2kn1V4=oUY3F=^KL?{McMe1 z?YIk<`Qmf$VcqWPD>n90WX&~@^FzNr8yzdMSl?;S^SsST}0v`k&{^4we+*U`_hIgc)sFTxmu3KmF zWyuCdBE%uqWnS=rPd|j_yDxZw4w@^`LW)ybkrT1fqigtCodjv%lLUzEP;>1!%GR8;YPKR-&4m54S zOQP;Jx^2|9$bEBU<8;~$NvGrp~- zH_=+x%*y#)N!nnlcjmu1gM+@d2N?wzq|&-wr4Jv%(r_@koB08VONi#%>`zF3j$HH+ zaVcewAGGvWUWHRxWHKF3xy>iB(v4Rs?KJK-H z8m3_@j?UAEp1$APHU0xJQuI93Y~a&Tqc)?j&T&G@7#lNn`CSZO+^;*y9N@5Mh$mEW z8az|NrbT(RhHKgx^}{tmmV5I>Brxzb?zGFpGTD-++61s$`!y5j=ib6wbwmHiWU2y&m(}EgZ0l{KQGFcn}IhmDthNW|JAz zQuoVAPoJ`7ZXRb)Y_-e7D~Qh0llC8ri?Is0x{i;C%3gJh8}olTj?n0~5XVphyke1tV>T;C=M+>_63Zc#HRAv0aHH+5Yp2J|6`Dt)2uKG#p^@A9 zq(p)Yw3W8resF0MRPKzHXe#(p`4=_i9Q0z{bQ|Q0$8EAn@0jjhQ+ufDTD+igqg`@Q zDRz%YGr%VYrd}XFdrWX{#3N9k7Py?(UQNlVKwWUgprDh_pt`0hqYq8|h1G$*H)PPq z%;J(;^YP}3LCNwjj7;lI&)(a$JJFL*5qw*J*)yH(X11}0U-jefexIOA-NCa+)fR(s z>%(^<%rG+V-KL^(6hD^*Z+E4t5!}40&G)0ecJ#dZE7o7l)FfG2K14ykbQV93n75=S zcuYODRzmNhw5z+1q2hn9AcJIeIs#nWv+8iZo0Lw9D{kX=k{#Da%Dzy}xyaaV_&wit zXPdN}jv#h*OOU_-7?cv~YLPwgy^=}&#@2$4Vef_dVn~D0nC>;YXmpZt$-m|(%LttF zHB)5}{4P~$!z9to3Z}mQb#3oEfF_1`70R910?1bpk`@laoY1e_O6CqNfx-CRDPDt* zgA|P6_H3O7b{t@-enjk|3kN?n`;{AB9273<_7qRIISIymkNe;HsnW7vP2*{T215yLhkGH-U zlQ+~2o**5ly35)E?aBw7O#(;{%ptH1*Lo_cSnc4JkpH7F0CiD`{~)&rbKFCt`ddCJ z>VBGlo0dzlryLVvPqfRM_}N469|(@*t@Xb7TJGn6@5|Rq{ZF~B?#JArkrqEFM%}e< zqXjPi6!keXt~a_bRi>Uo!E;QsFE2iOE3us}cDAWrji;L_XFQbE=?bT!A!V&8Fj>wF z)7jKDDT1Xm4S?X3HFW5--!9fD3yBCvw{rzQz#hJENe9n-Mg(QKd#^~62-9>a{k zxbz&bxYl^dwQabc?wl!kz`Dhr6Ofp6()Lt=l9(BYR`lu13T_u|kxgZs6LkA^yHNyt zyVtsk#CrjGTMaC?wuCjp83xpWPHY&*Jb8NhXiSwq;+0g6V9x`*nu95B&&AaD`d_{n zCeO}o0h|NFu&M(5QH?7MW@Iw2En&iuzR@CySEp`ZA* zZ`=Eax?9o7sc2MrmSVaK8qqn5x82(c?M7GE)C{krlIBG29k~Bn_c9ZByeQ+YXn3EBjM_MM3S;Zg3)eUMmNHS~EqVySE@R?|o0uoXKsw(%>C5E=C&yPp?~B z>i4ptU#!vDXAcVkfcoXv-xesO&}XGU_l_p$5ejV=!NscEs~L=*eW^SV=YJ|D#E;r7 z;HjKJEjBERmDTFtuKeG|eT6yf$1}^MF>XOcvAU+8qPj*L0;!6!ACpgYO-)S8J zvilrDwyk=dJG8%Kyj(kZo2t9O&Pjs00+Ly@uFxONjQMe&xo=H?Y7o)lUbQ4f6EOA` zY)(!F^k+J>nG2XosqP7!SioCtS{D|Ctr|`fz>m8XV{xum_^(}LV=6xTCb(T&0LYp+ z@h#jt(j^pr$5Gs4p1xg)a!vf4K`4xt;_rt5hbaKQ-I|F}ANG+1e-AXdR{h=0I7l}D zP84*S7Q?D(O3he+3lcGdbQKUT$Nz*%FL>;4dykV2J-nnlSn}fxli2M&So-UOUrplq z?Q?`Lo$o6z#5eZqWz4O#Fea0#MI)f^83r}o+7#6s8_YM9PF&GO(kg3(^HyNvS{h04 zu=M;?aDcD%`w^m@`FbCh%L_<}B=~IC6P)4zL|pwCC_8li_Yb`22zSzA_-P32MN<=b z^jWXgcngD}d&`YeAyX+IKY%-+vyp;-19g|OWT^1+Z(5niQ+M|?A$wXO@pJ}rKXMIx zc;`JgTs}wn=FADvs&#Y2X>$Qv-ysH=AaZ^~CSP*e6bV;?YJa#5<{Ao;74yO}@aE?~UFs19WrN@} z&jgQflg5Fzdr#7_6U0&3x`;vS!tuEk^aKV4uu9NkyX8|pqj6&|9 zcN~OK2o^*7F2vn`CX#&FF#((D8$Qk~Zk{jkIc#M> z-wX5ec9CncD9GcshojcoW$4wq#JVr;)_wT{hv(PTa|}rHZ?5)}rTJ~kzwAUhZym#- zoKJP`5CKS-v{sO{Qs7&fY?HN?j6B7yaejxi_istrEV%R#zE-^xriW_wN>89vB30cViaE2!Njq zh)ht7wqjWjljNBVxjWjw^(#i*FoC38xeL4O?YUgRpeo49wtIZ!kYk)_Nn=d**`hII z-nk?ena{i_(aiUwxzP98co%isYk;+$V~ z&2VHcnL`BV?eoP}o=xm~JCAMKx@oa06|(>dQf1^8dsp^(J`z4n*j*cnThYm=Xs7Yd zcM24StUCtmTRO)%jfhiXi1mU{m)lgxPqLc!{Iif33;P`>&JY$y;iecVFxtEj}A0cBWx6mX^bN2DWni z)jO^6(Ls!mt?`-sM-X+#J}7C^VJbMB)95iQ>U6zVGRSI<(jU)$l?XPGfU@bR_Qq&c z#0b?Sa%%c|139RGtr)@GqJ%RuLAwH$4SsfN228FhvaCwi$3rMxCL5&K; zKNX%*Tz*u5Ji`cW^1xfLC@w#CfNpNcPrI#EZl=qX%y||HuLJYo07l+UdZV}$=v<8_ zgue^jJ-@QF4a8>bCZtvfE&Y;JuhmBX{YT$W}2Bt!EE*$Iue77Xom!5rB|5Wq9n++BPa{#@2ByS z77(d*KO&W`ow%u+F55Aum0VM4+*lKvffHCD?B?c36%T`0W9{CodAw!Bw&PR?Tw#B8 zcd6H^t#QSf1_GA9-q)-;Js#cnNRf5ASQ2~$hwY;p7ri+L9_o-ZX<9h71o8a`q zf}wwU1ept2tQQ|HEE)K-LZ<#nx}XYXLoiG>8KXW@uw&mCff=>VzgB*}L!OlY00`JO zwU!-Bm2l z={G}AMhcLyR|1jj&%lxvx0C2y7#l(+*69I}Zl(h{^~G}Yyrw2s$*_ennlD@e+6e_S zv~ul3S29|@*I@i+uSm-W?v6F+Xe!e10x#IiIeg_TZ1z2x`FRQR`XB#6D1Zf1boMG} z(84)qYtmZGfo}Y4r6+u3@#11*A=J-&BR-=#p|=!5|3fX4ZA(_&Ky7hMUG>fDrHTj$ zH6}$j!PP1!Ml#Aph`8UuNdE-RicpssVo1J;7<(C6C1@i3}4JR++*idUV=@p z;MQpvFn0wCEO8Fkj+|T(aAu1X5RCKG1Z2UpxG&lGiL`-*MdE3pF zTIU)+zfaL+=*Q>!pd%HVa~K&RygcqeY-*Om1Z_2V!(Zv;(ib+bNwZN z1I&PtzyN&aG;)#8SwkA2hmTn*65uE@hIgZs!9GCXdiD?+?ky~=>_mri+B+T>J>v4H zUfkR({4?mfZ*}W;R%oWCuW7xXFq)HzKt_El7OupK|5lYzSNZ_xK|sNC4W`ReofH?K z6Doa>R!>gVjd4Qr6b;JAWhLdGmdg8byd(sjJN34%T|yU0^KK_>CeA||MjbtkI1hpo zp$yXYIqqoC)u4dNF3m<4#q&wb8y^^8*!H~bJK$*Yn3MhM&xe7h9V)wxCUc$M4^+dl z0x(ZgfD5PV!Pr_0=||Kof;_eGInfVYpvoyGc2(Lf-?ZJjID!Ih_8i?tOzOEBy>29$ zQ=iK4br*r){3`qllg{4k$1;ckwEbN6#uNJ&B=QRBwq5E)vQxJ8RwC+VP+CeTK&F{1 z;IfyfzRLAPceAC{f5m;^Kn`mS^fY2RXK;;U3H82C@keDu?!=Q(R#GAnh-1yGqKl1pqXp6ozO+ z$Y)t2TxYCN@r7o|xlaMB;ZGkBVt5d$wIA?p$-;P=5&| z_j?wXY@V$GBpH7Bqt?ftsl!rQ5Zn)ya)8$8?}lh8ASEUHz%oX}O9uj~b4x65zV&0^ z&;$Y8@o>b6WW5eR*^F7bepc)FRgToM5A-c%S|wt8(M}oYN;{XDSo>vx3J~?p&u5wp zVyJrR4sEVHM!ddVdu<1`xv>MhYO3XgNAQc)<-4ZhdGxn@MBgqN?-pL&*0i~IoZet8 z2O))>N5eQC0&Sn2yR4E_y!w2&o?{0R_z7oSTy;h9jSaHubO5BD<1dPKpji0`M2Gb5 zY5I^49OD0)!*icS2T@4kmw41*`%F~!TgLP?7mH3F%s>~~~OmzF~s16I0B@ zpQf} zAO63$bIiHIA_Mv5v7=y(TGP>-5+$`wzcEiOug=AC!xeKFQhIedFxKAQ=O38cRCMRNi?J!jyA*(|R7K3|X z%|gTF^lP@Q>`no1njJJc=ON?(SK&;p(8%R`g@IkZb@Blo)B)zNO0~=06}f#FGDsqv zCTU2=hF>X9K7YCQLms{Tm2E`t49*D~fv^UEya!~{mhpR?u*RTO_D9kqIN;iv{xQjc zqOnWq+ChwU>JT-wW?txFf*PBO9rBKD`)d%iQqZOZ#zg%Y!yFkZ{(#*Oy>?hh5MZ1` zBe-${3{v;rW8~~x0)fs{qinbXk@;|8lFMa0HfC*-9gmuO-8ThW#MxOX!XRd#UX=VH z7Og^yvf4(oyYX!g7(KSK`w#FOJTYZR`wP1`6-PdEpR4v9MFjT;X>BT!KYim*F{iE$ zs(%D@#Q8p%yJ;Scpy7+j+Nf*N{=*ahrK9@&bZwH{>;kj@uTkmhO%LjZLoWBWRha;(abdn$q3!_L~2zhNoK1!kY0MUI{UEcaL)E z*DNV*qQ49!G1oWA`6Jt0LrwxxvzHsj^Hf6=gaDuZ@>eukseaB`XlCwcgi5;JUs*I0AKk-fvH*wS_qTK!MNeWn z02u=sdm2LTwtE1O*4za=a%N2PP% Zl<(?5Wuk)eUY1nc^d+tTcFk-5|C(Kt)LU_ zsTEFaN}{~Kl%ZQie5O}cKO&>SlN5)`ohU&DlglSe_kO&q<9G~9c?)C_ux?781gc++fyev(!iZ<57lb8HZsAj2QPtn3L)ioT4i~M5<-PZWw2bW-e$$t7~ zV}*eNcWxv0AN0&)o~5g`pKcLy{zsd~BJcnJyV^L}9ChEABlGsYAA215_!JoT#94X;Ac6o!8V~_?5QE+^)~Tw()A_Gu zm8|!jdxgCCZ28{~J3FN~si;v*bL07w0bu@a;LUSpo;*#Xv6dAQs9H#;k7l)IN-(ew z_9;e?R0nevQPA~r4O2mD#5hq52gJ1LMuCu6c?WGeT%;FH^%iY5hBk%eFM z>v$B-{m<91xJJ=Uo(kiCx%r~gU{3bTbQks%#_x2bggqhN1(g&fb2{&z;89T4Pp8l9 zsOm(Fd-A1aMIkA5ih(|ROXo{q>DU&kMV20K!oU4$pT-z&7UkZPbT=$F5$LSDFN%K` zMx&jDGV@~_TrIyruD3iI&48!fym#WNnsuU}s)9S2ZQUAM#0;Y1*lQwE?XX-h_M=0X z9ATxIcC53?MFiNDM8QB08wGz3$*Wrvs7XwvC-rAC3qQ0$W5Bn(iFZ?c1pElniSXFR zFZiZA8Z>bb#eRBhuLa+ob)jC2NU<`TG(E$PKxOG!vbsIGBF4;{#C(`gur@r`VxM7B z>$b55S-yD&7OPI8u}c^luo#^YelJVB`u7&+}{U{ z3vq#6_N6wiPC~cv3!Aa)(S#p2yVn3m@&y8O@;E{s9m@{g_3~OR0p^^wzOK~x&ZHAL zy+DiZa^J`45>e$gITBI^-@YB&aM5F&2 z=Uv!H{e#q1-#e- zh>&_9d~+Y&cc}TrF?2PHU&9pEJWm+puXbuE;yf9|{pn?1=DJCRj>+hVvwhx2QNd-I0T zLl0ds>@trZpuccnIdYbw*d#tx_z4hj4TTHkScGMEHVhuw{sl2C-|Lp1?>KmxzxN|| zvTs;FNV+t)qhFK_Ck(^@SvCQenY{He;6&riN1E->I@(JZnoT1xdeeo8XRp5XDwWp$T5U}J&uw$0Fq4o417?OfGf+U-n*S(VVU;=k2umriD#Xb+D zzVi(&im_efTtD6^LixW=5znN@8F_RX5aqxEKK>S6r6i-4K%`aG4!Bb_hGxstlI0Sj z5MJVRZU0W5yv$9+yPl~Rks0PbF4YxBk$mkp+vWK&c-)OHuXeveP)45cdioB!wl~8V(@@sfKPK>!7Q)YRXJ^F!lrpwXgcs$s2-kZKA$zg&zu^lF45!$UuI!&|AMdzw z$w-JO#8ZrOz5Th;Dx!|v>!)h6-1>5i56I6&@1xB+?w|;qs%K0f*(rxPl6%~5E^v-j zFItKUh)yf7x5dGhi#ewE=tV+_{%29x=1WdLK|IviJK=XOnLKVlb~uH2+e`$DwT~rS zRs5kRI{#+*5?%mv5{WQ>+-}DG6n|#%80o|sghJ5iBS;T=DH<;vKnw~kNoh8574(FB zUasn2o?Vc+9^dR&Yntka!INeSpqC0vVFp=V}-2IL*~i0CuFvdT3~ z#egE94x*9gFBmBy+b6e^==@iL;O|2gC}1yt{XkX;`)ic!Jy{I(t`#-d%MGQL*~APqhVj)pEkMrYH|n@pV+ph(A2+%HpV8^Jb(11n zzVKf1<=4YE79&N41Yg3)#&odhEh9p(WS>EobC(XQ^dPc%6G{D|qIt(KC@yaw%@960 z95rdOW0fT!5N{mNww4EFUxx(jLbg76d;2%#Wg>tt$LkrB84KTUX4}36FE};XPpR>2 zfTD8_Z#Z5zk~thYG#3uDVmzh;!@?l!AR)u{rNsj7X zT*j|MGk$*-j=e95a@Wu#0^uMZJFI@FDUVWzB&g9nD`4tImUT9ZB%;jTud!3-I z$#4Wl7cOZKXxGsz$ zpyeQ$_Q3Tnc!I;ZfV?(i3vjbrdeWZ|$~ophlW zC=@4!`vllO2iv>{ybr86K>DeZL>{{0!GH#zDSIQHrQiay>SkN{_8`=UEKq=m&L;8$ zGYOh_o$D7@ek~j4?~z&_=#wju_eBcjL;5@ni(G6ca#KJuNzjVHu3Ug~p=YiWf2##) zk@?q?otMk%fmi+~wUCR1Y4MwNcLpQfPb5IQ1{D(Je$PcYewqkbATsvEAtk60(L2*u zv}?OyjH`k+X+7dwQ$tVk@K{Wc1&SmVBIIy;%lqmPQW@e1vx!Q-7ts&ptWOtPkaP-_Qxty5SAi7jyzy zz^G8=C61SU)f!-=`~Po`ZcM}NM2!!_?<=Evo3f|Tx7LEa*SyD2rw z5^h{U^w|Vd`@&#qShp_BfM&CftW!1=?-1`|vyQRvx2nfCRPPdT!pzj?DM+C`RXg;d z+kKJ?$wAbJXF}>b6t%fC7+l>x3vf^}`|~7x#RC611?hz8JqkU5d8K(c@z6!XrCT@Ia3{iKaG|L z${LNluG_ymgZB(e9U^bQ{@ZBhVPb@Mw6F#_#+1}iu!HVD(H*2Q?9hgkNG2S4uHGrC zmWp5dSsnSHU4MV&6y`nV4sGFP3|>pk2}68w<75{2Q? zT0o1MT;Khpnb+l1?!p0ek@gyR5rTC&=3vEmzcb4=~1Z|x80g+A6>tLjU z*sS^(P1%?)#OjVnGfc`w>J{XI1LDibvSoNHwB!~n+cSkjDuDxf__oF=D;k1du8|h& z*Ztxt#oo7JWe-798>zM|y*;AeVOL6i8syx&ZVQ-FGm*p@ey7cJoab9qNe@XS(Tl-$ zMWUYGIG4WT&22ob(~;}8@NWToaqAEocd-Bfgjj7UXNjK1p|H75Sl$IAwL1$@?q@-Z z4ai$$`-EB!&f6Sz@y zB%r0!s<|SFaPCBmA^&(*+oIXcfLx%8PQ(@2>IAVwCu7a(v`r!sr{3G9mla4;4|cd} zS1>k*L=vmN+51P#yWggT@WeNUaN>-$NNh5JQ8_!!)d|6_3r@#>UYCcI3n?UnSl&5V z2H50wfa1(=x;T6(P(mp8B&YGKuxB`46>j|5n8-b` z=zx-vl|A^ZUQHuFmm0fCXl>? zQqQd#-kd`8Rg7Vbplrxpr;o!$i|Ngv#Ztk$!E6;YN1rZgLA{`$b*JKFQ<- zQ{YHf6HLnn&(gW(P_fEl96{9T#;I2ZL6g%kx-%Ck4kyo~bJ&A^Co`hhZE%=py=vnN z6ljtgF6ZpbC`e*znD}(**R%@_|GQe1LLz6d`}wh5-knw)iBh}Ty%lvon?%0dc&gbA zlgRs!fRTBz;4Qt5#16NYWrvX+#Rh~nelrKgF}~A`y-zioh2w%ue1YsjQ3U7@g=nZO z`A`l+phDxWF_dt61^V#^9X&syqY^>j#d}z<=Or&Wn!xrFfiB9}#Af#5Z0T*4ocQ$y zGcmuk9l*^Qk%m~Ct;uw^kwpZXZi z@Cr3upW$%?kYz9(+2|{Cz)$<;tMi4|&wxZv-n<7#{g7!F(O6s?M+vZX%K8TSb4iRqg+ z{xT#Hi+IYJBa1H)$-kQ{)LM|KswO@8dH!6B4Zr|gK%>7n89r-e5IG@$jX_3lkMGRU z+GES(opQYx7eh6HItS4SDEu?w{v~N$YRX(V6dx%YFLB~*c_*!D!Y97Qzb6=ZQy%L* z>K)boS^q09`_q-0LhChxz3mozyFXyOdM!a~S#}Z&1>s`6nIVGahM6Hc(TZdSRAkIl z#0(+~tAc{kcY%mDthK8{uw=WvSNSEN{I@W2q7RKtHP3E`_>a)fS~s&q&eZCdm3r>Q z&@I|EOYGhA5n^*xb$i5|WwfJ?)Z45sln>6%(6hZ481Py&E+OGH(g-r#VB$L5I{LKC zPOeGX;o;m0t67~Kd?}0?Y=`a?F=xRj=--h&*2q!g_?zCK3;gr={NV}&@#3>GZ+6MP z&xf&{YuuU6wII-_Hbft6#S!~Ub}5O7JEx)q`auiMHLwrQkTa1DwrBxBD7(x*$VIPmUf##hlT#P#enc-Dx+;gO@6x;0@3TizoDmb_MdfZq1V7Jy1 z{2^C9Iws2@&yJLw#c$9!o1%EjT9}2*s`&hDT>@UJ>QkBIl#HeVgmPU?=EW z7Qeng3WE-jU(->jwYh{?<$7*o0*&*n99psl51l@ipMMyqpR*G?TUuvMHhVL8Fievd zeYaLsU#XlOLy}bpKbIGZlGuv8);TyoR#iS{JZU{SfHb_gt>;7WcU<#g zR_pgZfOkCaQy?im1jQ{llpoxls#OAEM8h%A^;c48B^Sg~kKspIO0KALW-k<^-Y!l3 zdDDLwTKS_!LYoF^3!bqe&IfGboS@Maw6LjnR4k4)(_HcPuMvOlBq*q$`lOD-cD5t( zFFgvB$tm&03cVyUxLbq#0Fu@f9it%Ev|y-n zRAI}c9Xe{zb4kJRvw}YszWqK&bi@UcSi^M?qh%e|s$1l&ry7m7Ex^T?i_{?sT%^(b zeoSL7X?x#8F3| z!nZnn44Qcqg~DE55bLt7>sX*Qll07-snGrZWEvXH z3nGnsaBOp~hrxBGcT1TcD&i-#zJf_nPd| z)&qHpuMlX_T+ui!c4C{UL|0VuUVX~h{p9{IpRgEd_<|ny=z3i@Bq#xb>R-wyiK9Cp zqn8x20?)jpSv4|tNZB8zAIyGL8BTTvB7cJCO+<7DK;L$!+jaKl#w#L0~If=eA@$LLCsdenp z(~^{oZslEZ$6Pkn00Joad7K0Fxv$2r5D+M44^5b{#5v<~u@A{0cEsOZ1VFQtfL+BE z>Ql1?HgCy7MALag#~S*BXo9^?5Z&UgN~U&;rkVwdp44?Nv=`R;0uVUfRaxf z@F}iCPgrXvL*M?WrN97qK_Gf6Pkl%mqd;_P+VH~1SQiB(N0(tt|DcEd;wiD7*aqQ&r4reo)2zsdIV z;FXpFiecC$_mLNimt?G1!sf5O(FyU19{O4xKLI((!EMIH_uX=2rSo#(k z9D13Tlhrh^iCdHe5fAD!iW@Z>yQ^X+WlJEPti6LTip9-58*_Wo*6s#8Pb_q%T>I!b}$hKCfn+lKnB zlI0NWBdJ;WmCf)qOMV!H=@}p<-Kazs~}lNr46 zpx6rcqXcaO)DFcaAT$~ z?l|3t_faqm?(YyuaIo^q*vkXdDWJ5Ct5SK$M{PF>tF;`_*gE@0W3Y$Jc7h_{I7N6h z4#i>J-hEF+fRTJ*eN~FKcA?WQ!RIAd@P4^kUN;Nk$O7yWVKsFcftsmP1>dF4NKYhm}24f)fxH<%jX047DN3@0c-|YbfHqrJct?!xrOoaMUKwCj*cP z-9GASDXxio{=$}+2BNV?MXq|#^ILeB8Y=;Xwz-$hgk>xWiP&#H9%w5toSIsOSsxl# z01FJHwL5SxA^hda6?J9d^OF@Cp~7=Ez4XtylBqroAUaL!r`XP#4ZwK*!~LkA)!y*~ zNye^5>iYF6uyXh#(GYGp%B~#K%G8ymQi)#RL^>nx+4OKcm^=32WGd z-NIO}tkxk(oB6OYoea~4l7Zx15sNfAd?hbN!bB~8=DCqhzcj^#CfI^VJ!Nh$UEl)S ztDP7zQQ&eF<{_)Cn$O7<8xKEXNNs&=x*Bcv(cSZJqDCud1>MlN_q8D7mHor0{AEA9 zhX0z*ePisXz|Fl!IJxngO0E15cwy@P0YE@rZCpK|lUJV`r=|o~>ZVrUYP}ID@bCd@ zJix5#5p_j#w0^MfXeF+}p+L$yR~#%)l0lC~yhdgh909uMDa39jjk#Kxh(_8n|Rw{h5qA7$>3={#k zb@b8pGqa~SlMIWr^99R;fB<{rG5I_Zin$Cs22)EH1q-}7!5zedvx^P1Vv(-C+0cdcTbn)7HJn)(tamK&M4ajd zO8m5dP@)8Dej*B15|n{{x)GjKP-91e;1gI1Q~RyJa}uLJ7>V}C6T?C7fen~{$$0Dq z*sQoCfiH3*KmrV%EQlxMtI{P{>=O5;^^5VWy%2B4H=J0lIH+yRItB89sDz!(pol390v`{-}}$)8-v|~vaKLq;cBt0pGsRzW&kd9sCS71!G1$p$QW#zMA3-Nv0!BY=&Z$S^KjfMi%pTo9tO{%UMalFi<6>1bMulQ>jT5vxmrK zmfGdfd|0_IQgba&MZ-)sC$C(Hws62bp%0EMbFT&n81=mk^TrbyCyj|T-HX-B*S82H$BO$~T(s~!)#Kbk-E%{1Vfv^}rK8KvM zg+w@>g#YbRVLr?n#%HnT1MW_$KF)BfI!T-=BS+)m2e7!T7?u>phQKVnQe`Xlml~7E z%YmN1tDa92Xi?}BOTGhGU`gbD@NL->^n>bKHep|0k3iz<*~j&Vd|TxAY&9=6MtFln*f#-lv$ zau&hbg=D!0`HSRC+wK}T$jePZ@=QXbB~PZtDX+X?!*1CXXd|NuBta? z*R6ljn5L!a>;ahH7rc$u3nH;&1`3oKV)7J0uywipG%$GfH(B{1L^pS`t}Eje{(Y%o zFe^i=dq82QCXREW6GFm}VUHdPi_7AeBsIc4@Lab?kb2C8@6Y^^+Ss!Cxo5e3Rd%c` z0H!F+qe{u+2v}~7@xlmDpH0N9V&s8*i6Zf>Wnro`gNH0rh!!u7F2M2Y`wiRS;3Ppa zG_pXOu1ZjRm6@zIB3By42_+((kN2dfW1P9Tz~GMEefsCg-ph}J>q`!zDG2egZ0nsC zPy(_wNjU_evikPEFF1bqvB>XlqOlJ{DeLCw_&a+ukx7| zm^udpFm(BUW33Q#kISGjjV4>o&Hh)v`C1b`{~4$ig;Y-FCoX)n$bqb5xuuIdH=PFZ z*8ijvnzE=>hLXk*Vzm0k(}Vp~U_+pTz>}n1IqQe983pPWN}Kz36qU!uQ^+WRxJ8Ud zPvu16q+@aksN9gXlZ^Pi-pwBawnkM;I<6<5Oog2`ai)Fo0u`>UZ&Kx{>pJ>iZ$-nH z3?9Xhd~u;LK@bg*MX%m`rNMp0%RXhAE4N)Cs=bD3f zDJeUnLW<@JYA9Zl)n&)bbJBV}K`$|e!7dRv$Oi53p_{?AdSw5K+viiA5eO>ba z!Z&HV8vU)VRrMGm^R7VddwX+imq91ZqoV&6IhsvA2+uuArRU#lKb3uA`f-Px8{8W%K z6rn}!RJT(YS!NS3H7=iIf3`Z$=NYZ76u5l;(BFJ5x0`e|y9MDedWg{4y=f4>axUSb z;6P;?MeQ_xyuK@TGQAOsKiGI&D^2m*kTMiEaSAZ7$JjvuI{hiBeU`^tR8t{>gQ?iv6!9ucykvWMm!U5NQo$(0~ z_~gWS8$-sYw~Wo?i)J+DO^ibzWCp@LA987UV9i0;00C9SK^w(HLouymeD`ZeNE^6k zCb-3ly8%aU0n!A;&Q_SsYF0p#mb~vhTi>rEUS?p7<(MZ!3;GF<+X30w^T0yYW!G9x zf=Qs<)sz-N^3>w{De;@nAFzF_xl80 z7DIKrbXK&LV?(`ubY@CQ=x7~BPX|4O94#{G9@?r|N2?RawlD_^ERwdgOzERDkCtx} zB%5!Lh*pszH5Y}B%5TDSikvYhs)w)1(M&1I@PH=~Rosg$`|!+Xp>LG|liiILC5pwI zX||OkO%_y{OUv|!7FNLzpzpzS6GL*xrNoEXQ1p55)UeUsW-4sVrb{Q?ejOyK1l)?}C4k~2Pj z2(92{I)8y!12zS6c|j%EOln85j1*xM{uE*@#0N0CD{bzlQFuE`ui?a_@{XRHEt8La zn6dF$JtwN1Zumx#ss)@RZ7svDxRjmt$Yb02Ei+7f1?*(k_oKj7B-2w&2#2CNkTh44 zYY2l5W8?VU7ag#63i4fq{i-4-#L;IQEtVgzAD7K_py8v6KmWkKD|!@@%(wSEmbglg z*urbj$jbl3#2Z4BY>kbv^kHP`<)gpfxj@HNfBVH{&OeN6#9)QsUR>z4h>xLtmi>t1`MYC{|9@N@q zb@)N9NQ|T*RD281`SWzIya0L3FH~Sewm%9jb`Vu^doLy)c$mikIg)~X(RiOGHZlNp zdTzn+ox)+4&)W8R{RZ+FGEC(ew2Y}sM|~w^i&l*#1%yDn={+JFD9lTP+%Ah$&CWr5B3n{UG}oHGWF?}NYx;B;WIe2Jh!Fu(Hu9KI#{m}RDr z=RyXSN-yQtT1@t{F~LHu=(Oya@}bYqh*z#YI6>N0UTzU7%SUE6BOGW4a4@Y-rBwt)T!^pKhkre+r+kJVm$t_Egci~gm@ z|JB5cc>4*isfUu_O4jyw#09hooV#i2jYR9rgwmFm(IWSU;J@gDSO)T_-l4|fjBmG-F0i8z`9GZLefU#_ zo@L64qkgm1&n^sNfBC3s3rHCC)oTL&{5BP;ozl#>ZYLZ+m*o94!;HZYVFsEpNvEEh zJ9t(}s8X7N=4XOq(jjr%?%$PU4DzN+e!;5)#cL%cfN~LY0BPn6wl9mM`tRYM9?-Yq zfS;ov?L9(XG*oz0=odIVsM}w== z;nR`^dN<01)mK|VP9P|@A<^`f3UAR@4`vr(11e&#O?w!zSLgKiqKWWVfB+7iIuT0C zkY;JPlb^>1+Y9L)&UWDfnxs1WFNGpAdH&l4ssdn|XX6C7J8h%?6*j}CgVXA|MB&ds zUJSTu#jZUWeQKRiuD8X?QcjDWrlm`Av#9lef{299i9nUWwHXAJSVipz`In`IOp%}s zpP}@dK_S$+)($4c*5Yfa2S3VQE%UM8Z2jlDoLmD(bGgo>ovT~x6@mw!w9Nt)C1gzD zkAix4`Esb#(KB%YfPyX=S&+ZA%HrO7i-0Fm_=Ieu0r;MED@aN{AbOmL;R&jmp9j}K zPfTAk9Zgu?$=qf`7_*|I$?YJ4Q{S8}ARn#h4)HX6nnu3E<)UScok_Eb>FG+`a6ohz z6y&}rEcKTMkR_KL68GReRpMMp))+;d+hNlISp+9{6c0qUIp7NzsUi;gf#Y3y&ycxw z4kVujhF>|aY!VEcQ}I3gRRk)Hv9}9&tKUBlTrrtNhy>L>V@Kzpjx&X7AODtc`LV7Y zd^?U4mud@ylYCp>dsF8~#8qnbSa_rB;@);PzhaZi{EB3IC44Yw#=h4ldoCgtUuzU zQ%emIeLh%v{s%DqcQb&=#6vhDZuApsVxnPp+UC@P()_br4fy2t@diEEk7|7BuT`Xh z#G}0S^T*>`%CeUth@w$7?-vsFBGXo@l)|+)Q~V|kav*UpLydMn)gB7v%?*a5bfx5E z8j%#G*@f!Q>b14>a3Jy5YHkh_TbZyO`>1dEa3t+9c6q+)e9dv7m9Yr)BKJnEeDmj)4kRSchFBif(CQ(_Vc>X^o0^ zkQ-Fy3hyeYpX^OtK!i4@qh{K{MR5XYy)Xob#lF+ueawA}&0g3c2pR+bP72sEz^ih) zvypTn16m;*-g0jF(kt)O{&Jjfu7PIU>$n!3SsFLBqUQympcIYl`k35M$3mt9l$F*0-_VZk! z%Qa~@GGIr)FJtm5v4al<5tB_mJHGO>aE~p1c;tGU2_B=(?*?$7-gqPRYxzavL{UJg zPixqjxmdl5D5*hDl)ZquNdK>K>yT|Ap_Z+8N3F{a^GfN?z~qO8ITy~G^7nu)dk-F7 z_E>VU$u_SP0M`3j+Szg6IAxo+C?YW*qs0gp*yGEN|75Zv=?UTlf~01YnNXg!*uhXl z$5y$Ti&f62A}tuP#L9$&K=EQGu`rnJDS5r25n2-s_Ri$HSTRBz9X!ik`Wynt@Xs?e z|1{XdK_|Ya1RULv=fYEvdcSyyMC--D{D8czp#<*u?yWKvM5`2uhNwg6mk?9(0e1uIw z@@%ugOlAn}q*pI(#zN~2#^GK)H!L&MiYkEIxb%2_i{S5SrMACY2?4*1-ns6R!|ut? z;Br0$SOh8r|5uCR!(vos+e*qVfg$Vlyzh@j$mSgrnH>&(SmbE&b+VsllrktwOJ9fJ zkxs|JYT?IvCe{3eY>ZRnoCNhIiC%a^tPOJ}TV1(9`Ce+&Ah=_jk$hLj@T_oVz1Le* z_ZGJ6(b>KDh9Q~Le?T2CU0{-QbX6(C3C}pLX;=NU zZp&R56TbT>oUeMK(MZ4Azi#obi-h7$zqL@@y>XB}CxP;9ZssRA0Aj zNT9vPWK;=F2k$w#Z55MK&+pY)9)yun+>m z-a5G$Lr+x7v?Oi+%J2^A;d6vnym2EMDh=fPkg70O*BdzCp#SnUc5go)1W^q9Yny0#X7SHf)Cq&;<( z<&Yp-3bH$z+NzHe(6j=(GbY)vU)M-HoQlx7tQ)zO*!UD+^LjEutD<>c0Mrjyh(ila z=aAXhJY+-H1td8h$8W&JrFZhinhI!-64qil9c&Sb*5*E65zz%KsC^guS-HC`K+Ep z&!>Zd7d&^A1`2|+%;lz)Q{|TFXaEz2uK(RxF_mnKa~J|;PNYtIwpMgnePSzg9>~}< zT>^S4L77l^w-GTBctH#J|E67q9Fw7^6hU9Vd?hg}&b!4i#-EGVMn%~jvxI=z@2kAO z$yNZxo|egvpM;Aey=P`${;L@5EnR@AG|}`6M!o_&I8d9NpeNR+^|Fj`-N5^jOlw^I zo9PlbhAUG`BX;A7*&db6XMs+Z6t5(qi3$|WbbAkadW|$=4aRN%T2YopDS*pGp!&Gq;gJ2aEAtT{5GGhpO?r_^=yYM3dkA1|3wSi^byXHUS zX&%1B6bJ7^GZXU^J3^0?&X+fV2#$Ap7Qo+&nwcBROfYWHj5cfB8Mgs~kfvi`tT(`t zZFhr9t%9B`&--kgK~-jLyy|30D2LxU24}9Ekrpe%pdYH|%=YVWB^Hh%&q%@rIUaKf z*o^AjyeVCCLkGsf8f0Um!bc8XEFKw|CEtF8?a=_YIg02mz^-vkB3e)9^L+@t96No_ zhuA?khTNsq`)yy9*x3H+tb5k!CQXlQZiZWoL=VOG---v(#1x7!a-5Oj01V(}hrS=U*>!f2m1ow- zhejLyE>l9`w5-P{>s718;qLiFJpJVD`CGzK;gNSOyDKE$d*|wjRfzb(_2SZ7n`9|n zpc^8r(pOI`yZMZ^q}U!aBLu{g`rzN^N<73$F%Q7o(BdHxkw~z8A22b7K9a3%PWrh$@dt^E3K)X2yWZj=%j=J7Y3}r%M#5bBP+#H%8Gr+3bfxZ z^9@hY+1kkDw5`e2;_08*QXLDS;dR&xapmLX5h{O!r_h(>yQiD5)g^aPIug75e0|7{ zaz5;rw+KjB@-EZO2JF_1A?qE-aiQX_iGS=SGlSpOft>L%e^x((X->m{EU!Qjt`(Cx zcV|6}izq_gb8@+jOrFtz02Ll-iz$k}zb!fVS9FDmF6e=ZXBxep(JC;8l^fXs?RGe@ zeoWv!SuJ^fbj6o}j>vQikswLGCIqCk#*87wmLyi&S9(Vbf0?Kr+a zyB>a~4?^`@DXBluXo;>dDZ%S7fze_}wK%bo(WjJkESl~mB`-H++rQkVsXVbsKodMo zeEYFMLQ@(x-UH=DcoKw+cFaQ=o@9SET3Sm)p`+r65!a)*z7BlN{7df)&Pt+x5rL15 zhdmz6dS5O*VQsf^sTQXy(Bdo#a%cS6a|!$v@IfccGq#D8;v;z)9w|XTuL7%D-y9_W z8~pAacD9+ahJ@RN-JuoBNeMJwVNDWWlPChWW8Bh2RPC@u+EiKitA+$Pn z&9(_PHe^(6YO2jcV<2_D_tb)6JU0k4j_su51P+ihiowAZp@uwUob-r4kjVZLQgY(IXu$VojUMAlo?6Z zKP>~5_U<0DYP6H7H!rWB{ziuSdf;L02Ex!@PKlQ0b=BMQb=D~4CyWxIv(a;%3GRQN zK*esTtFaOv8W#e>g0N-j*Vv+r-dOS^P4+gVJu13HE0GKmbYPkRHeG};_2#-kpoMo~ z@LIKR_4w0d4Jj=skR4(JE2BSe@7SwhsR6S~6>En{Hy)!wq$0kawHk_+_n;>4v?fF8 z+h^!X3Hac2p5!B=X_X#sM0mRi5kijhn;SxNjLkMPnk}_KL-QjxWnb$KOg$C~9tmH| z78cso=x*B3wLyi?Fd`%YMmOByi-iTtw&OB!aohuPiyr-OzuNKOu@&eLN1vzW^3(z>>dj4 z-WRiuKBa{zazG{k%0jHF9m<_pTKdtUUzT6`u6pv&0P6ac;+CCipF~Al&!s;^-M1DD z)8vPk3MwmwbyZ*geF-_w&#&?|}*Ez;9Znx<1g5hOtrrZNGAS^aVudi7@X@R`U(Wb4yZ`DZFXvR!E-(Z zYA;@I1{`FpY>tPPE9STO04zwB+=Mk7lez-QqZbb=vP028pHvYWD_W_^D_Z z-Bdoj>GyT^qElC8d%N6jl+=b(E>pG0w@2JbgcsW0Hy0(yz}!&yG?;4aLH>^R6Yi&| z$vEV2EqCthG}y_C(fJP}Ifg|e%L1?+`uIpVH{;?v4Nf|i(tb2(Q*GdqK2hU-$7?`p8&oMKi9 z;0XUiy4D#A7b#y-3n|q9Kx5yN+TQHRSkaHCZ6U(n5C^u^Y^l*jiN?Xw?HiYcM4Tu&+;RB+c0XIDRLr!>U5Cs&-Y~u%{b12e=sZiMcqJ zsv;@K3A`Tf=b8;rZxSXFa1%}A?Hq**#U)U#`imIVKr;8meD$+E-`}DksDtV{%ySCU zW0G+VuHkzqRE+Mjkfm%|qUv)T0&!N9iAt$^rZ_iRf{w_Kx+Or&ubzF9UBTGIfnoN` z!C86(s_tvK-cUE)q5hhO?}!&fiO^5|Xx+pR`x<+_*&|m31PzLEfw_*zmwf2}uB&z0 zg&CA0991Da#*@k*hEeG<-<_FoO3AS_#h4zJaLs8Td}j zDod=6bw{1YBwlUaSL0+MOKG*LcPRrLXdl7wbW3JA0M^H)wlKnIqVr6ES4ykX4V(xm za^FW(XhCRxHgcbZ)182>Vrh4lN;OT<#aY5!i8xItbQE1vd<4YPa0>Ussu0|BZr$6I03 z;HNbalmRf$Eqi)cs*IIoY%UJgubKGm6*;GS z=?g(#_!J>CC9CS)Y{xU|DH#MX)Mf;u30{7P)zvx3W&JG3wsZweOf{&VYamB9-Jm2U zD51vT%?&Uf0?VTZE6lFSC6OVR(ebOTP8NDG>uzP@Ec{+>BfqrCR-|V zZyDnlO5f1O;Alv|CpIRm9}>l_PKrZK<|D&|OhWo*jfdT0s;B@NCp@DbRV(OR#oYHX zSm0yO{sxW*F}kF{!M~h-V7UlBvnYi7#Bb}zJ-3I+yozqnU}6;M@>*AiEKgq$?@?nV zg?ExVW>cPMcACqxqPbR*7}h6$R>s zSR-vNolM15XT;+Z*1#q}yR7ELx9k$bZWcq~PIP+E(lV-h8Gm{mi z($%gt>XtIFe3l=`+1*nO=k`tZ1rOV<>dqFq~5V_F))S8l`tfzJnw$x$5&z7EM%>yKl2;bI-V zmF-^a?h@G1vg5e2)SM};c3WLtdisfh_fl^5VFRdX6zzcppt4$L?`4liHv_WscB#d- zM}YfsF9Qq%+jtVM_nc0Hyo9Y&BmCeN0)oO+$r*`Rt0<2QMz8#$C;7Pgo67Ub6sGrp z&)v3|ykIVosO_-O|AB38js}A40l{jKQYt*-<%*?Uca5!HcmjEFRzfwR4G z9H)5-i=XkOqA?5O7Xok;#(ORmK5#KDG#c@h;2Zedh)${O$pf+c8u~MJgN-SY#J{<+ zwl8!9&f0cq&5j~8x{e{c9Q00mTfjhU^n%{|G-F%P>?4)Jol7rWQNf_>`04a_LfrnQ4C(f{M~W#LEcZK%l-DQav^n?K!d$SYF zu)Vl`gNN23#ahQE@k2vQEQE42{Xq zW~>!75d%#w4H()fH!J! zc)GuNg;yQ$v5jMl(A_U`9Kb0-;ySPs<-Ho-Q6*q5lt6y0?m{1s2v$?i2*>Y3j`P>u%F z@Wukm_>0jAticK!IK^$n)IR^! zBtlMBj5)73!~*zhYWz~ofwtC$AGI`^Hb=4H&xq<%sM%lzigIS?<2&CnvY`dHecPr= zqVE=vsR@Wp>jGo{9(w(k8I^oJ)))FEeIuC0iZ#g_Oix)#x_b*^&QV8s0e=)9Uz#mD z%y{F9sdNrQg#lWPwN%9~Qd2w!?FL<~mFrMT|L3RC#BJee9iu(jLaa0c{|qUV@U}h* z_Jr!=rsNXe(K4|8v+K=`vGH${z9-vlq=aOpo>CLBotezrF^A(jddC8mc1|5Da;C1a8t_{`iM& zKGg1Yu)A%6z-L8{I3ob36Q+m%|7p9&Q8h+gPo?)(z#f`I7 zV61btuVbJynJiZ`!7c4#UR;@&n=DugbIY&RLmF&OiM?gX_vRY0!E`+QQm`i9EJ)aY+uer{2{ax%gacUH zoWE&Q-M3nQc+zMym|)FA7IJvm4$e|gHd1Ru=HFT&i46$(62G6Yy>$R4lXI)cTr^oX zBJW4`AedJVeM`T>{ojCgnx5vtN9_7>2JTgKE^5(%nra#nV2(Yc*_4o+hw&;T{aBip z_kfDj^)A`)ntPmaNs38k#!=8vJ?r39qA_bF1ptnWmPmw@qO3)L1a{fYX4K2g9u)RG zoH`}S<+4clFE?(qT%=~1#~nVj=iWfex4#jOM+ruwl_cQ|g*Cv=A%OW?}NL4ij(W1Xv@9FRB68$m1 ziQnk77^*ol%k7bm%hTna?7hn6V!czFt(RUE)0!s?j%i?;q4R^P*I4vPr=1!`nVh!& zp%zS$iuSVy2z*iB|7UjAKI@PD4P3*8q#z$f1)tnK;3@g%*@6){5hA+tIoxb>BOJ3mCB4RY~OG5&fao|GB)R zgXdmHt+2n&b5L59^f%~C2S~+cDoO#aT4M^h7wBxcu43F&6~+Rz7z#Ucs8&Dn5FVgc z*OZ!LfqZB#=z-w;ERfeQb?Ve6ST7nZ&nSN7#@>w=p8m?+B}NfKkLmmxF$F3qgz$bG zs@RS+)P0hF?~eA%XDIV{NQTCXI|`Z(++BZ8rwov?Vnyp0BkpunqDh%ZJ+fh<8yOu~ zykIClW@w>#1DlAl>YcOjhh(zhONhvpQ~5o|jhd8nve#~7PL+d0GLQ+P1fMuGArhvK ztPO4wbTR6mTft#h7lWR}(&gW441Up2F+u{L(lRwkLg^fGOQ>{8JV#8&Uv= zt?lBm!)CU?NpP9=ZB3Cm20hYs`;Y)ZBzc1Z`dsr3ryh{nDYs{uQ&?ApC4N51$^vq- zb=qtf9qI)h2^!d&>n&3lz2%d6Y{HO091Jsr{|2|Q-EHmC&gybR2En^_v|~9oJMLau zPHq)&XvkA3YeA&!6qH-a18KtKWe0TWQ8c*-`1qu>_zd_j7$rpHs7M1k{i z=x^IQhV#ugkOQTE`j#oATXw!@TC}aZBzYwos!1#4N^E1Bu@iqHVHuo20!8{H`FPLY zR}eK5U<^e(@z8ghbYu|Yz#C;RWHYWQH8Mkz`E2bu=N{g$F9Vz3zBhc?_6RO0LOL9K zgv1)V(wPWVsNE!RxhnAtu4@Yia zL2y<-<|r=W*KcsG0?G*-Twl0ju1OzMU8w#P%tGHYl27>e&sJmw|nmax3{8#?D- zOYt&G7==@q6gP^0{gu|bh!OJMOGoYc2OAF=Ogyy3<{B8htqzD>xk_`$j6IA3ED)iD zPL*r1bZY*IL*w4k?VDM>ku|nkQw`Kb78H_Y;3=6T_8eEZV9Qs|FFyEpMO0LagF^r< z*nmM9S7oQWeYJ+|kt*-GYVXBi=^8epolHOVNiDt{{c}U^ zsm#v?q>q;NNR7`CK%(a(C--1kg-G*_zl-92@zt$_=Zux882g$6#KeA~t!ql;(?tQZ+u#$HQ2W`N5@$aDU#nOEA3)&0ijebYesq+q|0OH^mgv<|<}1;u zap_v_=Kxyn1zvYT8nBKlbbrX#EqB4f(@hFc-^mcWMB(Ko`1 z_c^R~Nvenj_*dGxI{sE*N8$)W!|T?V-hFy8!w zs2(+^B;UZYNB$+mvzLDos=Dm8oIV9MW#FRu@5&LX^0I&xz?{CC?ubfEwc}xPxk8~; zVS1&fIN4*2f=P_2Ry4)Ksx%wr!^Ir>FeWTngL|l&xX>n@d8;(LVpfYolXL%rNV+35 z(rS3_t@FO-xOXNBuOX7fz#1`7XU-_l;ob}(V7eva>!r0BT<0Y+w50GDG-j3pMN@^c z!f=+uo2{kGI4*5EQ1IRsp`H|X;KItyX4XrtewYHI3Vzq+rwvb07@|_)LPii2tp=<} zu_mNk6T(4q3eW^?qT_A_r(R25l-iL`#bWenJJ#C=H$B@uAV=g=xVHXs?|G=IZ{(i7i3(JE8-c9~W&2EHdm__rI-kMhU=ijoZEJ-JPmnw6K_>EWXO zH7$o0KD2Dj;{_|Y_7^u8)4w)K^8@wMJ48P)A-3&pEnCg`=XJ84U-sfa2iz)Ud|WFQ z*4s7-Rq|yz&H1l1dcAy{f)#$Z@IK14yu#Z*Q#WkE@ewiT)SFM%2im$Yo)7=gi`TMF zzM7&=7ek3S0K3H>htT?bYT^!|Rjx6_9L0J%WTi~xigqB>`O6v+w%3PE+5rqYwG2Z| zT#=Hhn9n?DZ&JfTOh?Ck?$GgC_<5>v^G*Og!}BA@rk=1F~OhHS)(sDVfC$ zDL7#W;s*o><`il&;qHxAc}zut*Gw}855nbc(D>Qt_uj|6mTEVg@x`IMIj|A`1j3Ro zZ5yHdF}kviE_+!{+Axn34C6MeU_~R*=%{&+5WFcr=Peq6kWHxGw$j!iG4tz{r(7uN zf1agRFPJA$B~$z}ajxS$FmfbIBtd5pOj@g}gJ3W75V%_S zqZ-bOxOpWqJE5KUoW=J5p6b^5&7#Q^$PgVeTXG$p{KWZo z7M8yLY(Z6~JH(S3x0FnQYz5EpMzj`5r1>oG84R0R*`PL=H1CuD-P<)W8Q@5y8hbm_ zhd|ky6rfm_a&uB6unGd2f_Cs_HBI9R!y0q#WyY%V*03FU(d73ia3pf0%5Atc-tb-` zV3{55^olb~zYL|4dCa%T=hC4V-(#Cdbek8>5dO#X6|6vrX0gynCrigcbd)>t{qy7F zEqvGYeqSxD{3BBessR&)4Y)C)##$caKccF?SLryE@ZXipSbkVrUWefnmiQ)uy?cV8 zzlpT#H`EaV<@WPa<=D4S-Bu}K7Fz3?Bts9;Nk||Gh{G> zdZl{?f!NOyA$Xz-wu_uS%hEqn3D39Jh(Bhtv)@!);naQ|5m?hLF_~nUr|$jkIeGV3 zl?Sr|a6!m8bSB4uem`SX=?h zd|%XwlopGtqPM0B?901Y`r(O9$Uufd1E9EO%jgrEWYAFZkvoXd>8o8+Z|g`Y=X>+8M-EdF#si3K0PV$SeMHQowC$23zRwdK?|wUh60u4p*!U zXzb}hJwQt=tRvT#uXpmcz>8sOA+ebwy^d~%-+51aMkYgTylfP~T92aEuqGgL6T7n3 zbp*EaAOTR#Q6S%AKi18#CMbg)y2lHw zqR-4MCv^cMy_L<|V4`-NBJx$q5so#vC%I`k|hdDLgzav&=>|YfK~lTLzu)rnlFS$fq+a zC?E$YD03Qo+MiU#hnkGoLpoQfxu(I&*&(KN{XaH$a4G|fH! z_CKH7n&CCxHb{3@iTyRx!1?bw)RMlaKUe=6HK!BS@+*EK^Gf>R+Pdl~psvc5B7~mF zm9jzJ$-EkaMDU_g`!FokZhKJUP zmO0RU*cq4CH$~7hLyT2$XP*_?)ZF&Dfq-*DQ<(do)uPgilb~kT# z#*wn0r_p8CdoFwkZ}yzO`qQBl8(f43#y|p|A!y>gPtjKdj5a+A)`~nfJfY>BYs%mD zjXy^yJh))l&@C6NfeI<1-g1(5q)(|=7cj?y;ZA;q0D#Vs9B7$7;xywF4S~!n#L851yYs!amVwanTj^#dsW9wP^Qk zsG;pCn?CI%EL5@lb+7JLSPCMO2;Y;RnLg%2=Dy4ma|x7U#H2*s!W!+^S18>Mgm zy^Er?$OFBSUGb#UqeCpNsU3-)3~nR7V(V*|WonUterfnRg4}BJH>8a~d=s>SSE7$| zz;ll-0iX8|3h0YqfXbh_)KVWN4y`*>Kk(_$2m@dqsF1m%I=0L>N~z_N#nZQlzssvL zl*R8MQx`2022U$r7C9O*VLp|Z6O{9>&Fheg@PYX-Iuhe_d33W*bja+UNnhuT# z_ql(BQg6I>NhAX7*&9N*@HSOuRbHyJ(Bm0uk1pSdZ&^~hR_9i}D-JAU{F4-w1*C?4 z`~=g?AXTF5=sWp&!^p*_W35w3Q-3_AUk+s%=aMQFNeXBBEA&&U6+FF581##*%I9Fz z7aF;EhN!N1W{&iYgUeFC1Awq#CTGlm;1}|Bv1zL4E#35BRs&LG!c@4 z^O~3|P2=m=nWUA8!z``tYgzXWgS%~c|rnlncsUTWZ(?(zc&Rs8&_JYhf;Mf!gF>Y}z$+FgW-bfpVwkpG&%l-}x^xCsvY~jB zohY4E6_D5O2PrhM3I8z+@1753%WG3&bF`@<-)>?l^W9d`Ce0(m^@);S zbJ-eXQmH`)X$A+UId4(CbVAF^$@Qrt6yn&-p{xHj6_Rx|ez92}w+8kMMsn}?78sua z9-gY(d1XVk^@xI?4F#n8tWDaQ zPe)z|Ik|bLaf|wW)e)Xz@$Quof?8P~>2zND%UpmAMIB7#CrHMAvudS29ILECwV;Ih zCD^vpG|^YT$=tT$wmsE!#pdS2vH$3|)h$p!meyW# zKhR2)H}C>(Nv?lG3Lnz;M!*pKKv$+7`M;=?dlzR8J)L?;0>0hPSHHymR#OIam;GN= zx$jPoJ8;tuS~;I85_e8j=@|_K4fg;kgfr!0v2qL2em2CDxl%w9>G_y5h_XJ76uUqK zbK&QI94@&wS$;e$$v$F1kk0&6w280yf@1rgc+7Z0?6Ucj9p;~%RD2Zw%M2b9@s%DM zzn3(gPyg$iC}%We3GtWm9)H3h<&FHf;-sMH-M4LqT(d;cC(ICoX zqQuN!i{Oi^o*IUjGb<`JY1p9WU`Ni;LekLE&;$B?y0T`q{p#8mQs})~oTKAq4A z7sWcqW&uil!5V%WzmW&q9b*?^JytVT+84kgo z(o+(q;}Ho8Kek&SDzb4lL=(4PIs(J2IrtuM!I8W(33XqpuKKyEO@zMq_~C}Ubzz=$ zbHN(T+LQWvc(Y*Y8<)-KE&M4W4}N_|Kpm9uitwwy^i0GGG7#Zd4s!Ee_Kk5{p_80X zVj|l==mH}nwOJ_R$S3gqjR$Kv;*D6<)af|7ozWv=)s4k71UDM>MNMkEc_kyN$}X@e z-PQ1n;ep&hP>0@oNI=xEHFhfsZNJ7r)=0n9HjN&(ol)`Cpsn-HwIbCs__-AUrjp>X zBuuik%>y-P4YtsBbDET<1Dp`Ve|8z_RfZr2$MHZXfzyw3*U@JS^wVhHyN&K8bN!8y zR$>PvVVv^oRmZZO)i7B-Rt<b+>i?Zt z@ZoMRYQY_~#c>dlN`Ml z#oqQ=#sJUy51$bQ{x(ocrnZKaoi_FWxBc8Jgu8p`)ve}RPGGf56-hKvP+}AC#!RM- zuZ&Wx*>Tg{vw&g((OA1mqzsA~tuu#j30iCr;vzY)(t2rfu0p>3Z?p~=$&T^3zbC6~ z(gn+Rpnzjg2{j>S;_+TfJKxAtf=FzWCiIxX2E57oi^>>r96t`#Kc*$jHU}1n$Nf0E zRy&&d{{PkvP{H-pPSp0-p)-ia7E4}$@oId;rb#g3<|zNf>N`PQ#BQzvw@$~t2@W-JJj``QX+tOon#K;JI0&ERa1i zo~vPkL!Yp|?4`fv7jM@Au6yekgv;1sX|Emr6}_spmrWLlOJG;Z+^%7smb28n3|=?5 zeInZ_)4V@&_6xS3><&-Hv=gn2O(-fgnuUe^+}pA)wW=yJT^y;{Zx)CV#{AG(wdin; z(5+_~7mY&(%Ja?5kJqp_`jAVGz2Z-sLCSie*&Bg{K?<}H;70Exh#QtbbTKw(*kxas zy^*1lEPdaMxZCS4nFy1K(@#!{YmU=g||uhHZr_A{1f{0xtAb{{*AR|f&Ww)P*$*$U;n!i{HOOc z*3{Ci#hLkY^55X!AKRkE8r0tP zwI+ESTKxPavLux0SjrD_prvo2%#Zz@+Hma)7m_bol8|vSJJp)-Fc8yrb}S4+_nIB!e6(ck)y->W?v(Gy~HcAGOdq;!Djg`24p|Y_9h$LWrH( zurbZz%ODvqATk&yL4g2cZ~Zr*hOE&n)S8 zGMwT`#K?rM9gBGz;;un}J&Q0GF2?`Dj+o|>tMQYwHMyNRJArFIv+tY}>OQz=lNs%P zyN>T>zQgkNDU|L%C`|)45@35d_O|z704LnqU*I|EMs5_&BCT5><82uv&taO)zNixf z4EMnX(I6GY)@6zcMSJc)qU;#Rp|d=9l1et_6QxokG`%zbd_oL0sD)LN1=lVGlXSpX zRp#qd?eWD1Z@-kM^m=0^&%0b7lBXpKjM&H636)ThTX%hjU?WJ-B`1$7WDUp=YSr~7 zPGg=A-G$@V4)!1=1{Rc>%F$4Yh*`AW}vqNwy&xM8EI;SvC};k^j*ob$n-^dFa> z`H~n?kH6AYml93!w6(8XZY9-+Bu-Cf%awgS;dyttjIUPSt`;(Do-X+~Z=JOPA zAg!J1=H|tOI+-k+Z(@gt3vRNdze$fm#8IIp4kBgEw3MKZk#Qc_iL=4Gjj7{E*!vyi zJnau_)40@5V6f`v-5~2B6GaK&Kxnjjue!;n^v@#yRG!xIS?M8s_F?Y{7|C?R1Q}7_ zAJEYqd!4 z(8$#1XIq4&A(D|;r% zMiEEvLw?T!B|w2_NNeE<{bE~0*Q&nvG!Vv|FJ!)Hb|lh%$H}D{hYlC$W5S=Y=Y)Y_ zUTIYc#7FRki+bwxc+3f^Q_Q-gK|RzpnWE%d8=7D@FCJ4BwBb z1dyN#_}?dG=hm)`Wev(TFRjGn{O4)wTC@@P1@U%ki95pmBd9i<61+MooWWsoV84lr0%S zy0Pnf(jx(=91lt5lU#m|vq3b5hw-WhDmG?*Ma`h|hl{vVDf_P3w5y2(QCl1T_hR(h zBo%{4=LXT~flsP1r>5BsAE6w6VO8EOyxCDjJ_mM_24+3F_dqsuXmBFow{tx%h+yY+ zJ{r)gIPPvD#^ftrtPPUFmVhOP!$XKm(gx;MmSOmib?=7`+F-UNMqbkn@sR(ox$ygO+78o?=@cs^b9L6gDKBcP zAhlX~v{ALSU_^V`k#uc|<)q?!=Xi7SU_~<){R-kZ^NpCf$$%YF(ys0m+|AQ>^3O!B z@Uf~`O>a`=z2FFhhX}^Y$T9K|`Kegie-NOdjM))y@miDbAB_FECDb@N{?_>2KX-zUKdBwSoglw3&rglbTNWH_ z?rC|dsg7?QKM@J#PPNRMrt({+gk2 z&L`L}82O!Td|u*rs%W7Mq=inGh7-g`hca> zDsrwpsqaKAsZfUUNuEi>$aY|aS_gCTf8*O5jcaOg{d>(qgqI31m8bPm7(2Tc>fO4O zi+Z{L$3Z)yPchB&V3!q5`0gDDi|AO#&;(cX=<2t;(2KgkIM{>*Hok^tUbS>yR~0I{ zoaQe@cTcBwfpvK2_PcY}P*z`wF>IUyrvUp7YmWl;qo9=gw@~UiVv9PAKhQHys3YZ?kZ97~-^oj!>AK|lNW#I+1Dg*mW=QuO;>X8q`%&A2lZQ^g; zd+;$_Ee}{4YAXj=A#SPtl0iR$?LA*CfWqn*sa#}WQ3DQq^Xjg#XVgj(#tFwEe!J+& z;2JU9Pz3Q4;8YCpV_ya>E(cY#YB9^dQB}_< zu-yzS`*jdRT$KljuIlDk04f`NP4s$$wLvV@e{5WZi z`dqB-5b`fwV=m|d^*+eGO31`w2z&jJlJ3#|9h~}nwA}NgBUrr#j@gIm-dWj3f*%V2 z7!$+WeB^wqx}OlwfPmQDM4f+gLB5|$F8y^f(}Vbe)~n~@wN0#=&436`)8cq z$<3aN5o#_ijkiuDbT)P=)sC=Svn5;1h=r?^T~N~^!$Qc3%kC_R=IJRFbrVx}Jzsp* zv_nC9E7q`aZw<^oN|7p3cN9&IMl6IyZENKhz_jwr9aJR|KVZ_IrSCv+RN}~xwh@6@ zPn7duUrd=xc@>)~Fi>PfrWavg)z{X|#{nXl>UNIAOK zPP^EM7|N{6ls_?=wcSV5_#ts6Jhy$`@f$e(W#z?Py{4*C4+BrO>}7xO zDG1p$+7i1U39Xi)hpXIk3=&eE?1HHoV7H8j-$g~*0(s)n2YiSUS-#gTAO~lB4O-Wu z6NjD=<86+U;1yQM9E)M+q%JAuO__zD;mBj|v<=o+DvghOV!O=|>pug&PB@yXi|yhCS^)7{Dg7=`7*B z;Y+>2De~+hbw`axF$m+Pm0ZmSBG4q<-_+`&oQBVE6#4JF15@8rT9PcCmZ8-Q2wRAI zls@F_vbsK^NjlLE3Qr*^0}4)bzD3QlMo$NZ2)r%%SD`B#0XM`KG5e`f#y9GXpN$dx zzxJ{j8S+8=f%vZ$y_R$qv#zU&JY*P7Wn!rX?IMsmON~(T&DKXHZ7(!nFfc}{H1l9S zy3$LCuHLLj7uW|r&q46TAZCyp>*s)Vd=6J$7v(=zd%E(2anYc}|F-U_2^L(*tXt>_ zBYg)auZFc*n{DYh$SL$mWZrjKmbwz zL1491HCYF~R00vNT_kE(WVC*1KYr0}B3r2`^v*V7RK4^c!>%uJUj1S~Q$z3wmyk+y zg40&zgELIvQD$@9nv0fn1rxM{%(!vMADhI^SMjL&py9c6Yk&_?d#UfLzu3-|8ouz{%2~rabxcT;0$t^aR^wo8>MywH8X#PPlq zHs^YO;*>bbl|e%AuxRaKfJ`8Mf-ex2RYuHI8MDY=?D7P|Onlt`0BXAzw3@Yj*PFkB z#@jPnkN1#RD-Y&Gh1ehiN=%`#DZa5pI`IYn#5UUZvNNz2^WR_?zLdwyT2( z>#ya!sKkTY3y*sRgNLl*#YD^QVF(4}0I-ZP-S`fG>5vxz*7^C9;ko>}AlyfAD--Ru z%KJiC;P%a5K3%9!a-g$b!q$IB<hc)B?>PtUqkTp$L*H;gmYtO zZB-77e7~sMHsssfE)ZFSDHM{fR0C&2{%0Q!6JW03B4pMPax#eGE0-g6`?cf;y=$gs zmoHGvc1eIdn?}oo&3ZQVZ(1hBf#bd)*gl*uJB-;`-w1_(Y9@s$k4i|o6r?AiVs}DW zH=jZ__h3ZaK|)Y!-AY}!382GJf9Bw3bT)>9=V-r3^VUL9e$JXLi6gXb-x(Tp{fmI$ zK9pbp0~JkjoMft|Dc~v~wLlE5AK;4jSe{If1A{_3_JU`G7bT1&)^iiSZ$!*?j-bYD zr*QP+dFx9)W!?+jD#zx{)9alHJ&&gLgm{a0C^n?rYzwCqBdZ%Fj|R?Urw@(8E@T>8 zZu6ID!a?leP@(l7c5wlauY-ub`k&IXf#9iTDO1VNsDXfTdcyNC#C-QE{uNnw7kn&I{m^`$}UOey$J znZ+icn@mj!>mk?Ms12Yd<8|ooLAKviy6R;&YOF`V#emFkQC8cX#~WVGnM?sSs$m}e zSlCi!vC#%~MwbvW%&9{|_)E$u0P5huRb!9zI5KQIUk;d0m(g!1q#B0bd;HtC(&;LK zF$QdVm}wVbRqY?I3eKO>onm#)s{jn9Xj7d}!wyRs6~W zrARvn4w!@lr8XaNW_E#hOYd}=!HUQ*<9Wm;^Y-Ddp>$=I>)E2sZmx9Thd~y!wmv+c zy{*gbR+?ZMKN0+yb^k#DhTo#paNwr_E*{KJE>R)a^x3LJtLAn#OhmCJTgOEPQPld5 z<48?;DdG*1AM*(lFU8~%J>6BLoD?SH3b$8_3;*NW9v`z3u@l}?iQbA6{lGrfg5Hsv8Z_V7r&%p~WD&l@dxHjp)76F|?D)9j9xM6gpu9oxT>N%_E zj>FWpW8wp?ON7uHj5ZG&$m$an00094qsE7#{tZ3mm3>vv@ju>b3bp;@N6TdAm@+H} z+1HB-_lQM_(AImta&6TC0G#{5C!Jg8x3xYOTvk}M2)q009Q1N&c~hyU7zxj^m6#_7 z?RYj=mVo9)9d5;tYS1bcdsgSUUCuD$x|@`k@bR20XsaQ@4ZcnyKo#@S$|RJSo4mcs zbni?Xe-G=BSx8iiAb&IL&jxvleY0~XNK}YEQYd5p(0zH!b8F*c(|VrYe5ncMIzYQp z3sfGnyL%#mjk-!N^-9e57!+z6Ks-mOs$~6|VFH%gOg#T3OP3H<`$!o-j*a_na)18ttz5cWv)8?a+`2j5$9fFoli;S98Hb7^tTnAt5PUouUY%>)1CIy*?cC)lrK>4KCZVW-eFLqu33>UCVx)2MVrC z1sIm6h@SpCWv7m49ps0fdPGXJJqF9{IRJVlQBlpUVvSxw@nHIcjeLbOzEz3_9MAq-i*`YxXI6=qGc0Rqt@Y+!^&A@CY?<$=v8(Pk0R@;~)eZ1_An^Rn>o z{V<-_K4UPt^|mUyBEr|0E$}%voXmLysfc9Zn0D?G2a4YtQc4sXfGN2Qy&wdWOeG`3 zYj(BIs3uSWNf4T@V}21li}ubX?#@yy(hGT3-bL?5UXFaiMKBjKnHN?w41-X>EPFr>uK@6Ip=?WVMK5J-^~f3weUIln>FcFR&MKDUCN60D9Iv%F^w3eyrun{}d|V z7x8qL;-m<75U{9nT=ZLF>Dh^%ul>l|Y8s7@P%J&vf8`!7W_O5H-A_R`DH_Bn0(`IU zCSGfKCR)#tWiCbD<$k5uc)xaUgCFF&u6l#FA(ErX;C7yJ2ZWDpSWdD=LZpn_mP}}n zRol4eU~-rIZWFh3p{6`)n*)%#3i#Ma*ITH6%-3N0p8Nm$>}T>}KHB~>e9uYA*30Mq zcz##%YaHazed0*|3%=>MS+}%3lUU#oFXbF5;;nJMV+2&QLEL_}$TUj7m^poDTac+bM7vPdzBr}9gwOB+=0Ov-LgV|>~ zayP`8v&v@qusl>Cz;QvsukYh-fGwnfuL-wL6P?0)91IWOK#8(p&VIv3LcxcsY+L`r zxPpN+O=);EF$9~x6=Ri{X4aIzNT6T$A}9z-^(s!9SZtP8Qu#Ne+=pg~TF^X`Bnx16 znygKTw(V7XT%<%n3t#eHp)ei+r$72>+2n7ghh%exb_IUsl0q1%zqF@Vk9D%W4^fDW zyHEdjVT@#vU{K`7&l3W6f$Ouwb!jnaZHVR(=V7cths?-d^(=0uJCU2P>p%x|8-K14Y0;l~8fN?u;}8i9YT9(I?(0>9|9Eul^` zQfO#$!Bwkg!)Xra@+$S&Sexp%51L;z6&4PaseVQfoy3|*T>yspeohOZX;kVh;GFI8 zAKZF2Y{QrBrmb(fy(gD-tWsg%i+cwk(6%A-A2#8KtjJKbsS=dxM@)WWOeOn*7S(Iu(LAb}uj+j5cf3ZiT|Y3DFz zI`lQS;kz4E;eLT^DHMqaSBsRW3UognZp#p&xlWqIym;ej2Kf;oXp4NKw)hV)Q4x~w z=*1C@!~y9pJXwu8Mr@S;d$~&8$rR>E8d1HD-QgPz5Y~J7U(Wi!NCR@LBZRIldV1Df z36&NQ4`-Za$9iy)NM&2_BIPq%Vpym?cMjQ&LA!1iN9vnM4J(?dI{y}BI)1zdSeHOi zaaMJl*@_RQOk3cvOaE2yP%6?CAdoi{id!_H@DdtG-)!hR;+WzXnv|-b$|r}FOiRq8 z+^L)1i{maR4m3DXwL#?5FV(+_W0xJZ0;gZxW4s^(g$E1N_J8ucC&zp8BK?6FRUK({ zBESe!P3cZSP-v}IajfMxzF6TALCGiLxxXfgU_VW=w67w2bKmgcqYm7};^-$q4-yk! zyIY~)pMq1kTW=8tVU71kui}XVFMM+|higOzvqZ6sq~JkIHYVyRg{f|Jz%>>%Bvh8x zzJj#{oD3o@K_WakEts_b5(lKdU{(S1@FDw}edK4DGob!H|e`zJ{v2o^KbQ=i2%=wtEBW-{` zE2o*9DCpIPW!&_cyd_88Z~z7^gQ2|`6|d-8iM^kO*AG}HMdWf6pbh~V#tH{w019qOM4S9JLb?MO6A(@h7VW|#!d7o7P6 z<{~nuC~&%`7TGs%HRsD7c~JySu33Lth2GvDt-CRl24;|`h-1S+ecJR%34j0hZ|C*? zso6x&IQ2Zf@J2eh6erC`H5tyF*F8q5@}iV=*>7~Rt=a^~OX;ubedQSaZ42C0nimLZLsvT1z#*E`i8fPhZ{ z0SA>k>33;KK^1%{qP3oD;n}bulMaEJ|NK6qe3mDLvMKpe`As-~?MfZ{d%FEWWP7yx zTWYA-s|sU4UwOxCMKWWjRwK~^n~uuc8zPx72L8{tEBtDvvO*w^*jj%ul2-VgUY3s<;npUjtd3vpC4iyF>p2^SRv`>); z3asga+KQE+X+}#7IGMuq5L=iX7tHQIBJo}-aGz-KsDP#2&~l`BDnh7Dcvc&At5APy zgil(5QAyrq_y7lVa79Y9wzXqC z-Rbgs1bwEoNrFvjq|;q6L2=`jt0OOqT=3^`zg zz_k==SZWLF{Rr1P1}ZQPFWX|YDEsUs0-z3BYnZO69pDEDr|4XHfx$JZRFpI5N2d;~ zsu!!qaNknIIt|rOOXwbut!!r}F9u?;1ZI!t4jfnqf`rA8cT+bOn)VI$Hvh}ZWg6a| zpLXne>PC@G-fv?5=z74o#K5-~l8w~rg3%tmVl0}lM#sN% z;IzbMwRvM!k{+oHZ+(FdnU|Z(XgB#aL#p-#H-tkzG0E~x3>Stz&JEP%fcvgC-CJlE z5pt8tT?f{%<%Y?dPz1h~zC4vGoB5BakDEZI zVN=RLJFPeL^el|d?aQ}bqTTb9On4+#ZZ15tSycDgx$@`T#+riNPk$Zt--SZhHj1^k z^zYQpEu@;bx8n#j*+99kI8NbF?c7MVCIf~bkYIAq!d&4*_)}|^K{y@$odtJPI5Lt` zWN7Da4zVdTi>LWLlwgE4l-BSs*$u;>TxvyJA@s3aT6 zGknrs)5usi&HO1mE@ZnWDTsDaQX@S!lK^Xoye9R*J5v}B<&OxVN8FparEUJnMh6xqy%;d{Cfqc^X5W*|jJCltq{%<(;aVBLv9VHv$) zdu;~>YRZmA*@VM^B1bQb!Drb1b5i9(o}r&V`Mu4x`pj5LqjPZ*1zjwMzftYhyrN~5 z5zkpXg6liC74DD|aCNW&nEC7(F%U!$3s{Zpio-US3}$OabzXd@^az*5Q$b zHd*;gjBEESvBuVe{K~N^tS`Q`730@=#)Zs%vb_9lH1pevsaFuek-i8Cre$_5ei7Yr zF<%z3IrqMbAXd0mc1K^|u_B;vq#Ma@Qv%6ZJp3GOI|3J^K8xdefX;xkDV#QXKR4Lu zFJz507`UV18AH8NH-RGhvuN3)pJoUTj^k-mzu7UzPfbqX(x4fV=7BWZ>P$BsHl*@% z@mFU$a-+o+=L5K3&I7-PHcgS^lPny6|3%^0>p{#jEQGu1^- zdlIs-&p&3;(OUNN_vrm%D%I(8WgzsYU>K0RT4voW3Wb05N#?di8NTT$0jz$GX&=FPw^?*V5 zklHtpSE~L+UfJ+P)yscJ-c|EP<~vAr-N<+25E)v%aTkARIxGp)O)@EWKFJXwN)(Qu zyX&j##6u?Lc{&ht+7N1E#Yo7!TRk1`EvitHosRQwOPSoSvQd3EoR}|`zgVL1e5UZ0 z11IJcp8n?pGsh7dDBG>K$hDX4lSDNw9+U1Jjj%l(B#g23eDAr~5?qc%OQr9Q!nHI< zE|iu5cGe-$D1*-8IM}PJ6QzC8-L~p2V?+;ksk37|D}8e{xKdrFH>u+I?u`qGv(8n} zu1!yRn-5Ze>9+i8r?@KK%ROWyF2MR*UTqNvOn|H^SXB;T_z2+Tl49Wdu%||SQ5Dk- zz*~EuJYa&_`qKDP{16Fjnr)lh-?`v;P~fC7(6cYX3j6L}B`~cBE8N%#VQ+k$H-tiO zeb=t@V<(LlNo*z6!D>az_FBB1ErG+*ss13o=^)UH>G1b&6||O>GD8mwogQq65uIRT z@?2>DPYIsRU8csGnaMrsG61iRMci5^vP%k5TJ-uy^S^w^h%D6|UbPZh66pNGL_g=O z-SreDw^ zLSrc8Xra%_M66Zt31rc(1<2)eO6BdBTBZeu1Wgu(ojK$9pV|4U#4>gZOT)E3%)KQdo@EepGuMJVOrgs#iRcl^}W_w+VJd> zlYxJ|*FkuiPfoTg03bKaCWX^sgFo)1`B88(8Z{nU!n|MZIVFHO<~GU zS@e{^#|c^oJ3e-wXmXlq(eohr@{0j>EokGoe%*(+!2BZ4ORjPWW+|1WV>^(B*RCJN z{IIU@_D^W?R_kbJHfgr5n3e6iy+VA~I+M6ey8*R;^V$*YnP~t3{HYaer{u`QBWwz0wo#Wjl)$ zk0||oQmq5LS5JKT)IEEG)9^Q2>HFQ2VDgu1STT?P{WZLz&0pHrX7^7bxoUdRJ9eah zTcg*3-Pz>$6jV-+5D6)8m7$8;-fA0{0IJ>!aR4a>*;VpU(jlvVtt7{R>`;D3n2Y=Z zz9Jo687jr%;$f?HYi9RmI(LBzJ|&M_z+PVNxIDT_^q0!6{H?x-6ZKenCa$0_7HLmHGK}LL5s)0hFKwum4h-0s#h`75n&Beq}eQ2qKdJxvB{4FL4J7OX-nY5lEVm9yw# zv*H4_F0sdZs4ptsB1BTOwbKCjIq3z0d?FzpTOC=b@;KQDrpHBt);E$PCi3Q`+3Fpo|O~zPM}gVq{P$LT6D7CK*Pnf%np{33R|KZ5{`&4Q0f(me{(>F5qXMSqFigXhM&Es@1Zj? zh6Z(c2Oyck$TA+G=$)`Tp8lZxWervSzxKdz{!r&tC=MNt!7b6X@`))|34 zvD%gSV{L7xW^^`orsGf0(#H-hi4oLOsqE{L;T)=JyR%?+pD6_YKOEIk0WxH zm55BCaeW|s&i!IXjFL@Gy%?OfKk%sp!zZZAu(erd1}maNF{ouuK?RrYY_W@flHqco zjM{{0*0(dZegh9t!%P^SctUZm0Hf}FU(ov2sq~m{{b*dwCAgM4B10pH{}>;Cn9*H2 zxb0$}mEuQvTE_u!e1huAEW`SvII%^ zaiNf0yRh8xwe%PNRVL;-mA$$S9Vj`51Q#9=IPtOMj^n)+ZNsRhmZ+wj&d37|F-PX4 znAe89WPlQqxx|{=Q%A44+DK0y4i6v6Xj>B?lmDaxCVcVXOj;SR^^1rzoky9$Z{~#~ zn36yk7@2(15eBR;sU$sb!U0&7kfJ*71|A*8bfhgl*WX7_#LAZ-L5eo5B1yW;f^!)C z;(YNLty@Jd(?N19FwPDIM2=QtoW+1rJ^q_ZRB#{sNS%=Wqg{<`<;ca&TwKW~Cvh}Z_gj_3Qf ze!!?KrbKh>4rDMYC&NaCUP)O0uDxgd3d!sRdSfSl6SZb=qJo?%Fps zm|`#9*w0b8?Nfii(ahvSaz>$~gpgCs3?_L*ODU4tfPaA)j3VLDnEdmq?~VyOhg>?F z@C1AzSSVS=wv`wM3qZ3g1Z);?f^^(LRh3)w4(DBQ?;fnOlJOp8Ng{je-y#zq^^N@_ z!9Y<4^wQaO+xx3H5}AARLhHIuLPmf*R`?|hEjsXCaoJ2fMzf^~J%9X)m#q|rgO%J+gt-P zO;Auv;4GwhK$DU1ETuA1O{U^3TQ`xGmad?J6l)W=^r8U@NzgV=SM|gE%a298|6b(* z06d{)C@}Job{z__>q{i(YSYQLVXOqVtuSjmZM!Z6niNe{g?yEzU=I+-u--&z&d@1{}h=I20^=BB|;lKa|OFsSzkzN}SXM1tbtfw zly=;eS=>YeQ>bPCkSor*5kW>^%H%8a&4ty#YcyNV!tpQC#`NcZ@MAg-M8FQT=#K1HtCsE>wVhgl*;VRAs|EU^~(L@?|nG3p4Pu$!1YHRY}+$_aaMpygyPndAuA%f#Y8 zuAun1qo8!Yt9n!g&~u4$#M>=ubD|BPnnopMUj#f50N!R*=hMZ5Zq+)h!Ac;Q+0FO- zexRhu``V(-u+d`V(D0rfBcdkXT0E%}DNFcnkVuSN@>>VcNcw%g>_XCnka&j9?8DhOt3AH$pfF0Hk#gp$_xcy?v?mW0FBy|h< zc+LQioHA+;-reL*Rb8vEcYX9k0v%^>r?JHJ>ud9N9kQC-)?aj%Y*jJVFp}fVzR`m? zcz^3QI0ApB46Scj!!~idpz|e9*#>O5WmqMZPwxO) zaQcaa$$8@KRXqTeM&8>UX~+*szSHkBpcBRb?NURnhIha*2hY$1=v2)^HB1o>M8v;E zbdDL7_u6j$pG-xN2sadtwI+cLVI_!sMk^oYB_jlVo5^xh0bdTe(+!4d1-zXMSS z?u?+$qb#Zxvihz}VposJLn|eAX5$t+wHxY!0+{5iz*XzOmyu(w+P5BD3%jZ4Utorc z7@6e82Gv$1l2rehBCqG(L<|Hf2cwdjT4Xt%-H3|OLz(!F?DB@YaTk-sZlu=9eTz~8 zfqpmMM@w`ZVT&G>8cIr|G;cs4wtfraNAK&fcg2|TikB^7&DOO^&3NJtk|!c93dd*O zFw9;@-USiISBr@gm&jODk~!n5QRTizR!G7U5CI%y87uDK-*u>ay>GY9yE4V(T@F8D zeh>Joe!vtmkN}yBaHIxEq!Huij#wZ8H%K_1`%nE=@-v)tp+(J8Gkc|S#O$&Z((^h2n7aR&Xf`Oj@ zDgcORV5Ct-3C_7!*kq82YyH5B@-{uhAe%p3;OM)zT)qHCovJlnaSjm+=kO6vEmBUgI8 zC@1DvSMeKCy)XA=Oi3vI8$Nma!gsjt$>0b9Nem;VeHLZW8v$XU^nwy5#8XFq>{Obv zQBl9zX@`QUBFqL~m$r~HwS@MuNLh#RFznXlR z702fi5g4CelsRhCqc0u;cKcDD4|ct!v6<;9fG%_M*v2jJzRJ4vOcNya2OOo^JX`A$x27KeuD{ZhzrJ^^B$&z zabM}a0+~ocx_&aq=Q_&7BqbY2#gWP**=P5gpMJX1vl#V4(Wc))d10J=-obkD^zjJ* zL2PDn?32X2W!qVNsY@K3!O`p?5Sl~J(`t;|TAW$I)5dr&1vzeB+E6iwD5}m$*YJ=q^kXvy+QB@W>LRY6HJsn0>g6wvQ zHu|$#ueU4Ul*Wh2NH7N6D~fdljZeI!b}zAS0DsZ|;illPQ~YO?ors=C``lv>Md|4s zGgOCPk|+cj%Hnf>{VoqK(>do%=&kYl*3faQ%Q`o>dVo}1y9G#>b~DIOu#&t4VGPJ_ zJlp7MvqGk&6HzA*-~-r>5sPirhghhC@JG4FZ!BwWQ?(s)iovYAS0;u9?dG!PF>gPD zD_;qAr#y&pWSK3Ya4bqP$=|(J7$N-AtqDaM#0U`kq+)DnWp;^aU@3t`lTku_3Ly zmwM0=>W9U4Bph6S=jY`NkafrFN-eW)MsLb%sq@SJZ!VnOw+Dm5wA7EhMAyjil@P$2 zMw8ss&`K-)zxJ9%y>oLk zQH&K++1W!lO4bYBVn9^fxfp4FzTA{%W({L+4l{2ixEx|lnMFCX!_nQki;7=`N}K!h zbU=9$XnqUmCkk>9_a4gaopBbus$8~RVfbk&RxEQ%YZJ;=LBwro1Kw$57kO__g zSd#}-x<#t9^3oa!n$I^<&Uu`nq%jK;UMI~_kk|E)$H%w6xmf7c6B#=Xq1=&7o zcNz;Bn(3xSF8ds^zamXlzWyAUOSNWZAY_^+L^~$L7)#8QRg0wN~2oVZ_$gp51}q?S`wsY7fB(xV`{VwHqQVRN)Q_qG zda9_2d}SX4s%ru(TU=>hy9H{|@go~T;598G4sqTUfO0*Sel9H_V=LKDH*#2&`6BKl#>64lMQ(< zma!}V0NE)cwCqt>td$xhMe(4C@q3)0(gpr1hRv$S|A!+l_30}FF$TIG*RX2BhwiZS z5TuuO_RnTxOeBNMN9~sQ?(>Fm@#+!J(XQP)8e6Q@S(|W$-m9uWM>ar3knc6{s2Ugu zKIN0AFQx}vydZHK)F9i_nxQ5L2S@dAj8x~|5+Tnoe=(VdEuuxHKv^5)F9bg>CUG{? z24z1}jnM2dI=t*KW-brHl?%Yg;GDQ&>xFMTOH5 z-<6>nB2iQ3kzkEx7diK9R=B++>?yZX_4dLXH!q?#;`0rsZMoeVcr=D{*du{hV1p<5a2~ zrDbKCt_b+hbr0X4HD9QvG-QkV|48%+mror+!MRk%!PK{IpN$Ijg2b0}jU~F@Zx5eov<=}j&#+a1q%THw=1Z=?I zp9!@eM(yV%WHRfEdJ{xC9X6`^PbO-PlVG-+_;!vB35jTSlNt6_Xq`-H6>rRTtvZsw zN5f+Nb))@EVj228uc!VzSg^z3y6$G(1-zk#5hUksb$5cOivapHu}$pqjmhy#m999m(ChBQ0eH%QRafFS`Lo8Bq+(4Cv73zy3n=ovPCa-?=oH)p9- zZrd9&ZV~6PR4LH%njiy-MyF-GadsG-n=4n+{x}jR$t#;kNOupa?jazu&ChTlx1r9; zbI+CGnY|8Ts6CW_0t4N6SUE*+edNhm2p&X)sd-Iw7%Xfno)ar<2Q#@6mK<0X==qt? zd^HU24;J<6^{XwHuy{jS3Fq3u&Q|8V^lae`B*w04{N?)m|2e`G$ZUTGT6beIToR=n z_{$pbVA3g=)q?4cxSXdGUgg^&tj=S4ggcxNh{G8Mn|6fhXgI2Sm;F>_QbZ1^dP)2J zB;DvpHU`J`=jxQKsxl|27`8yt-0J{1&@jkOB}X6J3=OHJ*^~Jl%6=7}5mvy-?^boR z+bv&4qrT4{8^PbyOP7l4q-@H`RoUw`8jv~O$+qS4D_3g>N>{IihMc6fGrLF-D2i|tHL(LIqd{p{JO_4>uc$ay;O!ZVb z?s+yygtF}6dN#4UH>&DLi`@?}BE3h5Kmbi)HQ>=66OVRN$Z<->VtwC!A?#Jh`t3fz|pA|u#T!_7S%T3=8&uhdZRsr zMi5R|?nl&9`wx+*F34D}sD7z>V>|2I`8gLoTCT`c$15`+uk@125q)(9)DhUgua@U* zwSRzCk5^M^Rb)e!Gs7rk*{L<^c1$lF+$5}W-%UGOvJ0KL5v3#G0;;!-fl+GDBK zs0t=VJe8J_S;q^Th1r+1B7DJry!5U8VsbSkVn)3=Z?8&+J_b^a2RYzUq+i@vibl}d z9%l7JzzV6iiD&cGAq;Snpe6k8(e4h;N zT)mHt;w7B+^%12-5x<`j#Zaw<9fhRqb5m&no4OBc-pb0c?EVSy>K5ut@h=2pU8geE zyzSSE<5Je>F*L@7xGC3n46(c{+)^5dnk)Jd35Ks|nD60B=nB>DXzE7#E}2rW*Tono@~Gv~cdz0^Z|Ooq ze=|<)Z4|l|sWkH=Az9@Q=4hnw!XGS8V@McB=1>R0S2?moQ0g&MX#B(t0ui~@qpxh7 zmUDU)e@Yz+f`A_6QJEWfb|u`!(Ma3%@JjDP@-(qajm1}i^z0Z@4A@~AdA!ngWajIC zAmjoWP}RdvfgEOC1%4J{zFg=32WD+RordEdt@6AXQeMlEWmit@z_ebYmbut~S3A64 zN68lZ6tPmzzBmiuy#lBO_w)CYEm{hf6L|B4S|usptfOUv4!agS)a^Y@bv~Vv;BPy|3OHz2O@;jJe@fCHzz7 z^sorTL}J37$XIXZB!@7{OFIAx2%PO6Bpf#TA%SMN7Ki)1TMECm7gMx-Ec>ps;J%AhU(+x{?15N%5{$nq21~|v2 zTAPOmMu?W~OHhq}x=qKd%NfiiU1Ew3kQf(=-_pGhM43Vm{_fhM{bBB}Qj1JH`dnt#v;K6isStjaTmL()N5 zbQ)8Ualk->WHO%Je6^{bv?<8G#o6)~2;M6?5AgE>tT$fUCt4uaYC0J+Ru;t=GvBlj zAcwblE!N0+cPj+A249OqC4?v#CL`x1oOX0zeOOpzPyzEqaGxCAF{x31=8p<{8~<~* zl8wQ9`8AGqQ`n~o1^-~FY$Yu&15&pMro}Av@Tz&BXr4$xgo`%^azC?N74fZsAA6Wq zUk=GwS;{y!?xs#esqME@Q#+>{45>p#j@4xui0kgge+W@BIQAaHGAq?hql

R%)lFk)T~gaaaeS!F6#lu5 zrSJ9RaMpjkq1fUy$CQtVz?c^7yXwdN2XTrHwmEd6+VkW>94bdV^amI!D0_6e81MWo z{oE#nw?W~~Hs&@dr>ymO(`@%q&O0jl5MbTnw)!5N!R?}Ou7ur^O3AZ82@S8llSaPr2p; zWBOA8;6(iSf|}e=6mYtHw(`+>x&K{EnU_5=+#2t$^l#(MZJZuSS)fPgMUZi*P`{ zDg;?X{l*jO%k1%|T2r-;1#)iShbtGVV=%!+~34^uh~Y z`iJ<7ojklxO3ssyJfe@oOk`#=M7~D7Py!%8KwmVkjXgdTBSA3vI~KM3Y6Ha1dN<4z zoxlWLTUo|GNrg~>P3y|dIhMYd8b{zG;`rscj4W~#l<#TI3iJ}EAy&h1-g@p{@p|qs zdegX`H;M7z7y!g(!g@^pGJ6r4Y6V}(fU%1b1-`DWaOccn*A>>N6y``dq7vm8Spj{m zY$z*GtKN5JDYWS}PqbrUo!=?G2AuX`7lROi)Q~Ic>M#0xXaH8eu>0c&QK{VMU@Tq8J=e;=WhO!${mX6$(6`ODl|UeP8x%!kH;`01pt1_#5APh-<6ui z+c~`!8q{Moaqe)`s};nx|bLf634d3VXGH~E!pPh!n@@Dj&Y zG&!MNqwF3%jcy1x3*0e(jY$>Uh66_C#$CJ3emv6)mcwp=Jeq{5*Mv!5L3-RY{cPMt z(Nx_HH1z{zeabBWf-Hy3GP&(=|1d*8o-kgIgQ@^|L#oyXKZUdyNmTsQhMWcwKL)^ ztbvc3=kc=)@=4!_aqC)mR011ktzDbeQf|(jL{*|1*2@lkqW<>is#zw%p(o^;uLkh& zVVzKn?` z3Lg$BRg=iri70cV#(+inFiYSS{FFD%SFPI!AP3JvEfPK^`=0WhWwNudcOl^##tnN4*h$btPtYT0 z3GAW-N_fn8?tnJ#Oc&pxLA?bUotDg*2im_u>{HQyJ`WV#10V5|ylLT7d6w2`L=X6N zT91ss0clXlMiYKdx>D73J(sHRES%5pCfifT7u&}=4)KcNs12^pSXS+rjongwL4>&$ z_!mV`pmg6_%uBBZX3?IELGL&qe_Hfa;xbV&0L{vby{rOluj z22>^5xl}*m0Sjw(k;!u&-Mgd9K*l~$m?=R^kkvt=@T#3vYKt+PZFO@%`E3Ccgi`T!-?`iV0z` z%4n{YXt%cZXZytUx@B8BbCv#f3yiqI|IDcNzp8)eYC_rKG~SxH_Nsa`1q)CvO6Uu- z>q8u)|FuHyKr(zRlO#O?F2WUg$%eYMp7-Lftz=d|$IxT$7r z`$X4~vaQ+tLIgeya%aRU-UZ>cp^nf{K?t6N1x2{@TOW(+AjnbQ4rhB5`(%@x|4*-W zMolus(fUpU4*o4=uc+ z8wf@gPJ5-*Q|JAP;st9%(Q9iMby4?;uO1T zo7JTlBWGPEbHK&h-v*}@k87WPT`)wN zVw`DTjgyG18lIF95r1u!jBm{>tu6K+r!h-0k0&PCv|C5wwBT%3o=u?j9+>afg12;- zS5DFL#Q60MF+J0A4+E{^+vp}9qI7R}??U`p&}AYYBUJFL>%her5k#@B(=b1x* zFkv!kH;AaqKR|^VW%X}5u;57wi_@5%E~9uv$JZwdM-5nti)!SxQW`qhpTUf2TA-|h z?)cq@+S#8$kBm!1HPHMZ-GQx&%RT_ler`O=m+F)-Wov`7srcPRwS0u9LbW(Id z^&d^H2~c|WBlMy^ynwNl=?2;xV0Qd9CxCEa20s&NsQQ#?F-|BvE;OnDzDNU(>)Gkt z&O#CpR6tHIaW)5}x{U35sJS#@oJIE^Ii)Ji&4wIMWqGa?G)l5aqg$z0M{=xhK(1S% zmhc7A)uq11sjY%Q2)Nfc_S9DtI5GG$vM{#+RF3b?t>n9l4rw%+p(yG>4MG zrz?;e_UqS~NA!qcdv@YKtR6v2Ci|Cz+K-x=hEHJ=0C3Qa?@l)PwI$unM#tj=#x+!% zK>-L0^O7;4^zLI_2T2fHSI_M|7iN2h7YIh@_5_uRbu!-a_6=F5SeR8u1Ve_gtNB%5 zJlKdyM{^|DDuhE~)Fk-hUO+h*pWP;~oXxsF4Wlh8!fr6zeB*@WLw3!&Vaq!5U~n6e z@YPDcg~P}?ZB{{(h2wnK8Su%<5hw)JRJ7~6@R|k>J32mR7!h34WpIFF>U?egb%$8s zhXg^p{*}{F_jBF1I)~j(j$ZXE^KQP3?@>-rt5(Hc9x)S?*CqGOXt5#Vbx*I1D+{9r4dgIWH0}ik^ z70;{D0)8lcsw5b*-)COCYuiaBvhNA)?CjXq2Dja>j^8 zAq%Tx#fH&9B=&xN1~rl(aJ0_+e7!i2e-xPRj*PXhpb6Xxmv?Qw2QdT6S4f*^{UP?- z!%G^)lq@QcrrC=n8~tc!Bl5DNg>`Cx4Iq>Z0^ORT*=R6sQ32_B7}NrNk@U2xzjU2( z8=P;~NYpI2OunMrT*7=7>dM2$z%;g`^XO8ic5Oy?A_aLlZ#t0F$@)59Bvhl#+=;L; z2&HPd;o96rWYK4cQUzrXKC7fqN8*REg`IAMv-)ljD+iviW1?4Q5^`KX0_oVy1wWz8 z=A22HfFe8w$xeVyUJR(qo8Q!KZO$y9jFCis^p#deR*l%m*D>%6i@6ON=AfeXZWdzQ zc^5%2^&7qi5SsinI_-LoNxiwT)w1LKKBGGzEN+WR0f07~3jiRMzD5keu4d zW>TZL%V85;*t*IAY73Lx~C@;n(7Lw}7TK8skJ@UaQ+J4Mn6 zj83B-OB@moagf8)-F-F)8!-86CO$S1@o861@SuMI({I18b2_gU{?i@3)qn%&b!`?) zSWIXYZ)2eHoHNc>LW=}yqb6RDy=gxl*~l^~9C-y&6W&(`fyZ<}dWV+WS$b`<%sIMq(z9*$H=kZXBQRmL-nEo*;I7S>kvM6Cw9FKRlW6(sT=MT{XviUUe9xftZ@)ZdD~q5 z0g=Q_;tC@VVMZ<&Op^(+60ae~UvT#nrc0lhxw%vhT;H zy8LA0X)O;@5wzyMPa5M^S+4tCvXa+7qU>gsFlXNi4qs!bJ>esRAnKeWmNL5lk^nHa z4p+IH`qaN6PywAYJC)*?K{dc2Q=u%a2A$~`#|Gt)mQQa^E{0a2hn2(ljpt@8=(G@% zy1(=j{x^;IJc!r6E!fScK3$dWA)JnPv;G>fXmU(f(weWs+VHsfHRvwVnVzuW%ko#gI<_w|>cyDLp1; z38`yy;Ii$YQNiIK>WZ|MUo5EBqm7ys=z)kYGbVPWDFj^&S2cDQ0hVlD&p{n|VG_wZ z<+gHJgN^9BS_{S2X`EjEw7nIQ1D%RS;^}1dvn|tlDWUgY?2A?Wfqu{P%*nLi_(hjl z{C{<+5ayL1@kFVaEG@5UKdEoQ{8{LB)gIRdx$xuXZ1#g4lcT>Fk-Q0lWL{V-6KTq5 zN|1yFU${eKx~1}3>cMRlR&qc>>=zk&_*w4Ld6+ zzpGi|vN$(-i!>|;GKtJs!uXElhDWx)xziHu@en9Uql(SWXd)0pju;cQbiua7T9}4$ zo^@{c@Z<@4`Vm7Rp#Ts4Q^G45qt?itHWHaW7(g9XM z_X6eFw54kNyoGq-2lnXP1`{51v7e*GI;pLTmvf%?C^iZx&ri1k~2hC1ds0lmP`#UDUu zlkq=pI?BQ&YaaT-b;Mbe;^fl0w`oxVWoYz$4oxC^wfL#HEQ>30R7VokaHW|#U(`xQ z?RJ6Ycp+OOkY%%rz66lEf2_gR0v5gs#p{#oGj zz3$Hdpsn$p#DX&gpW&CB-H=MZR2?h;s`At)frev*vZZ`IG9m&LHM<4^k@DTH$s`=o zeU-5l%0!DDX_e~$82<286r6pInQClAa}VgIEmQ(Ylwx*#-7!7tx-uHQPAE|aVWds# zZyrMH-5wb*Ev1=ibTTNK5P74tX8hOU4quf;CY+m=dQCv>6Fn(6|9H3Av z=cIkbNi6tKAx6(M!umJKNkJQiO7$vBZS%wi-He|WA=SxxQ}Kg}GMCt-oKN=MP8>!3 z;4v#xF;m!58+Y-bfZ{KjPwt`d-1c`hrChHaJOhwE+}Qt=*S#h!G9Di6C5m>yA_D-O ze|Nn4cPb-l&DF9GnQ017yM05ZUC+z%M(hxWH=#Rr&bC^Rf2N`?O2D;;)e^0Vq?7bW ze3U}19r*w(edD>KqZO(nhxn`kqL@+$EpK6B^SjSBwmnXO56bl$WJb65(N47z+ov}u zZYY4{XBux`cZBFtF=q9j#sLOobTB3H$9lBfQgQ^26ICaqN?{{Um51aH%s;eE#cVfle8u=TDcQF$o)Sx_)ic1a)O_OOqd$9#_>- z|4O8u=YQmu5P@b*+Flfn*YpXL2(IV?ss1%+T0GQ|em!?wZbI->5u*zmdvLwVe&rmx zo#n5*KwpQP_1^tY2TIq3Yph-~tQHZ+O`6Tfjw$6m9lqc)_F`L=8Wbwe{8qDaYiXzL zAiKSt;@q-*B`S^db;Qo`9$D3*x1S<;{`-lu4b>1o!h?qg{2Hm)I@2W!4K$c3lA@C1 z%m8#UJ)m9?Bspk>gzeOrCA5BsF_yObv_#_I3|2TnE2hggAE~JAoIf@>ISaei5RPJn zy$-wM_O#Q$+7AJ-F^TNI{{Qt&fR+KxtdAtFJ|rdzknJ)L7XSch2(eh>=FX7j6M694 zNxYAc?9(uynUhQ-$h5HZ?TNZcBr9m}MgXTRCkphNBlI91a~hn)W1z#5$ym=|Ngj5! zSv&(W-%}$^wI0C@h?FvIlI$g;cubVq75L(XsrnOSIkF|!E#xvLh9C$%~ur?4Q zM$8w&c#wwhn&MBwcv$JT-ic2!8ppWp?~&nw1{k_ivFCzHIwrywn%BGdcYeJz-a3q2 z=iClkCPqLzL^__maES{Ey-(;V^Hc@0eTPrz<^q?6dMj*WPQw)I29ty4BSqLmQ~@K5 zaw6JJOp3VR&!H7i1-hoSX~dD^)WwKOg0;6srSrdFD`7_~yMgP|u`W1Iv4wtpog*$r z0rw3ga*t8#U%##fbKUlCw+Jxv&YY0K{n#EI4ge~tC zE_?2we`#~r22hT4802?YyK2Dr{~xYlc4zT<{o%>JQQnN$;kS@>@ikK@iy~U%-}J^Mg?_quJm{MyO=jLn9o$Af8wGb z$Rj+R>TSS^38Zq`_<28D`(=+AsnU2Yt8-pf4o}U{J{S>=R0sOosNhQn;q8p0Oowv5 z0C>d~l#s{wi5RirLD`~nBvbxlBs-7i$fHrT1)KzmURcUEiH*@{1g!RX35H{b0|~Sn;{{+dEyahG@p(7>UHe0=7M+w20m9*(Fx(; zctR6VVKFcMSpQz(@ufT%6Qb9e1~up>NU@lHt#=?&I<@?a}ygzztS>UtA$H z1L~S)ha>SBL{L(_%A|T{NmJ;3yRX;UGE;&RC=}W(cUZM){Gibhi|S$ree{jnZ>p*b zz^ukY)!_lMtwcwb*F&1PetqyooSb_=(Vzm2WApP-6kPLG_X!Sx7> zk;LAc6oY=5#)Gx0?1d#>WvXqR60d%J_OXp)Vyw}(YCG3uJ~hU=T;9n3hmAHcxJ}kO zC$RNDwB=?HIeTHSJt!k=z0#T-3C7*5|ibPo~_8yV;;?`!MXbLGICr_THqPCOQ zBH6O0LJJTgCTJSgb|K4;)ZPK!0N)u{vheFY%<|z2b2q=*(Y8z8z=YJU|5^AMFp<-P zaeMg0VhB;W5#U75$U`Ldb!oN}*p`V6m&%tJe08~>89ddzWz*iE|8Kv!DQxL zj@9!OGcFr%v9x14C+TjHs|32yM#u@`_%xUCfML1O95#H%X`y`8NzOjM!*sWjBZOc@ zG6ercQucvLFA2BX8A{$#?}#rDQ;B$32Xn@osORrrP-!H-t*ezo{#XD_`J0h7FB0dd z&ct92jhL7hCXNo#)|2g=u1fwD0o>;yqE`wZb_@)-uL5QQX8RYh4Bs|6laxZ#=mGVY z8)5YlR+YO>W0{22lHLj5JgNM{{@jhy0;@8fY!Eh8PBcY{Bn_NXqEO}g%o^8hy*IX{ z@YO?nch1G)E+13%Ssw@Mp6?b^Lsl6@s>p>?i^%{-agBV=QbNv?B_iYW~K= zzy^2;Chz2o4!hWMYg*;u&S;B(00jT%OT!{R-<(+mMD8CT1&cXI0k3Gw7TxYs$zA+0SzojL@ zS{!fV_u=Wv83P%!#eo{NJJ_@fTr9t$5hzJ}9m~dVhZ>*kAu;^b$^&K>OW^o@58Ijf z0U+iLY|EXJi9q72>B zDDb>>V_3~IhOprMR|Le~`Uok_Mue(-J1^z zlM%7yoQDYfiVn;?SnmtIEu*+)q-18*V15cjW0eSHj#4bCp94;IOFA3u*zJEBThub1 zQ_89K9b4m|Rk^-r?V=~|X#>1WOeoc2w3!rpn|t1~G#mmHD*q-pIOxP<)Jl(D(8yiC zbiHk-OzMC~Cog4^)NOp!1g?)nH`Y^)Bn=x@GFkT_=bGhq2ky}m{g-dDVKMlo1p46Ppag?75BUtrMxg~9Jw<IfzF4DBmP-31ADqEYqom z_l6g~YKrjtOuZbig4WO;ML;zqXg`*RbUqZU8-qThh z|BPl6qzOzzziTLAZuiA_j88-?32o*v8_nE{?xj}|XKj6RmpjFaxmrG>#I|;7(0Sax zmsULH_||#^JI?oOMa05?stq9^?8C_suZCrbgS6z}doM>}B)_065cbLja3w)uKfdeY zhM1_})D6DliEk$pq#yIWGus4_-_9Sr;~G1299pOd&8Zjhot1IR))Y8=TO$UmO5`Ph z$Ko=sVcMdj*-@HG8^|ZGwwYTsUzlzCt3KfRbw1Eb&lsi&FAjE6-Nm)jT{aET?@*8f z7SaPnin_cMm3Y-L7`b6%dFgktgwKiHwgay5e#s`LO{JRKjD#cEg}N$DRzzqV&6syS zfG)BwUdp`h?zS|{j?%Xb*ZA2_LloQXla6dzsra4zjV~2ipaR>#`O*{PXqaaO}V3zG?SA3Is znb$ZO=3|ItXL-}oDYE1hc-Az(`$4!^#RWf=Ps<8tlJp#OFFf*X@-m@yTRu($unK_2 zRN|*EE5I!4vJIF!$j0Il8G|r>{1!=Tp&}lCBsvW(H9JbFVS0#t*%(j=>xLI~4khT7 zT$vf!Ik1z1D(bY#zjdiwY9GN}*r+y~!Sm!_RI@=_y2dDY>)dYzu#aa=HBFvP{X{KTKed%)K!Fro#(%6H1*e_BbU6xrQaz? z%c<^5v`6%vedrniruTfMAqcO}#iO%-t&u3Vu;3#D4fzuP#lf@p2yV@&)o?(!bZ%w{lcFu~n^)0+TLR{{l&Hm{4y z>4oP^0i}#~!3#Iwg`$5RpuJl7&76MNP`VS~^Po6qqD|a{u6U5I1TsH0iWFHD;h9C5 zK~Tvt!1r^8Lo3~aff^*sX8~Y~*O3zI5~!u9$0Qmkm}#x_E6k@p=NE`s&ed4IRu{5^ zbdlM@f97~Q<>It;Zo8C0ri7k!9)#I|k;x(F>W1}PRlBu#BvxU96~x~@h?;;4>iIDcq(CCJ*_kh%HxL)CQ||Mu7yfu5mR2Wz*@2>A@|KXggt?YHBw@*yVK32%Zxv@M1 ze42YyO7eg1<6R2tBd=k%HUnRvNxb(FKDbMRN0oe3m1pSJ| z`@qx4dmHR21d1V12rj}hv_z?flrn2spYsICYc7ri|5sp>7NFCB=jDW*0%b#LVN20CUi3!Shn=+52MK|h-`_;j z*cmK$>X;&P{_|@It>QC`I8JxB~>YF?SoeoK{5K6q>>e!K2 zBNB}?2}0fTXr@40b!hr9*2POTmxALN11W7GRoT@E2v_^~s*$QS^I+uh$OuN4`SKZx zX;Bsgc`G=5kLfyfg5EK6A2m$*{P(bkj%$H{`bI?U*aN6(wnLMV=cK2wOT2F9sO_F@ zrt2+5t=Si%6Uv~VLOk~K)5pC2V;eA-Dd_G}MMwntqKY%sJJ@H~(7~ES4&34i7?kJQ zjrBAzU5k2VR96hDKG`Ig==6Xca8C$m7DD`b7I2kHb%hCD~n}%h*s+*wdQe$Ho+#{n3}6WyLc{NXn%D9KBk$a76bj zBu@$V$9!9KS|Y#FSK;E>l4^cM3})R=fW1AQ0q5n@v_mc3ZMVSEKCvU*5ZB_E3RXHb5Y7CU>AHxOC=ECa+P{Th)#VJ&vlyespr<7iN zfH9CrP0>jb=pbxW=+x8yUtLowWt`|4qqjN8AS(^t^kVCOT7bu-(8Y%}JU%G>_iYqq zc1z>U>c~Urd&Z*>`4DC&^o|Db4dGXn?Yh1nO8E2PI_FNUy>8qrAsgXY=n2n&8H0L4 zABPuT`_n}>3BW#=GFJ-D4O{sXv`#oTR2A0wPo+SG-sPoDRM5&}K%u!r>})^E>Q}ng zgb=PM-N(3}CkrQeGnC|FO3a?`#*Da6N^;yFv=b~^YD%U#w^MeFJob2aV3Ashy}V@l^pWHExmRkx$%ZdxU69culXzArspEY~@TVVQ2W_(B1Jj4zUeW zxngi^0pAChZp*5o`-it1*-b8P|gBjk8#ymr0qX~xsub3oRR zg5A)1h|-IKTYY#}bnsZPR(F=g$g1-Dh#xttdFHT;yYJ!e;4SERCOpaCW6#bA7AJObK+lL-NRAP{N}36j(;M)(;MWy-{B7&b0A$ zd^(e84h0SfYwzPPqZDE;{lXf^p~Jr9fpJ0tMk<#<$aRyVMW1AmE{Op1MekdOy!n$s zEGP?tih;Zw|NF@e3E!EuJ&u$Sou9En@f6J4$m9SUBC(ct=WdRoq7zZ_kDi^8OLxlAU}8+3=czwW~~R}f-3 zzK84T`ynoZ%hZHU<(;6TA!BwGe@^{cjE(20--&5lBUW~NkU{~LlfNoe@)4MC#bz8- zp;&;3xSUtm*3&7LB9LRxy{01M0a4^)#r`HT%P$$zd}zsa-P$g}jm7U=O5xqY00OC$ zGML_F`+xp#Obd1!Ar?Vy?rg?FiE(RdfRW5@c9cTBOfjB+$%-+w>-4u}t|NKH>(pbj z_LQe@|8Vpsfgt+1)<*W`EQHIyT^-xiOZwRVx>yrG-a%rJv%+U3IH&O{6|MuvfHnQ5 zR^Xrbu8vFX*YU-ZmfPk_iVKhL-E9bP81j5pUm@fKfi))>_{10`5M;S496Pt`J!5=| z-IFZKc4zkk@0`wBMi@B(C1xU-5KZnZ+-Pp#u~hiUA2|z5*0zQ1F8OZnyPOvAy5wCa zl2KG}eijx)sQmD>0yO;20ZfwqmH#JW8ph6p=X{Pis~aElEmZ>CB~5R3^R@*__=A9| zR=w8z488vdvU4B2EYv<0cNO?+JT{IOaBxcK73X&IQ24ZdtA&eB%^m8}Hq)`B;LCeM zrx$fVWA~e~&sqC2#fS&z{&^*2XGqY?nr&b*YaDp*Z(#?+RT6yK^@&{P%m&iw%uZT> zg?F)vNa9JE+%;DdU|$@JhVSXW;mhR-zuz3^y!u!XnZ^6P(E)v|@k?in=<$5LpA@9&XD$F?9NUuVzosY8ZbeU_h3ERB zh;g>RpuB`Ro$~)n`6`ZX{aw;MtV59ZPBGl{t3}gPc+N?k*D7#{M}w>Vz_JRrEYS>h zK=BHOkKiH)xY&HCNI!0XhI^*0$pDxA^a|<;KTdB7QW2S4{Ty1n7|Xv*%xf5wa*wKH z-kV;sqVwC~QQ>U@qkS~kC-rTi_ttc8Mh5HYfScs_h3x($%fj)k7r$y$*21hw0)R`R_yq2oUNSQ2{hxD7vV4}AqsemjHjSjvH z(zaW1)L=d~2OCvZv{HOKs-O32TiA};w9@+6GFo%wdfnqaP-8sa|=ye(ekX zHZ(0M$SF6USZB0_3*lgv6IZ^%Cy0dL^AOqj=bXtO6Q8T77AF~Tp`o~Bl-PqIWE-vY zaMJF}1vV4`we)R$)_2^z45~fTHp1-`7@yljh5M=t_pZiYmBx2?FU0Z(L}3vaG$u*q zcFytt@$rtzm^J>_Ke4_p@la7GH*1A9ddV7E#TU8rb_G?(Ke#@gcF1ZjBN7 z?>YkKuxz;UQ1z*LmO=qQuH#icc>2HJt^fZB8*hF>6jXbv@kk!BL&UxoK7#*pgf%7k>5zt4YNq>h;47rx&&Mt3ofcf~ zZ63ZUh&e7ZSVW&}K7KKuL_kiG>}{*Hno$*pNMkYt(J=rBuN&tvzXRK>P!^ZYxroPi zadMyCL(KwDYVCmzY&6}Bt!lc4jAoHnw1oI~GH8u}CBgi}$Q9Lj&h)6D8P3D9E@;7K zH0*(902SHa^A1%qibr^(RI#~n^AuDUGdoa=M5(m=_IALN(!n!frI~D(vX)`t{C@>l zkdzdNp{oZ+MTLmc{G40-Y>!A1YHdzWpkNt%BUtwHmhdt>t8Xe`OUWBo6q9S{PAzY` z{w!lUF^02zZM|Bclv|y?cusiv1J{1P4NdaLRQg~cwQdigd_VR5jEY(QSX=|x79gKA zf$@l>i=u)66|!*-lHY`WYZmUVEG{p;0HE`1+s0F!axEbNVP| zqYdlm0S)RrBLT?1(q5#q#4*RHMBZ5Zt|EdfG1%A}j+1p2;nwA0>Kgi?k*Q&oyfC(p zz(Rm_mEX1Q3;!97NldsN(3s5MDihzTB!uu?qb}<>!&^YUV=?GcKZ@ z#71wy32kM~?c|W!h!xYsbQ3v#4IdB3g+nfAsYbwu0M0-@tH>P;5#kll&{}NRP&+|N zn^B_rq8yV~(A}mBaj)*u9QGOQ!cxOr(vLc1VKCJqg>pY=q3fst`#RxQ05KwI`^4Oj zDD8WmDye3HHMG#Yv)I!jj;7sz2>~rklF!Qh&wI{pZ2C749187ro2z0$(*qokN&tPS zKAmA}^)zL{vkC*b&&ZzjV14E)p+jf8t-y3*;ljanW0=v+nU9Qh4haprO~B!1coL&x zT&Zm4I6O~_eNXCeY?gwAxZP(1fbeT`OM5`omZZKj8Xv=y+HTAZK|$iBA(~5xyL4?` zP6w-~B*T*RryRbn5mdBeChESIBupz#J9|ZsJ~k56z&w1C@thae@zzLw)ovCGI9iS! zLPHPg$Ow9s2ay9`WZ-=S)jhIq7moA11LWyO|JQ|Su{;&*E1^*;_%+}0AcJ5xg&bYU`ae6oIk*z@Pvo(`xYE(C#frW z#)fasVe*~E@ZY~$X&VyzKjunH7e}RWJ4N+*L@AR%W`vc9NK1OvaAT3W?Y<0?OWN!O z;&}BE?MqD0nz0nEH}B_XpjoWPsNWhCWXHMIumAi}Gs1`{?y5HVMh>T^NXvmf=<<}q zQT74k>2SOUc5ey~D6p7o3@6q%rVZY@mBb0WYq~YV3|^1eI6iyj3O%Mdc&8GO4tj)o z-l1F;&Dr$LO@2w^RTgp*YXaHPtI-VRN=@^*IbsnxuBU&{o6QjNpR50^z2HC0 zufy-lEULy$_Vz2lwGK&}fTv+FL8Jhb(R+mLC)m$a(USA7DY?xLl2)7_2HfS)GR7aHgwFDz?u7 zyu(7}PV0(S7JBZF-L7?}Vj)1m{syY6vC1>e<-%nAG!!ue$lbt{sh5IHO(xG+SevUt z*L=txYpBPGZ?XgZ>wIN)XO+1Ajn)Yr_`ne{vgO8`fUs-nHy#u>3)2Hh=JMsgtU11! zy{9VN0Liv6XypzjsL{%u^4^7wPqudk9c1pKmL;Q2hZgDjx)__cfQQWN&yBmaS|agP9`Ieu=}tv~akA8o02-lwiEn zQ`-R3P7Z`iD*YXt>O-}S@Pjr*G@Hx3=+NLQm(uLKC{qunk&cFK(t;LBOFj-}jKdmK z57qHk+>P)#udGL*s4}Tb@XMYmXyq)vI&CC8+CSi`fR=wQ3#B1-)z4wb!&72&)$e8rU*Rzi=J{n?|r7H1KfwNW=*`K(mF4*>wey~ z?fz7B&E>n}j;3prMJ1#63Q4jvedrFrThR3m9gLom@P$(N_DOoK^+>T!&1Kt(f4T}4 z$-Kr5P>4IC1dc_P-nBq?zPq_^!1ikqrwO zZ20B}f?&q8beFFGF_u=U9JD^zWgN}cw4&!bT)||SqUwTbS7&;{q|G$CtF^TMl(Fuf zW=Q^9f0Wq%#OHUUQ7DbyFhV*k8{kyWPeY_QAVI6c3R#R87J(Pbgna*}TM8#l_vY~6r7f6D zr#F+p3I;GK<1)CqRnslBiE+Fuwkln61)Hsp#=a<-Y3}xqSio-bc0Ic<*IhWGby;Z{=QDQs;p%&7q3NPJuXZJy?=J_$+MSr z@2(+Gw^bT`^l*6;sI>6>`&|B3SOzqr9v+GJh2xNy;Cm{9RdgXCZBU~s z>E|PdToDB)H)zmV!Mlyy`btdqHh*c)i;tzUl@)9EUp#kbeWc3(5&MCt0W!giL^#jM)J{7i~g< zu(J73w1y!-2*@uRsJJXXjYXf8Du>wzQtGhbdOhe#NHBEF+2;=~ zstBm*sAlVUv3Om7t9G8K@cg#ViW(@PLN+4 zR4gX@5MQ3}R7^U;cLF$u7B8?kQqr_9@OeAh+GDQYOFihy@9G!OBC=dlWWRKWB)fPk zf=0lIPFt*MYu6DuacO@0ha}~18s;Grwy?S=q$H}aCa82FN9<~HM5rrpU`Rp(DSj^L zz|@-fyKgVz;L#z19O!2&fZ9F#aI)Ko&z}>Tm!GI~5&G88IT*}Nhf3Ry4dDKD$pS6` zyY`bTx#p@^(g0waYiaA9>ZCFGL+N6Y%N4z4Jp0y zPimfX<6{GSQP3k=TZBMVc?K)l`=XdvIP?{f+2u)R7Wz{Y6%Y9%K?SO&#wq)pSZSOJ zDW12+#-eLUY0-AU8M^3tgbEUPzDmhcna4JY$7*}D;5@8zm`*%S5aH+wA8xKjlyY^4 z%i2({N#Y=Xe)>~d`$pk@*U za=9C?zcC0H7C@wZVNyQ9vauBRrKwgRPvG}vap%tnaT8`nPkNZZOX03q)j7*vYu2wu zFYc`F=07>nm~{VBlQ|pAlXo^NEDlrN5sduSNIgS=>P_GVEsLZosBsgo64{m4I>2-x zw<7!E!G6eEfaAW6g7bwgb9l}*%(+QHH3#nyma0~i#9RqiZtiATN;Perzc6O9?q?@l z^T+}HU>Vlm3Si^J*=l1jN^DC{kklkXZ^F|k{lVw~Y zw}iOax!jS$KQn1a#!P~Lm2QtXNcV^$$XeT?0(I{7T`YN_C`dn6^%8aEr4B(a@!+xF z+@kA+w1c3R)<5W;^6>`WOu6^K=q8xltAY6)ZeN&s)4c@JL5kh<6!*^x1HKb>9?lB4 z*GMSFCT7Wbl-KKrT^$R~^=1E>Ip2roC#Rjg1|T6)%o{&K`2rOdh=Y*sNY&JwQ4?ZO z!pT@voro0;}EI9WJxo|C8uR%@m0PXos?X zXv@tLD^LE@7t+MYq7+Nxi$?!$N~NL3xFPU@0^VPpM#fD3V{&#dwLz+T&!g- z$-hZHT9BL#1MFT1^N1tPJoCUe=@rtj!T;LN|%G>ofAaH#sM_kt9Zo`u9WAHEj&{PsWq9!s|y^#me5ZL+Lr* z6dZOVdORFz?IQ+jsgnw=iO5?dCfjBYj{$}v!8Bs07;s3gd@u%ikJoPYb5 zM;6qCTP9LO@7i${{0ef&JhHt+1S+dlDlMk^d@sR3EBC_xS6$qFX^AW1w4e%8Z*0 z6-vD0Akhu?NvNC?g)yrr`2jXmFVS_F0gpDr{QU(3XyTV8dbC$*2N zS0{wQ-dED zzGpV~DgGZEk1|N5L%ehY| z(fd7y$SZkRggz@hqVz5~@gQ%r%uDARa$YsEL z7mBS&)wP)$arVx6u-(vIJ>)Iev)rl116|}F&1qQa=^EZ9E89`GcfZSaJGrr{{Q-!r zaSjhgqJ}iHE?OISKvSbkUj{D1`1a=-1SCq#S58<9I`|gQP8%fg)u>8s4|@NKWsNU_ zxYh?ViBeDB?7L;6Tk4|>pdq?~5~%-1=feCYPRq#rX}w!W%<2Sl=gjy=MQ8|jkz2>G zm^RK$RFyj8^LjUg?KdtCGuaft)Qy}fugs!ytUXW11wT3`VlQ|&TX(EuFY{e;lkrsAkx3ct|>U_(&{FjUMCd=*# ze_oOQ6m0v(#fHj6k2|Q3NX`})2l9~+maZC#qS>&paJwHy@B9+2#GO`~{_5k} zzh@r46`KJ4CUjKS%G}SZJ;3LBSmBU;$@IJKQ?DQ$f&33sE}kK-dFuwq=#6Q>4128g zz9*uo(8L5E72{cWU0H&|D}|JnXEoFTt4+rM00RI30{{R6000LKk*h{$*ItZYWr(hV zpWa2QzW}UE+)=OFMzHyz;9HQ&mj>vxNSPnhZ#l$yai=w;l7=(&Z zQytLba7|P5!||S#Wjc1 z55CEdiL`8&T|q2^cb?MI;bMpDPz1v?MB*nP)wq59%k@%54YfL1FXY$H>+~bTJ_FEABGwm!xxAhRwv!i8u24>K689rNn}_yn%HJn z@N3yD)13@sr9+e7%RwWTEBv3c#vqAo@N6y~F6B+#cu1xqxY17=xs?*ew;fduE&`{q+Sq;1`Z z6#9$#)o?Xf#`|RGgJwl*XUMl8Ag&Vox7|6H+N9wXx=MAVSpurx(j|V@4hY4@YummT zU9ku`H8o9{6f0eQSY;j4fA6rBdxPkY??Yin5xNfz4*_6E)GAo(w$$1f)?J(*2f)$& zmU<%X+X~genXla6{5_F)K${h60CjJYdVL9kD7pKKO+o;ImVhy|dvZ}s;tT)QT=2U; zC^b8ui8D19Teohj6`ZrIGTZhrx{#kf;-w(L1zdUNqJSjkp!N5ugGSTO^r@Ls1h5}R zUl~wVgZ$#Vr^o26d#g&_P^rQL=rUa1^J|cXWCIQkm0WrM=1LW#du^=57_7v9zzrrW zjPsAsvAcsUn*1BE3Diw_-$4vdQ1dAJJ zc#uv{1;kpV*DHF=WP)M8I_6n!9M{*zbkE1kAfIRZPR=!Sn!A)n9s`!8M()*B>p0Pv z!m7Ba%yWgfSpss))5&guSv{on6O$Z${1=D~yY53J)aI-rQSrl5AIWpw?g0D)AYGdE znvOY^!QT$ZMm4hOzIO&B`I`Q$yZV~r9~B@5FdnOWpP-zvdL)NuJ6p-JkBx@FQs8nC zHS&!sMqB78@TlxEAhJ!s?R?vW94_j?Ur!^f*kDW`C~#)Kc)Y^TvVkgJUa9;f4os^4 zWsDwzqGI&Pct%23;uaP$7w-OzcmdbFM{ON&aRNaI| z%^Yz7lL{u1u=?Re9F>Hr>msw|ftPYlxTk ztgKxj>QhNEzdDQw=Xc~3r28;Ed{A^AQ$|*EEg;;2TVpdJnPqM8Ic^}hHa{O67xii1 zW#XdU;*2jUSZt(IryN+C8Cbz4aBal#9KpklZlh znEHCslE71DAu+{e49sX7()I5!E-78*kqE*X57RMcTBQpT=qfl*;f~M1HH8dh0cV(e z71qji>vjbLTSAB^+NnnuEB>)SEtp#D$~o9E`7Y+rQi52EcX7%liP;tH*_J9V1+wcx zEqE71<8P%@0$owYfn`+J~|;G2aJ7Rag#p!{dbbd$+y@#s>YU_3OU9|orGqaZQG9ih_`AXHMU{Q3(d$S zYFRjRV82nv#8Z+;15?3Kh~=H?#HKzs`@E=J`|eJdOwlwIVpi-Y>t`%n^`Ff?ku1*k^4V|4FK!W#!hC6-}V^; zgmQ3bQe%5+98OY+b6Gg1)yY9PSF>BwO;mc#Km@$Jchgf=;fchlVG#ae^G@;eXE@Lc z>6BmO1v8Vys5JRii2U`3prWJj!=-(1Wg(p&EiZFWOF8!nF_~p$5#O6Q<^}%eDfRZK zaa}=Es|?Y`6`I7LaL)qeYMj&&7&i;5cK{Rh>ho=qfTyOLb zS^i6z2Hh#EL+GV1m+g-2H?Db0o7h=fY)dC}Ts?c=L}7_)aAmN+9*MHegTpS~CEFJ( z5dwn%*@qeq`JI;wuXMnJ%U1!3>;FQN)}xqE}HMsSC%-(sn`D%HUsV5L`u}_d8jN*Z&Q8ZzfF7)+o&kmxid!IGp2> z?S)+(TT`(lrbYEy{=$EqY(6F;UmSAo0c6i(JRW*%8^g+0|8=a8rc3hJ6Y^)nFAN{S zfX#+<@=M+wQQ39$t;=7)bbsD^61$kixvonu@xuS>>6N=JXJ^g$iJRt;YcbHpn=XKJ z4!KcWeiw2!PA1a+^&m8QJK^8rQ{_;tt{+ksC!@U9VC)?MUqu*9pNM;+nu>al7ILW9 zibbeHFyMorsdgsBYTZjc1AZ*R&IZqrB*xgyxry6YA2gFiTwcprKw6I2On6B%Y#>w7 z2ck=y)|PfiZ5BKZ@gBGhy1k$)#27tSt#EA5%;gBW>1av}~Ypu#>s(!6e2EeNPb zc3(iVv&a=fDI=4{zVPm@Dw+kDrX%*QttL_-Y~Llg`ljcH9<0kr%U#^e;7GWr8f>5?#$X4se$Q{&IkO ztcHQ>FT`9m1Mxo6stMFNHvP?Z;YvGxKqz!!lmWj*#q5aXB=2}eff0ZjiZv0 zCsU@!#jL8Zh%=u1XpOh)0ragqWlOi(oAs|m@ld#a+(K{M+<2kO(v2}gCSmc1!$fZ3 z+bm(M#XtSUCRQJ8j~V?gFMau{NgSe}z}@627%dwqti81i2FHPQo_fPXdlanc?u#nx zQ8*KKsFk*ZE9f*75ic!-NlIqsOV%Z|zYYqCZw^UD$*wlr+QYj!){c`yb#LyS(6{{? zMD}6s{tM&QLr&->uEE*+A{fdW!qEEwp)8%^rR5kww|$Gw79)T5RiTsG|nxZ*QchD(k-wqnjQOLsaU9Vku}_7(mS z-yM^5tKUjW3|%T3TtktIK?YO~|LM}CWk^Vba8IPsw%AL^HFsam~Cp8EIh8@L-de*E5No-^cR4@8b47DhRs zsdwu#ORl0@t|TeXqYq3+CbG z*6xqlSa@jqaTA8sNhm%v0B^5anNuR$n=&||TfpI7m7KmbY2tTb5`iyw zZ@OWZ4BG(hm9^fGYBOTZDNq>zlUUvr82e_Yl~$% zv7Y6m;|Qj_+V^?yQg;F3)d=<|Zo)ZwwP6399Bvwc2j0`k&|}1Zd3+u*gp5vQs2S&v z%PcX;MCpm{FnMNd62rf-HhmW)e>wEZKv%!=9a3QK0o(!fmzoz<+;SdyrjJ`iP~u%{ z3HX=oS2K$&l4b6^s5peQrW6K}pRlu-0UsG*>0!@W7qZP80 zEMP>Wwlclfs}K_yprC`}96s-Ut{3_gdtcDKQ6xq#0XTH@#x1s0nBs$e*v6gZHCSvO zx86fuZd!$ZM#VOD+y8MFEDp3Q=t6Xmq$q$YLbyMJO{^BQ2L8Q*vd}U|YHFQOZBh#C z&p=3YG9Fxwg?J2bj2r5opAQMCB$INlDX=9hj5L5O%khb1z)qe%y<@-G)yBj5*J$5@n&g1eyV^O>d8nj5doUN0B90{1{UR6X$Rj~Xndgb z+SzrE0patutKo~6=I-@4pU{h}epk}SnN+RGNlCAxejES<{TLPL)21}Q*Hz{SyEi7KCU+GU;z7k6kUKVc0julHNGZA*V%4t5y(hW#>>e}v8b7_YH zLfwc?{(1U#rfM=UwCLA&uM?(4K~iUKJPp>6feyN(w1t>i9Ftvyh*34;0WhzQ%(XVanW;e2SQ*0>CN3?;^>ICi6FDI;>h#|10LIO%J z7(WiUzhQyIXnRQL;j^`~6F%r@tCI0H?=BjScxzHLj0*ysOBGAk6mv)_6}j!VbAwJ2 zpVCglN=+T>A;q)6I^uy4?b6b%Kn~ID?(oGiyEuEp_5&Bu zfE%>9+HqjR{}5uL>z7%WqT#=uFg1EcNKtV~bow(6kzdrS@Y3w5X=GOTO8(uhSOr@-Rf_d@XEO9mPbeY>| zVOte*RUD0j^&NREYsAyb>RhahYMtJ`#@R5b@g+#dUsrqyw|PJqGIE#yf`GWsTDP6> zP32Lpb)iBaD&N2@XdcIN4aL*PiL!>Uv%2Dre*e4bDMtRHpL&C*g^dNaAuV@7POu0> zLp5OxchU2ZeJwuN!nbP0pT!7*gjpvic9lIQZO&=)Mfc0&`U6nDsxZ<7Y=TAvV@z&I zDB3F;1NMAJ&(Vy<^rDV}^0ed=E}VL(5Unq{pc@I_K35#6SDgv?s|%dJgT+Sg0VqZb z9h0sZu_Z<9n+QhaVqnW2Lgb_eIdPP^(h=64J}*GRwx&)-wZo9xw`jxIfuSz zddYVp2_kcaU#HNzoMVP{A=2c(#aw|0&_QL%X!I>Gpx$)-ujGSkw*K3%p->~qS~$M9 zPfFdPj09P1b`au*ALfXNWfzWtg9v>sEtBC*dgh_!Gv_TE-b-n7)#`l@6na*LWYua* zoGEKQ{j?%V`U7P~UlFrCpB}9Tb~g*lqHCu2^wCf0)qfc`8uB*m(Q|Cl-qjs( zmOGT%?ayLZk|@luW3x$K-IF2=_w2GlKyW0Z8z~sOmfJQE@G_FQMj!yyID@jh0`MOK z6!j0hV!{yGBqR|-=D|Xp4h{|7YsYZ5ji3lV&MwZPDxc{R3-^P; zG30c7a}1*+B7LZ9jsKe9*{F#*UCFV%Dm|U_`OY=Mr29O0Wze+yT(K3z$b2;}UiEvw z{H`Wa?vsL{t?^REBE1hQ2nTvi(U@r6swALTGj*|BGpQ#!<}iLpq0F26*A3Z)3O54%>LY*v0m=0P#Z*)cfzd)(*lbyxx|UPM zpYGsFMkAE{NWCY2_+nmW&IBIJeV8N_r{#T)Ocn6#_Ky;iTs-%qy=SGYoda~gyjQEp zkZTL#H6pZx6=W=-R2~yf(2|Bm=QhY-i{0ylB*{Ar_A;1Ra<>4V$1I9kn89>XD{iS* zZ@%7ys#)9H-8tRe@Pp$19_<|?S;T}3lNJan{K8bLsB}oWkzSzcxWOz_`|NyOV!@rA zYvg+zH@E;QoA`jY^!nZdPygjx0!YcnS#{(``;%~?lAn+wI3op^;w9p=;@F>4248CK z=Hh%q3UJ^}r!_>uC+c=rxJ8A%Sa@Fp1&lrj|b%JZRRI$t^}CtZ_i1#~Iu&AXK5snWw@Ie+0s zFmhd(pZ=NVO!qUrE_s&RxH==@d)vBYE7)KmZ1Il`dc(|ljGf8G3;=g2%17QD7kHc3 zCos`CLn+88Lx%rCdJBAfTl-y(=f+Ii)yTc5IaQ@(#{|%GI*9>8WRhmeq-ax*;Z1G*Pz{%4S0vtWE7PFmfMKS$KhdaD}Hen7!@2o}{<0^q!9cB_4)k7xh|y ztcN0Gp7e@6Twbhs%Xa`pK)S!xP^T`vP~%m}{$YbsHe%T^#}q~5t&v+!8doFuS|teA zf0`w_(mdBgcyDNwdC8q?%3E1RbN?vF99H5hWWi||dEKEo0*J+Ir^4wAi^*uia*8u~ zi#gR+4u!_=DQtB#qr~Rm|JMe11<2#0xpR%6lmoU za1w7=9)_J1@KZ;J%KgUPJ^I{O-~ZObVNj^54%%VY1rE12)!Ehqs7P_<(i2a<1e<WRcp*j8uPd5{q~75J$&tB@&wEAwF(-dvZ_q3h z-&i6%$ovs+=d=7ms-eyn+tE|Ly5Y_3sp*(vSNgZ{iNK{wc zkG!mRVSYV+$v4bi1X00$_-a3Y#5giOL>oT%t8vy&64;cpun48QWiXecqWG!5p)~Ovh7S_Lt z&YziMHFb!WO_%`!n+Fdh?y5hj%q^|rf)|ySJ}10ZJI~7_bZ{_eA@PU7-2Wr!aT=|` zbbKdGCYu#3lSO?lG3sv`Hq&uk%768cUdt7UwZDoa!i2aWS0`o=jI+MfnRf^2FeAb; zL=zCC&6~bV$~)<)RhQGBlI~HqlvZLVY@Edg`r?>B*HMiRr>TRWjC~(D#@5T@I1dxl z%R5o3=A<%-&*OQzS&p#VKCZr)0>Q*QS^*6IVx~F3DwnT{->!)GZ^1L^nLo)@>C=^$ zuOIl~KC-|s5VfJ8IX!Amx9NYR@|q1hOgP&m|9Qw1!u$s*#~VO>mAls~w0PW}IjkfK zqE&-mr?@5lT@v8g4Z8oI6K>pC-ofrqLFkE$*p@294n;H;Lj0|UsFPM-YHO7cGX?kC zKoJN?_6jJ-l`EJJFOFU};3^9?YBA!qM+gz+r|+>u!*ca%Fz8W+*KBQR58+<7({IT2 z3>}rV+v;}p%X`nFvkPvrZHn{!r=H968;&^5cX2+JlZm*V2t>5ISfB(GcmEmZqQ$ac zo%47+1oiW;c1xD}6(U?R>=}LG*OOxPe zyYUhWHzE&h4?sG2rghmGycnkNl0u7{txg$7RDC0YOUhog#q3!7f))l63|hqrS+M?r z$*AAa9PLq{7#iJ05+sFdMvuayS&C1gq7`lglGX~+m|)9uyO90yXBqsghgnJrGVunU z_U^7ys`+Z(bHhHObGNv#oBIchpmSJtmtwAy-kKoGzmbA3I$c|m!A;C8N?_Mvgb5q( zyz}lGtaMS+sz3k=4RUKd9##7qDf8kq?VVLTqqg`pZ43PJVpH8DQ4&x*emGfEzuF9F zqsGuYEc4D<74o|H;0bAKg6oZk3-;L`!KTCs>4&GdZY10htSVmRxgWyM-J>wc)h2>5 z)k6bk$3VMW$nZLIk&JW%kb(5(X) zxkd(p$dNeYh|b%`$C#@gvRAC*h*P_o2FtM>RJ~)C#||Flbfghs-AD{+^#v|{P)^V< z6WL#=xYaC3C4P{wTx`Q~QP-^)`d40?{SbS#l@L&(+h+w5KEHO6$o-}&S&G+dkh6*O8KNd#*F>r)9ImP2uC%tH%qQmzKyD7^_*Q6>0Jnb6@$ ziN~={jjhMeLpTv5mHI}OFW?6 zG`4?e0r3RSnsn46Sj5w#{~gS@*Ks(XWtFg$bvjr*-75&0g@vkSS-?wgd@csCIPp$O zj%kPmPFOa8%7#5zu}>gYtXh~rR>2*7_0bErv9J#t{1eh~XWg62es>3s*=b6n7N>g|eI9$CHFjzlT{j8;)E@^*Oq1q~35Gx~{ z1ndR2MonC}-Ig7g@OA&lD!V+0s%pkEVK!8@LN+?%1Cx733}85@RHzN7Oy4B_pL&vJ!;Kf>?6$7zb+DfGp3(NfI zc?0?jPM-a@%NEW@&}uwTcf_{g0&hcDwvGFbSPwN^Rx`%SZAehQB?ZkrZ=^ZGcgedE zKi0F~QCQIbns++U0EI(v7?>Ug!UMct$G^R?x}&)SjayU7pCuUbc`z=g2+d6cWIw-) zZx;Y?5?1ld9SmIIoJ~Dn-gufl-@_`H0nBhSZwz^0TT2YELuom@qq!>AG&~@^M`<4i zbd++eV%3^KO@?@Q-FwvF4J6|V!7;wLA@P~g5D);|$TLQ!UFlb!dSMO>1zp#H&Cj5Q z-F_O=UhI$Zj**CCu|Jt3mA_lI0k=Ke;dM~!kUO+fsJGM;GcXrPA?oddoLbg#se9Ik zhW|@bRle+aHMKM)2lXDe@f;B=p}y|BEVj^)7Z6EQGHwGq8i&BFE;isep#eNLK(UV> zP{3b)1>Zz$hrn0a;g#aLv7j7cMyrvjPwwMPy+4aF&fHr`0x#NIf&QAoPnOCPXvG@= z;VS3C+ydL)zy0Y(byXSOh&OnjSEJVX|HSBR2{efIcXCpJo5z?uoz6IKw#T-_=E0I7 zm+MUX)IC(d`khtZ(9|)1WLk$Z;{_ay>Im?ZR5W%G$#Jgq-L)qupc?oK=Jxm&j{cz1 z%1ESmKFF{7LgF@Jo^|2ANp1+-g$}ZWn*M&C4tt=@!+zPreE~JPs%gc}ohle*>MjU!RJ$M(PhIQUF1m(%8;=qL98f9Ip z4OEDh{So^ngZ$8+<%Y}|X?c8P`6CQgDk0qxc%{S{0Zvl=w9Uv|9`9>20QU#3L%d$v z?uz;rP+(_kfoOG2=pR!~wHW|au1agrhkCE+@oETVrAQUR1yt$-W>st+DA?StLks<5 z`NUQ5Tpn~Vu3f}*PcEC13QY7AK{(nOIK(Q-Tz@a6C)f@A_jQcNtOc-(U zg1*j3A4Ah@i2gjn>fy4iv$_f_9gfJay(mcRo?GUTf!Y_ZJn<0Ze}5g%gW`%|4wH<{ zG(v(}bS`Z&{=wyQm08%T;{HIXvc2y*aS*ePuuzkcg z!HIl`g%5vdWM_Qy1V0)-5QC&tdP__9dFZp$%7x$Nt41;}nmh-kxR1+|FC_&WEji@l zomwz(w&*UJPm<;p2zUT2t-GjBf<<2c;} zuZueMucve~9I_XdJjLTsybhJ|pzgGMTtn>_FmkchHX1D|y#sn55Z7w(q1CpH&Py%6 z3lEyk!%}|*m@gi?-Rm2baCM0<`Ke~M^;i#s9@iY#QKOc467!#Bn4S4pb*b=$TI z1`OW*+Vue-JKd>ZC6M>mw&zI}jPv6UC2-i>hc}2~8ia0Wrg--B?CD2GNf((Vcn*$| z5I=!-Xz_9;(J4Jg6Er6iwqj7=gHLE-!i<$!`q<^N2~`iN`zV5?fsP+i&q zj0C_A#e)fg{49x>@VHvygxN-rB-N{~s<}zOYItTht1a+v-|oc3xV(>j#0h{lZuR)b zO@&dUi@!dpG|!J{Gj_g+2nycPf&hWmit!x#;%>&3O>?GB5?YhFmw%ZjvcFqcM{a^z~^b)QagKRHM;l(Q2s0>y^?mCfX zYpzH1HZPfA{6fs-@UtRgHcLj}o}g(i^xP9b>gFP@Kzm>0BIBgiJdB`6zm z%tBrN%EXwZ?`g~t8(B#7xeEh0@hyx&9&#`TPw>m`(oN$9pjlx zkP(uw4^Ys~W&?ESC+`M(7u~m39(&qgNG6`rd>`Wca{s~E2vCZiah z^GQ0!T%md`BpHd{!9+zpt^5%G{-K%tQhqaI=rdR_w(#t@*`iK4am5{zWbgj!4okUH zj0?`8;D>XcFmVn=(yn}3GUR?xY2lVpKgqEe4rS@kGLuNuOw_kSZSNa(Jc1mjeWF-e zB&s360s$k`QEm}PB+enH0VU&b)tfap0&Q~sMxtS+X-^3Ns#Oe6x<4}+v|iHX4$2s+ zf4;TU>9j`WPoP)-bfC%t8H(SnY9mH@=k9@~kV~D*#Ra_gg5P2ugtl&Y5*>9X%%3IV zY+l5&i-#h!Dfd0A?w??EoLY}~BSL%e=V4i9CCxF)>?TFu&cA)!uXQIuRfWQ5O}f-A z=)PC}z`ze7`{Y#vGpv)>&`vS=j0>M50~?`&hHwaVnaMr*s~Uf*6~@T22rVwbp0;p6 zF~x8!YeTY!IlwG~;amy7-$Y+bvyiwDT~Kn2 zR(g^kxv9R7`~dp6-nvGC&ol2GDjMMcz>Cdd_2J5ZI=TPhpBpX>KYRpv=Egu(GeP-6 zo9HBkz*Tnt!*}27OM@{}{r!Iyn^!kpeq#wjYEsF*&6w zZZTF-2U^J7h7%)fJg4`|fO0?YEI;48MKR_;`6+@N3u0btDZw?><9erc0s%Y?z$^Cd zw_&1R^52OJeUg9HKqr)ccldQuofa86X2L^r*TCE$1|{Cb?v}JrA`*ro3oR_^^m;Gv z4u(`%7cet#>^-x6OP3Ae5BeNcL25H-%&l$%Vv{63bI1iCJ=^9;G?@iLcXx%~ z^9$s035w`Tp@Da4c=A#aT{$)5+Y%70ByrBfyv!>KeitppCff<(V%+mx4JaH7g0Al# zs0W^UD^+!9i-ruO8Wee?YHy&1UOPbTbfn^FNTCwMUv)r<9TF@E>p3KKYR3j?=L7ks z>aCpIFvWP!N9Nxk6&%PEFl-4L|L9)X7ZcQ=Z~Y<3i7b%e?Y-1gqD46nNYa?V0~#{p zV`%SPb4;s_wIlhE7&|}bffn{iJvXTDJALA~(kzGY`dnB?e1)N#K6c5w(#@X`$k!8QF>7l0P2H zy*`&;FB$k^s9J^p=Ru-U8!Q)(&R(fM1;cse0cC4}mDhN%uSQFmjDjpxtHdL<%IsXV z4V5Jb9JEkh61VFK^tXt;v#dol`dPeBwRpOpZa7oFIBj*(X#1dzu~M!JMx6sEzz~x zkrl%Qg1X5<<{#_67y(Cu5U0|bbB1ql#=;2J;R$MqDQB^xZ*?<5eLYM_Am z6F;|Ly_hyW4o5Gd_6egdTD-82xi}bBH>IPso;<@bDk>d?4(_?hX{TK0do3j+bN}j| z)Q+r2b6%VO{#{rHjQT3f_Pt^L`GP8R_CVA@6>e`Js9TN>A~d!boPMH2K6nA!rVr*U z8GUVIl+ZPfn9)kz!$xLvqk!`iB^|%{RK|)n-`~m`49rf~b6lr09^nLfVh2wxqt=KcwU9_-EdKW30POUy zsspThqxDxYo&>V>OXd0-LoYMtWjYZ^v3KXc{1`2*a8bZVP1vYifRrTU7t_9_B5t~5 zF^!gyx5g;sT;I=!vX)WrsK96}iip$}voqlkr?4paeHe6ByO53eQ&c-Bff=c+saQGn zfIyg^t9S#6*3^EJAZUNkdm+xi(?;|050conlAoUHySMi!dzd5o9WG2;>EQtti#*fE z#Q==jL{#)Ax?eqO5(mWZIpKkgo~0-EqiqqV>nC2ohyzC0WL6v(f?>AvY8JNTFkc=Q z1KrH1v!uPsskbkgDb)bF%;oYze+TDq1>D#QdSc`TGY{NelWb=xj@}Sl_#4n^IWTKA zhu6s!#cD`jS%nVw8rY@_u1wS;|LO=?Le*9IAdp#z>WhM<^SrQPq21YFc#c!6V}fFe zdB!CVutory22PZ82PYllYc@}kbt=wPK3cAlL0U+@5Pa42)q+wa-N1QF1tYa7>clCF zg-#MJ6#&P-?z!dyAN<$xILp{iSHwqr#oH&ABkGxj>G%)X4N+U!sFV5S0oYjl-=L@W z_D+hO8|#z-JCWzj+&+wm?e!##R98yzGi`2Vd8kX;!({VqD-gX3D0B;gnBtqs9)8Px z!b4kGxs;+VH)5#Kp?}B9;4lG5{Ew78nrOBJ%q$;(pzCH92>IcoL2@^#xn5|!Lz>?Q z>O=Q}uU^9rG-!LP*zse@rX~QSsisa3?Rc*hT@u&wVnlhX;@A;F+eN8rV*+t7`7dkt zFdB#W#m7iQx6KIj{5xU|W++NR8`oOSz8n2elscCXib@y`|1KnyVns7B7}QH9lxC zn;-x-Ej*WId@>2B<&wIJLEbJ?%vtjN|#GirE011Q6O6sG+u0X_Xc+!qq? z4l%y+91#SOSUZJvRy#4z)8I4A0|=slCY~zWMDl)=8HZROYNVO%T%Y8fL*HwlNxAuP;y2Dq-b`AJK%X7KDT6ScCWY`>CCL<>U&M|4% zy%&ddOfJwT5Py`J7a0$Nxd`WXzIBa5vJU7R4?Qq zF`WtFdg(GV5{govjIaO=`4y%fe0ADs+-DYY(gvmv$4JY1ASf3%=FS9n1=NFhTXb@R zCXMwDVW_JECEX{Cm^d#m&rv+j^7{v(fRDb~!iQs5p!C(cUj@9%_%esdFsC2EVGuni zne)9WwT4ff)93;CuMdQRe^(CL_6eV_`@rd+7AcW}c<}q^ZmFd5G1~Yv zMpe|h(}~DJ;G$rwLM(=+2C=GN?)#*)fXir@lO>-gU_0!nCNlv$(*~TdGkX#QDOp^mMc|2*$SM zW<6Q(DqMeqoRBLysjNkL=gMbacgMQ(Y4ml9R0W}$lGHbzybe->HYB+#JuSI7|=;vB%G)XRB()(INxqAJ%=!t~vlbI2;kVa&nxi@f_&OSy*L7vQ<_Rj9Uz zKw$)FeM^!Z4>;#VX)(bY!19RD1Ga0IeXa^~Au$-Fy*0A1g?#CF}| z<8$VX*=Z?F(}knSqTcP-?3Rs2TG1c{!j*b)T{@?`c0Bo;S&wFhti`w(mUj29AiAle z$}H#{_lHV3!qwtjzk#349T$g=5#_YeLOm3`YpF)4pp{$|FcOx$H^mv%IOY*p&b8H- z@ydCFLO<&+Q~4bB@x&K?TTca$A}x(ogSK@3DLlPmkX39muiuZ~8H3Qf<1TX;r_IvL z$kl8tus++oW~&n%sgnIr1T-^H{HgygRO4XzfIyVBPXE_fp0x6C9+(y=fwIVM(cYvP z>!S{!9BmeQEN7W|Q1YG$q|{MJ?qf0p8*oIh>H6ew^$7gk3~B4IjLh`+2nY^kbN zX@cByMZd$(TE3N3Vt{vh9b0*m=&36QvoJQveX**i1c*-mWm65X_PzNKL4*^bhHeOh7y-93=zPQQU=UlbHgd7v<@1vAkGlF8fF%icT90fTf@d@3GG617ok|0s z-ePqR4vvMJDk0-uqO6_>GW9Z(6>DsTLNyOxl*ztv%uZ#LtsYtR5)u1DC6!7V3-(=C z$(}Z&w$RSf>Hv7xjQCe)N#wq)Y15G5=XfWp1;aeahZP_J{`bx|+o)u6_>l)c+^cP0 zjk&4UZOJ>Ms^vs?M%oIIFwKN7ocf1oyop<)K=DGLxof7nL=(khfk;A0@!y+63d@^3ZrNS7gIbWc?PR_A@Tb>8zOLc#Cx- zNc++0*rBg=PovPY<4Dy%yw#88r>l#If5ky#DU_*j|=(#x6iV+mE* z$l5+Y(WfPClT>>bsEmv|cD{05+^tMI(94c4D_9ND^ExjJJfLOY@gA2hI`%M-VyU}U z=E9YUG=9@rj6*XiLcx2&SA90Db+NXIX?7U!+gm>wqymwFP1#>x0#Ny&Dco){2Hjzr zXY78+d}=Ix`-r;93-bAVLui?lgOhFua;rv>Z>ZZ@sIJnR)$K4{ykUYH@N^|KXhAz4 zQRm69_9uTT&jyNZOv?N07g$jn8DU{oMG|iuJi_bep|c^)`~G6CJ0SVbBf-XoS;MW6 zfvb*TXN8lJM==QNIl80qBRnNJ)mZtcopcXrW1No>2QN8?XZ1beGYT$*hiGXf8vr{H}{%&&%W@*=Y;!N0KmNm;WZWz2_ zL!lsz3%N>`uL+(9@u++P!~CEjtm%!e!gg)82n<@#fL9BIhXSCn9jLUwBu`XzKaf-B z9wY8aK(OJhK6xFWnjpe-c6=^)Ab^h=rUOqTsw0O7Xn2}SKx>{ue1 zm?ajru;;u~K{xdZuSyuP%e_JF6+c8n5E9A^s=7%W{0Fq-c{MMInbAKjjefn{IK%l= z0pdfl(Zz-Pw^jp)ke)I#MCZ}}Mf2bT4$uIm*!bX=5iCnqkpMiNgopQX7o_}u!*8O| zs4R~`Wl&|;Tqe9yDk_qRiNa68wVb1G;1S6J=gU4 zX}xNPg?-$+`nZO0s;&Cy)Xluz^jl5p&Oz|T;q|LNijf8KBbaWVIsa&=MjjqvcV9S zGfED#Wa}WH(>d)Rh$!=bR~Ck6SeZ+dbS10*q@ui$uB>`Uc#GRWlM0iM#!`qevc=X6 z*q!JG2oh?o72XQ91YjJ9m2Hg}SeYi_M`;IyG7s<*05OPSN0{I`y7u-(?>=IS50b;r z6$5W`x7Wo*^?qG5_#o9c;f*uVU2w`?^ZIXZrfya~04=UHM>EC<#?ukw8frzqUMLh) z(&>_lP@vIh+C7#k63s5M8h@HJfQd0&R7|wR)YTIl*)Qm9hEv z?PZn_Ka2|I0BFg!DdO> z?2hI;WZXakwE?-wii$gIsTc<%ysT&=xiE403v$snst6i{?E^h;&}qne@BzO!2yGO6!lcqUrEGNS-8>Gg5%w z25)~73n;^t=3yyt9jIYvw?3v!#-l-^j-FsQtfMe)9X#$TMDdy4m3)vOh@L}A5@Uc86Zfa!1&4gr=uK)nM{jhtJ3QSJw z`9fwa%}R=S1bBBBeL26nW&KlySFnSN*VMtuYS<>T2ge^R5sQ1%C5@JrnouKy|)Y{>&&&$?$v===FX zjt-Romm_+55m-JeYQ9wqtrwN#K1~*TV3MexRk8bi+T8vI$s?eE%aR&>4d%XoA*f{R zB6zs^ex6{oq`0*5j%xBS<+w~<9z0FS}wlx>Ca|JU9+c8tF4NfT#+=fiVf}O z%&cmpf=f08Rs; z0$QD=KUs$z#EAr_7|wxIhwfpX=jE^$L8?ahNk>DnZfd!qL*||*nx-pBN?&~P<-qZW z4{K2hF|11t2^qK4Kz7h(wO@l%rL+ew3R1Y)Lzqm-3ke3Hh^{zL+1!|rn?RcD@tu+# zd~eA%{W-dL?&(cZ?pmwY^>1AEuS9`i?3ZYp@OCO+yv?NyF9z8Fq|qT%iAnI9`lIg_ z->%jcrRn&_Z>2n+{EQZ=mR=1S{X|NF_6SfZ0TDE+2Q9Ff2wZ_G2!|YvlMGBbWyvw~ z#WxT~>@1npSwiqv2D_zy;PGqY)KVT-{H*y{s~OVIJ|%&rI?Pu(V*<349!dLozA6`c zhv5Y@F~#02ZBY-&JS#PxA~nJ4`ov{uprXHuKHLvu&)+=Ac@kBjbYI8j7Z~@>fw)A- zJ-N}_nq-vdG!HB~-U$B0IK`jujCeH*zEZ6gQ?P&VdD~ic3LxmSS-veRa*xbWul{KPKBmOIZja}NQ`xcEaaAia)<{_2k@hR8 z&qArr3K9@#Z#>#w@sqN4pOaj{qR!jEbJF+Gd-n(4=W5}YK0RfANMdb#w=d4n^UYCS zBD_{mBj4uK=CD1k znc1~qT2}?UT_2^k#Dd~P^4^Ejpd7jOz@-i}Jh zYEqt?nfVssMU$mwh*)=7;(>lLkb6kxK0C~F)lqrnpID|Idt4xFmy%9)5)m3057&X<@ z-YUTnxLkAD&4Zs)$V%eSg94|NfoybPVAO`oduvMY)jr6Y-$O&^DV>am_F$sfk~vHN zP2DkFz@E(gV3rxSY{DBg`1Sc|eWOcfA7O$QCaWh)v?SRVi}!5+2+V3ZN*T+*e{yo! zz)AvMc#+i#UG=Ti18s#BwW3o*vUFy~7Ba_XAU}>;L>7#nAKa9fZM3CyTGDIexBfe~ z1&h*a%+AHa-Y<+aS|s%XWFMh)pblOp1Ie^d=22oXwm|uM-5(abKOI1h0AtX&R6ss{ zQ|gszuW*9GQGw;ETY3-1cYyNyX6Ed$i!V|Ji;3;QxTOB~F5sA;{R1qvtQJkkLQh_n z#Nj))I&IjS+xjqh-g$LMlSYUH-b?HF6drRx^kzN=U}3n~7I5rA-L5_fj^%$B-*+U?VqLR9$=k@5RF6e+B*fN7TD=#BB>Ncj*mXn(R{VjGqCI-5IN!Da* zmr}GnbP~O9wm++N5m;M2wBZ{NX!2889}OJa0^+I~!PnI4!Xzj`Op~w<)|O$^l|&1M z9`R3A{Imi@w|MX_Z^1LTbUJJa?>>G?Y2>f1M9ue^Kp<{SNXa_A@gg^MER$`{&zZI| z(QJZFe(LgWL&}>zdecyUYolGN7uyAHiI8$HR&jPLK-zdq{IBgG!|qPLJzgMgdu6W* z!Z}7Mu)p9(uxx(abdXw;(R777VskYj;k46g-JF|8FQn|yms4cAx3Dz#7>j_Dgx zHgFcd67)l&2#za1CGexPkDg_KlBBlqUBZ6bQ$5{AbkTopm+QGG~K?0k1svhIU+{9Ygc00gHZX)UcE+`AX4 zIfIXi*(Bft34eR#N>3KPAJAVl)dkayjr#8xXlynCL9Vt*ZS{tfMN$i=s}5eb-ImDg z!m39*LMaV%-VtIPmw&h_DZiBguo=v^(FtEgd9s_oJr8sl7NPHtypk;W#R( zJ3D`M4Rr)HhPV6%CCE_Tf;Z6FufJ*P0#>WcI7oY<^~NR^!7}eYYyr62%ZAZ4ou=kz zVV*{?Jyy_f=~9CfIF*Go5iybK_px{eldjV1th7CYs$R-Sn}d9YfvuJNWD#MD#*wTI zhsS-n8Y|01lJz2jMMr_a=Ox+NXTuCXXFYovpmC$thQ6I>zMD6j~x^*E4$(qj7a0^vmH!VsJe>UR>CV|8u*<=SCQ+9E(Q;(>;}o5 z7a~0}HHV;c$0byN#AsAxkin|}5jaLNmX##{Q#32GR>zuGA3f9bJZ zH+TVZdQPZUt)8;*qMJB9fXP+rw|iz?&qwFDvEh_lDpYRIBabDI2IxNLacZcq%~Z5$&&|-88@stASe#kP9Q6<+9H=u>~4s$ zivF-C9h(!%#*IUeoKvGGo%q}{;W-exN!dcoW>x?1?9W#&TLwz>1pM;tPsSr^-^^zQ zxI{>!;;PCLeye#oH!Q1B@HE`ysfBnEz=@Q_@{QD>SOGUMP{jdEh&#gd5{WV7uV%~< zrPDEK5lavVPhoo6Dm4B?whtmoM6qcJ6SQ3eVRMr4OrRG(@B*xj;4C#9GHc+N9HDF0 zhV{GZHJ2FQobe8tHH5c7l@sHdEl0Jjk?F{{O>O&}2<9DU*9XXyBm~-7bUKkN;Hym= z)_2hqx}DQv%oLu!dNTl$Lyz`xvEhnn2U|2j8#>WLuf6kFNZ}blJH2pk)8#>vhvUdt zTd5Sq{#Py;Jpw@5();U@0?_&=Wi;*bkc0*P>UcXB(pfw~Sj5J}lVPnzj=6hsJ&>{) z%1f$kV$Z;}zsx&yt|DA8;AJi-^?bt;h7tb%pG$bXLi}~PH;c>xa^I1;qml1SO?)jV zMAW^U67%|cXmqQvUSnvxch-Thxwfnp;0c~XAMrCJeDs0$s8I?BZTh3#>r@99cDZ7k zpT;oJ%vrvJuPKCb?K<6tKq>i5IqA^X@&xWS^7&ycvMQ#`jnhVNC;}Y=;W{CzHcPvF zgW$4A(dB1l0QsC8Gjk;Tt`c@fhASd45Te1QY~*T7o;FuOaAZvOPFOEf6@66GtXa#*s2_vVmUT3a{kHBnp=Ug248ji$4I2@kK8S&36XDQopYiQdxo z861amv$SO-Af*^QjTkB#DDUFF2*m2pn!m0TR)~n6A=cfy4-e*@th&yc`!}&|0IYEO zhna;(%n`KIvRmeA>&Z}uw8d_#b7K2t?cUt5d8bD^8#e{U#8z}|KD1AeW3ncDA83C| zxMV7~u3_8uZ0&7Xx5QkG11DSl)7{%4J!e*}h^Bt`pT*K^lj68P@rFP%T-;}e_Uc=w z+Us71eYcG1y01XU;`n^<=4`R-^B{DHo^TZK<0zAFYFd?XB}5tUM%*8IA0o|st_@5~ zzr>lyRTwsMCWvhTp0s$VJvPxi;?C~za+`d^pifVr?U$^<_nl9DXVXVlWvRPcX4rw^ zq=dksi!%j=w1dHdoBzixk#B42mYo#@)F{d(7c0o9oT8L+nB!hIUHTprl$jdX;XPk_ zMO)0faznY{&;vZ~gZz|Up;{;Q69r$l`1yVa1yjPK2clFli6Zg*VXi1n1NLvs)pDaSBxlXTH zQY5Kf!@zOR!l2?05{;l?D5lpnq{NNQ^{@@lv%-#RP*l(AB0csrq3yfeTYOI8R+6x* zK!>^LkW)U|U3qnsV^Ez;?8^?V?C#B@WBP-g!Z9tH841xPjFszExKv4qbqkBLf6#h=*0eRz;v!g_WgUk`t-FJUTT`7azqgx^1NmqFZl2Hp@ip zrt6u7FCQbREccO=L?h}T4lXobHYL=m_QP#`FI&cV)G$L#gdzr=fZ&VlzY!7QTY@QR zHUk3MlD7m!nami(v#qIlCa|u^=!^QurCzJ$z}vuQe_)VU*YA8M99vbQP5ah+ER`(- z5CWax(4P}W%D zWmtcJs~%Ajh_L)@!nrTvr$bgUy+E}HR^%hv4l0x$GuEidU_&7rPlfy`T)W6-7x&d~ zyz2Q^ldb7Z90+`}{G7+OzF8B8(OM>{k}B+9g*aqWO+4i_L8cRdwYun!w05U*%a|Fl zCQF(IVY>G}G_c?!aqG@znkopxcaaF-^YmX$c>{s^Bhg)%b+vce@vwB+!qzc0zo|Kk ztS*r>9L|!Pjd~?<+mR9VRrorTuI6!SekRkeIM-}Hr^4N~V0UJB;r(LBUHmn~sn~-6 z0$o|Q`O~p5oy_qDAuRiD*&oR}3?57{;7Aae+vYpnMl{-(?9J z{%UdkqnvApIpo`hkmHxzGIOw((f;&@d$Yy$TjmZ+Rjbmpam{-MaL&{;$N1aEuQhQ) z19P_=(~o{B<*iRP!UU0*3)7fM;BQR^HOXmtSr>)WiGxm zKmxS0V}uhdjel9KWy{;AlFtA8ql74?-0-k3`()_-6G5fG z56;O zVAJGnfEItU%*oZ=m9;5r2qr24_ zE0Y41Z_FVqW{5k9*G^2SCCQHWc)cN>eOsAV_Jr$L#$3UJ^Gz9`K$BlJ^^NU}`es7N zu@`J#Gg#?Q%Wr3k&87AJ)x>gIi(_*XZ8ks-VOC{M{>9khc8`PC_{?GyyS0uG0=Rc& z17>exy@BfI3QR*Ctn^qHN+eKQd7ki7k1>m@!Z7BPpLc>Y0N2oHy%gzp2cv?AeK+*6 zYfzJu8bVtI71gCf(JHg>2F4zarCivmSo&*ZUwPb8FyQZ!aC=;Yl?{dvP{!aOm z8lC+i?kJsv)2N#%Mwnw5?bZhsnIliUF?tOA?HCwtB0`d@)?6{Wn~6Cp2RyizFh~95 z;`?*G6AHMWIc#T`)GA6UyZb3t!3u5@+4yC2Fzs)Z5EEqIinz)ll_5he%>-2Jd+80WYNice8?$s6FRGT&K+d-xw`DUTMS*T;Y054 z9+&kkS5yZvm9&c3 z%yBe?B64eb4?HI#_by$Ma9_Z&4Zg}0b3tvzye5pv?^unpGCK>&;>3|H1X=xWn^1(? zQUQS~rJN;hY)gdn>J8yIkLUBE9uKRur#a_SI5NvUv)Ie0LD{s2Vqt@?{y_jWJ4~>e zS2^Sf8XsRp;K2ztpuEGU|5@LoszmxYzH%fYclk4xnaBTIeMobPGCayl$I-(aGk&k`Je%ygOQheKgjCXu#IK=$)5n?#S90*f3lT6-p&bOM{kje^iG&TC zBiAO=nJXK%$qruiX?=N(hpQGjw$<$_tQ2@uzaEBJGZ4zE+k=g8A^y44Nse`u#g`I9 z99~q~tN)J=0TJ-lr&N&SdxY&G%_HHREm)oBS$2zIw~+f(8(4wFhHD_EPksv>7q8T8 zP`&S~nfj3SKn`NvqLWNa6%oVKq2JV_jyEA9sqzV=|318o1#2*ZOR57#1D-pxF4WD8cJg1-r?d7M?zZ z0ZAIUe4r%mk8TRYUonUDF|cf5r)_YJu(zLinp6n z!|X%x-fFjW1FuOhL11B};`jjGKui3Xn$>n&%5vqLSsI2>Wkc~L)*iM>fv}xo$uUBK zp-tXGY>7#pGnx>{8&pkCA<5V_MW+I9D7oDM4yqj7az3#b_;X5V%?J~ zQz{(v)$2Lrs3#MsQaQV4Y$SW7k4kGH9}j|52{pAf>N``8(qX%_T@Bc@!{=#weBHQp zgzktf*5g~-2kpG#g-@$=k}9dA2F1ee2zYKS$`t}0uY}M&QuhQt1CO)6i z-KIEVorWp5VWPU)(k)Y+VpO0=D0w z&i(#WE03PWVxt3`@aS<4iEmgrPA}GaV&@Fh($q7aPc8@r)XbFfii4rh9g` zU^GC_Jrzo_YiQ>_wX7ZU6z7r#2<;8kA8vUX&)<$c{P<+Tp*CiY z)7~8bJ1gp2wwyRfUMLw=-P6zihFF~IWsW#X#9)!ckLfE7ZJ!~a!6ELq_8-vQRf{1@ z5rdt>`*-$^2U|R873K4~_x+JQ`9D_<Rz%7bT?ho~t=7?fWki{IY$e1;f8-WGbjHpO1E3DE-a|Q8m!l0Bs9Qe$A%L zM?WsQ9286tuj8>^aqG&$wV==0iy7Q5j-GB2ftQ({!6R^q-{V!q04+e$zec(pYOhgG zE(tKCtw(KKo(N^Tctq-v8xr}|+X88=HQzCLi=0hFCJ&{XsISv>K^9_D*QUCn{LEom z7e3pfqyLoX5fFeK{n-12iA!X70u#{Wvtup`9Hh}}VZ5iFv^7JAmLebvj1!M+VXC3< zUBzxX^NT~h^ja(9@p@b1CjM)t#@bkfKK7(0TOEXDR;FRu2l^3JP*T4wGrk0M=%ei<6PPWqCJtQ z)B4#|q~?&WoCvVTR}(gS%3Dz*#8P$p0q|s%<;fXLg2~A$u}Iy^p!vGT+lxeECmsIO zxY@}xCWe3N%8aOy_Zt8Di|elphqZLT0;sp3z>X-6XDa0sV01oI{roqs2LT`4M$EGg zCWbOrmk~K z44Yl~Pm!C9cgUNU@D+90B*lT!JIUQj+q_(kIEKp*`{Ge(!I%11IAmSZfT*4o z#2JyyR=rGIe0MqLO=wRn%s83KJCh}hwvG4?7trO)sN zybr6cAnFL(F6JrZHPo1R@~Yf`whuFK)p@r%od$-A7N15`393%GHsl2rgHh8NB|3^$ z!|&Zf@r(<*umGIk$A;mN{pRV&37d7e$;zkhv78+Ie{`Ak&iky`xp^8Wr~`>ZK)1q% zlbKT%5R3hNuU8`@*svgcvCspbJ9`Xo@41u9y8N28RHmk7v7&olprnuY$@`SN-a*`6 z!RW%y?VSO12f;l)BxB2vPzkq&sKr>;v3pQD7B2UH!*}VKehvu6&E+bH-1O4j5DY8@ zG_tS+#r$re2uY3++5@zq+rwnb=}3JUEU3%SSf!g3;#dvbk_+YfRzQC3(XVmgv%trO zisUdEvOIyiJO+MGp`m#PkJRP0t>gYU%(T z`~?~?Zd#v+phJJ~Fhvdcof4HIS}M3Uu0}db8eYRmf#=96G-uiUF~Dny?D**2`XFUofyfS=#)p@gAni zSaSo_t;s>;@-VXqwsh>8&G23P8)Jb)q|df@4zdyDX#Dr|D4{h9Vw)lmkyJ0_$3yjfsiQb_}wc?`k{{uiG;6i zWeeEbKMy$U$5*~~0+%*83R73)w#|wtAB4>L zR*5d|Az@D9K@8jb_0m=-BZ2f7$-RWjkaieA66WY2vdO6UUwj^xfJ7Zt868YHT`iX? z;GnFYW$)miZ?1|CdGd#sTS}={*TUKvM2#<;(x+=KY!_%mnY57lP>CwCySOlJ(oUf( zyznMOQvu9+0+$iF!HvN!pg!{yF!N)JPZHe*F5nLW+lJqVuxn)px_#R6T3k{Gj^LfYA#E?9uR^bqaH84vxR-Q;dc;2K42|4#pC1kC#4z<8G6xS~`>wU6(Ga~3 zWqcA`uC!A!83B;;wyMCYFTtR7_J=8v9HUFPV>NTyR~o1E!~uEUgn=Xhm8XCL@57Pc z*fhbRW?xii6B0ku?j3O5#!SE8d`3DNf9WFtLI}=Gs6>8@>2Gz((z3fZ?!|TXK~pU_ zRcFR17S^M9zuk>fV)YZ5HPfLEJ@NoNlVd;4;tplu(-9!nIBID3>R4XfB*^@KP`injeg z{1Oa~BfYhtEMND#n{Y+kr*zpViTtjOR?%e()`l)inbcBS>!RJP#!Yc?>>vehQLeEu z0~l!*FW@rFN&(VLyK^&!Vu}`>t%Uup(KCC8|7jcCeb0|mbw;e za}sOuz!L%!$^#e?dzY?&N?jJtTt*QK%bf-t4HvHyxTty(pI*(*APhwPt@KVCjC$pl zv?yLJ%Wa$0x$#^35SY4NrL^fiIOoza-4#LW_z80ckeS&apmzTB&M^jkxetOH5PS86 zqR&UwYwX-APpxQwF(Cc*2hs9%)v>QQ5mi)(1u%FlPK%wbh3=DxPdgD1XAZxhjUmATn^|#7~U#-k3XvwKbWa z1qth>6Q?~3dPh7*GyRILInu#~f3@FpsZ9^qlZ*?r8G*@AzK_UmXD%g(TK+Ilym|UH z1&rouL+Atd>i)~_7#kaZ_QEhL>-Ircs;lyqyMQ`h90Er>Nq?ilH+<}T#TZr;(@_@~ zhW8n#SJr>F{ykj^>b%U*;C^<1Yu)1Vo2XA>c$?$wHU zVb{D#1sb-T|h0Plb8y|Qkev?ukyq8zZ&QOty@O}Q9TB17Qn&B_d@b%XpiH0wYRNabjI>B`scLjM!J4-#(5%SZSmY^42TVfVdBLsp#wEF1c!-E4T2wVD`PP<|D(fx{0uOzQ;m()G`De5odD>Lc zg&o#nv(}|}{=J*i)px+8t-Ib}R76UUc0P}jlev~D<8ZDn&`8@uNv|sp*bG{$L0?u{ z#-kaS9U%X$FeMJ*+7c=#Q#PGS(N9k9g2jxXv9rYSU;P_Gy&;hCOt`c!MI+L_u?Br% zN168NA*4|Ou#VgEiS^TVl7kpjN^`y34&K8j|!kKTW}O5B?zBSVMs(DHFkDEA}Rd*h$k9c zUa;fIWjNx%=ar9r;7U3A(r!?V-3gTW_lXm7I5b$6Fa8glLn2IvdgCbWF2R85y$*Y_ zs{hF?{`9tu#}u?FKvl>9i_z4I^3u2FF<6+$t8S;p{jlvsiN;DUgHv(2_9x+1_xU*H z(c?{m{+rR{QN?wtDG?6Y;ZlW!f(=`IW&}<03SaaVvK14vK8BwT@A#M?-|nevRV>3B zm!r839e7t1xAc8@LC83mL;SSvoZ~-phw_XCA-fFj)o?sgxL4%pifgh+5xj+SzkVYG z$?_G+963geovDUC_(*n==w>1bSzi9qyA{YF!#9vgF-^HNBo1h?;zqSP(1zCY>bYHj zA(^y^z^f5i)}dcI$oAG_C?b?dU}nrf;Ej?9bTiJKF+JP@aw$Mlus13NWD=qk+epZ# zI;x`tpLx=5WjG2UmtwZ45v&t@?@Fw&xtSaxm>@oqH+N)$p3s9KO9Dl8E0%>7I3TCC zR78b|42Ua+xp?KO|8AF2*u>K(lftGCqPau-aYi`1!11*o&pmk6`R93Bl?>Ve+Y_xj7;@JPo=Fx3%S)Fu;2%Ru>y-| zFRU(&Dx%LI``KC~_f(=e`Lhn`e-}GOgWPQtkF>iOK7TP-BMIhah11Sg)H0>WO8hG+ zGSaKKN?Un-a>g!Y0BuXDAB4Hfyv}P+!yi2EB3c45g+b^3o`lcRQ@+yXu=z?zfi*He zuHy7amL=^>kc&{;H3gN(!D2Y@wpIL(X7)*cAv7|qZZDX75aFQ!9pj-UHn*+ecYSnB z$OwrF7{!dA@J(3F{q7Gs_65PzN8H|ylz5I4RKk%g@K zx#x9p3A+|wW;MFR^O_Oq$GJbeJp<^Pg-%+v(0TiR#60}R(`9t-2^a>5ZXA9Vw8Dn( z3WLe&_uomG*7eoB^{~JK6-v<5l^W<$^(EP~6wCqs8b6y=TAAT?#fNi{WHUj zJQoZ93Q9o=*f<5Sz+1B*;9Q+(jQxI-P1^2z*HmX&MCD7zH<9Y75A+<4VXp9*MOjT?g1(0=7^x%xmIIldNJ;CT z-TtaO1_|sx1jYoSVSqu7SY8RcLjIZtfT#rsVtM8 z=%=KH%lr5NE&$v)pL2-x28MFWOe@yug7mJ3`;)$Q92l zIMJ-2Bm72e^4k*Cciln+6*=kW!Tez2W_C|DA@u$@#Vt*VO8oyepTuFerC2BVS!8O~ z2hdHU=+o(;5c{#r;0vLRg&RYdFW2!TIK=Mivxv6E0C}!OJ_uSe6ILETcoqL(T4?l@ z#BdNgDe=xy*2bgCl~iAu5nJS18`lpT5-TH1F1~o^S7OA58DX z52VgC9Y4-Wq|5bR47et;=t9r7H4Jrx#3}e?K|Rg$ZkHLSALLb1Skyxgsv9h?f?2pj zsh&w)H^O8-odHmWtbStK_b0*Xi50OVQMl(ha#_Z0SlTz3TU{8GDnmPH6CSbhQpL$g z1=Rn{Y~$1(zsEvX|B(&6i(Tl{U!l%$$MM3$^rN7)0XGX%yv=mJHFHO7dr}0{QwoDp z3DJ73BaW!`32)!lL`Y!hyhTH&y{fu2^Dm1JD!@sMW3yT`*i%&2xr%uxt3Ub3Da?N_0c&1d!-R|w7fPr1vt72cRF(|3bv5nz>1F zGC=jIL%>vIOR6fH$D5cq{eE*$K{u!vjQTM6qgQW%3*c2EU*MYmVC;XUK|}J_j)eaZ%|6FCKt^d zcWLysU|{K5Y7QRbv|{H7{Bvy-sDIn(`R$TTlg5Tc=%8~7GCgw4NfcMbZC`wfL(7_YSPSh%3zYd@v8ie zry`dve@K!>ezAvQ_G_T_z1d^Z`0*p#Z9BE13ZSt0&gT^z#Fcurh@krumdd|RVV5>B=4DyPhv(EJZ z4a)Mfl?)Q~bji^eFH={cK<){H)%5XH1;U;0QFuA=4cIz?u9u!)_}6VFozN^CUbo={ zB!i~zSjSm-WOu%XZT|MS45?~zOP;Xw4m&1-63n|xP^%tyDJI#s31)%v=JGJO1h~Bp zWrD%t_qkR_!fCGg{x50NihDGRfp14cBV6Z0z1DNDQ{{}3jU2o@^2QwI-jj7xs{6US zo=XH+CKEy*jqHZ38OEp<{kH}_!e`zDBWxd^U_g>vN`_F)*0QvKtmLdwU*nGaw)MPmL=3C1lX;F^wLmc!UR_ zO!LZp+F)DG_8vxS8TE^hml8C)7h_8VZ;)0jS_aG!@{pElow&&HX*Cz&sqpw$W`DeP zusistW~JVeD*a6W)BUaIJQo${1t^X{|6nE!fuRHxg~1p8V=U_t@5G}#M7?yBl0=Ra zd%gXA)F8giFyh1U_4VII9=Jc=-q&oI=)O1@??-m|LKz&cRvv?8!(2<10P391p>oJ? z1rD%zI!jNl2(thz3hS!<;F}e+t*0B;Kk=BdL<$-wl?$q@mi(&=s+LhnU?SdZVKCnX zbC>HXBxsehapKi)-5`VbKb0g+mH2UJZrw~R_BdOo+{GD_1?JOXK)J{x=ORj_*F!%& zI=U$1mK;l?m6%k2V*B&3ac`14a&R23A>vqlHh7D<9fhF_Mpxy20?oMJ)og4?B!;pF z#EWuDT0~QM@5dL2IEOC=Q}9%3f2)v6X9=f$A#Pae)A+z$+haxHU1>Lp# z>T>WH4tLjbP=o=<*gQopkmh80>6BYY3|kCVpAOX?cK*qbq3YiBl|vA5fYr{16bL{6 zl?mPtPO;F^NThMyk+Dr)rd!2ct-K=2$B2yMKi(T<6l;=HpG8hP81DYT7z5@I70etZ~;dppGUgGQ}rhk+!LOUc}31;DK+jX0|9BqpW49dSxbK#TSzw`eq zn^7WsCE}sysd+Y+QgoVaRT-o6$y^m+K!MynN)@A7`V3r6w#Jbhsk-sD2NiEtXl4Pf zbQ74*LziKqnjzYh9or)0DR6z#ZOga z^i~|V_0cFQlPAeVT*+d}-0JXU2diuYmX;$%dKHdj7rH&In%hNOn(FzUy}DGb?zKU+_BBwm@*+>b>Go+7w~9_#BVN<=&CeMLG%Yk$h76FpzUYi6x( z>&U0Q`$0Zg$pJ7zl(fP9U=Bxz*E_MMbRn>Wzl}f>_muIn>5)Xo#oSj`ee~?_3&dEe zBVnmZQ1BmR?~0)60?u{GXr+ zLR8sqTHfv2VlKuFvt|jjvQqVYAd!7ThvP3#30CFSOeV`2YV8!9UWi>+-h4+Vp4j!* zIa_Q^;nSXF2C1xC)4=w=M6m06xV1)>^9Kwu03GUhdJqHMV1B)3#Frrdfy(1$>X*ul z4-POmQ8Tcfe58E1Q(8VXWqesNl?YWvWyEZ%1f%Y=+M$Q>o17#v8wU^8lum6vO91c9&^@W z&61nY{h4wrhluU4h)?a9@3NUg5W{1Xr0u=TbU6j#zhIH|r^bU?fpGp<80lriITok_ zD)9)FqDj=HjjBDFi>->5do|PX$OI2OBhCOrJAIfS);0T7Ta?hk11Q73VrZH3F5+Dm zzeXU8>swBSc2RQLD0hn#aS3iN$n+DXpXIc5`uy^o>Kq>+l0IgR_tCqUQu~T*eu$d! zvE1+g{zT0LIxL4Z3~h~MU&ZQ)7Q&yg!Xuu1WDwHT$T(x+Z85qGj}QM8$A2;ZJm|n9 zyL=g8E_Jy7a0|N3=YU*3MCW`yXuw{j7_mJPH#>>Sq_o6kzI>xujFF>)(m^xpW8+F- zc7rELlyQD+GvPxFW7wQmvB0M}HmY1w+DB2a%n(e& z+(EGpNyPmvTH3v%=Z45oYxXC*Fqu=eu4o>Z`@1aq(`E)L(r0P+#C?OCH#Vh6=Y3A@ zV%c!_FMpx>6%hlxto&Nr^`{^YFYP?->)tZ&iH?UA3TV>0pd$BQYkZtg`eQNnip9Av zIA`%GlaE=44F7w}HqZJRUr^ZIh;R-i2zaU8t=TMp->IhF{|29d*N>2wqdXeP{fLIO zHAz`>@6=dhawLi9WOSCN$$)B9^r?B?Fx)$%;M%qyiG=l}vJFAFw@T#U+;{FIp4rzK zB-%hXeFpkWh@`?C&;NbySCR&XFDAM`A8Uv~j8K<$$49s|ox`ZqybKgm$xA+xOb)2X zYPcuMiBm&d4a=v`6kFqPy6#bF^}A{S-{Z+QTTnEmfXbi&NJ}7?M-8klc2#&|pVmh{ zxlj`yHP7R407>Za*Cd8h=>U5P{^#g!{A@Be8i~Zi=O{Ym{B5+|qNP{aam!_Sm^zmB z|1z^W)_BgZk;x_{B#{COVu`blKD~^AaIAZsaMq-!Z7lWtfR)uC&fsCvz&!0Yf;|yr zz!U2&TI@xM>FpXL-MlsmN)Dwn&$O%s)9)XmD2GDdI}^6vsqPGsz@a?qw=GUr?{ug=y-e<5ex8fcS#lHrklCUML(m zo4ZtT=!`0hHc3YdtJSwnluy}m7X8ziDt-bZ4&&0d-vl^mV^&1_L!TGcV^}7-GAdS2 zoIsA3TDHm@sI4=z3WNN9P?2|EUei=+H7TsN2)%S@aGDN}?#iK3qkAARy)CeqL!^|E zj>i!{L#0J-n(bnTv`~`0P(C8&{KLz5USQ@xu$STn@y5_0M7SpoBcbXF?XYRW?v+cW%hGIvUmLKHIB;Ihj$OIE?Q*-ivseSc6lZ#p zIzAwo@_KFn(6r@{Y^S#snjIq$m3+@mSg%}4&+e%=6veKYr*gYj@1bf`lC$JlrR@JHACv#uWU-J5c%d!>6*zkIRNeh!2q(Tj)$h%)?7KPX zP<%%us(q2RGgI}#b1a~$`wf?_c|DHbU*Mnn-tpW6E#>HE-4K;sXr^W{0+*DEYBYqh zcopkKy?_T^7p=>hGE*kb_`DMj$~v0fnp%x`bD1&3d9VZDU)LPiNW4CypsJSStj}kd zr$1U$s3*YKJrJJ?OC=t49!xIcajgoOq;ZoTjZ*4^t;B5;Z}X`mJm3Eo98ThYDrzJe zY31hI9cJgpza(N$(cgqGKL{bx2ULGW91_{r?-DtuCJmJb^8E|xb29763*|N*VR(^0B%@3ZlM>fh(9P1yAMa`io*}8PWWcMl#~#0_c3d+tl%h7m@EgHE?`4#b|iXpeO#VS*1GDDPku%O1cn=C zSPsIfIIoJq~|9znibd#s-wg!^&2pzCopPp1YyDt z*+MxMW~LnLsEzrul4E4Op|ds7GY_gF3eF=@U5@lG;|lW^j(cH`r#!{~tfvt)a^IN* zr@!yfbgy zQJ>?EdLw_1xTgB(EUxVs9ahMTAZ6J@h866pZVf~mDU957=xuv<;sAHI<07t;VV$ro z|D<=RS!_Kq zibXtF?5P9N>nNc)D>YT%YyJY+;IzNxg(l>@C(eS=pwkaszpi0Vqr$p$H9xfjSM>Rt zE!-oANe#Sd0b^Bh7TYNP$sz1gsh_YTX+#FM62Xh+&J?}G!n7LDT*Tzpylz#Mx?{lT zZQmLunm$!z{@0x$_qgh)=3M;V6Cm+wwo?`Phv&B#9aA#PLF+6~LV(r+Ok>K4>oADS z2(Y0#Dhawi#Uaq6AsebAN07e7yAt1~TI;EHx1n%zibR|SN~i7T*nvCvC>RD~p~Vwt zfFRlDC@)KmRJudv-+MAB3Zz5va~rNsEFKr)boR%|>i!u;65EDbNVp zr<|=*RuNnn=C8?y>#vht_{01cf<8oVPq7ru9ZumLjZQP6T80W9WDmPKn*$X`tmypf zjB;MQ)i9?NV>TY?DQ%%eZ?cG2VO0Z2C*8k9Ly<4%9#Z9lQei#bsW!}Q>`Qr6I0 zLu_V6cU&5=CzEWa3z=LhBZe=^tT3KdfRKG0Mf-DdIwUL%EBtI1Ri`dvK?bbJ6JpI@ zs0N)}x$bcw*-4kynEE0vGSMa55dpCHR7e5tl~S8vYA1b1?mO?Dd9xzW6yhM z|HH-2F48~MvQq5joMk#hE*wHir9drx&lzH>)(9WEXF6t$m`z7)aL^U{oSTfQNncIX z%r5F?|AD%2_Q^{y7@GLQj8HG{*_!kV8<=GAlb@B6t8^`b32Sp98zj z8q12oZ`Sd4jq1*D z*(a70;6LM~wK?OSt&Ct<;1oKV=DqiQ!E2*N{EHNt96IWdV&&pm$e8)gU0xhjMD$55 z_c9EDe7&2NePZ96Y%-s{YnZ*3EqL=rvq(1W2&jddLa_b9H<%&Y{<4pk zFkl+k2vHgVPNR9oo`yz-2xM{p6pF;f1%R^Is!tc~r`CgLp%pE?47R-%+SGP-@UO+! zk#TO~m0`OyY-|Fug_A?UNE zHy(zh8wd1ljqr(x4O@NBeXDnDD8VHYmX8A{^-P=7dhdBW#`*rc>V~&hZ{`{p4VqtE zGwIT-VHnYSUk`hywE3cgMhTGro%1vs7}*lYlb9cx=f@Tnn8Mj^zqqn@hG6ar8mf=N zjl_peVghWv8%Ho2gU6FUbQPa8=bD`Is4kK>s*ImqNMSKsaD}i+(h7 zAfoZ*HC-Gd4?cph2F^UE%T2V>G%MJFI3Fx@HwJ5LnV5-TkakySQ+*%5s))lA_`p}2 z*;ODK!dd=&5;GYhxE(TC`iv3>5L;XJ<@+P1(vuNPhW6AL(X32Gyx#@_gj!r^v_|MJJ2cD#ZZ zpX@uOQy<2fNQ1jlFPt=09)yQ)a-u_j`e?jnJj_N_#YNo{c^xtWPb81(fw+!xPIX_g zpO0@)IA^flbGia)E&lRbS>aGlHzSrM+eQqqix<$st&>|T7CvkqiS-RCfd@mvOe4)M)0X^f~IKXQGA7Xg( zFqKX(k6QxR4F6woYFqq{lA&kLyi5FnxB$tEcI~lhla{R*gYTVH0O$sS9$gCKxarTk z6^^3H`IH_=QEvABoM70=TC|>KY zEyizCwSv5~e^@B+U7+nDF8Xp=-`oVxs?kn0rkW(nLLLurk^ejWC6czk@GV1svN!Tm zB-NhNV5s6~wda?qU%QpElXr6yiNiu!v|XilEt|=_6~!mhOaePsp8Kuco*cF6XHBQtK-a(9t1i)JIQCkZ&}ym{HE4Be7#1huf6)4lLME-MKnNq&}7RdC1O&OR(9 zLIMzXUAGzL9BN|}$~f4}EXoLrbGemdkNcq*KOu@q-lA$}=UUYUryFjYpH${OnHSIFf9cX#Sope#BHZ@1ixmhf9|*pXy4Xnz*!tXh|NA|8+b}V1Z)`{Yq$# z1Gg8luzIxst#g3Gl=r$IV>uchbKhOEZDvzD<=`ge!BUWLCk&ooaWaM9|x zyO9t@^=_?YtV@|`G#A(5o>5XogoEIg$Y?Zvrw9N50|EsE7S8iL1mG)Fh%9iienB~%Q!O)csd5^?4G0GvN}(c~DahC=4aII#}p zlM)|~96gQt1rq7Z>}so~#&D2gDE5>N#x8LF&^}y6(WmZr1BeC<2je8rR6%V6v2x8z zOwZ*RuqsWnr@$Q@tIAn|?SKltLu^-kGl>fIC(X^(h`T}JJ>H&<0=&rMlPHjh=Fl*% zc3g_(xO)`i(O!iZM9cU}dF6S=SkKFm;cxnVU(bdjXj3;$^!t^tCk4SQrnz#?xG#ER_HtzRT(itzgkHP7q&1!eIIK?W}E z*Q?{nK#}FbNgJH}X2=7(8RL_MYrmN4)B^*0<)cFv<96+#u$#1jpI768Ja>7A7y;q| zV)$M#;BLW6U?`@Sd^3v^wN-nKx)DCx)?^aPIHg4+6E!VNoZ!z?JzeMECu0xig*CSd z$fae|-wMVy2igk9Ydu|Hw`aVYFK|hLLj+r!D)pQ(d8dx7dy*p+@B?U$c}1G8rTpdAPJT?@zBerpa1Nph%cR{Ek-FV5eS=p}Nl>%r2dOML3I9CBo%H zM`>KxT;EUMR@woTY3nGkFQ4w64URWK<SdO!;apdYgq1`}_e1|6F0)y+lVmXRp9vB10fy-H zc_O+lFRHiF2(q1@W!3?!kjd|dvQxle(6NAj3)GH&-^7?pYZEIJ(9SAFwG2?Fp)Ecy={Kr(Rs*Iq|+$?f|2x7@Gy&kPZLxyQBRov*(G3bNi+np60( z=+KsWCWt|OhofTXN&o-FK!dk_sSeR{z>sWtqcjerjqy|hw-0Z1Lwg|HyE43Sfh4|m zf$+`SPzPWdi&WPFh9WR_nObrYe{H#j5GwQO7@Knp-_e8}p1LZMX5NTIwdDrCCP54g z>F$%VNOAT($^dMO08|?7)Bu-kbFGq?f0wev6XDOjx-*#<7UI*S(?RQ0l=t( zuy_j~gvyW(%Z94KEFr@*P!-bDFp`FX9}CkYyGV>0HolSEsoiP_6#2#$3bc2vbV!CC z`;uGbIviv!>kQwtl^&Qq*eVz*WLkv9?$7m~6gHkttecz3P-u0`=6AkTMVO4fWg-nt z5Wp^Yv1w)0VcR0ZZI>F{-Dy>^1k&{#Dxk$q&G8bHmO_o=W8X+&sixae3gj6H;NMPP zwNVOBO4WXMYysK|LHTD@+oyIl`wwPIl%?*?|Lsn!*g%Akm3|=)+qWsZ*NZ=}!{=>0 znnq*(Kq9H*^MoJ(00RPK zIgAtjb(*0aKGAN8wp3O2lA(!wwb)mPrcpugZ0VGhLB6ww*3*`n&)9oY-aw9(h1c_t&(TW2|I_oIHMlH{@$R(Q-a^v!e@uY z$}%?~Dy4Tz2R5g4hq((W0L+eDbwm45QV4me)`_mR(C6-@&Xl9DA;}ZC-Bbr855TW? z*z-4k*dCN9%O}TIHRsRF3Zw$@S2oB(W7wUFE$KjmLmyoVdVQ-U30Mdsf1k6}&kP_C z0d5Z5uszA+5AAcAb}LkGE8?hDB3C5n&^%p8vgPY%UA^{1zGINM*}p!DvaiPRJtigb zoLYQeLGR77`0th>wA`#`0Hd^B9>swhnfvqY^Z=C3YH)nTf14jFE6x`%lm7=$P3!=Q zW%?85TJGE&=HqJLX%Zk6AjMm2x{hYh%E|-V^trC(#eL;({nA7vX2Z9$(>k*sp#9rV z(Q*+Q+bRXa#1tvkIeTNCOE>*6nu7*jj~sI_-l;8m+?xy?g~kT__j*51hYBH{$pe{8 zTlmQcq}hc1(Yy+ON74Mx7=>NNN7mprbhj%aJXR-oA9Y(HIFA*p&UyC-Rll>&PX%}u zMl(bOxi7(adTd=H2Fv&;;alRE07t^W)iC%i)i%3BNi_CMOuC^F;WA8xnj0R`10K93 z5^(DkAE*MwC|NcW{d4GHB2CyTz8Tiw3_d;^CTJgIH#xRfzbX5yQ4ZY1%@~1IzOsL$ z#NgUJUc1jMT&YceR>!0BSeFP^E^u3|(0^nJ^84OdXn-cCfk z;$Nwup6hHVWoCT7zIiR)=v5E{tg|lh!0YaONvqUcaKNbqD_CmMin>{_ZH8r3M?$hV z>`uZiw9AqW4c%@IOq3967yt#IlxhW`5}h^tLf5?WtDaj^A*FU1=p{`w#F(I$dZaXF znsiqI9&BBPn>eEW54e9=m-TdVW0MfHIUy`dc1RBCCgh2)&UPe ?u#C}?!gmkCR; zv;+40-%?tfxGFq3-u(n*J}g&L_d3f(82bH_3e-$v*6@e93|?rFfMVUW>!7*|`9JP4 z540(bAlLjftYN>dN{g$`f%r-XiI6g!)67P(xwkBd?lvSC#1jp!-<)<}FUed;!PC6m zlvRLfK3VW@7HVKJ{=|*mq+_j2WV+VAX0b(dy7i)LR@?R*5D=2k!llKpvlTqF_yiyPwBGYENq=(3c1Rja_ zvGpJA$O_QF?p&3YE+{b#fqja#XK`@z{^c@xfj=7;u^dssHVG)wSl;)Fv%{^sV98Vr zL4G&j>Q(T+9!(DGdRp}FHW}q^r#%{A+ld{fpUa=(-Tb2;2<)jTu%B2f!i27+#;8Kd zR&rP z>nTu4Cr=Sh1xyid-+U!gEuZ{GXbua@94Az{_Wlu-2?#o|M3t+{mXv&tgfU@Ko2SSu zaVBHGyK41s-@UEUP8t!an|Kr-1KpNGX!o$gbzR0J_rTTTkI}t4Pj&)ry8FFBT`a={j@YYyCk4e?W33uWfYS$jc zU&t1x<6;Vp8V_%3Q)n)j=f-amyA{>1ME|koEB#-az7DDlUFnyRVW-=e@G`_3UZJ#6 z2*SsrvYU-S2MRoZStX#n4>l#zUV3Qu6aAxhqwNnKI86_6E_)3^xY7VdK)JtRT&1(y13%0eaHf_R5|Jj*X&Ly z&as1$9_bPi9qg}T0NLRyL}|RC7i$vlrm;EzWdxZl=kQHG@$#0H2F3@ToL4nJO)!eo zdhj7R`L0rm`#cZn2#gW)8}2;TJt;NjG9aAAIN#%HjH?)Ukl%#@h)Qpof`Mg)@(S&L zWp_hJ1*X~N_vwJ0ivkE0jZlM&)w0^gAJHSFDLfK7m>sKQq`Y-FR~gnmBsnQnWd}0wu1#8a~>qQ z<*N9EaHUgPGZBOxdjf>3$T4b=ga%f3fRTYQa{2AbM=NR=q zg_qQ7iSh$`w&;-1)jtbsubd;+oElnpvuvppH!WuX}C>(T6{iHHbzrFhk?VUZ`Y>76-x_6sLw082U)S+ zUbVcdv9U~_nRsxn|Dj$${{)B@f|JJ95J%-@F*txBO5DRYkdagcx%uA1x9@hM37-td}(lSku zrO>fDz7C2}xcf)eA8Gp$oFz5Ei4jzq_01>;b2ie4BBDVg30v7?xMg_RlJl?ms;NYy zr}G)z*5{SkVGix@Gb*oNNFOs15YrI`*a&q_NrUdjlRFrbi~NgKtBSpQ+6a0Co478o zMwBDFO#$)HHdh7S=#vUOY%|+f1~*;**{~9diIf~;Ed=`M8ee#rG+bM59)o?=D|tDD zvEZ=F1jE{cT7EIy8A!1v2F4QzMdBuhl&=%u5|^4XU7MONN#=!OIC=W9z;HZg}UuY8k=?tN9nzTXaHbU zeqS~ABSC7y{|4CGHfRDY9f6O(9Tw|Z5~IdwaX6>OF1`Q&EYt<;arnv>Zw44^mQ@Li7rlYoT{;_|dASnW_qqVV{m? zri_{g)f4!U46SnLQ35ruuytKHk<*`D8~@B zPH}$e9+oXf%dMU$(UQfuOl!SA*2?qz(k-Ly8P5w@4Bk+`#?pLTEQ1s75XP?k42%## zSF!2#Ye-^TN|*QWr^nQxe2B7aJR`gV{&@|U?%aYk={j#VN^po=N7R=GCFSoZ z9p>N!iJ@rCZ*M)D1@Uy{1W~Ajzejg@|5}gjdPIkItGcO1 z8S;XxXTSMTgQF^Z>{o|H&Il_XeBt1T^r?>vrlb@|4EhOUBMdU=fdsucsjl)dE>CA! zG{+$rGzb+a6YO*)>m;a%f%DTemY*rXEbkvf|C_Fdsf_AZ+Rt&j0Bx5KMG6d|YOIX^ zGBRAdzl<5Y@jZTo`UYXu#^hW(?jD_vH@m>xK*ly|cM~8al z1N*0+xO3%+R&dM#(waFDO^Ct)DQB=+O|Dxbs5k zpIcO?-JS_j-#)Vv$UiQnFa?-+a2wmES=~4N0+6#d(LS~|QaR-;0n6XkGzJhof+y9z z?zI6E!YeC^;Tu}I6yqY_a4e;#%Z!HO8t?z>kk9l7i1(HRDYCYSF|m>`dd%pm5VIK& zi~9wdw%@pbYkE=nc^pV-qU~v0pQ=h;#H?n+163-A6h}*sv*HdQ1h;*?AyYN;g3bTR zH@L36l(x+La8khmI1i zP0a8WlF#^TxH1qKjnELi3bvz5E?qhx0gygN7yi$20^3ARPT6#itRl+{Sn(+bsjsmM z(4lEiP!DkVL@6geT;BBugEJcl9c~Fz)SlK z6G&N0k#CavAtOwzEyzJOKdP@y*_Tt)m0&>{!N!}Nt{~Q^WSy6 zO=}1D!1uFZ43poqe_nDFW#PyFT%(L2z+mBRlMjjstRq%SYw73<1pHZJG0{%*Ylc{{ zypo*#amN`*_T!=kMs5MK)^BoI`C}b3xQIPxC%4 zeD2o{^G}(#tZj0U=5ophKzJmTv-Q$~iT=fuX&6Z5Kf*JR6CmvL^YXhYO)rD7EN&~Z zv|=RyYWt2*#55leZOo2C5*3`GZqOtt&6-t;FyR%!?z$2S)0=d+S5UXHbN?C0tcQjrntf0MR zl^w9k(g+CY(ekkme)H~02^$Y2lizi(n@vu^qE*Z^x&^d6i>IM$turLL)??KX0rAu; zN=RK2-GqkDx{|02D^Y>$v2kAOF_MiT1sn-q(_9VCWLe4iel4CgGn*pxIxy9SET2zF zTRs9T#ZI+Ye|V1^nCD_|v5M@-l&b@RIFTV2h`V=p?XZQZj!qF~e(!NCmT}kOt$x}Z zSsj~2m~+fnD{j_T#a$Ybau@B}=&uQBI8J#RCfN7 zp6D<+90D+Q)XB9WV>iL*(6cSX_H8T^+xX0vDsudD9v-y~YB>^#V`LDQ^r(iZKWVfc z8QM^{-tnb`4fOP_wh6c3*}S%>}05pRrNX1Ad{#I%8JUeRaOY+ny?i2dCB1;CCZf zBNjX8AvQ^;!e4Q0#&FNdINn;POo&iPz%?TW`7he7-=M|TdJ7p{!(oQvEl;y`-)3d` zODy6O!+i^XxKjbw3d&es4$t9Nh;XEa{-tZz4E4nxfM9sAKjtpCdNyL^T4vuoP&G!Y zwtWnaO#vX)Csw>`!QJYtEjCO4ywbI65LY)6NoRf|aoKxFS{iVaX3-*>&355Ctm0y{ zFy3Fw&_V>2D+vBGLe{O`%|&Bd{SXxtzivctIC$T85*Xv)n>}QI^s~@dZVF1NLLJsgIzpFc))%L;29s6dlYE zBrFYm1n?qS;~Qy-?til1LzVf&ZVjeljV8|TXB}D_w2axfkR<|c<>fy2sKKm`Xt=#A z5okaLogM5eF+Vwmd*2p`MWjs7)+ddd=LBO3%Y`Lyjanv}3v0@-tn6AV@d5Q==WM0z zfTGj6YT-c+ySVQ${hLMLbwoAS4}D&ZZBY0EAI+xwAdy=-?GjaJx=0G<$X9y^0(|R^ zvsvm_GRCs`yJ9+Cr(waOqg?M?h5Z|Dq+5;ewoDvfQM`ymdu@cRgGd4UA0iPT%1OBy z2O)6os%Wkj4-7*4m7+YCX5^Q%UW26ykORPFPGKSPXOGyko%ulp$usSM&I47kP{baQ z+h7XQKe0n9iVcX=_tDyVae0V2WOWsQCY`xoWKCnN4XG}BmT>X?hORi z7CeTt)26=J%>7jt$q-csThYg|36V?OJA8O^O04xHIyJH4L*%D^%BdK}=b>;W7X0aE zfLWTmDbMtEr?}qNdvS6P_O;NFGaW+%?vT^_h*k6>q6`sLsD*=^0@(PtmphQ<>9uV- zNm2&|-v_WqBc|cGL~`?O!hi>Iku|FLYCJFl#fb=naAt=nacOVIk~e6y4z8xV*oC+) z=~rPq$*}b>MMK+Q^SW{I%0yv@y6hs21&~CE!&*}nHvSo%l=^^mt zHoCkk|Lju(O4a^90yGwOO8L{R50ZIwyir=W#?AMEU#b9WV$ha(GS-e?@_7hq>=ZFP z58Ts(3Qh~vgOMW3B9eR=Q(<&|oCux$kX%k$ZTv~TdS~>#!!6I*SriDtL>ox)p~U#+ zH-flLBSyF*|3GazF5GBVsowW&r_6c#AVsJ*_mqla0W5B5Cs7iUpGL zlK{fh{#Le`4mn5gd$*3R?J!7m;B3N0jylP=ud$*`LCUWeA%?tnkmgEq`=*Do|MG66 zU#Fe6=$-}E9s!|2nQeHf?G_&H970qleFlPW zv(!XEe66r(;b!Jpt>YBJ_!g4d6-+hl4BLh#l9d}I|Cy*s#;L(c=a0k zVTH&`Eyj6C3Hv_Zvn3|=Ap7{pMK#3RI{Wpu;E<|>@uY9IFU0^;g0HJ*<=~Z96Xv=` z;X1&Gfn6o^R&KAP@bHSq+6++>24#xN-XQI#APizD{ezYv%&(jZk}(S_))&B_$ZV%P|% zhhw?nm4U7mSOSg`XJtHn|C$P=RUWk_g3qgA;^1#A5sgV(Ktlcs?*j_ZaL?}PZ_6$v z)#O=N?7;oBhfh+J?S8DVM;#nS|^> zC%RkCsnC^>0R3J7E~Fq;zyLN@&qIk^(=0Q0^UVC|0MKr>IV0sy5vS_Ij>*mxr?&!X zr0?Y|khIra*-1BaxCukH3*&aX!34SAT8qS7tya}9kR_-x{zUmf^OxDEm>%)1LF<8K zpK|!M{lKpKD-cVVeUYX*+~yg08GHWBysE@jz-YW__YDL;OjJq85G_kIYWozFsjrok z`sIP3@~kGoEG=}ZF0(4FlK1xIk`uuV#Y^_g`*_z~{kd{I-{Z>CXQ=xvw8FCju)7 zP|C!jOLg4UvgH~7q)wUCIGxzr#7&YCN*556J-ND{Ord96XcVD zJ*W)c#BnQ*L7LRzJ*g0j3F51OGnY{W@IRD(s!$oiwI{OfK{OZHfDYS~0VeWa?n#kV zBLe|-F{Jn)dIf;`%J`mNGJ6Yyq@Oa=eJvNo0OpV({!2N{ziZ# zCkZ5K>1WSR(Df({Xt)@+4>JFgGif33pLtH$KGEG(R}13#n1>HY|CfWp8{vpIFG{Y9 zm~*;kX(r34x5tnvlDr(yG0dGvd()uKZ(X{&nh|Jlaf_dK->gg3>``dwG}mATN7|rJ zMhYQ_W}4g{G-T4T4n5p-xG;~>6mw;RhQ8XpxW17_Ph*j6V4)03E;i%dG`nKAMsffj z8R#;>P6)p(DwOkI!C!p4=B!)Jj&{6+?)=|=#>y+R*?zMX%p}xbP#M73ucow*pFxIk zt)?+~**aduwNy7ISAadSvBw1qkB9)Dk8Sep_tG@h%J!UV&Ce)q+IL%`anz(!qR^Z2 zTM19{L~w7Aojj~g0shh^xB4RYJPQjSI76IzEc;NgCfdMFF&``Q(nn3N3yaytRuIED zo@QB=<83mZ%yVhZvC7nf5`AIv;1ys5Vt~VEc$+{_OMV><`<81AoKa5 zqM6~DQT)oWI>5c9Zkn3Sx9L+N{iLOP@TO)wg#+lUPnUmRWq4OyNS!x#u*ZF5eVmt% zstD(;^&Igq@cPwy@^ul~?1(1Thp?W90} zQ%IYuQkF15YO0DLAlWv}bSmsY+ZQj%9^EV~clH$?6rbTT8vCpSytXm#`l6jM^p;Twy@a?Er30Mw5M77Tab2!LSwP`oegjn2ANlO6y2k zeEFa%5Pum>L8tqwg=OeJeT74Zw4|f-D<+N#WhXv1H4wjJDTm$x5V)olgJ)t_xUQn^ zXx@F1pG=lderg?^ml_wDd)T>#t7NW|2<#=iGXmUCF+CqjE?JJkVZFoGto+uL&9V6t z=-A6}s3y>Jl=|P&>#Qh4y_HP4{ z*^-^1P(k`Pp0Xzm>gB}3aWkq9yGobUjTGpn{&D>(Do^bmLU=D3o=5_|3}(b-9@uU9 zDhgu!7pztu2{q?&cVE*;$Sm>!!bLebk&&xypY=$Gx?V8#5)6<1;ILr4BgR*3B@;S; zvxGNz|uE0(_;8>ou?qJc-;5Ai0kAV(cuYmj9JD4SR+z1Be zf37J#4X7mb;JNN-@3wnl)=Sywi5b>4?YLorwh3y+$>N^36)R*ACKXJzWt5mT zO1OmSERpLYfV$q-;4MFuX}3_j&XD)|GtNjy^hI@NiHaC1Db$-{Qt--$@wa^k0^6F* z9vI!f77socOac}WWO$Is8w2es`Da&VCZOThOICVZD>Ssu7FFt{IiKNV#W+^WU8J;% z2lh~;^6QYs&g!uPs1^Zp)z19HE9hNA?78j?IBI6tv`2FvUziM(jP3h$ z`$4u!S4~IviJSOsxhs^+P2!d;UiWnfWvbP`mLoiQ1 zNQ|Qu!FDp$EVI;jKe8S24?gZ*^g{#h@&&83nm$XqDq>rMuRll%TsH1=)o8d=vP}=Z zMFWggbkG*8D|pOpQ97=5ngj{%*hDvZBe9aV5uf{D#~jA~bPEaUt0RI^{Tho{8o#;n z{v^+3rveNQ{HBdpCK=*%7`zv|a|!4Y^z9G18nz`Ow{^CY_R2Rrq6Xow^^F#%*#(*^ zy15W7U6uE=0-o1%rFdjJfgo7!J=Goa$Skiw88|J`@tbPRNCT zLnF59{6IX2StF`NF;-GP@!a3fETJOvKVAt%3zp%h^(F8eq8YbMQe{#46y^)vF+I3r z4ZR;^S0b<>gu3erxG>Xmwngpqx?dxPIs{UsJZLXp3QI=}m5m3S^@g{}s(`3lVe;@j z2T0a4)9p4z6Nl+wK9Yh7j*5lh4*pe|wqI5+Comqq2a?N;EchK2vWU$U zp6{7+5g&v<8Q-Ntr6@|M&75y|n99f1C*iI&>u&nUMlnB?@)P zKhxE7X#?4FSuZ5SNiVz^AXTj#?m%U#9CDWu!lidn>rI)jr1RCBF?Wn_>s#e*-zCeo; zdC&cl{eb~#2H|^jm@!iGhZfPfB>r7xhBfTTa7n+Ew&NC$iX!5otjxpd2Bhq~BFc1r z2P;h4{e?jGhA3}jv_uQ2#%ZId7w}@c)@a84_!;_(?C;X2WBr;AGdWi}^dR+WZd1X@ zfU8J8%9#c8YYZ1M=tvThK~Fn5Sf7R3N}*MXW|^g0WiNKlvmcX?LVC;`i@#je0mv?% z4q*7o$9e=4fUhu^T}7w*anQqu&Bo7svjG9g%`!ZqQf_Mz^iRqT44}{!se6@VG}{Xi z+4CYFjaiwXxMX-?SPwpPje;gDfiHzB3-f(xR5<{%O~G3XeC8ep|97;!ftwqpE~Ius zOPuR!LaehEKV2tm^t!bKYEJ4w=L8$xEC34K0mK5ryY&OjBrw=JQAm((kI(}v9-u3{-U zKZgt_`^SXY(eUgw^=zqnkG>t#tD4b&25!gwD+jD~fM&hO z7bUh7qJr4CIk)o-K)`eX4tDd=GynjkNd#Kpc#AdXaNnl@(4x<;@6Aac25ZRjG_fE* zP=|Y!dz*3_Sg#A>ZPZi$VA^U1XfU)&T%VL_{|7=fJ$t1jB%^Klx#S5Jpj22MX5!FL zIjwq0f#-=O=#yyvX-ERSj=42JPwM4>i6hzo5K*x7)f;KWhCXy-P4haho}lOR?|SbN za=q!}@7C@Du5ddC`{)k(y+`3{ z1&a-!&UbyauI1;6U)ALRj;eCst*7$q68?H3n0-Sx+lw`E7XoX8Ro6GNviI9=Qm0D4 z))gH(Xlf<2y;;1Cmk3VR{WS?L8bpJT^I*6jP{{vsTw!w_v+eefYf9G4SMvIz2^ zVc}@^n*EIcRSZ{+CqE4zT(iF16L5`AT~oY{;kZ@`4%qADJseEK+eA+;1_|p<6cYKI zwDB=`9nmy6NQ_DGjo7UfMh_^iMCU1pRexm8vm}z9-WYsnWrQU`w1P zlTw?+!u~7S<bfl-hbU7$11 z-G|b0eFFoxxu0F9`|fHOoFb1klv>$?vm0#DC^DPCD)d$+^_5o1J>quq^*0D5+$*zY zl48bZhn3GP>sMH1k^nvcXUxY^ss$@}@26qB7ZleCddAzp*QEq^4TXKWTLR&fHsK?? z^|#;tE;Usr9mKFdo(UIF%*`BSGq7jT5(7?9xCy%NxPUM*9szj!cq5v3ZY!bxv?V>V z4q>(q=@u!&xiLqt48#Ko$+xtf{c&tD^!Br8W*%`!fCP@^&QW|k39tSSlFB=K0XmTT zNHZ;1tk2MmeKrmX=gobqe2U?PsqiS~-GzY_z&3!cKF077cxKaFG_)^U8g&}I-faLv z(Kkh(X#1Zqzo_)B-jIm5E6JagJU>F9PlQ^(^!!S4QSUJCp8Q0 za5u0F%g(h&@z-$W+)E8TCyLoi*o38rDps{OByj=;$w$WIMF2C;mf#-WN8^vIj9iOfdPeuSd zM6DG@*(<;H@_D@e++Jk1vps2!$SagIv@JoBia{6fZ?*T-cMb{k%nV(`7eBEu9vd8L z@P~J$++=TGdNx8%HKkv<%#uE|rR1;AGqoC?GW)IqlO+g9Z?px~UGudhYyM*kD05UF z_4pRGIQ$&+R5uU0bTpA}?TC`eqvH^50&|(XK!YZZ$>;ML;){fYb{S+VWY}taa;HDU zvf+rrFb&xJY`?B=swFCwUdYap=9Q?&4YA{ZK3O&AyLErWk!dLm|939`ZlF6;**gV6 zZ%Jz-R%YB77v>I$bayeQJ?7)9);cdx^qxq&8M7hFCeg%wlU?*La z;_ak0 z=wF$e5(b)+w{QIp#m3BXP(SpO=hBUf7jw<#Nq>F7-xc8n^jMz)j+SMbz_ndvQ-2dz`r)+`493a+oA9c#3wRs>G zJ=tL?Ww^QO_VqoI>8TdQ~ymw^XoJ5b&W%}3En0yetSk+f$;eE>)vPA zBM}B&g315K{oSZ@LJT~F17QroFJM3rhe(VB%`oI|4p*~dIK%HZ#iQY~O|fe70@gY0 ze)IWuoBiG%h1is2Mzrce$V55HOHA^S(p+JlC-U~DAA-feByO08dC5vLL#t0OuSMZS zQ*L`EH;@@YOr#q?uh!a>oZv-JD&5&m1n299P51pnRqOTR5n^Se`{Mm`KR#YIfZR*^ zx=6tkntGuIZ0XF)a7F^K=ZTrISOK5u>B0f{;p~T&AbWFQCG8vF7w?mS5;gt~NlXtpP zaCfIS^v~<0->!uWrBH!0IW`pmaoC|iKfVM_)xP2}eNJa!s=io4M>J={2}8(?2D3^C zzY;*;iV5n9gak(a6JYrDUOMafc5lUoy09Vk&-YJ>=c0%`ORE5>RQp-ck~wXn>;Zmu zxH)Wh{L9#0&HbjFD-h+=ctq@szx)>FVf(6mBlbXiE@!9=T4KB*tSCWbZOxB6vS5n#!`MQ5%B|FiUE0(t z(PNnCa>{#hll0CqaL4CTq$u5i+}2>aALlGpOdcp}7 zRW24Qv0XQJCH1fGp4O&*1}xvU&Bt$h$o ziz476)HsP|6wSRVy3T=jM=0C`>HjA>(TD{p&7_pc+NP`Pi!eY(^TsRP2-EwgP#aa&TcELtUKmfeCsh1%0(yh4PX9^B>zTE zIm6C^M<}u&`c%R~)eSbllrm3Bi+h*z*t~3D+_W{4h{tGkbeH=kw?14#iXbbh$3cJ={#56 zgRyxzOAnMf>&quq*INg*TVJbphbqbKUx!GBX@nI=JjOf`-xyS0m3TW((S)|>t?ijK zR?H#!X}?_jg!z3;Q!jW&sY)8gg_Wq24%(w4ef2CLR7Zv*c5qF;QxqfWK{02Kc|XS= zuHCIpJY~UI@FNO*=k*kWX9z}tegJ_w?nKO0$_L)azF_{Dmek-OOlJB6cuD0pVa#fe z(6bTHP^nuU`gqa^XsW(i9wNh{>KQo0>~k|SL?#2Phh~Cr=H^XaBZfjw4O=-z(My!< zw#)>yqA>5zhYcmW0rGF~e>dUDc6|WX18YcaPv6GD+fj4nMi*|!wfpDC`6olv{Qcs- z;hVMs^*>z3^e^(xmVWN(U_0fCMI823uM+L z;_P+6`oS@(LI__tL+XcaP}l5?Fz{6dLxDG&W#@X=44CKlkO#H~Gv__P+|4?w`TNiwBs_nVGNZ&xEOp=Gtvvu?4*v zR3)iR@C>DRDIkohw47P1K2dfpqKMf(##hFOZ(Ahv`r z@VbfDP)TWTHqK?=88lPpD?L3da5siQKbg_{IL%5DKCVJX*lOQFxV==?x7`$ssQa}z zftxU%7__o|u1(AtZ8}@7f2rTPlfdn-IbEao=YKrT092Pz8Gcd{Pr5+MrH{r~K&{YZTzX-~TjGdoI zB4FzI{xmeaw{Xop9i`5Zdfbzdq?sz0Z_fnl8G+{;0}+fDrw%TsVVTJ3>iV9MAlE~T zLtN54cJX0!FI)=#mCq6R?r_woUiM*uR95?mbV>iDCRYWsz$tMzJwCh@{MiM zCt`9gvTS!k<|j0d^qIBzhrWVFNhYq5O?=)*(6Opf(F|}bt9898M5BtHD>4pD_-(;` z^;O2u?T})hliL9HJEN0~hw)tu3biwouMNiSfX3zFX-<$;pBr@a52~Qt2ghm_bOQn@ z7P(e$nK70w2@pMaB@+*{lNle;34jtdYsO)nqz+s43a&6*dsH9yU1wa*eqtgyeYA2; zB|J+n=X(=xzQV!L&ICJmp{6koS)@Dslft|P@b%cFLk6qG%0m8E_AD^2rTzpsaWTj} zRK-S5|D`wcPS^s1v_CGzY>nZxhCrO}icQ{2Hly_=P^svUeqXFh1sgf@y`%M3pqp3( zsz-#~riWCyt<~YyJTzS?altVeEw9qFZ;v}O2oZb)GPQij2!#K=Ey?^Rsb^4JS638% z!#;5csoN$CI(iH|ayoUzUG|8VQuvpZ)wC~rH-Vd&E<4@Z5&IE3?`Rd`AOePZ`EKy8 zj#J_FIqg+X%CH0@Kt6WHzWjK0$A?oaVWC`U!fU17(D;$q#sZz!T}=ui!pfU1Vvo!^ zuzFAUWgD(TC$^2^gXC2NoIQZ1xMG_L9lGGVlh3A&(9`v;Zy}OVQ)i0G7=ZQO-8?``YtFqIoT;OEbhGipQO^Bsk41n5BqIajmS;ARU?9ar-N*5_s7 z>7cJyh~Ko<{dFVAWa0`mycIpvbH@KY+MW+%<1cY~%AayYkTb*K9;oZmjML3Ufjcu_0g$l;W5mYOzkxRAsnzv(1WmtK8 zY9oC$Xuuy1nz->LfdQL;s7=+FKh2@Mh#rD?-rdZrksuPE!7|0$X?0`LiofRG!6Z!o zziKx5bXY-zd`7M&am2<}|5U6mGfbNH;fRI}_O&64KK2b*WyuVcGR32Y<+^@uxkhUT zJq^%_gcuEh9&5V2)o#Z1t358uBJU^5iCTH8k8j6|Jm*B-j4-e`^|VbI1Nc>tk>Zhq zK!XHmldl2-KeDY4cs(4!4_cE<##W$*v;-f!gixPBV!uKh*frcvTVulxdPFd78ycP@ z%*@aRm}Nl;ivC1=0T zt6W-9C|!&kXaN8>3q+Qo7%NQxBVR@HpERJJ3kD4)lv{Dk2^nZ?1V^_pcP#8+yT#G`^Ne6LdE2ygnbR8B_$++ zCT%^3St(E#n7PzhHFbc*$@le3OxI9Oo2~n6CTxwcGa))E^{*_;>|G=q6nFM2zH?Xz z!?|%E#=j)V!nRxHE4cbHf%haU14gF2SGqBOdA0=j+4ci_TOi1nxtvCzmKaEA&%H<( zu4S=rIKRu>F~(gDm%?#=1yI7qMYZ~>9uvQ)oWx`??>C>7Ff4pmJ`T61q;b~^@oAWO zqo24c`inXD3)x-hOaK6%-DRFh_frqw^KpMds^h1sS}p0v;*oA>UC^dTp4i>vdB6JH z9zrfoHPaknPC_F*`=E_FhcyPL+mr{8O72No)p)B14cudYxvZ_-&J8Xl?yd|iC zCk`!<8vXt9$Fb+;$(qMqdg~3Yo^>eTY`J0t{ZUj=9w%z1?|>}GX8HRP2P_>%+M+pu zrQ)yJT`p8mUxo)l<^+={Pmoh=4i_tGN#0OX77!S-WJGS02Waf698O5h;y!1&nQTWs zNF9L{D=|EjEh6YuNUQB`nd~n8rc%EnRmX)nFu)9P24Yv!j3m=Tb-5}QRA_KeFxZ;& zULKyjgTyUF$ba8X#(soOE(C3&+^00H8W4h zDsO))NnfPXCuY|}4_*;0Ua(Z&{yH5|A)NDK8%XD5wiMC(mKV&ChJk5h75j!}ey zQUv0k*@{$a=~}*@R46wAN6$S4DyP*S7%{y-*!R6PhAgGpW!1&11$1wlOuBYTrd35G zTWSkwB+EpQ8DQLuF}9#WPVfOBmyO&k(!>XMqE2l`3XDyc1A9miUud>>%99PqTJx1xD zfUmYmpAR?1rh_rrz0sI~th$QI;r7te0S9 z{8Q#4CpXA%(911G4pXZs7 zOYqfrZ8ah}pJ`8D*YKYn)cbPj1C$MWNJvo)Smhq%{z=}r{j3tLg2<(Dq5+>B7nqOY z!9-!}1$kK+{w_{R|^WXd)n3qOZvj`ZmL{0pobWcI089-yisO#R%J4k# z4hc;{J8N^n2jzpYIK$HvUdUOXiAgc{x^0-OlXBDr9nJg3h^;avc8l9F_}0PQu7bxA zHvDS?)P`+p-XcO62T3a)N5Smk9eElNn@6lU1Y9UIQl52wtHn-BgXPpHg$~!86#iBw z6N*;hLjQE%4BHFfbI>bXeAUG7!&OlhiXUUw--QtbF_ug%p0V$6Y}rhugQqmf1`~=v z5Qwh z@w(`5kS^>2%x^T_kV+}Xsacd&8hDXxL7P#C7G{&WR$Qh*OH~I+ZObW!=YLDg$*ag* zL;1HFbX9;V`a0^KS@QZahu)-WGVPqp2d%G3*B!jo!1E~cKmNQ8w84IZ&1OIZzZgh}MWVqN)X$agQ zHtKL?nb6^L!YOcZCH~@mfil2+^{6m9{I<~&b(2f%8cKv~Kj{Q9 zplbOej^<8uYR>2-F~2m^tcPP!c8NmOkCD=&6%1Z)$t{@PF$0A-$dpv;dHS95oZ%~j zGPeICP7+|=%|Rq}0u7r8KIp->un+U(81AiV{(4xQDdf7NOaX z8l1M^B^Q=?MtYkAA1tZV5S5sGk2X$zsaDp@Ux#fJ^bgJu)hD>uIJB|8*r~P4dX@in zA`~MUfn}}I)11zIb~^1jOMb%D6=6JYp6`HKhDGrf#(^7Q&u-B(54s%Fps!#i4$+lu zo_!zJIG_$HAgMi}1)n-d2HaB^TO;+2B=}rNm0UJ84CW7?J|p7{L+4|Hf-Wbcr(uE@ z*kD(tX=}#-Yfl5np0PBI;)M{hJ2*3~*d@e(*ORggTGf-;4QwUFrLo(SrJ@0XQ*Nn^ z5Q0EzY2j1H_YjmL9VG>0}3HY};KK<8K^ye`T#yNdQS=f<^ zj%zEHrv`NhZb#}DJaPP75oEG1GEudaWu z{gyAhThaI=S}_NzgV@FPB!> zq^aFp)2M+CTrC}%Kc@qez&XRj!Bk~d^H1JTgj~&r6w9V;%YexR`-cRg%?+#QI$BF1#ZkMZS!$o0`gh zU99&$n_hzTaV31STEI47*10z@MFM%2!WOesKt(5$nl;kmY7D~(*vSIQyVhAglM-b+ zh@!qLG7O3xq5+4Ovobg=`9qG3chIP3x<3zH7y4(y$Iv9fWSIL&FhvX15%-|eHx&JD zW4Q%^4FTKoeN$i$*H6!X_LaQrj#FfvY*Z$Lp93|Ky-<>sMvuvV@30e~T3tqN6kF^2 zS_WM;l|+A<>zSdVxVi`7igv{nf-C9WWIh0R%?qVgFDDZ(nAIRj&!Z>Uy4_f+;oN)E zWF(=X!_sZCVNt>tp;BAdk#eY&B&a-5IMt5=(%hwfftpQR=6#NjPvt39AX)=4JyJd{ zL26;~a$Bri;^Rqf(w&irgv#ztp{jm+g0r%(H^+Q`It{@L=C3)Pe!j2>i70U4!O-Ji z&tXgdO@0f)#fM6;q9qC@H0XkJdik6%b0$Q<0`wb4FHGu0m%2FDXQ`|D$Fq1Q z8sg~>BhE&@M171cO8g5OXK~Gg99`8|>jW=Iymn`9naCwJfvev#lopr(%rpa|JpoF5 zsVI!5ewQ?EHd9mI{R=9{NG|eTwTJGYHuY^1*8vUR&Cio%@aJ@f!|;Z({eUz1aU> z)luD^M-ZD?r9ZFvj+6`q-1-*ID|NK&W2Pv8wYh(sUh#4Ibl1U@C*gx)jRwc4A7)X2 z!t!fH|7#9~wy7HlkoRPEqfU*gfN;kDRmqkoL$d6&5xTy?)I1Ll*$}l)-pg?5_td zqG$TJk$@Snzb={8Lm80ei^%ra=80zLR@`4HicPyl7fW?58Lz(e?WCaJH7KzGU(fM- z&z`U?lh6n#LaRF`J7oejDbvoTGO`{Y|Gj?I=fxB4wz|w=@~PM3n>Skh4Uz&~b2ojG ztUL8!uyUzH(t6oJR)uJW$d+k;HiDh<;F8&f}g$TbdtGozh44%)vGK9y4L zR%Mx9m8&Z!XwI?9?um!Z!^wuwW?p_qL6*BX{3{Q;>o3RuKQzP$mZx3`y&6_e_ah0A z`2uzQl!p(Y1cQ!}wKV&aFkT5DUXrVZ!_9iOPq^lI>2+`4F8MD-MNI%QjEf27*B zj4c$2I+cpdVAz`9;YjaU9@f%99NDS>a%sq?u@^|&jNx;RGM~{4L2Uqbh3b58SH8Ne z8bF~&bVXR$?89mT+M3uwTH?BMSy(k{4*1I7-QSP+*R7%xc6U2ZDjk8VBC%NTA2yWo zw2V9e;^bVDheExM+2N&y+5<0dnu3-CiWSBrc))0rif`MZACp~?0OgnF#qx@&_=k`} zpv;&HNk9YdG$Z-!9BXd8uetIvZ*V44j|PDGA8ybA^8R|PJ`Y>cQ zWdh$_0I{*pD)3AGVLnoxGl<@(My-1%TRwXzeI`_WG|}mxiM=B@&@Isq-hR#Lw79J8 zsDJ+%4u`NM8|(D3J%m03!Dtitr zHBdvo#rRy7zC`uFCrzLFA2;yejb;Bp6!2$NOTz?j{K{OE`soCg$|%-ui9p2F6Hqc8 z_Coh4|I!<#WM8Y|LP=h!0<0AK(GJpzd7l-#W5!??(!HY0?`nR2ht<((`S6QU|Td8aZt zM5^s29<5`@&b-lfh1v)wkcup#)#6WuKIp+pMN7-yio3qR3&!KK(z8mM+iTVq$s82n zYx?LaKik}|;tDw`>V8?N3I4CALY3zNsDaPMrG7ZCH*VW4qz(1a;bh$mkjHvmHt}I8 zjgLY0BB8w@Hz3D5B&p>5pO@-a;*-;^?QZeV@g@)zu0WJzf!AJ*9%h9hekNYNgU^0R z-rjYfuNm`!qdINx)m~4+32-obscsIv`~1jPjSl*`<{IPL9CYVa-(Bi+MorOq^WDbJ zz8mHSvbT)T6@LOMrt1|AUwXp2XIB3erfl!PT?u*K0p~d!Sqy<0ukCC}O-Ke+d}#NO zXMD?H$!Gh|@ZTVEgVt|AybP_db@tRc_4*&-L6Rnx5{}0JvZ?_IN)GF>EtFdz3Z{Ev zXgluRV4kFg-z|l>S_pLB80HUC9!a1um+u zB>+oTCxmiqZT%&}((#YQa3hrhyEj-9$P%WzIV$R2Os&4$JGi6%lJkF9WYpqbZ)aW zW61Jsf>B;aDUfg$Ao&sWJy6B*I$f#@IaVb7qrR29JPRD}OdF-56CvST%tyC=nigLiCbpgRJmb6Ay1O zQf1!NJ@fYPX-zTDBxsT|Q@oFl8T&z87A7GsUrU(-6FzN<_iao>CeTgtPc&SX8kOnu z_hs>dip!#Bq36qXy)$p3G&hXIctz+SUR=x?J|(oN7=LmUO;2=*bs2p7L{$0JaZ2A3 znwu`M2^9uJZjRQwle_ky^`9@38@z9(FiqHbLR0P`-Fo>J(RrpQgopF9NA}B* zWo2F%z!6cu`XH^#55r-(STYq$w12)#MXY$z7t9mEHxJBZ+LDs2jEwL$w|5HLgN>U*aSD2=PeLH9 z{!sKxNIGZZ`heh1`Fm}iK=(^(<6*eUvnSqka4l>P(7^)b8j4s` z7Ftx^r#}2r2ixMQVo+ovVVM>eh=H}9{RRp5x58yzP<(TJ+&XWur`q7J(|zb00JX=pt=fhWLNrs&H<{Q{ zLf>>^B=M0=E%x6oT3RW$`FFMn#C={?b#<9h4IbG`zuAY|oQW+G8O>jl{@RjVaMj)z zex=X4!yjxNg5@;@gJ*W%e%cHqgmVlcY=~k}h{Q&MJHtl>*p_2^zGO7iN<5gUSl;IWAxW2$eJL^L zBHC$Dslh0&_&<{i09(=K&psHPG8}7zyqJUb#CC_KIF}%NgY+ANwdg!HZ28$jfaOfT z?gGA+T(I}&w;CyYe=Aohe%I>y8A)}a)U)t&o_0{1p}ZXAeQvA~${|{s0OniZ0X(TE zDa}S*N7Q{bKklPO2`c)odQwmj5!UVTo=ppKF=U_!k>Wb()^B;M03DyHAxXL1Fm@#( z+fs62?DM*7t*cUDEVLVk`#nn=ed4+h!qDX9aI)QPRSw9;=JfL3 zXVGaMnj<*wB!k$WCfKvmXNS5*V08MPmZLM`rjou=Sf|w)(~{D2Y$rro2|{C=omlUK z{f^6|cYU89d@kGd<`7wBU%?7=VtuMZrtmw@g8t*8I@f~$4G9M$UKFj{3^|>TN{is8 zlcgjyFKyR(!t<#36WC>)LkJxwif+E6_xC|*oSpB!GRZqO7aEg( zIfl}XKdO{$Xp}q5Z&AJ9CY-?5dma(UG<0uWr~;h@T}KYMO?{Ln0&i)Y3BU2$6)hbQeCxdn zmMfCgzRmj&I`g%LFGT&w&l(7{i7~7!1)f+fYyC9~3@Q}TWX%bs;j2>LRR2{l$DDOU zSD1^;d$5N0GG7oi&m(?bUU2I;4p<(6IuMfp^CqOaj}0RX(ka4_HgC_Yjr?-@z%t~L&qht!8WO8Qrcz*6DKUC>C`#O(!#>pv5^Qug#tyA z?x14C&xfe!pd@uYd9Z17Wj`I!Za$HlQ@+*HxTy1MtUSi+f^~j;Y>|sQAI0+kUjQ@w zTT;dMEoVZtI)bT;!>*2lB%`#>y1v9JF7f;%FtCU2H^X69?X=TQZ&1TWnUGC9lp+9J zn16X(hrpIcJ3^K3%Tu`&#nWQibW|es9LcVOAZtkuc|}92&F9Y}l2FI01+udQ`%4$p%9{w#A4{i2ohM3~Z{fxUT~8x5Pre)J56)gD#I9 z@Yg)eIUdD#^>3>Hw*Ck{WTroi-+EFSzq-b4{uN;e5Pl{VkNFljt=z_4<~efQWM297 zLld|XdxydO@^fI|TzsDcmYRs(uD1q3X>Yap;aG^+_26KYVWIaMP3^jxzht<#IiMRN&k2nDh4t z3fv&U7Niu*RF)|0ht9c%D*KSgH6X5KYyu$<830O^E_cLbC*Aof;`Q!Dii?cP z^fw6}g(nf}g`p*nh3DG#NURpP)n|6JZ>4!^yBjv4kVdGqdi>=F_!#Ao_&b$Iyvr9; z1*zkQ-%HY;bXP;kczi=qfhJ^sGloWq2rsp#LNR^ySS&mP&Z%tJsv{(GEE9R+Rr9Yf z8q33gKn4E#t1;*#{aB;i96KJkHCIxtk`Hxlgt-oZwDY2TpTYtz_oV%+z29#~vwVQk zMSC(KXWUew76lj~GAd7#Pc=qOj)wes!HXbNh=UMk5|WbU+u+wZ5f1`^MzVBZv%4cI z1jox<$;;p$uBl1vea5o45{T4kD6b@Z637MO!9(u-^Y?U&$l6A%`rgCXG6(fEoRd!Y`rt@tNp4bo_E8eoOAs>Hm9_`qC;XxqM8_KG}# z(cwudBu0T6Zc52fU^vy-r(-aIO_}lFcy7!t;0`Cw8^N9+o(rG=00RI31g_9b(G-rB zM?B9sYqL0l;pzv2pms^#%2SLzKrTF2Z$W}R{e})wa$3=-!m3hLI*`4QsW_so3s$PC z5th>9DnFENU$KP7&ZsiaGkVr9S;D{>*7L`hycV;|0k#v{`p-MnkC;PN%*laofinX= zVp&CDnCX;x1ftIL>KdFNAwq{i7!iqoa@~johcJi&>LKi{#9D-3S?$jfB4`p8lvQ&S zU^kJN6l)0^Xi3=uOAi$YNLf)LlK#`-))qoC-H;~ga|5Kkb-Rw}iClXnmO%a0*MFdy zqbho_OGE1G#U9B5lBoS}_54S@$HxA{A4mNEd>v|5pWx9)ZLhcF0^Zqu(pTQF@$&WA zQS8ciZu*AXRHmQH$*hdQ6x;#4VjY?n6i1jLB~RTh-KK{8!)e%p^;;MH5_xM3&iCSN z3eu2MMiZqHv2&r2I6-XQfgTQp5+e<}-T1|Ak3knfJ$1g-YZ9^2&iF^_we>F#yohl_ zSE*xDfGDh=o{uX=%K5*y^5PY6mxW~7ft3y_{-VaWnU}ZhUx(<)& zv9+ag_K{~hEaDHUsA=lcF19WorE&I5Z7K}fbII$ACwF#yXDw@+W%z18=DIoqZj{QG z-OJ4TaqZWNGG9*dmL;+UB9`nwg~_k4;IDkTwHq+L#4f@SM1XuwM@9)$c)mh|u!ar# zHjoQCkn(T>0T4J_ou4Q`7%AU*oB#{DXl}-7Y%-=FJoMGBQ(ioWbSJd7MdDScrhGA| z_8kl~K@_r-d(!beNyK$+7oY7;lPyC4e;LtLQ3truAy|%=1yCCF#tSl2x_l3{C@99h zTIGS(__C(Dml7M+<5VKUUfW%gXGSdQ55z$DMkoatQo&>x&AClBOY(Q#Ef%LhOBo2-dm4|N8s-@^Rz65xq4r0d@$-9iAs$8Wi25(6rqqbS)$s%n`8VyYb z-xLGCXD=g?(SPNetG0)0#(d|=V>qwai^yK@{pGucYD7O~F3K7;w4$bJmIhGgO*nMr zwrwRx&(@`3SCkPqI^Q*nZv$(*lmK3Cg&=wcd&;5nC6VdtM22cDuTb*HwW(#N7E z({H-xd}_I`(b*dS?=Uqd3Cxo4r<|iZg%^y>GzTU*u=w^NW)mqCwa5-?mlJNbdqd?u z&whlp-T#CCp#nJaXgupiPDRk;ecpc}s6KxVVG3WpQ3%Qsv5x>3X2`nn&|^FU0!qoH zv}r6s+&nM2V(Pm)4eKP6D=KV#6v;{1%Kcf<{@)RY*6vxAtzCD8CR=o0MvA*GOEL0% z6&CdVSKH0;yB+vP^0BuIo(4bv0|owrHGvSz(0IA-UwyrO@ORXXhcThFb6QYhLi$H(ew_HJvf32J5|!{$w5u zl;a>a3TSu*oP~TFtq;h`w?@CKGB>}x*iQ40KU=s{;rhVk}9#0U9W>5w(#q#?W13f6=OBF z+8ju_53tG)Ey$R=9BSc_)oI{atk&LB4W}(24~x3`UL_9UdpP-(pH6O{v&%rc zb=BDcG#W&>`hG>=zFiRxXkQ0RxUXvo-TSig+;sB*trl5};_m+d6-n4#pqEt+85z|K z7vj`K=~kLSoFL-G7L9vFiYo#L_`urxs=Hu@`Wuio$B6?`>u$gr+l-9A(ZPqj`ga z7hJKQB-LmRozhln-^-9;b~9JbMpnG=t~}uBvb=YoLH7B90ctkKPn z`sFNeK#&mktPFjTW}0Qd5!SkwOgRgw{t0JzFWvVYspBEvi5-MqOL}?^fuS`5!f40p z5OsA zPOh8#4mWO;P5HjJ4MyNqgClX%q~A#a8QY^OTsHle%BOS0ao$d7HZT)$zIX_ z4ye`FTU`io2Z;}3{Lgokqi<_sO3~cANLIQRm*hDn}G)Cxx1Tb)Ho#`eYb5q&`BoqICnei2LjVSv+iAo0pF1B-?K#O1Li94c2s%XK4~S^|u{XqEqHkN(my}m|k*glK-d; z1CsCJmL~HRFgT+A{ktI7xg-ru^SKQ2C8I$zr<5a-Je%56NEYKf0!pmU@j6u|4e1#9 z<#`=5@0vz&AvBYFDbaI8wrOX!ZryF6V#|-9oG*?bprak^tp* zu{A5ogtak3yG2&CHvj&8V`WdtBv`XcwQVaW1s7|zFv)3nq4&nVk@J9@5i*LmiN?hH z!EQd+LD|u;bgL*~1w-k-Y@~M`IZF{Fb4{%tLw^&hUVTgEQM&Cd*Je-Uj^C4(XR@fkiZGbj8;^ zYV&KlMirEBfMd8iys%sCmPgYh`1+>^*D?}2-|>Se0@so2lW_A&!9W%brf)&4Y=Cv* z(Qr`)zT(qV;Q>>~<3IUeKUW|PYQ61l$px(R&-TmUjMPcywzeFU8pMs9kGTE@Cc8nzn==dYhBYoB!l3@zw zkNmA=fI8jJPgb~BpA+kj)13_B@bT<0)F!jVTC0!%^`|w;s-)s-@=^n}3}NymU0_`a z_VC#N)~pP4x_{x1cw0*0^nI!Y&DDU*VqJ>g=RHs z>MU{22W5nF?8;~@+M53#o}43Dg0&Bw@$6e?xysY!>u<9aAPt)=A?O8ud6O08ISHKWJX^WA{G6e(@z3#_xA)6CV46DLk$jV9R?iDfl6 zNqNjEO|1n3{G3y&mXop22biFem~y3`5L|M&rOL_nxw{wsJM8$Q6}p&}i_Z@D=+8en zycgP)1&(gAoc#E#L{w6PD2p!D9;X;6p_{qVeP3;X`fNji(w5n6$GwHpD$?W4VMZ;& z?hiM4Eu^$XgQcZuCK=mhpwYB&>FE66L|ZpBgk>`-rL{%WejPrkuBLXE0rsWSaCRSk zot=41-^CdRh}*z=tWqC**4T@u_8{hh;!gO)PLCV}M7{J-E2>DVe;obh z;f-de91*;2m?{5-Lg}bdm@LVv?I;CCn2Ge%9L!>B8@IbIt~P>CsdL-v#CD1dFlb$) zN<8{yDd+@y`?9T;<)@-s({IFQPuorF|(LBuwP51 z{zK>8j-P(k*Tlp^r%pZBaez}hb;I*a_QXX;jsRd!A-95MLmM@d*$arLBJ5)oBo4+T zKapqyz1_S8EeC+GZAxx`8@NA5aNerrCXyo8oUqL6W^D?R?#Mzg@eAiQI(M@sxr%n< z(P_h!c+dtZ?6VrhAIbotg4txpyGyb4^OC<07J#4zPB|L5q7?34f+u+*Jaj$YvLten zUX4C|08zRCBab#xin%zG@+s{Qj(5S+oET*nf109w5RermfhE{K4|06pk;$VP?CK-`uXtKz+`{FzGj55}0`c#Fe5-{%1*x z$yk2eF7acERfLq=*TX*172lvz9&clx)0hlO&Lne?)IjWWEd8~u(qE?kMT|@1mBrx} z)XH7pVr_m??On1JH4u~;%7TF)-qTQ{kqDE}eFZK|o?8i2`FcmN39YA1Fon6vIm%^6 zMi`JnrJ&byegMkV0XC_$_3F;=tDV@GNutKcupD0Pb7BP+tT;Tyh{Eca>Hm^;Rf@`r z7;4#Z6Uz30kLA7Fv_lHxcm=xd?UBn29v}m3y=$_wvw;RTKkb4mhD+x5ym*aJ?5gcU z=(wIHS)AXE@hWdJMTirC^72zlM~$PIo?7?Wd9C6h4|%EO@Y;u3&A0z4O2W{4sM>4+@TxA(nR> zX-*ZxJZxM1#Djj=N+eEbywJYZBP`dsBc#`H88`ue_q?C%yyEO1fL`&J$4Z8UbFW<- z`yNy;vH*JnllT=FLn&SNkN2X={8VSw;M(&a1Xo_jLRc%~Q2rLSlbUHdhCt&(H1bo} zNzNNDLS1?Jy)}LUNcM&dGC^ITJzhrRcn@R`MSL&rLP_@QQ-uG|uD1kROJlF;odW1e zTjM~ZPEu`vn5q>IuU%(cLMk#wf0-J=QGVju(|`pBTj+kC0#2xe>RH~V{lcN26fX7h z0rnhpLwUKqBP()uu>D+!50suB?E~PD^EwaIy1-FuO-cp5!PH*#?9(4qeLhLtwdqSDW@<3u2{%+lw)m>iXBzzG=j zk%tz<%PRsMK&+6A6h)^Geh$Wd{g8#T;${}O0q;*J?Xl264tymhW0Y#uqdz$vYXxD1 zGQb+=2jB|-cNYVXa z1YGg8)_Y|w29MM6>rnv`Y)s7OjER_qT+K=$=M`zjV%*74Hp_C$YqH~Lyk)McejPle z<5A%?emdgqKf=WmF|NKTrApN~WAy$lHC7w;_TsYm8yRuLtYA=1 zhSrj<&5pD=W^W+W+e)Pjq)fYmEg@8z?_H%vo!xnIRYfo-){>nY7@`A4ywz?^0p*Mv zeRj;ewJ`IDmh{n}w)US;5d{T!qHBm$n^}oovEz1IgyDHx zq$7WzCP3#l%dwmohiuBog#ZXmUec~|Fsq=};da6GCw8{{Qm!7&2nif$;*)7J1!E2< z_-%F#vQ+Q7cvay^;GQ3PnBv}&b*fYaOPm+PEw91Vz<>(e7GhkY9?Y8^<3h`}?!ErR zG7Lq2xAjG9xi+h2SvdS3X&#dBG*7XNPg5IVnl~hQf5w~)A|5b zhXcW4w1FyZ+Lt5q{~H^d_@7;09wAXCvuL8!!2y>2qt0XlXHv8|ghvr*R^Tc)j3pBy zeFZ*qh`1@~z51U32|a*_m_^)T_=6C= z%}}dkx#Db%t1Zy2pyS=ot%$@r!i2n~T_&G%_qzv2_z%r)EJwp_h#jF(9`p*f_QXf? z>%Ph5skR3zx}??=659V%$erv=t9seS5_s+u3LWu-IIBwM3&&Z~ttpyNSMHw4W)afC zN&b9gvvym}N}ClUS=y#gEE6G}{VTld8QG5bs-+O_;)E98;1)JVBSRJlwHqS#Pjm>f zlD!;z`a2&|=Pjt9j^Yq65(@xEOgndXFV`AV@XhM~=%+10O@oT?3} zbJs=Xu{?Y@!_(Wh+JeMMrcCU7><#j(e=Fy@mfl*qn+!o~qwDTZINE|QFA596@|ZEup}>On zJl7`iCoN!4t-=N#ris7Eli9Z$)re_tEKOCKdEWZs8J8;Wo-1A$`oPV-r7A4chUxE0 zzFq-%4Rq~yId$9H?U3iaiJl*;oS{G44=__rQxGO%4nc>H8r67jI`kjv#X^deakO6Z z!Im_O%{XC%GKwKHqxpp!X*#R&=_6rRH`SeB-U#FAYJ_D${;>Y?2HBRZy(x56P{S>GloN&G zfW&6b%1H|`n*ZS@e-Kr|^hRGrKxy%ah8*SmSjLem@#;nLBEffLND}D!xJF`mlF=S4 z1yhcM14OzEC~SHfS4@WfXCuWdS?YMlWP^C-8ox<^Gv$yl*^1gmc3zPw(q++f(|yl| z+h(9LoD@579_OA_;5rR4-2@(WMALvjU*3)MwXPU@_iE*=J^2%BljKEtP^ZA9kG&Bb zU76v#`-TCk-0zS{KFa_le<^;0`4*vQ-Pze7z1rcn7-aBzO{k+z$-3b%ieSt7)d_S4 z1T`hOBk3bahdZ9&{XI|}I0msP>&hO(y&NI)#c|sCr=Mi}Y)5F+n5#!cDcsA*HFA7F zpD89Vxx0Qi0AP_F%;QlVE)9V&;-u+psZei(JlemsTw`kNmi|o_2(ga<@InYUUToSY zUMJ7d_8IQDVpD81PMc90{xa|L- z6+fDkUBLk_FM#yL1g7m_U>~`=Lo~+2;K|d4W-E6eKT4q_wiQWi0~~Z|q|3Ud2>Y+y0p#2HWPhpPdKdyQOAx)IVMCPapS- zM8XBbTFk8~^I5m$xyk_eB3?e8-e(Yl(omb3j`MsR)ar7!u9aHGJ;_;~xC3(~hWaOl zZ7E>l3`{(wtSOi-yfIs#rG+BA>DCLFR4J6JZ#A*1xbL}TfWw#%EdOqF+Z9n}H!{GE z1MQIA->#TITw?1L{e#$a)!Ymn(@s1F)4a~>fyngzlRq1tt}|9We)=g->(~(;Bu%QM;*q72_$LBlD4Mx(xNnF*xw&FjNb)JJ&|Zg;mE=IVO8l6m{$L zR+lKe@V3g50Wc2w?X+0s8pg69=$zSOB<9 zrO_nZ03H)C4`yTzF@jlB{^xg|qAZw@+ec@?lg5pD)CWcDd%~B zDZ1^~+Yd~9-GufEa${6+o+JCieU}E`0rLpZ@3oN3Yc{ydU&Ck$S zPozGtJ6@@I+B@7dExx{avTX*q^U7z+lTB{a*K)ybQhd9=LwYo7YaZSH<-m;1ZA%JA zAXR86Doq$$^@)Blb~aoMGeEK*dq%N3;fns!N()ZLZpUhSi2+9!G+K)|&)LRY9S0J8u z+6gS4i3YDE_CD^BUW29z6im%J#!e%Ml6r=hbhOH|z{*L(Z)OG-0(^q-N!(s)Z_X6t zAK2W}QNCK^4z0q_nBF)ldArZKX)khsPuy(NpDbhT}1wmW-K4u05GFeqwpfS#)B+2zan# z|66?BaT8IFN6vTKX4qk((Irw&H2cC|uQtU~m+yVA*=8E@JK!f$+F`-_=fi|tFr(ei z%!$vzcligI5vRLXF^rDGue>PAiG$%{C4+7P0}SG}T+6Xtj*GcoA$uqW%zI@FM|02D zRy|lq2K-~%GJ&)4iur=Dxe!3A?fCP!L!?5`!VY(W9ygIcumc)2JC+A}LmTK$H>G%0 z*ov;ClA-5K>TO|kZ;$Ay-|A#LX2LzE3eYRxEjn@h5&^r%O86(o5<}9WcaQq=-X%bxfs?)OrG^; z8L@I&XJnGbl0IZJkt0n_;yKW6=DI+2FqlQ4r^J|9C^;vKk*=#?bgfCJD86{e;vbeBg$u4pc}@A%F5{M@H4-i6A)7-MdP+OsCu%9I$_2Oua23s0e^`h z2`mp1JfD5Njt5 z78&!5!YFUbx(loFqB~!hnOSQ|moBp~rHF|prKDk0QY!L)Cc05 zF8s}1R_ic!x$ZKNc1R+73SM1z>L_V6_UfC3nM1Z*fVu(~?EKdTdw^FdFV{^5)krwB zbS5*!7*nIUV91NVQ4&gcn=nI&Hc*-lc5o)ZoF%M+Op|Z_|JU2kzdqX4@Wdcig>N8< zbp?@DRX8f|y?V%?O(cK-q|Rt&LO>RyL9;-CoJx1+H&}llrSkBnaS9-Ky&>~s4&iPAraLdoMyb24G?DeD7)hU z%E{3$)Rzs>KB(qTq`lcr0l3V|$()ZB;aamC;PNrwp#0MRB=&#bQmH1CJ8iTpNZy+2x* zN4?}3I?Pv`8nuHkWUuaWLR7*dQJ)c=80qZ_k303{nnv^3nQI><4(He+Hzw z{XIeugt`RbpWR!$U6wjPtZejzs;X}89j_Lg*w^TR6*yf`VI4h+=u1t!B?|{LauoOw zHz_EBrD9BRVasaq9S(T(aAH|P{H1?yn=<;WQ8`4sIus*-cO#{ICho@_xHb~*%h2%D zPNG7 zwbFxBN*Pyw&On5Np$?Jx{&*?}P2ykMs=zmYbrW5q{uwgTPai_pnNwNy>nVte;E&JT zd1;uuDD`YHpxpiSvnX`_c98_^@J^(a+3w<#s#nsXT&I+AK~C1VQ+xk<;fY;pZPGK= zVt+uCo5_{M>1hGFO$27fQU0`?3k92#C0$H;Dj;N1Dp)s}Fj{dR3HRM5`xyqLO+3}M+Kv5d64Tp2S2B4a1&or?3<{d}S@ z*t#{&1+sNCc#!pq$NgoBa^RdvK{krmraoXqn4}iG-}U%1DtDGo!HAyorp$w(X;I>s zkaPJWMX(Kb{-Vc9cu@!WY1TQ7;~cSIt}^$`M9xt2#+2N%xLkSDbz!3~{$&X+4khV^EOGAft?5ZPW&$2 z`e-P<{IJ{|>ciI}phada1+JjR&nGy_lV2>eAgT|qlzZs?13hv@1}=B1lan5_?q2Gb z@v||Sp*g^BY0`>mVJd!m+Domy4ml9&V-T;11%kMk!5$i#Pf0g0bN^yggCGF(87 zM_%v)8{R7+sjxsVC0J3I9yo9a%&LNjX@0lMGYW>J7SKsKG$2|vJg02K%|35az(s^%wH7(t@rNJUoB z?ji@B+1eT1XvQ7&rEkl>q3G1%6D8W+s0M`hj2EL2J-BGp1RkAtHa zEl=)S^~JzVGNi5oke776Tl$P$#?c!)&Aa^h(xF5oZ&0m6+&7*f?lkGbX&bF@ztpDX z$MJm%OIrr2X`#-^$S~Yme!iLZoWMj=E<<%CZ3Br=+@mCz0W+5Mz;PN-?Wz;oX&JCJ zSX$l;`5#HW`dh~rt1aNFu-K>Q#u^FvFBpUnHF|`=mW=!m>NkNV+)=ZGC-Ot=xq{xN znU_)j%xj=*1YK1%Rd}SxjiHBdcOtp1gzSsUHgSWPyDahzEpTl001%9Y;ZAaGD*qgeI8yMZ=HJIsV9Al zkxPQmnBR+9KjBvwCW78fkTmtA)&_@6;7hI{weE{tqgDDuMd1zrVw~OB|Jt zRLGn@ZOLFE(6_^oXZQb=&7KjUR{0(x-EQ*$w_M;LJ0M%@4QKT93(hI6gr}fQB(|`( z_k7#&n|K#!#s5e<%>FZ1t5`xxYd_HM-JTVvKyZ(?Bt2*T9wM0GixL`w)6%4)oqfx> z=O+Fqhev$lt%uSy1!~Pt*GSj1ino=12t7+gk<3w;v!Q&YF5ugfDZs3*n>7FP<;w7N{J`qsb~icoyJ;4^5|LP zaI(+NLC0^7A=R#((lc^T`R+_1v@92GMn%$Wqtyt6A1oY^WF5T3Jp~fT#r|S|VeSOn zW@j1yB9P*-wfCSO_}UeEuI?jTr06}1fYo@G9D5@y6{@V)P_oD-#{Y6KJ{H*ZdBZf+WkbcW3gK z<}OYV6{)Qqq~OT?dg=7hieEmNkc!%62>PB9AP90WNohc3(Tw6T}Z>3v}Uk5BXxrcaa3 zNl(mFYJ+EWjIUThM20DXNB;%i#~ayN#Ak#Syg4a-1qgAH5lX|Q*kiwAcz??lA- zHy#C{HmgH_w1TK}%5Pyc-trK{&!3P$fV{ zqk1c$aDQk^TxE`&=l|kOZ>ZpSJZO@)zh>u?c(oUMKKCndVt^zJg7!Mys%0NmTergi zeJdS#+T#ECw#^)0Gft2h^TF=+fPXaY%_++?Vl{5(v87rRL|nu4 zrxTY!pV<h~K3LR4l_AxB`e81w9@~<#Q^u9`C`L4vEE1HF5<3^LXYFW}o{X9$bOtIaxo5}GNB{@M!5wd95~VKeg-2nqu&cpLydg~R ztom`CwDjz}K)$mDy`ZJD%&)ewp6hD+-9S1agU=D<@rvSDug8S>esbKuY$HD8x>9?# znY&@VyCDKj<{Ph`WQTMbM(B@%CRM}GbK4F&Ge&w@Ajmd})W1|`4}-Pu)RBF~)ywIX zC(nI!y#-Jl&GtS#ySTf%ySp#$?(R--*Tp5c1rG#*TOde6f?IG45Fo)VNPqwVf_$4- z?)}~R*H<;Q+cMMrobH}JPs^NMhXRK4`qWfkuB{tzcRO4LF|aKOM(OHzs3LVPs-8#L znRCZs3glHiY;p~3k%X0Ws~LC1-t=gl+2Pe9U5Bj3;FK@h$>K2#uKTy!QytWS%YPuH zh*X;3Z_>_1yZRGIPJ90h5@*F`(a|uql+1X~zi74k`|^=myHDQn+CN&_-#=PpL6{|_ zEZL(4-zDY3f_x{Lkt_EoIQ2fyeE-}wZw5bF<#yxpGVDNOO453J(hECs{rTh^;>o`H zt)>OH_w^9CL*Ire-vwV;z0^=8NTsyKun>)<`I*2qW%8J@M^)BV)|ln#YZEVF&fl}I z_+Ibj4|0WWuKV`Jc?y-Q%1C;+4PB9S_3C^AV>@|f&VO?OB0F_*KE8~a=~4j!(X8FMY=@Me5bBMq(+Z_|`*6R`Bzy@A{1xvPIY-29T{?Lg zcvV(~-ZXK{3>8u4(^*jXWdRT7EQxw@Uc#W>1jBvGTCa)Z6?6 z*}|3TUI#{tDq%}JtLP$Oa$K!9bwr42#ByL5P7K)Xd59DIXt2dppxh8ERb`Nyg8%$8 z#J@`vtoGaH%>k+J!l-4(=Mx_b!YIR~djGM`o%3cpmnq?swnwY?2kSt#9t!NtU*3S3 zCNy({c(IzP#Aktgqv=b|S z;$7ishZ!{OCi`5;d{J95d7{W?jMIq%q6m6FatM=85l4NFE+r0b;W`6t&H+9|TQ&wePJiLn{PF*EC&zXwBDWjMF46J9mRYG7@Z zS!0j5*USQJ=-Yio(wO@fE<9fke@*?A)oewwm4gb;TXz-l=Upal5=mbcVAyQbjR;B}`Prz4WNB znUYac-6cXp=^=5e)XB?ROng^EUMj_u1^vNsy|-r}AcIC_eUJyOd9$)-7e8F9csPiA z)D;28YntQJSzCet2a2;DA)`5ZY-Pm#j-#6fQ@}@quhu}J@a7qI;S`$XnxE2cZYi!U&^PYG0H(mL5wo z^G@XY$v4F6cxPXB8uiO|#?Z&n7#^Vx{L(6Bak(^O#g}J&Z)ck74y9T!u-y)<#TLzY zh_3SGoKWoxX(q=QI}$G3=r#NIlPetb;#x5TqN^NsL&~QyiDS4j)X6zzwb@LyxN2Fj zUSW75E%q(G8L-?-Gj+&X8-0_M=64)7p9Q~g74j|Qp*f$AAd!(W@+(fnhJ|9n4*FFl z);>tRtb@He*n?T(?K9Z6g{bApI|rCin(dT`YOh#a%0)$+PywxMEQTJ}2-dLDr8PMO zU!`jZK+-QN-AQq_G!T=-%7$nL$M&;7CVt*_e6Qsz*M+}5 zKUSPX=K7Gh&p19=Kt^FpNM9u@X%SuqI@J#ItU+vo{%3K=fS z-Ev8Y&>d@d2=66P-0C8UQhTv0jB44yH8^?n12bBlhQZJ_Zk-?oZ9*Gj0szWZTr2N~ zQ^pH(F^rF4;x@J{oxH2Ip6v8&3zQh$sw#UxI)O|cJZ z#TmV?$x-Kx3NMB3C3Kk4C|H{KllADG_qshAPP%mdCVVo>-9VnE)a-LX>mLpX)@zLT z_kJIgp3=e)7#X${*g*kDtJd?4OMagUkZS0Tri0)$Msah}DDNr7YQ+Yr8JJN~r7D6KmV{rn@JKqwF=&IUu ztU3R%N{X$d4X7dstzA=P^SA65FlC76lGxE43D6!&R%m8kapo9*uZhaWV(E_mOHyEn z9;NG#@NBlduQ7%0nAI5X3lKD#Q8ffUSLh`tSW>;UyDs(?K_k&IU;m!KbF@)0h4_|kNt-;npNd4q&#guHrq~(*vBY06+muc6T5HU|nJ)j1c<_Eih_wAQ^p7 znCOq)ygUq|D^8x5M7gAi;t)024w2%gTYAJxv-ghCNjss$DHfzicrKJqZwPkcFuec( zp-{R21tZ}J{-xm?B*Isv?}dW!7GlW56>kAVc}J(;y&y|=Ws0|JEXQg-wi13NmWfHa zfq?ZpFk{u*r@zF89m4mYixhTvQn{Wa+=Y}l)LaW@K$_)a85F4LoJAuEf3nxJjt)<& zh?6Ew99$<}`=q8N(s~+wRvJLpNxt|pWAB&orH9J#gex+&&Ib!mL5gN#&Arx1560v_(8B_>vUuNO=D1|x zWi{4g?HsSWu9ko$M#-bGcO9s7a|cD!PA^0xk(Mncu#cwF3oV~OCHd_KV@zGN zcLa#Cgbln5k}aaTTpR?x+%KB9ho&7RkVXxDAFFoL+AH1+ZAN4nG2+;45iow-B{#QB zMnn9St*`fTaUYqBh_IJnK1O!<#Nd+b=cjx5HOTG>+U|7!Q;fdRM%tuPO~4UOWAS!o zxzzNeAkyyy%#nOOmS5kl0P^HFStp=)S8|J2*wxcxbO$(e5M^b%FfsF!Mz_GcOJVI( zs}lT;jvvRP*;Zx~HYfxfZ`i!cY9#B85T8fV%OmW&J z_F;@>`|e+tTR1$$9XpbBvRG6?PKqxkT>b6l$Xj#?O|7@&MPBk*UC-oKI4#?}zR;KXC5f)$Gzp9;-jph4(REEk)n~fWNx1Mv% z>wKWvfF9w}92JOXU7TMjQkEqTN4~Q6!hE+ zmqL&#SBYEUT*csM7$bT%fJjZH|5+UO9#3NP94Xzz&4cUhrtqPaOC{UVW>Q48I~4si zZKqFB()x_&^ONcHM>x5(1MKH7QtbkAwm6kIIxv?OJy&-#y<-|l)mv7g4Yk!$J9Xp^ zlx_p{5t9YrbBo`kqx=TFxUe47is*hxq>4kktCk*p&G^NKTPcAg-qS2oz_%tCej|j; zCNr=KIW68R>v@U4!3-$4&AZch6K}G;&!eH^cUrTtTbn}+n%vI>3xX4lUk=Ubn)Xyb zct2qLoHgroB`)sJ|4bc&jaqXdZ#(@Q)w?R`y%%MnyrH)i!RRJ~dlOq`4!<2Pe`mDqIVc^JkbJ{lXljejm#u7yH zlU?o6S|SLdLWAx86hMmdgwNh}U>HIwKvTZ=>;^}Fb$?gyq2QzWRb8{Ex=5ai$l?7! zal{4-Q;u(Li&rwd`-I7S@ImV^I3gooYrvTBTo3ihNv`%Cxv9k2={($}8uNTZqdxKT zu$s(e{77k4qM8b+b~$vInVg^ymcvmD+Jx^6#W!xRi_vrQRS5d+Oh=%Hr=+@HJ5}w} z>upNe@OONt4V=fRzzT>1El-RYYjhMGsmu-i9S-Tw7uiL}F(@sZs7l8W+$)n|2Y$}$ zU@1Wex!b?Geu`T7XLN1(Mfrm$sByl$e_jFkE~!}QPU%+|o%ee;^Kb#L-{zYAcV5P9 z$M1 z^HugHh)-?m5dI6kIm~pM2!q{Q!17;4Dq(BuCe^+-9VSOpuIiV0O^>QhQ?PpCc92=~@$U!B< zoJmh63V-SfQPK+D?imf)7XTn!W#sO6BtIp5w@|2QfG(P2gD;+|wLKvE)^GYct8HYniH+V2GA@9(`COJP?R~)F9caZQP=_D=B9GO1 z!`ra=xbR~cwIzB0$Dsuig9&_b=YU!ud|N@}Y&C#{q3;HNsOGr~JN&GbDllya=?9f? zG2He-*gPCOdGV+;7=&rdiEPEh6X7?Ov#%~xa^X8Vm~3PmJF9Vs?y(25)*1QZGYroHIci1Py;EMGwH zfnzjpl3dF9_YeTEBF^FMHI{~z4>7EKH2#zi65?Mh8{`4d2LpZZ?|=4E(AzsxVBJ>m z6I$zg#>s^{pf|UXM#KHgezhi!E4kExQHI`^N1(bOXxM@r`~C0AHRym#*~YgM~Bq4Z+uKtOLs za8(^Mqj*}m9Tc$|!29uOMx81drP(_aLAI?N={zYVj)RvQ%MFBxS{qfF%CxnU?~{5W zNnhYR>NPp!V;T@>{C&%53sY6v1Z*sJtvyD_JsC=0`<#=|bu#G=061CfzgqTg2$V8H z0W2?PJrD{|W{Q+6>6G^dN){v)i|r%g`b-Z19-U6nn{i=<0o1_C#y#o(VO8LT9Wy{} z2MTVO3Hj!*&YNVRc`Wf(zd8uunFb>=!^fbE@}QO;`Ko^6bm|YFCfl2p7nb)0-ho@S zfR2sc;7Hi^z6S&I40OC3s>y05da5u|3qvBiiO#u2by7E8&sZv4}a4?I8t)t z4S3kMRDkpV1k)1~r6TVODg`LJA4c)i57WVL9~S(3NC5zT5E+?ez2Z9nB(g4!Wv-a^ z;>DxxCJcM|L+EK}0MO(;fQt(9H6g^r3E0qtw|%5oxn!>Qm7^02gCdx zhI#V;Vy5m|r(}YHQ_|rUaC_1LU>E>>0!R?j&9LTZV=`%^Ny>&Q(b?1(ZN>bRm?){Z<| zp=eQj(V`i`(u8Y^)MIZCVKo8Gif`wRW2L{+DQrJ7eIVr>8$dZxhUr_=4-w=>SCi&vVK<%G6Os)%X zk-wENgLbiM1gtzT{(9BO<$6(jOn}#sf(6`oV^H#y`H3SC04PDmp+H@^^6I0$%LoB- z>C#aDX7{{U~ZZm{7R8CSXLg`2tO&TJ-k z965r=NDE(^``}KGCA6i{tgdUCsU3@;8Yw`9wSd7S)`s#(EudZzg%5j&fwcn;2 z5--qO_#-NUYPLS@D29V9{B>|XTU&qSXEVT`$I8k3U_y+e^okMfA^InVTYir$=SMy@ z2Cozu=g7*pw>Y)~+=VUmVl3s~=~va#+jV7B+~oql>Cn(d)my$D?{6-N0r z(>sq!Xlv=(7Y?kv5=H%4=7QR5QDQ<&OHz-gw0gO5SMy?hm>46WiQz9GQ8bk zYZtc{3wC*jl{JT#=P@x`jrSz%S@3jYMkRlp;@>?k620!Dc?~ASq7RA*>^6EXNMb zlr;`LHfL<1n{FJpP29%n85;EOmD3P?c*6D4!=)^Ta3h5-QYPLfW;e(1*9L1eczaM}g7-A*FL@OJcD5 zaMWuVYjv~rB~+423LTC%)DvXc=g`7WdsWk^GBj%U!`X2ijIL=*S{4p{1i$feH|!pJ zEYVBDXSaubz32+RM_OL%3vMH@IH+kn}&uOjU(8!a-u{Zs} zZK6xBn8U>vI2Zhsl1ks*Z;w)1z0+ufk9Ria<0{8>%AUC^1%1KddN*{xauN0t^{ zNb>Rv;Ux&^MCVFe-CF`*X3(_9Z}w&Slb`Q|nP$JsR?g6hv@;5w+8LFdZOU@qr(&LD zWOe8gc;t8Gcu6qH{mjk|LJd6+Guysj>Cs_Re~TUKKP3GTI&i!GfFm4PgyC6?dsY-Y zp?RD;9QKA?+b_$Y>c@Gv>1vk!l>Ctf=LY>7TUGYSp73b)K;i3KjiejRyee;dm` z`}ymKfB;;0`b)*#&5sIdC*B#`;M3h{G`|#e(yvpU1fNT5ZTG%A{y?(S1~NYFB9JDn z@cL{cB`F?0Uzzx9_m(Hg{gC>TF=pRMYF&-*@4eX%sU!?ZzKV`|cj1aN%Q26_q&{$@ zjGQ-T)(Xo|1cMVCyytrEZju8Ys0h!}$G~M2_pYpjt?J4@BRJYk?dyG7zi;)14LG?= ze12x~$xknF0}CJSvfmDKY>GAm|_?RNz^Ggg8vj zKDP#vsqLPg#qUOju`b*LY-6mmXSeGLJXe0nuX*Cs;SO%&5{jpc$5>Y9TdaFxpm4D9 zQ1F%J`U!D>OVGF`^;qDgg^BO4b^L9+Me78FOaB->S$B4cd?mWbsCox&NMHhe=H`de zqGGM1H8uC=Mr!l&vgSabr34j zgIy0~_Nq}&mO6ivr@o;fy+K!T>HfL2wa95Nw}?pI%)WQ{>BWcFyIVmrB%`96Fuk=1 zDq-Px)ngX-kDj1mSHTAWCUKa)CEtKQ1Hdvc&8#bTo-6^c<`p|}2`T{mP zr7{D68gZ4;3A}av>9j^kYOKIFH#Wn;{Bku`^9ddaTfEJS5FdYp>Y}B)Q6RimJ~|F{ zS$$zY4z=5T57BPG3vGP2Hzwu`S+%+zpTtixCY`*=T|ou9)+@I zm}Kg&dj63Mz+IICJ_7(&!r(t4l-hE{E%NrHm7QJdk5CNfOlP-5b^s7Sfi*(EzwZG} zmj3%V9H5LU0RSlE!N2K;hMU%zod?#s*_+uZ&p5x;Jjxf5%3?YAT4;}QCMl$10A^q| zdogC3{GIDp7R`0@NWzDagsC+kNv@TVgESogAcg#uu3p-oKbN>0j7?IEaVOFlS}!u8)}M$lNHsh?%mE(G``;S@Vd;=-Kk9BfKmxMwrU*xJ z*4_gkAJ~%avXl;+Z@eonh4;$b=gqN_=+orIJ(XxbP!icG2IWV?YW**spbjGme>w1Y zV6aMHut5yjdtx zYUDZq)ZLZ>AdX7~5m^bTC@yHUfYEo`cF4EEX7DfS+ zpB?ymQMZ$%xz}5V@rMFp?h(gm!}ZD8;UjL?9no&eq;QlnXe zFUo9$yf>Y!TgKmmE?VYqX47sSKxro>bOK@e0v>(eo4WS9-bylffZ|yAj?- zc!Q{%FsYTUa@c!oge64E}>u*`Uc)^aOq)H}RbTTqsly4D= zPl0J7YvGaT&99+HSNNp;ark7@i4%uae znNyX~qLye%>hDk^W@QuIl(WmmCAs!jKGw*&Z^K=ac1)+**KES(nX8Q3aU5w+-|!sg zE{bj?AZuHiM`S{BoHw*$NLGhcmkn%B<69)N3s7*fzWqNE1B81$NK2<0}$&f1fj#itV2*5kyi zB^|X?O!BU*oGEI^UV0SKjtupwN6t&=R%*5^?DL-mm&SFaeOW#;!29w2NuG1F>U~~5 zl(;WMEMA%?W4~n>sRub3?D@8~QdIqP7E3ASjl$P7&O({+a*8B@#OvgwR>K4v5Fg6a z13Tl%WdIaD-FItu?`lN}{YsOa2mK)YH`%mwbH>V>Wu5yIxZ3QmFWY<1Y!-t^KMAs5 z75?ZpS@cGCXAP#(;Saz86S|x5CD|ORU%zU8t(K711`Hkb4!=*KAFqUbzAt_C{)lsf zG>+ime$UpqX-J`KM<6ASWJ{xG^T#)8))4sfzOX%OI(bdU*eFK9*0NCqtPz`Z1`ZS| zaA5sAhLjyGmzf!I0hm$ZtmiTQUZo$NSwnB?-ee)Pr*Qh$Cuu70#5KC_Xk5gg;_SHf zq?K5vrlr*-sYGv=)P<83%eOIDTBg#po{YLB>VL1or+%5Sz;>)I7e_|j@eV_H$P(>w zGc~n;HV?1Fh}btnE!_I`Vb#pcqd%@~|BFy+n^?Vv=T=PI6=r_p!@}6dVvd~JgycSyP!F`O~ z0N@m1^H4n9F*Kv`5IUNKsAi^<-LXKpEb4Bn;zu*8x?caO>5&9pq=n?i0HweOOs~?Q ziB)(TqLxae;ToW90@0a~<1uj~p{g|*xl-KSOI4iY^H$U3=iXV-_-eC&^f!i6nOFDc zcTMc*D}%}f-aaUZ!_>>Wh&78(xFthG);<_@w=4(a92y zYsZblG0?&bO-9z+v1c8dFvhq|F@KbDSDBLy9<^aXq;j7dj%v_V8tpYJk$!DmL4)0G zCukd{ZMs1vBFEKD{}k{)T|H9L+1~-6Q!0%abi9GN15{#~avG?aH3P{-4Eo0RRD{-Z z=D-#$<)vTfqrOi5eh{K|s5Vqb(;KH@I%f2$OS4Y zAq$hHgNhj%{S)#>Qj`kYZ=ljoYeK#MClGlQ0De+qRhw%xL|Xxf>DmxhzzPwvgwi>3 zY$98uhWrysS2Mh^d-nd!Igwig_9(VFKS19bW4_shkNmn6pn$kW8vp>12E(QHA6&5f zG=BY^4H(7qkAv7Vt8@g&b^^VC|2rHmx)e5(ho^<4l?Mgn;$bPn{Y41jfHu$4KOPuP zu4;qyJtk^oC3fnPbCfR?>|;()f(__Of6g}n^>v|0luu!GrC%79|J>dI1st}~|G1Do zFj;?uId-HA#1c{<(DwGXYLx(d#NV1*&-vPQ!)_UXC($vw;F5J&ZOpwVwbh!#X_L$$ z4XF3z7Fo8;y@wYnYp;FdVjDG6*ZZ-r+XlT#Pf}d&J8^fQCcVCc4$2Zjg0loT&e>P; z4VA`3EwkQab$k^$y^Uk1n_QXT+wXEXzg=tZE_M9T@c_ivNkr~U7ody4VN&l3j7jLN z6*UiLoAmzsDd5GL6jkKILlzSbeSQ%QY*n*jwJ1(JjfM?R>DuHw(EK24s-^tg|BDPk z@K*tpKud2HGzYX;cG6>RIS$1K`H8;F6U$}fh)uanbjxnG92N;CT+x*brwC*Jp$)nr zwhTP6FYWp*O&`y@`W;jN&5bTZl$WGsGlZXZBzVK_VEYdEFd`6;8JdZ6m(V|SNoPSK z^Z0o3LXna&`cGAU2#s?ouVkE>m?3@`P_n75Fm3rQm9u}uU(Bgf8;RJ$FZS{?(=}9g zJ?kYq8KG4!mrSdZB={~X37$(A-Ck|(L|lsBm9e|vmG%n>nMV`p(dsYXezs0JG*P<5 z@)DJR%<@mq-{e@L4B%Dm=3t_el2_{Eik>{LEpRBFVVbRiNOQCK(cK!>sk~PbZwTCsv2% zThJlC#n%kbQKXG7q8(@Op!+hJYUatYziF46h2mIvR~ zMOl?KD%NHh4x@9L;Z#c>1s-hZd9rt9=34S;bht&F4+ZQ)&%4qBGaaDSZJ-_^&M!|v zkeKaUp!hfvN{oA(lv+AhwYR`J9*(G<2}5Eg{t@!Mk4o`yGCW?L)?llG8>0dv$Jtycskn?bN1PSx zlzEHbE&(fE#T{C3g$_TTj3i+IzGw%>j)P}PQIG6tQacNVqk7WkuJ6rF3<_j+-Wv`a z9Dw3n2c7jK*{f$knym+ll*7k7FB`%zzPM3b>>gHfY=bq>j`HoYB59q52&wOtMHhW8 zkvozRFI~hW_mxPt5LEG|atxSky{{TJ9-&*z9BI6D3Pc)LFB8?Kfizk6@OY>BFo_!z zC&Dzg0@VPgOdTiXJf%0o(Vj2yH7)A&a;Qq4ZB~vj390ON65tOJ_xuO}ozw+JpR!`v zP>?HH{7j0v?~k)FhK(gaThb*m$LCysUVYdF;_$f&)Q{t7afNXFuq}Kq%9xbSA8Ah zGRKr}cI!fhzPPjLSVzRk6~W=bW3_N}WBl5xLk54FJxtSM?0A@BswXGEW+C3%OFNzK zjSm98*1zaMI*WeHg725EhM_n;uRm4YT*MPRpXC>w#sLoaWnD` zX&4zEtc^Y8Pa1{K$%Qf|MiSG$zWwIrHCV?VLH$!!4ixw}6j=oHiaZ&~lfIgeg9?Y1 z$}>~eaVGc4Z%arX2V1-#=bF-buXBL zoK%5(+jC~kK?-K5XD;8Ee~^qyv)2%b43e_Xc#3@vQ!ss?5|!kG|EO-$|mhRi(s)=d_U0PVsvK$;bx_bMM_zN1n} z{edb-{T?n!cgWRg4!@R;Jvz2X65je9H)qjNvb=+UHUy)T6AFM|)=^H)6wzM&fd($Y zh-=P*0swFU6QcgVLckjAuz((Qyh#=_=L)ib;2)$g9g949*qSNiyN7Z1Y7-lq3<6M7 zn?nHjOYDm^5Dt4%P?9(K>;5$iI>N+LmyCpvzH{OwplHEq@=Lb$aIFi#cSuq8H=RWb;Xh#~+gK_@pq`?kC@4*sct%{EP%t(euEctzD&g z&-;kQn&uL*dK2pTJtm(V9tSw2gs?OasE3T^>c{%lNv9zkr|+9uCQ9+)l-Ws&-~!~v z4xx;xBv9Z7v?S?(73!HH%S0ISc2EF9$dj~)15^HgW=m8i{;$-U#l3LVe}siy)YJf6 zCY;py%|Cuv5c-N0>+`uAIN)XsPJpi2l^bN3jEFNwvXJM&R16@n6ASLrQZ*v`joIQ5 zCD;qIaUOiHkTjJB?+7TiHagTAY!I%dCMtW`4mt13{8}${x`RspBq<`Cabe zqdOA+b0-J~03<@J5MhjsSKW%;>fzgIL`s?H8=@(7E3r}l09s&(*#BQd|AGKcu)Xde zMC_1%VPWlB0YLq~KHVA^b4v$6r=6;>3H}aZZCDe5WhW|+Yh4fUc;bV-qYUVi2Co8LCVBvxlp9e zsW~zR=!#B3-?JQ(VB7;3fuMGYpM`WF?9@uf&Iq=!l$6@e%cL82ZMPNpa6Boiy<9+0K>a#8Pr>&P)MrpYtD3$#?d?f<9)&D z;~Yr2-)@ktHiESFcAdik&8$Mv?V>PJy1AyFvi8HDj)I&{4igzYvXom!KLPL#3MyDc zEXdNC_M`OlYzBX5%s$?tMmL5bhb_9Py8SQmFkB@9D*(hTM=1h@K?0-nQ!Nldaj|FZ zjj3QM|J9t~*8-aWm{k=32MqwWEc#Kf`Zg?C9l}+gjRR>ER4+5@#MW}xo-Ivs_!)qS@~$zQ+*k`Xh_iyNk)k2X zl=cD*6ql?ghhAU+^8hwU6(wDurqu9<>;6S{0mXmjsnmIb8|O{|AgDF=J{gO`nyB7| zI)usCf8(YKVJIBYWq}cxm8YESpt8}G>crf4-!%3aOnw_~E2MPot!xW6w!9iU zG)(|M9Y4y3&W0OZIJI4Mv;yc%uP{|@eW~(eE6;moH`vv-wTxViCc8>$HA5Mp-x*Q) zVgwGWuS9$-p6#<4##rN5v)O#s5W+jzJ{}ddCp=LR-izQ}mJmYpO7*2Wwh1hFzV@oF zo#ouj!EEf>R6yD#2t;zc@ttdpsVeZ+nr8Km9?d{nSsQcjDpD($k|IMsxdo>r9DDdk z2@GFy+&Cat`-Ec4@wwRCv#PgZ9YqV#+%++x;HN6fXNI42;`HWrf(pHU%)rHCCKr=O zD|c*KR-2PjN8QRv$>sPaKQ*s_ParyiPzyy!^ZU2v$#q`+i_!r00W`Vz_G*Bf6 zGAr`(9|u4}CwbUGt8KVMLp6dl^y%x+?~Rd!)m`?J(%JV%G4W`H`n3_I7HbxJd4ofr z6jMJI>6@os^(vo%IPnZA&9)KeY0s)Tz9fmL_28#Pd@s@{L&}~7>8-sSeEG9oXi*ty zP%`+Je+8W!%fe)SaTp8j{TYu`PJ3F>tlbhxdHB~E2Ky^rv}4_JkyNg0wrEz?3M#l2 z27X=8%7=+uCVo~dZu(alcZeoaV6ZD`5xs+_WFT5%pK8;AHZoqsY@N8U;Cr#aU{0Z{ ziiUOKk6vA}wsV5RBB)=yYEeUeTpk1%z|IP=?ASVw^_6w;40e`l4iP64N4Ii+FTitV z!*gG213w%H$;9eyGAk&`Dk#j-791p>Y8u7<@#CIMDV?4)A>3#{o002!vLf>RFCJCe}W7_R9PytINJ33IWOWj{8q_IZkx zmN8w=aAH)>jfbq$`)Q;P*sckuc04I$p#%)1Tl+{AUlNoz zY5!OW%0n>@s#7~RG4nb$cILbf(K0F?glG_XHRVFKHL^Z9D)UHu2j+`JA!~@OiyRR~T={57uF13Jb0;P5 zu2{TVKk6;j@JZdV4aBcpKNo&Z?Rnl7hpVe)#k_Yfon)C(*UOlt_RFiv>AeFX8U8-S z<~U9uV$sKWn6bD80*k5w+G$yVY3kU;9GBd8g%!$)$lSW2U0ZpShaVG)t%&u^hkc<9 z6rSHe$k=ZKZfL}K*Z;Hp1mE( zX`}2xdkHZ@U2sYCnX*;T5m8`uXS64_3R$R$eca+bb)HxCZN9^irbGL1axX6wQT$RZ zHwy``*7@rN+4uVke-zF}Xf9r+)c3pnwRbtZ+i`kg+VB#1dk32e)&|%LJ|W=?w7RyzcM! z6`q8AtsmUk=!YJoom9JI~?AnD_T z<_3RbH1}~VYzzj>fJ#j3RoI^Xt@^)o;UA6I_(xL$D5K~Hf@etS(q5iC`!fL9XnJo9 zJWVvz3JO0Wvl4COWe=LK3#hH2#X>401(PzO+NeeDvA8wJ1 z1Cb*PGckiQS-EymM4qgrbSDT5S53BqGgvX5#R~L&47SHfZpQWf-H+36zwj}?ZA7c~ z!eknU$u#jlGX3GLFhcjQa5(7zumU#Hg8~?PgXztUk-D&5jzG8dK~j`b87K!uXK7Gg z6&}iEqy(fGrb7Uv1F0Z}ag01X>}T|kMqFyTA+?NT zkohMia>}8**I46&YtnoOxbb}+G%6q=Z6(J+iMYDt>oa(wSpnPBnZn#bt1Q{yJ=%sk z-v)M_@X!;T{WA5b;!_R7+V#KKYwdzxR+O-r=t{%HnFW=Yq3iu0N(*B!$wx5qW@D#$ z2BQ#i08n%SIb@CeJW2}z0BIFZs@`DfP(*Ul05M-jt$m4e-Y98CIRc+n@{jD^xb29 z;|C*jwCb>vDg@P*Cp?|Sc11>LwY>ExR}xxm+fmwB2CiIp$)uzEGAbU#%@vE7JU@az zFqEYidW}5Vcw4R(8-#f~e}rR# zP=gxHnVmoCi)P8Y#AXdXO-Of{o9IZn8dLSN^)G@hPTXLZ}EacQ3iWG&3B! zAeF38BjEl}hBZXkUMq8@$-ijd-@NbNSx%)tt(2(XMel`GY7Lk%&r2&fBIA0@*COt; zK|0v_69(q!dWBd}l>(}#={}+oQf|-(z)M$pHJA1V$%ialMHf!J(~Hh^j)y@R=~?RC z1~u3u4jX_s+Q{x}y8=9^&QX zy7Vem4md@8ZJx6#rEEIn*sa&d_qA+xM^nO%je?;GpE0>y3(&RSlBAe_Nt-dws7vQx z;OgiRa{w$49DL(jfn0oAsNN3!rabZ382jzJcDYaAQzm*RQyXP3?D8*LN-3 zIAu=wD~myv4zQbC_xoJdLh{L^pvve#%MWYukMy(l4PhfL#Zi?6Y&ALT2TX%pgIW(eJw6zYqJK59Go7z+VhggP>FC61xdA)qm9>DmFlfv=A7ESkCGp zwRQ5+_rzI8fNu2#aaxRdnP5H^3l_rJ2a+(hcFLg;TB^em=aGX7&Vl&$;_}+u>f__Z zo=pW^Of)g&0`_xaH;b^DSX^9}xu7^N){LF>+vpzW`s91V*;fRz{@8Qj2HN?g1E1T) zyZ~m`YB8Fwz3U$e^1G(w26KGk*y5-yW6yT8m0slFLh<^<^^>u6Q8Bd4DSuLH(#D&8 z43uS^p1zFzLfI&=LQOxPOmVig)*I=!AWJL)se@Ys=2vAJ(gBILhJ0=<2*wsr=|ld) zx40bHEpI=pHRLBOedztgMTW}&BCZaK8XL*IO7w8RFy)yCwmEw zoW+YsL%cW18J)zWMQ*w^6}2r?1~H>doelxE)yS&ZA>@c1W=zis@TwHjmT8@{`sjzg z4ANeFtc649JHnG4I9x77fsnWNmubIQx?Vp%r~AG;yc)P%el*@T(u_sA?JR|=YD;C< z%l!RJzjYrsw?K00St4VOiiV$ll!2P->L$9Ce0Ny#_3O|H4en+vc(^ra%#1O2urGI{H$g zQypM6&I&4Vb2Ir5@j*-P1q1aG{`X25JB~SqmWXD8%IuL=DLu5c1!w zZ9@htm;vOrpUuzk)F_E!;)&_q(5CwmNOR>*J=;j(44Q8lU#pF-g#ZpYTVm-}B7+KA zA*lF{b;Oty_`du;-CUcLouWBupYUmnxn?Uq2$pg)=Waqa z7Tpx)dTu`FWHKz%3cyv!p)Y8Pv6xzGasPd*$dXYMV?$ChjyMdymcgjaSY%KthAEITeV+zQ6C5D9vT$P?GnMM(HE*j-v`AQX{3X=o8&5uksfQ4#>Kf_CrD zOBCHw6n8K!{u^{OZh!)oQ!7H`<#4aI$;BSNQ>v0Tp=0OS9&!qHl$js)w}IFEltT1!@r20hdZ&AzH17-BNB$(!b%TV zfx$ht`>}U3d{;nI;V8z{eN_Q1ymh7!|lP{ z-Q9}2ySuwff#UA&?(XjH?#11qXo2Dm#o^I=zx)07f9pNgtT{vGWM=QoBzq@0NoE16 zeSbn21c0^vd;*CJlT&v`YQS(wl90y#bZ=sYQ$i>54}*=aVmrah)+pyG?1wMF?UXfM z?}H-@5|iDy#8F5Xr0*2yM2jv*J?h1}kj7qjrMU)nXNx15O3ZonmMOq9jvR45b3VVV zNNWm81Lr<%EW~sku#Qr9e&BxMe(gs@r^t_n2ZJ~v8wA|_sgT?OPzC5|3?&hT-=DK^i~uZ&yz{#((vO-1bkd5Y7)i8RmjA?q8;Sj7 z4M)Dd#I7`djPBXJ0FG1Gz!jcq;TqmJu~X4rn;wEl6Bcc&z$m7ydR{23(>4Y-D`>}h zJiq{)ee~2WObF2Bq=rTBaFi^d5SvL~oN2jg7U~QC-aN=AVhNm_d@YWx7S|GQ%$Nml zZhD)kS>q^N_$DF3xw3-2wjDad_6wZ(f-nwFn_x9pYQ*jyrw;!!%K)Z6dDHxt_a_TL zv%dfUI0`ZO%P~N8^RxXk4uD!mW$-`rF}>BAy{!hpRbDy+$g{JUfY36|AaR>X$`c6z z&geVvc7WKi%5%!-1yKXt***avqCZiAC;#k$sN`qTkWUU|s-d`1c7BZ^20^V8WX}tD zW(5n};+wH_0mJ{QB(G`ruQzU;MOHw?k&G5Lx2a&9THoYCgiefuiBAOYmSf<*) z^fd?7`m$ejk5U8ha?fE%9iz(se2^d&f*CfH=YLz=zdbIIa=F;3v;HrsLPri; z+N}^Ugki+phYgrquJ%Y$m9S5xM}R|?DVTh<$H0{%;No}aD@*_gWA8zA8oymUP8=7Z zxmIiK4gge~`Nn_^339a1{WvGqKKF(3uQvbyXPG6e?`9fiAKU;ZT`wZD_?XiL<0;gMbdUWwsxNXVP@#wL#7jU$?19&6|C@W)N4c;Dn$r$W z(ufWAK1aL;Im=P_+Q1V@pb!$VfKuCF#CPHN7`X#QC!zu!L{qCm5zS*OvmV??RT?qb zLc$$!fs4T{vcaB&P8ia0LHVLP&)YO1KotCAjI`BOaB%xniaBly7++$^gBKH4#&PS;Tug!sa zxQkV-*6#MDD}pvI8NDQXB3La0iA){>(6H9di9RqyilOj&v0tNmC!el-ZSN#qQQB3h zzv*G5%;2CFs2w%(oSy#B#k4x>EGqnNMh%{$8FSqO)g9_i4WC*3cw3=j`~l2vI?}G` zkOJ_Fyl5&T8`22Ll?rXTaKz94k;gxp#ug$83e7~P&+ejYK$NV~ZCb`Ksli?V*jeO?d@ew3kj#e(coF_yMu#T! zNDtNGA2K~b^oZ5YMeBQf3=@6}a@{ul)?@%L5RULmIA+g$RZ8>DpH)KPMJs4p4&o$5 z>Ae(U8Nfrwwdw0|DgtLncg|^s2L@e0Ahn*t+8-aTuLRwbSB1^r6CC_XjiU&XDA8mY z_S2LdJbMxeF^u55V;2XnwPHrIF{uRUuKv^7k6Ubvu;2x-rgvyNls==(Y8 z9*f*}qcOiSMwF}7KT!G}s9>!b>uOpjFj%174jmnhb_rs(bbe|R)eHEmZllk84j-&W zI758D*oFsJ1q;m#lKZ6b3TvYP`@rpGvWP;A?*rJ+ji5Yj>AZXnI#V?w$I-^?b%0ox zw@CT~Yf>e3P2JOV4ZS05EvNyjMKH#XZeZz8op}Sw@wT$~ukZaM26DsW$CYQk1 zNrULO0BFxeButV4H2_#x@eR$_*%yD}lq6gJ$C*DtSW1Uw8~TBt>odZ9`{Nl=_f-UbnZKb1DX&Bp4xex zyL}FQJN~^1uw@Bg&AhX$MYm_g)t~%v2?=t!vQfHtMWTA2vW5Zo%4N-cN zz2u#V!Vm}nd!M=lgz=dGQU6y0VE%!{+W5H#T4@6S;p73}u>PyGlqD&r7*IBT0GK#s zq@xv?VT)h}fj<$bpDC*6Pv$$0XWhtG9QGE0<)c0b99|`FMMXW3DlZ<97n5 zOPIXxpQ~h9%v9YeNiCw8K7!YPv|vB^6EihNG{p@5ek(^oH5mPVf*L=_QFpd*0s+pg zT)%_%`3eB4Ka*zC=^tnLi5^HA0199ChtPjFRKou`rUtfy1VHA|h^h+wClI zQ-~*Jacv*c7C7&?UVx>jacixVx*rFIG=a?luiiZfkwRL3%$Gp;^bml)PrzsY2K)&V z1F!EN0HZel9Q{pzmZ-CMv*=l&B;{&0R4siv&a7rUCi%$ zc|^Zay^r>4*_3cjC5lly$L!ScBrlV8!&#+DJR%J(v%pHz!CU_@e;a9&Gn9pF~ zAmAJTg?pXc8mw|5+#>+|uWZfX^PiYK-I;TNc8tqpR5)1+ua`#d81e!a{FPJ2%<}c} zt~oWJTy!qnJGM}Znta;=;~}^4n`FaQvn|x{7P}I8MT{is0Vj_huWJ~Df=*dwGPg^Q zhODWPKId(byYpxPoSaO6KkpETuV9AHaGrqnUw>NU%71PS%>SQW?Z12i3Y01w`DP8oN%Vvf8a?AMx87Z;mGiIUD{0M#$&t1NGT!pn9S z!eQ`L(T{}GskEL>nWw~FOE#0U@CQ~{bn0Za#R$RctjUO|SkiQ%LeaGbWE*Jc)Om|K z?bDr0V_)0}>Jc0EbgyR$yk_D}6|9fU+cm=*w zpOXQJcRZB#PU8ji7&Y2~pv$FV@>s_i4Z}puU_%O@u{9cVy3WKol|!kbPYx0aZ>AqX zL!s&=HJKvxFT{$d>#piYb`_Pf?*rQ4tsEKSJ-4s?v#o6C{qk~=z;woyz9}(0+YB9q_n`KLPKxv)8Iu}hi*b;*3|2fcm&HPTP|sykkEg$t zz8Sc>O6f;>2=^zqr3F}%(%ilf-F)LOP5Cy0ODNTiyq!M{Wg8U9VR;yxk2~JY%ox}Y z7a+lBA&g~F8bSl(=g4d5pzo5CgRY@CDoHPH(mVJR^vnuvQR6zFItvDjg{3 zmpOyuvi@-%ajL7(XG%Vkgkz(VjC5;V$t=#Sflva8Hav)6U??)rqRa|lO_j1S<-64- zXe8l5D)|ntk`RQw54EXz?uH(-W`;nEQhRClaBc~IIoa_B6RGoRz7I#sA*V!2Q7ju(2Z`_PUuf#{h~kgX1u>=gYei?-f^j24%mcI zaX|O1(4(@X0*APDek@eP>YKdM9(^j@s9;Wrl~-N>Uhm&IAAn$i`#E6C4;+rrQ~)T3 zX*(R7A*6|4Ar#fcwbo!HreU>x&szzZhny!P)JBIwdF>RL5AN+%4LwWXb z`QHP;jX8joOpSxE)Tv^Dm21t)$b3aI z)Lf-V2z7+!W$I!49ii-uUY~+FpTl* z`ujj#Lp!Z(Ntu@J93*d9^zgQk{Bkf|N3t!8p<&ESHIqGFELAMWyOctRk!_oLMB#~Q zWRn>yhM$Rzk+(0n#d*YflsvHgyb?t*eiAA2 zXXUmlXBV2eZ4pp-Jx=(~w^#@#W^D$!iRKTgz@4i>qX>$KdR?6-5ux9|TLBcyV3PuK zjkz$<(3aN;R#-svD)94S?Z-g}@(>;|G~M>^i#6W}%B0ORvg^Z<1+H9{bBz@=m%18lMT*i>aJHxvt~Z>LZEVA2@MW4QX!BGV2_0_YP) z%5Ed`Nd_0I*zbB(k|+V5^b~s_(3t)kM?B zAYbI`syG13{gY(VC&{RPOW+?+fAjf&?17+w4w$1%0Dxy3i6elr9{}XjzCj#?5#!AU zpKavlZsY;MZnbn{~1Wg#^s4TAYv4(4$1`@ zXe=Ph%&h^-E_lTrLZfP26*3(Vaiv3_}RITvUg zRHJPR^>0^hvoh7dC(*R&krSDm`OC#q3Z)i>2sxQZIQXIf4lEY_o z42Q_HG6Y{yP+3l;Hg{AYt!HFV;-7U;>k@d<0M-HR&)a>>EWt4NgV2&{V9`fxn31^Q z(E}PpxlY10^M2q~2n87C-Du1@g%%SvGbx(o0WFnFb`VaQ9;n@7`}i^>=w0HT2Z<+w zx*>Xl=!B5SS~O4u)dxiIVmfK>4a4bn9NJ%2-x{dyy&vRRh`3Z6&6|Sxn>cnGkgi&d z!gzTGFf@ksUwiE!dr=k{H|%jLg%}cM(CNnd^6dM7_+7^V7K}Agfj-C6LV#y_M3~Lf zpTK%Ok+$$+2%5&5O7b2iKVR`vPT*TCJP#q}t!9k1Tv03RJL0e|@YJA0vT@5N4k2YE z>B;;LhL&OngR%%`2B-?eI8(sw?ch5@P*r6{yA=fZ8H;y;?eJZaqUM&OvO_iu%0dhg zI=&?}Fzx4mY2?j<6h>r+m$!7}x;CS?&C1n2c;34nKS>D?mzEsTi_u|TV7u56l0*>Z ziO(9-04^%8(`$Lqr3339_01#B(lxI7dS3C9t`cwco}zv6D*`^@F{<_4w2WHj7@R_w zn$)o503Opz15$uhu^LfOCxD}Iww6iXFF|h}$+$a*v8qJtYDHQ-b18Cc3}K`Zjfjqem5bCcsh62U!f3L-D$cJ$aulfTK{){>@Va5>Ct0E3{L2pm6fVHpV%L~HR^sVglSyjJWci&AeVo>>GX%z9~ zzV~ZAIFzIH3QU5=7*ev?WIV!}1@%Ar5*PR2Df~ogX;V?qF^yQ+`H3l3+IUsxy!h;J zS7PHUd_u0^o>Y+VFf%6JjDP?t_Iz4$>;uSW|J&#P|Jr~G zWdNUZZUF$qOecMbL6mNB#C{Nm;(Y9W09wA|OOSHEPYM24jKlzdjD*X&y#niZR%yJ~ zQ0I{8cKX{2qjfrCJQ%vNw(#JbY$Ztiy>Vr>b0RlVl)E_^c@v3PkKIn%YuxYZD@kWa ziOCyj1&$-n0ZnDFDY~F^KuUc%TA+7%;ESK&yFbCp{99}%{<%GB-9JbFg#%{?5DNwI z!|h{&*S4ttl|3>vKg$f>qd-I-1^}1?wE%0RP6`1245E|~0676bECPUDbIkFjbeK&r z)ouh>D#={G)Bon{PqDWL##vaAmuMR5JsfBooU0Pd2L{)1R53n&a_0Q??XE031iB9+ z4nEgc>(i+E(E>i==9UvyDDb+9#<>FxFW@@@xSyjvEaR42?Iy>z|Kd_>;x|@@jx) zbN~R&FX&hw@(+HHTLz$Q5So9ed^Q&WPuk8VQ6EAAp#2$}fdebDrnwaSCwvx#9uA$3Ovoe0`xbY&lL75b72q}(Cqox*rU<)8S?#Fqf)_U zf#g%xE_uZpv!8nZ=jH1JGt$8SZ%gvOS}KrBo_IJxvHSWIlJA;PxvqLj&PWv!B{$9B z0=rH9{-H>N&<8Qgm@&BD*UmEa+o+z#S7e#@`&(Nl+O5D}-@&F@n+P1shsgks^h2JB zjM&zYi^~3bo-RMH`i$>~s|o-WbNzCZEMv!wl&~2zbJuVL?V3`pf?P=py*}ZmeQ*)1 z(J300h|-u1!5fn`dr63BYFN}ef4D==c_@&hXM@eKx+3OyR}Pt2*sOOdx6#@|qSg5j zzSi8a=7915NKt80krfb%RXWXMzi;3w?i6KeIlvoIg>W`}yeQ})5T$9U3ofE`{2sa~ z;m9uxmd&Ov)@!^ZD=+oh;G6}h*K{RDs{!I&oFImF(X)F+^k5I6p3TE_fXFFZ_$Ztj zoOiu^H@+%Bo_!q`Fsr_Mi<>yBXME@rxjM>=0gtNf5cbDS$?ttpWc2<Y=wW`BL2AiWq}`?(AV2IkSAn(G(D_& zCp?Cu=9bReo#Q#wNn#ZAP`YCW;w1y50JvEvb5+X1Btca~<|Hf`n3Lj%a#%=kNTxnz zUHJW7Bdxu53xuE%O;!7=5|v`S zut)C>CMO;5N~EEN$SJzGzhkG}a#dfh_eCj=6h#nTD?HpZ`KKNo&v59%pNJ+;^L7FO z(xn2kr_L-IGFFBJ%?oF_8_ZhMjBPcU$pIf9d<~w&yRGi#M15^&cS)G_sEaD`V)Rf0XGL@xP4RJFwWH`-zS|%^S zoYKiZmg!%P2~h7zK?sl%U|ScST;CQDs_g@ShPnYj(c_oLiT}=|AP&$dxY~A_slmj( zC{yDyyOz^NpLNDtF!Ow$U}D8{Z##$KFMYga$}-fb>m41IcVO(8PQILcX(DVtHyr@X zwgPz3yE5y}ts>l=~wGFy)({(5$sE{!7iOT>&Pgzjd$ zIdGLQea4T;9xNHkp%Z3egQW$sjw0A*y(JK_yrAV|kMWywN(qAkY1JjZ8&d4#f=UVN zCPz3FAw5+9Xjywm)Z37o_Vl^M=NvC(ZCZR$k?Qfun{K7S3wg|}Zs0p@HtRz5l7q1M znr3zP9O!jCn66);b}8!U>qJU=I}|uvHN$CTeiAP zr&oTK{?kA?wP*jYl4vgH4iiT@E|pi3)TbD}HMFF5!rbr|ufYGUjzo2Z8@_;}@U zkdAj?IqZr8n1}!n$G~)Ok(4&jq5s5>`m1n-q~$kvDyE%`T{q& zEY-tZpU30Ya6(1Oz;uxK4}M9DQfq+K(=maWLsN)G!8e7;|P>~UL+9Pn-1X7hCZ zmmFRH_4tvhUwL(yNe;nL=DkOI^6am}IVq1uDjtxh*8YXB0?n2&?QZnULtEZ8%>?KN z*93~!k;WAbTRS>!ouD(|iZ?=V+kOHw77u}G%2bSG5PTPa0%+4;X@x+q3PCQj9|e}s z<6D75iWh(Z91Acz;?%bHgRGY(^W%nQJ5$1b&~02dbPvOBqVcR;CW-kh_Vd?(*3N2* zh$}LWdu$}xFR#WiwN$!-3Udm=f}j=VMB>)e+2+i_MeDrh+8Ja3e?L9edOW^pYv^{K5nU3jI!GFnZJaG*^gyW-Ml?L=I_I_{m zx?2K30w(7ZrNB3}!DPU!Iiv^ALij1Woa@75O(g&?Sgrz0zrfLO z<64iLg~C%-x{8a$On#`&70!M~Lnc!^Q?HewhdodJAO+!Kq!xW3NEYio0*a_=ZZf+m zs^)@l<9y&y*_aOo&W=>z0u8t@E%I>B5UYrH1) zw@n0H3?()2E@83+fNXvb8tk>QGC^QUIbaa6{Y|Y5Pocm!((YKQl1}Pi$o@mH+~$7L z#y;4A4hd0~(iNvL(9W^Y!&IiCU%F<^You0`AX}Az{-h06rl9W|UytVYn6W($Q$P(c z8WuIA%)JmGJ#%{(M!)hD-I@t^w#gI8e{8-J{=3Rb5UV{hEbtG6j2B-;%2B|$5ob2u z_Mx_}4~c#?ShkptCprE&OEF3`ng36sMBI<_=eAdA&H4wZ*5BupKGs+He4f8E3R{%9 z44em_Qa%pz)|82GL{6b%N8Cp@vPs9=O52RO(PI0<0t-6j&lWTqUvPY?-5e%He)|`y zi!-=xY-V5sGtW>lnBPRae~gzAY)cNXf}q}Ztb{D zJuz65gz=pTAHz>f*g^b_l;2!T^_<1~RO2-F+y3Fep(C0<`thBT^|^9wcywdTsb)LW zq)OfSg>1+-RkJcVBR*wgv)*2`mYdzmyQNqGR<)p|3{erxrEtxar4J{5Tj6x;>x5h# zUX`f#d(AWXWAAodqXbRqIn2sYEd%%1AcNHrN^MOyi%;wV8Ef6l@{)`4REvp+PohkW zk~ut!^|#yh@B|HB4Fg%n2Gid|PipD;*_rm{xM*;>_tePC#Y{)SKVLzA4~Txw>K?YB zYXx0TFcSvbtcoZeW<2kaF1$zX6nkfd2DM`Qh3%aseoC)&WH>9Ne=j5x>e3J*_Y04N zo%38^!@KNexzz^TEm`e*VXS^HhS-WX`M2!tHq^boW-=~ekW3dtSRKRSuBqneXo!-x zQK(DY_N=ket>p<~PjjLMt#O_sVLZ1@K?B2Z36* zt+EsW`b~`0BltgtB8Y2^H^B44E(}^1I)&p5v0qVN{eK!8*5y5k6^pF=Y@p14`R45` z{G)n~A|ARo2~4lqFNK?)`HxAFX5MA3H9WDIlFi2q(E~yu|oWv-(tO8rLZcSY(t=@5oIhp zyam4*%BzmPK5etxaOnE&S}%-3LW(mAa1FOHhpLM}jQW9RY;8+gX_S!*EO-|y%0_Vy zT;DY>GM^~@NDsQBBK{x?X~25DW`#tY#~UF8nvh$jxcO#EXnenkfu7#(K#wNi{5U|P z6rrP|@Xd&I{LNdUmonovFFrB!! z{;xe!b6ByR=G32>D#HkA)GKn9xT?kLMQ|W`ZrCO%wVpnkD=(}(>(C3Q+bp#P7ne z8EC1%ixIPyn+O@y<3js)55-LawK)$_cM$aS^cyc)na* zwJ=_0zKxi_xHO3l9N9SN^7elaQjOEmiM(ioghAlRgI#A=4ewUNeb%t36MCi!PMeCO ze=ke-s4S=`$^>AzT4-A1UUOneM?E=;LHizN4A8OjJ_nO^i8Vv3mp*S3ufniezx{9?EetOD{c;3CRTX2%+v5?+Gae&?hBqg zqZ~ivG+W^@>LZHVO1jMO)L&LQE@*?<*y6swi>R-VNY1E$0tE9UPOMb7TxH*R*3KOnUeWV>_uuj7&Zb~Ezt>c zh$2Ar#f~*{v;>tSl`GqAdA~xbdYnC@Y41M3F}rqp#uD@$;$}{(25!)Ess7G+uo8@@ zOvoMtF`@%*nILE85d-tb{d6Yos>v!-`ui2qU_KKhm&$MO{u9_!`3fx=(K?oLT`A#u zfL&4~QDAr+0YMa)s*mD4=8>)(@OtgX4%2+%HJLQXxDm_jSQ1_v z%c{mtheg>6+oID4$Pc=l_-F|~(_9;`aK-iW3Kjlfyu zqU)B^B-2_911BYA{bopxDEz|~tIm?>k6S*k~gRUE=U z2FV4yu9wNdzMsIPgj85^kJgc>JaWq?ZlHByNHRNV+~^Y9Q{LoU$OJa^>&mc0yQRZE zI$edg=2TNJXzyjssn|sN=4`IrG?FIP2AVcM*V$Pc@aKVDK`rL0ev-(qX zy>1_K6l4_J8hv(7S6KB4LcZWqw1vNo|PtQnRgJ;r-54H?!-o4K28L2o-S$0 z2(o7xG{4pQe@>ZOU<6}_L#eh6oK!F|TOO(_Hlg_ASX5&WRf!Yz!T9LA5!!rP*cp>R zplXTp&<-nMjjU?U_PeKJ#eTsZ%-#s6XABP9YkToJS2RB5VUH}X@>195boRX_Xib5 zOPcq~UpLcdS^_I&OX!?VV7Dq)GsCtP+_9i=L55g*y1U>;U$oD$lNf!@Ax|qen?YL2 zXVf5jPw2D7V=NR<&(dTtZPJ$NliI9g1?#vlk1ps=fCYQ@l(O9F#psE zTz6EQX(%?d^bqrto>ieR@WqA9i9MZp#oSV3lmTZH`*4T?&K;%8Y9RlJo{N(G$v0i? zDP_N^QI&0#PN49)+-4i=?`@&(A)LgYJ6|)Cs~Se#gvQ+M@YSzH1Lf|Ol3O1MHazC0 zCYItt%S*IBA~_}}+a)I1fuqrw7hyG_--jZ$gSv#ssj*8frEMK5e0#T5h4%|m-%!b( zPBV&}cJ~BcJEn{%h>TE)9A_gRWS;`axJeZHnQP~M)Xc%_&*jj@Mg`?pE)0^e(NV5R zs{0}zkbNEa0qS=jZIbsAurU}Ev1N<1=Z$WAAnHUv$oA~A)V_BfSHTWVs$Z!$nbBB7 zAh_W?C^rBCw*2D~7>X=Vt~^j!T2$+VEP-)K>0vHu%+TZc+saEsb@i{Agz&Wu#W_bx;Ts}dBMcj@0Gqf@w()HqC%vp*L%@@mrpgB3WoY%yDC0|WM z6E>A_Q9~Vss%U9XZc+KElyi<7BTqMURZ{$txA3IA7rPduO}mr_I#*p)RS2;|8A{2` zNzaa`JC<<)@1(iDBX07(MV)4AA3rlNTd=LJ|L`0o^xN$?O!PJ@5xjM$-2-oEuW*n> zA}jJE*vRgw&Q#uNP_P1;h+gQR9rib+xRSN#9ciuzkO4gpR<%CkjYUwwaWpt@l$3ds zsU5Y|%WbT!w~>1(rlAWY`x0K5%aJElO<121f4aQpQ5PC+(8I(T9mWt>R%Nr#a@h<} zrW#mQgio9_K653o*;qeFX>RlPPQL>o1&rhd`c``cP3mD#8?A;}R zXsvp&?!_J(zz>hZ-&tyaRxTRs!CR<5q6`%LsMKw#*%ZFaVFp8+U`CO&BH!~@1Qm{U z<|UzY8)S^2@u4hP`QD>ZCjRn$dMM93^y}dqA3-uU(f-;S-TSs{mdFp>B>B_j;Q;Zm zVgovTKQ>t2AMVB;oKxCC_^Q{(7?EDUI@x;F$INZ;%R;@MB?(t|g2P9a=4T~uSKNJ>lO-%eu?jZb9;xdxw?1_0rhlDBs62FRAS86&|vzX>2IAj)S z#>P*ndpUfZvo3|=ZAK|udzfvD4m>41>nfkP%0H|&_=9sDzvhr1CwjQ%Y$`9z zAEMYf>B@WGNA~oi+{u!<=jMHI=9VT9ul>lN*%+lNgAM)Z7Ys?W9Y*QnWVL)3R#II$ zN>E;OY`V=5ke!`~KT4=3QXNI!Q-TJ442g>T*i;zF0!tnLQ+-Qw_PIF9kvcNKY}n@1 zx`h417+Rfa0Qw6$$aiJBV$JZj$i~wlMnWr$CdVO#aY7KKn#6h1Hw-&++gK(XIq0)_ z9MQyvruUtE0%{%1gM!u;>R}BSTdg-u^N}WlOi`?7#v2Ly-zVl<(n+Db;CkcgDk*#& zw`kU(;vUOrSEj?D`v9G6*!;!x-u@W?6Q+IAbWg9o`^XDN9wIxB$? zx$}kXl}^R4?&_=O`eS^KAAKj=XFo{&LhhWDGom;m7RtRcn;b^KX@XrL?=r%o5e_2H zOE)Vwp}$uwN$bbf<8Tq$kc(<`+|RD<_zw{KrPAIXGN9$*7&YD;Fd3kS@x^$xmd+KR zfDpSaQNKkrEsb^(S0C+?5-EFd01U!{mum9~{k|GbKlGSRH<7L;fvar-0}^1=qV=E= z7$>dkh4x&Y5f|nBtP2d~_2WiroyhK3=)Kf3N;@7a(YlZ5s6aHVYSC)^QGBFy1U*ii z=>2$yJu8V+PhhO?@{NAP-5-+{a*VysnPUng`#n z&Qw*cMy+DIPxay+ss>Oa;4|8nA_}pJpG@rFI{4UZ1D+jxims)yODl3{ppD6jRp1+P z#HK)-oUc_!*3%8LKuE735YXtKr%w4<`$~*0TvD(TB834Obj(Gld>>w$-4B?Est}!g zPCGBPop$_hPkSAQ!cfKJqP@TjM?Mj%GEWjj`y&H>KY)0IlVOH-S^C+E$wQZ4YXzeSVQXfp`cp@GIniM~#%`pvXWqcefXoUzy4SyXr;?)*yxEoy@ z8)`pDY2?mi)-Nb!UBxQS-Rry78^d4hvQ7BPz>u^zzBTpUWlFl~B{-02zr1JgpFT5p z0mX`Tg%1R|iYF!`2-LK+aWm^kt@!v`ck6Ppovg>cC201Gf`m?gPEr&LY(}Zw%Mh8f zWTeOf!XPyg7nz_FjU1OV2ZjdUDHUVx)3$6<82%GbZ|^w&?vnbpddTmHKCjy>@@q{i z4XmNUn2I`HhrW?7_jXJ->CvvCk&QSK1p77{*IlQ(%@lyU;r&6^pO9Ow98o|I926R@ zW0zopK!FId!P8^&v=tf>(j^_tx;GR|f&_-?yyZNTtW|fWby3Ot_BrkcGDd9}uJ_W3 z(WR0{;2ROQBjN$ykwvcBj?7w-xeE%R)Y0;3YP&%U7clK0q;*JSHJq#_?ggFt;%C zpm`aXOX>WR7**rYZi9MTRI=nYPdsxa20DF(BneO(yaS_n)UD&}D599p`wn#>&A+fc zcS3Uc*?*uj_L{y*QsY@G6q)u?%c)10`0|Kngp9<`3g6@lXt3S}=t`=hXGAQJyksF1 zoO{j*7Kg07`j*RBT0iJLK7#^~X*&rTviz!+Ao$AAET~Tg?~A%n49K}?=x=UIy&_^p z0+23!1mH)vqPbh!JCZ6|>MHZyU}){VjssEsnX2e(U^P_p2N}yV$Pa zZXX%lO7r8Y)t}#2_IF~xv zLuvChT_kRoI6~EH9+{)eVC6wEzQXi8I)^W|1dp%SeF#VN73urEI%QG*bdad-gh;UF zi+fDzr^Zp8bk`u;u=T5($YDgo!$T577-ZcpR0s94gP*^m*QT=4+IIkwmdtne0(4qD4wC*}f1ZeD+e5WcR1v@b({WyNnN z@V7%UX)&H&!%zTtyj^iWc5aKATrKKh()+wUVHN9_`R*9H3vw)FHH(T|z(XB})h%As0<)hCX0?bR56sm9^-zd&f|Ebc6ZFMd{WmM9ua_iR7GW1ASFWMc?6XlL`V^CK;)nAO2mL@m`+P-4cA zB(K?$RQ5z>_#;2POOB0MGdxD<$bfhgc_XsvN*$*(f}uf}-oxow^t+My&PQN>D^#~B zt4NDS@lr{*BcibFIBCuOxSoI+=HMq0*xc0v8arKWmDVSCOeYq8kW={B*pIn*H4|vi3d;fkLQ}Iz#&^F_Zw(H;1}Ui*P+s8X^LzZF6egG>*D4 z>h(RSt)5TJzI=GLy5yHTs=^Rke4veVq}P!0T(}D2t04X0``)+oT`WomBT)vF##yZJ(ak_?p;RDO}~by7P> z*v~u+D(wG?vhwaK%XWG2*c~OKdv{9gPJz%h)OtPTuv`Y`iDG4b4Cg7( z0Xpg{(2g5oh_Xmr4H?R$E1r$~6JqvG_uVR%;Ox<#5b8`!^N&>p{T!`b?o2(f0d#EHCH+yI7 z;ABRmqo>sJR5TXzzMtN9@xU~hrhk^Mp4Z>V-9MMX> z>*4#b^JWM!hsTw`6wBFUWtq2QOek?;*pj=vE{c4gK=_qv01>G^T7V#SH20XudkDBj zltiCP1MOO}-uQKriD9ljGRaxYWgn7SN?em3aNz`xQne}wg{WE=*IBu(y0=i5kmD#n zp?8g0Yqx+WeS89JQ6|mUxI2I_+%&tB^3evFr!o`86OIa40PWP~}G!p(|b!^RL?xaBc zhSlUn&y63}lMgFV(Z@=M8{}FH}W||&^mzz zwK?;WcirX5qJXKqo}clG!OTv*ylzQMQ$5&=aKWahc5e9ln02hDmEyjoz#_qzoqKYj zXofR6kD=txGO0ptP&7?7&V_@x_WC3YT2_uhH=K&)R<~sGNb9c=B!p@c(oU_&_<@!K zMWsp2YLK@H*6P;y`%A)xj*)3^oWDe;6c$C^Z-=f$bi;-AL&ac(VpgX!iSE94!cHA! z0`=Y4j4LSDZ($FL^eVo5Iv*YiXj~7ijW|21Y=+~az^7T$g%se zpO%-CE?qw7C#4#=B|Cl-AqZ}|>_acxQv6kH4;jwWb#Wq$dpFO&g2=@ID^*VXSyV-8 z^h8Dp|BA;_13yXvsa2MuN24r&ydZCnRo2wo2DkJ{>oNkM9Zjok4o_74_zK%KDhJDC z>a(JzhFjU@8C>s94jZV|znkp2od5N$R6fjQaP=tSa!}JQ=^jW{7zJf;P$43@H&7TM z$p%!UNmjr28XB`7T;~vVKVBUh6?{JI%N0|>)TZ5X>2wR;)u^q}z)ybPKLp9Y#{7#T zd`{prD0WGhPrtyTps_E?99hK9he}5j>kd?OeB-ZE^e+9;UxE zxXn(t^#! z9A&cPv%a~+FN_EZB>^tHRxBCbWETx=IruPq;#1gYSUGTi{jYJVMvx85A>rIl;dOiU zF)G>wcbw?0us**-E#w_FWHGk3p7eU2sDlCHPZ5ZxP(#iy(9gwU5)?=v_q)#6o@~fp?5dVA{($g$h>TDX7!8`mINWA{&ifxhcF#C>A zn~OCGT{>TmDyS=~>uY{3$_TDgMUbc6Op#`Ok4}!f?ueRMl7vr0i6917Qkfu$^md^)KN^()+#S2JX=^yf?6}lHd&dEb8o{xjI2AgQSW;ookPuqtME0RaB-;5jV zQZ|L9Y-f4_Umnu!Ez@t3G}OolGSseMD;{xF^|kxTC&ysPtUOYqwm$t4vWd68f<7vA zS{4c?;C+}PG5Pe`Wh4jdlFG7EjiG93(b#ec$Yweapf!(n$d=q7j(qFq1)FEJi)}|i zOix8F2tq%8VzxO6!A|j;_&3kcT&v4{l9=jw>baw;=ws}zilnm}LxK2~Zp26~V?}$F z!--p>*?+a&3}@2b+jm#dqjmi`6jy26fd=)CBwT~P%HLYNa*^(UB8s|KV@Kr>- zh3<=+l*ji8s#P90Usjgx2<)&LjR$`kZ0(~rV?}#0H39KBS z?PCVZ&8VNqnu(Wt_!8Nvk66tZF<$zIYRK&?b9Uxnl7oi1g@ry0=r&G~-xzaur-i-vWHw#-p2*xSe zJH63M@~sTT7E*lM9|Ckpq3PNsa_Nz+#WU@k{xL|VUO2N4Oxrlf1T|?E2e5K!pl2$n z35`_L#jVG968P9;{Kg0l3*{SH&I~78YsjrjqS zhvj(YgpzkeUfO3tQ*pw0h65AMpzzt5IC{mZS8`SRfIYSAwB>o%2mO;&<$K4y4zBOJ z$Kw%goF;_GtQ>$+Xv@#?66ll*ro7I)`fx#^E5m@sgvpk_4m$HZKjsTofsR5g)uhyqp;-O)0w*mplt8pb7i-+>>g)|7hmH}vi@H5A z>sF0(D^J?Z%JU~pzNz`a8hvVla<=(%UgtYEJV#1U&@!+AMS;X+gkk|jV#l^nM~lCn z{&qKWTzEB=YCH5V+?xJt`>@9?S>o3CSE)9URQhM2T&(3AZ%j zliGP_->OH;UgG*5YWio%RQiC*@t{mK+B&R64f zEJM=#)fa5ewx;Vs%Y`oRQ_$UquZ!KEt6hE)4r?Dc!9f<=y^X8x-R1tv7;#7^dxTP$ z#f84~x7|I^>gwP=JW*`)$lV_rfj#WzHA>blNi6n5ND(;zyI*oVyRFc!n$`C5t4nWD zkObmE0fdvSyOB;etXMR$gWYPPC+ejJEb4mG4fOVDwR8+`!Jai7%WX(Pom)IMKHBI` zLd4q%lk+dp!x!17DIP8*L%(5o{&3|a?MUEO9oR1Fs?sd|NF5`vyyYOx#lizDnQ{@> zBbN?>%=IS|E~S|`>diie>4tt3qjMfVW&2q|sZ{?kMcTTT+Znu3!DD7?;9(SF)T88? z$=YOP##3^+cQmL~QR)dtRv%8I&d2v3Y}9>6Wn_B8UAN|^+H$i-D=Lk>>=}gVoPEhm zGIVPkr>@pU&Vq#bsEyYIF>24lb#_tw?fk(bsf5*2(es|yJ91oJIGQ+EyVDzieu7{8 z_i@iN%oVa$tdFGB-FK@ggY{4w6@Qu6St zF^_w9v_=n`OEZx!pe{X?XSZS@4v0g)XR#h6$EvTBm?lcanhxxrKYyKN1(fxoq1gdk zfOWniIe`mL5>Suh*asOW37@g=Md|w|l{3v=>+Ifr32~)AkaIkEK@EGac2863m$^e) z6MH>l;~ywF9x9trIyG2Uq>JK%-jSfBzIOxk(yG^6a%j4%vkWt$(X5*f{$XV>8>gJk zEo_<@6DTSvnEcAQm$u{f+Y(FKHFCIefd^f9CHa#PB-eE0vT}&VTcbf(bt^MEP%hND zo^xeafq(2W_HxUM4dl+&M;mao#$sykTHW)(Zu>QMyE1G5^LavKzCVsTdV_Tb5p7|& z&KqguoXQ~D7G^DE=UJt9`48F*E(-K(_svZyEUXUOQc7w@@+24f{V3eJ@DbN1#$JmkE{|C^@Gi8oX6s&DbTl$V%Q~r(gLM8wDn8Af`Eu0$ z%dV*D`>mra!9sd@64iP<+4d8-N8WjC=9l7SI*xebs>(Rv$B`8fG7eI0XZ4($jQ<^m-%%)L&A81j+pH ztGh14|NH>^$5Lu>W~imDmP9TWP~3Ts0RNWxmo z`|r&a+rJF%u*jfuV*!ENfOM-k!PDS@ZmH_$u`ZHdRzSqkUWH{U^Mo%stIj zEaR8+ju`OUGK8t?#YZT9VG_mb_U&yLM!44GSg}e|C}A#qZi)Z5ReG2z0k4adu~xJjZ4q%tfhJ>+<57^v%q-*P^9Dj|qtL&&0K zzE*yXsM{fqxXahCmLE}09~Y-<#5{Jc*r7At?$J}n>mj=foZ@-(8VES?0eGB7k*YK7 zF6)8$GQy@=JPNZqPK=09z3Prd%f}w5V{0ubF?-7npyPk|Y1+a_s&|ET-vVupTFCE9 z2Se_7j(_#m9MyR=-w^wm5lNHD_HEP;P5#R1lJK?X8UxGv70;@7Q@!~lG$kyQIx;=! zz`~%QrOJ;QnVw0bFz>lW3S9*1mlw)dBn}(U`A9$=-+lW*R~VOC(tU z$ESV%eGY3)8dJgNyo=bob!dNl%K7xMYLnK<*1gt7Z!_J_zlvRm`APw zjkmj4f{EgSq-$U%jCTb9crBr1eUcuEUg58dYn+`6A3kJaZ#@0!sitHT=R_`rbl zzV!zZEsUx%m+Uj<>(wf%M1uSV`1&ZG5jdEfuqi}1;(keCi8NiA?Vkl#^sQ+Ak%4Q% zEk7htIxZA1OY!+^O5#Ph%E^Lqi7cEX*qVaV3rjMaMs7X>L@1tZ!2Iv8i`D=+n<2RD zx12!9kn0x?#>%OQw;|8FQiz*vdY0k#{9XQ_aj_irzXf5AI6u2A7wyJsjOb=HUh>b-H*#v3zU7 zHQQd(mmKJJKxUymn?~l-O@pMYx+Km+?EXH%>x#8^4i|OT58p3tdD@y7+>crOvmxW4 zNe3D_=gsMhd95jo^alb>L(q}-lxS!&%*A!6XPzW>C(+=#@U#NuQcgp*{HI!?c`|?n)<2d-+<~f_JA49kyfg4 zXCVmqLDVA}{H-TckrK{M*(+g{U1;k}Kw1=S5_jj(nf6oI`*+16)NmA29{mWVP7P2>&rMbJX$5z1_ zdkrAwqd0OH#*vCEXl*FOPKwHkKv|d@K-V7YGCaE+hZ%%6NyP&0DR?{d1Wtu&3kf;& zhviS$``qA#AC`* z=-7z1sTokGW-n~a?>l7vx#3?vriRzwGXhbvkkGtLpkNXfmSco5QlT z7N9;L0)4t?zeq`|ddB#u(udk30}?KUhUj|DW6Bs#(r2)Wgy2w&=0>y!rO0X`wL_u) zRsME6Fah&#l-1a!M9gg!u~b&um1!7SvgnKO4#Al;@})awk)&I?QwKZARzV|-Hw+BAX-f77214LHkC`3<0B2oDXT_Fd_ng~;KW%Z0n;jqVDjRbE5?d% zP&xxmRVq6cmc$*kK=LGP=qMhga?O{M3%P1u&X^QD0aFTVKNs8Q0QEw@Z7_Pg(J&8f zGH5+qDIJ?>hZgmd-kJ)tvg)u3J?|oA{Q!{>CCfW69$NvoFQmS^q;C@O*{A{9Uy;zD9&*1|NK(K zBUpYAguyq)7$9LO*MnNJJfLw?Ru)^{pU#gy8)#k3D~%wbyrc^;lG8lYI$c$*zQ^`4 zP`dem6rI@cElY4{iWPTZ^xNBKg_%E6tH^i6n+kse$~ z1|0;7lmt6oX|Ys1@`xN`n0fWU1)B|d6kSGY@g~j^A49x987>tJK4{cI`ckf@ZnSM; zwxUB5S_I{S&3RblYHmM0a-)Q~9uTFyebbGrA>b4Jf*nm4&6j?#!(5nFh2g_hG~oI! z1Qq7`!nQHkc}fF59gxR&z^jA(xhHc}0Z}EX0Q+Z2C{;0)PwZmlv<}w&uz>~7l5T;QbqTGaGEBgEwTGI`pdY+WU2=I&E#Xey$ z8y$B9KH|Wb97x;2BO*0NhCGOd9a)G`HY&XIxb(95F*HL) zFt`b{n}(iOEH5wij8gy*Z2kvb3zSL*IMo1)1Bucof>bp1aLRE6^+IFgWm1L}*A75dmrjq$j%CcCGx7c*~Pa zf1$3{Y*e>l8HeB_XXLK_RI%g%ssWoVH=g#~_7V#oflvwu8oHlOwDcWp}Th^i8;irHHD z;?YWVg)ap@`AK=B8n$HrG}+nRK80!*3ZI0R*Z_IT3CdXoaa7!8E* zjZ!tU9VDG-6_OJTsBfQH2E!cEO4HX7=y-+9VGFr?GU!zB!gy-fs2wq}_`}{95a=P; zqIowJ+nrxi;5v%k-NMNy$?rtnc%a!cWyX6S-V+Ck27=iT?hUPXg8k&0+Ow~zf%)L@ zE+x3bOL2Hk?Z;3C|D9!S`suGw_PwL17>F`CZgF~JO%#ZZXmuCM{@H3=0pJRCo2E0W zlv*rmV^h}+Eu2U4y{ z$@uevG<>g1{p*b3FYmJ#+TjT+Ph`#F*0qH6fNK2lDm#ak?C@_er|vfj;@7GbCO6|m zKaLJlCOPmAV0FHw(Nah4oq(p2l!;aw&P4+ZTAm1hhAaiA@a- z;a6=WsD3~49{i7Ypzth?L*|3D`B9VG%6oQ8?L@M*7>FUX8+(=KfZ+Rr%;7{aX;8*w z;i&=bB;L3Fpr7H*5)689u7(sW2nplf8V`Iks8)w?OocIpO)(O|vD_A|03vjC06HK} zs^BR94?N_F|4V@KSwR?V{=aXN4wI6<2CS55&nMWgvAkdgftU&W7a{NiiX!2bBfr}q zh-tVR)vC;$+d@K3U>J6La8l#c>mNnCxk}*bQu`q2qraX*8YP)U1&}jTUdh(|D-cT2bN=hxZ{Skb#R=~9ZjTGgpU>w272wRN4)eTBqty*b%_Wp_|O%)ne74GH@kZSsNT&h>}V{MZ5F#}H> z_S|5v7*2RH(6BB&7VBL`DX1gs=Xr|2yGp;CL21)&d}1YR%#3HFYAV*#2z!jRrRx-M z{-KAl+-t1h{~OiTpETdbDorP;Ty+v!T5$a8QS}iO#btre`rSGWoQV6*$w*ePijU@p zJvvW=IOe--9QD**SPoPNR1z+8B1{0T^1eQnXbT?$Vzry{k%zdl;r8ssJ%!a}P$_Z))OeKKqMRxL zaDRXh@B^~kYYA22_98fyA(3dIG~=3k#Gpo-GZK(UO`-TqA3o8+5h%%%)%h__$510!Zidvxk$D zsWtF`Ox@48T5})XBp6Za{m|`ASdt_hicr@t@E@Yu%!ziO=JrS-`=C=8x$F^%XU43@K(jdO zk$r(wn2%MSc&$h3{>~bCVTmhV&TFQ^E|)^8P&5_%YRQ~R&lKCFQ_5^%zuNixkLqHV z`3_-BMNX$wyhx@Recc0-YfR6DfQwt2zS2Z*x({gTS{6q>`3B6Bc53U6fR;=Pcqc9@Z-)HI=a^KIy=!l*gB^CA-eNGF(&0@*$Y%xEOHbzMvTl z$+tW0H$d2_Jh?9~RUO+TyLc4hW54E4_&H8fw(@Q5s10l&Gb#*jCf7f+7%I^=TJ z{E=ca)MenwR@X@+>+=H`}w9=V|!8V~ys zx7-QYBTjnij<##rMolfRZ)-81)FCeMnBm{pj0s-Y>Dxvt|4Ovx_b=7I0f zifPz;{mZrn7ZW2Z9|s_+*`G04@9CLj@{Qj8J}_ZhR3H)i__Av5>A%ac^JPR%GuQDj zw;xHyS<0u8DU7BK*%Awh=K6bon8Uf5s3cpMjlNc1_4-@c@2 zTcvMIZ^&K{ku$KG_gX<~!)H4!as2Cln0e{-sCH(tWdXXmCsU69@)1XWHiP+C4f_?3 z%5l(JhV8y3O?O)|=5%;(BsV17`ptPgmz;_sd})NX$W!grnu$?678%cI@iD z$!yc-hqQ?JTeo8pzxwNG?IJaF0Rp=Ft-?2r?%_i;qmJ2&cf=KD?2oHLWhz!v)1LuD zeaSQ1TDcK9?K2Dkf9{BW@Ircj9Q8?fP6X!MDe5`!u8aYe^_8F+kCc*zO$b&as^(Q$ z?_GsWSl6*Du#p<75)FihZnH~Keati8J|<*ITU*%2AT|nSUOsCLQ>xjPdrK$TWIT%M zKkKPStIX77K+-&N-;h4gm)FM@9Sr25U=K$*^5OO}#4^OE)A2o1&ci-@Ryb-~W^oA! z!Y$2&oj~WWz!nMp99pLI*66~VhtfbRt-4R}dDr?RL~`L;2DKw+7xY@+cXgPWv&-$T z5W8&Aax%UTDG?}#O;=-Sxl*kcU2a=F30Cbbs}8>M`j z-wAP35|aE4BK%N3eOAm|+U6CmUQUg^9Kqk52x-{50)rPU6uoONEUrUT@U3=9Fv`!q z2RsXsp~}#IBYq?PVfO%4g7@zlr{kfwS_3y;rul?GnFdx{pt^ye2#SFccYoV5n&gp# zfzflEbDLy;I#yrHCj&)aMos7)e0p z*f#h*K4>v*RtMj9#cb0AV%Znf$GJPWbM`{sWtc^s7p7RJN%^}*uu6}Yh+}$l&LoDU zU)~Ad^_rMB*1zOlU@-3>IRhFUzy9J{5L92O0K^qEP|n~TGP4#mvR)gnWai(njkjvm zR?y_9n)2|48Aep(lfG_;;1)p*MT#HPd`!=4Rm$Mx_xBgaaX(SO4@TiG7U;d5g4z85 zrz(D=g^%Uk=Q8DLL>9EMwC*_`p1H5hCv*;6yC-Po*;Vor`mVQ?fM>D_O2z46=mBKg zDR>EA#ooN~wZP<-s<`x9y_fwJ5z}Vulnqk+SGx7~q@w(&BZ1k};0Z6#a6{NE%Txh| z`^!i4BQqcTP8AqM(TGT*$WpvNoWUgZaL*z|-g1SiPJzpxRevp=eU;X{SXm_30Sobsp(Da1?w^^keAWi zSe~|ek_HSC6%HHI0LVQ)tkDu%0Z?sL<%Jx(s;id@90YM=p=*7=9ocbfybk*;L9pp6 zC>c(!36kM0stn)0zQDYSL;s_`jY+X9%8sk5HYakk>(ayqQHi3qI=P&KZ z0u#iC{ikamH#a+1K=QL*Im4R`gJ<%04AtzhhB%ry&+vO&{1LxQQf0F*7l0=v{#pRP zVQ5Eb$o8F1k#gWA6m!;2%5(Pr5rnDFzK820BV}Ut>l69tD_Jgy0jSC-8X!WG?QZ~qFDxF74V>pP5M56M*5etGd``eUG%Be}!z3mSff+lE5>G~N zb4`($s$h6c6P_~p0T9(Q4IGfW9{*{VtRiw`V%Xg%Od;?2*oev(EV>-3Gmin+#n^%t-Y9d}LUieQWdKDZ$H)UZ^!f|QAW z#O7457RpXH16lCr#U3vhWq0uuIdxrn&)9xUk-G80AG&#TKGG0XEuZFY2BfhW#{zX1 zu7{7$ZAnEh$~|RyW+y?i$@32UEE55_vY@#xZ!bHU!+@ZksK_J1~{?XHZ}Y zWY_*M3Bv!wBtR59e}ESM>*xE+FYE+KJ6|@~N@uPXbi7gPl?^wgf)Ej^=Sp6+KZm&N z>`Tu#7ujz?Dt@&0?SYosrQM5xtGd|>M8v_*8SpvlI8h5^8b15GG_`a5CcpXDf(t$Q-DSR>IN(|0-_Nr z%I5od`ejcJcUzqDShfb9+wz*p7zrOIM?J`Q!Eq)Uh;)N79xS~RAf1H+`OFhSR!8i(1WTYX=6x~Fn9`>P4uNohIrN2; zBYFQY#oUMl%ART%+$fu4v^hTX%h69k1uEd7EgQcZWbqp$hVq6)iew!!4UwUvqo0lN zjU%()W;4%TgYJRX>gajryFnH9pYL$;{4ubY#t->Hj4~4f=e7W7_KdK>!JS+P);4K| zA0Wq}wN{#%QAQVjq7xJ&!PSdBX}g>sMTSLLJ^CTtOMO2Y2PYJ#G`DRENwVHfO;n~} z>MznA>aCe-?PuR71BEF4Z#je74t`kNR6?COa5RKXeLyy#+QnXJmm2-{cu29V8}Fu{ zG4{NI22t<3_P6lANU@kLzIPw9+k0T27*DP8b=N_*`jv*Kvavw5uH}4VUPCLNZ9mT) zkg1Is%yQP~lN(r1C-eqxK#P*M9m*uoVl^b}H-lMdsPsAa*W{Zo^iQQC&o{q!SpJqD zK*KOcOQkVqzf_G~hXNnx-P>L1^~4~1;&jRI#{T#f5Ajv-Jg*Qpcv5x9eUGp+w=d|% zj(bGZ>2YZ-mE6@E0F} zXHVM=b(Io^-m~BRkE^8wPEuzUp!>5|7o&8)_M;vfCEUB6Fo3Q zgPUCZ1MLzzhgS(knD33`+AZYml| z7g!n`Pdcx&l@xJ0|8|JZ^?%TGz!!NsmRya z?HyBAOj};4dB6%3oyswdh>vaQlsLR@i7mO1i@#rJ+dCpsRn@#Q5;N+G6aAnYx*CTU zGDp1QmwH-)r3nti&(jbjoabrFT~7h$e}n7yb^Sy%@Ul=x;&q+*xO4ukF~hN*FZhD|JOv2gIDr3zXsWB=5$>a& ziC=ie{;orOc3ukcHUnn4we&7zhk(S`5tzPqyvWYTBmN91=QrVw=_0NSserN^PLWX< z&Ly+9ib+CO723-zL&V9*xA)d%$^q~r^C0nx68erP1j^ABk9UzTaP!Z|68`CP<^M82 z1=gSkJiGniRKzg-7E|{OO4W=Iwdr&w~~V2$&Jm+VAk`F4k_OyV*o3Pxe{`{hd2J_1BZ)UBlM%^tV_~ zHs`akI2BVY8@UA}vg7>|3$6aMbcNz_jXbE6ful{R+}tT~PYgCg@JO)F4xwL>yCPNW zY@=S-{Cu8Mf}#``zNnP5RSt^i>evNL@3d&Ay;F+==t^7oK3M2QL{ z9=`9+P-Sp9$}9UV4!U=%}LZp$ke!R>o~&WCyuV8n=HO)ty702BBw{EzXs%e zyx-akK9l8s0%#=PluUXJ0_6b+^K0}@s=)%OF8CHh0Q-@E1iPeub%bV7WU|Pno{Pw=;~NsS2?;c}&&fI;7gG=7$0J^X@oeOQIui*0lKP zhla-Pb04@GzF_PT#Mh z_w2H8$eQQO`R%02sMNsTR?N-f&ISLK)|<70F;CS}`kOUL+VtbDJTNiNRnufpZW2qN zKyHwjRGldUhrsklw*!fyrq9(6XfR~(P3y=9Q@8`>$uKK`oo|O?`p)5kew~kU z$AhmW-X#p-SOuS5j)b*!X#g4jnwy>BFiI`4F|lIy=_C7;sApX=8Gu>@;QRWum+K|&HwGY z`+lJ#oLpMxq9#^_py0W!B8$&kKg&&YhyEyX3M_;_-|Oc&1=WSkx>E z0V0zc1@?asAbMJqZ3Y=YWoVtoe} zeLLab!o6aVEsuPBHEL#vi*Z>BZVmU;&q#c~w!7OJGm)|1=Qs!;$5ynR>mprh@h=o# z_uLxyl_l>9SdUh~EFVuO?}c&JMUI<_`THDd`eVBj*)|-$n2Pa|tYr;p2UV*<$h!VN zLE1;MXo8P~Fn<(Sa-3}eaLP2I#*G?3wY<#!d~c_x`S}mV?7=%d6aGz@J;Im~m&!43 z(0H>&>-!N}(huG&p(0N3jf)w|*DHE0N6ruUn**yPWNav(DY^%u0iuj#lcj!rxGezH zfEqK=kIAl;5~Z5u+!ek2)!4r!>CpDufzgAYDe1A+67v%~{8~MSIK;Vnxg}k+NjRAh ze*9;;1s)g3?)@)Sy!s32k;2AZ$4B9UEp(E}w_dl{$!o2on!0s!%>1mY6?5hPl%rovF{fS@5pVr6|j z1Y+Ml>1B8*;ji!O(7cgVs=pHFkR2+euYj*D2XKBXhC*C>rhh|X=v-&OH$hOLVQzKR ziXxGj&baa@Ji+Ar5RY64mIY3jCe1ydy&^@Yqta`YPP1%5 zC?4KSE|R|21KN3IW=na{kv6Ft#T{J4i@u)v`YOo|9Li`Rr9705lsKvOyoW+&0B2?$QW<xhmTcX$lEnGQ82U9SHzTXde zlSgB=NS3r=^Q$U$q%4;uK}A!Eo#UC+Ju3vP4u@#-7^9i z0boJ$y?mXETH)U4LbDf+br*m;X%yDy`J8ND@saY19EbWdhu)SmM#ECyaY%p<0YDu? z0N2txty*$ZOJ)iT`&wy9LJ&T#e|b`>D1E1#zWfem4D(9z2W-lFA$$8H zJtnz7nhD`-NRs@>vTXG-J+*5)Tjr)I0YRz+0LZz)X2*Iuj*C>7bIF0M zL;$c^|1N0sV|i*$NUchphAlH69lbF@!#hExbVfY$130|FwgSow8 z@Y>S*mZkJSAVUOvowZ%=oOF8nWTyudRJ;{FbwEo|E(*H*?IA?tT zeBe*s0J#eQ#lI=~X@LOu-hpJ=003C@0I*cxKsH_q#OmgZnkUr0dp()dgF&dI$Tk%k z{w3}CI(Zo5i!M%7sw!oyzQI%7?4H!eMh_G}hkeQ|@M-`ep32sdv2`{aFg(hR0*Uit zhtthMGUO~*1bO`$!p#BCfxahmn!SBiLhj?hH$-6}Zmgog2`8~g>M$~cp(0=g)>yg} z0Oo20t?i4^nzJ66a?sNMP9NPp6};4boQKA+U!gyu8UYA3Ea^EqpI~VT7#}f_>2WEr zdidiIDZ4X|O%emVRjWwWPLkIkJKKek;rz>qIIV;36;e~IcdthxX=(iMCcWFp5avaB zoRAL{yDwo25aRcvft^75*#9L>P@fft55DNWL_A6b1TLCKLT9=CKZLynP#nS52D-br zySuwP1a}GU7Tnz}1b26LcMt9s+#$F-1VV5~-sax>{&(*$^{S?}dUm#Es=sr3`uk3w z?eiB&04xrnkMC{)$e%jV$B?Zdly$H0q;Wf5?enY+M)-#O<=F!etIXOr%o!v;19f_X zX)=A!b4_ivmSbeckFF4}n-JF5=X+h{WZ5hZwHMs)rxAY`u-2G=)TMpxz9FS0`re?h zlM&IZa2i2aTv`Jg2oevN9%Z@0^!_qp;6g^E-&9WVHFa=xD7>pk(~i5dukB}`b{3%Gj;#&a%vE`WH9R+E$wsh^z;-ZbGX{RJ=Z5PFKD=jjU@}q%Rk|w!Y%RcwQDA*!@f4HsQNWeO(7g2GE|5Q=IG@q$nYb565so8CO z&~&W>uP>N);Z~$sup39$CWfC zTgL*7=J2)up4#llV$A6Z$EQRL2q{h}c+(@3A%*U;rq4oIQcSuO{;t_cMc88v1K$mA z!Iif_SE6|fi2q+jLJ+JK0En@tWluqc4tL^tX2c!~aENo-QX|ut7ORSbQu=0mMNjPZ z+FKm(OO%s|mIhlSXw4TK+O$zm*_Z3&hSh0<#SQo*YHM_u!-*0&lE!?_B3-gTXgQ;! z(a@5U{)dwT+bOnB#X+lD*7PIy{>gwGJgoC%byFxm4q?IXdVou%eHx}fItcycJ(HUO zIwFtP#0Ux1e+b?v>NK1&cerLLw)lKL8$c*itAm$U^asc0R|3_emR5~qe6$5T zV@bsHt|EPmv8w6egxGZ;wcy<5JUhYc!~)axO;g+rcBue+Dpvl>QgbS$C47AnXUF2V z-m|NaBW95`F6N1m#wxO3VJ)IL{OE0wubHUWG)3$6digk(;z2WgW7WUhC&hjvS(Xvg zaxa2xsT+5H=$?y*N9K3j+TeS4oh^IH9}e^W@d!YfXnOml^9cdlE+#0wPt!p)_vM}l zA`MrvGYb*o`#Erq%C-$D`_Ztm&09rxCiO~0gC0$kWC1Wjn0D11mJ_>5e0yDKHc84L zkxLt9W{^NRi>=UuTX!B&@RqI!s5 z0j}4y@ADpUZ=uOJ0f-Rdo0#p++Kg2>A7794o=jSa!?x89%j^pd&UOp_bsjjNJ%e8nTfVTuIGSIICueYy#hLosRqRS zhwvS$lC+!>LS@PBgOBJjTWyFmkr4+5apW>>$0j$L$5=LRE4TZN~HSS(Cu2HZ7V0RZPYtnI#0kddUWj;W7RDQro z);+Jq_9ZN~V@Znk^Xgy}{|jHXHvF5aYK2z-@H1)#yUK;e)!EF$94>z$8GsNkkQ4xD zEQ`4>^bA^?O!b(Sy3xU_Ec0#IFKQAXqhVAk{PfIN z=aQ9UZ~7N7c|H5EMkMwHs+uHVKR3y*+Mg^3>zl@Gqcp&FL|}SUe*x!6xV+w4J*n7} zMLbn&0iwTQGlnINTWx-jop28-mRCB{ONWeuRf%ila~O{Sbs_i~>G~A3GelR`#!zIZk#W7;zRh zKp6Q#S(jiTntn$06(J+An*;#CY7(diw$MK%=wCtf4`ckpLVvCDza0=>sEbZuGFCay z?vG~^Wg0A?;aKAe2jv0(lB7YJJK=>moYlaWZABM8ZS*d&oo*%&%g+EwTMubBKA!Y2 zUt(clu^T|97|N|;`yk-93xE&ztbkg(0U$xu&AA!@AV{Chfjr1#>cu_OBm3b8iv399 z)%xf%&@_gl2$W5PG?;3d&&X^5v21uB2G@+hR^E$1C+nL@z@tYxFP1muvF}^bEK}on zFK10jrdGAo!`Q1DX1KGQaVp;AXM>+(kZ&Dn^OZ#s^m^yMyZ$)*oXmF;XK5GJM(%Oo+rf|oQ30ssKOE--JM@&Bx;_CEl|Gona`5t;)K zOW>8e2x!w2Dt%))>PK2f+-AMWPxz^*S{$vCw7vBD$UyuZh)MpZTN=~5q7^4l0RSU- zU1|v?%J>D~v}Pb)a7;34ucUL%j4t|{i?Xk*7P}rkQcHk zwpOPhHNyAc#ToFv$It{zaN#2g9yEl5SAup?r{!IB$%vNbHd2!gMq9(y`@A$XxG8Ii zS&q$Cd|ZACTuK0+zk?jCsn`EYMgBwe{JZBsO_Ba%U^n$IQ2xuMz!h1YajTU%Lf%E0 z;Bf=A>LgGZSrjfJVEGu0_vf32+5^qs*l2&0Qqlk6m+xppMBAUEa9`UaLkuGAHLJh_yboZcB%0B{wI z23S+C{|^mFdKz@3P8X#N0MHgp0+4Q&pt1Y_2?0d`(0to6lv_7YP>c(I`WZz8MGKSn z@Fc98dC7?LD;ObOIKu^zevgbEw#7e8(HssB8y@ZNT!=UovFWwL5}D!ArnM7(f_<3z zuC-1;)rE`j=vBARLAf~8e3V)vYw*4aa`iQg-JZg=u3g#e6&D=lX+SdH!_iP6Vmxh8 zYsnG*6E}3xr#*ox7l7~4P9Oi79{|$-Es6tSFG5Ymo`EF-%0*;pSOCzjn=K(jt6I5{ zi8R6lZ7;lkK<59w?k0Nsj!g&W?jEVXhuK%+Z^3{X>kwR9OT&P6@F8jO4u@8CP+!Ms zi0P_lj*q!{krqJ{``7d+;mhNm)BODaX3CEa9X7EVg|R^9G+)oFWthnxm6_q6t`gK* z{%<5EVg(Rizz$<3nzbSIzb`0(l_CHFzlaTZw$=YH*ZS*uux{x{sRQv-Wr4{|koRl@ zPy(U~X@-}6YtfXFfWw*u@E~apc!LY)xiK}7m}uKQAF-5`3o62HF*k$!K@*ID*R^Ty zmpKeSCC^94M?^DHyF)R?XtH&<+gq2_z2sx z(+Xr1kyhW+%!nh zi}Tz}O^1EeLd#(kP(eBPa-p^Td)@!@QJJJGxVTPIJN8*Wj0{$}P@!C4f11+x3Khdgm^3g z=r@>aXrb`YF4xN1c@&6ss6sG?z{|^fA@9pN(b?5<>Yu5o?gs7I#ZAV4-p&^xoqr6Rnx^ggnNPEGP_F2+>^zxfInG+w;+I-+XtzM{ zk^;ile~0nKYs%phUh4G!l0G6+v`|gg0Fofwl2WC=Qbop4ntz9kg_!%ewXyQ6u+n12 z5|yMFe=11E;}?@tMw{NElY7(%0L27R$Vp7>TQkyV<3}7g@iY7WZ7aRckL`{Pc5SCw z{x8YL1xZB#a2&i?areP>98@vJs60Z^P=W@az~5&Oh&V27s*DHQ_lib6h%t3qL z@lALi%(UD2UItHO3TkgApmtIlj@pH!G&N6`F(u?WQ}K92-m7YFjz@vJk=k}KJ+ci0 zxNu0;i>h%8ivC=H6WU%pRs3@!tRv}@G`e*3D=c2%j0`!M;q+Qcnokb;!D`^B;8TkKAe@bQi%Z{}9FgA^v@X|gjx;Ldgq|F;hrL#|F# zKI0xrk~|?94449x4HQgy9AX+xi*l5R(RuvB)-J-YFtImaEsC-1v$iCO?{GVu3Za-4~gxwc|kIYononjn=J{zFT?F-$j#Z^tD4ZG>7aMi?{lf> z&<~@%#`TK@6LmBvZ*l9GC_06i{ZzI>i^4!tZ%-UmCMx6eKpu%}18Bg!ulYjz31=@O zYqI$!4sY2T=%hP|VFu^kV3gc}h&NKiC1B^rT+1m0!|%)h63`(j%-bv6&OxacJ!b)w zLhnm(hMk@-^1p(&rYTO%B6UJplTv{zv9(lbiJC$kyfPKb?uSj$mVk)y0Kdn9V!*uf z|I}>&Tq6L0RpjqGo*e)nN`PVnwgUjjnmt0X5&*QsDgc;nDM~fVGWO!gdHUaoShrO4 zH0;s}usqWg2f6f58QKJ>Kt4*Xa23E-FsShED6s_q%N&!c7~{4B9ggM;NvcNm+b=){ z13*US1hssnE8UJC2doP9Q@ZNbzj2gr%OO%TQ(a4QCR%kLylU8kU&5)QCIGQs+M$m; z{>e`qbOrOo9Vv6`s`!-+x2rYeH-NMhpd$dztjyDc^NDD2sXYb8JT2{y?9lz3FDjMd z^XkFfkL7}-_&|vvPGS;416|l2W@9lam{9oS4$iEv9|6&CNj@r%9_K+rB3%evJ~U8k z0*-vtAkqC+f*cO7y>-)%EKE&)6uJ50HXs4H;$v6DI$br<+Fg?OdJ}*q7)8Jv7{&ih zdi^^$1Gi=WfhxE`O|bx=5<>V;1Pp_eL!d!$RAA7AS9y7}3B>ca1kDi0W-|7bNyK9p%D!U6#P)N8Q8wMsMrET$YOlf7ip z*EH}qqB6`I8)jBCxaj&8{j_^`S{_PeFD%-Aaysba=(h}O{#@iW%( z>y`TP@4;nJnJ#)P+Qt}3%-gSnY-3yOsXqfR#Z0^Y1a}FRb>X_|;R-09OwPSLs9=+k zXYm}~3%>=>?}7Wj3e3Ae{Et}tf9v_*Q`&)l@dk)7Qlj+!i~uS!^CVFWrbQ@(`G7g3 zjq>XA0P6N0e`Ek-qN{%&bHHF~k4)rGs>i|vqPyr;eR|w;V^X)qX+vWve{k-rMX9vp zA}Ro`#0`8~AR=@YzPp1tTbPZzH4X(!(6GJ)Ka%U(H+>GzvU24ryuoypU`$~uJ?{h> zIbtKQx9-x`;brB5|CQ|hpY;s`_Wv}%#6H8+C z15QO67tOka{=b>yzqtc&EVp~EsD|gQE6xd$|JIX{ZAYujlB>i=;ZMlzQ)^??JBQCz z#HXoXjAc5zs;GVoWvCVnWg0Fpsqu$LmP^(*x9Z+WIs?ZdHY8LZHG*6W}VM2@;$qzWj9P--e*LUF2T= zM)vcUOG^^pYQC)c98b$`rh?Vv@KJT!d^Q(# zr+$}|L8I%KMApV8kS12RmfrZ&B~l$EVIL)cG3leA$;`)|%zolaHFw9~7U$NP{$1qX z1xD<7N`8n#+I{UESgFdTEYT!zy@0jCRm51b&wZJ9*7*(<>C5CE{(;a4Ef>i4rttK8^DC3DHPt^bwia zOcA45x4M^sFIqTEA|A=7`O97KI>5%cLD)NAALw5tgLF!ScLBOo-wxZU9xHmCfruTm zd5&V3A4@s{WqY>Z~V-0D!v?-3EOkX?o*uU?3&f%@Z6aatr8 zHsOE)50WTpVF!+`j?86Lj!(bL=~6SU_p6x9yLwQ=rtKvy+!a_gs$+kDJ?>1I%{tQl z4*2?0QLJ7+S@2t+?#%;f+|v9?f(ue;$*Pl5z0?4HmibTY0~qTNZ$i6yzQAYp_EKd8 zkNY+RN&1k}(1V@gR<#B>w=WU?1)+q8a*2MAFx(?-@2helK!)GiW^zxWHwxnzkef%W zc%(Icz$<~RjPOwwNxNVO_U))iS&HbIEB19U-jjz!WeQO@h>xm@p_Z#LOTgQ6%U|Mgs&3=SXpFY=8Tpl&&l~ z4f#{wzCh=FX}Zro5MfS4;cF_Hw&fzfVw5s{OH5_5@2pTf!iAIP=TAXu{C;AL7 za&x;{r>PU%uZ$2YBq(#|3I~d=q;5;7VaF5nuQ zo6l3xG)8}9#Delht*pE_3T+y&M6Ed_>%}{f<5GqosZY;nq9#!bptaN24E2*voWNZl zFEj2(TGI@(d%_yVf$>a`GH0v6#Dhp4Y}-c!)RU^x{F%#Tl_ubt%5|(~V9rl5M#p5~*ZqDH*r+o_MyJ%wiB~Rf4LuzQ?3?m=afUafPr<4>) z84o?*u{`Bh=!CY=Yy^xxNwc?^#x^yl!3Ol$kZ5a)Cemf~wq8s9uu>9ac->gZHGyhP(MqI$hDrJ1WAY9N?ik@LfFRWu?{drEX^R(8 zTd7!QcQaH`PwzNAmNUvcl!v>t^D^dLyC9nwoQJE8KFhP!&<+2y?s}9)UBVLxn!72; zB+@ReXE;S3VsOABW`W;h+HO`gpuAncH!diZ0+HT<n^n%<}Ve)BVHHo9H{aJcKrq?H~Flv9iLK3G}e5+~FPUE|z{FIM4)`*$4ph zUhV#Kz2Lu5e`K-Fzk~eG}3H3T9l@a9}8ssgBj|#cT9Nn<+XWwxt&dR z?N3zIlyq9zOs_Zi*I&_<$?XEJ;>{|i<{{WJ-qh<+l}wmAW`x_70mWtbYDP@Y&^TgA zmdb*phzV8gKm(Ag{}~H|H^dLAAkMS^Ci;0HZ?4?U~R1Dnb$$xjH} z-33m4)F;fW^;T&+ZdXh`Ft@fQD^c+>ypy7tM(y9w3|T4I>bowN$zWH!n&SBj?AY5w zqB{qzRW%KOx0fP9O;Z)H?MkhacyOY(eSK4;AmM*<{@0lQgztZZn8D!v7w1O;0J@AP z`@aqYsCI>HB9_l#`A!mM=UUS@fn3&-tag*JGDS-YPOjO$PAIFPU3nxca*81_a~ z`F(~lKOf-X4WAQYo6*-5Ac+95IRW=Uwr;@;fZ9wp046EHZc0nbV?Ty`-Gi5J6Jywv zt95Lm&^7>KB<71Cdsla~X*nV}JnB#s)W%iGUI}nC#JR(w#k#()kNgMqRzH$o&C#{% z*v zoasCYG)CNDb*RdTeytcNMti0m-vyD*dNyGmF^Ln&yBH)iz^V5`79Id_(+53O0RZH` z|K1+v;8W{y-h~b%dx}fi)c8EP>_eTyi&B~pbbQU5l#Hh zuNp01Y@q_eVa>dp+mz1m`7Ev116oUk8#l*{Y<{*B0pKF>hBH_~$M*u53c$D+f^oV0 z4_y8!7=9vIV#U;KoGkA;?njgkOccGdq(mk11iZB-1u*)zjR1((FT8x1eP_u14H|Nv z!un#&^PsanNK537X$wyMmN)zxpamd>fYNO+d2=emnL%+`OG z(hIksGK^!8DWe``y5|nX)uwtEQ4Ya7d(rM`bTc~}I^1VGDW}T(wZOcnPRl#{JMij@LmG1 zYGYnQvjX~@0I(78CzX`6j_f;((0WSW$P#*8Y?ahK>Ty2Q?IknxE)L_l0|qID)xN!9 z6|WSXiw-c!xof}%R|edx6* z+Z;}ehTmqE7xv)w@7BUX;bpj|7Vx-c7qY-F11Ol@fla1le+Wir@B;d^wfUr~2$rY`ox+thG z9m31?Pl=UhSLagq$N6C!Y~bp4p4FabOi(4OavNAq$E>N-1lc4SHae)Ehppl0!x|Z|S^FxWRrV4Uq_nOS`C$%eY(roO+$+I_D;ZIaLVq#h>HWjO68gy$ zjyC=yQ$=wKEe?g^@)Y|$ABEsGH(6gJj!Op98{{b`JA2~SoFoj{z@72C6$wof?0W7c)X?&#r?_&g9Q!xo+no3n25r$Fp>7NBPuif|g&l!!FP91yl_YniTNK~v;WJd>YmP*RcU*A~RvV)cuI^B)28*4s2W4JV>yMftiP5VQVpO}x+~oM#OBU$Lr?K!|p_-J~ z@=bCL8)aw;jE8)$(Ln~DqLfpPe0<`FC2mD-DXSusV_M{LS@QaC13D$>CgGQYnM zJ3|$@tyMy3rsGX&{-~bzwjkJ*K1!zXa7K#5dW9QK_7$>u*N+Dnd7yq8?^HO;y0KKI zeXKNx--sX%@9u~snmod)L!H=#S08&KrI_0Ls4^rtGzWwhvq7_gHyP#_oQ%F`PHs%l zR)Vz8!{>S@RF$6mkq{BCdM(J-;7A&@#^19k{3?i(SoXOLt$`guwk-inq60+pAr=0O zM8|>07zD6AfWt2lRzh@81cZSq0}=Crx7%#fk8^@HhnvC;fvi(ACA0s8T#?sg$W_zN z(+{Xw)csgY49-s7s{?8v#t#2vYf4>a11xjw=AS{PAgp{ArysE|q=u!)|HUqWx0MPF z3y*0|=Lp)wpR3E{7cglr{+KA#>A*<*5JzGW{5(~p4po)LCnds2by7W@9XkMgJHbu# z?XSA!vzT^oly{+8;e}sl)tk(d2Ng!B7F}FOr4#P*gVGz`Nc$4wy#Uvokv^0)c7^ck z!Yl0sjn}#!#IJ|`_bPF&_wzxR*{blNw*C6|$;+ziGPc@MGR0G;#o~k=5IPG@jUjJL z4xvoBsa2sLSazt%;~QfqVJRyrq~8L3l%MLP%z;8k^p*xJ2p0)5<3oR-;F$7>XVto{30bvwXCJh4D%Z4FYG~=;qd!D0H9dHa0QXD(!uw_fV6xLrl zRORgr_`K98=YNGA|6tY;ixzWg$(Vw=$EWeF@nJfih8l2C{&3^wSXo2>F~?&uxPHYQ z=WdweI=GmXi^S5h)+*fjTk3$J+c%!Li6>!c`P+*13P1{N(R2imj7lUPakoTLHh2RU zjo?XTP0&+3x^T1SR*9rFE)<9KGq-wcxI`HlgZ+Z`B5H{JmBk^lxaTu>M~U(4nFkWC z0G5e`Ou`PtPaMcF1Gt`>SK-3D_%otH%HX4ohEt@%@X{D|uV4mIXJECLkX&D#Y551f zQmHu{62b$?{I_am+>mr*|1kyQw7$K-ZhN@?M!U7&W1Mimx^c?qXjQZxN34v11SJ91 z;icfI7!sI|$oRidw13ZtK?3`wlxpB#@BDi-0I(ulUZ~W`-P4IRVXG?inXw8DJi5mj zw6z_v685v_sVQ>S2>R$h)-(c;)PlI{hVLhoiXtk=eSYq~OJ?3=T}dzBiI^0!rcauT zA|^G!^8u3v$2BKfc44?~&ImIeE*1oYBv%2*-wGI~c^S=?z9t=Ke#OF=gDWwjLPE}& zdV?)QBOauasHc&M;L)SXh%07yV_KsGR9zB%uFi^x^>qNeK)3-}^)*nn-oE(rjRY<-2-YE0zbq1RQh)tb=i|`wvR;&&~p%f8hUPdi>|9 zZOp$wK-iJ&g|>VdhPd?Fc2`z^J|ZV9y7i-!P0>~gXyArCpTNHWG1Tgnj*DoW;<5*= z=OxQ@nGGUan`4Nvt#w7xe&-%5M=jZm)YaB^kp@2idJg>W&3}+P0N-qG5$U3P?5wjs z>tW%f6r-0c_R{-+*ei#WXihT7(&er}hY>^QyU6{tKwd<(g0btvHdgbLDYQWn%}0S` zG_`?5`O(3fP-ll%N+eQLC$NFR@-h3JSt9X zq3T&#M)@-tFA1GZ@+!&h7L5*NJwz&JOkP?6j!wL^P{H^xU*!O4tGag6-?Vj_9eCYg z>xOsmc!w!$B@vo(MThMpwg5OBP&CP2=o-D5Tqyic9HK*S;olb-_{6$fZ5oszvYUc7 zH2_#ac28#V02mxmsNiey94}i`w@9}la^h$s^+gB}FAr6@qq#PEhvYde^(YF${ENzC z+~+P=46T}#!yX<4Slm(e`$5xtU7i+oQCRtg4TH+4RXiG|=rqXAkMrv9CH7Jsg+yco zDU4>&U$Es3wxIclXi$nVEAVY%x5y6Y-^#~t0&@;~;`K4a-WedPa9g^Q!7 z$p4v{zqYJ$HGQ2Kk#4EvmA21Fb9>3)o$Jnm(QhyUT4N8b0>}bJ*F!WLY4pESG@d{I z@~?k+-#_INjyhoi&%b#g_#zaZPCY2Pt>2$A|X64Fu!W zXi3CeL)7!OHNUu2fPQ@J^zrlA%Kh}I06Abaq%9Jh$zokSZ3 zS|}XHD~BN$cAv1Vi0@gNMgx~=(6a0y-)IaTWMlohv)Xri&=K|NP0#4KMa0T1K^n}k z*w-k(9=L6~k&8UXZ;LaMD=0+SEQz`SC?{Nm%=9Ijrj^0eOs!@_a3OCxYwjDPY}Wm< z5wpRb*CX9lM!Vg?SX^Y&j6%JEt+=Tg-QCH<0um2i`7Tf#?K8`Z4+)j7GZ6h0*tBw3 zl+pPW3;2OQUYqCRVMb~fy>=}Val>FuH|;(@`o5&~3i(2DI!J{+#<;x)+=W;o?D-fO z>5EN7QkvU`XJKe6AKq}$m<=t2h6L|63>g@f�}Ue%&Cu+g&Rr3&O7@OWkD1A zDd}F1qYMg_{kBWs8*&I*4X4S2^}~1S_MFTi-p5@swGKB91F`Qu4uFB7Koi;EV$y7N zNjvyoTLIZbIiCJLA7;Dwb`D=G5X%lHm2}|5DPb7)F~%^zSeY4jpMkvCw&f7e0D<_u zlY%fmtOYL6p|NXYu~YE{DJtdXh*z<(ddX3Hk)S;orE6gt*%tGZYDz|BSVCQ$?msZw ztk9v7AM8sD`dX0@#S^aA{77{#qt^WDPt1c>3fT}+FRyfF6#x|KwmQFKW0i@vR(yNZ zA7$7tE4X>3fm@>}4o|eypJ&yr*p=#{_BhDvj?9D_PDcQKdvoexkDb1Qc*u4CO>?y3 zu|qL?u86(pM7v05Jjdw;ZQ~U!n_FFU*z!1qA9s+$!%ch6E0F(lWvfLv=vMG; zXc83yO>PD5kD z8FHK1;KNF@I9V!ItX64f7?}WPk0eGx{i(^Qw(5Nmidspn_H(6P$NI7y4&;`DG%6LV zITA+0tT`9}!PzhY19%~(R5Txp@qc8VtN7v&=p}Meo;h>NP zXrBhv*}8BCH#y{*Sv=jm*7i=SC)F_8v;qh;ZUpy$yq)duN?~3c~gIq@Vl-0AlOhZeP z(;B^5*BeLAde$ymiV&2{?Ky_%CxaFAqDS^lBt`a@V=9oOLay13hzlYYyk}T=6e?J6 z!uV+NS#%gZVGQ4)YzMwF6DL2?ZEOVg6Wl!E27A+RYT!wxPuAQ9LCa+vYDJSy8zsFX z|HRWkfQ{-_>sk0yqD8wQ&dfn1_G{4yp(X50TcCTMc}(eoC{M9ys85b!K}AWdv?t^2 zY0724iQN=d1M;Umkn$5?F6P>oCU zIhnA+myG-iUWD*{7X!dK+flAiupUb1zMZFH!U1yRVKo> zcL%Xp{9FuZ;AZFRd-h^qnocx--V@_6j9K0`UiRZ3Dru)?Re;*#wZ=mEO^go`X%(Cl zG0{~-Uf`mAqFFDBiz=USl2D(Un#wMnQyN#+3$NyNb1XfLE&q@>s>8-Fop$+Jy>^O= zGIB7KTmM zjE5pt3yE^7+ z(89B-c#(A&3s^5h8O)M*on90OZ{BY4yC|1u5AZ_!XvFN4m)}!nnpD1$cwp?4gxSmu zA+wUKtY`1WkTvO*GF+5QH8XOzTcobfi`nC~$FTVi*w{!PS!4lA4FFD%!z=RGvINhD z6F!n7JIl{2txFWk5fT-St{#gr>QS|Zvw&bM1I@4H#J7nfm&OUWRgn1FeD+y(Uq`8_ zA`=vMFw=+lT{zxWMdP)*$Vy8-nzoMRAE&xDKj{Wh`RZ#VW~!{Tp-l%AZ4RnFrwAP` z?RM?NjG;lmG#NXarKKN(OPVx16G_D1jK@CE&!pi-sOM*Ka|!quSAWXm!F5#kyjn9t zW$y4LMJ90J`mRfMRWa6C+-VOV=l7=6 zb)mla8i?My%RcTgNiMXkABaS^8c2TM9QljNm+|Gk_4LA4CL%xgEy;Snn&g&WAiRtq zIx(6;E0{&(z12<3C=?Cb)tU=+Ij|W633)51MOl~W?NZ#^U#iknUpeEl&*@cF>B ztqqt@_@6lw1Obp-$erT;4{XL$9IQ^PLs8a&a}a(`lpE9ioh9jv@TijR5wRc5$x2Vr zYWfiq(aY(6PwxxQjRxj5qZy0wed2IkhT`s7%GOo7KK$*1mCvR0r4$f!ukL!$EIj4I zG>Ptg_nyTFyxNfe(?+~!Nr>V%3GKWIdBJ%#6#nh>>s%#-i|E*Q^oy`U%C=2McU67> zhvAa_i!`@^v<4@iO2G-Jv*CrREnmJT@9mSe%GxFxLD!wap{dZtgq*L8%!x9jvhuxk zAVd0HM0}G>r{nBKiY*Uy0^fT0TRxtx7K-y?F(r~PHUcVXF$#$Eh4J+IOrv8D0YS`h z+oX``n=*gIugJq<3;L4U?!b0DDfNeK;5x6GUTj^nyFOB+TxiDUK+$`+yLWKWBRiP^DStI2uE(0@Z5iS~kAB zz`w~ML86&RA%bc+Xa|-PAXc#DF8@G zZz-}#M&CsxUCeR3H1Rib7V%Mh`>J@hu(r?=676%ZdJbdygv*JVlWl#Y;de#7{@8Kp z>s=7xX<9jkbxpNzlY(q>qs}wOBVb>Q%Icyc5oLMJhR|kLs4bJq4Dmes{=&*-HlyhQl*j`^!DvInj-wzT^YeH4s1Ysz{Ga&1AWqFct>0%Hov}PC zy{)XPP1CRu#nD2o4ym-bKTODpbM6~&X8bTqPJtilbllT`#ydFT4}rn`bX}0F_Jw_W zSmrCLSCmODh?1?KvC$rF@;&=u{)@PX+e?RLm?_dK9SUtthLjLd^PXSoFvdDRa=L3Qc?Ea?b}!~~$S902$|IgP$a*ED8=L=}~x zfId)c!<%2nHbI8xh5R~q-dPXR=p7a#g+^iB2`>buY*F_^rrd868X4$br2T^){S>=p z_9)|f&NglXPlk|GY0_v1G-Y+_gFsFknpH+?o?{G1Yam(yEL(0^`*Ak9liVF0Av&rM zR6~dSis!?1P!_6821N{Z{9bkfyAVas&B;m2F9UF)tc z1YjHw&?Q68bMX42g$JrQivx(M(?OQD69f=C0Z{pXf~_!#Ly-XhED>*ItDDG}HY>m? ze67l!bhV#NB$9HAVDS{L8{nbjGhC~5evbvVXV+PpiE@#s@k}A)^m>xXI=fIu{%+i4 zf;BrUxw{`zPT9k@86#4fcwFXQW$|bTB%ZgY2I37Q9Qpc!X+)Xg7el877F>Dzw}?I* z64%B<#V<=64F#}FQnD5q8zuKfCFlmk;}fTuaw9hH_06|o{4APeB#bj;<3M0SzG?`#h+ zvcKJ7re}v1{)n34>xiuH_%j7WigF9a%n*#(e+EcUJ_pT;0ARLda8;7iSRKiR+yag8 z6CwcE7Mystv~$e6!x;dClMg~%7a`5mv_qWKq%j7JanKcvT#V`Tm(#@T$TJ|?^R&5( z=MqKHOJdQ!2Kd-c*dS-?xS5I+!j+PQp!mMfpku_L?=+qpLJ+e3`<1ZyvBW3!`(yoI zqp(msY}>e0Jc;kxG1;ud_N@Wh=x2sQyxZ2UIpwqEMe`u7z6*#r+f)ib&8@+9l z>M1(n6ay4??lKs|#lv~q7m5n`vR{ArIThNJsOU_J_X~2H`LP+`X7;~TIVN?+WCmo7 zdmD>gH~}H->hgSz3VzaEFPJHA@up(Ir-vGwG#r^BRBh7?V)z7hhWorX;k|1emU)SP zfe2xKOTF76KO#wgq@RZ+gM0>#3F~IB#mVlkU2!q%^@P>`^g9C}XS`FxsLwdWG&R8f zo$c+x2>)l02BksPTLF-a7>4(bJfE^AfFo+N3jlh-P5K~`@(y9h8tTq;>GV9Hky1{< zv60P|HbL~`28f6nJX4h0uautb*;`1Con-O?C+B#8d70s=BCCKz}Yasa~b27(h^70T{bNc7@UVv$~T3RLYxsMqxA~6 z9V@=MWkFDQQ&CrUV2nHNeI}JHOBpHM$N@XIq6Ez*oCJX@ZGLu*s4%3`RbzO#t@oRf zLz!m?|H=UO8flIchMwDl3x zRco*_73pT633|sQiR{($`IS<$pR1?Z+NnI3Bj%LS;!a7k9kU~5Of6j6bNnB(bLFox z!Z1X3#jg%0j&z{-X(mI+)U0RDM0+bJDyV?tJXkMGq_1J^s>T_g z=c7AnypRq%KNkA!jJ>?TM@&VkkzV-UwjzgZ)LYi3b;(>XwzU8mWOezyOwjcJpdC`WAQ#hz!z~Wm%vm*|bs~L?da5;bXCmvE( zuF9}d_j>bdWLk#e+2WU-s*8O5FE@!X6!Fw)JaV$TVp?or2(Zj{a%19*P6p!hqgbu%#DQl#mm7;J0l| zOITU8O~M!%lK_S_!K1~!SZJVLiWYoov1*|5$Li@}MWEthb@Va)cb*m(sg??=Td5_O zY#&l(zkS{X-LI^mFnb42%WP-MTP5}%J?SAqvr>fe>(|91ur_aO5wK4IYZO44>i zeN*G^l?h9{{=u;>n=Axj%9H537ZhdgEZrv_+W;|Be#)ovi6w=Rl|dvP=fj`r$jj*6 zQQO!`NE@$CWHy!YyWIW@ct)CX1OFEwY%&VrFJ$iy19u$zo=*C0VS$XWq=bxBtHV zb|X5v>)zYZ(V1D5bxvkhRs7#UTgD<`A!6Y94yg199MV9n-^yoi-W+twX9mJM(Zd%A zr4*Xu8USt;`z9+Q11b&r6IAdd8Ee3${m!pCm1TC0bqd08;?ZFKF$I?vln@L2tY=^P z$b{|!96WbZf$^OVRPO2tQBs|Iy>fp+?FVQ(VQjXh)Ox9YbzG~NB28_6 zx)UuI2Swb4?KKW2SR;xQes?dxj+orUYIdhLfpr9TYko;5itZsS&19IZ%`d8LSnJN| zveyOAD8W%KbShEL3@0}{L58DsRg3Hhyzt0-IaMOAP8_A89S?E@Mr{52Ksj+t;O$+_ z0>#4#+G(2kqqHeoZ-DLLEIf zPVUL>#%yzF2Iu61l7w$;lL&*kvxc}NXVN1tIXVlu#e9t$74{?r>iu+UXO+1@9$P`o zMM1Sb`18UHO`sfXGeF{xd`&S(9wYpJ`0jrV{y#Drf3~s;0dPC{fN*K-HIT-?ts^W9 z9s=3{x9Vn~rdPY_1d@cHZJL8_X9Z&MBJ~JCtyolWSmXJTsL-=o_ia#v>GZ~D7@8;e z5#Y{^;XM3}1(Vwd78z`jV234EP5(wxSa&eV4`x>y0HTO6!;1b0(Z#saicZ`L;GX)` z`XNk34E{$t=UOC-vGl+AFV-)(z~zE?ltG$E9RYdB9js<&UkMTj5n1y#?Cg~htepT~ zrP2A{+M>npd( zN-XHxCvKDVu+!t;(_NPtb+6PTc~jA3;ch};K{|W!mVN4t*PWOyi#I-73VoC82A!C`bL9;()n*sEbr->rr72z245;OYJyRj(_``W z3s7NIyl0FJIYAUlfN)~W(u+al_C-zTUOJtOHBQNvVBWn`el53AIZdjZ+?vV&QB=MN z5z>lX`WmcT$qx+Sw*cR)4sYI(w3enknYZDs^%ZkU9VeIIQB%lNmznp<&==MaJ?PDh;dS$rb=2e6eo1E;>JD z+H9jYMylE3Zp~ChigySSYTK0zo2?;NyfyRr5#h#@XVT-ho*~DW$vb>_{IogqnWShs zmaB~J9vD@yFwQz~CQhk=pX`TZD7z|;tBo~GcpO$khq3)J^YIp6(tG@<1}$Fbm=w?O zsNkN?W4QO#aBi}-qw`9KV10|L7_-QH4F=v*PGVx14knT!$F0%8I6^4DiP&rrE_vXm zvfORiZpNuN?p>K9HANCZ(f8eTD_vSI`-qTTtvYA;X~Jp`+^81{vN<$%x0#nh z>sDe|S7jb}iY~-TE^u}z7s=za`)79O2bdPb*`@~o^A0F0!T|966Arb@J}rj6kP`5d z2*Av8!IKy-7Ht50s(CR7Qy<4|V2aXeFDGW5xc}L0CP{D(8MzZ>{0#w5bZ7vS-p1Ls z3@nbzB3nQ*%PXdi@u_NHL?Y)@a$wC9`Jm+%>IRWb%4(wYRT&94@#orz_)?TUI<}6c zfoE^tF%|X#1#@ldQ5OX_jv!PM>Q%~bzsrWpdqY*uAy`B(=*FqC?nQOHh@h@OyE%A1 zIZmoJz#~?~1{%fbz^dyPdf2EyHkEf!6xxBYsStz9skMdIy8c*GUqV*@hCst)1J-*M z(I{#RHV)dWJM@i+7P`Q=fYo2uN<>xd^zAYgUNaeDVx+Z4If6p2kgc$OHSdfpep(afA_<-$w4OpF6fHaMRF zid-rN|LOWJSAA9&V}4L!8LzKQD#x+&u$PAFTDSd%bl-l>th|@Edx`9hxGM{>@+UMz z740!q9{==zc=(k&DX{tu+dAL~wABbmo}m0+F_#g5;^Zy1vjLWe$2IyDIF+iy%;ePaL*{)S}~AoxMa$Q7`+76OZTQC`Qsu31#LA`yrj zyXG!*5kG$rzR}x{SX6Z1e_+J)O`O!_7M;qlP48N5g^W>F&i#E_`!Y6e3LqkSF6tmO zpUF{|ajcx@#ThdS`LHWQ(gJ!ZBa4E#s&XYVOmE;zi}n))xDe)M9+||lgm!uznCEpb&HvN&x!P|T{nK|c5*u#ZU ziB*2n;3Tw|=@oCAfglyn+_7!v0Zk)1wO?Y#x!r*9;@ws+63$sLnvpT!&OxFrZ8)ea zQo5{SSSM$n?XO!_i8kVx^UaaUzK%V98H{nCvTuOv3vC_mW8aJR$#xTADRSTF$?FLK zX8-^IjX+EO!=4SI(trc*Pb2_kV)SPVe#YSGj|Nx{)?ZIRNB}rS069>#1#dQ>W$}^l z^TC&_LYo266VRk3fjp)9OPDdgpkz8@E-qJ0oDhSpuKS;Yykq>Qd>RanSY;eSC1#Pz z%_L4>Nbuvq3KW4q3wp}mqAb+-2^`ZHc!HuddjkL>E*h*=O#4BBdIuW-$PNG`))TFl z3)A)iz%PL=L0BY92=ae|2g;t-%2!02IoTwh07$vjk#I8V^lfht;MOHzpe&+SYyj#K zYvc3|fH=x4j{Z^+D=?4<1^}ra0)P-O?;zAz8jPCYzk;B%S;YZE9TZ z>wK#|+aQ3ZFJ09Pa{1XjT=em2KW~klDJO?ow3Wy5#1lKts=;(x)SgiQPCN*aonRr- zJ}I?WtYi=H-&YOQO@ilA#$zAwi5d7D_6_^j$HgZ9@QqN;P-YvqNIImfm2(b=caiv7 zyE;-dPGM7;o?r>12;orPr_n4q;(FCOVHAOCqj%!KBQc7;%W%$q_ZtnDx~a$9*{}}h zL#gS6uV?BbF`zEzVk7ZK0=v%?ff2~IIlkt~Mmsv&fOau1a-1o9^pTo_?{J1jr8}5< z5cv}$(q}ZYD5_j*fbu~M(M-6KUQue`q4WCNl5f`|1FV}gicC}#jm#$B)8nd3K$Rlmb>c>E9oOBbBucJL!A<`#Nw*0bR+{Qjr< zg|}gCC6Kx?ov7Pgh{4Re-O>R5^AKF&$)RB@q@z#%u|Z-EVre68nqATShNWdUh88C~ zOO!t^t+_TbuTy&OBPuu%8IoyK${+jT<)|=Lv1iY{Eh5{<+DFNvQp)4Du`W#l-DO%g zj7L5~0tu19VM-&(DCg@qk;jo)-6-)no+Xt}uXRE5tbP&Ww|EK-*5Yn(kh7`$d<~)> zwG|K>@v#b@Rcnl5oDE4h}{tTI=#-qayc z^)w@`5DoOqGQsNnD06~)Oy)p(&-^>6_CBC&lj1>`4I-7649%Ppn$eBm3UX8gnI~m& zF|nj>oh%6CH!$=ZY6u0wt0sIr$IX0F^FYC#~uO z0AQ+Mn_~h%!W7G)psYwE$EW%TSL1640GKTCv)S6D{O;$bR%C4{v}URVbgm^P82kVb zY8qMqe!RO>akO*|6rQ@}b zR|7%EJ>kZ1#I4ML`4CM)(D$5Hm9{d~91uJiNMEf0_taw;5%Q>#sYrR$OIev4W@|==h`*HO zUv-YPJi{L6vGYc~_PWSSSxGzQS^88Bo|%Mqp_3Zn8+N2g7^Y}Y@(I{E$+ggXEyVpc zOKR@NVD3pkCaIg(-xFq)n!1G*01Ug}px$03*j+8OziAL}Z}5iU$Lyg`CPN~fSDk)+ z`;0HJ;%ByTLQZeru3_?U zheIq97!eB75*LMP=t1(bQc~5l@Yj2UtV+wL`gKmDoVxlwq>lCQ(1CY3o88<{b|iC@ z*4Dk|Tf}38D9Ry@yz*g>_hpTd_?N>Z^icepVQ=5{Z(F$UmKTxqlf+J|FwF8huI=oM zhz#{V+oK+Y=i0M&7JEB%7nnIrrsUfkg~%hq0X{&J1Fk^w6fgc}#RkA7;QykeDqA*A7c`W9H1uP@S8FY3%tEV^!L8qA zaj&bOo+J|BG1=r;A$4nyY+8+s!b)O6&QHn)I;hCaHN2>iadndGas~hsIYHq}sg{V? zL@R8^W!~p}efGd1K@I@wEWa=SfS}QgXqKWHF&kOFjk6&XW676XG3G!?#3v>g-Bw78+PdO_T4enPo@)7HrV(f`P=YOy zEb0FiAN+@3D+70Vg8HsIqzWAX0B}gfGX5#Hh>7cd#8(pcy&+}-ER%gv4Czy%B?)K^ z6?;m^SJ8)z1XR7Lh?z{AtN4s_=?K8*!v$enni6@?(7EDQ3a{}107%jNZhF|M)nqqB z%`2mun!`X-qE&?R+%H#6kNMU#<5fJ&X>!&;(Ftu)a`(OvCb=k=D_hn$k#QuKPrrr03S(tcESRV&vFu4MLrSp_;aA*(?X+(VX(yyIe7RkeKih;g*cU(G23O*{zrXf#@)f>7^0&5u zZmr%;=LTw=Q=2B*Om(AQRmw?p^iq{Q6jeVe8Dd$vty}o>h&v=|zXR)|UDOrj%g2U>^jY(#br1t`E}~AWtSiLR zH+~g|Jl@rqFvtP#h#f*M^^vO~@TNZa<#`NY!&fDf`Uh~8E(Sq`-$!ExPrlL67!)fx zBClwzRWxmj@d&ZsNC&T$Z!$K&=NE{|LH7us_{O!fmKsA;M=d2>;p@zzDvF+qc;uL$ zZ|R^6PLhwUcKqUJ$rh(i*zhQaFA4!riC?oTvGQZB#;YBoC2lz-`F{>I>v*3yWTLyU~Tc@`nz+REAAa&-e!O6U$tB1AUQB#Ny?w0vw2{0YVtEP*eI z^sz$mWTE|_PiN>j_?z!>HIfd}5V;y6o4Y=mg^mB#mToNU6PW0#WTSrvDO9|Yy??1# zvx-A<;B$j*Hg4Sd81vnQbZ456XB_J}_(JMK9EM>C({vk)o(!_rsYLt4C6A!Z=?s;) ztIcTXfOGA#%#wV%Oop2aQ&VD-7J_dYB27PHD$PqcYSCOpS0aR-JA6t@fD^71#d^xT z9D!)otC@S3|1nnfSYP2?GNYZ{gofVe&Mc2-STCHIXKn0${qMN`E#qf5i}mIoKUVHP z#p0-IDh6CAUAq1xE~$a-{e9iyrMyP_2!wL&e06UMpkhMQ0=os2T&=?!p%N9@*rP`4 zE*q)ZZNhM$jR1JMEMR>FrD;Pc!;ItMxqNJ>7sqxf$t& zzNnrHF&-PB8;mXsAlAP{q$3S?zZ(mU5;vd9|M6|`=gT!bQ{PAUfe%bUjmP#>Q;!$5 z-&9+673>`54^C3WyD;0GpUN$Y%RRA4&E7m>DHuzP*jfYnV-xYiM#bWt(sv_xv5VJ% z>WU_A)A!rdrF8Q+TM0inv39qDJuys-ug!PypgwzwbmR#q&BBYkdju86WkyTNB4dLR zB`tLh70p zh%ft(qXks+C{mErE7vLsMS)=J+H98*Kr%8HId7-Y585Ip{W1k;Jill5bdi{NVBU~& z7hVm79;l2QQ zzrW&j+Nv!-jK?-B-G?)1J@kr2nV7jQw|dWFWNJ)h?#vM$*JZS&k0W+J@H1!W);8?j z^5my@_nLTVedBOFjFO`vR{k~T4~AZ2c8C02?FHg-b1V49_TBXvi&i-$yt2xyMGj#} ztaXS09I1wf@Rx=DsnVCtI7>>S#arqH0Q~E!6YBKKxkZnxm^X&^${T89C&{wUBbMRH z5vjET9FOEAX@Rt)Q{?5NE39ft}jz9E$$PvvNsSEfT^Md)Orslhpvb|O%nHZFt}V~%ig zm>53QU0GdZh}lg`DpJ;^RGmmn1nq=km|BQyPqmK#G-xFzy9ucJy#|Lgwi;`@4vt%$ zUVO_UTqU3FrRO^|%n;E**|j6hi-^lX|1ZCuIOtT6mcP_eJ1gmtG9&w0ulu`V9T@_c z346U{J(F5vDZMlpN~Z;1^d1xLAv6TpXR2TtIt}ieDnw=bV=ni&;)}=?`+xxn9gsXj z`hSW*RQ{Ty0j7Ph%pfr6^#D*(#77Vwh&p6X$JnN4=ucI|NPWP?in_-?6sJq2Q=#oC zdO%qbNCWbrYD)?~FUKQ94XJ=Fid2o^jnGVQTiS~T{T`UB?U=1HNdatzVU+NAd?q=$ zCHbg;^KmnF&w)mEN_4!4&>C(PfewKtnPMpqS-|2k=KyzLSBmr}*?q-p-HU& zhU9|kU?E=efCJ-5WTaOoTo!ut=jM?5OY?y?ZG&80$S5Ya@ZuKTIne@e=YZNx0BZN|a1W^JKiUNY(Eq7ux_khIC}u#w0X45M zSD!Ofg9|`Q47fTL3;@04s99K_ac?5QDXqQ?u}o)DrvQc@#k{v}pwJBGF#<3?B_@Pt z?6u5C7MS4fY=665k3GPW*ou{7`LyS}?7$7mW3w?MBQ`@5N|gmq_@#qltpHTYfFKi< zHU6Z)M%F5<9O7=BL0tAa0#WBmU3-ay7<5H72pa%O{dkMhM_YS*4yUaCh>IMy2qhca z7jLz=P(V3|JVGff8_z31`MPduqU~$1H-fb25e?ASALEAfju^|&$iPFH4e3gCKk&Wl zGZ1RoT7IW$LN~h!Ac*}|=FA2mT&v@G8>c0VXWBhl(=+xU} zyhe^N#HaGGHDev(39rI@wfPnyr|k0GW}@SCqXf?nH;)Z=EdW49XWRAf=R8$qg{A$0%ur5M<@f`_d;Py|897#AU)p}KM-D|O;a}@{r=At=qH}WB zk=fOsBTT9Ss9c4`gdsD2fSmzACjoK>^J!||qs$UOquT(N-*p4e;d85C>>|avs4Qb` zKf4|z-}!UCiWc$wB^xl4ZYxwguh7b43*3(gyBd8#aCiOIFY@%hda^Kz(BsocVE zkYAhxa2f+;2F4u?|0+HB3#0!d@Bg6zBiHNirVxOr8bo9+tQ-278C9q%dkDH2C6Cr6 z*5o1L)0At=#p@C{ss^GPO%s9<+w^*&tm%M`A#zoqsJAyJG63EPIBf!hL*M8jndbSh z6|e2caC+sWt>EJ79EB}K5*`syO4=I*t4F^}gi0WBS0?#=U0S+l8pd^!jQx4{TTjyV5L3K?;fI9_T&EC#}OK@53_W=;v zcK-Mh40$TTJgi8he}_Fj$iVQ6*nNvW+Nc@oYlbGCHm|~lNq5iDPl*j_x1(R{tLdX& z)zZv5(XxRS36-9x6OAs!%<3dA6wub|B>Fycs&cm3yaf?oWOX=v)IHRPjQ|{rBe3n9 zhF%D+_*v$SL7x$GF1>n^=~nZds$R7n51V&qt@{HL@2NBw+2_^Qrc7wx~=G3 zi96@`of?fO<~}#uMzN|OKoGK$G1%&ZMo+sjsvH3M2#k_5&q359LNhZq-Xxwt7c)lz z3M`(ca)|9~Fl6u(wJqx|078r0EOyVr+v-FRhmN0gwJ|DxZknFRv|>ti5g^4)Qa0l} zGWV`pRW@r(&4Jgzs4lw~)$Xf{dvXEh7o zuf%;hnTJ!Z`trXc7%-4LSX6vRQYJ)JQ;6TG=`5kluy`U8N$9?i;JTDIFIGQdL(Jn5 zhky6}+^LMSa_hdWTselUn5u!F5g&=Y@_U0`+;^WiOj^I^nj3UK;~3!?gKSkn8=$X& z-PZ)b6J7!UCcwI9nf0#%?TT8D&}98t+&Aq~)Ja3vf~Bd{uo^a!49XnlEQp8{BYWoM5wDPj0K&upq#M{3ZbY)Q z{>PlNGW~iv!rx;xezh!v0_ca~9s;nXCwVfP2IDMxYeY0V-vmRro0|hfBwMD=fgF10 zz#YW0YzQzBb(%tnC9nvc{IPfg&+uM6hJ(YL!|#!m@(NyJG959+Y_kM=nsKdo}^T}8+7X*17 zzbe<1U1Xkz7qQNVXw~NQU^(Pdb~@kYtZ&~jB4m6&!a#oXQkvsqe`LWk`XM4-7bO3j zKs~-m?qXFEK=OxtXb-Cvdio>@80|P+Ca0eP39YKRT>2Ti%KppD(glLY{fHq(=IL}+ z;O3L(jDeN!)~L_TYLx3I{n@BwjiO!5K84 zb;5BUmP*vMQJ=ySrHboQWvDYF=IOjo83X-0(){77j9zEy=MuXF%Qkx_e!`Yp=k2Sj z;fVghH1JURIHb?paxTLty9mBz=IJM_A6BijwVE7g4h@ogP<$yCboG3rxW3eGYYM;F zl*y}JI40(04p-^wa=w7)w6|S6PA3R}<;DslQ_$?;bT+z{T_A$IWN0#&r>{EGm|}g< zo~Dv&-Y0<|PD+NY{<17KoMWS`t+5^@oHzX@q;(~Z)%*E2ttK2+m8yd@rg(6R@1bba<;nGRr=Tn;OGi2Q z&-%5|3IpE16TRe4!9g9{#5TJMLNKl%6A4OWIk+EbPv^l#TDUM*mHZpIg|yhJyMIlu ze#MC;r(`<>^BE6mUytqE>$z95RXtD-CCMqxu(xtxzInzP%HDrz>;cu2SzO6 z*C(6=BwR%9xCsv!7W%cJHafebVTs=x^&b2@!24#Pp|Q2YEw|I*fzvQ3mq?zG-G2mu zbI*)``%2s71CUq%QqCZYi(t&nY!R%kbAXFY@gY>Q%P*7z@^@{~_AYInUqe!^St2}= zkqA{%`6sLeIZw+7PV9SZZ^KrGsrV|i+Av317wSIeA=_EJP0-ygF^rem*o}(pDK3b*i31dU!LIXDqpAfr|+(^Nc&L9))?`54~&R zcU`7VZ=S}M3h#W0nHOSWsMgGH+1%wkRVqpf&aC!9XYcs;DpIyC?1xV+=TolC8?SnA z_ZEHI!Rd7FrV}V!Zf6|IE-RA`VO}9( z!96Jj!|E710uhZNsMPJX5+Ls4ZO))Z0we;;mKQ~3;I%~$m1EQUKD?6jK$`bS>LHY3 zn;UK(_h`AleG4Ht5|zb>!H>5`JDavJZl~tE5Lh2o-r!jG31tW##?M! z8?gDbTFtiIZ4SZ&cD|ee$tWx&28(c3mKJWJHxWhhrKqZ)z0g!%^Jep$WKH3hs-apk zA3O>AU^?BI$WLXfD`oJiudaZ|xCa~0ngizi0}$ovFmiks_6AQb+}cuSO?Hg*ZRunq zS^gIo^ygG7FOjBs`>8osyiYJI)q|w0g=5iu@)!T_IJ}nLg7x zX9j4tK_+?|FhEUBXB8l9DwskPl0u4?$5KEJCY!wKcVL>2)hKT+fo+fTpP z^X2e0nEj|^t`1$D^4^NbYyeoH{Exs=Qv({P4VcZ24Zy`}fa5m#R_}{IoQzq7ay#O= z#TA7u=^kKyo}{>t1v#>~zKX-eCXK<7`BJCO1-{M}p$&jF!aNKp3BnDy83v{9g1JCr z`7v=H#|}o!sX0%#Zp0sq!?Pe*$!lJr2hZlIF2W`^$|%oW~ENlW4z+2(T)UvhnN5 zWFanU5=@YcAXUbKSR>)qLX2_t-rdA~tr~6gYNJ7YOs5#}kzlpO)tsriMdp6zvDdL` zB{@d!4ILkK%jMwrz_lXjF&}X4&>iz6gg6>hCd{n(mDC?4V2p#azdC?ANZU48P{XjU+?Q$F=zn!ym1 z4TPqncD$?UNou3w=ebB;qwx*bX@+Oz?Rm5uL}_SCuSbk9@#)-L5lWW+I?RMD>nm^{IJPGSLDi8)v4)Gs@E8eB@&bJwmqV+sVM06#PN( zpidC%K1JCn(H&jJ_yAg(Ef{@=bs^jqpG0|EiCXj-;=+!>GK6fj^4~mpxG#Kag=iIQ zROveXUTnH`_o8WfVx!Kfe%~Jv0Ipgggk0F{i3YY8r{6@G_3;qUShOswyB{$l3TMh| zG-fPSU*1Y+IEJ1v1I7=%RFZ$R7#SM9!wD)2*6)E*mKra!Du7V!j12sg!sP1Fc1H*o z(pBQtd%y+fSWT&{Y19nF30G5!<8_CyzV`BAp+T!jJzUm=jH(2&szNAv_3cXvj%SD06jS#T2tvz8r<0Q7F3Ncd;Lj59q1{BsG(} zOhLTtDT;5$@;>%ozQ zzN#&hbN*uSb98~kAzHqKO|^rGWC91Y?*f2O7Rc=5%9s8gujX4qvI)&m8)Fstum6g z<+y_P0D8)My&<4;wywG<7SJ%;NBMgc8l7t3z7Ko|q2&l+m72)dX!0I!!oVYaYhcF{ zT`&{?sVwz))5`f)NnL5x0^gjNHb3JfCj#=ByazKhpM!lgc$%1Km|xy&Xg;*EE_cxM zoYqn_#^R>|w_v86sxba{k7gDlARtf%$@852Co=j^xcYxd1^__L9EDlOshI%fE>MIR z%R)xR?Buqg$}VuqXvm+Ac`RX46VQ}%@9+?u{qxjwqJ6~;6C#EvR$mnu(Lq5O9v%P% z#;R^_^d=L%P0@jB$P~@*5JwSM`=<55Tqym!Z=F}TaBW#;==1Oklb@J^X|ge5(}!?} zbqf@i86XjVZhVrOPBI!YCPViS?OFM~MGu>AuM7C>B@)KU}8EG#| zXa31{)9Xcv11`=of+ppiu03YXpiVgwHzqU6M+HCo<57fzKrU9}GVP}LQUEl}$tN<2 zW zWyaM^02T2c*Pt{+0BR8gd|P?cP#6zk7+C$9%J?A0+$1;qwsqc zWJMae$WK`r3CaBOE_cO|yOZ*B$u@_RJ!WY{<>`nkCjRz$luZO-_8vU6x<;>o{RwQ=V_EMhO5HM0D)e}#_?e|i;Uxh zo?rwS7dr;2YA!tVUi1oaHhn-@bh2uuWH3TTVfuKO+{rT$%ef5DD^|cGRsaCNDoEZJ`2V7vKQsb-!6yExjK8k_ zyay@@w&OSfz+qQ(H^nh7(Y#mZVMyD%_Q}j z6Cz6>e!t7Vz&Ve17xAq7ACWb2Y{&$NU`Sq0Qgzae6_dJD<)na z=R>J+;2R1~*wjcr6a>|BjVYTr8+nl@n+lAK=O-{K^tM8Jt@oVwjFrLUCb$@|Jk?fs zJ3UC`)#7uY6eI@E0b1S$D4YDh;57)$pW^&WC}2n&2Y3l4{I7dp!uC z#lUQqBXM^|=}IIyjW#FO_p6IpP)PFQy(=u(0;;&~9#s~5@0?hBQnXE_qP=D-M>`zw zf?g&YQ=n-FXmkFK)~~ThZaal!(C21W9aU?H0q%D_y zCluDaw_+@lmN&(TpjQw^TRhLIQ8N;^ly!)Yi&z-_O?7T@|N4CW_rQWa$a57atJSJS zD#H=0Uj`;4Kc!OD{CiCxitNve_Y}qUzxLyf`Qq{(Ofl>~NhE#ZlZ9uxOn)FV*M{@Z zMuwaiLB%4<2s+UC_3?2WZ^Q#iWEO9Jp}INT*=<^u-O#-K6WzL2ZQrRl5UA}qptkM) zCNuv;Z2#SJzWs-i|F~P`3afLm<7dyxi4JYs^VSa5@>q|c6{MG+db$rk3UXabVa8f~ zF2lP@cG;&xcJz|07V<4Q>f0UHSwQEs$w4oUsk$cPS#Ixz@sJsj-whe`)cIxn4jpXa zP4)}?l(&FpG9sU5a~u+x24N64#tqG975OKL{Wt=Dn{4RVPI*1TOEF%PfiUtM%PX)4 zOxzRx9IfxeC%ww_rQjg&Wx_CpMxU)61C?opWWP7XMvc#w84C7C(0$*GpoF;-_oyg#iCP0adq_{?P`ht0 z5Jbi*L^tPSW(i)eG^|(XP~=gf(Sv(Jfqt3BTyFW^&Gv zUv6)hb2zBa%M#*gFB3*svhE8{XWFv-matjJmY^i-ajUKeT?cYfW05Sc{~IR-rXnC~ zJz}T=lo+ZX2U)9~eo9@qg- zxbbpX0!QO+9Dr~RLY_Aq4j601x-oi;vMvF992qaO1tn8PRs)CiE952BGxT0>fCriC z$R`CkGNFB?sIEa`;pE7kG5f`y#7({U_`3p!vcy)wMo$R1=-R>n)ishcc5&LwTQ>X) zm~r#4g^dLmM*7J#GZ5VZNqbguCe{!3N6bv7w}~k+)NM;XhS|6&H;czdOje^N!3_9L z2*`EkqQ`nfE`OZ$CBdhQ@AeT+M{HjvkV=H;B4u$W_@uXf6}s@q3QRA~Go^7I+k0$K zTiURqwW9A16Y=rkxogUsZ?70$$CRnbm}M{X3!=6bcL^yM&x#jp#~P$Ky>7BEnSW-9 zMfCv>`1TbJBOC*9mJ4L{Zq`wLvw{qBflWELFkN`Q;j?=HeJU^S=)&@dM`#b#HpUQA znniO!V`$GuoAX0^jos_`sQ#iB&)mQ(3B@N#$+!$r|Zl$OjE@K9&f zye-gyL@eNQT zsG*h~3R#B&US!vxL%i*5J-g9JVqH+vfkY5kAm0vd)r|=rrMj;?WvsYd07~}@+OHNz z@5OSP>zB)x?I;3n+d`V|8RMbEN3EUJ(xa_~B)bXcN#i$IXqIHM98$<+ABOGE?|6Q# zD*2^qGE~U$9G%-x!pyoctQ4O*19;e%ZvBSGMomF}+wYRaD_(!)up{P}a}sL`_TPfD zdH~nCNoCz{>j@Qq|52i;$5!Vu&LbDg0-xOaMZZWy`$y)O2<4`YZ%*jTXXdw40 z6r&A3k}pUl)uL4G@xw{%?DD4*#m&g-Zm?DIP5LOAg2``pUE;GLtJ+H2iiU_9`K&Bl z3>vyirk=fD*`(SBJIG6kA58|5hJ!#|_u-4@*+pwSSBvFZt3pCTRQkl=$Cpe;|LaiUZi@2uM6nP@^IE#76*fdo&?t#TqS|~-;2~~7yy3kqHEv`ezz2C-vAsTPZ zJ03UJfNIF6ADN5j`jQESAZj6rU%l+pA};&2WD>+7%N`==2GVp%s~6(P@^i39Pdprg znJoAv<%0)#&Dp4~_3T5~L%+j8_-_n(5C$-Rvf z_m!nGVfe8(%o$)C{HEDkI+PPC8%`u|^mh;h`-w54`18|aJi?!PCFTWfoT}EGCxY1OAD`ikCkUsAsreYmB7i4 z{x-)V@e_N?s`QNhAY!;8HODQ%M4 z#}Q@|mQU-_YIK=QE&Wp{@w(YKK;75K_Ri7eLTFN_C*h5BKe%%%0S^t_*sT&%JAN$H zM-@HHYs$1lY2W=d1*2Z5Q@3c~^4`w`%n(egf zwTQm|^fV`XP*H{iR+Id(!%XD=8{2)?GB(^m(InBYDt>#_J*A8>sl^bJF3IRpCt?>_ zx{GNUP-0e}fZ6i!H~P+Si<;hYLGtxes;zmDZoe|vC739LrxZ57=u(DSUfpPBfyu6H z&@~riwDu9cKH&WhyB9k|lr8V2#N;%pBCaJZqV_9u?x*j3drAxJW0J(&LuCh&0}X~K zLr#5u?aIl9!pV8~&|9q*@q~f1RyPoxcq6i(-I&Q#vDEJGdcIjX4a2?FNI z0J8E`H$kxM2mn-|vK4l)xe?RumzS>(ezHOPa7ub|3p&ujHdy$vYTr-S^z_i@JD)KY zTv_Tq)An#=1qysfKp!fyEBTKWcT7fExZc_x&fH@E_%G|HkM4B6qBsg!v%bfO}No zvJLece~Hc%#^ z*S_$jJX;~IqQd{;4eG_k|EXt(2YG3~OwD4UnkYR8=84;#yAAm6D3|HoNR2(c`0-w% zjXIV{Ay~8p(gK$Ul}H^ssYh0~svKzITCqk05(OR2@95=j2UB%t1uv;wjqp^Ii5`Rr zP_hF6l0$~J@qb$f*j7-5^oA@*5qE91G-X1nxnV;n$||%C6Pq6;#$gR;S?~3}J}%wl zqu4o^hBI-a+x$iX-8V*0LvrFJCF7!~?zC`fC{Ex1S@i3sCH99K(xP0tU9dXpirxWl zEivXr2S$(Vw#!=v~rj`AMJgaIibg ztEES86VS@45SwBpXmBz|@|IX5ltD76JvPA5^=S7YRp@=7yaIWmi@2^i zW;A>-e_%I7H*6Kc-F>yCMv4w`6R&}uGi4OzDiD5hI+6p0-Avo^Im&Bf%TIt9@aN){ zsK5C6e~S8F+Gl?OYY_PNi`m?^y8w_$B}K9Oc2J81yULJF1xf*PXju4O(&oio<*#yv z=0<|Cn2r}xs_I6>u48M>E}r|6=BaF127SM)iN9c4%k- zIaHK`B}+wc@j;OIS|9~%8A{R`c9G}_sKO%G{GhtL1uOE7Rh#~U;M(9eF~cm&OL4n+ zKX3lVH<2Gx9>SFe1dyEMZ?J9o7+`MK_r7U#e#C5`+k1knyZEADm_~YkjK?UT;s4>t z|69WEFTqizfzpBi9V8eaiWS0;jyaPiyN4%nzFw zF2Oyx1`jTQ#wECg;O=e#f;+(-g1d!afnXtD=bgDTbLUFkUwu_wU1xXqANyJR^x11Y z`;i!zd#PN#Ouzz{56jCDA8Y+E-tKllpa$IYUAUg`x#9KJ$Kdv4z2Xq6I_Uw7MdF+? zD&rGy+_K!`g>4#@T?EUG=smbTsGDA-h?c!c8Y_TT2|HX${cW`IbEIp-D{@^y6fPwj1H7oAgweX-kzj|k+3e!44);VV3mlr9> zHK{SZhO1WmI7^AU-1@bXTN0i^FG54wYm?6wF7oGI2Tk=RO4wpCQC9nc(FW%>`7JG1 zIpS%Oq0(WywSJv4g2qXZ4}Uxs%FxyLKgnZ&9iYqu&7)5LSrf(|g4`|1EDfWqd>p+O z_rHc_$ZLX)4e<1$yi`3mHf>;n#$PiS1nl~-`;ytb@6^S3cvUq`*M~jW4tm({``7R%xU?PKc&D0J#GqFS z@l;Z^ggRgBG`4V?IFS0*6qlHU?qGdiqTn$ z8c`l#+6#r|NFww7|16kui;)C*=y|E}tbQ-5epd>&P4_C<*I?At?%cubt!H@`dB#WlG25=_Z!adn`8f{SZ%!dr zHL9!NA6~oXYI~xhFH(cOj3g*p{IFx7^?G(h1cT7u)4!fZq^R>bLv?V~aWnD)C*Lt+ zRaarZr?~wRhuO=o8d5&%@47+w!)zj6|4qb$OI#?o6(V`z>cz#K*{|8E+mcrt1S$bi zUN?yZq)7**gwmIeZ!s8(`f;xI!LTeMt=t`x(M$MASzTiqP zim90~UNpJlc*-634)Fa+6o9!bH_#=4$&6@&#Ob%lMI&l2M^0E+J^W3e|A9^-s zUJhR|IUciTk#t^%L6ldpap|*fh9d(b5qQ4t%n}aw6ZFZJos$naT;wpuO0}h+*EWmu zJEW%`f3)-#&JsUlgcs1>q1Z5x0KaCGVDw$A*t16}%Z0qYLsfb3AbYTqi?IzI8_b`h zfz31z4LkI9PrRN&oM_+u?q97acKtS?r&TnAZ16W*v-N@Rm)BKE^qnxfQ8{4>1?I7p zU$jpJ5Oc9tTxJ))$B9r~Q(PdLT<=Y3k$OSE+l^QPoieAJi@NZQ|b%rW7X zeSncHOu1|Kr<&=Un0mC59t6G|nknE7n`)|>l$uOyko{zYZ4|eX9ndF!QM$@3mjY(N zry9C{O1G3O#Zs#|R&a+CkFZq0f^ zgQiIW5IdB(`dD@ed!QmDnjJvi!PJ#p#!=4~odqNOJ@qSENbA=4MHb&V z@@r)DAFOA?&XzYp40P|>w-n(ck5X=?-+a<5!aGw+smvS7QPkUb*yL~?L^5#>b+QlT zIb}8}nU7N7|A?X%*B<9~8G$PPd`M9%C#dIMZ}1MzY(kF6YCAg5D8MY~>^6+>i$xl0 za54j|-3I$0+}+8riL)$hF_i;ZEO;%T!DqHMM!= z+?F^8^rFhRYPMX@J-*M^`y@76k+?Zoo@5Ao~p`9 z_eih7+1E;g$8fj>uKbOK7&C0j3zchvMCM!x)_#joX2JONpKSL@E>2W4FWuCzLafKq zF%GCE8lI1TY1s{igj|TPCPGL#5F@j zgyzFf!e=RgH;vT&+$2{o5ml^uFqS4JzP$9T)7Wx(JRH}xyuY&vCQUGTspmgDD}Hg- zL`q86nJpP2MI1_%065A+DgYRxLE3#RL9WOPoY0?e`)G9?sXyP@e0}OiZI*|*&irLD z9&6Tu%7vAZB_LBAtmt;Ii{xIq_Jg(rR<`L{)hyn0MWph{{4^!9^>NCu+Z;dDG}O-2 zWqN?pDD3g4+%n4tDKQ?F|6i>kuJdVA@ zV(OZ|15y?YF2Y^l*SB`{gZd z`hlI%0U?vetkG%M2q-=F%vmlCmY0NuaO}150fRIE_SX9Kws9-en(Y_M2*ycg#ZKWY z{i=lp4mU=LZ>*yDj2$A@?6qQ3{d9;MS7;(NKm1I$v67%+Kw>-pvbjUxaATm%Q-UEhs<9MCx_KJyRN`#BYvTCj5!n2Z@7n zGyfkoAOJ_lr!Av_pH0MYEJ8N0|LudYj_#tE@D*)!dndiP@8hzh$ir}RLCp|oMkUzF z<(nT#lKKF5!SV7ry4g;hP^33Z2MU1?4!nF~HY^TBjt@Am)pCsH?Gj@CmSLbFX#^N) zHi#B*6z=`WV&>*uqMG1B{U3A<=0$D57N%r8>u~A9Z5OM`#P@*S+^0sndx2{-MU^ie zD3%Y9_p+{o?QUvKBe59nFE$yz7d8zyRz(l$!7=(Kz^BX<4vFfh8pCIJ&q^{BYWG1# z8J51TZ|Gf)yoQ^i9X)jRv$I*0Dth%)QzD7}TI;o+WHVpHx^FMdXDvtF%qQX$olY1F zC!OVkNM+%Mp)3~w07ju0{@(=TKPV?%GV%az5~iOeM?V*)hZmv!xaa9_Y;P-hjIvu< zPO}+vfMaN@*x-tvnN}J>G;65$7iAOf&y_05SOzaVS8I5@vM}+U>?YGiOcN81=7c|y zvB-Ghf~dG|RG~S8yMPBV~GRBT%~uf0Nn5 z1ZGlJnyK`Z>ES=I;;ahjroT*{KsM4zcb~37y^d5^Csx^khsk70jV6RDHZT= zXyTg+C|`eVXTF3dec;}48!2&r!}D%2T90obrt)# zFhsr|qB&AcmYgE@(KD}^{iX6j$$M`yZIx83ypAJm_R!U;p&R+Wq8S{WCk;)Zf_c!{ zN(>w#@kLq>#4sC3;n6BQq5SFViX9>pAT&MdHHawbMRp4n=YI zjpP3oZ|s}rbU|1eomH;()CpXUz0%g%MUL%E)!Zdoy5B-ihyE)VpdkGJmt?))ICp_{ zVJ_alCpDoUESxSLi@7=6DQxOetlGThVI)j0n-Of`US)X@Sb~@`A&Dw&^<|0v>(F_O z%3!=q+NyEH8U|tI0f&)jV~mr~o&(Z@O5BmuXWpmv_k7>FP?8TuVZZy%rdQvriSugw zGF!v{ST!bhgb^$qvW)m8pGJMFfg?itq!suUbioGG3LqZ)Ey}N4VbNJbxa<9N8&flE z5=(^g8E_&Mab~CtfGeyAw}~58txv;-;=bgRh5q#Y=XknaHSA^h!*2wJTC)={2(coE zE;fGEkST##1TF|c!qBIjp+sgD-Tzuj3R(%{pZCkZTq9Brpi-=V^A6GXEQA1pDH zTU_)c$(V=NB=*m`*%)h?cP3N!NTMcP9bwYClxFWFkRw7#J1%WuJ(=7;H5*=VU$UnX zos!~s!jd{A!-OvptjPF&wWv529qiv&~m%KNW5iGv`etM2>4kMgJtEdXA)y;6< zTqh0^R-i5>cdrQ7q?lW1bF||-Wz&>79$PVciuYX$ZIneWA!O$n~aXh@gF{m9}P_WJ_`u3 z(#KB}y2=pQHb-{)q5}2t-Y28qn8k1jnK}(3 z*(X6fT`5dCQBCsSK{E>}LY9bNSvp#@bKOQZKlr-yJlCgQa#w4w>Ax|fzLSIbKvCT~ z_*)~VEK&HKwPty$-D3Pjx3Z|;W}D4f$cOyU_?#H3H_2_)CFJHTn0FYCD(`-`Y1Y($SwT#?+G^0=!lXE@hzgE9?xDndH7{p!Z75Oqb-1Z;$;&94^eUj zKq4`UpaBrVvFe^yT%q+n>2Zn96PRGVtP@fC>|SImxZLS=k9t04n@;LrY9-u^YOh{N zrqlDfFach^dJq!KaG5WWV+BSM`LOd|o!c)P6|wT8fz(nt59b_VA84S1-l%63a-eecqHy>4n?>{KI=rj_zBbXTY4Uw^B`Cq)& zp|zf2$o-_1Kxb%_THTDbTK(CYQ#5T>s5h%O-`>f0p5k@b`z2w?5bvVRGow@A7<-~+6O+~o{pyyHK0V4}P_3DTO zdOY1|!AxIkG+~eXay@eV-8f@hm6v>Nv}f;|1s_lk2DtSY;4_%1Z0ibtf8OjJ?k{wh zzCXSD@jmD^&T`Nrjn$QHd13JifT|C*ejk)uh5BFPwxA`X{$Hg z9+ztr_NBOMMSN9&+a*h81_IOY$5^p-q$u|lfg)nA%j)dw_chl0<+4I+J7BD9PjDBq zDHbO1>N+QK>IOpaYvRiph}JUul9yD_DT6?uwQhm`6ChgrM>-F~b0kF^fWw_3^(-v;3QsWtF*lAOQiNFp)v zb7Lk|Fo&@H-cgjVvje7>o8Hhc;YiZ8I>&J^siHe*2!*7z7-ZyjIS~TN428dUF5-WU zqGw7D5vAA~U9flUOA2@9iCx8RW?l+1uuv%IR7V{O7B3QKjlH3U|9#>0mbw>#9On{CU-#x9DEL|}<-tzFV+%}U-3;Gq7hd|l_$_C^pwBo* zqO*)>7+6ji+3O9p9JXC=Fs_3ncWGJJ3*+`^u$)8vo1@Z{YgKSJ$92eSmlE6Hi4UI8 zA}lW1Wx0BD7%&mjb{KG6@{|11TxOTHDOQ~#wkw7N?E~7+o9C>$3sJ!*4Kj$t5%Hq$ zELTW8;5&!jsXkj&v^AS1l7W=bnB68`I7HUA<*06sw-$p!w3}%~K2WhzwX~z8rBm$D zU0jC$q|)$oqj|+VGtt8clYV|9ely&Eu;bDwrG=`G%sCyev5geI*IPPNi z)0SV15OVp?P0=M*HiR0H-$Lbn^tX?>iOa92-W!vZ53@m8MsiA;kBoAVAjsbT9;Yd+ zFGFF?%IMrL|E)oHYZmNp7cDG)*b5PTnZsiE%y33Ra$0cJe#IkM<^1ZJ_>GBe%fUJS zA)WsjJ<}`(jBcY1W%P(&w|yR`F0$356N^{z9Yp9XZuu5F

| z_EL>{(p%ePWFhMv80znSXZ@qxtlidG<3&>}HPJLXW@nNT+32!a~BdmH(kQ0m&7>$#>)x&8q$v^fL_!5N>@LTx)!$)M)-6931R^z2$j zsBiBmxeHKi3tE&+Y7r#j z20Qd;*bdhs(Dm1P7jK1E!7P6Hs3Ki`+1JPU)dUBD;-%{DT?4Np!EBSVynym%<(C%> zr&N|v`)Ff|eV?fBq%ZW|IT$Pk_t`}vt*Q`D3u}lAiY|Ka2VL^-_%ixyIZrrYO*R$X z&1g(U6Lb-Huir3Pf?8X#erscds_ERZaK<^$w=kmnIkqf|KUxp_=}yr(y+t=@IPv)| zY|K$Z6Cn_DesSq*r8k-$$|4f6uEK5rl&RjmJEDs8ZVs3s{yd^m>1N}Yoe_`r&Qj?< zRz)3VxX-&_t^j9-84sOoN9o!;LD)dNf)RV2ohxde|C-D3scK?-$VtPfM@Mnaw`f)) zORFYwx{Oh-Q*~>L&v`7#j#Er1_v`9$(v>1|Vdt8aVlLz?3deiJXC~XI^l}@>-vY$7989`9d7rxK@&7zlUMO(X;oXqd^_ie zgmldFjN&{BN+;;i<26l7Nljgj?{C`{Q&8xUo$xY;anp+#gS;c*#oR%Y@;~6f%~pBC zv8*Ys6V(0UULk3mOsjmePnaW-=fV5?co<_>v#J`D&j^IvHyjmLt0>f)K9Rz?1VfSW zb7BYGNdha5u83%lF1vcVYZ#LTr4y{*)VMQj*3Sh#iEJly#3r?&5!K(*A$dq7%6(FB zOpQ&K9`Pv3r`#6raN(4Wr8}lqeUE-)qvI73^O@mQA@3)Qgll+9_aw6XVNMnLm-*ZI z#SY(}c{CNu(}h=JkukiC(d|dQi}zq7b}>iZw%k7?DLV!bZWxI98&PEMzj!i{Je_$% zQU7kl2kmtbO^X7F&U>B1W7J)yj*fufq#nX)8f_@=lLX~6K z8ydWKqte_|Zt8)#NtoT;5D_wOV|R;S5Bi+gx}veBgBD+plZUGJUbRY&VfY;d+j9At z%<ANk*r?Tbr{K|qH5k;oQ^ zmxT|5ThoaU!?8~AxG%PbX4#a#!)>H4gYrbFuL%DwJot5mdKwSy`8`E%5FGOkOPpgt zCYsHO%u6b=9_R5-O54@Vl~;}-$XXU(TgB7%{;Kiw$Gz3z@b4&sSL>2BE2p}#MEWjK%^i8(63qVrxR~~gvvLt{+1EhintyWcv%FxNzbGrEkzXy-nwM5+a9BDq)A21bOt; zQm9eL^SzJ^*y?b=^%2SNuw0-hfVXlwm?H_c`SIz8X-T+cXb5Vlbwr!&r;rUF?J07k z;a-FHFMGil$d)IM_A<|6+TSVsYpUIFaa@)j^c(GePWJ_f!@Pi6y9Bj%{BJz;KfD$& z`W!GD|1|aQAH!-ukZ9=C0czMnh}T>K07`@DI~k&eby|OQlq4CH(77>9Qzvqi<9g1d z7=glGW#E(%+ke|Jb5tP^0;-GD;9VCwU^yVH)4YpB`TcRP5-rPN`e9dY+}0AiEXXXT z6=_+4u;-oDVl#z#aG=4x@9V2qc=Njcm2j$QcppvgEN%U!2Nnar`pQ)#lZ{jR;rI)y z;T??&Yc?`EJ526}u-pv?W3h#BeW)I$KoSsx9+rWGp{9NN4~ot4#~{=?EvtGo z-@~&Fql18imUi}zEo|C4an^9}n{N{nCzv8{X5?|;G&)ceo05sr28_0MhweY4&&~1* za9V3SzXQ!vVj{8xT_LdS%`UfI-IC503@yCE-M}^eIfAFcZ_x?k*bTnXgm6LY1vXGz*P%_*t*=RHx3b}{p_1Y?Ftcy!(OAq6s^T6??mZYPzQ=^T@f zrh)HUtc-URnUlHB9M2C0&7>)=Q`n#-_FscLjlu6Z4n3B zPf3G9nz2xtcUns+6ir#kBGju4yOK{|GK%*CL}>=GI7b+|>j$%gBuN<7OkbKCVW&0D z%iyJydTPKswz=C2E=Ut$qV}!$@ zSDR2Lbu2z2kDXI4%pE@XM@~PUh%SC+CdpcUA6)dM*r?yTr*JdoTzjWXAXaz|{qqnC zGHTBep%Jc)n*r=A2$xKDggzSkf#ek={%iCBa`a?C!5))rvI#0!O{_L9WctfE`io7X z?Imk47lLHqHzjCE7HBzl(kAfE@Y{R#3ISZnB?nvCAnL71{XTe6-rg07wLCfPMg4xO zysLN|b=Qv_pKW7%S3&w8=@Lt|bmw3`p?~lTrgwv%8G5S~*N@jo#QiL366Q_sJV3_y z#h+?PqaL0|JzjwUInBfRz7{ku#V?ICL`}5D$yyl(g%_j+T>+N=xPkxjO@nr!M{{UY zj~Wn|G!|%rgC&_b06rOm7*454^;~Nqd+7CAGL7h>Q%#d|kBjNkTg2G`Mpf22?W~Aj z(ka=Gyaz@&7)(Tg^nBI9DJsApD zYR+U+vJdI0TPR^#Uz>#^J_Qpn5Zr1Y+N5S{o-ZZiRwA<&8?t}7!OC+vRGkZukX%h` z&&WBqOEmBmCL>%B*sAN2SpG~h{qf+}mGq~NH{&WMXq?nRYW?8L?bm~bhw-Qe6(=_e zWC$Eg2vDZ2E0NjtKT6U+&4T_EGyWIt{m<(^E?npyLC#^g-RD(b3qY*C`dR0X_@(V$ zG1N=8ZJ1TWPUf>wEeg7<_caF~sum%2+2#-N3d*XBkXu6ZNIE*oU%+m0<+f(T`BijO zAjq;#KzMQ{qzbKQvd58TQgU~sF}E#bm+c;ZfmQ2~oG=%(&jl)d9cx%P^S7VO{k$kW z-AQ5f(tOI_$OMZ1hPxI>Ciuyt9Z=H;n2-p{Y#eBI%%@7ma; zwo^w#sd2`v+vH&B(tI|4;6W=)@HI;`z&s*|17~N{FzFL+%w5DCpF5_QsnBnAuJ&{( z1f%LDqtUopMHupT!#$1Gieg=Oi=xvBMeLSq;Uio^o6rxj7nW|=?kDfjbo*z9B)7f{ zJA{+C7v+7a@%r7&R3Tv1qh?8;b|AfVf=375{TX75quEC*YxTN42#=T^qfbWjZbjCJ zU@2Ey_r&53={*hA^XqoxQ?#kfz(V{clPKO!(O2m12)(uN zC2|MH{|6C=(wv;|u%rg~N!|&F}mxy=!+U#>zHFl<94I&7c* z)<{c-z&!y2VZjcLBs3=RyqCE8bxbFJ)3;7u*di(cZH(4*f%9ncN_eHt<&nJ8%wI!2 zxwci7CwjVxFFCUIaD7C&&@|<;;+k7+{pC_i)M*bkvKvoXQ?D3tPnMc#l7)ULx1TGn zc%)*-t~|bM!D2eIuowN7u7;*VVWiKgPb(y}Be%F3gN zA6X?^?Dq%=p*>pMT)mGRklGP6(to|*d8f!FWF*_J2X)easFp-R<)ZAp`j% z>Rr2udNqC!>$M4+#g`jdZH7zCFBe!!sU#yFl-gVSvNk~Bnqf=bCFXJ=@&Ne)Gr(W& zgSd-HdUfEK$XH^P;-94Tn?>ZumZCrt_A&90J)`&@hkI@3WN(tz0b64k4F|{s0Dy0x z+=>4}&4K@1arR%6%;7)%Q{V7KY%zl@TD>i0HYLvW5bRM3CcO6S57F2~MMMppAfUa? z3cifCnE8Bt9avuu;%B1w6JhURQjWidoF?w`3ngy_39DqYx)o)XILmH{!_Iy(Qscg6@Qqbt-R=Tl($MP%o`4op(B+rM;>K*}!QzCd zP#z#-bu`!^&}IvORZwTj4$Tf}hY){#J%Ua!^=W4T-{c|((1L~~{&DY4{F6rii=boq z>)8se0sD`~D#;eD>7S9K39u4Q(R<4AKp}MUTZ!{b_|)4b!~k2LG!0-E0Xei8ZFg0Y zef%liY8J+PwSVtt6+elDXILAI+o`DcUWGcrfhmtNGbMUz?nlT7F574NL;(YPPNnJu z*;d>1^@ug!(g{Vr(MN{2moITxSQ~o>wGkNfSyRj)2xYNiOhF$IVChRF;yc!ef#*uy zej+r0|Y;}yuS`;+s6a9i0(Mzpu3&q>C369lG>Ia?*1 zBkC5IfO!wp`Ut|$R;0% z)hN{iF?5lRr8Qm3g&=vqs8qY9oRJVx7N&FufDRTDI7vRN!=7AxH>^h9gF>y5M6|87rgid}vpAxZ)BEybxcTGVj>YdA z>zLofSs3NOc%5G+tRSA7diEpfa#{>}J8$)%lL9#-4j%nh$ec^q?Vo@A zI67J_5hQ_v5Urapriu0iS-OzLed3JSm& z6oCKC3IEvq@5#l~{s74q`Unsg@>dK$a@FgTaT?_6dcmF2w$}-kT~~>yWyajD$T9mj zL9!GM>;l(ULDIW2s@Hme;NvndDN5hDupiFwP4YWJ5_eotxk3iQ5A+d4`S=MZt1UQw zecX!$LJSD&)VEJj%Bme!Nq(!?7qC3g%A^{-Kb`QwTYzQyj1mf=jW}F&-Z=nJH1T=m zQBn}0{TxAO4UT`mBY`N^gRlnOFN-BIr~Y>;#_((H%u*T9P4w#R0il2R=L$muj=1&! z6ve-m`OghN#07zOR9FsPC93(npr!*K4p(5dh#u>|+Tx^6TC1%79D3p-9y7Et$VIK! zw7;(KttQZTr|COCrSIDT8|^3$y&_yiafH;4oM^^gB80F^Gz6Snwc29h=?4+iI%_N` zWGYCI8xJEE@7zOq%VE0)IuDT2q|5KJO{QHZ+b`ApfRrEv>*w2cicyo+T5-Ku^(?+% zGcAMRjwGr_nCfsw(z0d{9L>Hz5CRW6U!Cw_9O*~h!6~=#pY_~>yZVV;MUIJ4X)IA4 zeVh=>`BP5f(hQ>uQ!%p+(RKq5Vq=;kyrcTAa66TdOw%)tM8kcl@?cFxiBj{f;L!_V$GZx#h1lH*5sm~11z zxy9w3(jew?WTBJGvFFdy>qD^b;9rlvrJrn+VU2ytENmbcE}J!2<4y5>k$Ryl| zrI(NftD{~;xRkJ0vap}%)Hd`@of>0obc6JlD$1xoisP%hn{zWSUu62PH~g1j{Y42c zzV1il8ldD75rK^YdYZC2|-4TVe-_ z5~Ef4jBJW8=yU*=?TC1OhncWOSd?aBDo-f-1(ljia}QBLo3=+kqWqb&sh7BAtMLr? zS3N43Io<|J;_`{_sB-Y>S=7AYJ7R_t`!`KIf>GhhbepQ;ERC#P&6SEPcgXKGO;%zl zRv#x2(FTK0_#axIt2Kw&pkOdxwLYLVj|A*89vUhvTII5*SG!L-wThzL!O8}0C|Ya>y|I_TdPJlsbq zdCQuK6QTV}Q?4!*T2|=&D`;u%2iz64D%-I%s(5s}P(t6uczG2f{Fy+gs>*EnV6Aad zP2xgL z!Gfwr%JVwh27Qfua(_dFc<%gsD(Yd`+mlPDqfPB;NR&>vzA?EbnQv;Lt=+W2MWMaE zP(SI-(Tn+eu1XubUe;|Y`#{`#RCJNPn{oWLiWkUK#_^h0!%S=Z)VY9y9c&q0t<=WR z1`&3FDFMEO7%p>>{;i!2#oTUyU&!4cTXxyAu}-M7w5uxFOVvR8oO%9wk z_MtiU_#2-A@?i-gaGNsIw&iO~xO9&MfD{WV<)KM08~+Xa`*YY0E`vTd!Gr(+J8%z? zRqEmD35Ms|L5zJ#KOaaG^m3OJ|90uktO&ZvTOpSh+1TM4y8)`6J&>=I=oHD}_)#;7 zj^bjUXcTJ|Pb|H#3m>pHXVi^YOx2)a>mV)HONYMH{5GZe(kA&+b)^yIO}LeJQM)XnL+Wih2r^N*(G{n!q&#*fTbDK zvk3;7Woa~(I_7koS{^d49X0l?y6sh=a z5FiegH({MOAF8eW$u*SwTImd0RduRdPOX%R>Xfrxu1IF*BUh_gS6a>*@5zO z)`7wOsMQ!8D&4x~)Lr?iy0PHcEm_%w4w4}IYRsebWkl(G7-w@2(K|5Ms(>RLYj8j( zq(v?CxSLpt735iE%TS#!uc(1Qrl@?hpqNXYePn{60U80+4(ml4hZURqxz4oN!vYH3bul~hHf~yA2Au@#@L1Ms!hOfeq9?8$q zm61C}+VU025UZWQYxiKwHj^o>9#dTlDL=vQl0_UF>*?jMAFZu~iLZ6o3FWnz;PzRo zbuhtneSgQ6T4e^_Ks?ln076JvWxB5?Tjl6GqGx<|Ov;O4zS|;XD_gSGt|Vvgr?`=F z6NQ4jK9+9*XfW0Wb{|O)Jge|Tf%HTeg}LrQSEm_Ob(4JLwH4+DG%-4@=hMNV^inuY zN-Jj4a9IQYJPlOvCxd>q?t!+aHEl(ogk=P14j@nowfXOi7-aT0#lkA_pA1HGz0ZgK zZ=L&wz`<|;;t}BUMs`&8O)v^4K*OM|1TG$M&q6WIo6)79vU&m6!O{aakePfuin@u4 zq0&e^dNYaTqb^bZ|I>ftUg9_=mAr(!uexRIY5@smS8a@r2&@ps_sb`PO0d>wrT3 z+8nm$d=x{wc)ej|gvKt*?XGCk@uMzM7rXjMtX7>%agT09iS_B&3ynL%I(%&SIm(q_ zik_l(eL2Y!l_J|YnC9(h6Gp$<3UA*I?ogKCglX9#Pd@{;4G+eg_`mw4>vgtCa9;QT zf9kvd+fc**Nr(S#H~>HQO*-O9JeUput>;18bYRaT3x55$OhG{+4tkAzB)XMWI+jNl zm*QbDnPjrR!yjU~L0uOp%CGyDB?`I2ws#k{5`qugT{4S&m4SBS zA+X;w^fV5Gui!20a zfV-u%Y6K`vq1*!^k-2RB?;$k&zX7q&|g72=6;7`&oOfjyFwC&-ojK? zb$>pDzCd}VlD`yD+DHF322mT zHf9^iilmT{iuwV2IX>mcB-=Pn; z01|Oqq^}OfDi~Zu?3j9sIi_!yB84qD(uA#OOP>~8`?jJ3Gs;{>=1ks2e$fdnM7K82 z=49H^mXsK82iAIJ!1CQa$%X$ruTDF2fJ(szyBCxDJoS3i?543Gx=VXu#mhuSTKMA9 z62C7!YP@RS=ac*aL70!2MOysuB|p)WKT!eD!dkCfhVAhau-N1_LYk8rbTYH$DC}?l!6L22RO-13Er*L3VOr9yRKzpk8`@h<- zn!LBE7kTW47<;-W7FZP#qT{FC1q9CD#^V>zvBUUgv7Tya92oP#`nlN zu)A4*LJPa|Sipk{qVHEgOY#jRMsa5yJHqK{h5 z;xk1^I6`1P7bQQbr^9h{G8-&E7dxKOHJ;|ISJHhIxkAX&*2vTm!Bi-&Yplf5#1Nd8 z`8pfstM_Vt6`Mk*CmzEOP=@gew^=$tIH9xC3ry{KYZ`MYv0j;wxiFa|anDe~1=aC+ z+*D^BtHcoc*LTm11!)7T?=}=M`WY@_Ic?;e*SA`UWS{qnarQ#v-tS^^)=&)_%@RE>) zN~;YGNs|jA75#a=znnxDo4*m!3gY>)S1_}drt+hLriE`RBtL4>K+A)Z!nEjBuyxfZ zrcNrK<&R#&D@0Sh)SBtt3mc8m-ufSu-KS{!%6|QbM-`ZDQlyL19JwIl1D+S8i0vq4J{q^A&BugEdiinUM*5L z7@**cj5N&M!tYNQd#lPm?_QTIrX~?8@YcnAs!V~c^%quO%8_j~9T4YFv2T6LFQCFlWSjx-yCh~SFmmX=m+oF;OpoaX1h_bNX%0gB1uiAGHHzB|Xe$rz1qv4-erx!p z13sa~p59yb<~LT-KQz=rT8KfPXYr5A_ObdVkW=m|L?lpgIN4$qtt|UfXl>iowvI zA)aYX&({OysLFAV>b=B7=z&<4v<~^xQxsHEz*31$Zc-AoD{({uc)R zH;@4+qab(1hX9PG0N(WTdjJ#+P>%F_r`ADtD77#G7#u(%NDN@aMHw1HclYHa(OcSb zpMrh0x2Ql1HiXs_<@|8;V~1~49xsLO4klc{b`$+Pcfy;Ol{h6@Z$Lm+4ni8(8$>a=Q#~D!=x-%-usW%q{~?% zJkz>EyrJ>A1_PO_ud9z~sZt`%v=m0QwC^0YHD}(NyUD-Yjo_p3`T_)>!iMf419W>d ziDvEcO#T?+nAl!#8AyzXKs|`PeS3X**Eu)1i~PA;1V(n7B3K-gS7IyzcQb_cMQ>VX z=Qd#|Xal!n)qM|y(xg+V1x2!Nnsf|f}@83p(i9ef4ii*y}>Fli|9Y|0|6 zjPj8TN4Wj!;Phv|B%C>FLEJd@;f95;v;`n{#y5GAX-|`O_uc$U5}OC{Q|&5%CL9-k zvWxPE(>9pd5G!4-U9>MwJANi!B=jLlgR+7QX7#Itz5Nm5o0@eWw*=FzAnDOZPct13 zwv3eGqr}IEyjoelZ#d3;oy_DHq+#DRVre<{_oWKZ~O%6$V&s&n-%Cq{++M@X!I%4fXdCE;T{Cqc8LiB zBMG;RUKrG?DB{-3d&W|etVNKo)^zulwT6w_pKF^E+cbYW^-FZLKby%u{5+-2CHVL5 z;WKdjMUG{)YBg|F1hq;F#IKrojMy~D^R1r^fm@;uX%{$6Nc^IF6|M}-9y@)gAtW0U z;iHEhs7p$U#MDuJK;8mC6#(#JMOqsh05JXpMZke_kN!!t1OChqv_eM}?g9@f{MhRp zR(T2k9)N(np#=){mY~NuJ(1#Qd0QGFCW;(2R6W2FhB%KIj|)A+7mmWAfZ|<~nal)= zG=We3VUO5@QR;^Tw2v*1ySg~>&2I)^@zijI6_l~kR7KH`Qhs{evNNAfWROk!z0&Wp zZ*DLFJ*@055o_ftt|oyaHOR-|ej;m|45@@!@02OMi?63ZF*K*wQVE*+=q|~YIE5C$ zdp=kD8;8|WZu08pMn@Q;H>gRCn~+0-By4YNW|7-Q72ax z2MkJwmP0xyU6uu4SRL!_5)uGl9s&gd9}2{OA>O|IKVjF}WHbbZ(LfYXY(Q=urT|P2 z;ysV+3RZAP9#9yA;VrV9;Neb`2ab(4Ex z&*Hjasu;Td{y$zog@O&ox&sya5oWbVYrdH|+#Snq{zBeji1hqgy3rw~vx*qR1x~Om zAwAQMi9429+uv&dv`mU!(O%}-7qX)QL4kS-|7fuz<$pwN{9TfG0A4sl+Es7j+(EEq zXoDaT=&_7^uhU@w6aA~6cQAvLKk5KEX}1LDxNz|<;c0`NV4}C^{Yka?VM*g}(xt?; zbBEwqRi46&e#E1QKKiDu&7g_zMbE2W`QHSUz487CyM{3T5>d91cWeknbi+sp9qs=k z>@A?;XtuTCp26MS-8BT4!QEYg1$Po$2X~hM!GlBaBtQu6PLN8GS9fb8 zHo&m?k=h4#v0lvgv@DbSik&=P0~ry-pgNDF&PkNi~d-vFD-IiKKS#f}6dy z?xV@c8G)N^eBB~68j1@bzP3nfl!E=MyFy?Tu~+i_-oXERn1aApyx@4V%EtWZjK1M3 z^ty-BT0Z265RoqRZg_%F$oM-y)?u==({0G78?pCInCXQ;=cSw&?t5Yg@<&0}TX-bB z)gkf_z7CUpVp48mK*R$INK2NcP7`CjI-uyC<&B8t7qM~kPR;7zUPf{OiKf2ml&9NG zsGTWE@LTWNr+;(iYClzWzwDGImAgs6)KENfcY_acy^9Z&>{&7hMP7C3tUCL`hHmz0 zqLEK!{O2+ECj@1&14dnG{23_N1k5Q)?72(PaD5uN6gSJwc zdksN+@s$Y>kscmM8s{3nC+-Xv2K~wPK>t$X6)rb&`GOt(jCIT z+h%`A;I?mTdpv*_vZBSIO2E59VH|7AX|4NrKkw5=O6ZZ^ zZ`>}brz2Z>Yrk?15PC?>v@DUfmXE&I=v??#xCFm_v7kTZy{s6FBH;Q~#FmhhKVA}- zT5X?yWCx;xpFXWHgs4x$*@kBvU9!3)c@EoUjw{}-1)ZlM!>@D4k2LPG(u%W zWKmEKq&5NPTQ!XC)X`0!viLMpB{0#8+q>!#n!`KhMH-)HF}bsZWTk=VoSi3(wtkTe z=Ev?LPi&Et@@f;SgsPCyr1b3du(vsN#3CCU_^_!J@O(Z)NGu{UYkNJ1w$%qdNK;EoJwS?CfSTNV+!BNTsqOgc zTI*$HLw%mi{jhMkY{aFBls-m7`=`u8+F(o+#!q|2H=e-ZcQ)Lq*aR<7_$SBF0c?kjg^)DIU3SNWNNYevj$(5JZz zh{p9QHdK6-{3$-dOYN=d;?}$I4RR=YMu6$)63}$)yt?4<2uE03t{Pq0B)y-y3I$ZxVsE%n42P4g zKfzUEG1=dF+%~jj?KFPl(i3j-8&F8g~`6bccHZXnmHtuxg?bmYLHlkEn$#}S&RctP?&iOFRM%A4e-)iN> z_Bo-Dn6_5!IVz@&pTQ+UvbwQTIo|kXr&B$x98u{hWIXxu^%`rKsnrCrZnE^=350KW z^?rX86-qIWr;+4H5{$K}c3N|_thk%kEVLYZN!v?1dPquN`TWbe@*x%cN-{MhJQ!W4JYj}yW4 zOW)X+<*TM~izQdGU~h2V^AwfO*jIzkJo8VoT?F3qGH+^kpV`r!us;4yJVQ>F$q@Pg z#dr8|DD9!jVmKy=K7B5t-k|t2Fe#nFNxF-1czJ~NVKddyEqnth+U>1P*+)-3YDbk{y`9Qm`b#K z1auOQ#gjVyh`eC@8iDdNhVFa(%hw-}r$~ThZ}VpQ1$>JI`7oFChUv%+{hl4)K;JGi zc&PwB&Dux0ptbd{d(uCw<7?!3zwMc;ruI5#T(PQJYH1RCzFGSyx#t*)kxwwuXL3{s z>%U}@`5=}5?uqt~eD2uPMHx}yfr{p??Un7h)fA}@yWzi4_NejJd#H$6o1N>m&T<8x z1C0=Go#WRBRkD*_AvPJMNAH(;ohOgUh5O2+$$6DbNKts={jfk1wzKRQ=Q}zJ8l#dz z(TE#m@6EaG&J#k5_fO)(@w%Jq)s~^9EoH|4)|^&X`7mt9{`tv2>4LhO94v+?2ES;d zcv37;oqg4*B*&SC=t(8HbQy0n@+QPx!9N7C3&gEf9)xcTQlCc`Nn#xtvBVeSwVXLN zDDbZ)P4~q1Kw{<|%rixV2;6@r=d&V|+oRgw1*I5kZhuqam}H@w%U`gmU?vd9dmM`+ z(ZVKXD``>;a=Q91!I{nfNScc}9!t71`739sw^TWq*TvA`YgTN6cpmf;b>LOO zUEgHE`zhS`te!mjNT)>kYny$!U4hilW32fPbZSVqTG=1Ebecoo@`2X~Q#%f5I7xM> zrb8+H-^Q&CzPBWPq?h`N&8A<)HM>G3Z|!?VtN?;KR|)T|>KI2GQtMN}*q>jyYvv zL=h6R&m{UBY|O{E$ln&mo*rgkwLIQWfuL)jZ#<2#@f{&(3kdQsRMTZkdM&!2jP-W; z+6@pX0rbFqkd$e1#tUPyn!w`F9$@`v;lvOqPk?vu4P+#}d4I*VbXJCc8s<+m!H^`& z5>PywM$1MF%AM7fA_NcyRo?M->E6`RJz5L$Wt-nC(!#5AR#a6U;$tIln0hi`!^J~E zZqu+t=Sr_s_syn<)_(%{jF{Y9G)R*)P$Uf;YRyVyOF@2{%H!YaTtp}rG9o4%=GGXD zzuH*Rt&m?9I(Gp8Fb2v;LI0nca*uX^4^LE0#bxk zpAM_u=^qT>|6L(E_P?GA2T&J$Du{w+Dj94OlIAu+@-)JRjiU|h`?C*f<6@7_FaR_+ zZd4G1s=ghS!R53VCYvw+CyRVIO{J)jYKf?7C=j8cw#{zbYT zmepAZCf77fuK54XOh7rJ|E#`V?eBtr*}uhs2|oqk_3nVGUKpO)14{yxy@V!T1lw<6 ziDeyrex7n^qJL3l9*ZBu5MP|-m++gQv`O%=eD5=3ABd4R!AY-FKE#kfImwjy-q zI>skLg9z~>`VjF`RlFlb=yDo&{+J#`T7e=6HrGIqpg{rQv`EODi8A5s%p`KtS>oj} z9h--{9*WY{Z0(Ch;VS6-W{z4)R zo4n&(0q5@1QWxk+;*k5ZvP6z0?fl8 zkNwAcwC{t(cK=tZYFOW_z{aTnV2*2cfF~?A6$~|MAg0Q3Im^$W-+CP%Kz0gtL55M` zw1KOAelmZWQIO%MLpoW>L?KFdYMq#b(#j>#m+oomlT`Hw%Ws{_7Nk^9m;=&68qlCx zZdrI4wqz05EDaCD-M~~y=?xF60cZ#r9D?12Ma+GzG}03q4tkaJgmVFF@u2?j z&=V=_UrgRXHc*aS%N`hfofk>eY|_?K$w8XK<`ADG?=eQ2+P!zQ16=4p8J% zqXTZ623oFRPm}nN$@{sb^|T7gEwkeM+}U%T=ii*M4zWlAvLvDa*@Q;j?iv8jYt(Un z>w!OYzOOdY+qcYy3;_21nDY7oE08@v|LO=pWlH}UsVgjjJQXiEywbv+LDr|8r=k3H zE%knt^T4co^>qasXL*7x_U$>tS$$!dKr$Pu@8k{jF?AG!T&qJ$JLQvM&kmT}PDYRy zHDjJl{$*4o`I2jywO$C@RTFJ!7%)1_9)93)ew=t~e%Q&~oez&CEG%8WP0 zD!Z{?T@_0F=te~mJ0LGU-f2j6ZnN~#El+#X0+)4V+Wav&KF$R`IA=HMK?ZXo@ziE=7dq?%DHmoXi)y z1iYw2ifV~({H-Y9JpuCeWz6|!13Fgr_U^+FF$H~OdNQTAOyGvzW!persb}gpVFuEy zj?b7z#5Y$7c-X6yeDW;04#2QqA1`(i%Yb?%Vv(K_GJT~HWF1`cIf;`|2olrhblVMl)c3&bG$H4X zRU&?CyUH85PCWfZ4IXL<7$FHK70TncBR$UU>DZ?-*eGoaI~#s48(ezwmdVQHjrpbZ zb-50&mSnt1DW4|L=WzeNPrXN?Q3lPciem2O4@($hI#C_izstcs@R!ZW2DcGx>1C)AoR^iRdyVX z^iUn7#t)v*KIfQdiy4QDUw!nqt2O#r+64c6#t}>$TTy+l!k3b<4R2= z_@gyU^*b75EJoM?1$q zRp2ws3KtzJ8yvW1I0*WdxwKOv$L4`294$-&_h}WmEH9MHq=lBVacP04Y2)W@s_P2KG zTqsfr48af#fy#f^@_z~Yf6pWQ0}1GrIy%}AL_G_^1D`tma&_zsf-!nap;nO6Bkv7> z>k#qP>hwPKUy$n&{V{i8J}(TUF14Ep*&q(E#$b&%+`GXeVcl@N`qQV4MznbxDSn&O zH3N^M-=M2gs1n6V{Jx6jX|} zf8V2gK>zCmls5Pg9YBiqRZuj5C) zMc!`^e<>qby;xdWnbKaQl+>y$85-=&SeL@;5jqt~aM>|4Ahs$nL9W}D#llLK7R@j( z=+S5kt}eabdv!iJ;QO}C;)pp5OCuzO&sZ68R44~a51Q%I%{ZCF@-^>lUgqc}@sXc~=^tfxlZt2Jg;{uFjpHCoJ-e%(L$Y8^cBHNQToxqz0~ZS#;4b@xTz z9Ow}t7X64|2YWDLoq!rFfwEJ=IJoV-1aE7P+~nM5A;|WF#)h{#W)XGK!;+C^zR3^l zQljcySp8>WlE**AtY&f6ip}HfOUU&S7Dq+jUU6hy>;bMgepI)c?FtqXmDJQRSgF=c z&{kME`Fz`97f%}XGFJ>AF}mB}>Q0f&RA}Y{5VrW6?2jmflu$dDb$@dpio6dbwp^)Yc}7Y`#nh)W6XqXTrW^z%%LdWOfzus$5vqpcP4;BB!KH^r8mcz~8a#wVC9Ve&W7Gm&i*h z>?m?gkuElXXzS{kByALXuiS+UTT>y-OPhX z3|8Hqq9mo{48)DllZbzRp8KgU^r4st4f+E}4hEabs zLfEs#q-fnQLm>CT;-z>|e6p}biu~kjArf;;jnmg;x!7`&RV?>FQuP|VXvM@kJqo~= zhguIC6c<;^wQfpxv-XLDiU>lMGem{mm{f}RBRgV+)2oc9hgK!M;QC{_U`3j_=s zS%N5GO;qzAO$6Tpe%#-wM>Myv3@~+h(``rYLQyIZae@K6{@uwp^O-E>Vc!Y z{u#T%oxmD9UaQW&CG#4)AzGp-y7uA zHh+|P3>x^pBFvVQkSZ06T~1>}wo+rd$ry|8$&vec>#gBkVAALa^7O!l;VdH)0uHTN zV-;qT>81@qprQj$L>JLn*~s8WY@|86t>KNK={`M*d0>1&bl{Ra8-Lq5F!z52MM1^TUE;F=~RYJ>eB#8OJ7|cyr+cfK9KfkOBZqg1?>)=ej@*wL{KUa|SLzhSWr1 z*^oX*WB{}Q2$`P zvI|a_bZ(L6rM}bhDci`4*?U}%X6jQ=jy6V`EX(_{#81~E_yWkpEHpSTpGZRWZDb>W zl5MZzT7|pz0VR;oGQ3KaNj=U}-Gyc;(9g^oS4EQGDs zf(JG94pId3+2{tbzt<}_l)xn3JwdVpYCFC)k-c+4zf33XXcp(a=wD=4yVIjS{6ouUQ#8u!-|-VKFy%5zRFESpJvf{2}P2-$POSPq~^* zEu*iT&!7eV^EJ)j-LBtl?A zae7R8)!Bwj4hUE&$Rf_E1-RD7;!lA5LP8Jto);uu!0BC~!Ln*mJv>$v>z{;5 z`gSgvg9Fko?|1Jk6R>v*&b_|>jvQND4rsl?QI->lnO-EB2UEKt?uB&|9HT~ZUv31# zwb!BOCp=PieTkfRgB;!o>6B>fgmp2AK~_|IiicV^YLws2_?-Hn(k!Bko_Ryh0#&Sr z8EF^7j0ADK+rvL`b}^ObT}t2}HFNNhNvtu*^eW>y-O&8u$1V6WYk|Mwjv<)$sDjs< z0{uN+_>M|^Xog7lagOLIfL{&1ve(J0W&uk#M}ft(5Bp9Vu4 zQw{QM08JHHv}UX{X#Kjy=A-nYXC{3oThsGkV!26dYqH!aQDcpmkUe^T7MkS^(qZ98 zkrM)#Tk>;2p3E{szBPGdXrX(2(#jT&<{rKhIXB>vQbF3OFZ_gnlj4a_EaoTsYgefag1!G%tIt)C1Bn>qsS%@k}4HLN*1)u5p--Y2Sd zNC(ekc|HmA6|%6~$iC1@@>JRGup!7EqB>f4_V85M^Y@;92*??V$LWS>9sJ@7XIAPr)$P$6RJ!6PLrAOQ@)g{ldc9NM zv}})f*St6iF0bf`zp!u4D5%PH2~q>+aVh0vFg8 z0W^p$<=2eU4dVka_Rfd?KeBhC5^oJtDjtOf_6ZZ|sRl_$8p`5#C|UhET~GADoO1wE z)PT94h}KmZ#B9F79IhT=&3F*bFYPQ5#ZsAiiYj{y<~}!yd+n&yXY%GXZ|$C#qbUut zi^8o2X{+TX#=TeV*X{S)`ruS%$(2CiXf;^k>?54jlPGrg>?@a=D0z)w@1vzGb#!n6 z!=SHD!dpEkdNengik~C}Ph`q;hbk7MzLkT@*{q!Bh$OZ8{zSv8L?)KDjH#Ua3pKm9 z%tOVFVKJ+1Gl+&IwTWtm#%Uw1Z~lOeB0c zwyBqlI*0H{2a25z;5FBNan#*qwtfu?$aM;Aw!dWT8EBCD<#Ql7B7J@LrCFq9`=+dQ z;DfSsyo_hL3q-Wu2#l+DkSBw8+?Xv6#Jr?siCFsIAmS3uh#nL*!3H{#DRZyW z3i!3v$SFlt3oE|jZj@4s3brC5u-&zeVs7zFAM{}cy$T1L{>WcQgEa>n@CADE z*D1^k8dHJV+zNuJt_JUex4Tsf1?=h3cnfgDt5nnhWK}Jz=rp)?zj?!%>-uZM`>>oZ z#JE5)Nw4BW@*?$9k%u|v>OFVP$J3DFIWgf-$S@!&&jR2ZQPL0vWnl-c3oFo6adiCx zvep%d#@@miRH8GnjSPwiz;CD253T(r0FDp`O?G}8$iycE!17V%gy_8=|Lb}j0017K ze9?bWz<=#^`#)d1! zmwebxAlHSS6RnX%-$D2`lON7tnLKl>Z+eZb4dDNdxlBt#;%ormYk;rX!!li9F|^K- z3qCYeg1iCJLXj>&@bK^LahlD9*o-u;FKd{+@>X zi%G)Pn(9a(ux##L5I8&Rco& zphanrU+Zd$jDYdpLxr#rk}~*~Vc#HYG)o6TmGC#4PJJYZ>kT=;x|pFY7O5#(0XFmn z&}4s{`3-{4fZC|a98oMEkm&}@QyhJh6i9}xb1Pe+xe;(LfkNBPrIWA$tRLERDn1}> z0Kn&v%n?H@goJ>c|NbZhz!QMr{}LOBecsc0PoBcj5$J`VKtlut;6(FI8Y3)Jj=q`v zNx2`E{+0&ufJcz zvZ#8#^>$6JB*#~=e|XbmclWMuF>KI3sm4%U-(jYhqAe~ z-q;Xp#=w2ahE?h0^%v<(qGJ)>lK3DeG)cx!hQs@+x!(q$ijC`4Hh$hT2Wvgq%hPemnN_%`Fe^550ObS4PmI3I?w)d7 zZAk*^)`<+a<;R*M@;Kyf2ud@%kuyy-%e&VyTWj%x!HQidH%Y0bhIDN~G zD9MVa?NgP5vjqN?oBeE2E^jT~Nx&sz&t<|0iP4t*;KdjabZyT8*I|L)LVliDGZg#% z8y2|V4bGhd8?}cDo`LDPQ zQhB!LpQ-3>RHIa_OrJ7TUtbWtX$w-CyVt6vjU+LQa1}stJUa&m8*kkyD@bfKwKn`= zSx?9gR~47lOzYfR7*-bPo2EY@qzGFVQqmJ7`nWRokxf%sU5E~2=_!N5i1zY+TYpYN z0t3`zOK%)72#ZbdOk~vaQQqZBH7x3nv_@%?B59$tO{7`mdh07P2}8m#kw=My<4)D= z(`VK4);wXB4+l7-m1@)KVvm!jx2EEf3OrsK^uDZPKR(!KTNPTno%s+>^)4O#VYsS( zDL-l%WBEkS=P^ocra5hzI$zrW6$J|+eD{3Mpefo>AGPm;kcgaJbt-2ip~sNaeXh(O zQ<5pUE-X<#1twe{Ik$F?$cpu>y;`$=I{#z^ivVq1;DFtGk9nd@xxfZ zlhez$jI2fiMGEkc*!$u3QVx5X^{;Y>AJ@BRM-DlO|B9@q&wO9DLZ81gkk-K`g54LR zKs=nOMDX(a(60-|^v;*QK}Q&1#(kPjC+25Z@IH0wbg+7!Wa#ROmzTprFNx5?0#Bue z?o;-mdMe>XZ?bdUY$d2a4`C|LAwreyCE}LJGr?|0SqXzHrE)aS3PX?S2ZaqfSzf)I zR2n@*B2tCYrFp^Q3Q_$#ixYc2ilZ%@G#d*&vbjHnPo=&b6Joz?(;_?)aNnUm>oLAj z;dpva;*~MNcgFm2p5Jv-#Ebn$DqHg_rjS4I!F{c&ir0$b5qd_`@-0JWGm+EPaXeLz zi{#V-kZ6AdbFWCc2dSyh?hGa|`g-$@HT}^bjA02A@n43IZ#Etk=$eFzSeP2Ug#&5h zPQkGGLyray)tT@H13_x~ zQ|A0V$YjA7=9zgr-XaD#9PRbkg^tt7RgO0B?!IBl4Yz0#<(J>U(MzGdY!>W!Ahel`11CeO<$u!c3Q85AOL;>dLH zN9txPU134LgDuA?X{M7GYEb?yx2&H3o*1#-{Z*{?&pCa))@gq?e-F9%r?YM z@lzPInZ0`Fzb_Un_?^1!_YrDLl{3_h26na?zlq+WOp#x7o_K~IV2#=wl1-p}b>9`) zd7H;Ba#1}W`i5usI#Ifb#Iv|=Ac8Qfy_o)nvWl@qTePIBL%^v#Dw0Zzja4qPL3Sow zKi?-sBAOVhmx0*%k-a4FLz9jQl67=SGx8;#3?j zm8DN;Y#J2b`Qgq3hhG1FR;nfz6SE(FAxcqz9T6YJ9YZUeQ0yh&PvM-r%_jaMc%fZO z`mOiyJlTXr!=}6z`dr(s>+3%yNOjRYfdHTU`jGCiFt;Ytk^HrFwu=$H zO?mi-c#-&STnUovA!N)~p)-S?=N|R&(o2AuuhOS9*0SPEO*fE0^skZ~jPZz9zJeEg zkw`wnaFj1?pG}dcX}gR*cjL8hq0er^_su(e-=Wuy9?2f-8LhG5QpJJ1qwhUG^)Fez zteGIg6engDSI<6|W2ae(re?*Z$6EE+_f&S}`|h15vHLbC%&C?!L?qW6_|iRVY^EVV zBzsLQP0fsZ%z|Ntf*_Q|5PsKqR;1z`<`aIXT@VOAF9(rN#z7byYa1@@988zu|BNBw z5xyRBk96EP!&O+1UZ7e}#qcIZwzbM=16u@@B!w#Br0_H1*P}$2qO&=Alg{A}aEP|* z23l_Uzh8HxmEa+!R>W{m-M%GHdoWoX(w#AB!eID0ohHcef_$JQpgodTl~fHp}L|;&|yDDe|1A5PU|1wA?K?#l{}1B+|Lo za6y_hG=-#$nhMX=XwRod7ZelpbD%xCZM2gmg8wXDp@Ry%HtFJ32H&lzEB>bzEtsrw z<+S0Dskj1M7D8a8&m^aH_>Czh+WMmX+CXCZKsWb?ZrzR3ozolh%+ z$zwqZdin59>}En)Kc#qz>qq^)ZYmQzG}o;5aM|mhTM3^^-FL%U)Tj#=x%)JpX=7TQ ziFEzpeYGR8$L$n~>VG7_6>-F5@r3z^KPwP@BSKnHE#g$W_Oh5kBf{`#|t@ zjMGF~j^4$L3oF0ey8e6N`c{OaQqi?9(_vt;+1#;j!L|e$`y@yWU}d0rjKBWks3 z0xQK>rA8?02SE>JAp*WW-^2flk?zp?ypD*tczL!|~2Ns=walp1; z;>-DD?C@F$PNb~Uw_VQ(3%;R^#MJJV?xv4R5s@>m96!*dEq+)#C@Xq)QlGNzrRy2Z zI=ng4vzNtc3K@w!Jk~q8>OSHNyym1>D*YvosKN2eh}b+U`5+(dq5n`d?D5Jcl>wYWXGE&oQ%}TmvC&=Ne6E5h<_Kw|K1e zO0<8KgxP0b$E}QsG@(TyEfN3A(Mc zK<-ob2Jp8PtDse3$Wn*=yT$W#fX=FgrnVP#av1xh>)ljkfmyV>4s#(ciYZODjgJKP&HTnSl_x@|bUqVSwg zR)}FqYle!gQMBo5Ifp^by^xU(=R4#W$nc##?|E-n)B|$3@T+3u7@sh{9Efel;hc+@_a^(}bVh8YqjIjfP7s=LD|{9v4(M8S0%ejK*07@Xk-ntn`oY zu>z79jtgVIGgK}v`_>KzwogXz^@qIqn2$GRze9m5Ta2`Qv`NjMU0>zeQq?9zLaO7C zQNT4`6gR)s)PWaec-(8x#N>k3-40S>H~iuJYve4%SQ$S)doC|^nA=l*v{@TwM$z$f zoU$ndCA{gz5__nM2)Fm71JKg#dL4cgI1!G zi9LSTf*Y<6+q}Y;yfNxRG3Znq3o4ZstMm?(*DofpjfdxfJ*wqpHlB})x82)6*bU>3 zoL^W+YGOTV`g(a9A*f<#s6@CU9f^$G9ofEh7Bhjmi479(iur?k35_>;0%(0I-za@G z`Kio@J7q+PFm+#=xRcsrQXieU|A+TieIiZli%@5}aOz3q&ZHZAL^T`Ej zT6tlN`FNzE=2L|f!3L(%EKHRd)9_L))x8-jjd`*sS0`hqOlgI&Nx>ib@1Q*1qcjsJ zuk17rR+yReSjrTSVqJjn9-8U_{?@? zBT!#Elt}mKI6Cw+Ttkhp2@7Ouu_5wDvP{DMP_@So(}5pT_|FL4ZkS3gt(@~js!%-9SvtC^*c`qy19RjNPZJiJA@2J=qcOrIjcl@$|~i7epw{_ z+)S<;2xHYcysJr`7A^g@rbdB$wmVGE=j&>otvv ziPy#gf8y>800NlP#?=^T=J`~?LrSCy5-*^i{@X^xlbD@jN^jfXSic?JfaZZ{Dnmx) z@~g<2SQnrnwUvL#Pd{bvAfMi%qt(~4)9B0?(Q*FqN5B59u}k)B&1Z5i0WZooJ$==S ztv_f`)f|Z+w2>eV{AtDEYyuRoFV1|!FW5%+jfbfZm&wwJdC9y>*aDg8J^zphWDDhv zU?c`{tMUa8E7A?|o3*VJTM2Qp^wweI{=)KCQjh%@5Vt&dq3B1pj*eDt=BL!tc>px_#yT#ku*A8;-OFtE7Jsg{F3qHOXQyMu({@$kc&I z#B}vUq0)DbF8Et|i{^l$zwzM{} z{y;nd@2547)AG~7$Pg9USY9_+5Eaw|C+@XgK><3k_jRk}-qXxeOgy!1En|_^Lf5!cKF`4`ND9ouiLSYmqz$&*BiN7VC>D*D@K{406Pvn}`b{Zs9kQV!!K;h7ZD zy(N<4Vy&QrL@lzPz%H6^FX0PP+8^rd^mh$KK0P^@AGBbU}uCd)IZk?fgxDqkHSb z0;41l38TS>tJWmF6ps( z!TTmhdO>so7t|^PLwMfc5jowE;JBE~lrJ5`0F|7&CN=Qco)G1NkUIgSRvkChGw0z2 zhg$K-ji-=wXA=E!sjv9a>!-$>&(axA+hWg%GawwNElO zn`VxJPPo)f?asAF9fmmi@e3{RY_WUw|gmrve2*3Sb&3DwmqjS%z zBBNh4dQ}#vpFhaz30F6IAGXN-azQB|9r+Q?w5HsKH!7R}$=}f}wF4 z6kbjzpxD!}A#~Q?Nk`DpBSPTx8>=18g61nE(mu(@!Hc5%?zG zsiiAWBJuI{Po)a-xQXUm0><|t+f?lXxct$CiO#9t8vrU#&x#P8T5E9?l11<5J!2{4 zx~^PgxsDYpCPMN)^Bm)NG3!OPDK!t5S9g(;-T4pXkmyOtN?nhTiqKgfuY+xrDS z1UGK4>f}PgA!?OgreC}SQdXKqI#wL=3VtcBtr?O?_uTGr;4ZnVUB$;VLG8L_h=b$5 zcjZqK{%W4(+d{mZm27yPWQx7|R)Gt_4qm^1w32w2IJI#U>wSQC^rvfIcYJrK=0voc zb+{Vt?rgqUU5p-^7~;(U+13E%4`AAlk46$ z1Z?)`ZU0AXdABRb^NZ9p{Q$SYaO=i zC<)3}`D-oqUJy3x4zQIjEWCj?PK03jO$vk1supF)yKsc=quanF=H)pu3R###m|nkb zf#!YkZ%F)Ka2Uzs30n$nz+n1PY8km(z*M&9B*u((b!$#A+v6%j=!;9Oe2OlcT0N>if&beF$WF12zVHWI{ISOYi4>4&3UQHWMZdpI1 z#yky6AIDgYT}u4G#90cozd4v?Tr|*cBk7u>OuB{~E7A!(>f-$dl~Zln>U<+TEDML( zpWIwN?|(YU9%9RCend^`yENajq14F_WsVudawLM1rk6F#mwqz5^*b{bQc&oZ5!7@u z0nJgTX1y*?ou?e=ve5NY-1ugX$=0PHSx>o$5WX!GPtN5qJ1-JskiOTPy2#)q@s-iR ziSMujN^6@dCIf3XF<2uWdBi?Hh}SYueExpM(A|;P1T;5C(Uhyxmd2B}GrVJAj0WhV z0X~r_*5k7{-?j`-rZoR8GdFVzQZTsZ^zUSf_=Nn_+?7CQERn4jzRlhao^KhbRgbrl% zG{h~xMoyLKBL%*QRdzq*F-ns_E1P`n*r?b85)0&XiJbqC5PCeEUE-;0Vx?w+Mg zoM(^o(v`OBXMveqv4E&CEiFLdU*O-AH=~!h8X_L0*TfQ}kBv+Q9~RCOxb}?H$SEJ)4|cCjIPQqhXI8fnq7y!vM$XvSNP9h#Kn4gz!EDZyYEFiZNHuxD zVf7sx`^duI_#O`QK`L-TWxW9g!v4q3xc!U4moc$XH4{CE$+ieN(hm7|fJ=|9v#&e{ zU>@VYUnGqXM;ZNdsn%TklfIP=1S-gmy=;{YbXkn9W$ewSxX+yB9QOFlL%MMBWnK8b z<)pSPzf%lTM;%fmeYfuS{s~`rLgKTWXFHdgGx&}&?NC(R?XV!^%Zf@a8!wvecN%(T zZ?b}ubyP+0iW!XyOVFcsY8AP{9Sg?42}_#~r>A6IsQqODQ$d)et|T)TKIHuefvXt_ ziToM?QzB#fVr_--0o!hXMj_e^wzy9L7F1sVl%&W<(cp*w?u9`GZ)buW-1GyMNnZTMYs5!kcm%_2sG-$Nt3mbWg#EwQ%m?pPDc zGf6Nuu9u}~1O;0AmkxR8g!%s~IOHCT1lQU)qw4MyAnt-mbvjl}Bm-kuKmV015u073 zg(=H^Zu(t!;X#in>Ca7K2iW4435 zbrVFZv-yUB9NY<^zFSPH1_qpoAWv7=|LRpCE?E13*d_|56mf-Kp5!f9C7%taCnnc) z^pUi^=NZVRCyfO?rKL1cbfqkWsPiMO9`rdI?U52l-Zv`{w>ga6hrPi%zIEc`^!lrp z5hIwxdr;J$-Rp*n-@VI3-nQ#yG|1_Xy7JV{un78{GX*2RXMysD$2| zjfpv)8#y|V^s~1{a_HJomUY9e=`LT{5jdJ``^_0hM9KQ;%irv=2$U$%85LXx4tbQ2 zO{VJYz)jZY^$pBbIe^k+w%1Fk^Q!8`2Jj;fQHqd|@$(x%oiH_QlAE@U-=1T-(5K!~ z^gG?zktASb?9aLnUBDbkZ7rMp$zli$Knc+>XH^k+T}039T!r2)9;04YK~iYO`X$ez zEJ8Q`P9W4gt2@dQ4^Z$2DhNX#v~cV6Iv7v;)txUC-3OS@2TuC!l3F_=y9VlE5mCq~ zRAj(Xp-2F|k0|Xrq^(x-lBPm{?QEo(+T<266!wDr0R&sZ(xtT?=euQn7LD-z&0*TC z4`vrkvvMGu&Oew-Hyxx8`!C$)*n9+Ynnmoj;+IYna0FK1yE)^D3Rm zBGf?|HCe4=i z&YbHh9QOrhUFUA|K8OOUi+l2J3YXRWX~AYH;UlHQ>x?4dtBBOdNF!(LLZf>gXm_jr zBCHd0f9yM8)x_45uW-|#3|Gu#!w;@6m3c8>(?Tm_4hzqMSMi+&Nd}BDx!T&P?tE#t zbF(Ng)5LZRR1yqLQm`8jPZupz(KAfF8LaaQtJxKGFl$dZ?ME*~c9G0+x`TEUST$hS znt$&Tyr#*%l|QI72%AQTERqLOb}rB*2((h~dMzilb%F&8hzEkD{)uX*_{N@kNQ_E- zQ%-+#f7txnj)1n8-*pUO_eLwkg(t4LvD5p-dm#Dn<1phf4aLlPuI-*&OAJ6ZG{~~T zrnQuy7wvQ|6nw&QQ;g}>wdMzj_G@+gyy`Dip(yY&L8ml+*TVSZd(W%;bsswm`uRD5zBAt}|pcEgf`+ zYPF0j#3pHY1AD4&@TG@GmH|V86XK!EZ2&jMD&luflEtlh?Q!&PxA{!RA3hIumPIW7Q7T&HOllb+P9_Xhj&|R-Gol$k~4lv@x{&hgSkK_0G*yU z3Gqz1?C7$L=Sjj@$X4$lHp}x9y(2utX_$hzS)~di)m9lz-SlAum^^BhC^bZ);SKm+poD=f3g#~@j zF!dkbQzZG5XK(pud|oMb(}mGk`=fQqxZ%hX(|G|HAVQ6vw*#G!W9!AMQyIj{><2@X0;U*Qcu>Yav}m`y3YL&j4rr6zS{TA8!e?_{;X_b8dD8 z{xUrIH}mCe=3E1e6bv)@1nMXU_VP$B#K$alJQF)Utq{*qU{H7RlWw6CjYXLL6Yhvsn$t)w;)_m$8@ zgr$wWTks%No1cf5GzZB(I?4{3fZ8-paoYCxIkE zR;dpU+>oMP^Ul|R#u$#%A55Y5wZc^0dqh_FMe+XLw<>-bCN{ylcQ!lP%Izc8Y9ys~ zPN)#aVS1tRHL0o0S|g*X%=8uG!Vq{{F)ag@6)uHFVuW!Y#Yu#5zf`PT6pO-Jf{7VZ zIDoaTp(mdU018a%Oz?AVW*5j&vHlN$Bz-^lBdM51ZIKEGpwgag_|rRW|APS`o(kOx zpHHv^Nw4b7YUh&z@#yv@7*{`uX6a+3wRv@+%q7vA4;qK=a z)t{8|^+%{(%HK7c$1RY}<)hn+cq-&qPyJJRZo<~i;*%VMz%f#fst@EeBcaZ|vkYxi zoPC|*qwXxGa6&56vpIwVE|H2#0XeMQv$EyvfaB&7*aMD)ozJdFmXo}+1plT?y_P)tyGHnM^LRMGN-%i z&*8i{X=NG&5ghiw!YR)g1q#JFU&<+h9>^vsHxIF%|b>3V$w`)~|J zm$*{H7D+n(xo+YEv^iaTWY%%aqx-Bt#@lB!B@7lpvgluQOYYE0em%T@`~L+P@!^fl zeW-@{=S5*E>F#4yB`5HfQ~@KoT!F@jnX4B4UK5r6qj&?twM(OQ^~41Ei^QfD6!dkg zAZ88p)`AnWg&J3{E53ZC3mepNrQ#(M?QGRWtCc$?b;VfQ5lLiN9vVM2*GHxNt~cf+ zuxrIQ;ZS5`zA-rG?=b5ijZU)noo(h`jxqs`J=NPwHX&owzq{6oV511;(YKv{5o&&B zD7WpEF!biDCSlR}d!!QLC_yD)t)Ojxa$;sp++n^0Pgncp&otZLdrh~bUw%;?(m%I7 ztQ2*ACg03$^ho(6*O&aeV+Tsv;h05d??6hij{g3vQ6i>yofSI{9j z>zX)S4mfyB?vJILa@JqB37{^0bA52=X|GPW#hp(Js%x<{0!1H!pS z39|LbRl#Nv%dVe%c3>8u932`1e- zy<5CGdu}#;R-#gwCm=E9#fMkzmE^s%Md1kTpSMtkPFz&_)XGxgEEy_#CyS6UA1~g6 zFgCPZzryThRyyh-t!H!#Z?6$`XFd~g0EEmnde*R=(v0K};H{gp6XMOj>Qwe5dUTVm zpm&Jse~i(4*hl6rlKk?WVz^~O;oqsXN%w?!qk9cg7RI*{an{OZ_o=icMoMg>9dHi;iBddqR8et6{cJk z?zQKyp_{p&8X4l_V%vqG*}l4&&A8-9IMR$3D(00!St9>S!kcPyt8@)ki%;nCIX2!`c;I{(`DZiE7GFY!NL2oM^9?o8nf&ZCE$rDQm zij!(P&*|%KS|7QA@}Yul*{H*TGmilEyY>ZB)ic&>uBthVhPOw79qJWlYHNa*2}=QQix46qG+ETr zyMNHGW?XSc&2@#K6jv<^lE+vL`=|CVV@h6rXv5|Z2?}ZwFj&-f{&%ye+oDPx!WO&d{puEDoJnzX~Ngey8eomgCIRVa*VS)0So`The zKrpz7@tW-Y)VlH@_SX5ePe&C3G9-j>|9S#_d9&SGqB$Q7GAc0?M{vbp)Ujc)Yyu-H zBch0=SU?*%cb08TG{AD;@jzNV3N11~>S70J=i>(kcb~zpxyvrcGhz=J^1|CGefBQ? z36Ee@^j8_5{*jFWgdQvmAD+}i8o0yVuHb>-KNN+Z6aFM~V@ILvPvEjIf)SklY;Qn6 zniM)!|8?D)Nl{L+Yt~c^FI!T%lxNj+`xgLL1$wJWc2z{kY71=AQKujzwOsx2xoWL1 z*5mbk0P|U!9?f|1K|b4WslQd1-Wc-X(K<6|8};nLzTz9X+p$`6sb+FnQ)(Dv9cAnp zkvJRJ_)+b#T>=>m584F@aGK6-h^g!Paeem+$(=Pr0Mm5|o=kAiJw>rluT=gyy___2 z2=tMnvRiv6^Dkl!g;Yom#%Q&`0SPUdp>WenCDBoX#&M2HD~+1JpQxZ%_5R;dcbo0) zRG`~o>Hffos4x1I@F6wv__Ok%T6}_#s*`@q@ZMP>ag^C$zlsBCu zn&20I(;y>h4VJ*uLVs{QL6=#|MFY&5;E*aW5zMNADomM|pbvlKk-4S6`?ao)s}^YaIoc94!{ zYu0(YJl9{US`R%t;XHkZDRio&pD31OYQlra*<^)E4>i(jTw%j)9nUy-L%Q^Pj^}6W zf;%aYe_YeyaWUcxjernDOx{k0VPK0)nYf}<)Kk%E_CMz~d1@AaRJ!8?GIam{bO$K# zGgV_xX6dNm&#p0NiIL042M^_?s0m(S$tW+Dqt+=|Th0mCZ35 z(WDKN$qlwQ-4iLo%3n}I@|n>PUR`$2Db{4t25+ZpD~^_8cQw_1;wu&%Hxu4*;KmLJ z4bWfPcc#UI<0z!c2(ByFz3}_4&5b|mJ8Ho*0|~yv(PPf7A*LY7n`-MPY{z{s9BeaN z>#Ed6!mzjx!gQP|6~KOhmSEh`5enmedZ_k7DGNvwdtVf-t+mIBA0kg*gFHY zrdFmRfK|iQ?-TMgr%XhJJTiZd-bb=Tzhe|NOqwy37c3rpsLz&~7<~cGSG2lFx7-#RUGi@F@5wS+LkfT^{N_YzyI1dR(`&G{7VoSXk>_m5PFI~03EjJ^mmFWZbn!oR4;`LM&;Lj&j6T#X`BN5>!pd&)7yd#?ez5b!MhpysAx|6zI%whFL5soO8gF1ynB3b?+BrJ=g zcob4jiOE_Vv0ioC7$w>wgEma_zK)#m7i8y>Ck@A}m>2)7Q{wg9pvNP-5w!iyw(t1x z$5D+D7bUA&;zr(3wR;>T`>mszSuzRA^!~*^H8b>afV7$ zT#}gA^zX(vwr{e`3Is7nqn>bfhB_2!@g_$33VQZB*;NBy6#nZwh{ZwyjEEI14_2|W zYll?ALJA!H@{9&vgGl`pEuajV^cdNk7 z+Y$az)dkCNg%614<7T5;L|dErp@g`oOERj)kJiH|_vG!A+`ce--PAqgiqusl4q@07li^w~UtE{p(jzDnxRaeL7D^3<2 z5G`=cZmnM$a-=6eD0s@M_Vn5 zjthaq)e{I2nhY)Q)VWlFJ9lK({%*ysNXP*Y+OkxOhDu+4A$)?8*-8=0M#N@rFJh)~ zlD%w|y*&>kuSkQ=^2l3^hcyNBe_p7kfbHc5F!^W^eKv9F4#XSOEJh%oGRTh?pT`;P zb|iGTDU7|lLt@G~P{&LPGJ{Ftsu_sbg=cYMgS8Z}O}!Mk zDZC6XNV_y1cz%h?OPvVovvi9BPS;1fR!@qX|Bg%)Do8pb6}Z0yi$ivPZcpz5Ii}M8 zOCF#RartF;@cmgQfdzTy@^@p{`+RBu2~tayCCj>3UGT-J)q+8)?h=I1Of}1WWy1`= zW3!3ePSSSI`b0CoC~%EVN(_$(15OYeH%{0-FB{ND&E?O-NQV6dok};`^t~G&RwbU+ z-NmrIirjJozO25QdB$GJz=SoxgISgAd?33FdD{QwT_;W!vz*(Y2(xtE*u`U7vEHJsS}xnanP7k zEoor93V|TRohSDrr{1-XVYJU; z8Ex6^4!9+HaYEgVcw~;KqN+550J@jeW;H&5?R8HS!*P-@a9h$PmSMs%(*uP(LY72N zt5kZ{tfU&ZRWMuaf%n_|HDgvwLPmQCmqHY0c1Ro|7JwLBOfcGbw3nXkd^f+L%RyX( z_JHxr`w)FU|_dp@hTTruMU0q$ofN4(SX#`VDI?$}m7wf?jGNB>uEdNqSsPR{pW&cgC zHFY53nPxmqdQ>a)6ryin_i!0IiwINXJl{rHD&H&~c!zu?VrAhj_yyxm+CH<7bazdo zf^1$5Y8%*y!(wspE~DoFs>A6_S(Km6FaWh-ULi6zfNw;I;@y6Y0(ck1>zA%L#&@uD z`3t~EMu0~^u-`o^*U zXJgR%LP-d`sp8ztIt7C-LXm8W-U zXekJoNA!I|->cdEgNlWqpcj1V(YQ_r^Ls0$g)7xLk;kKy*rbKeS^6wRET>G&BCICY zriRE!_b&zcX&gOk8@=RY(hAvR(aSPFL3q`SQM<@`YV+cR=hD3;y4z*4c^&1zdhn8)-l)g}pW*r@lE@hv z<;C6H$mxfb`jIv#$fz>56Tu<6RCXgy7A{PR9*Z@}Mxju3Nl6xqqEM?$tYH8KQ4SJb zDHLIuDdUY)uX1zn&`&_}fO2eM{|ksik03t)EJOeRfXONDWhW%jJ-oez3$VVR&{S#8 zeuKUoJuhtSfEg^Hx)iF5xNv!5Yw}u&*aN>9Nrv)#({epBlpX-VwWsG*#yj`PbEkE^ zcpW=uaK{1?zZ2$glW2f+ceIIemSA;$x7*@FK}%2lOhJ63 zf!*1xZ5D}m>`xxuk2wM#yu>t7gd)KrWn_ao5jSY}6%!3F*qGPWE90#1la11%vx>g8 zMuXPDx3ekP^A@~9Un*e;e#oVoLQH*T3BLA3M~1skNnFID#9z$hg0iE$WPBvxaMQ4- zxyBa2`1@TA8VChPIKP)_Cba5ltIqwp*o+yB^mUb;XkYE5FnPv`Ku<22z5Z25q^H;{ znqd`=Ne^X~-kztP6>UWKg5tdEh(78+k^*Z#1RiC zgkgjAeU!Xoa1ZVR9)3p767M9yLZC2CAd51PU7712z+jXfJdFM`cj`6`M8FupXKm#A znag$k2O8Kh4|L=ufBnnO#~;v=I|TFnd-V-0@%SMBXIMaghQ<2lrVchi!AtqGnfwo- z0Gj$K{{{f1n%)~hega~l%c*F=^T3v%Gk!KGx8N%kBp{SY8aOJq``=&_S=FGIO008n z8-Qb9X4DJS=59JGGM;eTMw&trg-dtsx0@)}@* zz*wZCAxu?MASZOfYYgh@7<^OC(8~x3QFEy1*T>autPB!%AYc4muCapjQIR#$)xFG! z6<5UUKrKLS-vvd+yFtuBWD-&QcO)j;#_dyAeSn!@gP-iby5P||9vnt(3vKIwj z>0(Y!hKmqx9AjB1{3^-L!ztDzWVxv9YotviFw61W9Vk=?<3Mlc#yo;Q41yTd+}wnLx~DEnR|!d0jMdGN2}W#{4>jJ*?bs7F@b?h9L3RAhc8*fM>Lpl5sn8@n9($k&wwg( z`}GE})917rLu&AFw)_tW{rVZ+{{cdv19D=u~Gu7CkQ@-J$%t5CH70%n3o&U`|8h|y8Z6!i1UXO}Lt zKvj0evGGnixG=303;KWm17*GgIA;0LOF;VH{b9vNEoSZZp}#9p%f)uS zyG77AH{l_E=gb41bgDme4s7M~+e7Ll?oEKgid5G8k+AWx^r251=QPS_fws>{!fQ~<+Y&VfsL_S^~UYkEek_MFqmXMPss7FbRc3Z=h3BK z!M|utRWM7pyZeLX4@EC}5`y#q&!;mZX%H7dbcPDdV7X>MLy>M3o%4O8vXM9b`Wrii zAXFDb)3}`t>bqG^P(2!urx7`TsC$IW@5O=6f&w5lil19n#}V7 zJ?&qJyA?jcyxG|Fxgcc>fxHU0*ohN}iu$#9Jf|)<2=KG5Xa!DqTH8%-}1(!kC z1p@#Rub6}f0ARk2w-;2uuuVz&7glP_$G5w+GVn0|drzomOlKVUiZ8^q&Tax$O1(_7 zx-6Pp-}iGnXeyeX4~lK*9#3Fyy8Bg!;rlK|Fbb>pl+8__RI%R%9p-^3AZ!D^DC|6~jMHE@9CF zliNh_`=p^r=IXK?*!E9ntGRT3nnS0N@YlSn0k^-RSN?qf7`pdHEDfVpr<#40U&J*9 zQd_7qn3Op0)uv&9iQlRv6I+eW!5%~HD1c1#0Jun;%-?QSFPBqhkj!_jLu_vfOoVle zejBAdHLT+1d5b*uO9jK*b|P94pHA2NNqx_o7y41BiotQ|G((xgkjo!d-k|Wg@@Y9n zp4wtx<4K;T&~1x7rpwG?rV?X2&ZWob$_uQ!q!X_3qaY_MwOWjfZAERB$6OrIDC=nE z9UuGU`XY8tN$P~mT!VQF84O&zVv0w)-a^NTwS z?CUiXK)X&nHqRuT<8cIqv}WwsI19kY7Z}?clEm7b;A#Vn!SO5m^4ljM_eW(aWu@~I zODBvaA+{F$k=ahV0L8b5Z(G1v$LnL7Mgcet=zRf3CkxUpi?=5*col~G8w_NC+;0b_ z1)1CRBDw}>hA;pI(>sDTKoxzNUcBte*~w8R8b#{ca6I{_i-$(?)Pa7(%8!%JBMhdT z=$h(sxw23M_1sMG$kyd3-^V!mM@2tmiVZayCV+h+Iqe(12NZq#+qvnS>ZW<&+rl4X z7~OG`r#LJ>obJ316XIB-y{0)Am1V+;d64wXh5~y)+b_?Z-lKCaoN+4WqDVXHT@7T| zBbuU7#|k-8gvtuH>4(Eeevfh10c(qU6c9)hMde<|U2<847@?Y4iM=02w? z=55 zwy>xq{ugcLF4Kb_24`M%`SwutB$tPY9|NjKy z!G~KV*Zg~~|EB20J-7P+E9Lh-k**MDFFPLnE`!SIL-P5s2)C6Hgi=z11d zQi*u%z+|-(B{FxdK1j+X^7|IlNWTzJ7s}4F3f1oAlOLW!DX|3;+l@I9H#KIF$KP@c*mEDCH5wB?t<4)WdmY@Ph&LZl6Q@f$DOOumCU8T6JVG4 zdl?{L)C$T9aGO^T6%ImlU*ulGSiVKD`c|WG{V3hT%vqJ@dz;H3h0llueC}<_@248B z%e5d~!S?y5ZH_gb>@QB$P70F+mA8#je_qhg}EEx(PuZ z$#`!jHnNcCAZy$xcZUAaiVf!-;7Vqiu0}{<(Rm4@B*Qy2c~(eIAfQcT-e!owz8~i# z1%n|c(uAQmP;p;pyP*#3)D6uF9m`2fWZn-8^c8YX(*MgujeZp~-4_L^Yrjg~7Cf8@ zDPVaV`LipN~(f3}uLL6QnA{FnQSJGB<0uuGjg ztRm)gXdtz>%}(rLh~(I$?k;nsQO~D&NI>XuHof?s@@;jUtc0Z62G}z`;w$iu9ADDG zIII))w$I%q2|J)hIt3$Xg2gD!yN@(P(wD{1Zdv8mQDn9I2Q>c)uSA4TV^tX+!3fei zG)QY%uup;LsEY>)3X3+gFsA~ZUhIup??2XiOkOIL0w5|Zo6@RPJ(jmykAmN|F2#8P z`1f_Iy>BSrz@Xak?)rhZ)$um^W(_Dmg6k=_gHa2LjQ6R)J>s{poLg-Ub}>%)rk4=Lnt&^NkxzsOiayWYDZ{y?r)Q5W-(?hV9+(@ zGhfeaBb;Kid59!>0WQ+B5@I2~LXr0ZGf$7$QMzMB6w9&5lBSI-TiQKB?4wEa0e0mZ zzSs+r#5W%#P8ci|t-rlB!kdfjPq~WMhduQQbh$LlUI2h=jF!&7FB8ybI!moYb1EOi z!|~*<68a1rFpCJ3u2Tgn-!DlnDt--LakBp*N%-uoG`-~AJOZa2a@U=jPiv<`VU=DE z4%t{~ZHxGI_v}+!P>+GnXc_f9te@1o3!_1@A9|F^NP6crljJ_LB0+nyDaA0`xi4gs ze~S8jhqr6w@LE-#@b(vB5SA&o#bn9CfB%Z!P*ERpepQzAyNcHm$M1@q92Yr1=ev;o zU-9drcn(kDH<)E?FHrG}-KOd`kuy*O`z}~;~(+djv z95NjwOs81FQO%ES^n8$2kR!E`{FJ0+Iu)-%8>7^@J)}-)V7qN z@6;}-@>2R?i>TY_zvaDj%ofKEvxv(NjYaRclrePSgNtEn&97S7UKbI+1g=m-wYSVL zzVG+x6HxZ>^8@-y90_4`$zhvMiK?AQ3$9A!K^Y?SQ8vsUO?Ci)^7KUm@ygnD0fM!T z>I9F;`U7BCAZki$-B69RiHsT8cdm@%Caqyl%i4QAceZs751IS6ie z0p&{-3m~Jy9LlIAdUBmu5B@scp>mTH0UjdF;dkOgRkQh$I1=4wi1=h_y{N>|SPz>8 zmyN{FL5QEhGu`G9-{Gju6puMt%SNZuihB^5o*|foL5u~?9;D3@DmW^n$rWuq1}1zZ z_j1zk?mSMTa}8$mk^xFYf%0Qz#Sb$$vQp^he{KlNko9VfY*+|^?O|#Nc_UD_4 zbPrz9Bf~1zjGMN>I5foswYpg{1B_pFIPzB^T;+lH91)9Y)=A>y{3idh-I$Wpgsa}H zvEvY=2DdsY#qA|tIczqXa=r;utOxe>Y0)72{{NB z-XLDPL*-L&5p%5~=#WRkNB z23i1oO9rz(#M?qH#;tn0uXne8cKPtT?K=XD>FgtmbHPOsM%s)M!RGA~+9%?j*~xB^ zfppV%T@Y-oQO~EHZ8|ebf=7>2tiV;@~Rx2uP=NX1d*OV2?0>XO=L%(WYdq>)_jv(h#)8 zfrNNU$ajgvtKDB1Src>7@xYJ@uzQjCdB$4l$SsuGk&b}&#!}+8F(K5roCvy}Uf#;c zv`M{_q>Po?_goZzK7>yXTEWIzS--bPjnLr1YpxCHC&ed>PvE7=F!XwcN8b(g4STuD z)#%0A!j>m|Eo48-PHJ8P0PvOoH4PJjk(XO-@+^kGx$rV!M#bgtKUhCcqC`Zvl+YNO z0&8!7KU*DYlPl3bq7~F!J_^R`o!>d{fv@mm(&=rbE@m@7*LgFdKolJ0QG3CKiS?-c z3hGgYn9EGPJV@Xq6B^7!rULP@+(W+Ss@s}gnwSPDM`K4Vfbs6d;X?3l=~q;}6VU!F z7kip@iTV0ET1gd~ykK=#v%ZR(Ppaq&S!Y7xKXxy2sN`bQjhu7}f7?u+VKUWHtEk#L7`9@Ac6>ea6nxW`O`h&x(R!+nH6W4#PAnFxs z45D=`hm#G}pJn7O`v6s8M>22nD+ZGiauMgYr^;D-P|}vbLY3DX(X0N)nH;)72fHQ= z`*T;_pH$tN&pDp2GZLf#fpJxABHm>k!);U*r>5sqP#jq_4CMFx)esZIZFK2g#RV;s zMoL$pys)QGBXmkeqrRMA`mQ373n5q2<9Gu)JB*%r!2q59a@N_5RekqT$^L&b3KPTXYh;l_H{`(%(Yt%zds891U5WPhcM2%2vmjQ`VvnOm7%+{F1^}VddFzu!biN;#gK}_yLE=psxkP}E(1LA zCA6&sI#uX*ipoG}-N911AOz@YTt##dbR$2j{$W+&>GQ9J@4ywymc4b2+NTmUa@Sx6 zAokQ4qE7Vq9Y*d%8b5|JC*}Gbr!$|vmUiWl-!e%_)n5kOC;CyINI-|rhMl25)+)bF z3=xaZyKAuClvXF8SRX&s7AStJhc=eD|Mm-qmHvyHTawGOa$Xk>WbTgxYs*2%cK5;8 zN#rhAw*d25r@n>Qre@KC4#)oTe!b0=KOs+f2OrEOIPt_(v4)TT$A&MMsA&)i~e zyL4MT0S?#g;DRN%yA8xL*N|pYnoH}FLJuEK;Cc8mjBk!YB3KRLu0Fr!IcxPoPOjYq z$CWW^L$J;1Q`ub$-p_TVnJILcZ+v38kiX0J+H5&}G$Q4~R+>?oKvT%8z~P9|lfFxR z7yfGT(?vQ8NEw@xB}#OP3**^|Lzfa<^K0DgdAahB${^$w84zbHm?gZFsQijY%RO_F z-+{y|E1f3sZChCx*{@{?Pm8MU;ECGw3<}*yzx}rzLrBkt8ao^iEBm3VE!Uv&nr|P2 zcaKyj^1|$`;S@$?Y*-%iK?)H$0`}u)cIwLDUn~}nh<9bMH&9I5L}_QOfli6DWw)d! z^2fazj9@$>XS)x-BdZMoZsFT4;JitJU!QJgIogc!!54EDcCzSo*;44@X!WI$M zpnCA7nbLsQd7QYO|)vv}jE4h%BENZ|?dHUA)9tQWwJC^KgtyJ&I#krr5%G7zcx z5pkVKB7!+^;kCSkh)H_t6-zdJHWK#v?E;y<0*jX(_RDg@my@#c^XZhK>4k?X#NHup zIC9Tv_T$g}JTdL&!=np<%LNVh2+ zjzi*ZJ=}q;z|Ry-uI)(d`vK1&fFU0zdg7O!ll_>YZvFa}Ezt!NNH=L5Yhamv0<~VX zlIy#<%9^ic#GRb_(t5cpw0fO+z#Oq_QRF`#IX9tlBHP2}xdj~GI~|j(-;0j7q%6Zk z4A5h!qz>QP=`K$ynZmb0#DrjRO1AV|V7vBM0T8HS^Tx-2UT@nhHoRv&f$OUBWXI&5!j4j;`#U>{$!(({LYUL( zb1(@Tl0NMAx45^2jgdxcO?i0(y`YJsa3i};JZJCYJX-g;C?3YCNJ*m>aud3vtb0*^ znUDO5cT0ifd2@5=`r!7$hE>};8a>bUFN*l}D7D}#?zd|rb>j4y?}!rEgXJM2rvAz2 zv?8ca5o@~qr&=cRF2_6pa=fXhsS2lC>ALbYZ1=)_$OOH^cbRpMs~8ri5h zLGhuaU|RPNL>Zq8d}0ULJ*+F-VF;3oG7ubA+}FO}sbVsU_n-eH2PqgL9rQRr#}d_rPAEys@k5ufY!E zd5L;M;}+_K(g{O_7WSU4FUV)JfOr9rgBE-d?;7ZRgoGuTe|PYs!0)#W(>tzcmNQ3x z$*rr=xix571zH0QcD9nFH9U~O;~t*$E`qhZABf_v|Er&@g_O(*kWF%o&MNo(wY&}$ zy%3nEVg_m1po%=G$Zbo$Vnrn2hj`Mane&uW;m`DQQRZ^*I?by&X573Jv`*Yc=Y zfB24AEX{fEKu#ON*HA87G4`uoevA_8Jx||iu;AQ78&dCueUyvV1%e5q_Oj=nj44G> zD&utH+m5a2z@{-+sCl0QzV~B;f*=UG4zPrjTb~HCcP+D%&uY`}KsfvU zXAA|0^Dh@`T2P4Bi5UwgP%AX*pF5#9p=4x|3&k4Rhk%#hox@;Z$d-~Q zFkhseG|}f;IkT`c)$f&u-M@{=!t4afd3busc30jXV89^~*ZJ)vS|JM0eQD)raIoW$ zrSJa-K|sF0K~!?N;P@UCd_tsDv%S=zSnmPAzVj%P3_^%!$K>E0U^>R@DU_{lwZP`u zun4(c2Hcp6s{m39(WRR_GY|MhvwrN-RcC?ahzE)qX-kGB(kjDI<+dCQmDy-akYQsf7*3Y9kkamn#< zH6>kCp`#0E`kLpt&F7#rc|3A@xTm zos&`#c7y|V&>Um%(Dy@RoZkIK8okcMdxUyEdu;h4C% z8|KPiX6~kDLakkZ`+68+W$54Sow#($w!MCDkfDx8yP7lWHTJmXOFHLYy$<{^^wF3` zPS~pvs=`T!JR9Vi)9?v;Vg<JD z?UtwgmdI?5ToI)}vQ(%x>$3(siQ1|U@L6smo8C||;+}xqT~1H15!`yz1IrYM1lwZL z@$3jN9G*Gy-|ohZNmhMn{cd6WF6_GFpE_}elHRUSF-&(}9J9IVBNQ=8*g2{xCmHNu zltbOD_bXS?0p;RX9o~|QEY$+6(&=0Fyf9Ar$J+YHOfk)`3Ni*?_m6zSM4`lKm2`o+ zUs?q9Ry2iMGLcFVX+%4h*L?UBuZJjtZ(0l#-WeqL`=BT&NS4@s&hyU-a3hBZ$&q@G zcHe5?{wo4D28_q|YL?=I@$+I4a4T;fI?hVV`YETshdD{IGFvf85#v$^BDFHG6Rs zLuPYfOAtM*zR#b2W~*r{AXp0b%rNNQq;1pBV%FpB=|#quYgwXx@SJjm4M0Q+Z{wUA zfKEZyxV4za$1{fxTG4-UDTZ^w!8D`V$GYW>35TW9R!Qi~qlyZr_;c<9TNq0WG&^;A zL^48UwFd_e4Qy^KD#ivXI)oiB%4B$*4JL|@OMl?8&weh>Wp=rqcN_2?V# zVx-5`qI18s@PeTq?MAsI7V!}L0=$goPth}}cz{Qt9(VpyT<#EUT9w}`TfkhK^aHc) z*Q_|Svf7D`vd3?(lyZW>;5h{x<24>32*yOAaj`l@K0h(Wse~Th)pnT~iGy82>Esr~ ztsH+NRIX2a_VolWOPr|Kxy;5gbWv~tf2kStpq+M~&Xq7&#kP6w(?7z;7s}`f;7|{3 zxQ9LY1&NDTsnpqH$cPDnwD_4u!Fi~HTcD&5vxR{8OaLr%2>Fnd8<(cx9pODPAn?r( zOuc(rmuABJ+I8>y7K7c*EGu91Z}fG@-`vJlSms|NY1D#@3!Ut=ip|tpVg>##q^z0b zzGxANaC?Rpp{1yXuXk1FwY6<`NRp;o8u3Hjwd9mju5aK+I(}mD z;1;v8gd_P7{0g%qb6Mb`crG;I9sYh6DK{_bfl?`^ZZ1@bI{Jj3z^r8dctKC6qQyMJ zj%{VV6*~a(wC<*l><7=7TBPPvOGqcPF|(AB6%soPkLZJ`6+fu$*4bN@Gp~PmPQBltAqlMyn9K=eYlx{GcDV)U*+K`qF19xow{}sfCiiS+f zUr3^--;ou0LOfbDjTH`xT#evj!g;)9tjb5k!}6sirpfl=?pb+9JR4q*@EEPolVKhc zGsBYjJ2zBM#qe*ZXI+RLtl%?e?(EVGr7uBKVjjU zNe5dp8O0KFM1jhjiQeXRG3C1^JTPdn_duii9hnhwXUXSyGs;%F(o?|P>cz8Mf3FF& zYVk`+PjEb)vsqFmjex=4M8OUL5wY1G*VrNWjx8MuhCn7ZcUVSm!PfdbYlf+i%ql@! zEjk5A$a-fac3A*MyzA-CI(=8NnW+8@Oz&^;WJ70#mL}xpG2iv`z>_r6E6AmT_`Lxv zRls%>+-KMKZeXtzKsAvrJhYGwNDsqmhPqwyj=26$51_S!rW$SW$~5Ht20p4uQaZHwgV;?Fm%M&}C!tl?gxZ*yDa>9PA9 zq#LtvuMqh)B7A?XF0WEK<+Nh;9h$!z-+IO{07_<)TD0Z^2e~W9PqrH$5^#I!xeM@i zJ?y+H>z5*t;d(*~0IZ8zo+gT{Ty~8zAK+~a5C>iP^bde$ zTyrDTS6s}sjLF`jo}3hwBkwCBd*d4KVsKZC>vU@~Q0W_QNt^`JvQW2pch*IqQcjYd#$bjr`bQz`hga&!p-cxTZD+~u z$JshyAifw1t{b1YO2}n~sGT!PciRseR?f<+u zcZTKWESw+u=E$}F8`=6!&OmWdqT(`MptEz@ zghAUeDD6(7spWy(3QXHw&{O2CggdS#uwe_P(FI!Hb)Hcyhl{5XgN3dHue*gxa~kgA z_XOD-OU*!GKm@}5l%=5iCXCZe5r8az{m0(dA1s~iW z-r_$*F40bPF{&WW`=%klf=1%aNRG>4sV*2AKtZ4rJ!^1TG}(AxcGE>y0uz*i*weG{ zYsGmay^^0I!;H%1tS9QS0bf7sWZ=Tb6UL*A-v>sb{#G@d<9zErZGPRKBFKoq)&ccj zB1k@>=t9R3txnER2aybrw?kPSY~Z^aBT-}57$)uxYLFd#v~9gI_@6t%KVgWCv35aws&83;eK¥RD?|8IB=9LwsGT{GPAiLBCyWQYajv`{nBqGTI0NvV*+sjg3ylGG@_Ch$Ia7E}7f38fc3 zft!UxzMvn!&1zR`>`xH9|1KIkV5WPx$)z>x72LBt;|UPOW6@WsHU~PH^t`~@byfr4 z0=z-qSP?=R!Tmb#7)D3v@p3IarKR=H-1V%gBwJBA@|#$M4-a;CYs2w07w^I3&*9I5 zOZ?5erc{3#VKbMHS;L#IaKsB%I)feqNIP&V@-Xqn^(Z-%(5ImL-0@>qJpe~G?#z*?I>1wU zB#{VNjIyVXd-dMc9(z)^uYL{-3hjngL#RQS?jODoET?3w$OIIUj4vJ6Wg>Dcx7yVH zqz8sTnFxl6yoCD{>rO{|O!$Cl-nPN+-Pw2jGSLQlF{VhYn0UlhejZZ9848@lg6!5O z3V0Gj=Gz+v@Me_r-@3AcF61D{YK}wu84&?x7VwZ;B#Eb$f7kpe7Fn%UVa^mYgn<1p zmywaaeu1NmU4s zqENJ_&>mc9PZOc=u-$t9KyM3G>U7WY5plLhF~Hb%bSWXUzau}|%RUY2#CC83~F5vb3(RTWzwwsW9n)N~5laFEDObMV}5bd$%UxR}!w2EqK zF)vxX7}Gchzs(dnX}bZ(0x2N<*dgON(4>l_`0im7Q36nnrBD2BIe14Ze410Kf12Ct zqQzZ_%22N3OPrdTA$;*RIx-qNEKr-6NEDt5N*kR7GK7JOiW+ig>5`-kOpMo1>D%4< zb?#S&U>Y0}tq$R=>Np+rgdMb1*bNYpn{NkB=R%o2hp&*yyJsj}&9m%_u!AeKD{M8x z%FgseRUk;nB8^`$Z5XDu$(UdOKL6uI?ZTdxZAkdw`PP!_2qhri<33CEb&Te`;h9u< z#9z%B$gmOq6}e7vgBz<9dx|=wii)%--jOP|52h19N^Fc+gP#o zeitdJSnZlA$^0asjgh?B_a5c+sZ~ml;dGFT5e2Y(CWPy8$!Lc5?U<|keJB_kf6wg^ zA)He`8Ca7wwBk_i0P9PdL(JYeb|eW7jN7jb;D1>j4vZ~-vN+$Du!HD>-PlqMzt+IA z{W!SX=;`7qOSZ^%$EN|19PxE(<1}{(kI4&eE`e983ur~B;rGrvoV+A`6#uXVf7m<* zpQcwmY`i1MB|u;zPGq|Mb{qUD61eNDKaO2kD(A_zH>wb0avTC zkFi(1JUkzk`eunekaCt;isB7&*vs3ddN^`gD=1U2ZKnZU8n3jIgSz{vu4je0NK&Ym z*6(amVfHhh^d%Lt4IW+^PLn?F9o$&*{j;-GAX*H+o*m~~Rzo~X{+HoO!os#54Ts|o zrYdcdcHr(}Vym=v|EEOb_QOo=Wc$z-8HywD4SK$6>PNg9zHq=V!Ms1;mX)b>E8Uoz z@B!bn?0P-EaHSDRm^r0+z%gDVgOl^}205{xFvM4;A9VuAI)@(`D<*0ijUecy^OPs( zS=Gq+%J1VCt0D#nT3!ZL9|muKQb|<0g|ip4P7hvxDDVZ~UVb%Eu`A-T_+P$Uf?}!_ zLZb-qzdMo_70|^*upOHjdNg2ZZTvyFn6mA9$W5Wr6F0E1bO#RcCO~Tzy#<}SVOB4V zFhwv_JCK09`}L7y{E=m7zS;&`#Hrsm#|;EWX@`5J1YV;XWBqPN_ZYnPai;SiXRKnd zQZ76ML@4#|;y-a{zQ8$RGX+{xcxBG*#yLR(hu`iD7G5~zvz4P@{bB6!?W6Ws} zJ?GyJee?eOc!qB3pKp7>;8xzAa8E5n>uWf-iMXW5U)|`pWmI~yC4jFpC5(LdfeBYr zwFGO8F{g4(S4D0f=12zslpu2QkzCXoMmdZ{>|(i}3&mX+7=rs^;e&;hySD9mtm^PM@=YcLX%!x0S@NkT0ZTEh1sso5la3ujl#_vs3nD*N%5--P z9zK*1{&&z&;cvn%`8tm{w)xy7KuhyLM0_<&&x}(a|LBN#yW5mz_@8c2U!x-k0?yB2yoRjU>hrHz9gwOZD)>Q>DwZ zu_SU%8ztsf5`Zf;!UL<$-Oe91{=VMEtOg zhYZD)AQ=(xA^6<84L?m-Yw!EI-2d*_%a7?be#d(uCB-bqv6=Z-aaP*8US!4ZTocMw zVG5w?K10rvW)33!-^1IZ5NKzhfJk#I0D(LQK^NShT{0iN5k!Bhk7%D20;wterF6p( zFRxkq|3L5%$-@NBqm5FoRwGI1@6_3OWczb9cZzoo7W2OOy_@@|gT8H^05jEDkHhvy z24CtSVngcRI3zvQDjc9C#fp4g2ru6d8Q>b1_qfwPgN2`w4bgtvY`2Jx&;CCtlecUq zZ9=WOJ_h9N%zhAyasv(E6~WXCiUo??<=Sfd35e6>zzA*_^1}>!9phrRP5`QFIMXpd zGL@|;-g$!ziMbN|HE}yv_c?ckpv=@VdMJ`Jo1m-4)k&8cfGKP=+*#R9&Kay}^Xl6p zt;y`fRtTVAL@umcFv)VPpz0`uLSXF9~2YnXi=_9(pa^4WAeF@%^k5?bm`23-7+ zEFMf>ubsk$CLSGa8W2!%1=Wj3Zaq1liignc728Wceab-!TvTdyF)IH0V;${=)aJ=J zL|d>73s?gQ88T&WM?9Av`Yot}D&Hd`YJ)K0lBb*kp9jL+kYHbY%tKHxqV09>7vPvL|4{!ic) zWxuTc6?F!K)EU_f1;@@C3>33bCnyB}Fi7zMx@q#}h$QCoA(2AQux!s2(OI9S$Pk06 z=IYWbae0{{VFW(z_T5LDK)-ssgx7?zP6F3^9s7OJ(o1{xExq=Yhjgja*L z@tPdh{qq15J>B=!wD8|6?TxCoT7s_h;o=|&y~Cz9VjSlB8Bz;UhXrm7WVmO}5V}Cj zVcGGC=jmNzG0i#2X-r4#*gY!Lj=vqx`E@E(~Y( zRE)}X(YYYQN1(7XjL^8#1yS?m)Mm^1r>jsbnhN(dJrh71>ecw$1zLXFCue;3YnDuv zOIfRnao&kr417zQTp!C+FFBA~&wmp;i8q8Q>8|R6?kbs9&T4sJ&8M0tT*0O}I>L)% zb7_0)d7M=kjl*Kc8g(9RBOF&({>ecGw`DY?te)wA`ZK%|CIZRSY-7*4nT-tOI-XIJmAf4tnM}u0inU z*lY&EA|{!Ly4D|F#i@avxr33QHcPL)Zu1TdaD`QS_O~u{dYtq(>7h9w2+~K79uxWI zZK3A!c#6{Lukk$GZw|J9cqHVI-vtBh#@Rzf!Z$C|0(C0ukWwR)e5-3h4SAx<7C=hP z>4)qc-LT$byZ_2L$^pK#gD3F^!Y%Ri!bbbNQh18}oZBH*?9&?>uM3OL-H-)}ian^-htsz$Fd!Os%p%iDd*U2ax?;Ig(Ztaz@BW!Nl77pO;)cs`MU>(Dn== z2K3J{dmyZ?WWHvA~D56!_N)$8a=KT?SuY*MXRmY`B(} z`#_`fl5)Ip?Jsl{GnOK8J(+Z_4A0lOT^9#9Ig#Hf>$aXgZ$yPhDX~wMyxk`^lJa3X zFk_it$b7xQTg^g&n<2OHbH_FHZUJW;hV;>Hp^68#ykXyb0iOyOHoKyq;yGN&0{hEn zNIA$xwaG}t_YkrnN|(3bRIN&z8KPjiy+G5xY$celvSO^l9Gw3O#}!7O!uEfoK_zAMa(oX|V(?>?!hKH@7ewJA1k1WKkm`<(1ua5XZ*v-A zsVCMpKIh0yogxMill$SoQCDXGYw@*m3zdt*85)_JP0$Y189e^Trp%e|OXk z!}ZE4?bgkIALKtRIcX1-6Yc>VEQ)%_i=6lWI}+##s}PMR+&(V{_AJf_yejC_kJ`R` zcrO|+k{{&Yk|RGx<{dm70CJHVDpSNSYB)O%8QXZ?YZSOqk2lYei9-fHU4r=V=BpD* z0M2^h&&6$^7HC8TPThg28m&((haN6=LbC1lr_Q$(WJE9cS5Tp>V8tO+OmQpwv;Nna z)iDU}^-f8xYB8KrW9LZTaNuS1L^djqba@o9%r8)pUN})T+~H}Lsu?XbPJdN{HL|gi zG^7!zYZshOD^hXr3v?fIG7u?WknJ^tbDgUWv(@S616JYB{v$TS8lh1?3lIuMMl3lJ z%Uxz9IALQ-`>;lkxaSE@ds-HHnAyMB!<8PmH>(>@NQ8*9_=lLg1spOZf)0E-*~rnI zMem`9r96NQtdpS&HnlKREwaRpYP`K|l6YW6X4gp8s|o?hxI1Zsc4I-!xHDPjl^c6P zO(Guag>5BVx!@C^Jpe)^T~GMh@>;R`3ti4+aC~{&>h7ee#r*=!-ztmJa!zbDUy(+t zU7Um%@1dNhWQ&K(5Nb=EQ1vMwjHwon=`i!u&99l2XbKPMZG+>AnwIzEY00>A@I0O| zu}a|zLWmrx#x3CJhwW=u7OA{rD+edO9^brz23bzBKS@cZi+{9F-339qumbfYG2W+- z7265F;k5DG^91YlQoyL+5g!rem1Wy>0*%T^Ns`rY%jV=T&YXldK~!Fpv7l4=$C~y3 z>torRW$PdS02T}THyg{(bA*_4UNn+@u#WMPJJ}y5D=K0;=tFT^DEX+wd+0xJ;Xr{~ zJv1@|vK0n`(38k}b=ZQTvL(W0-wQMr-%_NTG-mUvGhFo|1tO?Vv_%8@3^`Vgt&j;C zYks4hG0e!$UO(`*?)n{svvFHQOWoGVpM_-p@!m~i_5EkvPPAdD4074`9=W>s(RC-mbHjg%S*ZWhIk;->`f(fT~paXHW zTGv9b$Xk#Py`3hq3QRSa7jf3{ZP&|s?;?D9?5#sA4;WrhT(kG6+)5nE8Adw5%OX90 zeshezJ6xfH>X{QI2zLdiZ$39Ng?l6_RoUJnNQ7eJUXBI}**X?*d=j?RL%(%ol$_JJ zOvg_DR&fuM^rHJ{ga8)TqUG1oc)LGgSDomlMMIpdS+I4V?*JZTT3|gydQ|?YQ{0=E zKuDRI1A1XbJp-HOR)^>N&qjpF3}5eavt*@m!9_7r&N2>`&Q$bc5Hg75r#EqUUGQZ| z-1HT}U!{l>aOXt$B!(jKj$rwPG3JxHJz&dL?I|#2I@$f%uM2PCm4&*|#_K^I(&WL9 zRyTYYyBDDijgK=pVQ${eX{$2X07l`C0Tj66uC&4W1LcqwawzC7?*gi-d2y;bf-oN! zr+Yd?OVyCkTh|!At5Rzp!(iJjDVEiFH+x(QmF%R(XyY+Z|3Mkz>66So)1$!~kO%(< z>5!E@YPeS;3k9`I6w!RjJ9SIq_0zFHK84PfAv?i4hQ{p4C2$ zIYf3_=yWQ~I@)uvRHYSf9>4wTGR)I%c-V8cYg7jD)j^uzTbah-oT9 z)UVUm(C)SXS!dZeem72me#%0r-~RlN-UxY;e ziDkJRn>cDYD4Heb7xGatyCsblKGN@TP$ z%gnJL;|JhG@2d?$M>e+>=q)dw>_;d*D>s=Ydle{!D1HRKq_C^+G#9Mx=K&D*5iKqR z47iOs^bcj!BblGVhZ$BppQrpU8rK1Wl0s|I_l>6{VrrD9Rxr|8WQF|f67-;4%CLmK zaZ@mAzt*+x%Iv<&m0^4rlNfj~V}LiRkdzFk0IBA`OuRVMe@6xKyd>y}3$h95f7io`r?a?Ml5 z8)mjqe#SnpQf;lF*<{X|4E0QqM$>@Y-LLtSs%(|)I2WhG$4M<7&gX^*Oaw*ziT}Jr zx50liAiv{j?{Ezw0@`*JDNaSKMQMujgBb{4nIQvf(5 zAL1gcly45M^XXo~#rME)r^ytmkzUZ{9&Q1{ewK2ptQ#d)3z?~61f%99g||RpjFlCW zKBrB@*=CQV`?Q#Nu(EX&?JDx;5?-t(8&UYy2s+b&3j8~UIWOj?dO^G?*;*RkxSfdO zXZ-~9&-_P^e#4bD-T{Px&qw3ezBsr=MHgwBFZbw!$R>U1lH0zg+f%Zj6Yt)*4=k+n z5ktD5;P@d!cEVp`1pF61uHbVUu~`vci3MGek|2+QptE{w2-tVsz>jWOJ7;8dMGXvo z<>!|<1206XvqY*wBGXrFDeZq_40!&+ahsN#gacP#waju!FW>+B}b&HN-WZv ztG6(0o6IK?G>%VgtWt?{05UQU?u3hN2Q=D#Mz#(`o4 z<$$aD6)$J7!Ijkdm|GTjuW4tVj9Rft`R{cRXfkhM>h>H0!3zR;zpj?)?fDxo?)X-@SCvXdyWGqF6g@h+<7%Ytveh%5&1ag zdbTq*ldT3W8*7cM_7fBbxb^MoEw&En>s{>{o;v3pxR)>eOfG|qPv!~Ur-&l#tn3$Y zw-weK3Hl18G4bj6o-~c1(g2B;H3hk~NEgM~n!p8oV8ECq71*B<9e@Q+Y#$(S9vDcD z@1jop|Muud)_mS!>~qXP zP_8j?B+H1j={GA&6*S~Ay+fc^R{cR=X=T94Bwo`-7YURXZd_u*qIDNitAGjwP}#Or z2~*@2%;dXiv}^Y$fJWA#F_^+u8NOUH;iB43Z+o2x$Ml_IFjnwAr-pRp$^Y}e%_o;{ z^6p2j^z70L5xn}?@|S{fDspY9!)P%`a+lSXzOI(rsu$DY!zm;EE0AODCYC%%Qw++s zRM=r#74GDr-XB23fc!~A@(`ODKo1Fv~k$>N_`M>*y>b22-LC$ zq%+hMlE@iuq@oWZT4g%C5}>E}!B)1OJxeHaASPzI)*wSlcgO`lSh%#lN+taUZTZ@B~HM8jwGJ5ddJVTZmE7T-VRW$YgJnn<6nYQ$m_Ko4*VH zb$+M_Er=NxneO$Tw5{9SU z&@RC}If7Q^^RxkqtPDAfg8gIw=b~N1gBZ2a%((M1W^+rjAsfSbX1xkmo@QJ8!5y)i zO6ZY)?kpCAJ~z^vIym1lF?>;}AX*nIJ1+RO{?@j$hRt5ZZFRWEVHvfRJC}zb!7qvv zUAgjd(XY9eI>a&4)~}(#09A+X+-|$6ZdLO$&;kBMCLjg#kSry1SV^i=jeBq`Uem$w zZ-<+sQ#Qq~Ix;r6sWa5bj^+%gm+8GmUhe%Zl7l5l-S(0v`cE&P++T{D|9i^-o0I3= z08Pkj5g5j(9_}GajqD_yS|KQ(U_77vcfrISt>fD!^vkDYFJWI<(q$BMz`n|vF`u+5 z{bg37#atNB?AgbBx>z#HA6qf10K~jMKmY>XIB9SkgL}^B6tbJGNCy&|)xB)6EDy}L z+E9I5ZY0jj<(`QA|LUQ5ZR1!kk8ec_I2_Ce~Vvs@{R zE@&NNM7060X=iRAOpBhQn&zGYXz$kqfY|{`{F9ov$^nm=nRQ^;S zui#T=V2ZW@h{O-M6RxRtxENFZC9gT$amDc1k&3=}b6gnydDQ;0=%#SLX~Gw8ghN9s zSW2kRnuf%Wn)?eGCXZkQ-!cT{=rGeZ6oyX(g-GVRMq~MaeY*P?(}(8@Q45|dRBiD^ zKo1CH?^DjEN_tm2nTE0UXm?+)D`^9pBK%yzuO9^%DQli9QS`&KXY#`La_L7#iRoC` z@%K{`z8Nc5($nc7Om-Ck6-H()xQmZia6U^C+VF4P7))wq&Y9 z(R3>EhB_Q6A<{sJ_*ETDyw579W+H6=0Vfm;aG#(PRx+;V7VojfJ>($UgMmVu{b`>B zj(jPy0dR`YY6T}WcU5VI{0?-99>YuZJi|`-=ee#UsS1$l3AD71-^tJ3&ad-3 zftjEf6`xR*-~K@$t@GcZa8ONJepfRY@WlLusO;t*jnr0pFY3{#*cETTxwFS1Bm;ju*>On#wE_FdMqxOh*pO2<%C4)8*R( z#GyWMO+f?isMfg1^UW*+TpL{V#hSNnAuj8Zd_3*SPEx)wh`NFLshnCa0m;NFAHz9} z@)hOatAQG5eJMXvs8i+X^7ncE*CR7tT;&L3oLpx&Vvq^y7TkenmKy}_KB)#AKaBq) zUi{)sn_$2sZ>CuY?!-sfz4hkM6Q*d&cCzzy!%U}LqdtcJlO6WDE)1Qi4p@eJEPp|t z!(tmVCI?#<=Fj)i&O@@VTX2b^Z1qLrw7RdIjknIuah{ksm$(pbI(1$ID-}Hdcj(`C z4fcuTVH3&X;3%sGN=|K%j$=o8P3fP%H_dumVwSN2r$23_qx#nBORfX{11IhZZUhfs zB;(>k8AbHI4=wpJqsvnS6k_1lC;BTh3FYd*DA53wm$_%`h0%P(LLdr(vnh8_ICzUz zgO9pWUY@8-I`?Dn#()=n9UUA6IqpHV>%1l>t?wai$DaSa>y)Bu1W2{?5CMhYXrXgH zJXn>yB!z0ucc1UC%jeJWQj&kvxD$xVsBZAA^wYIoP*AAIY>quA#8SsbV7Vg@FT4hBa%l#Ha>3h8J zRPVa9+FxS!)OKL_ZOEgr?e|X%3XA(&=U*}SS6QYayR84A>MJ@Z*s%q&{rSjSu1S-6 zx80c6$h2l%9i@^rJ-Xy0zHCa8MJQ~tx8`z~7AhiP&&V8A+Nt&6Iie4>0$XLk+kBGZ zcY;=2+L1AAA2DIplI-8wWna)ExMn6Z((XDTWuz_V#}gP;$0HXzFrcDE0d4jPIPTnY}kqV8xdfawo7O>lkADo@a%rBu;Y)*9{os z8)atNp(N3@qn7rg@OA=~!gh$?^VnGVHN4`rC8t!@#bQ zrea?wjLRhv4dd3%yZu_2d!G+_I3$Lz*dqZ2){xoKQZpHtTKRg@n;U`G<;jVI!nG9v z!uX3X5~G!$cj#0lpC+MY!l-|9RO$1BvZEOZZ4txSpB|)+>InZksKRh_cU)m+J49k@ zGgVRRhQF?2{@9?{V6feP3)(td+Sxh4*Td>62)f~-eo+TXy#)+PFATC=+IOzqdLaT( z%Yd)5P!EEL3jard-x?~7Ne02f4;G#j&BiBuYHf4_LmfYs7r-2nHH!gLVNQj^gAWX< zIC3aN!WB0@VRO_YZkIzo32L0JQXeRG@s*&1O$e#!0c`We=h-44mShfcx176TxFc`@ z1>t*i2jqzEGYc|(LdzY2hJ>#k)98#!&K_!RV6tP1ZQLXLc-Tb!(ELpN7SKgo*t_hw zN7^2;L9;7mLh?m7!JC5%94LEtQS5G3GM0+zhzv_o)#$=80LTZi^SGSVk2K7YSBit+ z_)VR>0M~Vt&cZ*^bC}wA+9(g%yP8qsdy|KofB$-rFy3ippzqdzVD%x$LwmvF7IqW2oznhGMc7kG8;V@g@2U2GB0p6!9_+Rb$qO2 znp+zcK3`u~$f7LoNa3?xIlR^4@rOJzq=qHtO<-@Sv`nHEuI7i7 z$Til3LK3JwN9|TXO>)oyd$@q;w{rQ-7v4EqfvryYJbV2cPA=)?vsB}Y$4eesY;3)? z72X=#t~;a_uz*Yi(TYsgr^Ha&EN}Ki?kR@^>y`MA+u11VV_UsGeoq4o*VzE3iBY{< zaMi#dR{LxgE25fA;tojFHenX*gD$N*4OS?GGl}6C`SK0j35VEEcsmh#L4Cr1#IZ}= zzAiL9*EV zjOu;hEkU#-SIb5p@JF`?v_rDESBYKyX7)IEuEVnz8SpnD1rCn7%=b>90Iz`kQS3gZ zh4})_aPbPA8ZRiaknLJ6Xy)h+65ivw{jWmx&^iCO#!Rh1T!sppZMXE0nQz%()G3DX z?4d^h&bUkG#zsU7t}HE<0R5GGwB)|gS*58m+Z7**4MtXTxG zhPW}UJNlBz7+Y8EWxuT>SO}=~NqGnv*MYmjMzY}EdGD4o*x!(x+$5MO9f*P?d6qDX z^x3P>P4V;jR<~qWX?xIRMl99R!wy`Sxf0(73Xe$XW~;lyJE`Hd#@ z7GfTwju`OEVTp&4S$Uk1}lhr-ef9^TR2MH)41J%qVK;4cXFEGapEa2@#e zdH57AllT!fmbKfq7xl~Uai;C6^T8eTe6R-5lw-v!-T{yDf>hKtTdlZ7Fo?x*E$b+- z3zp~460$Ca)`+V>{{kyJGZssJeV@~g=#Y+Xb6H1XEa@+Zdn$A`*Bfv0XMc@Xx`RiH zF8t#a?u0wFkq5U?XEdGS+A9?p1i(dMKb_E5lv<_S%wh0}EDK{*(wL@MRi!rC^f71Q zet+)O{_GE~0pZ zfvVW&YX#ck)J;9ZFhnT&_)D89AqUtG{8b7>D@#L>TV$#TE(&5g*PT7U8fY-!6{v|_ zT!Y8ZGRvlK{$7V!WnzGVmAPrg1_CE4Ao)v&j_TMnZY!{N6^u~n_1)_5uGIj+TQrsU zRHk2hz%~i4|G4NoG$0ZqxLl4d0ERU0106{U{YKJyWQ>S_Le%+81)7!RCKG318dqL* zTos=b(B8QonPe!CB3EfN#G$0sMyt;1eiM+GJe&Ta^F$a6`~o4dkp@~gd**m5bhm^J zB-@yf?t9rahR6MX?2b+;Zma$)Nh&7s;w^r&#zbwRu~f$4Meh4PwZs(FKkRt32%uMn zZWYfY05@hiAqA#5uugpY@X1D>HIJAp>05e9TfiPbwjhj!jjp?Svd~ZE_frL4!x#It ziHH9Xpb7t*cD?}z}p|`1; zkPXdD+W6`sQ~)|61DFhAYZgJ$qtLltdUeoK5&?Z3wd~jh$et?gOqr}7Rkn0Xruwn1gMWl>Mo!-2M0YLc{R%+uCwlxsh0*>*HYvwr;OBq@#fugr z|I{KAwdRw#L6PU7>w8lZwg@bdL}De_G<^T2YUSuMgg_3y!hElaD{&E zQq#XCBkb?}zvtOywktW8ZG-^Nz7AiYc8liAhbK#8 z70~CkLgPn}&Ns-64e&Pn0cNMl1$r&|_o~a%QGCTyloQ$?*#~E394yA{Vkc3@V==Wd zMw4Gb;5x5+)-j|-e?EX!M`*EtyKFljqQiIKf{~$){R)T3Y{HF$2!Y4r@;%~YbQ8^ z*D715jlGWrz;~MzagSe)d@P1SMJ$kKUqH2?2kwk^GQhaVb9KQTWD8H5aaUi)So+!U z2_Z_-510oMUW;X2KPik|dw@K_bXVb(U*PNKU$X=G;7lkR`^?)bNsL8aRWB54ue;v1FO zVJP^=LwQu>=24jLT_eA)tf=cYvE0aP&>@C6shkDDIWVl+Ay=sbE?Xh7)>cnKwa593 zosGgG`4ir;T}66X1D3QDa2Gm^q2{AB@3u^P+4OTld8EeB zeD$LTut2uxuT4{?iNyer?#GXB_Vq8TZ8L0fGSff*@LAzg5?(b|8o$){7<#Z=dVyp> zRG?^hfCq*3;zcf(tr+3=untj`_Fn-3ABqujuWlW4iEn1??PsswZbv%ci zwkJDnwfPUT?%c{!co8`@Ze_x*EqL(5Oa8Snd@s(LmKcF?J z+94e5S<@S%!KopQ)-j(8bDQe!_jvPzvB4@fuMyzjnYCUayjC=r^sEue%PD}Ab02Q( z{7AKJCpKNRWrFgIbIFzC;LE)UJeHW*eM8d2?+WV!l2=pYVMAC+P+~U?CF4Q_U4aa- zDqP5^8 z%4)cg$jm+I7HRi62ItrEG*Vy8rB=iRo&gVlnj=w$&^RMi`O));FKu_^f@ly21Ox64 zaDV5=HNHm*KT=Tpngb6M4wmKdd6g4wCoa)Tv|J zKk7hDI3&S=g~q>54X!LO9ya0Hv>*SIp$Ae6hAB) z{0T#Vi@7mQcR!~zKf=XzkIKduXspxN#vn-t`__zt!jRRbv*wZZ>}j>+4M3Bwxt;LQ zY_hETqtpQdgECOeNiFGoStjW?6S!UR+Z*{1Ff82)AYVo_=o&I_pK%`DLk?Ae8QoX6 zw{2l*1}SSM&QZhT3=Vt@7>TtiFmse-uMdGY7*q%XF)4-^qgBsw@jMfVBR;&(2r3|y zVD8mr*w8#xn+-8y@a8+{>=4k0TZ#9Sv%GQfceTOYeFIX{BS>2yd=t?#UTi>UwnGeX>uIW&Pf z^UgX^Sc~TM)FU|0uU7+qe23&`SS!_SUaQM(wtlY(GcO`%7w0b4-OP39m-3t}Pq|Jh-J$ay* zArtkHZdRJuAp&(c6_;dew4*g>Os&w4fK@FfY{-6_l)kraAQ!=lZ1@tvA7*&cg*m-VQu)1KpLRG}Uu zkCz5sel@{Vem15f;RE*57!`w#z~UL?$I+*$Mf&+Non9z>_qnt>)%N$>E1&8#0XGHP zjU&IKTDJB5WWE{@#Y*pWPN??(^`-)k=Bz?U?Tg29e!9w9nLA~&5^lN{9iO5)b>CGA za1BQ2!wo7s(wiR28Z4kSXM7`qLO)tQp59}wqIec*B8^IUwdvaAH^)t*kp+%#g5L*g znq1_F8#^^H8XH(pnCwxlFU@xyqlFTwSsVZ+G{iS(NQkXh4qck}e4-<&@&>JE=xe>D ze(xL(@2G46lemb0iaW1K#8!)_ogM?swE#dszrR>bi`=1kUei33*4A%yOSj;da1VV} zUP=eJnJ>)0HVIBLtg4mtU+^uKtuyY7oznuTp6WpnJMt*bfP{6tyFCGgnl7g>vPO)_ z?YMqRwl<Ja62cMxHtIMQL;GP7)k;7Hhrq7h8-CPp-ExIYk zDvwJfFzppTOZ8%lC$$wG<6`IRpq;9sENFV%PpGe=wtS|14B7lvqPaU8{>jJocwnzI zzhpqrkg~hO?V~mHCjEVo_fA1Fu!KM5(T2Khe;l+iRd*@Mbts|c|6rbc?BWO2pdkdy z^W~^9ZUl!;{j<`c9_u+Zi7za#b-0$jWFcnz{U>Q)S$(c`4GKzpRH=xv?uuOq3D zOVijVSSzH3mf7p*wHE+HcY%-+467EJbl>>zTu)GlM6}w@6F(?73MlvdbmN#SYnAf4 zYp;cMV;H+SDj2K5xu&=I!bU|~r4(}i7?TF9v@%G8ggAh;5X=QTb75#{Gq%ATBUKVV zbKQjlu8xFBbv?y^IwH-ZotXfr)`CfIcb}OH_+XAhD`+kySfzch-1#%J{>`Brnew+i zKi+A*xv405&0V=P&+DGRD68gz+V|JOAavNbw$voYK)lsX5Qf2anntZBzh0U@ItCN2 z;AJ&|NwN4=dm6i`T#*lk3j-KrM0bpV!OyrdI_o6Bcq+fr(6E)S!L{M7SOOX)bQ|?u zHUlo%-KAYo^wR8rK3N-kYSwOf1bUQk&h4Geh^_qa?<$#oZo?o}JllgM2vsJ{rQAc1 zeqDj0suUMvbssF+Tyo?tKd_NN1OAfBqoXH5F^se|tFI!DEjxMAm&<`0hSR}Yjl*r+ ziKt^n#wE6qzzDaE!6nJMbbKi*9s1+>{Ts397s3s+Oi&x+gCM3`t0yqEfF}cxrj`Ez zSKpMlPt##ed_{TN3p-UYuQrtdG|fnVBJ(DPGE`TDIJ>jn>1+AMVfn5<0~U*vIBY~0 zltDd=qOHea4__b>4C$ASjV_?l0l73X#ay(}DCx$4X|o2fL+tpUo7i8sjJSZP(?aiw zaJh*Yl-!mYc~C|caDj2~|CENr@5w)B1K;O3oL1k|=dU@t-}F60xL)ABDJwOzH-J<; z7IB)Y-DDn?$L})SPixk(lWNIG1uacL!oCIRPR?TSS)>caDZO3lluS9dtPb7iF7Cj8 zhrzPVN*;|!ACdG(?1+pfopexb45y0%JH9Wi-I8iN-|%WSjFt7ou`Tj;+h3 z$$nmIrqw3u0hZx!X#k_B)OFH$#Sp1?ild~72$7Aby+t)Im>7C<{mr9`4wNrQSsD@W zdqrXi^Ba()WGs1TLU3O0ig;Bv$(0{&3|q7qlB{1`GP`pYtqO=<^k4t<6dM6lAd);1 z`Y2L;Tn!6{B%(y7QiSh9{wT$A|$H#RN$ z`Yjk}A;4hV!H4nMc*4g5EKRb;SPNpTlTUM*JocaINv2ZN2lHrW=} z561J)$N5VUjLQ=WstdaX5GTg~mT2#=ze zh{n62eBy4eG99$_tTQ(7YPB>w2eC;L1y1E#+i)R_IXbFyyKfR+*V_hl6ET!yaU%T| z#>-^L@qa=f?*WdU$A*OUOlU5AFGJ@Z0TJGh2TY(iSk?WqGKJVgB7quD4k*|FfPADf1LH@B6GSkr9M~- z6AQH%3kc3A)`7p*B22LNL2o(TzKMf#D^(`Bb#lvYfOk~K^dw5TlZoB&41G=V{Nl%2 z5%!4qj|jd>hr9V^(RiF38mG7WHq^ksI}V|Qd6aH{W~5u$F?G;m?)Q4kzuRUX}Jnjf`Qz(VPhJzG)FeSFFrkgj?iDN}^sNnm;Rh$%mJ zWgipNa>-p1eO|0`i`B;%uk>*3=LENiK}aLVlrt;Vp%ZqB4aMa zauTr~P+JKKf@>e8^>7uu|E(X}Wq_qlfn+h;jQkhZWa2cbfYS=wMUNMT*Y;WZ9acOo zmSZlx?}ZVo2iJb!B&jmA*&!^tfsown8kUL3PwaDLCBC1VaF9RUGSn-34RzgCPgF6W zo@0;a`cbC~T&l=^1Ftb^^A6Fh-pfR5ukI5c#}y4@xbqiQ3D~COYmqfu-ehnrCp>XX zQ2s4dRK20=`tSrRBla@_W;My`e_yC1f@*oeR`k98J}-f}%b)lG;-5WFjG${dS~VPDCDJZcHN)UQCh)KicT6NV=vJ&gpf$Ky;va$= z4NHm8vF`)}%_}0Wr$nr8(3S7BskB#-K>MF~9`2mJo3AYQ*FCXmE2oQZ`Rpmg3;&kI zVXYHMi+SgS;Jb|qj(aZK(waBGBOiCWfyqWRY{@^VTh*kYTfxWaOLPQ>=eL4c!Y*+i zo-S3yHM<4Ak;?Wzj)@A4C0-tXmYPp+UjRm;!q|vj_*sQa9nLuWSCvo;9 zNi&`8(p0=BNu5UWIR3va72VtohB$(4CsbH%GH}T2ug!adn9TV3wAcyj#x0wEXNyw0 zf=unEwyK6#p7W72VcY@O;^by=L0W2i=le&xlh&C{Xl>*bIGoOEs{-eTNpPdMUQVOK zJjmznKuLb&9qyKXCuood5P;obtvMpf)ca4nhz^z?&Or*OHLvSvVl<_E&F%dj6;1#o z1Ch*FYg3g5PkEZ+qmDGQR0DI^U_hlrzWMIV0NTZXF-_6?uk%?(!lD#ahBhVitgnI_ zBnjlWmBL$gk!bZ_YB6{a41DEMos7l^^#hUvgvCPYMRb)dvY9s!RedmKMIZ z2B5X4qzIE`8kI~^wuecGc6xnC+%!`D+6{DRL<|e10g2QtIo^(0mxFUTLg|awq(pWt z7XAj`bU;|NW9WRiqx$hG*z*$DS;9@eEXRh@sq^a6DV(cW(xuA~!mMrQYY8 z3CV0_uktGZqgsJqqj#iZXd@&y`m8{U0eulb?D_SIHV^oO1F>%8a1$*I4RJO_FS*|x5V$z!kK+4 zkhP-n^n%QC`>R6XN4EzAG`OYt=El!4wbocj`lD2tA77=6mIA;e_P&m)~GFOYVk_P-6L9 z?qjE605v6h)PXY!KLX5VnCM0!)tMTr(rI`IJ0mwiF}Sk^(Ar%vPHi$h(p@OUDyQ=t zndAZCDm~TA?6nU0ns<}PShOV7sfhrN2>8y%-vJ|0nWg+VwgWY%Y!wCV^87sxa`c^^ znEdQh#hyr|2gh)cSI=xHDx5EAYquu#IELdm%KrtLZT6>8b5Z;c84Aw0r8l{!I7qvY zE3WW(z0tj$7Yjjt0m8_9 zPJLIyhSbL8MI%K>htKd1xDZ#H18aCv#B!j)V7?}JO!W&qp!|g;`EZdMmtG%gJBDj= zoRjNL?-q=;zPBqv_z~LZ?htq1LN5oiLUVh0P~46i6*h5AFJDw{Sl1NXb-A5bUqFu} z6Qwkh%g|gyGMID??HY;NkUP^v+(glYfbx!i2Dg6oe)?68ZSa^xIYj{) zF(E_6UpBGJ-LlGVUoZH-@M&{39@sSmw$-y77Zh4!_0%7ibbu?jO&{PIfAjQ_D-9oa zU9uY|^;)Q%oh$Lr2&j#rw&Bj28!&3>^9gv{n8CU59Z4Pi5=?al?ejb+2|^G$@Qt;= zhahUwubTUK7^oA?8Y`}YMI41+Z8(sU#|GdZ&(Ay(J~~?Q@gAbGCGoX;P3ssPZA`w1hz>Gkem7`5TLIY4*WOaq34^uRlJPs_I+Y6&laqfJ7MR zGZX*kv^`3^`fKcXX|g7^NfDg5dszxPS4_XmjqHO*+cL{uXc5b8qqiP+_ah>$Bq}wc z>~Tx;_G|OS>K!_frxX;mb>hS`^VSUfH1B|MVc_F-UOQe!B+04bIu@S$r<(QYK+22m zDwST)=WMP3q^316ETx&PKNNe*YkO9&S$XvFXuK;gaW}8SC)J>;%!s@6DPc3cBFnX- zcutXOgZhmlVc*Ezyu}C1NFx?R^|Ja#O;VCPsQH%(Y1+TRJp7Z|_bPrX?z-LmZx*z> zr9$fI2PT4KHcR$I)GW@GM(ue=x;6f_&*G1m++S$s9BZTrU=eQKnZVUraMo5|B1?E= z=>eV90WCqV4!KOc6TfKM))3##%>8ye!GN7NK?XI+#$m3B#+q`(t z4#c`K)b{GNxvO}59p9qxvR8(>6v+xnx1Xffv;TLsT|ZHz_ayc^Yr)=VKp-4`EkqY; zZ?%Uw5&zO0+oxkB*Jm7>uti}w;sC{ReY4I9fmS5M@Q8IE793Q$q=J*0(!K2`xi9mB zoG`s&Isd>x&krdBrmQMb7GS_q2s#f!_%XvOQw3~F#v>nUrVy@-oItsqq+^?e#cuUX zk&<|se?&1Eov0+Wt;~nMjXdl~^hqrb+|aDw=ytATD~o))o_LWyWaWEWds0ALboWK(x-lt(JO(etjJCMoI)WACl(32uRB`*{&`ojZ70Lt!RXt0!)mr#Y5Ch1ggKl z0s0uk#z%*L(w9W64e1&zU!B3HGiPU75^+Uco4r7<0**UWYXi%0nI&{9{+lF_f^oR( zDbq>LIsC`6=!lCyW*os|*%Mv#kyVAZgOj-vUqsXfIg4I!8SY=0ej6i7WD*8G#|O4> zM>OI4{?RP51!i(0v;q#uoz3Za?sTF`Wnd7?S!V*!1T81lQq^Bf3m6A=HwjTDN?a5# z!FEC@y_g?xB3$i6`)~V~82PG%9lnqVPs-m)q=;8E;?;IX^ZZD;BRi0I1uE<>ult+1 z(BOCIC>7R;@QMF204N`%g>UtxA59>CvugE&NEh}G@hekrf3m!;f_ns}z^4|nrYqHO zG`V?#A40dcasJ5gNJpT#4#hO5E0niXZNY&^dNe7`}j09U#?)em2N7u)Y}mRbsDsGQ*kd)8RlC;ujS75lfX7cSyxH4}{%xW8cx zW24BS(|_MZY#-bOp)BK_5vDE_T;`D?LDGFGFVB4Tj!pGJ(a)$e;lz^iV7p%?Kjc5a zA{b*y9-`YMaftQr_I9M?6EE4dy;j+*wGOHaRqOvwoZgB!wId#=x$sdd!Scvave}L3 zh3RfAEq#WX{C$(?2(2PTn2jW{q@T#nDUh&-VJNK{1#RGbxkzanS5Nu?xyO~ZWTDRc zk_(^P`#?OpvQyelZZ3;`NdKjO`tnYS?vnH#=H4+)Hl%_6sZy;!R)j-%4r}Y=7nOCo zOYNxG(*%=XO)tDPu|`ksov4>$sND;k%X!38LHd&nF#TkbWFYGN6-dG_`^%F`nI6QG zzU7alG+YqL?ZmcTb=E;|PBUgn-1p7-YaC-|mT&)gE$!9HSlM~$v*tEAN-qK#R(F0X*dS)qozN{;y4igh5hw#F76eJG3Mb$*Q z$>+HQ+U2k<?Yg0$(9*gP|kubGjMUE|}gQ*k9|0 zXmQ|OoF3hYdN)*lyPlz^lJb!7ynRY;T;Cknq!!vMu_J6HcQoJ?y^LU9}b*avt zgSGyb>{5S2mxG$wrjAYLwwvGQJ)AhXJXWuSeT^P?dgF7jC*<4yO!)P?YG9Y&QyXy# z@Zlg2o=m94=06!DGZl-iwO>s<{vqqO0(EA;EfRfip0s>(Jd6XtXP*kYz(N~S)ttXO zSNB+Q@TtwK5<73pM%beW`Bl<)JDatc^*Uuip{#^~gcY>kxZONIGt;xx{a>Izi< zj&VH}MpD_DA|=X&308^_dm9*N_D{P-qC}#yb0{^XlJcr{>TJj$&&bZ<+1{i)!sQzE zEq>0fHLy%+VWMr|e`13$+8-5HWQ~MIjPEPNKL=$03z&`x#LIBGLCSL5FddVgaFlc?Rvb$Y$4u-XABd<*J{Owpq{ z2AF%ipoP-OV`tb#q5{<;97!cXbbjC{(PYB|OK34q#kreV;siyOe+a>rs*kNN1g+Qc zDg_XGDbB@7H2=DiCFTGh8wt$5JReJMMe78mrwFr3z1Mocct{G|3?4}6)xmHlX%`9> zJaJ&Ed=x;+ptVc~~ZzGV8`AG!0 zaAeeBeZ-ts+BRbbl@WT}=w9JRTU{>MAFhJQu5GJ+ zKXu5MWl#0aJ`LaIfSdeU0T2G4CNQaU`fbgvUG{;voTck!EO^@Y(5?RFP6VDp7M}&D z7fd~%`fOyP#>Lig#YgJa_gWh6Wf;o4irbb^l}oPjJnpT zd2j}lJwak0{sB!+{1Ibx8R*^P1H}`d2BVSubcarYX@wX707Gq9Kf-?6E4O9$ubg^z zX}?M=nX)r^tp${K&Uzx^f{V64wH(hltp|VrH{fVlBSBq!iC(b8?GU}i75r{daLK)+ z=t-;;awy+L>5~L6tB_0_yC%KGoy_1v4?8KLDS6xD=vtdOBl3MM2fXeI^0^s8Gi7BC zH?l{fs0FEv_yV&Mo9|M{_#$zfzPSt1>NB2NX2};wub|U0nNm|OBMU_5YBD-V0j&YB z#VlZS4LaPJ6mjxp5FD`cAul`FKx>lfZJjp6|MsS5_Ymcw&X@QM_At;AqE|e@<>8|ABM4YmQ;SH>QgZ7v};Je9~Hi!LMFdOUf0QHKd z+^NiDZ;(c3d%SLets!S~$tBSr6VQqH;}0&a2`ILVi)ZBiizh#kd;>GWmkw__+-*(N zFW=2$19Q0&D9A|23Jyj}uFt zb$DNym~g|50`G)A*)l0ieh53Da#NAaR{+3~@6I=|M_BVF$co$)DTlipYCGHjq+og* zA%%ox?g%4Zs3$O}wV%3%u)>$8#7YhaM48`y?Mq&2MT+AO>&0Y;VL%MV!z7r=)b97% zamc>`JYFr6@dZE0215kMjevhMQ)k zNL8u4tzC&GyvpFz;>kXo_&tT&xD1|GbF4Ej!kRDfX%?vbAxoSy`@s*{lFMKTQ(CvN zZYa%NdO;ODNlQiFojA=UyBvJ{@1|f7O4XS>AN-1Ja@9#YZYMzjN#6y?%(c2S%C(lS z3>>5O!_G}Fp!Pk1j1NT-(0->~QHM1WBpx04i!#3kx@2-zlfQ-!ACvaVd_Dz}efM)}>t5sE_aRs=*`_=pC3(oP5~Rj{R(E%eJQ z>qssoNbRRg2Xy~;8{wTKk!0t3U1s_wP0Gt55lo1ZSx%2?c?mU|g^ZbOVAs)q*w2v9 zVY{0vrigM!TP>{ofTY8ARC8qYfpBOW)4e_<3USZXeL%C!2EPv zJ=G&fVb}zOO_>s=D^HGYUz`m6ufRE})o<1dY9Cr?OtW7X&%QfAPIQlQwKW z``nRaKjmgqW4M6}*FP*N9Q)7tA1$WNBF5`FIu*J%qi^7XX5#?X<&|=Vd&?eSPj^28 z=>v94w~#$O(vL6wvTs+~84#CKB;@FhEqMn<;G)Bq8=*I`8&L}s7tVQO5@5>cE1oNe z51^^cya@Rch13Z_51wHhY0OayE`*-ODCzgujU$1q2hWwA^$aab=8WC{Ccfpd{6jtT zZ6v&Tsb5(>y?F}VnEnym&5E%m?#vg<=q4}LM=`BY$-|=Ok~7Axt!Z_>m_R8=ymMTp zNA5=eSbfK8z~J2(-=BRbsB(CF7?;h+`NL5qUdae2P+BEDB%POo?Gt^hl@d7ZNW{S; z;Y&R1mLL3!))TD_8}BJOWEF-~h)dM5?h5Zkdhnn|Ecp|21F`TQAWSi`9Ky(a?eeZ* zPXsxu>K~Kk?foV%@-moGrbne2xt~eERzrmp$X~|^X_n?QZ9wE!6RO_0l6%}US3jAc zL^bY!oFEwGTN+wQHktkVfG@J+;k9 zG^StQC9<;#Rhs++>E{wiZa%dDO=xy10@d$^CKB?|TsnFoqNip0DA5i6(!0M_GvUi1 z%nFov{>tQ3s~Wk(cw2O-F($l;{?b%8r3ot5nDEIp0%99JGGk@JLKo)dKdI`$TOoUT zs0p--#$MX;z#y>>0$YUsXJWpbczb$}Eb)(xJ39+Y*UM=kor}4DLiLNvPud4&@V=5{ zmK7^R#(k!5K`mW#vAzoiF&Uls492ABa(df10>dCWe|0Gb`E>&uSz_+8iktQ#Kfe~; ze_rJkH#-u(JUp=@zVdRqvY!CZH>gZx>zZk~zM1;{cxMEa4J5DmI3X2E)^ujk1~7iC`ETrKMXiaSCr)a z;~XE77H@gn+#8L6z9H{c$3=^odw zY;{{eNXM(Y$=K3St|xd((S?4Qodlo?LG{P%dR0hTsa(hQ(|R0=w^R9aZ^#I}a99@& zwG9DSs9O6B-qn?rpL2sSJLkN9rcB4~drT_KYW?zk!W%5q_Zfv;BMVhr7B7ptGl6(f zODMGR>y67TJL$#NnGjovdQCAZ{3&y2jH5aO+>qdPZ-Zjg?*reZT zKV%@Gso6z!D~G9ArJul`KX}y@WQrx#)}?IYUG!YG(9+XplIVGK%Z7lVtI@9y(38u3 zWSjWc`Y+M{=nlE9|Ls;`CW0`bKrOz)n&zRR9bn2rQ6Qs9ut|IIu4}Qt@^zM}0o1JX=J%N3N{N_>AD%;VRn0Dy* zLkxYc266eOLcFT8N0js(@mg~-gxrq}T5$m<7V3pMcJ;>R=vhNAn0LVMK0^49 zvLPP`PMq;8A++!^$#s~gMWK_m&1-=-$PzqpEL1l4D)rE@wOlL!Rp9HH_{fCeeOnZ= z0#RS_bS#E80T#+KaP4!x_3xP$zhAiZ*1MJ!^HJ^kF#Bu%)T+IR=hQm>J#1&!2E#L| z00n{P>kx7g4zN~xFp8<8!8kE^xK76C#<}cT1}`)zn;ixm_duL$D&qx6mHSUv)AAMA z+b%OVXQ(by7ro(i05QBB^0|6SV^JZxddFM#Ijg3@ucPt5{TOtUXSYa_6-hJ2N*9cd zj4;G1jo?5$0_PB$wucd3&kIO}pYgsTrz}!$1cABiv^b4R7UYh3gp+mau6p_J(v0c~ zcyfRpGh>;Ckj>$sLn{kAOjMk2Nb|ll(`EJ)xElm)2$x3YUjBOLGp-pz`r)U}N?Dh= zX!E^02FH-naZfPYKSXNkXlMS)(|%_@D#L8$px3z>+iNvM;sJ#{1rXZ0`5x=s-$q+y@1qPx1 zD1+vESx2{}drpGBB4;q{Q!XO>f8!L3fmU*fPSFDdlDd0W$(3|kX;@SFGUcd3FlwBp zm$4B%_!7>%U*bsD_E?khaGJ$)_%kYDK%$wWe|EWOk)ZAzr+IWd39nh0?V=!)~LM zPU?qw9P#7vjc&!fZ=S34mX@MCPmetJZt+Z^*1yJW)SD|HG~-Xf7Ejmg(JIbt2S;N* zAoV2lv0V!qm+_e^m6}co{5OjD*3v718JXs;qJ>nOjMrmUqK=MV3VK)(czMiRR!C7f z9-IytiC~ju5X)3{Gh(|_(v!)3(0`gUvY02SH(%8clfqvv@|w)hx-UVag-q6S<3fT@kMkO)ip`?cgBSvWeAz;nE*OxT{#q$w;8&C1m zqM}K1Q~-eYYogY^+n8k57(L$9$noZ3iFwGDbZBezmmC5BA( z0qWy|d>DKmj>}gsm{RSaBg#Gi*6EII!lj-$0cq&e9XQJ}q$ z-usgO__-!D9+Zhn(d}^{4MaI-+b^+HMXp|t?Ce!c_7!MC5PolUHnunr#U9Pvo7j9P zB_t>7gGQW3nHXK^>Go=;f-2-J!~#8BWYSv21WSaxH%1d$iLbEpPoSn;n)@XFU`a>B zH^PXZlN}dD;4yIngvy^9CK^#-+q@)7BBP`BJVYX8z~Toi6=7D@KeV&hi%A6rX?^E$ zd>FE13qQ=dPfMC6SFT?gc9#saVr(2twN_3&^4Cxh{#*}cL$?LdM1&9GjT&#>4$H-B zQltS1bA3l+%p|0+aoT3=1WkJ53+X0pe#EU^D_| z!ipH-ve0xE$&N)fi=BgEvJx`;JUZ23WAS6vluexy`)b_9&IBYBFhcpGcy>VgO%E+PMKM z6XAi-%nTDqjP*+)6x{AY^fUW4QYJzFe6C%_hwoRoZUZl{G7zghPjceZ_z#iuHNI zAd{U~D?u5^AI{!9MYcE;^OO8FN5Py2`WpFcvq#^$ou9)J<*ctt+_*O z>L0dUHQwQ&f~ChFh(ftl|C*tK(6G5x#|M2#yM3Viqf0pz2?Wtt@X?blTuj6^S43x4Kkxx;D|L8_2WF`v~p@=7x0!bry&b*G#9^A_n`(Z zUQ)oP;;O0wtaEV(gfIP)s6x{4pC1ob&3hgBoAK<}=+U;+Z5| za-(|lpH;y`;7_~4c|Dy1?B7saRs(Sv&Q4}iVh2G7aB3-fm)bV+>3=r*-w92Kgr6dB zuxa8}NblY6f+hcN?G%hQ$UOzEMTM`;q)YJo#Vg{nOy&JgpTbn|-A8J6FMe}Wcc{oJ z8MXTCRn*v&nQR=Nmko&*BWIfoyxvM4JHp-jVP_vOvgOAE7@v5w-*vsfGaFeJ)98KQ zgIJN{T2gQws};@05m8|T0FJQf& z4@4%uw}cO{l5M#>cUDusH(x(d_o4uE%C7zH^SZ@seh5GeHiA zcX)QrDcXl-ef;G2OORJp-TZ>^mn45H)Laa8$W1R$B;%!=qWn;WHNrbW)>i2lQQ~ca{1>o;FLIUH40ob+@O>qZy2yNmj4sSnS3CPd5ZBj zq<6$Cg(?)u+(k9)fH7Fip6Si?%`LFU8ZOfow5jJW*0TI<8|~c0%NFy;EGAf7auE3K z1ytX3Rt}$+?Qk!TEnU_2mPxdztV=vE;wjEBDR#&}3c@jA2BjbhQRJt^26-zKD-cEk zXJCPVPZ03mD6_;81ElRS`UlN-U$f@Ma*a!vUZ&cJ^%vj%wAgUWhh-_5{$}k~^ zvhbEV-Idl>j{6XV1lRQ%7J-OUBdUUvDqHc^y0?2xMUlX zg~hH9wMsAwd4Whtcq}HM@@R3LOQUq zz}5?_E8yk!EWw^MFAbS1+l(!ksw(v+y+Jh1hiiePY8{j4+&VeX)hZJasrm1HhV#2@ z8}_m$auV6>%X|W~#^22lPN(O|l2RomQx|Xh!GP{a=VIKT4^AZgNm}uz21*~sScmy7 z`Tj3(duz3^ZGKb*#?p3mrzr&a)ImAHfTG;(AF%y!CF5Pjq)%EszdJ!JjJrUy=;dGr zjK#g_kfeAG;e_c;Q3(-pnY-_0$EM9O3u zb?n9UBUK?)1xga?{*p(vC&MaT_R)W-Ra!qEp^U6QOqUUQkez|Vrhoq0zH1Ln}_UDsTwm{ z^xBpG02+H!cvShFHdv%san`TJ@;F!({E-i<^x#Cc~v z92-xF>93zjxj;#2%tX4KXtPh$g(POHrF=b(KDgAMN>y0wos^RvC>zuWTf)6TxfXl% z2e-{c_zm6g*{>Ds83*S-gl_E{2puw%Q64Ar?QD%=v!;EYM^b|PZWoS|f9tdttn|uzE)mM@pw3cR?U`Q@#eu;k zrDve~$(1G<1kj?W9A}luuKWT3N@wQ4sC@(9E7H_8g?@?5b??%ozJ9eVqtAEuTM@XY z2VH*vZj0w%Qpr$ucqwtR&a*kjmOiLLTCg_wk75kE2EQG*q^D+Zi#zKo2!E-OqTru| zWnapJERmjiq^m$~vVav-hS#IZw({3sqp^n=H`$ME zr_A^br)+g4Tfu0p8aCL2tgPf63~b}tsmJk~Sl3ZFZnTUD!(V13UJi)`(Nt*l5{{z$ z#)?bojix+b|7ty(3e@CD*LAHk3IrFx|hyRV;*qJbGNzra!jxRZtyJ(`eWpNlz6#6zoZ0H`CNif%LL-4CKeJI z0;vyV9~21Mki4K<$56ot&OYeF0JwdVPjYGr&x+T{NVYdur>C6ioJ!mdbc7o+v=*z~ zD&Ps_h~kW=aiau%B9%*}TX-4EaJbQbhXP8+A}&;!;dEP2rqZ@VT*!7>fP-X#<>RUo!W-OYW8cC(y7<&ZC;;R`Kpf`oh}}ZbUK%{gSL*qTEo9gn-QoB< z6n1*0nghd(9Hfqc6IS;le)pQ$n>%2~Guser%latQAd3`WZF2{roraO1T{8HmN?AbT-g z#-`jctCDs35@OMZh`}KnV)e{fhI>nD5-Pq(tP0plAsHBLBN6AT&XGvz89_F;8TK%A zBOg*7+Tg~jUQ8?wN^ElCOnZVY`WnL2tF?Hu_#Z;f$y2WJ;`k7jq>K82<#%lmfGl_* z{N@#ThfZ+-)B1AjXctvBg8gT!?<+g#d?FYf4w(z~&t;I+UdsHjuwV^Kdgj`X+_-wn z&;6@iHA1t$ed1#@$w^?D!;DE$;3zJBejRfcc*jLCb1-c1xq{gVQI%k+ApGQGH90p5 zCr4lQ)_yR(*ma`0tJ8bo-CPj$9wrbK!H@tH#;6sUAzd@Uid3&&ZrS%z-M5_Pt(10N zyZtU%L7~@4kg-xlS8a=Nf#EHKpFAFd)?LAT6vio-?eTg<^EuxVshNqU6r4WoW^y6O z>6?~&-7Y}8z9^2yzCGS{NP$hYKGbkaTg^~>TtmE zI6t2N8TH_oJJIGrup&dbQYvA}_)jv+wG7BP;JbCQY^pl0t=!Q~pVeIE^N)?zz>V)- zOD}*#0qDV#09Y^Yw}Zo9)E%x4I=)5pPUlt}CWJlN+1DOef+0hlPG07dqFCJPX|Tzm zFW6F!PFQofwNmCbX+G1n^JWY^wqe(1Zy`@1$Dg37o$L|$#NFn^D$$7Mls@6$NSZd1 zKr&SgRQMK46S!j#^RTWWV-oR^!cK6j!Qq`Jun2BfGVtMt_N=hA0NUPDj)`WDOljz}VH+O5PPc^^(4q z)6Z|=r?KX?LF_3T?KN%5v))rTt>s=4>$2>MD>-?LQ#$FDN$cb~nff-?mWh1I6!Sj=hLkrq#_~5`|>#_{KdhTn|A{>I6w_z7J%o+B~;x7G&pVPA6=x3--mqoiU2| zeYU4JQ_UZfZM6yh5(7eS>E(qBLFc{H;1fM;zS4Fr|DA7+u!AITdj;NaKM5WFMgu zJ4W13|F%i#{d2t#F>lL5%vdE?tbhN2@oDUYCGM{Q0#^2XpADYMpMoS$t(SDw6%cngR)gq*1K{Ver?puZIc@wbP>|M;LDIlzZeh)J3ee!(_9wMUdNRUhSQB1(wiZs-d^`udc? z$@0(@b?o~i`~d53_;0v%GBs*)AWyur2%tvS6?hp$;y!>hI;dUuds>p|^tF#BR~aNL zV5D%Y8(1j>1EJ}%X;^b$s7>zyIWu}ljVhxQOFK0IVeJj8%9UuV30u2lr zlWua9ffQfYx&0-~`%JY2)E2Sp>&kK8YO)}`I$0I?hV)2cSHGkceiy1d8>j%$ANjeI zEnOH3J?p+;0ru!$RLYjx-g0PY(T6aG!-tjE0r**m=5)HyDBjpPW((-7UkO?t@n5RL zKm0c=jF{1}tIB)S3g=hadO*y3I0W zh7i;gQ>!ay8XPv0IjYKs`q?i3KO79$YD3Up8~DTR@-}_`WD61t?%y`>>ls6{>d1i~ zY_c?@5!jx(DG5~eo#>oL+Y6+|$SIOY=N*Cfk+_8WERz*qKRRU+DxB`DO$JR%Ix~jz zFGm|5p(IJqIW(ayxE;D4qg{*le!#N>cDe*H0*VF=d_Wa#C4OUyFr4f$7_#SwW-U=} zXqQe3dOwn1vDu@Oi2%$6DhKF9eMHmJh@1!BpgH&VE%CZPrmxe1sP(x&d@lJP+jR}AnA$qWMzZsXSqE*J$7~5i`{uK?3@-3u7-1uQQzHNy^B?7WAQW zg3s6x_l(Blyb&6jG(e8PhE$N6k710gP$q)fJ;5-AX% z4=i9Yx#6gCoflyV*!<}AAnQ!i!FFMJn}j(k*?F0pRq%!s^a}!=u4^ z?oLCM#Ozbv2wizV?+5Jy688h;LJK|wJDxiszrN$G#iwIoHm!*0mmWeWIi%bQjM=E9 z_rf1e%wt|rGfnceU?_fmB5@_v4YL^43p&s(^UkCTydsI3<7U;=RU;u(&|)Q!@+Tao zaD^zSLU#+DQY#hpPUm9NxLXHwr=XODC#k=*o9U@97eac#F30$a@j>VkNNBAYaZ`~h zZuW7KoUlQJ%e%ZNo)jwM4z}(HnawMw%Znf#TKScG9?eLqYvIW;c7&f%$RmHABjw(x zn$)#Id-+j^3a?Z}uO|VC(&NHzSkeapR4)CWPnU#(k;v-}iERVmDU^i{)|wFNw&dE5 zE#fsPRwWGCfrcCg?dE^WTmrnd)1^bRJa_Y}MvFhXb-k_ZT*e#Fb734Z#1rG1qZG?=}EhK&8J~ zOhlMdI)%B`27mmyN&J6hBn{6RJm|NvKK4k0BF4k;*LDwUECY&-w|hyT9{R{;5q*HK z1i-GMi~G2P>Dx34v4GQc%J1@*E$0EjlH4Z{f{6@93hEW%satP+F3Qx8Z&Jgp^NqXX z&#%=>s3<#Xgx?*D*PqGdEDV*lt=^w0ocGgAR?9gv^t}wlK71wja!(4>B zCK%i=CJQrOju^23n8(1_LHwIFSnsojy0_z)3`E5EsP{tzJE(>O*vDyXj}Ikb@RAWo zF5T!F{-x>=uKH_qtN+P$BtT)(Y}J){P1(kJ`lQm2sH-wES>wgojODgX=T;LcFf+mm zzUgp&p_z@#ebxi;1Wa8hA)^B6apdXWzlVYabh$ecluuEoJ|_>(L!3+i(?Mv>4O^b6 zMEs!zb-Tu5o|dFMQSiO~NaBW3d<83V&JbOlVi0Ht0t6wE81FlojM%2G9dG%}U*d_0 z;8_ESYl;eC+wWexMLqjO6q&?(?BHp&^oa7gU23B^!=fM(x-&?}H& z$n$sNuqVKpX0@;tab%l8k6^m2i%DnkkEw9srdVT<%RzKoK#i!A*L1A>wy`N#z&Jovkk0=m$o@rL4*cu_$S=w8WlJ=g> z$>hlTG&mp$f9b(bvL_t-)*0Wn^D!BEVw+t)pOv`8(^sgU52*+9<`c)wI6!h9x3B4y zjpm&j8gpo|>!)ALo-AAdtmZ6K0GTmJXmcg&64D~b1ZEsK_)#tbC2yd5KOMT}gAgZy zMk32NCKH!gv8KI9DUoISc$4e?=i^W8p}0J>p)NnZOrh+TE;9an5jTPJgD$XW;7j0-4qYpvl8ie3?}>$tU=(suR4%ZTWAy&@LzQ0tE*Yjjz3f>_ z@3OmB?oeW=$&NTN%_!4_SIF8vC z{dbPPtBm>yZPe)?Q@al-mOX-zfQ0I*9-J*bOxy2&=h&pwlDg)rLPPXE5)u!^8S5Ei z`(7ORE^W)y)p;3o zDhfHNUigKM;H!V+EM>MTnQ@pzy+XgRA45H7x@2fX%!bSR zRMg1y9n9HYflMUYz%JvO&;Qdt zarV^|;l=$*rvlo&+x<5U|EKC`5GB%~kDZx~@2X^^WQB)5#gc|G!14`es$!xeWlQ2u z&FHR1*>Qp0LNN*&4#kk!SEmXun(v9Ktq}27P*GmVK{;UP^A=&7+M#VVO-~w88vgHM9;$IQli** zNT?j(kQ5wZ=nQ?}I9~?a5k7@I1oWLD&od7iE9U;kSpNS1=OLW&BuSE}(Xp99gf?t9 zq@QzGgb=OiZS*E&qRtE~N;!v^m_vo-+cj4=`W6ItMJ%ucvOSL#_c+sgOz$QX-k>nWq9>YATut^s;cy z$B|R5rP)d^#vP6Eg$NBRT;yx#P12Y#oL{F?KNB0{FblZS@yoTWG2!~sNx$5*&-Y-k z^xFO22oPJS)wB1)nH#<^XFXYp-5wAKFghwY=210BYOxswO8#bDPYt7Y$3$pB8Gcf` zwXviuOgE}0uJGnWH8fB`R%);^0VnLU;vXOs#b|LJ;M9lQIFauGwr`~8$LnPjdo=ZP zhbSuC2+PU8e}GHWuk3W)Lah!*Sbuth@W$37S3f@<>iaiZckUavw`URRdwJQ}?fioE zVkn*vGv$uukPZEe*&8(TyuM42=Q|hXL3JplLv36L$0M|uWgleY{}IeJfwPwsq}lKk zebSi$bAINH(?ps$1%fXpP3U?zsGf%R=C&KQmtp~i*AJ{%%Cd)#B58j$;x@ipMpi@PG9hlukt+gptQAtOU!(|?_m>>?zWgXuSm6tVq-2f`^KXq0hLt6dyGsz-Ks zn`$$1j1;P7&Q;%AEX@V&Ti2aKLeKgC8mopj)}c4n3^f1uKpz+Ul#daMX;N+Yr!?R zpX1@~%$|dvb_cV7RX0SZXYZ$nJ!FzPYy6|nXJ5BzMyQ|nwPBR6ixr4DRjBHxv<@Id zT+tx{3x#p;fJXCq9993G)hqH8Y@x)T?ouPlWiU$BunGk+C7~?MDVvf@)Aw#p2nwJf z3-oU%ijvh;4_)x%I*4Yi{Q{@KXXjjOg(w7h-DF$g`k&ss{7*0PK*uY?yneM^}Jd#l^pgsv%8>bM_7yA(4{ zFhZPNml4hHu8D0bw6rAWqWbn7%KFO=iXDI<#%juQN*JYG6@iqj{0g8-CgKTYDOEpA z*KD})mmrG1)ZOFAlwR!9Y^P+?;HLQj{h$u+%5I`@!NOsrD|cqmO{)&+!+{Gg-!^MC ztF)2Ra3Cp)^%b_59}phrhM&x-0XF#q?D(ZuY4RD{)sv)Jgo&56UaMl`J(XulQfEW< zv!%sa{tH`J)3J*f1_gf9P}({H&ymCAamDrNy;2{$!tkIYA0&9lw^3>xrzvH~dJ#fa zIvTdL1JA;>go((62|1e4KKB5*UA5TGuXRe1p30VNlIso~B6>0%W61;HD*E9Kp{p7D ztIpLPaKiT6TiqU(NTaVL))w%B4Sb;a+wI<3*Et31^-vLeda&vA-C!he9>XEpBtph_ z*wc_ml?Lt3?zCtfQqNyGd6G5Dy@-#^rCnO)pr3odAap(dk-(cN!2L0Aa~h)7q#SD? zZye+Lt!vRDQq`aKr+2fuuEAZn>bZ+=uoV42f+1bBH2l1_tp#J$qi6NaVUg>b|5)XNPuT?82O!oX_204pDP;nkeWB-?!$>1{B;} zd;ec7BNtty70UWLT}3Vu^0w)nX(tOnl$v81Zm`I9cA|)-^5Dqfp&t^~AI=J9<846=_e$OX&4d#v|KLN2sE>TLncQxv*vb6|h@H;uL z?^}+|4C-f7{QAWJVI#LVdJ@6Vr>?0t9}C7}C>;2SkzPsRqLvu+Hhul^k@aI0Klmr_ zm;ub(F>f6)CIRcsX(K_KO>wuXC45itGekHkRl>gl zRaSIU^ar;^c1V0VUX$q-xYdL$7z*y`3y7b`e_L_ywZ}o+yZMLwa`-BG!9y)>I?g)j zVv(+rh^H z5@)g7gEv^3#}D0YT%o}V*RW||Ame>I+mx4*V-|GK5aL+xhw(r9pm2Be-c{;iQG6hE z_KcVf2qkx6%~Zz80zkIucG8u2PvAVbOwh0L>PTZ$6&t{(GO!H;22;)#(lO(829Gm> zg17eiD384=h?4*M9K6O%A~aacr~g)1qfNK^p~uG}-14-$LR+PDjYaMn!zlzG%MJQ| zvSajd>u|(Owmr!!_WLZ9gS4azdZsUv=o5HvaOcQx=D!0EKaS^~&TQIm(v@Wk0025v zih_Zu`%ca1m3hBm?phy;tN+M6mNoel6sxFWG%^la@>+}Ds|1Mt-a}QZRvbm#<@`L( zF_s??QM&uLNozb)IDrYl6!9H)e`vB9eDpPW%hwjxRi~+9q32!1kR2t-ZosdCK!Ibf zl5cH<`m&#nUP*KkSpNK|n7zv|FSW~yPRBHiUL<%?Y~k9p(*&Gd4K~N@y)ujZzxGaJ zcj2>Q5E>|h;39T-_cjd(ETPwMjkA=0x%;j~=g|Onzb^F==z-@zg%-ankF@)gZl`v6 ztNAk!lXDUci@2+gp+ss+?um+>ySS#aLMBR>TPEvqf^5Hc4XJ zZhuOtVs0n`XOf(>kwQi?DpHSj-aiH-xMTvG%8 zl6XtSlwN%CL&Jn-gq=Os(|fc!)(86~OK7)9$+yupYMj8|GlU}XIdI)_>!I}Aoh1Y` zg;wXc6cBadpe<{oel44c8abTmJNm+J9+eH2B|S-9rY&`Uj0m_JtMt0009300RI%27nwd zEcC}fR+)e}cKH4^#T6>1{!N^+$EH|$iy;9z5z}Q%z}Q4ajQkBf$O1fViQq#Nzu_dU zr)oTxh5&im{cSVK9{_jnN%^y?otQ=NnQ8E13^b0yoz4`y&~6rTmcbqeQcN6|=y5(mzRs;uOIJ2t%Tza zZkU+(AJ^@6xiid<7$5A;Qsu*7@9=Sh#L6sDXj4YIc(HjE$($>e4q4nd?JR&qo{gf^ zmv%OAMgn`ubvLO8A-7G=>HcpNJOjb%vv)issK)tTTmx;o&qg1XoAz?w6+pfBIZfPa zlswcB$d=&UNQ~>yz~OYA6SNan@8HVn{fi~(fEL*=0OB_T*pnnFIWeF9f2gM+8sa|lgBcKM5Jbk&930NJ{;$OfzgP3 z#7<1;U3_foSpFxzDRav9X=OV!8o0>evT#76zPGg$T=L>~xr%)RCFKPrb(3>5Vb}fA z?q1c-5g3Jf=5}>P{b?VTL!=n@x>Of!7qMw4NwR!JX8oYLV6lyUt=cypeDNn@sdZQ6 zedDll%fw7{Ity0!^Af$MSDvyNETcWINm7!ZFX$6>oljI@vPY;Gkbe|)EHgycYcV)o z$G>JGgPk+D=laI=~5fJGptSsJN{$G-rh#Y<0#UV#Si;oRW)S;k$$rjzo zzOU3uGe(zTuY}DdJCL6NG3-E6{8cO$JhY!2!uQ~7E7cR{=u)QopTz@}MHW%hQ_$D# zeWW-(aXKyThP55OUsge@Pc>M{{9-b?UE(C@YjFNwKC;T{u=^kEO>*s?vq8t^{*Ql_ zcmjIE0Uv4HL_=SGm#iOFOIW4DV^Q#>K;lD`W4}A#1D_ zP{00=P_6@xUKYQh7n!~VOQA~7Z-OXu$~`w2DCkQ#H-kx}`w3fF%Sf83zQzaZwOGGmiZ7O3Q zlVCKKa!*`3K&?KV217d2>e4~-F-^o2c_$+Vyr8@QuF;%T` zFvICA{SEPVoBw7;;&|OL)E9ZnMhIDRq+-`!BO6ZI@5JIiGJ!S6Fsf@L{_HI^^^%#( z%v6(y&4YBwG??q0Q$hLb)USR9pahZoxEF$7moYbd``5-;hv_ADcF0e&na?v=m*;#8 ztWX^xIOs9Z9#SrD3S-14FNnIMh3J`_9~kZum%V|{$hH`WLx|jU{|O)6D7Mu1KjZ+_oZ)Ou3>Hq&>Y`QAwL1KiGI=_ ztvej`L0}aha_fg6tiC-SN)^j?EIm4*!)oI&AX72vC_)`Eb@0psH_tC}CI{$Bx*OkQ zgYqcQQ{EY)>-^jF3OW1fnH6;cY#~{umT;dg@uP6Ee>vUeK5A-}R7!6gc5}bG|SdJ04>Z-A12R zLJJ)4lhB9HGxC8x|D4p!<3oF4YG=_ov#4mTPmkteFCMuafcTwi^(P(hiqQci*1GT2w0s$j7c+|O0e07zZNYDnKr0PCi2I(dC zR?@wEZc1PTR;qsstdT}UYH(XIiS9uGqmpSMf(KaIJW+MRG8i z8%&|*!;;s3F#rGq00093H9E04h0!|a`%QTlEw;QQ8_0?aYwIkR*AP&&q7ds)E6@%J zu=jK{!xoN~VGbtNFe-sNIp#FF5PFy+ zQl!iquyQ4+3MVC0Z#iU)zwkg~smFXURyRmgZH^$b-u-c+Sf|5%&IN^-%($&b+%7fd`$yLt05 z-(@phs+O`i%I$h}^z6WkC6NtF8B=F>jA#wZ6lV7iDb_L|9BzjTRR|VeJk{-Dxl`5 zf7+p%KPR2i3KsN(8JPHCT?X?fZ$d0jY|9m#F&r(Q0ub?;0JGlesaaq`NY*urS~(yt zRRms;*ssCWiNeqZn*kI!w8Y)$N-q1HhMKPoCCy-8suEtq)=6cV)41YO-HnRoZ~v*@ zp44p&ob(tNK37Zn5dM-Mv0z-v)!0G#D0w5N7Qh)h7Rm-4%|k`ui9GS3fm6ph#{t(` zio)Tv$-Z0k5Dz((5!>s*FkmyM8JSPiJF?1}GA30Lmt_qV-q{6?y;>aRD) z&RYGZkrrfv1)dP-rpO}2*K9KKlYR%o!*|1ZFaYb6o@D%zSm~JCn2>-^WO0l_oL#k- z859tZu3)N7FMhcqSYQ%$bPpRM_65nXTSC;OqWS8~TJ}R_{h=^cg&>$L>MxVoDe~2B zwpc?h6a3~2k3IDDEd7WZ8{21#$YBPO{Gv6)ZZr2uCkxZMsAC+ssAE|WY{Wm<$0i1W#Sw!Z_X2;rwMKGmdYw&?V`9l6j@;gXvAt)Is^+mlgU0)hk*l| zA14zE(>6@R{a5D0l|4B{2PzK*faF2VH<*2h{0L-S1xSF`&nMtYNLb;hf&|G?sv4TT z3af_6s&YIUTqzGabC`&v_94Gxo*8TI7YiuMN#TS9H?Xq;Y|V!%Em06gF0yqqjrCo{ zPJTs!M=Ie|b@9DGKK|Qu8uC3Rrgcr|=EG{8WZ`59=^FtVx%;#hnSl_=KqYQhVt{i7 zd(N(JjLPKb%H7dI#1oK3{aivfBXqSfuz|*^HiVXkOm2PXUcCod3}UI6Hgz7qZf@z? zhMQ}ecCWzpAg@L$MHEqLn{?3-4Gze=ltlPdh?$>%8U?AlTj(iz(6YFkN_OBO(!XEl zuM5bN{G*s3G2bf-H#28`mX^fW9~8@5oF^W zs=WwFO;$>+UWX8Y#0YN-X~)=wI&~d(2PAWPm(gYlsXl$yH5MZD1e*L2RE`$gZ9tfH zRXcaBnVcLk%J|GLgf|dI9GLN#v_Lel96`=ytXUON4n9g;w@YX~6A-OAM0@xixv6(^Z6M6#a_#vK+JG66lSo)Nf*&!4ZTs=3 zvMHHZ119k5(ka@`$A@#RV`raa<)Xoi-VU;ryT_=o>Xf zj7hyp9{i@E6P;Ds$@f7 zA?%WzzD5jD62iMv&4ryunh0&Kv!(FlDoINmXIyJ!aq|*D`Aubw6v1!&M>sf^Po?QMN+MfHTWR+r#YZNUF?#_$)Re;4({~@)Zc- zoSn1pE=6()e`XB8_r7ZP#G^}hGJK+ONS8nNlBPnPJB4uO2_7rbyg4dPy@4J-QKl&7 z=Kgl@8I_)SBw1a|wka908aox%1;X$<_pOxK0zm7Rr#;f%q_V{dN7x4jaQec`h~i6R z^o+b6=nUDlv=;ae5%$`v5J$no8ayp)eRPw7X%dOkX3)100C#^ zB@6f5ICyrtd&au(N_RkJb75H-_(|GN)ShMouRuNyU{NoF+)$-8p2MY0HKboRhuK7t ziw3_QJtT~0U`B}?q%6e|P<1_2Ba!vd>$jJ*1JH(Ru{o32k*?qk z`0RhORH7_VVwq=zQ+;d=Q2}Yr>$KO4N@S@x&mp*SmBE+T5 z6vIr)=Vr?^W4*Fkn_xMMZLAj-SM9hNE(HPG+e1IfvEi2Lpr<63#5 zp{mSbV%3HhK+)pf6U4xR&5ujgt3VlTg_)cg*~H70BB?A2#{p4{q152}V@6{(Jp4#F z@A#`=IG0KulTU8FXIvs6t*f!5t~}!g|W7U;)fB}#z;A!JBaPesTO z(;rk@Oh!vT@hPb^$hw5_QI^+H$hSB=Je5D7?p$Zt|9ivFO%#l6f#;JN2bCM%s9MQCR! zFet%_Z`D%KnL22E0l%v9BIIFb0+xIJFL z*su1RZJs4}dw%pmCRmzxJEcsd5UX?MFr^W0FKp*61?%keA zLbY0$6Tl(^xSVy~iX-p3zYlZ*@2OitK)HjIB#A*lW1AE=J^?FvpdHoPa}bTV?r8{cf#@avf#wuUqDOo zF*%s28*WvtQ(Gy8EHDD~Yxy#{g-XKG;kY8n$PKb-i-Xkxh(6F0w5w$X7q_{MapBv~ zHuK=_<#IGOSbP7g(|;S#b}u+b@}wUIg@p+2rw+K;B|8qDd8$^=QThM`cNnlsf4|KP zi%!uMvGHBAsl^YYF71)3BC^~JsgRty;&z;&ULI;XYC7JEzwhS9RF@@`t5z9ab+BN{bz%t#E8~x;%A<>r0p)I;^>>>TWSH5P{?UzNYJKB|PQQ8R@Zl_)cQrv`Gtb==Wdj*u+?dx+1p3<79_LF3-5Yu)oSy_`&krJ&aM~{~-W)hGfB8m^0&%pvd7BN=S*$u= z_+!01z|r|ICoP%Vv^*?5*94NeaB4O6m9Fo_@P02m_G4P~H9#FuUY*%YJnTD{M|85} z;97+L$j;Y{n*26=@PH|dNsYj&z@-&-iaHw_?M4FgVF|cK*9na9ET5TPGR?BaiSH$G zwFA#`d($4t$_pv4Z^%#gt2!PbfXgn(GF^y{L5i3NG>gU5SstpOanNw9WS7vz(_R}q z#CtsY)isY!V07mF8;V>m)q$z@Pi2F<_15Z5csdk8LohunWXPT38|0~^7k>=JGlS1K zL~>bfPvkKT2ha%z-G*EizLSt1rf%T`%S%7Gzhc~oCGWZ3}xfUP!z5Uo3x z3IcDW51V}lM@jj`m3=E@QhLYelum4urs2~l+sqE*u^;>I8dlBK*l zO>`-esKW>dRn&LJBRAqpkTjHrajo5Ziphr+umxa{29sTNcQU0+3UAc&YsyxzCMzjUsPA`OiEDl%a#V-+GuTHjfaEs{<7`X zi@IURUg)w}S4!fz**2*KnpSM$PxRG@ci3gAEveDrUbP5nE8p(LTcyNfp-muE1Na^J zsK;@$2@0U)Ivb8nbbESOZ7n$^v!0Yg`V$&+Ud%?QDLb|)Z^d1`HOP1O%}UZF=e{mi zdw5V~ic-bg!GqoBgk6B%|3|AWHT-h)w^0Mv-`udKO zh6`fGEkQQM+$>Cqdon{{VzZM}_QO|LXGSEO78Kf5bRTI9VE~^#LGDr2rk`nJuS9e0&K|SIVNeIH6KN zqsG(xYMV?k+20Hn0;C>G(*p!kWlTXqB8x*V(H;vEU4e|UOQp>t{OHD}f92ilewCW0 zPrjyT(gy|yJti4^8z4)z7deHM5Y*X6`HOvf&L1H7d+IeTv?3-~*GH|7u4jr>4V;NS z-gFDi_g04T`KCG4H5QKR3C4x5$a|%g{=aZ;i_Pd++k#Cd4v*4t;AC_hoCfgTYJE_i zpW9)X#&Kpg?b9QeJP>c%4bB6F{LW|BmN1QZxV1U?go5|D(*V~ySUxvCOApa!vMaUnH0+&> z9iH~6Hom;vG{5fYjGeoIFVo#a9^8}#UH;hZ8}C;jsu-GCI>P+6Ft`2c*lRE(`4}F) zjuJ*fFIiUuj3buF+rOw}DW-%`R)6Btx!X7z7qc@7XX)|cm!PH{(rsBlcnfoGi-U}7 z6+%#-W1}epSDDBdlrJW9ExFh}K^yiZ2@q@@p|**|j=}t%!3p#Nci?JQ3ber$!6jrv z`XHTADva~>7BVS143V^nR7X~`1Iv?xaB@9add)UnKHb~@5?I|k@h@{8bweGh ziKOEL#iH+`$UR$uUG%)E$EhoK^Mo@z#4Yv(xr`;$e@ZQIZXrx&xN`zx$+|gi*3x z4Rpys-WL{brBdt^lXHT=%su#n`J`r_6EHO!cZ2s)68ujGb$dN*0q*raWv(N-^~r@m zo4ky@9YCNGT;Nysy}=2L;%=J>?QtCZ|C@1GH!=V( z+9tUx6+p1gIyU!a$9AhiRDRhzonm08tQ=go-+J8R&KBNr)kBc%y~2ykxntHOil7V_ zcGle3lsqAYp$67N(Dp((XErK#+U)UL_nxiWmU`lT1P-E-HzfxpA7=4HWGmuT-Esdc>Zn&805QWsO|c z$A_-oK$hxq(fxWv{XfcMgK$h|WX&>5tF#PmpBrfokw~HMPD^Oe#p)1$My0w@wzv7{ zEwGb+r%&*KA1^YHicDZ z;M2*x)XTRQVuvMdJwd(%NpYl4VLT7IQt+{%qi-=n>s+|!HI@^jRNEQM=EK-9yEjar zR61Vl4y2kP zR)Sb=Jp-`h)$thYmM*P0b~8fz_vO(Ev@ewms4L4d+(*Kp0+Ri-yM``58R4L&=vaSq za)=IC5rKXDqrCm;kC9Qdz>6^}#K)4CF~z8~s)%Iy0km^0U;E}AtfeB-?HfV{+aS-W zdO;QJh?1?|cutndCu5MM_!xIR{VAYRN_gkG>Xk`5{g;>6sq-=DcYCv_fhr#O|)KW1|v7NvQhB ze*;g6!Ra!owHTSjm1(O!TrnXpy8v96mRg&3$+Z%dXrV5SaNd(trR1WAa>9WhU&N^=6f^ z5)UUuJ2bc3xln6)VCqc#^sBD>KBzdPfEKjPCBvLtFpMs>Bi&BxVlCwbM*16`RbG;Y z^OWp(Le3o!EVSu?#dQ0gInN{`3rCanoz)v*4>=qB0?v*_Ye_V%G_Q<|}w}S&)DR zFp9wStY+Ghr}g?vCZ7aMw9@-`hm<}#_Z2Qm^=ejSBVtU?n)XutgKmqpOL=_kiBHJX zP7%@KBPzP3!Z=%5motEJAtUE6d#=PJ)DuvA7dcw*RJxcwq{8iRJdJ#jlew_K{bfB| z{8v)vx!1jWMD()9pLBS3&REmi9{ky;n*EIMt_izTwYV^ZhZry>*Km*94EsqcXUbh$ zl)U)7E^;|!#33Pmbs(E#Z*u%h%Ld{l#mP|x;y?3VozL^k zQ@ZSADygzqXK%~-r4J0`+~BdCBsLJcF5B83e*UFbeb8;&FJw&Bd5B!FSw){qgEY&M zPvD%1){k~=TN;y6oXzM#tc>pY0y9&kQJ6n=)*hloUAQ3_onlRxS5)vPYg2k#h*9UI zd4zR4>7^$xu`3esw)nSaOaPNy4^f!1)B7nRCcH}@JEaXS+#5`#rf0x^8E7BeZc+~m zIdIzsfr1`KAuw~DD^fR3{Sm}sjCmD;ckb$=LS^K6;XuKj@?P!bWXB*lyBdJ={&S%a zadBo^@Y7aIMsgdO3RRKn;|YSC{)0ZUrJsqe#i3!gEo-kwM~7dI-|ro)X*@0K!~}VL z4L@42f$hMNPBjAacLT8SQcD;M!FftB-YHB{Bqzu zTXd{j;k5E&9+AxWQpv)7d)WRTDP>MVwYq%1{qof&p|#v-Rq@>T9b}gj*ufh>h^Iyl zS_;CFCd(lM26YxufmkA;x+YPfHRoSeffO=5A}7+)4^kAQ)8AVZPYI^|)xNbXMJyJU zC;`IBS|9{QPEae|chaFyNSa7Fc!^w7k<08%VvNCquF4;_O#_q0uEd0j27XW(BcG%b z-Drb#6*lt%+(~g#*IsNY&xgRo2>~S@Bbs?j>o^hun5Hqr>t=avJMU(ECdPBs4g*@9 zEo@90{WwElkgG!R&&pZbhPM5+djOl&NNb3h=+*#?8Ri}bOZDo>#d;odS_ux{vq+F{ zuegB0AOExCSxx$HQ6g_1X5a=nAZd%;OoB^j)Y zmq8_A6&2sf*zZQWeH;EnnIMBa+H3jv#yG&7?6c0OpeI3=&H}V8;rDd|0v##8JpTaKJhjylEkaXQfqemQ)?kUb=;J;i5X?50# zoMT(h^b&UNdC~XzU(9c}(UVXv>SYih&hDfCiV0cSSan@POIeYLFQlV~8g?JD4~sg@h)r@e7ZMY$ zROK#U4%k2coFBJHWYI@x1H@M_w4{66UAvTz@#$SqY_qzQFp`}FFVRh0NY<%0wXm-m z&0q>!lq$v%^}S4?+P4xm(bx9;l8xq(k14N;N*(+1LOIL*Q4|}*i_7*gG3-?YMSjLT zAZhfoEp*Y;xHNY!6nauW8a&lLmJPP@=I}xG)D006pJQ3-S<1d=E)`WSkmCBB_d$bd zE58U&$RDknnh>Rq7~a-*mfMGI{Bf1}_-UV2ZS9KrwJieOI2iykzhoJr1SXl4l432= z6L$9tTBq`B|HkCzn->-7qL4Gjje7J8<6*g=XV#z+&A{jwIvHw}(BnrL7ytkR0B9!k zKT60a;!2F9J6$WXRNs$ket!L1LL?z-ug?`vRI*OK9_ zMT6-O^UHTMU*?1scjNR&RE^i_^ML?zQQ?akalWRAsyJn+>Z5FYVmVJ!JLNaD;`iLw zzQ7MKe^4NR+@sS_0iOtdOAoQeFGZC3#lMV!l;Q(NOGxf(uYU{=mNjlAhON^2+6YXq zU%O5^?XOzRBhQinDKVrkMh-?y`<#e(KsUqVCA%Bge8jG!$XMS6s!loa0kx{|Vqh## zq-NK7q6>fOB#IWROBqFy7@Vlr()IqWGB08pU9#LwzHY0F*i%AT91ACMn?Uwz1-i7v zyq)-*Gc3=+M{XjW)EtG=U!Li(vZgX#DmUgsQ?0Gbyo2yT7CfOUxoPz$VNQ|L%$lH9 zU`>^Dl>j%Hi9RAiyHJAHW%B~#?6(j!@<=4rPeogtzMldOVwt3G$;~dvZba6Vn|^t& zKz-JJP}x^P*--3!t`+LeTB}B(h-G)ikN<=(Wt|x@j0KnJ$~12f&u;R&z^uy{liLMD zhva&(Yoby@=yH1i8FbBmbs2fv9++7k2w5uk4#xTsZmkr~sg{y9M^Cr?x+Oz8&S2|u zIj51K9SBCsUy<}QbXAyEzNMJ%GMgaytvs1_F(gxx%1sVp)kS6^?%-D&dJ54Er@8vQ zzY|z-L|wU$KKDX(nDykG!~xAla+3Loh>0OKXcTePk138+@3`^hX1cse|4uG1Iy`#E zlt-RF>_$sz?7FY4#^C?%_I`n8TekR&el1d1a2b}RVlWg!(u{XDH$<*_nzMMQQzq6| znq5{DdnZ;E;M!$3K)6IioZ;w(<-!fxlQi;8lAWd2JrHSHvmTQd`4;-fjq;3)&ths-V|V!_=oc2pQ!r6sp6~2V2ba%X+nna1hllO?0W4dCt!-2=Ws+ zbf4~66m}%5MH?dMHgwW^CyWdTJ4XC&hZg9R3BNY?`1POzrM{k&DF6RM70yNC2QvOh&c;6h=i0vS5u-G&9%kVT8+!QG0gLo zW1^{tnu_aia&4N{Xk`>Aa5fnore+ffy!@j*PzR(;3k;5qTQ|3n_yAWxsJ~dt0^b{e6~& zKy0@@Gt(D(B>G!}W8@xkgAGSOpIQ-8xw-U=Dyy95fUOZheQ#*30iU8V#H#vy$b?Sj zwg7VdO+w0xbP+~s^> z52z4Yg+#pfqx`Cjv5lz~0a!Z_b|)tbRunlqv1Vgib!M3&(;WM>S{*JbsXkBCj_m=q ztn+rz$^>;c2mM9Qj}i&WdCUK@@XZEcfg`ji07gzn2tK10Dfm!mgmnSz}c#zS}U2eJq@*6tVi4yzCYTaA)M*N99UKfc;V%U=G z?Z<5iQTmDElTOkIR{iGn#847|mO45enP z2CfEgUyZaAZ4y!oCxW+0b8bPXJvX9UGwc=GvoGqmyQ39?B_+BwhhlpFz$^pK{Z417 zS@1`2tn8pAmhv{mUWLaq@Xer|raeN0uZ$*`4f6j@;%g<+g1Ix13A)(Vg#%JKhe?ZG z>|~m|uthl9b)==Oe&@ znB|Omm)b%cW>|a0wd9GdxztEqs+WQ9%ugTD!PNj!)KmZo&8r$*OsF1DR%Q0nVt-AA zC;$LmeB;gG%%O#225mnz&uNF|7QqG}eg*vyD2Mai+hBf}?5IKusw`hUDs*W_ki6vT zwjCc_n?zRzfT7X$5`=L#Y%XA^-=FTsiBXpi_WvSF|V%Y z6})Opdj7AmlaAW3$DGpR1$TZu)tsI!Y1gmk)iD5 z-YrM5pEkvtNzRS}0UlkA(duEbMRs?B2LImQ{gN;|h}C}Ze)NZBpr8uZ^x*_UN9^!@ zFgr;iR9rJ2ntSndwv178?U+p1v!dP-C*GqYm2vcwb+14X*`fFQzuCU_)(B=8b#po zvuo;xEubhxq%i1{lJ9K{h^BXDSs9%5{b3>YMpoArLM(#kOieie6SU8Mi%fX(t`jC0 zz%9hx6=}mbuavI`D5~Lc>ZQ$Mn*5_uH5(p_yWCbxJieOi8ea|qXHq9v#xm#NO54?= zdEeG|Z9=Nqt*NLfeN)@J#+4#WK*CYdnfW4;+SlomPM&}>>!5|Na;dL-6!i_xt;bW+ zY@1c=Z)W_W`ktJ%VNQTwXdkKL(%3NiTB>;gFA)KfC-iQ^tC@t2Xf3`Z)GjeP-1y5H zv7|mBp?A3{hV(qrgCG56#W{8aj#hhLq~qP5vskDARBM zv76t4L)F(4@&(VfF%a0~%3R=2HbHHrQm7kWzxS}8y*{TLXJXp}ya`pmxUkcND14XV zUDN`K-Q^MOkD?In0V!mvgP`dGLASOI{cjexL~C}No+SGE`jd5E#4hyyYv(bW&lV;i zRH>*-VLTJPR9J;CF-a8<^P2F~^s`bfJS15%&!19$cBax2%nr!ctG`k6nFG8K2$Ims4hD8bUX&q2QTsvsTQPE!cM3cu9=U&D#v0`6?3+$Mgr&DDR#`6^ zgi0=5z`;VoP_x>sM6U08^bQ6L=s8@y0~jYvXmce!=FBVptkoS043SpoIu=~O?5m~TTP%+jFo8mg}&k@*_5O^8vj z(^df&G)}=j9F?>1I+18cW*f&zdnF+f-V6M%^^a$2alAzsA zF`~9cMxC*uQ^i zyMM4Uz!mWqq(uA>R%lYEN>0~BgmKmxCK#1nxn=~3SVp6pP_xg38glm0pEROP{%y(C zips%wS1VM01+7+NNfbKVb4|@PlzT^?KNDdaYL3X(pLFry>QXCd_s@44$`WLRC{h)^ zn5DkDXR8b)L$LPS{$ZtwoM_Fv#Y(#U^l3VuBF$Q`r_GMtyaJn6w?4-m|OJ5d?4b(@FvqhzQ?e!jpf0NOA`T zd4(+-!!fuKn}u$SV!g&?bs;}9LWE${8C(@C@v4{A47Xa}SkJ2rHw}r(JHSGd*$U4z zRlULJdQ#F%Qp8-JONr%T&GNwE_d3M8wpfI5Q{`>3SjTG@1I5^|AW$Yk9*=6-5000934>QR$2CO@rB4IDCcr@J?-I6lY zZweVKyrc*#V{@a6>RpvXJgv6mI>?+-k$t8~Bp|u@lV)izZATIrZHDw0y3+6xkkD;Y z56qvhux9&a3mP3T+RpLhU5{GSHs&qNBC2oIiYizW&zQqgOD|#o&Ld5sqrE3N55qP# z5$RUQcSYqui3d9Qo8dF;Pv;Y5f!`sY$n={POx$!g!P=yEsU=kQr(v!!L)a;%0Huk1 z@o%pKn#&pT1-Wlk@Gx}xm42vtX-+XR84VCU(683>b(aX@B?mKCmz562g3pKa_n#Yv znUf$n>r22VDc+q!MEG; zrU(AdkBTL?K@L9C_)95Ti_~aGaQ_#72*6=6Fg$MMt$ef(X$XRgyHN#I2Dum&zIUN^ z;kH7*rx#=(W+36KY!hI6JNgI>vu=b>zKfXIm=E zkF$NOb~o66mt=ZQ<&TSH@yJ~l#2VsSVC{k&0r#by=AEr!ODO0QQH4)ESw|$nPMEDE zwO2uV6O*gu=}&;SOjr=sqUjLLE*>wBp(Hq{VjAk;!Tnt(Qo;kyi2L5yfuzfMhdH8x zzNa!Q-C-p_<8TK=cyj%RO*!ixrCCAT|6_C2s)2FT_ohE5h{;*)7O*K9)E>UyK1y9S zo*k-7oO3F@drs5y7UhW-Q=;T5%}Ge;sSk5x#5AJrkgRpYMCCRh+9UJ~NlJdR!bP}g z|EOK!7YQ*03S9m8Wu5#%bN)UfIXtPWvggh*wbgFJ%KKHlfO-D@YtQ#fdc9E7^9-IZ zXWEX{01vPL3G_9gPN}2;8IEIa@k|JXxdE=lO>I5m@*(U!Gm@?qYSeQ@)=ZzjP`B(B zTxA>xSqotXEB$XL>ZLle8*zGo8St#}JK zt0l7Bc$dmr^6+g{&96U0Gi!k}*TtoFWLrs7!Am?m{FT$F0XK?b)mlu!zYV$Da3Iwu zak!|G#=S0Rb^9%HLUQ7X7wr{o;bcbBk1a3uukc8ok1Ovf&K{O}D<%C;;265>j|P+~;#{ZsMUdY5!%m>S^>JC>TRC4-WNp?i!R zH$s)3It60e9);J&qg|~ah|K8XK=QO$5?zIF#;1+j)x4zI61k~V0u5pQm;J+dh46bi zl-K9${~+Ug?I)@*py;rcGQu|LY+zr$T0`mb@F_9%zn1#zRf>Ra&B4QdC3t<#NxtxO zzVaAc;RryTfLZ+uUMk$uJ131Qwb|$UssD-_l*%ALXJpX9S#G;v7Gig{ZuV`b@Lz{I z74!}4WeAkQw6|d~!9IB##TmSrZ~=1qpKvEr*l>_+b_phz9kwRQh-1xc3Xl791@^XT z;YI44R}{i}%CT$H46A;Jcs}D!y#ksWJ~)FsOZy{nbB%?Z(J%j=6rGjRs7ip&Y8ssR zJ2%J_7xIz_fnUgi`)_!TWwDp5@M|>V@2S9fhG=4Ti~zP#=zh(~@wP#SHJ2((pEZ!- zJp$}<@J7(6h;rr$Q<(0K9M<3rN*>N09b|J%zFif|Q}!!7%6Xq2V4#sMQa;VQ`&z*N zMHIiHCort9^IcMyNqHq@^;2%&u}@7q>-;Uvh_Yn}0 z>z6l#qX3+<0|h#Mvob-(%aDJvQ?PCW+m#ELCjz7nqg?Qg7ub*AotZcMSZ@#ePSg$C zBaei?^9MxE&GGOl4?rOU$%3F(p`OE_5|doSOHVQvVIx9WJ=0&ez@|m$Wgi*VwyRBA zHms{wVv+-OnUr$*6l_zx|5A}k5XD-!r|i^{uW&W!#X*)Da%iS43BE%))AA^}LuuSh zG@fETeb#2tvALa^SBVg?syvGf*zju5C_P#p6Qc*`oN6-zjQB)Ly5`Pmm^qTO+Ej4v z)+_b-`n%k0Yt3Y4ug4BZ5vr0r9%e}|k6jwqe{k%kH9LaZo`B5#^3OkH0(XICzEkLZ z*th~HeNgCMARH0U+`_oaHN*F+=~F)DZ1H4HH9K-$EJbN-Fk{lC5aym}@g*#&v?X7U zLi0@Y)M8(-85+nl=5t_>Vy*j|fE%oby||lUvtMj9qj7Os-bp8J=KBta<=us;-laGi zP`U+@!aF(uXIiyHseOpYZr3UN7#7-xtr7bah8;D`S{f2OI%P4MVRc57;DD3w*S_QO zVO6~y?*qjN+E|->%5(b-6{`^(j>2)|eljnY;;zXq;2YL`Mfv5y=ix@eq$4k9nv9pl z!>5C^wEL=WB()P;i>Q0|1e)qz>D!Z!T0RX3MEZ0+U~nvT0ur@&8f;+iF*_Qe`(&A& zfH@S|6{M9;80>8dN-deb(Fw@Z7D@0lA{>?7uY|u)@37&mIH_lUiC{uVs`q@DIp}+o zG;=!ht~wP0h|2{Nyy1Vt5Kq*`PMf285BD5>ztaLujxeI2yRx^n`J+*5T9YjY-XC#EuZl+N47Y-+9zseNqp~43CImeu&a>q3B{V{q6T%inTRNw_3 zSOQrkpd^P2FiZSbS)>c^N~iA%*1*pH-+LYUYNEh&80;?p03@|p-`4zM%PJN?UO5Cl zZg`qEW|OeJ_!IaH_5?OD2c_inQ8451?g_7H@Ms5}~E>>eNnj>-~q$7J3p6I=O_4S&9pSB`EYuX)WW6kyjDDj3K`O_YB=jPr& z{9$Tu3R6}_Wy(guWiwn6KS?U=;{)_fpFLbubb+BIofIp__?18ZvNU2j+=Kyp7ev$l z;rYlT*@5CwuP#lnfAeE61lw?h^%CJK>I4eHW3VIQVOr<_zyRSK(PpmD4hvj9W9FRf zPD;J9Yj*iqR5N$wlFV}}coeTyY2Gz5$XfSq>>L_A~2GI{+hz-aMdE z397~7SZkZYbk)LG;x_}rvt(ixV`pX97|bDA=O@^+DX=3J+Z}mUJ0;kr9Y!^QCW~&` zRJ0L@VwKE*b2aZQGLnjU-~a#v07(!dQIFRo9DtM6Og9QXFgoOW*0^+2rn4gUo#IIC zTXSU|R$iUbYIj(v52m6N#z3#{3q9Vl;sY_f*0oY&FFbBeFr<_GVNQ8azDSC$d0Ufs|C!D>Pe;In3x*7<}(gy?hv;`?<+AG0iPq zgeH-TQ2bvZTY89w>6a(mht{DE!(z5ZT*_|U)lnBc$~{X(JpI7)M9n{h(qwAFfbaBnguToe3eSEhaYk!mgK|fHrSXsH$}>R3 zT}*wi4?~bTuCvUr>5jWKHOkKxC11Cx`yz_NfV;;&fwsJ7*t@I2KAe`O54F{%55P0k zaWb16TI3ZGUP_x>U}Lx%>?;h)Y^&b*AOv z*j$e@{cyH2Q%_e=Clo73M17(oIj3N@Q5N$#X^6=$2Kzo-BvvUkN&o}8| zrzxUXhX*Xvp$B2053BVdP%r+u)=6K+3QJje0Hf6s0YS>(T1%6DdUgh8WOQou^e`mR z1>|6{g@ubAR2*sw0%&sX=hwC#6Lgs+pV@>$8qJhR&f8?9FE?mwy9B7RnO(5;mK!j} z*f#VugmQ-7sSJ0mH>IMb7&Hc?r`Qpp#Lg%^ey(i+UkSHoCfSzn4k2W@kN>~BM2btX8>>H8R|U4 zY*`fiEoD&$)bWTO_xV0?NP4L@d!z+FG#1Dm^&o<7(s#VUnVM?TF5VYwz=jn`mNNex zWbJlsLGg-xd?);&+gcp@QR@?oon|hg?AWht{iy za{259t78lOyRZ~b#mkNBlh&HM99$r|J{>E2v-R^(dWXiID|S0EvHC_J0qRFv3`4dZFiV{7dGlj(O9ZGDo2Nw+>SL z(32*g9o}FoonxSE5d(!`K}P@|iiTU{wsE%Vrov2daHP`%=%}G(f_qG?(z`cA&n%;T>4iV%o5XQ9;`FWs6R$Z2;#9+#Md$qM>l zDO8hkBPbVGds7gk!R(mhBj-_-QLly$MnNjD1+*h9CIzEPX0U8oFtjNSmb~xc$Z}=X z<*!0|2G0mB&LvJ9k(7}8{46^1u2ea*39C9?EbdgWy)nq*(Oad83k2UBLfn`{7M?N^ z2TrM?UqKWLJ9hXDn(qwltzABs|HWIvEv6R72~5=Hj^ed-zTfU071!BbgR86RebvjZ zdb^O0wR&I4&q&xa=}D_Ni7Ckj0{FfzBd4)JEhKN&X zuS%g{kwYO>1t+3x)ofj`Vo1@{gCPYrOV?O!I>{D?YF;angytZv^iH z_>>00EN^rZMzx4OVzFL+QzQo|0gD@C4bO!hXoUd8tr?{h7%0QhHS0=cE;CxX$O5$b z**T8-xw%e|{LW^D&Xd^yI#7TJ<5RehJ<&Y5X0d%Gn75$Ig>R8+K>ehCJ?YSMm*?%9 zve~pr25S;HsNSnwvGJD$>{=ofdlcV&2A0rP(S9}C3W6X9FSied7M!0U1VZ8-zv4M7 zKSqP3M%)*kdByx$lBf^bdh9FL1eac~ujBo;;9@OTV<&BY5Z)SuSDUPa)G}RR zN6T|GtdUduAAES~F-(k5f=C?*nDAM*UzdYU*x^Pb^3nFv`|IP+R?NlL3*@7$WVs*A zdc$k{J-vK`rqXS5eoA>si*Cty57;DKgVD;2uhQMpud5&c2J`2OqxXIMWSPGeulfRN zskTna0oR#2yUyOE?6f~UV2RokXksfx^m4WRiwA^w1yI{kHAP0W; z6bm2)Lwa&7Kyi!SD?Z@;j#s+sqS*+je}^1g6391#z}ceg${0;jT;RM#p_Sz%Ko|k- z9)l|6~m=PP@N}j}9OmRFUXF!}<^!T&XqYA?&*B7Wc)mEHZx4N(Rmg8i( zxeTqJfN4DSmAh`Dd2&BN>*}_9_~eqK>5L|p-Q*}lY_~XgIJsG7Y=a~or*P`+sRSmU zm`oR4H9N-1poIthV&weal%Pb&B{C%30KO@6q$A?W#}oa@x>2RONAHq0j>bWts!@|S z)Y{$b4v5djb93W+%!>{hrG$Y+I~FV;m4v9RKrE`NjC-^Kwa)Tt3*$8NjnR(AfS9YD zbSdCCWgyr!^ev;G10R}xTQy++w!-C98g_}}Ts^eL{e2w2?+~HWH18~u2-7i-1Z3WRl(Wee~WD>2R>Og z6k#9bZ!sAz9)ptQY=8PW;-1GF&xnox=H`&!P=!{HL`;Bmt*L)uCQp7Mdu{WnV28h6 zUU`C-SxDk^3)l`#tBio)PaUOApxngD*I3KzRC@9h}hc++ao>OmDkHTMAmRYzK3hcwP=y` z=MtIeM-trmy*U8|FE`bm)@d+-5D32L{?4Q}x`eU%8MIE0gd`M;28M5N`|)SIwFq%9 z-=J3&x3IiVQ|iQ0J|Iq?&`GFHrkm5u5GkHww2}dS+bqt03gRBe7+|u`4w(8o|Ku-e z9*ol#@6g&v_vbSQ(Q_~e@?_knrA2nQ0pEW>UZ2avOp9BGwVKBz2Styo{<8_dk|Y%) zm7bU@eJ&d}-!ATVCyG(M&L*9&o5F|}hTlmq{s8x6XU~#mcEkGriyBTj$7l&@^l3DwpI;KLWh(ma5CTQ540*Mnm#2JD1v#B#!8=w% z1rhXM2O9WHcLv&TX;t-wAmTb1+FcCQf%Id-6r(`V@2KpKJN|&y;v)sIE)nU4g9VAZ z=X^ofh3O|G(8Qxs*w`m15inXITbNoIvpnznQGp>STE)QCTY2D%QET>ISA>;mw^n#& zPYmn1L{-ZgZw#fcCP+>(&cnXEka@%p)vWrZ0T#4r_&U9hG~!*4erlg=gf0cKSI*_b z3LzR7@`8ma@^fp^G}M^fAdD7Y?)Z<)n3-Gbswt&JMsIpu;j@_7>wC3UIQHcLsU62` z6>1+t6kR{8OQ8!Z3GfXq0n+#Z#ny>|=hrpV&V@+9>h{pEGb@1B#2jeWrldihXT_$HXYaM6aw7{=adaW!^NPT$u+ds;>24r2X4hG9x2zI?l-wGG%d# zp^@?mf!EE34*Y2$*s=?_+YUe&XvxDcxcxEuQ}lwN9oDnF%AnY-G`UX zzSHcjj}uDnznud?;+xGH=#;~VE2hA{K)FtCv>mMi1G#FhXL?9-0f7HSASyg{{2j;; z6H5~=fE2~yRH!8j$4v{f^&pyh{zjMU<6p4TZr)=vx6Gy7RhE9RThW&#>4bAxaUIab^sGu*3OT_E5iAH2H!O*7=1vJB76Q2q+@;pL zHw!UV9^zAO$HKvf4+C@yZWDXM#I(cEV>I1~x zckqv9U+*|T;nAuH>3KG52|Ieud_d6^fX(=wU?d0W;Mk2DD6dzzTo46=Jb5F# zeeuBIph}mBBPL0C*nK$5aY~>MUMTFRy7Pb>3vaqNKE%?$JG?K_Vj&N{O_Q@9%Z|S$ zJYZ%`)$0?aUOatzfa4c27Iq4W-vL$jTx6e2V8LLzN)qK$f5pL{+)-^0cHmPdQBZw4 zq5@o3*j#r&ZT{umA~HsTO36xfWnoxyqX(Im4EVRE(MC~dQ2QtP6_6dDL>x~qUS02( z@E`&XB3D$AZ=tRy=84nM-@oIH(?`}1bh$!k|IT%#;Ijn?Vu!XtNC0*XWu2hIBhXWr zDg2w#xH5Yw#o3aa{P?6#L^WTk$$zZVKZT(-5SMNw!+ zC5EJcbMJ4kAs&SY|5+C>Z`uwif_7-t2BmYJpd0*1=by7TNwfl%L%~L#CrquzsTOji z5L9icY%4-fEqxoW!S(gZUqf1JKt~l>H#PX*a(sOPFke>j-Ssme8K$=r#SnCS$Suk3 zGSHYfUppJeHqvu*rNX4a&w@+$QD@X8(Y9I)zXj{S6 zMVGW4;;aFkuu0ISSOo^G=l&UZdOJ^4IZpX(wlY@%DwgJW|Ao9by2)uMGKs8N$9T+- zcGl8+m&6XD(kmeY&|TBe3J;<4s5r?QwXLrP&%zgS!S#o2`}%HUjr z7M2f12juUA3EBqvFD%9MST@ERXK=PRaLz7e>` zwTAcrc`+ir0mo0X!+zPEWLS6iQjXJ4{lP!_z0F7_@;~m)#GoqQ{hudaHogNY@=hie zTU8Jai;wMs%<^0AmP>2D1YHWhCr~jUyqitb!^^r^@xb$)1$h}7CLYR|Ui3-#e-P=>-IW7k7h)l3II(#O;ZHYsZP3A1bPpy zKGUE2KTi1*ga zYD|Jr}^LAh^!SMSBK z@|25W@xS6-#-uLW`D(1J9nLE7uu@b^jpXvY5^mMX&_=r9R^6)sG6CY8Oq~D#0{{R6 z01|?)gH)Ivb^U=HQIxqWpdp~t_Ds+Ry>BCj1z8J+X%^gr-j%Wkd`Iki)CcT)ah!a$Reb};@OEAVtd_}wz- ze!9B3H8Y=2i$JzXWRAu0CjO~YMio(t8`ftCH^RD2a1uliB~{;1(l8Sz{@*d<(7I{k z0NC4#(67UfED+P5%tQ1QiwREskD50GF!ZDbgm>kJ-S!Z}CZ#$Q+k|C5ZSb_W!*ovU z5KAay2*m8&SE*~&biR~iXwllxleduR91QxaTURIK^}9rNr+0u}!h8{-S|l9mGD)NA z>eJH3@b$tj)9ZG;B^S80~HIyXTRTScz#e)EJP z4NNesgcN!oN9HDJrf<5Vl2&DHQ~sS~N5G;=ac&kcBEsE?PgDzdeWf*I4$Fp03tSN& zRn>qZG^c?&z=d?a4mDpZ#Y4ijsQj9QU_9<798981A>+<|CB3SHgEfg!xI*F^ZpsmOBE&j2PYY405W+++my*Al9@U`VxhsP{<%kWlQPU=e+|d#t)G)4JN`MdXY|g#d--qN zq~f~XKtXx}95dyQX3=Nt>l13ofq}_%qE9r?K^h8QM!S`x6+{K(Zn8hI68&?W_6paV zaX^4kYq<0CuC|NU8`$BpJ^f60d)G|St5N(mK+D`L=Vb{0eB(VD|sG<)aDg$}eyH=PY zw=;nqD)lxEWm}bQHe}DVp`gSCvm!J$Oc0IALgSGP=^7<6oqSWAyinFteHDzugA44$ z4ar?e&lD)kFCB^!aPN351G`y=l7C%iPU(#)5}_}RTZ9M3HD{}5LX(l_Ar*V&q$Fv7 zYzpixi{+o6vv&jD-=Gmqxq;0@8f9R{4%eNg!eNpp<*M&rz8HJ_O1#KKb^M19SND3M z#HgGDLgaEW?EIMGK52n7oN{|;dQW{#$#g=#AaG&_gCz}H$P}Qb_&vuZ*0CgNe&(!# zNxWlIAHm8a_Y7_sd`4}Y!1FQkJ1&P8(+!_=H3c4%vx40!tSmW@d0Ir&Z*CUk$pqj* z%lf}pMziKQ&BY2=+#q5-TU2jBO+#1~FH8HmV-%-XM znL+24X&#!stP3p+4pPelOw{d*2%W=13iQSZli3PnuWu`Th9`c(-I!Z+A;NXI=}of+ z3Bl@5UFcdJnko=$n%NN2mbZFu%*^DCqPo1!^ZqCh#F6EH11*!Ost^v8grNS)+r^q1 zle0kNf0GOIj5dSCWc#qW1S789-@t#lk@d9&+-44K;yQ-VswCDa$PxUcJq?oAxzWaK znj#MjRH=k49G}r+sunla^kpnmCa)KtHkSY(*-ES9RAzA@+3*l;PBG=S()RI_7+v@m zf(*n;!(F}cw}Zx?tZ&J`@zFQ{B{$Y%Jp`c9w``kAP6rlI)y4zXwzbNJNe9c8U#~^E z*4SqbdiE)PNK9aMBqb!e;edpaW*+-PE7<}V8n^V)-=H!8A+h83r7At8!r6UdGU7@X z288_@C;MJ-AyZ}e1{8$STnsx~XB$hhi)_tz9u<9%?mE--SQQiB#S?!bCqCN8KJTB~ zg9;8MXPBH3U{iqvNF?q)NIkK2w334G>qC7VRu%KrelzXedTa9UfagHJbLo+tJgZP> z9K++I=GaDNRHuO?8NqgdN|>kC#R%8?Jq^3_=tH%)s*Z_}2Oom@85jWnY<(&M%#%0Z zdLUB;FY-^Hww;Q~4z@d5V6H!^WZPNS6Z*62&*Taq5LyWIpio`@^$K)&cO0mjIj07M zzCVMNO}Io4sknYxBwux_VeiSZi=*8x>+h1dls2<&Ra^(P$b{z6L+FrR3@5%GrMmx za#e01erfzXUDSD;A8$84qiD(b!2KXw06B+(7=Z68cytL0Wz{^AlhUPfca?HzqA);I zq0EJnhO zm4ZIY&p~}17-pAL3duWJV>X3w1uy&kzj#$0f56wTwa?w*m(E4se;e4J;)SBXg-tJNQT) zput*>y1(NKMhnb?r8@ng{GI|zh2_gjXdG|CH1YceHtXA_&M*+qXW zYg(n@j`-jAdH?iul7EQ@7sX$xsfnvFFh2})8s10ESZ7RxERQCAMhw%JyG;c6FGn%9 zOogE%6|9^{N!4#0(kF@v(#2jcO%*jaqXtnG2o<9y69~K+CVOksS_DX6{gW;FJ|23r zMkK0ANPc@e?(6^Xd64x?DuG3~ru;>tLC@T*M*5PLYk%TP?BP^)Zmr(1)*=DS_@aFL zgXx=ZEE`xY-wiGiy@*Ummkdc8$R?RIzUUI1CbBgtG@PL(=z!Ytp6^a%GMh{o){H1K zo6`~z-N1DlEY=c5k1m|wI#HUX<=)<=Fh)dqwEK9H-tN8dp?H1Hc8K@NYy7@WuZ9z69$af!KatXX$Wwe{;+Qy;1*UYW)1Q zgMw`Z^0#Pd#4f<&Vt@u+jl${4)y$N-HZ1o6a13*G?qY5r3ER)LKFmk!HK?QrzU|2B zCA&?{txW?CC1*Q@^5c79C8_JSP*a>{#W?%qv-fv!KjuP#%oZhBPxs1HS=ED{h5IT) z>j1mMM*dHgWjGR%DZo_N=R z&N?WT5;J{Lb1@GC5ecTH^Ey%#_1JOsn)Bj(jrxL<9_$mKiPZ_D(Q^~LNBJD=DHk?g zVc|o|q51trvLei#I)WhE7IMi^NoHX8l48l%S5Ls%G*fGAh9~@P$~DELzBMn3wr%?2DEG3aVTBDE1-s^xBN1@7&Sn z@XL?&RBhczjvSy7>M@8Q}D|GOHvD|pc&kf zetD?(gBY2Mm!$TmX+3NNvUzlwAugUpH!Yz(BW1hTAm2E3sIzyW7=2`ZjiK&>By6V^ zgsW^pA};NV{JY$07Nug^?&9@4JPQGcB8Gc(9c&q6XqxL^9~-0vuS;5YX|{1KBj}fj z08Ic*MNlBCI)xa`*IDEMRx>JA$jz_299x|cF71$V=9IPMeaXUEn|OXMc~gHH`<69k zA6%{Kte`3h!if%J$snS^4M#s<4vf0E(+ZlwPL*PcM6V~8vc4s}1=Ebu!brE}4hmn0 zxgv+}gT3x0lo4r3q~F@0O)B^m^V#x@NzH6rDn%1krqP)SD~7 z0@~7~m_RM*Y+J1_yOwxH>IFl{r% zjt0oi8qOV{p`8GcbwQ8;`LJx6nK;~7+;=i-9mjDv!S&f4X#2Tq{kbCMJTMO1VBBtbgF^SW9I0mL;fkTIkhQv3AE{c#C+qdmpD(7u{U8YGd~T7k+N5W z$R1}Q+ip3e*`&aeuY~Pi>tFF`$z-d~LR~YAUXYiswxqnsX9+5JlZw5hHn|XC%uKeA z4#8&wm3!Fm%iKr&@))704{j%Yx^6oQqd<>R^1V+$=y@BwgG7BN({FhI95ZsXaX!A( z$OwywfWka!sDhtkItK3gL`{tK^(f>zFd_45y;hN#C3{f_rRIX6@)388hT*M zA8ha)+J-#RVC;I#Yxd4#eJYZ-aMRdjvRYEfs>7b7!j!omc`0~_ab~?Yt ztD3vIK3;^JA`ki=uJg=N!sRIOeR@B$Tzv>vT-~`)rQ<2x&iNYjO7A0PGdRCD3%1Q& zNwDW2huXOUq|A!j=t8)kwcD%GSbFN}?ZGgtHx{nC`_cw{oww806&kBVCeTxOW4KopRf@-a<>dU^&woHQ%gKS zPq*gzv*5#)a7D#;VJgAI0hsX8Eqf-?b}tC|aIZ7q8#&QWVLxzYGmU0FL`s#dWo}2Enm=qRj*sJDM zWMU;-uNhuTs2lPx9cqcb)tJb^q|si59AssdP1m*#Sdp38#Us&#kttku19!X#`yOcS zz>9Pfsz|gr&=+>Dfb50-{L6E3Pr_OdBR|k7iV(bfi4ch^TQ!m=JFVL`KFk>(nY@yL zy1~ihPb#mYslNSz@Uf2&t^*+)Q(KOLUMe*aV$gsp{Xnnj=B)VaZ?+c>8)7tFO=c&@@Tp*9bdob^zgtqt@I_9Nt@57oIM5!1aH_h z@2-CLgQd5fG~~K%2P(AF7n*>Us%6AW*)gj-kMl#>SiyLd#I~}J z1p^lwNg#UF7w`lTRQS$&P&p2$lp4Tfd@fb%{pkuWwE20Z|A^5t$A~S5-=a=i>QOx{ zMi<<*(EKXBHL|WKHpiON*lI4Q$Xo+#71_2IG?+@H+LP>{=1lIxEWP*0mcK!!s0omV zZCW-kFVP9GTMdrWEc{T@yaok;_$*bk4=aO(uBFHPO)4p5i|)>0kQ@u~F_^b|YVz=J zvpGYmuYAoyZC74;Z#y6lQNX2R84u zJEjrt?7jHkdV4OiuU+44kIyq*^L;+}ieKzqDl75G6FCijBb7CE-0rX5vK2vk1^UK! zg(^*^n(cb{ZlaF1X$(zbiOtH>X_Vd{7mMeuOAq;^KMMXw&yFU(^A0zx7mh<&QOYVV z!yldDgv5k2V`b!8g$k^t(7wTOHr|=aG*u>8mC;o{+%R_zxO86nV(Vi2U^-LP@`Uv3 zW)lunUFWUPD)P#@Lx;rew`3kZqtVJdcCRqw2y;wg`WY zYX{+G@oGkXnN$9UqMkd=RbppDerqar-7uB#w3RGM<%EXbvF@>nFjR(5mI!;)h-u#} zNyGwttYsTNC;M~9gG|YYk0B!rhodXO_CaUr@EC|8xz11}!7aEs0DIiDc+_@;A^SBs z4Da}V_A_vJKdrylN-0*oUwp89b3VyII&+iyG~$}ei(Twaor3yCMN;q1CA?Q_h-Pi* zoYz$-x!>u-o60t}H4oYO4o(8~C{y1EIiDmV9)Ya&u3SKY0JY&=LZXea_8z4a{$c6; zQ2q7!{>1+Y>|I1(t^uuNv;d_$_j(4=f1lg_*PS8~aJU|~#hft4+C1@ekYGS3TGB|E z8dkRjb_iFi#|<1!!++^~)^C|S7F-N1tT5KAzxLVI4-6`edqCqckRX(* zTsNtD0_+#}!59c%M)h)uCU4;zy{&iVSKp;G*$Ha%WsL|j-E0DQeXj(C%d7YW1%IBo zzz!XE!El+`k2swDCh4(uVBAD$)Jc=23Hg+H%Mv$qr)YbJM1zT!P&HSitSM}>VmmSr zD)+`}!R^leTioTz;&xUE8lfaMPkq_Xp2VTWrMYo3H=Iv#bIsPou6OuvjYr+W zrNxg|O-9}H-7MN}laGsOrg^ko?li@yI#*8c6_EF2D)^eNzY|0doc(`JB+0iYy0x5V z!(NHML-O$SffK-tFmG{Tg>M_XO~U-Kk5iPPi+Lgw*@#hBh2?wl*?+FjauRs$ng@@o zaUG5Dcy5-E7Nfq&GpS8V@V|nf`w3)*ec;YE^j}d5M7ZAmOqZ?;$yA|9OBl1 z>We^#0As6CZgU7dp?maKxI4JtW6EV<#LgAYev7-}?Q&BF!-n3xtts#%C~<7B91b+h zHB|I|7if2ro}st1-cI_M7+?eP!Y83#+INICzj?~fQ9>g6JmM0?|y!> zsHi7UB++G(jLr>Q6;EST1rEc2FOZp-wEy{vYBqn1HccS4 zMXF{$AAl8JQXYUgnplWwWQ{}_l{3)DlXmIg;vn8ihqVOJZDPyKPNP0zF9DxtNobwC zfH0`#-y>_%W^c2tjiM13;O98A&aHK2hsx-#dU%DfYj465-0TZ0SN8XNtn2QM_K&yG zxDdgsI~2!BB7F4|c*Mo|Lb48*?qGR~JITm?YHXy1l=5%=?4-;P2Wi~N%&ag|Fi=8W z{XI;Lzs*BN51_$DBU|fbC5|{w@SlT^X2E6mZGOu*WMrXE8jkU`vwqCyL}NnPR6_P@ z0U7V09852^Nj*S9U*w#5p>;75WrVDH$$!qe%MnAmQC?@qP>UT^7Nhp=gIHF4M5W_7 zH+jY1S7^QBSjj>FM_1KXpos2c>S7QrBssXL6pKly|0(xGKJM=G#!pQ}^tmn|n^iLk zr6FUXNT3w_J!$P4mNk-pz^_V=ARLJ?7c4fUchqe+on}y^b3Y^$IJmmgNq_{J!*<&t zCh5gJZp$>4yZwNZ* z;xu;*rwn5RRL;;dq#n$P@$}=Kw%vg}Cr7M1Er5XLflF-sX@z>`hRwLV*Z4c`bLRT= z$B7fKDx(Fw;d{SpbN_F@mNvVT!`ia1M>ghKbqEB5H@yHncHKs9lpV~A+B^Gp(O8Sr z-Xz;E8)fkY;lhXU!n|~O^d$3=a+qp1#xMd)z`kD8uhHUj zF#XgYFvuEklOSyvoLx!_jGA~TL*xGwEx$&ndO$62mNa^p1ej$8q(>M77JTRZyRy}i zCJdhNsAt1|V#O)7^Br*m`nC zNCI2)IXaL38l&&Dea88`uT1slK;wFq<}yij4-I}Fl98txsv_qgEz+nM#djvGie=H8 zKnpmyfdw>}0SlAJDmm40Ga)Qst2M7CF(CS6f%{|N?1Q_v@R{1&;tG%7Tai1{T&kN3 z9Yy&&Tqq*S5#y>b5a^`EUjVBXyA3)21Y8_`BrwyLyI0O?x0fStOJwdZ%l+B4 z*Rj~~A*?qnwZ*gWi<|!#-o{lN0*qrTfH(=AeI%*HfCoW7haJ`y$CF3~bDZw%5u1LJ zs&Jg+0B5p?NO3XAa~m2IxducN~9MT3$Mgm_FXODb?-e4Mg1%lzua zQ(65P=H!!fKJF+UgYBv51pEC4H0gP=C>5{j`@|sdfh8!9V;P zt@~4;iD(#9$LmsyLRMDyYt!8wq+GTu@I|!0t*nWxH49?sY zO6L!XPTzk++Zc6&*j?=}Gp8_blxT-6C@c6%>O=p`bdR63dU8jYcD&9@n2WCLu3`n* z74>A1+@j-$$3`8FqOdak%5?Q0S%xgG9*Qn{Vng1vORFNvC!cpO zOzT$c&eC;8ovWbvGdy8P3o08L!EiWwT#8-v47}PZl78l*)S&bwm49R@_qSeK+LFmr z82TO?chahEKvoxQ4YYl+r z8U*kkWuU;El2cFLRIpE89VCWM{Jt_331-OnewQ1e1akflT6k&$di`S-jMMs69yPAs zBmrW$6;~dZGFj0&>j>!nq6NgSEI{jKIv5?ifXzaTNgCDr$UT%?-7c*^y3jQG@{cC? zYt7nVSu%I=Q4zJlfmXx$<}CJBLfUFV zE?We2gyjP9c>$O6r6?pnurEbfDJ#%|Vfh}Ic3BDG4z#pW*6upyJW>TGRJSUORbm+^ z z`dcEQ+oO6ELNwgt0nKhXJntM_PDkQsyE?nr<>Nl7@QzHSK^%2*8(T)=DY_0Z^>bDO zvOhXGLg|m@Ywm6pf5Yx7py!oR0G$q3;hFEC?C-4fitPqFC7>@auPeuzJIENCJ|#BB z-PvD6_GbO?Q-3Ecs|D%%Cp9xr3oTuo-H%T_dn=!At$Z+U6`tIfL-UTGfouF?LeW_@TXb zhfU2p_i8oF&dhqBV>>NUUFi_7HHd+#Xl`)^#YSBP>G0X2=a=;OwWbZqA{(^zC)jAj z#&OxFbpA60E_MVtB08>CZSOCMr+-)4dEh8wZ)kLKyeinLVWa*64)Dr*eu?7pE=pKZ zQE*MCljP6KU?_}YAG(~JL@cMZSWr=jqU>RP?GJvMlB_yf$xuNGdj_1i$^75U?8j$R zk$zNXUj#;8$j~7Bl-3c8q+un>_VN3f(#r(9l;cK<>PeeWPP5!kNItR$iI&2mhmsg3 zM&&<&7CK$9Kw9&$h_Rr#u6vT#< z;7bym$|dPMEwQFwlKR<;R5|}cs`H+okIRP^ybIQ4l!Kr_)qZn&Nw=j`a5+}P+SXd# z_ikUcbUActSy~IcSh8Q_Wh4dlMX=pg6WhTipfv^h@u!SLrsS;A3EsQ%x=ykGA(@dm zZ{4kkjeaFZ%OaJOW}3$D<$N~kqM6H&I;>p`A6t7fth~&9&h%jw@l{h&jd!78F6DWg z%o;FJS>}h5v?_O5Ed&on|KC{|;0eb@NjtS_=WG;c9AAM2-c}MaHHn!o>H0EC_$oNc z4g6uhgM9sQMy?z2{hY{R$VIpjQ12f4h?+{P;qfOI@!1Kzljhv^r}w%nReJWTlYul- z?RE8pa_&K=hTQ}Y@jCl*{hx~Hm8*$doXW!pfOtvBmXuG0wlF_e z@oL&YdrWa>sUD2=lb;_hiMcBG6>TT4?BSF9H4YxXjt1bM6T+szSdz;`G%40uc#mlx zKqu7XCB2moI!<2JS+RiLv_NlVD8Ow&)oHu~b@yNE*}kxj$?B?_T1-B^RATT-FVh~) z{J2}rZAKH`%k8h=%IAlvlSbgULf*x5pS^b+kWg2v(Lz3l17pe|808{*!ReiR z>M}$9(|`BFXQoi+Ef}7-D4S6Uf(%|;NGpB|O(`7DV3gTLGg{emP;FSz)QZ(q7jI0< zq4f%hb&gsY1{xBTC7B|5HZp6J7*XR!Am*JwnB8oOtlwSe4Q}H^UoqMlNl_PuhG|$$ zCMWNYxN|s+F?yX%0b!UN)YYGjR0kKNBt{m*Wu#^tq20A)Z`TL1hYl43{Jyvo(qn31 zL=SgBZt7QtZ*J|7p>tw}1&}q+eJltEc{$Y4~zt-9EA|@B;)1#6%m(yc?AJF{6LQ=r)F0z25`=1t-TV<=*F!!QMm&IrYV^N&T|s+^v$dG- z@S7?3+7$><81^KjiSv)*LtF2A^@6W?c|0oWp?P_Qdf2sn`CgO2shvamS8) zla&0Z*H5@c?ac&g?k(X(?+-t8p%OWnW+r>mP>C`&fc+I7L)5k;nBJ+KrdGd|%lz`A zzKcf|@tNya&cc~PN?@VQii(exWP@2D*xp@?Vc>@EP9uK#jeMVE zrizj1Tp81k&WRDj1gm3JN`RJFq$WK_3YXjg)2#*OL}l2A^N3MIEAEyffwd@&5FTQn zwiuA`h6CPNHsM`M;)#&5?RvmV74GPj8YQK;4^|b;wWvSW4HV&HY2b$+(Wwom?JME1 zY_pd68GW_6nDdw|B3Cnzf4{<+#^s=JA74fa9y1S%`_;x99Vudekkxj-gGQpF&N%TZ z1q}>6c5WkvE}*NQ7C_!4UE*CqKqb<_A{f|r_t20F`!%R63wT572f8||Qhswq!01z! z8i2(BigLaIq>riT3o6F?%7CX;xypX29*IKH%hDy~_`{Pk=3?oQs-+@%BLI_W;gbZk4e5cV9+$z` zxe;*TWoYD|duHg|z7)A=CN9#` zI3sRrHLP{QNns|(T}?gNSFq7W@(~+A!e-4_fC&#*j!Qwq?Ph>Ult60X1~30e6_)to z{gWT!5+YtX{%pq?J#Y?&~>EzM*|7Q zCgw%!d3QB(Z1ufy`y6HIX#pXsi1Jgo<4O??moC+xjOxmgb-M93$cA1+w_>S^E9;<( zhatCGSX=a#ukQMs1e4pM|K2?V1A7>>_ok+|oq}p)iE2ml`yC&KP+5Df?3@81P__+L zNsZAdtVw&F8r_K}YZkUfN{W@0`hNlI&i%|daNcr}N)cU>DJzbYrA};e9Hkyb&2?YSM#FMpUj1fz-jLSn zjJg9ncFpqpl9-NxAW&;H)KcfQ!o4w*8g;Q#a;5`hTn7To_KwO+-Ws0ljOQa zr+VgElSk>pmfIn4^4}|=Y);?D(N3X!*K~dEpYq!gP>nmREOOC#-SCZB-NSYQr}aip z2os_d0n)>dI9`N~xbkN4;ZuirNyLwC^9ATBk2B{#a6GqRHHLUcZMp61O|QNlK`rni zQpyaa0}Dm-@2khL%J;Jq4)ktQ=&o+U+e(I)tNRw+>9D6k&h9*~3v3Sq)M4ASVXtCK ze4@qp9Qi;Y(j_zlDUhl&y2oiC9yK>mdj2f5)P1dEt^WHYP_NXlv+*y^9d{|I4lEQ4 zmI}i@nWHyD(+RUY^YKUkDSV1Fl{fqu0oz^y;zyqf9HoTXOXrP-G}^Z|5awY!axKC% z%kPU_-mO|x&MQv0xIzMh#S~u7{##Vp+5+C0ayni@%lP7PyX)|)KaJerp{C+|NMM+2 zA<-A@DvmBp)v~HsgM=-+e~@fQnO1WJ`}l8q70m$f{cnn*Rl&5k99sVl>MKL%X(dnS zGU)k~*i;4sW0|adXEjUcQz{lCmFi@{EPRn9(N_lS-dPot+}-)4`f*iP!Q0HGX%%MW zE|N7PP~S_Zb^uut+zbt95p&4NB9amIyLho2;Vd2a<4_ejQu*h`Jg+_xTX zCA1EY4oaM0%h*i)e6Q)~2T2Vp^jEBgh#14q@56-oK!W;0HZB#zk6ZDi zxN8^ihfY0HO6N~jL z7Y-EiA*2;J=s9Gk>Fn%38)={Is_26m%V%Po1Fe0eLu(OryD!rE9O;TY->oV25|hrP zCN!znhL3zVWVB?A8SGAS8_J5AszF#)IrzuZcV+?)E+4o3fuMN$42IMu>if2rC}F05 zG(TIgiUjo1h?*TW*N|!@ZW=TIf8UHOc<-GALkVbq3qbu_u)CX*n<^y0i%CQ>V7-h? z8ayK?jqPK8PcSar_Jtp{TVc@HhA{pGo3J;w3PAkH{iAAUw5^EYz?}4YmasxEgbyfI z;0C3deRRO6dndn=#}lUXYB@-weaR<;M7O`VhfAOg5iSIvhGbcd`yAin%yC>a7K_3p zR2rLO2SjW0zvO)W*N1E)#pGw4@?vSPw;PW6;o}ssB0l;|YHIljn&{LHVa)-C53d`f zD0;)PGLD1ehza~kRTeOw*(0uup*cG-_CVi=8iOjB;2U-zX9X8Et-|>MO)1y!@7b>Y zY6#0Un*3jLlqf9cNhUV$$FM{C;<%!swLIw(-pO-c39omab|PD&f2C6BVp2!KZW-WJ zKv1qH5dir7CG{cUFudL7$iGQr&@Mi6`jFy5zs%A7{`ux?CCWVBYjH7d{B4wv%fQ-! z+C1aRET}nWG~pbCOkA!kv2oEGhIsC#AZ0LK4rVP#YG?-4LCxf!gY+upR@lmlA4#P( zox|s$fh+2`L-VO3^)Q$9^aMP%G1^1NZ3iX= zIC6kNG6#0Snt=U7-!lI<)S;II^Ko0)6tFjoT63B zqDn6Oc6uiXdqxpKRj4RT4-5-zgdJG;7NQ*d%ZsR9fm-$ZgwoH#QEQS-YARFuDjWG0AAf;UYPhr zdpj1(3DB6?%t)+u4$a_di$>o#)Hn=$(xC?5y~6c;|$QD3_)!Iupd7% zbSm(*(RUUo8@kvfvW)XvA2qT&h$ldJ)PU&q8bF2>?4;L$n_PyA`*aV87b|Y!Z}9xL z0hf&8Vj(4hIWXK%0kTkI>4tNSc>NJSuBo>E3TMvW8q`^#@JH(J2)fx19ASSY(|^_|lQBhfhmAO*wE? z`?!sK9Q7Bq;^OedO1*LeKGSqcp0VQ@`EkoQ=_4X6n$MRY| zR<}@Ffv!Rxzl;T>o022$ebkp<-jS_4d~yj5kS$tEU+J^+CBYkly#NU`2{>_V&QQUe z1GO-n%u59ty!(!F!z_Ge*GiX96gh>-uoP+P6fKHP;@rUn%Pq%fV8OTHjCE16QmJJ3 z*H0C|1u{p2PlH|H(+vksJs{KXcw_>Jk*tM6D*Q)5^9levz8}CPK737s^Tw%&q^Ydu zG3kSX@(ft;YQnoR0WwaWCr}`JykymLHQW~lNxk#(4&2|s^PZtc06cXpDl}p6pe7Y4 z$CS2&*(yn-f?M``P$V7B&Hz`JFVk4LsNk=bhbn_?$E-{61l#}E=To<1R8EGw8F$$R-a4X#!Nq&(K?Cm$Kn z!Xl82s+L|E^11^=P9JYn-D&Wt+zQ8f6og>u#3AG&SPH4AXIE37+R4#*WoKJls^gVr zo*>PY+`OYH^uc}za)K~%N@h;oosl6C$d^U%1y&Ve^amD9rykka4`{_vlPGiwUS3`e zla!#`k*MS@CgLb#C@sx6Z%4dRdYlSknJXes#JIZ6^I-`P>>7PiduCHrp)%cj<&-0z zu#M4VL8>h{r^1$x2D8!$7&uh!Wp=mt z=^i$qk71z%0f#CRE_q!_7EquCO=oq#&N+v86KTyLld|ftU3|I6uw8+^0Q)C`M7E!x z1i$Qq8CGx;V%8jhrVT6QQ}|(s2Ns7sFH_-akS*EBJlf;2)Kcef1&gZ@=OjC-8fxdg~ne_ZU`u2&MZ6F=Z*qY)})H4HU=BwBT?TZw=rL*9*+KDc8>ThLpqgA z=_lKviYZ{t8}k+wLx#}#P)|5n6bg<5KJfA|KG^quMjv7>GU;R2^+AM#rCF`ad(MsL z!Vs3R2s%r7XwiMrko0Z|jQ26AxK88c^_H(9lBF+;eaHBt-_nka8_T-uEv? zTQJY$o+`{=Wu#l$gW?v+QEo{bk35Ss9JGoGPQNbb1By|dcd!75J!v4A(`eJrCO;Aj zZ&$L6+~!E9V1E`I!9qKha#Q>dk<#I6vZA`hf-Po?yCJ01I*4!3ePd6Jh0?CG)}bryyJO?{NR5;P)%Gk7GdTQIu$uUvFS68;JL%XVtN07ddneIz0ml9hA0gsrIiN- z{}wQD1mr>sntBPw;%c4C6dnITI)$V{GbZX=W^^;MLk4&GJ6_{DafMn8G&IwzQcT@r zYlN&_Tkaki=IF-uL-*4g)6v0DMP$Om6tvs?yuT1FH?v=cgvBOH1AE;$l;t#GoPHOJ z;Nd2dGV~iptzK4p3VPWowUOt;6-UnEj)95q6R^ocv1~>*(@DR-n57zXpe1V9a+3Sa zr-FwLxY7JUb7nGva3i^`2ka&VL>Bz-5i2K>@_X+K2{F@1K{6|NV~oq%8zf#l<;Hoi zDJKKxDS!}`Sg3I)v)BBl`h8C&lS?)Phh@0qdMJe&?Yi_r3dW*|FGmF1chKU#u=K^_ z$0pK$bCUqz$adrDZI)=LX~>+45thQID*NG**zaGOfqvTvCx`0Q1oY&I@6qVAsW+4y zP6bD_e{&ic9}*&68N7vxBTTBG%GgubIziw9HQHU9Aq{)gDKK;j_tpbr97=LQBhnwU z;>XnE@-lx%vn^+&$E$NX(su^T*(7RviGqwh)9#gQNBRT-PKdG^Y>y3FLq%2$-FMZY zA4f>V?vI9OdE)wcP}eCTkxfipLA#vptO0JS>RyY{6bm?O4i_XDpY%)CX}r*4D##P z?9gHXI!AJl$+qNEt`m0nh-UWs`>%Ql%=~5!k4YsFJD9a0N>#%={Bt45K?~kCoe7y( zT8IqT{yvqT)>KBS(FQV9GbSbz;>0bVaw`cCeLkry+4R~m(|T>!uxXG7y%ETf$HJDU zqQB-!%3o<+`SO)yGQje|dB=G;Z0Y*{=?I+D4kpd0CQMq!zGcCTr^YY0%yzu(>^e8- z?p(7x5P-E%Vn1=PcDmGWlkw(+i615i3ncF9SMBQ9T<<5o)Nhx? zmVeRsHVwM7496XwBV31fZ9#%eS=j%TzSnRgbIp`)7nxufcr5Uf(1B46^@6LSEAxZp zbAA|sqS))NGOI_+jND6^ZfpH=x@8H&#Ol8ag<8IxvHt7@8vMzpPtv`Y)%?M~XVpx* z1`Yk0&2`feszq}Lnm?!tL!OX|+DNdc9WyUZ+xbDGjwiBkTzIKd;NZUw{jq){L)?i^ zSEp$&o`#I42t;UY9JOJY53-<%3`heZ#-2226=;<%tvJ^_u!KUVe`V>HHjW#-dtNrr zq)NMi9i9JDYR)_83*gzNYeP1w{yYCghW(Adt!-NBP0+4wV?}s_xT-z)HaDmwR#occ zb!mBRq==fDja|}B1WRV`QqoMwn;rygDNBqfc!&ybK_QaW_i;Uu>YT( zSTDi(xnH+%%VJG*I|*JLo(J`kncpSb`ygapOdRsm=$%w-+%RMDokRqW0XpHu10rx} zx11zKshdFFt6!I6XI}&l*zqLL3&gvX?M@RaW_)1Q0)-$WGJO?%EG-QnpKL6> z44P*RWWYnEV5+|SHG3*~{R0f>gILPI1oV~QOxRvmc$>)AH0-E}rv>Ft|AyI}7Gd5c zz&M4%wf>PviAP1o6r3TIhqE89aS!`EjIe9HR2BHtDv417t&%&}Eqwlx`-qRVV^KGr zKuGqntEWWwjh4#Q&nC922p3?dW8)xdSHN(|3QfsmUMWyIr1a zp7%E7s8IBsjH{K0SfC9@0}9HtX7uWvL7(Zw#?xXP@ulCSGK1BM(>&pU4-9OK7OlR0 zhx(p6Pvo&GL*@FcrM9Ty&G)r(x3`FB(w0vuqx%#jB{Q_}{HgnQ(I{@USGm3MsfN_s zvCTlC;whdy7XQsQ4658Q0}RJiKuQfPg$=%L%<|-@9u*3O0k==RW8Nd~?QuarrZ*J| zW@aHJaCUlN9WQCAf)HATtzEDhbxGHBZI#Ufm6H)@pcaRs)QTb2H|6lNEBx_0kYp2d-Jtr7)ZyGdkpX$^Rgm zX+APpP9DBcNZVsuN4;ac2X#~p#A)$=d>^|dnw_a4Tx%FzWM6VSYlcrdWb!rl2p2k* zgry2MKrPz%iQC=d#B=b$^)@I=u%_ZL)udhg0R+oNQ8FU^bbI$nlH^$$z3}-oUP$F@ z;9DKn*s~JEGPMK5sv|jC485F(5nBhbp#}1z(tj6!u`+-a=1FmuHk|42?A!}_nAG># zT93MCfonqP{m^@ktAW#Ht5XW=)USshPxZLVcz*0Ye0%=WF_ASA{Ua~(Z6PiJ#S5Hx zV_Q8i?qQqT%>+mX8`(7M++`PIi)NAV_dgk=lgwCKd592&OmX2%U%Fr9zRxDeA`Q&D z&VOZRE~NnQAdWDjx z4dCd@?L!2t?o80z3`NPboULD7gc*6EHkFyYIs#!koUZXX2T{ep!Mxe>tHRqykzocM z|ML-`4eF=fkY%Dx>_w_Q!Bml282NBHUT}00=qh>`caibF46OmG6YQG`n%q^wV^q{)0iueL%J9%g^01(hm)ix@LVVta7Ro*;^is15Q50 ztwSZ-MG!Er{;P_CZQZ6}~WQfG~Mw?}qGExyIA8 zxE4Cz=F4_mMekU`O3f6|BW=h}E1N9v z3y*VFiG|e$c)x$aZ$yj$*Vcbwc3aNVfcR<vTc3%92Ff!^|`{J4I z`r3}FvaD4dcCEv$a1NySg#;lHYI>fR7YhWcr%M}x_lQtq*z35AF@6*;r{6Hs0&dYKtLetZ(a9q&b%b{g_am;q@6 zhJVFSv;HX{;9c@|i?O7Wtgj6|+|6q&0;SqCo^^q1othn?KaQEfR?kF9=qi(|E?jkCTC%1;l zrJz5?8C`L#Q01^y_B67sasj=qTZ#V_2KfjqweuAI3);GkiGncLRZ8VK>^@oNV8R2X zB+_8KHC^ExSIW1U5l_IUcHNWw$$DTMQFTowXj%_@a^qb3o^|fvn?Q zD1gSGgyUj@;)NP z9>Fn#ecF;sEL1yd7ULvRn;8|>@yMhcrQ|v9+HlIN|Cc1@ewzP<`&WdEInDNu5Aoqb zo0f=XH&JC+Sg?f$A435B3eW%}aLz|7S;-r}^kDcB(RJuWx|j4rJo_3oMae`-+UR;b zQNHBYXU{&+82J@sBD>FIL4F#7<9^Qazm2{i%sk82x?Du)6j~@6J1XL|&Q9GCOZh`CDE`?YXG8^L4sSiIv1r5FRl%G z^*uYo%k(v?(_i}G_#PxAjkJACg8d8?Ukf@*%e#( zTP#{?3=j$_v$9{6szY(KTMg$Exl*(|7VOOmju-YdRTT5E~O*Z>kr$EWTkGm}7S~>Dd&ski?!wcek9ChIf$J z&oY;$N%!1Lh_>3;3pJ5X1F$#fiv z(J!bbgV7h!NjI~Kd3}S%RyhgmGsh)>D;W2Qp-aIbg;*L(Qcp;0Hg&N2b*`3A8EA*a30TMc=4= z64PrrDKxfsT8W9pyCW9q8R{C<>bpiYG}-I>T)BQ;`)T)0!%M9OEp-MBydn18rjS2Z z#zYNj1`tpSnUJ#`E*k~HegSp+Gd>x?el8gkvY|%xl92-lUpqSPaJ-0p7mJJ={2o?z zP`n^yYvcPe*MP=5mS5@$VF*LTEIt-NYxhPsg!pdc(&nm)w-R&A#@En#hWB2xa>SIn zG;r;}2W<7iaCl|0&0tIj2WFr;JQN~14zo-g4tqG(L|yZEtnu;K9HxCmy?uaU!`fQ( zvpqC)>W%tr`ZLmL2K7i&XA~Me*Lcf}N5iVZ$%hkuwbq`oBr^uv3!IS{FZ(HI&O`#M-%8xWp?1ZK&#q+B~#-5?Ufc3is>r@@56 z7#s^@_S;y|fkK|ke`i?79`^u>WKD)#k<3s-K5vTt_shrSm1QbO9jfL!eo8A{wX4m{ z(;Vwxk9YN%0rW!AdHB0B07cg**=XBS++*ybTGllrE)XTT8-a1*%q&vXL#)=;7eat+ z-jAkXZ7O`w_AFfb>WCAh5m-O*c$`N>uqpR|8oEi(9yQu0m)wPJ1oIURA~LU+*5656 zmryB(4)hX}(hCd#M+vGWZ+7KOw0PY|f9JR&GZc+dV>OYJK&@Yu_bxd?2FG2R`%#~$ z)#bOA-Qzh+h4;n7zf(ROuA09el^5Joc(Yuz_lgs7T?tjSD(GT5M!-Y)*%xQAUPV1* znv=Kt0Sw_XF{Nl?7*OT|IrA<46m{a5K_Vb#FrL4r9o=V#yYI`6IH^GFQE;;s0OwA# zzly<4QrtT#P3Pa6(YL#`jJCEO)?{pqq{~r=ZF~n>hN4$ta4=dcgCH}Oc81Tno<^sG zau8Dzfg_mO7HCs>2>$p8E0%v3>EAQsXq%ouRG>=W&uWc9&+yhA{BdqBeCRYb3)!AM z5SFOLQ6^n=$f>?Xy9bgJ)?;H^fRo|qd?&FJNjnmYQCHNi?o9#(KwUwu@FA<}i)FBv zHxDxx6P;+Y;}=(di7?BG$gq+%koj?)mchyJrZ<7bD2df}yBA$^kKfJ3E_{SfE@oe@ z+%!OGKp-;))r!noEMkE!2D*xf?dS1mS8JW{*<&fC=SGWM$nVwDhlW~&$)NVO; zfIyA=Fa{lJeJm1TFL+(bY4XZb^NzQz?JpoqOPT#%zLR)y2TRB`Zi_sXX8*VaZJ?`A z0(#6a7~|B({!roH=lS>wK8@_cHD@D=wyt@o_>9jiO~{}_Rr!RY8-JRhN)l(X{sJ+= zgzA1J*4DDEV0J(6=CCNPytBr-g>EZmpyuJtoY>CRJwp%DXr@l*(6A@e+17mY=1~{O z=Hx?7%M(ouc;+sq@Ne;>>HCjFv3J`UUr?ay89)i(RTsu*)Po`;p3n_4`Y<-X8Lk7l zInKOHz?nUWc(dzUeG#yee`XMf`=_^lq^lb7F* z1=wO(1TZg%&_`{|9U|mbu_E09R}6X=IxWjM18*@lsU~BgxYi8Q> zWkO<1814(CFju1Wc6tH0_KoWlD_#c*8{V=VhCZ~&H5yQ(AThg7?!|=o@7Z%dz}DNV z_zpJd?)mg8$uz3rrToqC#yA!;3>uWh8zlj!`ip)CZ=S~;R@lL9P7bs`1l!|$V&L^Q zYYZmP*QZQiYj+SbTc%ClQKA(WbX}uIw^ZXb!Ktncr?UdEgXb%2i7f7LviI-}FkP^> zA!I+$nm)B30u*{Z2+K@_Gd@VfV>XGM;H}HAPu_P8`(?B*gDIiG2mH9j1yIuN%_iSr z$J6D0!{0=c1*@+8?XL)`!{dFncUzQ~p8C6OiiMCBJS1Wl3TFO4f*^I0R!@eu#}p4l znMVLTK*PV^yy)~YgNqjK)^=p)C8PDDS4{Rip7=q^C;l&+SQf5RIp(!MCmKkV_z~>< z{NMn?7{xUCYJfkoiKZ_jfB*mk000FW1&8N=x~Y;hHe;G&(alV;MrPjSYQI$oNYHjM zzDepo1tt&j7$Z{{9}kW#DAZPf{Pb%h-ax*V0JMe0-SSf9{V&WUJ1iVeSlG~xYm_7z zp1hpgEe!}F9Pc2fde$ppw2N6GPpE%QMkblucAb&rA3~+cb!QNokCZOTbNC*ls|XW` z7dr|=a#V?YoAX+Q67T9KtnrR7ir?T(b~F9L==%?Id9nQ}R?qHi9~WAhV@{K18hR&T z*L|kUN>)($$$y4Y`Oa>Xk;Q*;4aVok7`OC+yo0< z4&~j9g{kE2X(u=*tK8#b25u)%h_%HNEoQCoN^(D<7rGxWyQw315FXzp``P75JP=fC zf6(tCYMi;o2b+lHg9XFr-HpJ|J!QQ!hY(~K2d1fI-#imwj)5QPaklY|(w8%`icV|G z+vLbFL|(9^vg>zE3d8dJgHn=?WjliDo39Tfy{>nmk;6=m0BV9*I-R*oXM|Br0T_^6 zgi(U1Ro`PT;nc>bFZ}`#oWrWX;e>um#3_g+3A_%VmVC)Exwq)^t3W`!J#an zCCkC48#mZBFQ=&XiXd+=Bn(re*IZd^Rb&MNDRE9;e(;WF0vcUyYHWCQuaHDW!(Aci zsgjwQEU(W!_8SIEhQ>UJ9c#lqUL3M;D1!Qgsl*5Ow>9*@e86`~ZCi1?35BHZ#HY1N zKh#~N$}??$0lFuhmDohdc21UUHyH_?P$8L1=5Hkh&^p9$Jg(Bclk@(fS@&2$D#94L z_)pLUkDr;TP;od9W*e+FPC-QEpF(ro0wY72?7F`6CHeRM3Kh7a>OGWcz9WWr-6al3w_UB$a~#r8A@Xjt(sN3|RM_ z^iU2VraeC$7)ACV&9QN?pfhA5N+dT7)*o?5e%X}oK!=*C#bGXZ7kF``W*!|VDkqb& zdf^GZD%INzAgqb%W?JY>TMYcIPc-TvN2RXsRbKVUV8=t4h~qI{A!9!eoHeoeEX13i zsLwOUoTW8EK-wF{wu;K8$#*2=o?=MBToUqW6Xd9bAnd+2l$9Bk*(=@^l)MNwY_?3e z;E&duGIp2VB>k335#&6EqEb6a*W<)36OeDr;#W@?T5JlO4%-o8Z7SD0-q$t=N4-EV zUU&}_w9`&0`8wnCv>U<4aJAXU-yrv}?4XgsMJVqBJsIPR2SEY@Qv5@IHK4!@F1&}X zw9Yr!2JW52i&N89D{y*^-cFm-IX+5tqud>U6w5sJBjpkfuYDTDu>$dw{hMWM4uFBn zW*0sZ-?wZO+~-8iW|6~uKfM;;X`o*xY&ei&M;a{i z`5PB>t;UqM{X`n+SRgFpd-kg(E{$tMF3*Q@{i_Z{h9Gt$`X;n9qv$UTlQJWs(hg)k z9Y7$I<$b9V{}9a0K?m}#G}C)EBe$t*al!T}rY#>-Jf}toA^U4D$a_R3Lvt64AYphu z5v3Aw=_t>0&kO7ZrALWpp&&LbM+iSHt$u?|8b(7a=j{K-soxh~sTx5AjYMF|c(Nc( zHs8OTyk8bK{#9bVgZJul-cu_yG>e(-Q1F!-bOm7;#Fp zsC|>UNW)FUEr~;bpox+F2U=F@tliJ{$0NW=*M%PX*-Ah?CC_@eUVUSL?T~wB)zKET zmr-l9b_TRtLX!!iHK8rdP1ot?vxr1uvw$N7!}aPR`V1j|@Z2s)=@^D~YJr zqsM~R(d60Da#0(VG?Z6EWb>)DETYhD0k9++Ve|o{iB4~_okhVF`86<>5`mR>*jfd-~6=JD-Ku=cvNZ! zm{-uL);PeWdhXOqWitp`r$XBA_C&1t+k7*~NSy&a_{3T;018ItZ&T*RJOZs18C=-* z!fE|>tpqN2rx*OWDVUoY4noLj$QI|b)Fb(61`WLJ#~ceZbuqT-f(IDI#H$a zhFn-*OhRTIcXMcT)uBB$67(};CD2-0^eyPR>98Qv2Hj?Cyh^N^ zuF)tZmnhGC*OE?CJu6Z5iH7%2ON5M`x>1>bm#GX6aJ09weHR3&#nby{68ZIAi{|Fn z+N&b{4~qj^5|BY_=tibTRB?h^<*5stz#0$)wS9>hzV{#I@)h6c1ARN&h4!nCRr`VJ zuo>`Aw85^HKH`(t>7#R43P|oEeMj7e7it)18GAzGm0N5|m6AYSkWM2J8j4RDZa?UM_<>y ztxjCx2lF!q-5EtN!D}2Y5fqPVJwn^u%nC0hOw5ueLJ<$3{4&1V77UOw-YHEG8@AT} zQqu95+FuNxJ+>2_!H5P*yO-(QUr;~;A^`wwFB*^)?M5W`sDj774b+hT!J1@HXs4|X z78h$(K`fw+?<>lX$(Y31}y`ptrHvbBAUeE3q#0~el z@5I(NCcPQn=i3m!ys>dK)h`yt={tUtv`UV|)dlshZ9(ti)4)8TSmm+WC5!EAp_H^q zz9dO;{N-U0KAQ2M4Hlnh_wKM&bx-Nbt}+=Ml-#!UFM=E-W`LAZFoq}h0kno&wBVa- zD#vhE@C#{XWtK9yB6d-A8@*J!1=ZNAIm!p8RiREr!w26(W2 z;SNctV^uYr4EGOH49@d%nBkxntlcaKWjX8^dTtzgMZX#4{bB)RdCj)3qJHooD>n!2 zV~t=7+loGMS$E|lVGyXZ{%c9a&NVH<<$Vjo+fJG>-J6R~e&N=0EBJrgRFyzh0AfF+ z+U-)t!LtwAu6O8viudY^TW}@5Dtq5EuXgcP%QB|p&7Cwn8ECYK7b5Py3~(s%S4kp# zA%SyMEgAJ&l}6NFF-2N7|6twy){D6LHC>5&>~;NT(NVsr0@ec?nVfyUnpByA9(%R1 ze%1lq3yMw&Mikh&syVKhO875a&nlQ?lVVP3x{CaTPsAJtQ~kZ3uDYSCqLFv$Kxre$ zR&}7kI7c;*S|Mm_*N%g|u1ksQ^msnWRk)p!~Yv-;FW#?WN+UFb$jv0((BZ7L= z8NtSv5K}(A1uyf5xeJZ;kL0QFyyG=*nRNm_sd>rH5#yE!Uu zknO}h!c7164n-5YiEbz7Hwbbehw%Ywv%FeHe+i!TTEDTUg-ew5J$}W6B7uq1xwxtm zfe}-rz8OTVWn$KQ^g5w^!O9k94bSzsE*L*#tq?(H_pPP*Q3j6Ki3-25A(3gnK}-ND zs3h3vL6lriBdr3qV;FxPCR3#xTXNqzl1!g`WOIcET)9h3+1VP@ldZ)|ja@VQb{HOE8uyJv0) z<)4E7SYT25!X@lR|DtSnQ42{zTb!hecJ$-o1|_M@$aTlTeQ5TRzV^xplu`S6Qm<&x zT08UAv_N)3$sO*V=-k=o%SkL==j`177Bdd9C{MzL!W;o zLNKTveu7erAzpP;>r29605fF&gW!P)wb1&lXyGgS;?=s(g! z#WUBRG#)-CoV1$=K3SN+ne1XdYr$2hSEao%^SwSG8=)3O=!ke#{GI0DksVSlg9xAe zu_2E5bz_7r{KI6!4B6&pJA1=qbU$7_UVvC%)@e%QL*X^BV7=iR_^jOPLY827Vo|;P zw~$}s?q{NRAxbuU1!Cbkv&-^Qc5|I)6zEa;5Vjo1p|Pm{tH1Msq`>2D|_XnZ|UaGV;_k%j# z=|O-LF6NMSmJgUVFiU;I>4w#_YdxYVAZJHWf=#%ke7I9_+C%@DoP2w>xQ zdQZ25D(S2UZxKvyz)~oU2)pF$mb{u3REOUky%G#$Fsl_K3d-<%(r6X%Vdn-^Hi zaSbC2SN;F(S{*o8E3Y@&@2f;+7E%z^hp!WE5eJ>~B8br2aAX^@VI5n&`lzBF^-|E) z-GryhQ6n59K}<$iiiKYRtQ9<987%9cgNp)l>!JHbK)q&Urmw|2HQi|i%h|H)`gC>2 zs1f5$rnb%kDHb~UgPRsitalOUi6=DIMH^6}|*6D+Y|vcr!^yCv$%C3G2k zp?f~S6%cP3UGz*}-Di~z4?MgmRQC-el#0DU=@pqTDCT^3jvTeA$O%J9GGfDYl({24t_sR=mP0M6#SR3z!LU zVG8*!0dvxY-8+;%=N(>7cS%c(4>@0*0Auc@gg|yuS%9lHM5ZzzbPGLqvo*kNNh@W4c3$;TD|)26we?KRkjRmt{y$6EEFC{dkpJuw6pMJK_?A-ADL z&h+w9xm4d=d!<`d8v@Z~Hy+-*_OyEZ{`Bkj5&&{~p%=LzbpaqIjhV}iR?nh8Qb5Pu z$vJ7ldLXW>zkBx|M6LA18Cm!w>WY5&Dj;Z(A`3JJuzAvVsVtrpwFNLhB|fzpxGAp2 zY(C9wYFjxV)X3=Z7?p@D2NqbUJ4jr6Al2OeL16;V(~_>@?fmW{6J&ijaaz32+O^W? zyyeRJb0fE$DIcywrLt}ypayp0V?3Br3S^8JTXW75Ovk^P={x&dlJdO3Dx2w66P+&B zQ}T*)#DbqV3h-4z2N`7@ae_v{5(ts<);D=(D>mPovR?$A4>?O8 zJrfr$sKi>Tn`IymD=O-j<0bP|?_=)5nu21Jpef>$J7;2-HW?8Kut(KLOy)31}Q!GtJs*oi+VC3y*z4pxs&qcSG zGLzvFYz$VT2K!cT+?eI45w);Z#H<+^2S3ML6h@1zRxRHFT7#Txr$4ZL(IeB*s)O2n z$n)`Q-E0K}d?#n{zxI73^ZKsw4o|1tD0dsKye~C8&T%Q2FbICe#E+r9%Ib%=bP4PlW+AZLfR zE76rtRzWa6EW2=46SV@mEE+yU&#Yk2Dn*>eG>26#7$7&$31UgBu}vVRf2_?R)7C!h z#})PZlCsxg{y-D0zM!{V6P#`)>#AtWP<;YMYq$r-mR3sqc^%mk6f%VLRxSDa-9W;t zb0Yq`MND%NS6{x0-P3UC#TPL%Kw?Fo_7vYlk0aGz*M9mrQr6atXe_sP<=2d}bk?9 zi{~B0>`abISN82s`i4upif1_5T~dMH6$oe1S_4bT@nN=%{df(qzy{?UF4t*>{+C?? znRnDW8LH`Yyp-_?f|IeQIEFbX+jT9pZlrE^;zF>%?UG$^*be2reDtqz#WeJKs~aEi zR!@;_^p9X%RfP+hQJQW~J=e3K*pNJ{&fNR9*O4ZgAwQ7A@c#j{^JuRRxqnfVj*nXn ztiF#6OoO@%q1}mFEoh|lGzIaWDrP*p*hgX6KE(OK|A&4{}t9ho$X!wp_5v6c^6o?v2 z$3+1ZG!aiD*;oo~si;=SG#53E;LP&a^Ba++5>zqWcRtG;gg$aXhuCG4Z1&0)l0O{K zbrze*e++W_nCn{AnJ^cTH$M`dy{d*XKt_VXLy?g|<#Yjsos6yo!*Q;75xoZ^Ge)&W zk=&$$KXI6n%r91AMh=v;WNf|B;=4-R2a>B@)@)9w5&O zKGj(Jw;p_peI^*qJuqRjJiMuN|0NlaG^WnzQ%iYag5yU9I2^6twoFNd=<>)2+qx_q z+oO{NnSJC4WOgWK^%HbBIl>nt=^J6(FfDeEnq1j*bQ2gQApq;dJbR#i;ETyF&LS_- zteZi&`~%H!U;1@Iis3ezXe!)^TBlTNe3f0HzGN;|KEgV+8E&s+AIVv*EA;hE@jRRg zMKk@@)3pPS(BWU-HW>bex#C0lm7LUn`6GB&?ARx;03UMW_@Ip7T)w&9^-^dP5slzT z=o_79I$KHFUXk}0j6q|KiKq&lf*QyjRpJS*FI5&gJpJ6unGUns00Q8A+;6Wy4JU!N z_Nx^RmhMT_E(1djWv!Kl2SiH2lKJH*wzX^{S7b!n_gx}=&AzwtJVpo!j2&vL3;}i|phcUf@Qi z;_><~1t5~~C5Jpc(8sN>vlt@>r1*qmiYvL5-fh-Oozy?S=-0!GG&cc#zRiddNMPme z1WMI=IOG2cu)m}sH1o;^26IT0lW&T~@z`y$I|I|p5u?V@NfxZq$%v`?qk~`rMmkP+>^l`RT6{;08@E@W&ed3%`BLB_X2)C7_usM2oYHtP7Txuhh5iNv@rb7Vzt|LrG0a zU9ei%`%9-*8KG;VnEE(ru+&W#p3y&}_(Yk3N!kQ@ZyZ~!{rlw(X zI&l&}HkzGx$kKVI4H#6;tUM?yUA*(XZ&y^FOx5eIIVQ@fewbN+T$wOT!;KFsNC6d^-l=KCv zxpVJYlwYq5azxv{Eynt^$t7(}QrL)ncs)PKpm0VD=gl5}-WVitso=Oc=B*S43_C^~ zFsgh$COhaQS^LhZNxy!sZBHO<a()8BMJ+ehNIWy``s5P$24A$V<{WGT#S9pm@JC;E> zxmENmMz7Z?3;*mZZ70eNffOG1PgL8PZSh3IxuH8DAfXG1md65bUW0N{?y4fYg~rm;!hXdon$u8kO{MHn-R1kL-1J5(lm zj{taLwJ{A7;s_p@pAVhugjn%XwD>VW#;`6~2bjpJamJLB^GUmfP*R~cRu&}7ruC2i z`l2i8zsXH5>qV}GcQr;VSQ7DR>#EvsfM26RJ%G3*b!kOB&7F?(3LJ(Gqspa zYWA}yTxH4Fb}i~U2>w4bWI5c=15N%jV;@yFPDTpiq29Q4D~3w(stqexhhxm z$Bi%>B05aM<+sN6-125mJx#vRmG?9nl{>V5((iZZh`k$x=JRuGbr}V#fuyd4xec&2 z2>aiMla?1-zG@Y@wNiKIt?}{@mCi33Bg~FAqX{hiNHH-J4cZy?xpD+i>WrIEZTLpXsTGoxi}F{i)9jDSgj$kf zRD49RSjQsIq0sObu>EqRw=KbTM<2Ol61i7^sq?njvMn><#QzqxIvIO7=lW=ePq)%- z_-6Fd?90<8EO=zLukUCX*Ap6Ywc6plQ5WBQi!c5fA*=BEc3IU#ltMh!{5QbQiwl`z2eer{pg5Iu>1F*8_2tUzfHRC7&|2J++x zzk2&ZL#s*D{<+C^8GZ@Fy(d_JO)DE+nP2s<_fvlq4ld!`=71>=HpVNA%{fb~O2^=O zaSYAgbPOT$1w}K-DX*PI&C#%=$Kt&`FQ@xfo!^JToZzeTx=xb z@&A^0ie+B)6HGTn%VnfBjUa${=;+P1CQh-8&fBwvI4pl<{my;qqCev5EnEmVB<|xb z?272f#c^eE(?5SSNFn7Li;&xB5rt$vv7|iHdiD^@XogmAwl*NT6hkDK8g4ll_AhLy z@fQ-qF!7tLV+}X1de_oH+}zzycEo4}q}tU`(1iuMRF?>QNT`2PwTMF7pAwD^dqYWX zJuCL+@^X&5tv87gPNt?N5v85jLL9L{4W}D= z512FIRiDY+e;5KP&l1Q7RZ$??9^31zP+b;(_J_q**;7~xt9RwBBLHog=!Ubu8lXkdOEx(F7mcd-4LVH zZHlbKqYCc}f$tvWHg&`3Q@ei9TB ziz;}Y;UP576egxt>51r4;!fM1cPef+G0@>-Mu@mA1#+RKH^1;`Hrml=|!wF{ybKl$1TW8i#O)CoJV>dvDeK|u2B(`-j=CU~uk(L8FP z6br08ujl#_D&w*7?=-Trh?Xnr42)JYOg#Qj_VrB)>bKG$?%vbc#E4YEB(-45$bJuL zj>omR?P;ESL5|-a%g@K}^PuOMEWw!}o1YGOW4J%sPB*kKonBk;ZY4!WBv^vL+}-Vq z2}Zygr((q}NC7X0sw7VLjDsx@HKDz`U4p9kWtH)*|L6jpYlqA^l?<&Imi0C;&Vw7= z3VevOB^Z1jH=0`U+*bXZIon!;p73A9f3W3wwpT`({CFR_B#J>H(%!@C2V58FdI+gf zs?~J%abU_SXAEEXoUs|}T1H+h=wT-5I{ua|k1k+9%+b7)=Yd|RA^MI7BQ=C8eoqwf zU)`ii!8c+BfrU}0dp=~YHMo_z_H;j1yjHd)@_eq>m!MO6^Y|uJ zvT5A2$AnX?u`Gv}941B}C!Emm-m4*CHU9Q&A0q`Sa{W=Yy;R+BTv#p2<;4xb4~ay? zKxf`g2;Ag2AQ4N8X(M6d99tl7e;ewQ;}cfLf{N(}Iz|=XhTjfNb+-5d*8yr}gN2bN zS;_$hr_%=*6f8iz+gkRlFIUJ=a!d$M8!_#sP7yar{}%pj0T6P!(+ed*wXB>UPITM! z^;_7+Y-Ch3YD!6N!^xyKh^Lm{9ubwX;W@*H40e)Xmt}S>Az=ygkB5RDnxvKu8lwKW zqtW_VpN03gro^KNdH1>TLl8j_SqM%y8tL?Nzu7u@ZIx2;tqG}X>Pa_k72?2JaZ-Bx z)>vBGSEl0T*nZ&XmK-8*C6$nf^Uq8hwLXyqDeZtZ4YLzXaJW(mkX}7c1)%f02sf{x z&q~1iIZ;&I{F>xdNJ?dV?qVIvfTP?W#S{Z|jnmYSs02ZRLvofVEk0R{KJ{F+arGc8 z?sDo&D|^G4S~R->i><=(T`g=$7=mrRgx;4%Q89n?8JYGtVt6@BjQte3w4cx-$e;Z4s&ESfI<4wtQ&1jvbac~u#9U`{ zq}6YyOHumgjW7doSo$dT=ywS3BQ_dhV2;|g5Nf($v^;Y`BywFf*xD}E2Tr<8U@o~4 zjkIgt!D|cv72EEE4y1~{e#_VwDqBzfY|{t;G9Tc(7qS&QX?Y>-m5}NJQJXYruFTL9 z3Ata#T7vIrm-r(Pokrn8T{@i`&^X>(Y5;@UP(~UJgKS2Adi3nVIu?Ib9EEB3P30NFnJ{!^E`XObl*^KLyw6AeeoI*+kF!3g)B+^@J+D zvK%a)r30FvexN!uofj3)ETvNw?L@*mdUzmNwur%L1Dm6i=LnyS60eC;3zm>#7Rf1Z z0?zFs;LEY0X;oQXPQgd+0@MtB0yIRm+ruPDBT)?rxzm= zDp4bDgeUps8IP1GA9I`-acdP+`&w0X1GZHOmM5n8fto@VF)BxkJ=p}1D8-!iJsAm- z*gu5|n$k*u_6I#L*aBGkzGy0ab+-Cgjv|BwfJ?i;4EON|X@5_3zaQxcy z5>A*Q1S|3|V}JRnfCe&kvrY2d!m$fuT&Qmye;|WZ@2{$i7)cI4cF$U}$V$Jd)KQiW zFW&%)9h9jaWBLXKrU3RUZzWMww(ji{+|c5>l~;CaJWoGQ%zm0@((GMCvi&MqRnmb% zCn7u63~(7r%eq$W<~J~2Nt1&c_3w-vmF#b4}q`z&6hb27P5g9RAt4F<|O70we6(j zR*)nFwPZ{efKk)s6|qyiK^{5g(~mTTqvkvaq7IFqS4uY$F;iDPZnZsZ*j{-a>zLtZ z0LB#%Z$9mMe@TS0*9z{27=DURLlQrh_(kqj({wWWqZ*#*yrqO~2uZ*uT71@BMrX+M zHk&W4?;=km`Q#zw;)5zUY%A4MzGslqmBaQ+Pip&hlU-i?+?h8{6_D#DKWLKO_7 zw0T0O1`2+(b84CqPSWw?PjObCH9=Eo`!k2V%CyGxtouy2-ZCZv8oqrl&>ymo(1)MM zBRb)HOvKiBx7rVM!;5Nf>K`}%$FKJ+M7wNA*b^6CrS>D*_=l1ZU-h~xt0bZiSH^<6 z;Y!|A00Pbv9oIg7EZGKwJEk^l-;GoO1i}*6;Od@|Rx82MLHB9Uy6#4;(%fwx9%sK?8G$2#JXOkO)6 zI=R92?!Wwkid-#;UDy{j?|V@w9WC2}-8MPCv)J4Sv%h#(q8i+ouqga!r^;d2LH7){ z=|SN3?XBQgpNIkf_cuPqp=!!j_8JjDJ|`z}zCo@UG!z7QJs%Ip00#Q^r`|zB@!cKK zs>v_iLw;Al&0&&kFHDTrZ$b`7{7N3r_sYL+fYfNL3>c>gw7C*3WzVIN6c# zSvF}JrT8LqwaJ2rq`@WLB-cQBX1_eMis4C_tODSz_~6q0{lNk(l;CVu z{laQ!+*tKQ>>3fs5kJf8gGn6dn)4M4M3rXNOX`@Avv1LeE2((0yWXXc_|mozYfHLC z;lIS71K}g8#vQBOL6ALGHCH`k2<|&JrnTbv-4ETwVL(MtqaV0ozo{}C<42>^%Vvha zC{o;0x>~X|dg!eAOPNDKBM~q%vN3Ha^EK9dZHoknn4^_r53lgmA@Dr&Vqx)fdy4jG ze!{#Nr;IpdUZ+oy6HAe>INKEjs`wJ+Yh~LgeH>zwA0BsH4o&rT^6|O^WZu_?bvsOo z)zv6Sv(xN2mvJc>tIe{>Ako>v7a44*jXWJmD`yQn03JpjgyoXEc+1=m96Qd6E61W% zT2gwdzB!skmDWKe>RwF`mPVAnb^Y-aa+@2Tr{HDrcbb=ZGWS|XjcNdAh zRUuqoY!hmf^4VILD~{bs@x8pb#8u5M3c2Dhfp!G zUxX7P1K2b=!siS+Yk!B>VQSMaqYmC|x*~OzNJy>F6uwm}6gQ4R)#qwyovl>sRMJ$0 z(G0fp^};r^e^C=RIFx(uGNIA_>(mWe!15~us4bxSK zRzQOM|Kh7=@X-)Ik*9IHHZJoEXJoo}-1V}hHps_Zn4O-Hs-+6(my>vV6-NmwOs@u! zM;>;|aS~}4Z9FeO@;UFn6G#Es9)#%BUwIUbuV@O2+CnC^`p@yvd-Yv&Lh8s@Zf^ZS z>Zu=5{L4VL&ivfaYQNK{@f~II`)tF5hA{8mjaDv}o907tZOeT=T|G*zV`)>Ckn^-i z0<U$U zXLw`J1pbO@;tP1T?WN|>D#hxReeU}W=W_2%ZIadF{>WFj^ouYW;(^}g0li%Ex zB{A@FD8Ie=x@p;J=;cp=fi&U<&=Lb!znGq32G)9DF#I4n;e!-<>_~hlph9gP7beoS zsq~h%0<_^wm(wjO_GS6EBNCG3CTgn~A0qjxGwMC#jlwvtVDB|R)@$O9 zUni&0dQD)4FmN<8oMBNDzMz?oTEiI^=-WLzGH;5zwYWcCG+q{c%<(0-pbQqmx6r^q zVzbySN8_6%{E>*&wRjrU3^no}?AIbgzFRFgU#3~$>jE#S zgnS^{X4W5ud{og(aDZ>0%6k&sMx&R%Nbn7`Uyi4LbvC6!;T>veLEO@$nCbC1zKrK` zmOWYk4%`n3=h$kM-L*Ew4pdSK)~_WOaOA?HS0p<6KHed9Rb}eWZkLR6X)641xbawe)DO^&4VP#Q409&sgQ(gH!pQ_y{pT+;kFeF~ zEpmnNa)L|C1L{65%IbwKm1&zm<5D#hdO*kF$TI9HLw?D8umpI=#)^`U()@nQe0T?n zJ6y!(xWU9kB?)>oMg1rsyO&!nce{hh$rKBKI~3kekysMX(($12zO{cTq$y&e>b;u;F-aAKV4qkR}wFS{DAZHRHmr5u#cj}_^2U~R;# zDxs;^CAHA1So($H7jn!EB^{zf*gH>_vVH1`P?p2wtSa%(SU89(zrUxE+zbn9T8Llq zwRauTzF)XRq&=n9PwXDv>4i_uqn!9@N-z3B3 z#zo_I5au#^K6jOn1u=_KhXZ{5((I}Bl7?abmN@ffZG52F+Mk$KJEu@3UHaOa0qMyQ zBTp#ewK>tx4Sp%00wXY>>~e?Y7TCbeS89KX=@3(S8}yGq#|oE<1AgUy_ZhScJF7+N zXpW&mxWw40)GyDU`2OD2cnGiDQ~@85qodPvZAV5ShLe0W><}Mo{au+4QZ>U;N%Yl2 zxZS|$jmez0ZA9t!+AK51@OM1np{y#3CvHXM-{4AYM@IYrM!+tk{l5D5X-W-53VgNc z{?DU9b011J(jLzJJ{^q1;pczZxmzs7%vJMM06ceY&OjPGMhc9#Yl^hYzcs0Fe}!#*0AoRHPJMdA-w-pP0S9C#hIk0?99+`Uw8k(C`d$*_{-rerBU^%l zyI(7-4fNgXMG=>6{m5dv6BJ}~=32Mtg8Y6=VF^`#yHS8%XYc=U_EbX;79FWOZ034AKhoV>`$vPuR#wx3LW1-?Ya)xdiLv+ASP$#+?&E zxBg#Xf&N>3Qt0iqKBPJ&nDq3lqz;lJ4A4vVnli^TAzknpR?Jb!=$n>Ts9uKDEbG#a zkz{$FJJn%dCw8;0eG(7MzkK^zw$=_72_j(-tN+h=H2J-8MQ4M&Z|&S9bakIp;{ahW?m%)hn#HQsZbMyAg?d`8VZ z7N*bR3~H(bsX=LpN7|}oW;YSk-Uo|Fk26@Nl{wNc1BuJ8##(Z%v; zPtIIq71S#W1yVoCbwa{G3&lJ}TLE=epPR@Xb0KDn?-vMnmU{-dnG0Fssa_u@f8&^3 zzkeE*OrnBm`H+u+_dSv3nvQ`c{DscmZbYkNR8<@P#iiMPt?_8Im1^*|<0xvooh!w@ z;GfBR9z@-EYV4LBr$z-uOhc@I_KT;lE`~FM8vtKlb2<(;R)&p~n%(ZcrA6JM^V+>D zD2^q7mIxihsfh$L0uu7@wB~PcJvD%jp2V5AD%XNt=&GDtCbyBy4b*^>dTJVb!LbyJ zTC?rv+?68!_tKhd_uKixXX1H3Hg)ws&{X(zUcNwDXl7r*Nhhg{kZ5W`i$jJ*fy?Uq(Y^ZY5rX!JRsNi1_qS8-1j!6t0{Lc6~n&zL-D4) zDz;$>>wt&8`(ui~I(DEYEMu-_HEtf{aebat+w7)jK}_$u$}E(n68mbj^26Wr(a{nX zs&V^Q8}>Z;k`%5uK~V4%>Ey+$yqV5mFPPG+LI^Y=mD$QbU!(_GGHBP|y`V+d&l>UL z1xC23?Fl{U=YDqDWn9daQc$-)aiT`K+AM;EhxxMF$eD$^<)wpCjg4c+ZowJUj~Ovk zbzcAg0|CA2Adboa0NdR%5(uIIJwU?0e_J3}14BHny0uguwbV(l{tD>x5`si7O3&6=k((YD9ctd3+U*FEe+-{f>F zgmQoool_GzQ##hF?aVYC_-97)DL2;7I24+)Z3wPcJJCP+U6p}c0K5q4S)0K+#1bZ zadnJLt~ZayN=`&UvET}$RdL|-A^NJS%}j$yCaaH#LNgy**Cd(^QsrO%t;H!;arCxg z&tLv$UEh$URrk}wDTD@ckG4I3nZc<6G|Dzgv?eJlq0MIn54Sgx_Ot(H6bu2_RfDod zi~h$Q|C|i4x>=td8p5vFuo>k{mFUH%3xL=x>#Y-XSu!tLkjjUK*3>*v66Ds1lsEzE zYW*f@vEoEaYStNR0~NX%SDcKoCh>L;_=>cj@v*qDr~q_vw(H7%nl~3CEEPext`G9L z^a{oc0`mqi1O_6K+m+Yjm7>@qLsmI;V~KL>L4>pX_^q+&9s`WIiLN9ENySazow2O5 zit9)|CM!hm+aasF2l3X%b&Er+2)1EanK4=N0qI`{V9lN|S#gG%6M|0xd$b6bxrzsf z);4#4I!!JQS!)P;Luk-nQ#4kh3yoczxF`segrOb=k!zy?&j6|mNBYR7UPEU?51vz_ zZYuxkBleb=%wRZOc(8IDH-nOQuJr3yA_+LrE68g2HMbtAHqE zW!(OJR;u{B9%kHKtPn?keG6R;@e+WXuYlhwuub*_MTBc`@?3}68wP09iCVS{9I1_0 zeAgAWyXqgWY^SkKUKs)c3432wpzJ=YG^`?W&Xc_BACemr?}YdZ9;%YyfI`AHjMZzv zW7`8*4fFvD*(sB!6r81rO9?M9UXe@Z)r)YfifS0{_|nle12mO`w^jhzVC`>k*Fi#0 z#B5iPMI3RGisBk(f_h*CWy$qlv}hhmmj|O&*`nx@;Qg6arHgVUH~cOig7fc%wW$L! z^$)7l;73D>zE4N-dzJ|u()f2(Ho;mtO=Av#aE19-kd#ff6M8kepsV$~u4SEH_V72% z)E+jl10Qfnkge-+eb)V`LRt;tVkGSna4Ouay+tl~c6RI3If_@d0z-d8iqVhtryiGx zZo*!^D4TQ`OdjT21ba%7o{wLF&Sjx**4Vbo8=iwNzj}zao51;O9d5vlV$NZ&E1iOvh zD4dH`BIfCi9pG7p4O0E+d!k_TO^r!P`1PCp6F=XO=iEPR)u)7f@q1BLwe_^gZxS=M z&iXKhAZ||p_Vy~EujkP4{{dKV59=Oi>OJJ#5i=oh;Vg=ZVMU&*SLr z=!}+ii@?Ht0w{|HEW!uKO)mto6AgY9gm*Mz0LjwHnPXb zGNc)K0py-MNwJ_=U{eype?#{}FdjY*V=+4vCn2{oVI(%4e#QRTYaO{3_tKx&InvSz zr)-*MnXQ5cPT{?K3Y( z2}U%NKfR+40s|b$Z1x7PK;*5`SIV8VxvS=lJ{gz)yNHAUPK(Jig}!Y4_Y4==Hg6P? z$;0axatlYNdc9Np_o|E%8BG{wAp}u^Y!8Txt&J5m4R0T3@*4+fyw zraj*$PdL#NNIxcDcC&xzmHn~pL?IG|0+mFWILCF3t}i6Bawxt@N!uxyl(|``(-A1b z#9Zs$DF%Y=N>q+KdGD44>)2Y&h1m-3nPYs#jY>h5G{8C8-qTYHkXAOvglkx$Ih@&P zkjKT_|zrDcDbJS?!3q>}k%R>8Yd!STdG007vLH0QAKG2VsAT@bb+ znuQHMJdHb>QXwjr7JlqlniGjzXGdq4{f3cPtsQBQN|Smj$Kn9MJZ`D>V8ZA-^vb}H ztJFG^@yc!|2sBkEU~N+B23TQWUDC4pE1B#n&JJ{iTMtx`ET7}RELN+g?E#mLKFjkH zU-?lfr;Y6UX$1mUamz|gCL_KcY5g>5E(QjwM4)LBt+FkL@+M}AV>z0kQOTSt8CFz+D|X5KVL zk?^WGw!hA$0N~O8Dxt{`raYp4pU>KJLFA9a;;Ji}7%5o@8jb1YxvrTcr%)p-d82e0 z-G)_}U;mFMDFhc8N>l&<0|DTaZm}oOwS{wF>%d%U%@CX+dlR|2=2`bO1U0sDy13Qw zLkF3`zyJVC;Q#3_%O8%)4eMlp!5^}ebxs^&;wES6dfIc^&l+%@Fel~Qpfa%j(`|bg zIZnjpGY?Cc&IU}-E)b-TY>|>_yl&Ou`)6p4tjdUv; zkkDp6bBA@NEx?OZNtV~3Zh}uFxMc<;&!XZ_9y;9XK?JED(h|Va;4blDKfzd)UyI=m zQbCXc!zddP{M~WtN&W)X_=sEjTSVKw+t+0kpogwM4C+UAiDsA|R~P&LM|@p0Q+VGZ z!k&;gBMx5_SJUcGG-*_(fxUlZ(ZYpYeO|VDWF|`TFo|$;;_L#Se}n&&FBL=M%APXm zSdp`6-?PB+vV_Lk-q7#QLyDcgH>^!a7c;DV#^VIO_im~OYtk% zn6cyc+GKiV9~UxU@>d}fC2Gef&ChbE)08lgNtR1`GC|w{lN5wYUO4#-Sb;+3OoUKT zj^6oN;E%wYp&iX4P9Ja9cKumL7OX{wdbWVANxhU_N!^Xi5-^_;EdC2~^QOz{L#E$O<#Sq}MYTPrDgwerho zQ9lEgJA)BJ*iakg3A$hQ&a)+*c+bQmIjeE{I*Z~8A05X8%niqEJT9lKXN)K6RAWwr zif_^GT?Z4!>yreyCXAR-B#bp}CVq1Q=ckl^mJ!81>x!RLusf9R+eMi^Ln*W`loWab zZg<;IzaJ#D)A+*V4)(pmG}``&^D<)!Ar5i0GdU!Vt$%wjn;-9OT_q01TqZyDP)9`|ywCw2OrepXxPk!& zrFcUYk8lgGXDJ`Hp3nw3*WqZ4_zA$HXmaH1YS`ItP*;LNy^Jf$K^>wb;YY|a#mb5V zx3A8VO*A@lK1pSjs}p7e1HoOTqUNbe{ShgSbVum3vj^XO&(x>A`mc`omjc~Em?7>R2b=+cWM zmL3aGv5p&UC1b)Btp~>^+c5R-waUn2vA4wdHIc;o%JKw-g&7v9Q94oy^gkASHm{=8 zFPb~te8}%9LG*;au_LLM^M!bN!ZM`yrbO+<^ZZ7JR$kR#GZ9M?-Ml9`I$?y3*yR$n zC6e2Qlxhdb7qwKg45tRP_2B)+fTkCu1t{Y2as^cQ=0-ch3-@O{9A|gdwp*{~pm)nk zK5ed~yuBSbb(>77U}l%@0=IAc*$ZH;I)*fAVvSH-LB`&Y1GgUkh66E?;P%1EUG$bM zAGc|@g8PTww8`5`%4TjKI7}58y%>2dNqx#FaH0Rs$aulZY(Ibxj+A;P7&W!F(9Sag zWq4Be?0N@@iNqH`8s|}H7(=ebp-_@sgi}1OU1W@)*ea^8Erxt^^Wn#K>_t))y=>6- zTcW7uB^`omLG?#4wx?BkO|-6juh2peD}h%VR4hQxEdr;+-OA$J0AOMakwT3FQXW@- zFFN0l%>o=e?jmYT?-yimp31q+uEEe8(k6buJC0Q6J_I4c@_F4VUj#50!nu z$iXIW-^4pNLoeZtpnU1){?;~q%m2av!)j&?g@VZ~6I1 z?K3F+KVO9YGgDX!FU~c)6@$vwaO%SN@C$727LE=$Y)`bCWAPgYY74U%cGlqEasoOiaY@E95x2$JO@THRS$(GSm1LJ><<0kQsFQhq63e5VLv*WC>`>#&d4cwHD zNP?8i4i_V+ADvVX)(33|Vw8z|H;X;&p^NY_FUkt^VO~HzDi`4^VLYBRsl*aebUr_` z^@U*TM$gk>Hgs|uTg3*u2N8Yv=%EWyIfAfmZQ$bpE@jr-uLhxCww0LXHJvZ1YcfVKFMgYealNJVliF~Vu-lg zzGFAPwg3{N-wBc*t%`Id(;63iMoVLjP|Ah9dGehYo{7p(PUI{e6dx8?JRk+Q{aMZz z*SN%B12u4u+B@X8RZ(PTfp4nJL!FRvBH~nFcOY1U*zLpg2LBd)a@`Y589x$eizjJ0G!p)Wv^j5v+L0m;QOU*jg!WUwNBFPh} zm-Pa0H#rt2d;e_);6dN4N?}owvM$@1PM48|G5zVhFfMUM?21{QuxujvobSX= zP@itdm{u|)9EG(ZYzM-`a({HZ(bN^$Pb>K_ zifo0JAKX+a4YBpoFq2yeVS)&mg)XY~ae5A5AaN~y(t1yW=+*sx`|i0%^0vXCOeuqX#-_Swp*rYF3UrTQ}5Q70> z9WC~{7G4vdJ{_~uFIcJs;yF5DRoh6Vy+ctqvoa~bXoj?opLNxX)vBx-p4!%imr&_q z;oP#0ukAOnWIVnd02Te{+n13H+pYuBAD04{#_V;`+2G20Hd3C9iGJ}PS%B`MgV6t> zUN$ws9Lm%1c`;*~lVHfjNk;kg2Ex+L@<1v|XSaTu<+fRdIWtT{!~27Q9nm$|4Q zz9XwC6`v}HvYElCclb*tW8VH?b%tJ+chb~C<@%mw8i|LAaCL!p5gT&U0LQdk z=`E^AP*K3}!H-~Yp)jA+gj))H1!1hX6fem_03yPdA#K#)KY7uyFlUQ9pHzQ~^m)Nb z1NX0wG4lc7Oh6UgHBJzpJ9)h*6ufbF_Px3n;6}$IYEkfj1H;_3W)z#AVr!c zw5Zp<!z}bfZWzq6?~A+T9OY>Em)=4 z1H&@kHWFjn5lY&OB{?GaK!-IVRX{xp+`dfm_^W(HC^hsKrZ^*Z2U%!2llY}f?A5ZJ z1oRNR_l3pSoPV}FN}&!;-EY`E_0*UP|r>2C)t0iLXlVbr+c!_ay;25o)<_^kx zJW^XKjp(Z~`1y*Y#$-9Rnr;UbnOM|J)??nKc*b3LdV?~P=Ff!LxdsQyZ1k=Q>TR^f zWd};EsLS({$Ga$9x*}xb<(b-EXt-0CRH>3h**Do<`!tegG8;k% z^~;9*ss*u-HFyR8N+hE7!Zn33i4aT^7|s|lzlSY}B%itMR(6owNg)=$#z)?f(8ccz zS4yRY>V?yn5EWhIRA;ays}k%w!rJY8GS`F4FeHWr+fP8z$%J%+j@pJxM~Z?N?H{pM zcB5&0lxdh)okqU{pxZrGo@WwUEm8Wh)?-_KjTciuNlysYYMxR+t1@H%%LSl$114i`l;~jt-9V)yL`G;Y$pSDZN~R5Pd{L_oE!$KZT8bD1y3!lo+^{?7Ntqu( zb(@;t=~$T0#tSN8VqJqJRL$kldV>44kZ2UA3S=Ms$);tnw=7zTz!)Z@=!4jzCNX2)mE~3a!#MjTYyzB;!3Q zHtM^Eue6W1=X{bG&Ig&I!q{6uf;D_Jb2BwJ+yKd#iFhBcwte6W7AX(RcQdAe|Q`vGCcVg72grwFMu zhGKA={sOTzw4Y>;j#;$iO6uOZ3VB1Z6J`evbHqdH-Z#Dt>+PnAcd7F-^fJY-+~)>zrN-94_KcGSugIFN z5nwix8vbm)qAn@r4>#orp~gncmKWBY)K_#BAhb5NgG;yf2b4$R`sNG%$Mgb^NS}AEBk->@ z(*x!;#s`?ZiLL#!pjm=#aga*azH@B+F}#sN_vYWQAJ3J*34f@si@-MC)1YNi-KLka zsH?%n3VeTXDPt_wkyb}M+{))ArVSp+?AKCH^s+Q$vso{R^9J8NH))PhW$yh3Pv?nB zl>1(`!DKBLgP`xN9Cjx4>7S@X78);HshZqbi#wBnYmMCA-hwHf^Sq#E(@Mk<_Ps<1 zhgiZ|e19&UQa8&@VEtPO3GkU_%QI5LrzHEH&igJg7f6apjReYQuQ5__+Ez9pT(AOJ zV2=Aw$*4XZkPL@p<|Yqo9yBdb%m&56cxOLnYzLzrWvBy?QcBank2QJB9L%Jwt%=(2 z4QEjfl2E4!I&l40Sk0!S2IRL6O0a#)jE}v*Ez6~EgxA%!LJll&fj9|)0!{aI72l}h zxu?2q^NVnA;p96z60fCH-X?6Vl(spCcpCFrCx`^^@U^K#cP4=GogYW@(Gr}UI~8*+ z;(N2zDadA|4V(3}F2XWt^x%P0#_ZX}SjDx3>b!7#X||CXyov?idLaWRoI*5L{|tO3 z+x^a`nopGJuRCYyrBc4>L|Py^5-RjIJ^2oiPt+r=<1DuMsNIb=y-e2d$?BAB>;TFXm~B6M3j0jH zd9-0VX_7CmrtNvFU&k$3<{!lPS+jH^Vu99yi!sF6$88u8M$1;)0~&oBsA|fuNC6bh7FsJ*_sfHEFV#8n$R2_f(uDoN3k*~6L2>h)Hm5eSQ7)g^ z9EYl4!>?4iQVxGrr~O3O{l?(9P~dxzJY-Wzesq68Riice*7P1AuYl@i&L-@1kY~7n zxv{wBD(U!nzhs0?B;^Y74W|d`7D5ZUMc5O@Xw$Hv7~uhOF7fzvjqf=42Qgu_HQBM9 zt>pJD)_~6zS=WzE0>csf`WqQx6qdNHD&qN`-NmwPnolhF+YX~df;NZo9v*|OM5An# z*tAj&CYTwdvFunyp}$)46#RW%H^jTA#FG>Kija2wraP?D;5Nbf#VLF;vVy0+9nM#F zb=7vNLnP$7@R(y&N6?Q5D|$pr+luX26_WY*(ZPO+q>7Q*UWD9rs0fWPy2cTC zV6wZw+6oSnW|E76vY%XvCn{E-XI;jCMlJ(853L|ah_i)Moo8Z87@mE=hrio59gg-0 z^DmZWC%nXyy{PriW;r{ z;>kd1S+nkwIy{W*$q{a!k*U9M?!5j@O zEZX_7%~JI%k|_zT$5_ez&9elRM4e2#y?g65=?d)axL!y&~6W z@z3{TT}}4sxQ$$}H4@KdkT?sOGL5sFex>O(gyY=9s}Q3j2db+?koNh=;})MDiUJYL zz00PBp~|CN$_G9? zvOC%fiI0_0jdLhdf!`fEg`feb89Fz*7aIJxzqzHfsyrFeiUng-3ZW#}^D=3%7ahEECHoi1nD;wCrDm2RiIrueW$B}sz%4tl$K zr+Rfxb`P2PlLe1^;Y6S0QYr4(v+g$|d1+2&AURob=kvp_|5!S{U$^Y<*!2bpx`qlq zO9}o8l3UVxP59(y8OM5hV}}n{2KVS^AS^DKzhc+MEl==4R%%hFe9hXh$%!wiU1z|H zEZ>PXkqcFCyQZ1{=m_Zh`CWEH20#MT`Wd(O^a*D>fs?xLe;lV-sE6;I95m0Z__J#b zM!1BC0452i&TjL=Bqu|jkpRu~nK0KHfxrT$&qrUKkrPg`b8=&lH~W59&220{Wh|1f zclE(3vnApg$8H6Xn)(#f4J>3G;jFkjy(t`m6)F7IqbzgDk4ND!m7lG4=QtIircN%#cn%XQ)pDVKyNMbAXu$X;u9y(oqu&YVapmt?E= zY3|C*UY>j5Rx;l~DYAa7Jb}`loj9A%-+NiHo;S$*-G%yS5QwJU&niyzwUc@~oCiU; z^-KT&8*bZx0NWBsidXdqcybSRMf}P(ORZs6p!fxnwk8R#J;E@7df;5rXnMMUdM;*_ z#^(N6#~3Ghj~pimt}IK0gbs4*V5U=IbjIF9U8c|g!ap#NP&EUZyzC03>uOb4X+ZkFk;?&t*H?Oh$`HN|ADUD{@FZV!6E8@ zw`j?zeeTC`Xo;q1zgBw^M^bS+$*|Wl?w~f*D>`CY%biZ2e6?{#fP{h-^Wt!}%3GXy zEx0zmK^=X{I5Aif;=rO&QRyBNp0qnE5|Pp+fNCZ7GYjRZf;7ndlEE%BF-e;LFdLEp z%{v8M#_$wIsikc%ZJN!qVMRl>b>v*v=z?PurQuY>L9(0m<@6*)6f$j^fWJ`au-t(X z7p%LJu;fPHnOT=k@uP$9*kS|t%Qyshem zs)k`hVRzzZZHamJ%m`IT7l@TU&(U2o!oWey$q_yx(G(#KN8zvm$|%J))o7O8Avx9j8@Nq}^_4E!E`O8ql-i*pej7hRG z`iWS5Z-Xk-n#!&tID`bJ_i&hT)JNCH;C?X-N!V4QNkDUY(UIyBAIzhMrk@23eA3sF zv-J2!Bj)R?v030kTw~0zV9J;~#A|J9to3(JZMI=y<=@XZW?p6h3jQT1p_8dsSXW=G z>N|nsDawyzBCb7Id@1Gm75oOV%VdXhz8lCA`z;;HfCO|eDlFHCWwu)t74n=|3q4Kwhu>JCbniEZ|qK)7$8GiNKkxttarf|PVMLMK4@k>WGoWBn1{D? zhN`{NS0-ujf^UjB>_2{zQ3wSJ?fT5d=mml^;SKMu6?3x}F#w5*0czmXItSwY7o)_L zKvy`og-f~Oe7S%&yokWDzem{V;y+>CzpobudoR-CS5QVC(UxP|xyS%kh7;63>*5$fBZ1@C4F)T zzDP~nBuU7|Gd%I^^8;yPTC{~%CcRb0KTL>U!8idm(n)!xG4sbuJqOc@9e=+8MGqDw zyD8{Z5e*0$3Sd>h2+rPf2as}XKPqATA$G6opGf+tM20*5+Q70Xa=A$mmZKLCwlnVY zcAmMeo>|bAF+kVYi8pmnM|qeJp4C^vb5< zJ$=Rz$CY+>zH&63dL*2J4~|&uw3ofmk@x|rsRYMvBucnY!Mm3Z@1hmWC_}2^Z-sqV z1fm+>{@?oni}d&<_Qcn2@#fbd2NAJ>Ta@uoCL~bRXp;#3!effE$WRy!Xo7BAJHb=? z+p(c&`Kw+PTV|XM+VAEoCCBuL-y$rJ`nEM(V*knqAM=9Y(bpsnZnurR?O)i zIQ=J+jkpqHZA`(YRh++4+HSd#Ws!cIWzP9MZu<-e#6{=RX@J2+?$BG%q~V*XOeRp#kCi08GS)+kO|&6Ad_gVP31Tk=3G6 zs=Km*lu|ZZ@)92bqm3Cq#v59H@ow>sZcHZO+-sYZv-Vb+(x{<4Y>o|yck(Hze?|mFNXJa-1HP5*N-LuFEf~;P&1B z9ACOKX^G7Wx*I;{*(Su4dHPT1L<7wT@QV=%OP;PiAf4efC7KZRJgWPvXH$oE5@7s| zWx0~eSlc9HzKBIW^Lp4Rois|CX^7qE< z>IQQ%pN${^zLS)+VRbU3i&;7{O4S0p$R`)p?S+Gj@>U6=jU3at+2m=o)EO*((%-*` z|Mt7l0RSju26;ea-D#2qNjNFBoc@|PV+0*Q5gG>)YJ>4d&0_8ytGrp_+_#b;`%X2? zTLb?3>q;+gxb~g?TxfWZiq)P{wDWG#8cU{b$Nrzi-HnwF0}+Fbl29NkGI0t z%3wA6!-`Vys~|Tyifr`1(=r(T4N;WUAJtQvNy8$efqz~$#ar1y-*iEru&a5`4Q^%S zt4*lTPz=Xb008Svw^Y~wow;$yyRvzJLi*W=?yi)U8Jb~#b1maM=B`&Lyxn*k0tl$k z6V%CC9?quwlYyZApz zIM|vr^D?ej;qb$a}OX>(8w)0`vU3R%n(d@ zt?_oX?g4}OXt{CJ7#~s}Ur6rV3tg-rbx<^sXOW4w$F{8^KqnWuU50@z5=edoZ0(l3 zT3|18ER_6(I?rCiCX#T(dnd2dq~7wMRfHyb?{r=1c2WK{=($C;3OlzFZ$qZFL$Z7+ zlCW{78c+I@;jWJTt6Po44O(47K_&?dURR+g~;^L*2;_ z(*EL3Ji!(6@Qu9SKp(@Xm+AtV2UZkA`SEfl^h|?96CV$pTdL35^xiEh*)GZn)u0$_ zITywj9UzCb`s?=Onu2GCjQg34{Rk$U#{PFww2H?C?y9G2Xm;95gH$h-Z}zQ4WbOBv z1!}{L<}F_y4-Hfoc+{+$h@2*&&F-{S4Z}1CZxCr(2z(+`T>}geC)t96y3GSqK6H+W{?Z!yg%kAh66V!oDT(** zMJeKKgzuS}`66)qvB}()19jqS$1TH9N^|hM0@bE!^ZX(J8Qy^rk)JmE@7fBLsQ!IL z!#V5b@q5)|#7c}wVh-})Fk&GshbecKR9k+%mmf-!X{#*F^+*^=aM(!lrlf5>L$(M2 z*3bC__CPMReG{L@K<|Bnmw#+?e=xIVQI>Am&AWn@SZA}vFy?bkOJL|!00JhBip|5D zkN_bzCN}@9-GsjV{IK{<=a<6-WwGEw1F$YWD*EJzKNbtTy&m;SCAngS$z+p0dy9dX zTTXdg!Sib!jOAMTmoBJgXH=^#cheOXisV=j1qOytA+?T&#QL9Q zmMSP1G8s4kHpy7FI;KW)V$wj+u=;|vC|rwhIpqn_Wrbg}E5)@MbjQ0PRsKE@GvQHP zH>3V5gT+91WUxK)!_M<^|97dzD52)Ta=5ZB5Zrg6tcOzDVnnY!QPq1;QgsQ(8%~t7 zKKp@-L0njnYr^38^xs;dzntc_y8guccCMiVnGY@oEC0VO7E=rW&cAUMOvoywPAStF zY%T^yEaNj;(Tj$NcOgF-;?KM@ci)ADD7g|$Kn`Z-lAUwD7j={ELf$FQ3raEM?c9O;6723e0}$_vFTI9y*t>w z5y&A+!2f>T6D@^r#si=2(LX>nb{27lf;uw-qvvRQ+c1UGC=b@;E|cDG(Xo`>pXeX-E>MDfBzmvS^)8`1gN zO-p{GCREjBYk)rZ#`ZD(L>Au-e?`3wdZw(JNT7t4!S#a`A(|lWMg-g0d$7&0@Qyn0d@6lnhej>5 z;9DK6y6mz3v?+II%%)P`!b)o3-F)5~nl}hr+_{CCH0-sU&hQJKrnF>cUt^rI;85m$ zI3IiR%snc05DY*5%LN-}Mnwxo;qZMN77ijIPO@Z-o&T7Mo6<1af$3c3R`CMX3{8m< zY4y$JIKnIVNn8zJz*Z5^)p~YRhgp%FkZkT$|Dxz2la9jW?%5D&p1+Wo+juWaU1kUa zNNR>?^HutD#Lq^gq(T&;_nv&nkx3bMP1?`#5!;+MOgwsT97IiQKKwOwz47bN z-8)U;r-?VY%j4-U5%=2x9OP*Uvp~TCWA{D*^_2Zrd`LU<(L93ITm-NNifzX#02Qr> zC-O$^{cX=A>pGjj%S`3PJb`$jxicwYD21C$XInQd=kD)Mv^^~T80(>3No92Q^J28! zhGTzzBO|UQaX?nYNoN^l&$d5G*yjyiZsykch<$9#F~`?V*_r{I`2I|r0M?+GdG~<) zUSDz^wgF7ejur1-h`1~0Fb}KYsY|F4q5MIj`Yd1EiOTBw?D zN%}c=o*bS-dKvV`__9QVPQ!SFr}_!a^8@$OI6PLm=lWr=rUI-0G*}{nYM-7CA7sY zZ>S@n-FV(YCAl56uem9l-JE0#3OkAgXkscw6*kI?S+ z?MZh^6}Sw`qQ-s6b(pf@KMNVeEsI3>&pAmh`Iqyu{iQKLJQ8l&PU7x#cN8oG{uey2 z3@>yn{=;)mPJgq8c%0+#)mE@ku@HK9e<*w6vMLG|P92KLhr_|CBKlZ<5cj|{Z1#2kdC!n_~j7%u4e^Rr79ll5S8{~_vpKD}yk}LgVcHH?m#KhX- zeniG%jJv&B|16>%_XUow5&PeIQ}LKNVCqAA+js-}o7X`NY;bggP?;EKy^(dVvmOc^ zLoWOUNbDVr4y{5al^~1pGc;Xd_aZ`|8png+4$JJsTVCL3Ytvwi7h|%BSIggBp_YXR zwUaUm^y+hNHU@hxKQDF2$jHv@ZL2nX!z&~7OfZ3~F$9cwnkkIQd|_TtL;M48AO57Q zIxu6(Fd^wD@AYdfosVsHAT_^xzaW_1J9~TE`4NII#-L6I?wAKk*FnV7&HM%Kw=yv9F?Y$IVy0=7mDk@^5#jR1W1?V^h|47!8^9Tz%5K)-+dV<4is6!*Tyog;~Wi%V7BZw`5GlTAsh?v zQ6>r7Ewe^jW=E$NCo(TWS`6tp9hRa$EN{X1xwMGWdRqx zEybyUbmn~p6)R}z-id*sX~yJeu45?(cGAUvop0V@t!1L4qA@m9aE#ILMP8;5zwk1K z7xCgdr85onPbVYV;UgGbKx8t9q|zPw0>+uF72l=JBo2iMHCf-gBb@Bg(_@F}y5?B=%+5|8x^ct;&l!uzp;TOHC5AFMD6Cm2Ei`=mZOAlnpD8o`hh zeay@MKht_}YnpJ4Mkisi>=rL5 zFbTAAV3NqxTqd$4Q_i#iBPfV~07HYEx1kf>{(DUvg-61#ww?^X^2E z>4M6eku6>9s~B^h#C54>TjPuH826#TE2;BKujrEy*GXJ%;h4%s0v^nXZdj0LpVtCT zU{2tN^-XW0mrgh!ovj}7i?XFWGTFPon1jc|o$I5dK~8zW(L_;TlN*v~wfI0=|MQ#0 zeQZOtl9WH)3vekfL*z*YCYPYwk2cQqg7|aWWH4p&2;Glp$RQA_kBD#@9Bg`uYSf(8 z(_AeZ1Jl;n-Z-ZEO@O`!K2Vz6+1?c9{FG-TT z&uDEIgq=2LZjCTpAFHoSvp&5zqF5z%O;xhLo8z(iC*X-C^L8cS%ah30X_y$3uR7fA zOZ#f>EPgqjxN12qg_JT}$#9evuJR1q5qd|J0d%X6Y0_tkNDtRtqkSG$!Ge{;HrKIr zJrdLJxD_kVb4qZY(I@hXiyu%M)H|w(rgMZ}7h>8OR0@lO+T8?aVKNnej$kZZl)Wy5 zC{^On)SP;zrBs>5BSJG^Ele5JS=6B;s8)UufN;pwM3k;p6-v- z6C!M=)&3Xw_%V)lSIav@n&d&1K--FRMWD`hjQ`s-HV|8GmrHj$fB(wU+On#wTX!4p ztEf2D#FduVzy|8v!n`4o_y8`0wgA7q1)o+ZzRT|AUAidI!)exZU)LZAn$faC#MsL; zseyULdf{Ir7PuO_&d4oe>GkZ)LH$}M+`^EAY0r)P>wt8!l`|EM(Uuu-YEb3bvx zbKEAPNtO~U3?5iBVmB0soIlD+?Sh3>YjGP6d2ZNVNHnM@pyEqdd} z*iuq?24BlJ=xCjK{iOTYdUy`^U!1?Z$Dr$Yw_LHRnAr7*TbipZNZ^H+1`)5%sE1e= zOaS)y$4YCj1gdFzl;?B)(W^~Mi+StDb|*MRU8g&8MZf6EqTlhiGuO@-Sbay zPX<#zK#JOrKn7_X+le?@JkqVDZag+HPZ3A2L+IOz&+gJWZ$ z;z-6a4@RH8X2a#u!XV7Zvqq;J!X8J9`;r!3KgxG$MNAMp<6(9IE?wfK!;uGmUQ|nd z%=u0yPbce*z{2lSul9zfbYazOC?y^+zM{M~VXb`@_Yru4q9xgpvYyEgN7AjBb>HpM z^9x(mcaKg2U89|TEwz^-Wu_#{{qtjVZ2@$IEDfFfco}^>59UEVpOtdxGeOJgLG10 z8DoTg+!RB1s(B9&KtQw9hVyRRHU>`}CA+YJpx_Anoz+MM-g^wtqFqo*2y3Je;aCA} zpje-P^RmVL)JU^h!|C_Zsbz-b*S;9>e=jHNKoI1e$_~00093 z1Q+xfWyy@SjzXcL{R57>GhP#IBZNwYvIg@H799Fnf+y)83KX&-T?-l8>H?Xda$va< z-t6YEx%;#3O#lM9)Ek|r--3gQ{hU)5W!|G0tT`5;jFip(!w=$hao&Mp zD1fy1GYy+Sflz)~0irSLi$V!orJ4PkASw4MxZ38A^iPR;@ckcw70&} zU%YyS&6}(2j2_2Yty$d=wpARWP-Z6B`A($Qq<3?QaZvW& z7V59GMwjY~3Q#CDAWxU$=r*Lt0hl@7O8L8&$*g}21K#T|EneAKv60FjY>8W!>hJE9 zNafodto=kko-CZ8)goVZqf`zz_+k-M(J5M($0Kcu2G2yO+cn;P95Wq`9b0EAI|b%e z2csStBXMn8Y7;Mvpc=*-3H(*+y|0rQ%EZjSp?rH)V47fKy~tkRi<}5b^QC>r0yH8- zS#IJ}XWTgYcTh9(KBBRlwvqtZMFn)_E;hTAWUtIw*9Q$7^YT*#@qK~#5H9jrcwzUdVvwcDO+m}H&+7LCX~Wx!5BcXWzu0F7B4flnWzrInBzf_t43OoS_V?@ua{1cQ|Ue zc>1vvRl-LAojqlwv0b=$^$gjB@N=`8srcvZyApL#2T|*dKKV;UmU* zM_muK#aS?Q5EA82QN=@~=#<{V=!yQk$-ltIK6d}9@LETSC218#5su8`zr)U!ZC$V2 z_1O<7*9Fa#IWFBvD=ibgVRG%cd>Yf2X7Zn^+?=35C62KRnK#KHOq2C;Iea@WGY`7J z`81pPdy4@?E}fB{*(E=_^(HHe;|=Hayy4}T*q-wiWdT~l>-!6En9M4ZN&Jz%y z6d<+5Pm$jGgnTfmmya6st;e>RxYY~fqMxt&XSnBEBPn7u=T-E^S!n})X1uD2#hf1 z$AllPy~D6@|4C1{P_AoE;=sILa%6_YBYh7WRr{*oB+laWvGpF$&iRk|ZfIv4;Rbf8 zHk4Wb;OP`B?|=XSYWbvx1;pXj-6YQ#uJ+9trlc2dwaMjyxpsW=TbVQLt98xU0Q>V zEsk>UPK7)lcAFcuSblv@d%_CN{Rr4+^UogEn524E-E_Xu(0I35flr}jjg%H9$frdW zMJ>vgOG8D@P|n}^Q(JeTPOhl~8+@;;$NRthq5}~mFoR~_$n~e}9H_zMoc(31Il(lv zrCQR32bWEBY;`gr*84ca?PXb~EKgm+enV$f>pvRGNJ|w8YYcG#$VNJ;Ht%{^fZpkQ z$FLn+13XEfR+Ou|)*e?tU z44kp4RfqmHPXMUZR|!bv;fW0{bz1$(_Q4_G=Vh8SW*)_pu1ELHWFYdLtdPMF;>e{i zXNpyN59r?uUb_k2W+w*gaCT6_aKGv8&zd>-^(+6?ztCEzO#xL7%!olyS$?TgrA_(% z$7IvL1r~Y{?8S2f9)2WXIG86aaXGX)J9cd{qp#yIzDpSQ-af(ofZYkFK&O;i8ru)R z!kk=)>uGC5?9_5;27q`BKNG-^mz^BA+FX&$ezn%Vp0csZ7bUiNyyA5~8tC{hZ^s9s zm}~HkB^p>)+xs_;oT0q}z$FuR2j0eVo@aneA}R97cDIuWF*|)|-{N8SrFwroI z`-DMs=V|5f`~uH#ieQpXx#6g{(oY6ScJjqP%kvd_B-o8l-2iN1lI)IiPkZE)SIH)F z3dY&!CK}mHqX-0&#$R{A5~b7av;qM8FooLx9W+_1A6H#FF{p+vsutUX(Uu})x~O~h ziYS8yiYgR|2>gkbe?(lDjcUbn30&z~>shKP=`dZ;;d9hijUe7he>i z)!I{8?H8S*E!R4vZrg~02ajWl>DieO&!EL@DoY5ggeTBu7LfK|8+m-brIT zT;S-U-EN#c(Cj&cDdlzR!X=hn)2QTk+VQ)F1fbmh#rW1JZVgCo7U3re!5t zccx^qcmy+9o}XE`wKuIEyQkFJjEHff~=9?)-0i-M&(J8Dn|2VGmTY-t){0PDv;t zjTy4ff6k7tZp@!p9LOGQgrg{aKuDTCh}N$JgAc|r3k14&fDud)oT&m4H_37c)+-bC z^chCRm-sXu*&Tp{XcOI{SG}&7$lR)dd0pTxgw-`89H8^6KZiWA6D^LKjjL62> zhh={W>%YN}pfqZPx)VBt!4Nc+H0bd?fF>9rx_n5#vD!aMMV8HUEp{xb)Tq$WZVqLW zC^rYQrW5(6PBl<9d(?Ac{w+T3$9g$p^K~Akqn*ygX-xJe11h7#1>M>X>A2(5(X~5P zLqo1KAV>*JX>lARR&m8c&($wE#gu~|u8abSg`nujh8>B?c}>D$9C6YLyUi;_Mj6aB zmDc_LaD1g{walOEPVfotSL|p`=FVwpfN_99}~3!L31}0TGpQY1({IUnI5gUkQ@ySLUA< z7w%Wy)_`^k>VG{p)juR1DL?)b%r>Y+$5p+R^o{T0_tl4evVIfLIVVh9HqJ5&3iGl+ zB9O4iJ=j#xR)_4BZWCoMBqa_8(TA5919S_Rph6M0>Jo+` zP(_iwa->Q)+5oIdxu9t7W9luQv>lMLE)-(!YX0&z(9N4HMA6AO z-s!_v`3tMP2;W0k;*+DsnU=Bws0STJuKoz1?}Z5xTFZjt#R82%JfrRj zCZfUlBM+7Tq3QT7x3T7l+mE5*FiKtRKyf`4*~hsKN0M16zJu_mer{b#%W3SrElya@ z1-s-a%Xd34W9T>Lq-ul7??VQ`k?8Df@Lq1NcnyqGhq)1`D@k&yxgS7c-55da8<}B$ z$hBVH$>|y$r6UqWwM3fd8Wf~z>(!d8^iQJc?5m7!`HnAgDpvfn@Z0mG?!p6tXS2%7Oh*i#h=u;n@E1gv1DT6(dXr zkhK%zL;L~|XOs0dljM%4s0=!(>$P(7;ke6J6r}b)M&7xB93CEGz@w1(W4E?iumlBw zf1vRB%5*eUM=+6jp9H748i9K`)&dvU06}@jWFp|GG;`=~){W>y-6Iv&G@^Q-KrC`? z6+U+!CJrCQUV+8hH$fV=%^L*;{E^yJ0LHHuyQ~uJyhJx5V*eQDTMWGy12-fRqFV`Y zO^?y@;<{RbmuPy$YrsW-eIO!1yEa}*-7?-lBw{Olc5iPHS0#A1iv6F<1D0n=NvUa- zCyYjGeGM3>)y=LDlUcXTb{&$r7k53F;LBh-5Fa!5TI3K#yfbj@>vWQ=skRGD>aEeF&rrq$`-t0{Es!;%q8n%Z-~H z5K;!SrUj6@Qe@#TlvYIVX#Nozbm(_F#oA|kx>!;E5hEbz8#L769F?gXSLz-{%jzq+ z*rm!M_kQ_$F|OX+T`=`izaN2H53jW7^_&k;g~>LE1f3XK&ii1k>WnyCBuk=&4k>g& z_#nUCbZsCD+I@$b7(kaEk=Rcc6OE*G5m$fw=e5 z)jRDrr+cDqp4=6?qrpA`cNhvE_SHD&P%fRzOa=!8VlQBCGEH$*+-n}8WgZg<$`BCN zLYbhGo1Oba(Ne`LAKj?evQ=w~uDV|PWxL6gDw5YCRMuUH3Y?r2XXk(vy-{bGNH1qv zZ_C(21!%tMl2I6L#lmu!`1hV7BP5%?SpbacI5vpJO^$)VFiAWgX$K%mH8Ddqb;^9| z+NuS+*!zNniP_qwjTEnmDY1KqJvv7A5irBG$YTB0N!7dsUAM+zYW(eG6C-EsOZkKO4 zfl73@*6hS$2o#d{Tu~kf5qYZ7lQpx^uZ@|>k|x=S68A|`nMT&fIAIH7gYJgrUsHr? zfk}=f?2w`M=~OtrGfmiUn!&oej@&HnV4jnYPYr>4KGCOUy&75w3RYR1k};0nnpAxI zohkA2wmO*$gE>_!jBc{2wRf5<+^BgYqS{-%?lWdxrP;)A>mU79n`$IPvy?L8vYUjS zl*tv1U(rPyn;A1$Z`)+MxVozj&o{23(U~fr*8W?nWaUNkaKCMAl%r`jL;vGAXH1^5 zJgkt7cWH9BF_J^0NH7klKV7XSaoKrK$eXdpd_U_8xD`*R;y~$DYJf+`&i#Qc5PxBj z=CHv&ZN+LfaMB&1!dG|Le2hR?3#xkZd=1Ef^)I8=HO#SeKdq%CJZWL4*=T`zw zRb$$(4*Gi(pu%&|Qxw`mp-?RnTfXJnt{bLKP632QA;2w>xgIkT2O05xKOyN1hET-b zn3rM*hg8L~DU2x*)BHMX_IAR*b;Ne~k`3-!ENR)e9Y)do6}xTMec?KX3hd57W@o}m zi(UDDI^W;WUd1pD7z6wSfNm=zvA|A~(CNdC5Q$8A#<|UbtpLm5&Fs zRoBT9??d4HxDwnAOg3r0Ir$@RVC-{--vFta<)g#3lULr+7_vWR>FEq=H|jtJFCnoP z_~n|&nm2RpRg;){3Ed&l3JB`E+a%KvJa6VYsqSGQVu8nY;R_6*X^+N^K_4RF&#CUW zbyKqU3lr<1KIi?(1=I|`NsA7Y8wu7&M7bM>`@)AVoSN8GRR4lf&Q3!%Lw3J%_wSbQ zfa9oVF0z1JDqt2rCCK$>BGiT%BM0{|PjyipdU}c1wnyJeGn-u=|)WZ%G;F|jug z!LuAN&)&>nH=Tkz^2(S9ZG{*Fi>rMStilB21CO_7H&9f^8)uRnIvNbu_GY)wYL~koUZ3NjaAc-Xb zLFFA-0l$)*Yj7?ISZ?7AAF{l?kEKE|000fMh=Qfr`F#rm5CrVh<<(6cveP}Z$_k|k z{i0{U5J-cof~QUb@_(ZBMtyMHf*?O3bea-oQCutaS6E6#1KW!M9|8(S`oi7EXItf} zgX!HCqt+emMGezyHJ3>MgV=j${F?<5xB~@T?t&x(#Dhf=uUV=`5P_V{9jpz1A6deA zIYO9E7w)W2%L;gV!p$}vV{lmdh0Q>@6S+fv&9g-X&NAaLdF%g_wRe)i$^VZk9e{w z7$TyI7$bQJOwO*VNhH(%CZIvN1O5&M3uk zpX7XwGKrp#O>NGb4!MB0P!eOOykThP2y@-kmLac0d|vP!_KVCG0c_aC#=#ADt1&Or zYGxR6D4Z!%1N7i36i3i=QH;Ej->4E_H<^6TnR&`eEe45)j!)!FK&vKQ_=xbqza;UT zv+}g0u{v?i6&pQTyCNtJQ+oFIR2G2NY ziT6g7+3*`L?4L`KP?Z63&8yT}Pt<^YfK8{`=%T?%F*QLop3qyrb|y}_bFwcp(~7VL z?}w#T+Bnvi9=>bTmqzcMr;EAKRegr`gn*L9<8;?*)c%GI>u{MkvIWJIzEp*W;}J0{ z;g|iAj24IA&Z)&T^h}FkmpgSw3*QEdX#tlkucid1$mDBMiV?_S#-2HIpUsB}#@hco zGB2ZN9PpytT8~{0FjfZ;;|f&kaEB8;Ko>6OlvJp~^6C(@>&lp$6l5DZy~xokNqhmf zPZs6&ebYt+I>>RbRTFJ3feTHZ4b41H={j{Wk}Ul&7;RNrnq^2byvU_S`7pJmx9Q@s zVq>@F8GHq|o&Qs);N(bQJPM;CQ5`N%9!PeK+ou^70PsN&x?g-^#C^O+z25cGiPz zj42|ub)bR)6GxB+it3p&7A5e^tFHv=sDoq=>BQMaU0Q1+$QVvhU)1?A{jHFrC1_~$ z!Do8g%CFLgbBcCI@8?+jUwV)ipNPOgc6O&6;4nyjIw*((ugPb5uIctjljWEzp&Uv?P}Cr;Q~WJBd*&XLlY?fgMoh3KlBfXCW|0$LZ|x zEd%SAWzH zXH|e^XJ0<6(B(rpVi6bI+2UN)l}{NF^bNBl?ia@-^Cl(7rB zCka^aRhj0cC_O$u1OOfC6wZ64KZ^v61;j1eW5lT?19iHeRY33;m{m((Q&u3-HV+RA z%^R8OM|H>Q>OBAw49J;9^r1|tcc7V6bh$EE7pmv^ZdGJNe|a@#GzaJSs3@E5Hfhz1(kbThi;%KHgLIP-E7zB2;G&hN*UOUh zv28Xq*uF`EVHwrTl2e#2nP9eF+$(t#`re097FpB*8kncQ(`pXh{(fMq_N^u?OECp} zj6a+GLj7GYWLJRC5HfUH{ zKI>|yv%`$j=nnQwx82^%Up0ST{|$6vux#*m*lJ@BF*z;wcM=;W2#$u)(Dz(+>%Znf zavU+Gsh#i>1iiw*OyjJ$3~hutm$lO{918AJ1(3l4i-P_QDT*ZSPPUGm+qH+z&)F2GT`1gp1IwgqUSZFUjVW_-Sz{JVjI}rNjd4qWawbOS0KPtZIuAFB38dCOD;wf7Npww0 z03bpBJ&m6U8YK7RXcFlFZbew8hPPHYPAO|WuhkkZ&H88y5{3~betwZ83kfSg`!^h% z0zy}&Axj!bxlY_ks5HX+5GI?|F!r$Ie@XW+mqn;lzq1lcby(pl>S%2<85h#}do+F~ zD(5Ug7b9rtuN{%#k;9pwPQ49zO{xj6zI5XEkgHviwNHI|ykxFwAI@XRKt+BYe@uca zl6PvV=j;uj`-TTcW$z)-2>JMI34jVlQHvKEkGUEIqfm%EKOHPo*-PFV3l)9Gl~{ch zE7ro{Fk8GIW`p_e$`N6J#pjQ7RdY}oQw;cBy3$Vc!-J)M$}n`bZ?;mezCynj(m;lG zn6Yr>Mto-zqluwS9p&9vFmWy$s=Zp2_i40RVpIIl#aUU3iTj+1=ZqPAv)Q$1)wIWkORABVNn zU%{~*&`&E|_V_xr%*@K-x9FhnLNsKJPZ+9R^ClEx*7e3S;oguuOfgh{|7U<$@cpEi z%W{hawBARlNP@8%H8!GJFn zAzQTd^~be+hP;Fe$u6WdwjhN^aSa+!c(Gf<6mD)4cpdD3w!56*PQHbf29jLBrO4*E zkJqyv6-4!4Wjc-EQa!y2x+DXbbAAcN#+}%1%`61o=;YMBCl0=8o5Jc zu@uE{4|8XFZbRsKUN6u!&q2hyjK;0ap#Xpw7N!Q^0a|5F-7egNZ;aT@_pUuYI@pZI(BxZ{jnkBRF`_=W&5@$99^&UinAAmF^pD{2bRge%{5UkF^TrdIl=Tm1N-h~HK1W|+`F;L0 zup1+W=jD8e4ntQ9#}w!u@mVf%ZL7V87%d7@c0Uo`~4|e zAq@(Z%%N^e%cFTZYq6&i@e(S%wR{XK(&^E3`96Z0Dt}YM>_RIUQpXn>mf}Zu5j`tM zc8wO4H1dW|f5x)cn=w%%9!@aHk4G(dY3#)-L>AJtt86##yyGnm z^^-$TKq!Wf15wSOK7IX_Q|$K|K_4UYQ*{T*+@{v-q0mR)Iv8d@6~{_I-iO^zX~#tV zuGFP%^Th#h$P2wre=NKOJ$w>hzQGbivsjNBT?n*EO!E7%s4(E9^v2D<6C7Q&rz*OX zx6*-b7m5im&V|^6p)3$`&tyMcdKDD49xt3h*G4Ac>u2Xu;`nDVpa=yyS|J{(D5g4= z%kU%87@rDk12ugIiP3q9oiS;FGi2?Uuoz)NHvv8s2H6r%TYzWCxkwZ4)Fh=EbJ}D?3 zW|2H*HpzX{8f5 zexkQ*@*=5_DPEn1=rExvgN7zFSaLHi2mU=eWFuvucT@U?(KmF9h)@IAiu0=Erqk?w z|H0~ToUpCPKXrCPKO7=XdS|<@%OH_@AgJCaig1JfD#y-v<(-|%z9PI@(GvA^YW}`U z)Y9Ect13dzoYn;bJl6}ZyOklfngKwe;n_C3s%Xu=|E6^46`qe4#BWO5ahg&LpiaV6 z`nkwuWA_)mDCHd%EG)s(K>z|&+or>cw>r@Cp@w$>$fI>VMH5FtJ5%@{OX_En!A;v> z_2ezRP?vcGFxr3TqbRXdVdcV|{QAYyUi)mx=_qbz78f>8$Rfh71>v7CesE6`+1*}N znccF3q}N=pA}5d*OH#mzjOk-r;JjiClxE5S|2-UiX}w{n`x6lFFh(t@+N>*ZRWi)s zF-jI#7y*@C^`Q)Z={!!>uhy)A6!RNe0K52laE7}{ws`C2WX9JYoP(P!8)#JW%Q9Y< z2=1d$mcwaM>@0ljoFqpNbr)@7bzsko^x5Tx4Q=)(SmJF}#4dcuXkDf#Xf9TH8^{(# zTiN0a^6=HRj6(NRtoO{G^*NM4tyqoH-0H*Bwux`u#p0}EiNdmyh zL5Q;}e0p#S#n2zXPADZ&V4h%>T*5^3zv?_{N9yA~0m*;VnLjz+{A)(WH=c);<9TzT zH7Z&=-;WnrmE9jS_NO=H9HsG%5_PR`(8DZ4-?H0T`C*E<%%Vb_KWx@~J51v!!#93QMDN|H~G(@Jd#-$V#fXWQq%4^T|BA&7+K&KcSAW zy}Zor4r5)C2c>6>ZR>`J2Q*!DaV7yR4(mnJ!F^x=o&uqMgoy~}e&{N(B1!OEO!3?Y zGuiSISsw9uaRYIAZoM$yl}=J%FhGh<|U9cKG}cB53RA;Tx-x2wz?xAPpU z4~XIRb|8=FdL6dliKSU{J3Z*^KQf#)=U1y4#a6T#RKn*XJ`je|h&l%o89J&!9^wPc-_fcUGObP%GBmRt@eg5fO7{z`ELh zFk&9)2FsrxtscWvtUbJLF$ngRkQQFcT?&~7TU-x!zt>1s3!a5E`35%ABreUbY+u7`Ht{It`m#u54LiB zF0}5P&IFAReYHbk0n^c30pF?47R^JS94ePa8n+X`@KWR|RUS-cA&QO%QR%S36Sdr& z7cBWVR>T}SeJtQb51hN0=5r5Xg0!{r=?46cP9rD(#@w@Fzh@~b!}mAINRoT`RfKBP zFGjOhs>)F)(gqbK~K$HI^hep!U$oCQULkEY2? z6|uPbSXWOWKhuxE+xwMH>Q4>~(7tXM5aTPg5Ve5HiSy}t!o*N~4RExmwN87T zFeM2yh!u?+2gZPtB zwvMD1h-taqk~xA2Fd459OEE*Nf6snNo&&m1N%Tg?XEXLs<*T;Z!0gKcO#b7nsp?Ze z@^7*@u~DCkifxM!rwLsF;EYIh>->jhrKH8+T*0F=L+Z!>`6SW6)Up;NykmbKMIbuk z!u`juS9-DKaN1Z~eEig(k}N&l-h3tH?$^tbxcZRD|L)m@M;c^UxGJ>Z?}zt1n^82a z>Q$ir)c&!5!*tQKD+K&fZ5SA!saxMe$vdFX@&Zj-g85 z=0S#(dVhsGo?Uwr0r75DGAL!$5x>xmm#Xwg0zVGZ%fw||yG3H8iMQ=|ZOCS@hIg>m zQH}@lX-&th&s(3Mlhq-PwK2@f&rX$V8%>dSU7OlvKYeQAyGqnw+ebgp!pKQ`EUbvz zYn~vj`}Q@cgzb`04cYKcXwg}BX+o&CQsfTbb>&kBLYD$GQNDRm)5NLXNV~Dp&yfLn zs#ONOfMl-xVXlQ#%Nv@8?|Bu|Z&e(i_@IhLP$?nX(09~$q zOUbU4_SgfY(Q|C#az__ZP7`vkvLx{(3Q5xryET1o0{Hv#3!ggS6Q7QR#X{DoKK}i> z)}Nz)7Nihsm92hD!{74)c0!#c4R=SKbfC`~S9ox$iKT>#`C2T~xKhjVfQ#!JLaN%X0SA18p3=kL#@yC9^~vznQ$}8V7RtWqyU~)ud8AOEB6H zZRH7zsG$U6MIQk%O`>!%@6JAGwr)=c7W&q4wkjL))N7Mx*KuHwUY%|&P zxj7r`tR8H1ZJJSyN*_SW24pbLhW!-w5*a9F3T?P3Qejclt-NPorc zQkg1-V#R>UoQPSoIzaKliM z0xLY|RTufK7fL0C^@eCi0;_Fb9?IOl*jcDmdpc~}O9ckTKp-v8^4iNinklimvJ1jp zAE_`G?ySZBe!rIn8czo#FhP}x794Z4Wf;Bz9^=)v5Uv+>64LQ-0*8>@M7rxDiV@K` zEvgUrA-mnE+U!4R55jC{lA38o8zriSVB8n0Gv6X9uQx2krwialkF$Kp+*KQFufZ@t z&*wh=>~FO-A*mQ$sg;JZSKnfmhzG<5g&Zx$_l?g#v4qI!#A(T0yv?EJ0TZDV92FI=M@9r>aDhP zKKc~Kc3Z@s*ERUnVIKO17WhMHki)%V*C0qqf($bh{NAyAp2bVEfQ}!2Z;xpkSYhFo z3i2PNOX(JI>X|%V_M$cFXvi_U+$D&tAr&MTrhpek3Jz!Oc zEO{&93?swSx-l&KX#xnm)mpo~Zo-6=TvC(Z~tUFA9lJAW+0NoiEHnB#E&mD zitk77B)A~fy||L(BCX%E(lKPnnj#+z>i;Hy_2A4IuU-LRo!L&=mUSaAj84sshYwF# zKc-yK3Ot%#NdUiM4ssoXCYSMkpHcR|OQN*^ae~=Fyc8npFolTSwR-rUF>2}C3km|5 zqQ&_hhEg=smn@B@O-4Weudd?Po3p}gWAZ|UGVi&8f1%x(MkzxW6EbmuVlbyhtw|@( z^6@*H7MG{QrfB;mrL=wGZofTkd1Z{(G-J3rX1s>KK3TLZxiaSnEOVy*lM)dCQ^`^j zRmDf~AaER9Wo+yyZ;`Z@chfGrff(v2HX%EbssFfdtZeQot=+V%Kl(fa&$d`H#kj7R z=+0`@9(@x^Yl0jWJ=~X!nL~#;6p5*z{Ls{ImZtE;7F}== zSp(%5n&2Uu%hHo~sUDL7hT8kwU+mV%4Hmy(PVNVDv1N){ zteyR+d>>d)Zxy-oJT%rNC9g7Z1mAzp?erzedqd-|z4TQ^A0H{-^$DE)uXitjjzLpQ z+a^grUpXjDU@lxXy1J8uk6CT;Cg38W0Ho(F)pIlkr>gG}FqeeXq})i^nZFU<3;B&F z{%VYW2R=f1RP5pXNI5|p+(ZYwGY7aX&f08uSL>0{fb`}bm-y`tvhCdYSC+nD9qG^h zEvQG{9-|yN+>=o5p-#b{{H$(5uj)+1;d_%+^b&RRiQS3YxU8$^8<)w zv>$iAIUj;I;9viQ1EN;KEDXz4a?*V@it)HyR}@D#618l1qoBqzfD4o1^iPl2j~%e3 z#Fl6Be@daG2+$haJYVnt06at|&5g{L>QGH*be2^a~)K5a-qn z0Nj2t)w`!()z-W%1QH1T&AHF~t=G_N;nr@aWwSM*a-JMGh8DVFc)S6AWJ=-WIE;aI z=5eczHT-dVifHi4BSAD@zm!FtkL7U*Sn|PhlX3EuYl-GyV5jPOebQ~4DX!0g zD{>)yU9F}@^K_RnOFp*>Az(ZNAZ+T>25-bF6LvS}XTvR<+FQSMFw&CNa}ODD_u92I zNaExE$#~?Qi?HpF8TP%c{=7Ip%CYogO{T$CL9U~pNNsYD7)x*wq*{#ZX?J(hjZq?~ zM849vr(-AY;Bvli5gV~^Bo~ia+TU+n4HQ6nQg_EO8X0zXMFMw-Vjw*RYDXk1IdQ%v zL_av=o&ymMC{#~E(AP3Fp;-4S!v_+s%o4Yir7iHT2QIY?**yV}QuL+JTMLxV1qcPiQguoO#9^G1kc{XszQi5SqeFE#h%GHp`t znx+0|Di5b4$ZEj7QA`C624Gy1Yd@;s|CSezCJR$`$O8IhK?Cl8nkDn0tl8^hJ(r(D zAMG1GqwlF@7HkP^+f{g>XpW@RcCPzypL28+w<3kEM9+y0M+q@QY!cDU|G)1E=aB6D zjr)<(?zJyl0kfQQ??tq(r`Fqn3{j_T85TXI?!?uI;SVwc;f*C+Z7pNG!;#jVPUZGT z42GnjgcQ&ZSs6}Au*xKJ!<`oDj8|f2%8>*Xi%H?{?3hLi%olCbbFj_P3MG21uOE9>84-6o4RUm@c}>cVO2QW2dY5)_+4XmHv9RZwCgAvc-3nOwIw+ zspw$w=hRtf(Q=Y3(pX#{gNivTG^93EjF_$R|BuUPjJ(9-h4*$jITsYE?b?I_lieyy zyOV*QTJ%&OY&DGLt+ukki)nl3gA{}s1P#@R^`T%=23lVIvO>2`Ul zTU{*L6)}ZHMmHf*z87IClk{0KAuJ?q$s*O)_u3k^cMa5o7JZN%uCa3Bv&Qq(5Gx_V zIo8O0@7FZlmup5-_K-(#9ANCi(1v~FW_jtXM8$yC%E7p5SATMH&Lqja;h~Kzs%n4y zC>qtbGo|zF>oP;|xhUU=|24(tQM4o7hdRh|oBXF_Jt7;h1RZn>d<&wcm8I9!Nlwtq60DhXfYrn2}BZ#e#a9}P_h9XHkulSCBK_D2iBsV_XDmERY;I7M3zaopTXH2nuzc1RfRkw05SnHL@?(aVAcOoqJW{Pi_wS6>f& zGF&&mh7jZnB4s1pT(?Eehkt>NBsg0&^0A2Guv#5}3(D&X00SuAFz#?E( zowo}kpH?fN@G5ivlvqwBC?QKh6WeMV2xgPmG{bEd5TfQnMw-y*W+4vNez_~c;itAq zGJAU@5566+y+Uqxx2CC!Emt11|!oz+sm-G~D)9DIu@_)a?9 zk_PvUDjsM?$e7Lz0M#F7UhVguz9{(NJ!rF$*CFyZ1G0}=Ws>}s@=Ndg>uSvjP-Ff* z)fVFGOjN#c;HR|$;Up@!|1{Dd_1nMF%0Kc!Crg$JX1VKJ@I$=fTIw3knMcCxU`Y?o zHTWyW20C%$1V(bR_=j6zToQE#aMr0Q&N^oQq0XoXqO0m%$ad=Lu@n1%3?c6pRrj9k zlq+W8T9mGUbX_!1p5)Ac|f~FBSO5qqbk;9pLn5uY#`YDzk{cXJ8TS`^?0cT z4m9zbs|S@FM-Mx=g z`aea;58(+nJbMC0Tkc>rlmxCrSk>-1y~!(zW4hVrJ(gl88q0iG2g5y~@dOjL{T>QF zb`7X`XHJ=q6R1thg&k3yYezU~38@eksll`WeDz%a<=xvC{pl{x;;XL1#~mvI1g_%N zX_FI~etuw!-HNmvRs)=pfB4lm&2+tUvI8zGS5_(lEbp)kD%JpmfqdUphx^PDP`2-# z@vm+vY(%TZ{Ey(ul6tAPTM9+a=ziY#0JGiXf8)f4PNIYsBYMnq7Ce0!h!a(f)`WeI zGE?z$rR{mRaeQKUgtGrZENF7;1_gTSSIR-9bY%7wMQi{*qOskBDlV93q#ype!*zz3 z1yJ6jis>N(na_cUiem@}d}A9>D~SM?`5_(fO+V&b=apRa-W+=!QccpP%W;Fn>nP5A zp-{A{GTInd%f(?5$X_cdYk9>S3i5$ilypSRj-mm>?NVY$FGk>1@MS)a)7 zz5O|3@Jm^kMLUQL?c_4~7U~Y(5;BBIDmg<9;^3rvZWJ-t000H|ww;kM00gr-;9i|T zwyDl4p0jFIWtEiq;@GU>l%*UunkLo4h=g=|xKstzXF0)qosU|wA|}R2YNz5|we3Pc z<4nKmx{fda00eqLng~sae*r3N!X_!`+V9En1JoTl**;PT+OsEV}s!g z8xl+<>URdjq*Cp7L_wl@>v9lMbjcW}8<0hy06fe({#|^0u|}wr*qGzk%r^K;ySr@< z<#39C1S+^>VSLVaO02!m>h;OzaK%%@j3_-N5aJH#UVSpeD85-rDp-~0rz8N7ys=ldi zEvPN?{9ibUS!dtu>a!7hB^|XeksB4Dc?giqB7CQN9Qg793HQO5&EN(n^%fri<|^Rm zs>Z=xuD@9vaRYbyOkgiG{xWw)^5Lf71+D7}ene#Mt+$Ro7kTABs|SP&!UfPd@5UeK zSZ^Bq#Tg)*AU_?GO>k2zn$o1V%a=3I?S@WxK=fvDf?1$FV ztK&uI#>nfx_Aq{fq@XWqa{wF@?pvu(utiDYXBg~jk^VM|=|%-9V>s9Vzo5^l+`HUH zWN2D5$|T}_#Zenz^Y;1$X%+sN=azQkVDzTW$y>4tf^Y$PrLZz+z;vGh4_a&s8smS9 zZgvM9`p_COzn#4dO?l?US}K4mtX(L>-gE7ro)Yh9YR> z`CMaq{njwe02xWJt@B7VMP8M`SqwhF5iQtf@lWmE4CUL>#Z2yqn^yhS9e3geB`6?T z#vZ|FsMxHnrm9@zIIZ-1VZ!`N#Va~uPW@N%z+<%X=WIxC(HpuPuxJ7)B@{GGcfsNv z_f?l6;B0kY0#tR|=Kufz_5q#{FCxDO3;+NF00093)s;b50009303vofQ^EpTp>G4z zH6XZt!!s^AgZX_Y`b;zH()1%x6LV%_#I&bu15iG?d5Aew|AY+uj` z2<+pHB`D2MHDBD4yvFnZ0!j?|*3I@XBY;k*+Lz-wOaP3n1F_bf5-P1lf=TptX>(Fw z1fl&ll!z5T8J_Eiw~fMo9ot9%1$b#v-Y}UdV#f($Vk&^#^PY$R0HY&jfKflk;uv5m zfCWqd00Wjmnh>k-AY{s6F8}}o0018>mq?eer(!%GLMq&8S3qTq(>%Cp^h5Ltc~K5! z2Uux&@BXT091yW22G|@!DemGysGi$YssVL)W7B4ed;n0BGkjEAyAl!SmrT=|D~>q* z$g__IUUuJIf9!=mcp;np-=fXJ2S)reHC5SD1T3>RXl!dlMY&-`A`yimAAu@ditoH~ zmAjek5Z|D26pHdWf%XDS+W*d0d5itrF(*F807JIx=|%2l2~GiY>+nO(K@*|my7Mt@ zi>+IK;>q%qJ`1kj{4n5rL5Vp4=5s#6IIr_JljgM?;>{}>{jlW-mbl;nRY_#Eu+Siy z>fPL4`9l<_Ng{vn082jOx|_j1ooJyr4U=NZPzlw>YI}kP&Z32C<+B@v!CcGt4wPEf z1;Zf{PS|Ov$YCfzLP0uritIEC-t`41Uzns`Q{CLDMa3rk*ft`L#_eKXI6W z9fx9gjV7P^M#j$|ZBe`eifh9ux_vx|a%U`}8AB{f7|8?(|AUBYM%42g1>EzQL^Vg6 zEG0nm_JE7xrV=BQp6>`=T3H>VrM2r? zWZ?i1ak2?7M+iL5r%HHSx%WJ>R zz;?*r;q^Z(JEOCU>%bDEku@+lm==HDGqxZ@A zJaRZ#hX~8;|8f0;ij-W5!(jnq+#O2P1i*eOU{zCTfrt!#Iq1T`OxzgF6iz;!hvQE7 z0u(h1?ZtdJG$q^^BlS6Vy(BRoG)DAwj`3VFvh-*UXq~Yx5?Lek_Pw*vq?@Kd6`=uZ zXt~?;L+*=F8IyOI>DI){v!qH9g^S&0vu#qdX>nmO&>l>!Z%>bkl^n|Sh=HhM2cnkY zSCdmz=$OjS)j4XMP87(bJqWMZW4ZS!9?XBR0tgtCDvV1Ocv=cYFY6R($6D*b?i`_t zJZDo}V=^u<7F$bztLK6p413_u<|izIr-2T18XGF&d=@0QMpyy)U*O8vZ2l)mGP&#} zA;nENfJ}*b{@+Kp4=i&t($PltTG`*$Jho<56TLNMy=qLko}#A9tz;p+=VYUN8fKQo z0VWoTtit%Iq&Ep~Gjct7iJwdRE7(=0t?|3dFi%ayGH=!vq|@}@fdBvjRY9H@ZA3=^ z00RI4DzyM+llb?cPyhe}00094TC{~zECk&nfRIN}At4IvC2{^+fEsng0Yc~Tr5gY~ zpasBKz@I)K2h<;61jl}@CwHK4f(+`$(|3hTJgdl7x~d$<4R$qXOPxPPR;sp{5H1WB zI~n^a)15`g`1S+^dm?XU;oTZ~-g&7t=fm2xp@)d+`}QGDz5AJPYGQYeF)sEw3z*8AF40qnFvn834{KeM0Zr z2t^o?ttlbKUd?Q}A>s)g@0JVz?tuUR0Hy(+AdSec0009300RI30{{VP0F;0L01cR+ z0009300RI3dVl}`0{{W6_s9SOg+NRzpaJGo000syeFyGR<_(}Z%!EWpr@(eQtB@C< z1*uns;p{0x_yK|xJaeI=8wXt5j|MM+<3bWJW{1E?LZ|=^ie4%c%1B>$bBXT3Ag%xs z7}f}3k?kH`oCp9dS^kWyK7V(_aO}ZU&04~003}6002^pL7E{+bpis`Or`-Z z3*R4I$VlyPWJV(%dv%LXDx{d3aE(SI3^`-@k@<2g^hNP17$^d#JE=x?T#uGcF`LzRq{_+$Pl@;G+x zuV>my{B{;(k|KtW-)x0E@>3SRnc_U8(3!4##*|%c*;wqKNB_?K_pR!+tY>@*k{O?@ z!~iQXxp!ZGp>p%%bj#PzBeo2^Asdema-FZHW(E%gg-MbyP>E$w6C!sFJrS)UTsdTK zUBiv~@tAbs-M-x}?r)G_s%w*bFEh1Nrx|DjQ0u?!*|8K=T^x{Sm78NqEnBsagynR% z(2tuh0~RJF&N)}%{Cn3%t>L>jutPKJ>I8x{=E=mUL!gKK!Kq9k2?;yRY_8sm?gFUC zk6eF~;w0K+jJ0l(83owYvgk`11iKJiHCjMEChxTFm$kKDg2mgCaoDg-* z*~bU!GSv;CevRGFiZQ`kq>D!hE%TR?Y>%oUKh(ra)l-7(cHm-LPuhTuYyyMBc?*@s z3(05&&pvOiO8>@#KQgL(2kU6Pg6~(ohIYAm8N$kD1p7PdiB7&FxpA1-Lrhxsxy4W> z+280z+UsNyOj#}L8gBN15Z{y}hys!m){wI6y-TMAhbLkRbA6U=2 zLGFaW&rty{&H1I=3BO!TM5H_;x*~2z$yTwrGCpP-#ow zE&5ekPx7AM*4z4{7Ltsv0)_Xj-WKSgRnk+(wzM;*YJP~md6;|Gt1^e)b!OydZ57Os{TIUUOC0k_E|bM z(Kb_mtur1(AN#C%Bp^dGRFVua;$GWSp0m4XVrg8U(aI+5Sh~V#DA0ijXQxaS~M$TBeso#B3F?{Od1u3s7PSJ}?8Zhra zX(80?y4Ix$5Sk_{NpXcjt zj0WyNYHobl?lx;Os#iYwlbqt{@D{=G%uN(4^z&xQ8`7pcVJT&52ek@nUtXPVrgn}? z71R^IS(1VX%kJJofpfAcl20{l5!Xb=J%`G}^AT2GT8o9JJA9~|XPFG08>2CTFu2Ro zv-(=;N%0BTvr?(k^u+?ZVL8ImqaF~PVQP2%S&Xu8=u+sU(ZAD2_pOP5js6@9IiXY- zrGQta?Fahx!`SkT^xw4DJxv5S?QMECaiEm5_s1xB+88<+H9|cob`;FhJb=~IUyBSX zpwBo2P&HZ$Pk~b;(!UF+Y+dn~IY2twV&me?o|&5m_2dax+Y-`pT&3J-vopN}`(GOs*-nR9b(MPv%jUeJ z!f(NVHV=G`#q^|Ibw@0I)lX@!z-B=eq4aI2(HzK-9>8XA6j&VcL~YkrAK`Jpq*g|5 z1;rVQEB;oJ1%5y=_SAOXJ+?gjQP8bNLRGZzQ=>`(Y3KL!?7J_aXI+=6BK!+rp!+$2 zb^q_51n9RyL(Ko?rU>J7mzJ_*6-m5F%9YHt36!lSi%uNUTW3|!Ymp-EQyzx{y2qvy zHiboGgs36kpzeV}=qrT-5ziOSk`Xc?t__!jcZ*e5u zUX^%Gxs#h26Jjr~QPpJ;7*~R+@}PYdybE*QR@*@&1Ze%R+XJDd@iy|ZkF~HIE$%U& zPsWu|B8lBHE<%8e8pqigB%TDU0D6e8xbso%30=<_VXM^u)BVcA%UK@q1}$}8cmJ?ryK%1$2dosg61 z?0(=|UgY*Nvet_YEIvb0H2%4h7?_}G84|l|3S<@zhspMu=czzk{9H=&G-LVx!Rlbk zD}IZ$+yozi4bwO_)DKg_up+scfMy^mp!g@lUqOI)GFGnSi;cm=F|O@Hp@Wn83~`jY z?$lVD*Jb$>HA-YWfU}RF;yNUSt5cd&nk>;{OpP0>m#XP|qU)Wg>3ZS4QGAFn%u`b!TOvs^zJ}|1MhDB~qy#ZS?JbQS;FF zh?EVU$QOAu&XsI|fZ0w>$Z$P_Jo9UmU)Y7;o24Y}akw6AmtsQs(jhvCYHNi3c1#Fr z`be%Gu~4YX-l#EDaqKj=0q8|T4{2&mQioB-JxsJa&>BcYFYM;!&3_#&mC&8VFZE*nG=;en$rY091m^*In)AybxoHqf@mZo@b|9)f2%cpVH8ptX;e1kJ;>yFDJZhoR5s0K!p^f5Y_q1 ztjfBO1Wugy{_ZO9#5=%sh_jLA>V+J6dtv`Z4>d}qw;*>^1{h$m-r&i^CIK1TKuQ9{ z$;~{<+Zu3KIkVmAEh)H{hqGq8^suf*I4&P=*O7rX}}HG(4KC-(W(ACg1;! zJqh%(1IgicwD&VQL^30#&J6F6B+K~Xhl-{uTA0!9`+LZqAMNPdgKyPgnh^%O2!B9Y zRsQwTI~DD={w@S&-sv1Wh0Hy`t@?iaaDy0g8S$JHSwd?(4u=o*v3sztadV|orUB!W zwA(aSDg5i?+kDN#JpVdUe4@I;poC%ETbR0jNaNZyEHsoc(9S?yz^72B{zgQWLu|ER z{*pYW)blGJQbgKs2GoOq4P#s9D5OTA_8ZrM}|#v$_QW0+WCi z8t15W+E5lOu={$}D|xU^Ieh`UC}x>+9dgYG>l=!AcK?wk2URnDvf=@d+y&7<)&|UN z^3F(UlF$2z`%xDz?baC^U)-kh&ak*ckH=}DiszZNLyfbKHt;Wq&7%l3X~pzBlz#PiP$t38eFYDq~;w zwemNhA0hnBAK21o5Z3=jA!qI=ITP=M?ri%X;D;thIceH4d6a%` zSV2)ud!{cQu!H1yCt>dgVr}p-q}HqaF*<#WkbTqE4Bk_&jleCPtw{{$hVKIW_qqF4 zSH8Hcme~hn#DMUeR{D@Il-Rk+U~CwW`M9V=Kks8e@zqxCOtx{cO2i_qDBpdcA?x;O zIlsHURA3!hR?Qz513a^O%wl*9hhWlWK~VdsX-TaA`xgn4^ZP#Qh3d8y=W?{xP3jba z8s*0l{8RRAa4HKUYSUa?~adO(O|fx+|~U6pHSK`iOp$Q({VEEcbsurcTDNc z>j3dA4>Mxn7a&Gk;0Xgwl<8+@c#96<)#(kXRqlXk(=#*SFuWbbx~EwTD6i0TGOgD4>2ly!)R(aj2 z_s^che%kV+nUXsYzlxNBd>=yl;c^SB5!>m~{O+QhOf;X5%g|zf&%~-RcZE@M$(!~I zH0CYA>-*cx6xb1mg0>{pzrl=hcY{rXSgOe!HhQT=MN7kopP0#84R_mXUP(JN2dw^O zyWi~N)`ozr0q`hx;Pn1;572-UQ*r-IGV;S#F$s5_tAb1Tu4;Up`Kj^ay?*P@X4#-5 zSs;vc&<+@E&l=AfDW&4YZ(I|t+MjU*mPU)4$omR&Z|)oNpqa%*Mn^usA!y}WcxHjz zY&md8I1u)9{g)NyFFN!L>upatT~HN!k^=mAWOPl4vlCPi$#K|Gq|{+>2!rwB$3 z<1jdjTJ;?Iscj%$x?fH_p3LQd09ouD)eb>q%LJf4G4A?UcT+a59@ z-eQq%y({aBBGnObXY7P_>U-K^WViLgNJ%25L{c%#CZqt?( zF(Jk_4z2f?9?*qf#1Y9`)7>8!W?ElX}WpGVa zHi{qmnFMTj!{noE4V;~ydFmPNy`3vh-!bV4m2l1X0jT=t`tct=StUWX8@DYfd8X-+ z>|gynkL*nnJ4ASpq>jUgOXdt~)~%4|09ZpW+K|>svL^r9Vqr` zGekMiwOCClHAP5V6e?-;Nd+|ZA&%`8oU3Tj@&ZPTTmLtE9t~Fh6vUmcS4)B&ubPK6 zX&dKavn(M@vW+C|q$r}YF@n&5@9v)464!urEi{Z+XFVIn-u3x@j8_e)^`vdpAD6&p zUU<6ik=!I%TQpR)r4~wSZIj^057pz3OflJ)#}JIe@f2 zo1@HBs8~|!HzsV}3>k9|%&heTC&IEER*B`ov{?s1moMBY7r zZEhKEP{{>X(J|F+7#?KJ+z*pP_sJvtRo@Ll!*gG^ zr|!>w3Fb)zg}aNjqqkq{T-NvQ+=P)-J#g}HAB8}vC790z8pOPonI6Ow%=cWbbg28c zK#R(RSonirqT?O*vnmIq_u6(kFSb_vI*m7q7sy8;TI>kG62=wq8=uWwGCQ1op)}b* z#s@TWx8w===w8dX-1*tP9!P`dJ#|P zQvdDWCZ^64NyDXThzfVf+iaIGq1S80H2Fko{9H>OSbY~If>Nm%ggn@KTRFF_ zsFGSIhWND!i+*3jhPn^gXkuDQBxTf@+IePObzFW>9@x$(tJ2kUd1`j=DG^mp0z>;> zqhfko?lWu)|J1TS7FGGjz29k|mBmLa@Zc42dt6kPOg(5}mZ;~7o#bo13XxB$R{r26 zp^&%IA{UmOB`{ix@uNT8*cOPjzNZqgD6w~;ItWH(B=s0`6c$X1Q)&7sorB2R_Mb=w zxy06Lcnvm5@ozV0V5M(4?Z^FH|HrcE132@$Q(h%R%OAxi+F$t5|L`9VTcL%Snt_?~)8XfWPp7BlG$FBkjs0p$IEs># zv>eBfI7dAH8?F(}tHc@)=)4hwU?-P$;NVB8ZX5RLdMNyX)<05DPD2w5Zn}f~>HvCZ zF{41s$ty-a2|xJGZ;&{02{l%X78VRfj>Yzqrh49g0(P>5E8gi+0`11c*a08;IOs)X z%09qNZ@FtIzVQCa+xkKVe?D=vLNr!FVWl&NZ5bkM{=Gx6$kNNi=0$u2cfXNEP8Dtc zrHKF5_il7VPY|L$7==F%_654T?%eycp@|w2>qZ^%$ezMXG2qmi40Zo&o-lfi)w+~R zRlcEoA6zstJfjE6v+sz}sS(o!_=WNoTM3So;~365^YQAj>>o<0S1ip2RKXJ_Q20&e z5xs-Kk*box|Ke`uSH&E&J2P|23_BV$`M-&(uQE4AfFcQrM|(7XcTlsLNWIpbtFaR5 zh|CcIvQ-qI3tc+bXd$DleY)`rd?))NZU^TFoV|?D6mFvDc1a`lo4ot-UXP^`t}>HE zYWBh6V~C6~SbAFo&f*FCm>MA0)FeBQow8oHQb<-jlwnP1);*99uqkX`mIfi~)Lmc9 z$3cyT1ygzP76hO;M@ng^Va zizr3krfr5w=W!`PH@AYtiW=I94ah}5`?FaW&ilUO>%b=O+r@trp14OfIc!V3v9Ea- zwK&DSi6!s)`8bX-#WmB=dCF2$jr#(+E2gzq(d zmZH@X%JVx@(lehvtaGGVF(qrg<{f62s^<<|yC>|>_F7CWS#+#RWcvDqGcvBXmnLs7 zMxRSCcYWbIPPOFktp!BKYI#zI44%@JcFZR3aP5lBAI+Ie7jrN<`%&O`?H+kcFR?pJ z4v)kiHtT>8p(H2o*br`DBowRkOmq`fzlCrHluTKLLsVuMlQP+Jw*a^6q9iZ#huk|S zhe=Nxdo)y0E^ITAz;|p5y=azLilX+TUcq}}3Om16S`WO1FyA8*`WEi}=4Y#L8jX zsSdU&u7|Ilo~MNQhjWL1p*GmdWjbn|FOYE^2nN?xdQOIn!HUagOGa36xcbh02p;_M zKbqJU)JzwXR3)bhBp`gPEY5%Z8}MDN0r5!CYHJOzJX876Mycukpx7~4IPczV_Xb~V z^J!R-jxZ=pd3lX8nW&J-CZiIqUHgc-pY^2vji&eZ|KReqP@G1-m$e7=$*l9o@7oMz zfE5%j33cJ3)`RoI=-n>fn)Jd?FT=0<*qdSxNgWSg5{PM)loVevyj&Bs>1$9`;O0Nl9Hk49umKgiHUq`REOHi&@GKTlr|{9348$ zXwMxkwSExy%dU$PphkuoQxG1bUdG`x0Nfq+vdXB8pz_yh>%yka3)52NUg zHq~~tmAF_HrGQi&#EyuuCvg6{+SM0un}`l<_RV$#W3W24Q#M<99HV@(9yxxc^3nox zY1XC)!Kx+aQxVm8oyI zS=dbVg`^2D(q7rPD&GjnET-M7;BYouR3wJ>%UK^knQ>WkexfB$<8w4JG1Awgdni`0 zaasFG?6i4b(JKS?DO7qY-_5&Bm{&nawaZ{*Z>j#%)G06q5OYCwm0r4+3Y+)DXbJ|A z-fIDzp_@p;PHI->hAYr%EGJnUQz5nye=?NT77a_Q9gL0`tHY<4U||}GR>{NOkVV0k zIE|gJ@9^|o6jrvs#t>=d{CSX6yW48@;C2iSdb68DaA63Y*@x0B^KP_7v5ZBnpHJ}2 zaCm#b+&ot8;;pOUpD~~lnE1>Ivu`{5$*M0(NF!<|701hl7pWKK@vf!U9Em68cLw3Z zkAFcO4Qk#d!283H(7lb`6vR9cAIAT24pmMWBKKnYZ{8kTru1Za32dW1t0~yVzA3`| zVQE$m{$M_7eIf3+`Zu!Bk$!K;HT0}pinR#da7$b)I@z9J{}Iaw|wb zcMkDx(vpxxq`DnKE0OSTZfKS9#=7p@Q-~ z(L&$f-&>miEYlzG(;_-$LDa9{ZoFGQ7x6kC{0PGHQ};WKGdKclFmnfI+9q(P?%OP< z36twWjz3hVz8OXQ_$+?x>rQ|+Bl)DS@HOgD>SY5iRXLmJ0JPq3#jA!( zzE(Xn)qcV|mfyjp?=ngOO4)>7CJd|+v!HvSGQ{TyS+bx&BYmoQRaxUPl=P5n#M^rf zkY&Q+uD>VI={c)Ng*n`^Q^ENodj>ol)Frba)$v@-&pkfZ@hMy~cg#vpl+m5%M~cnH z8j{$dO^zG5LG_{vZz;5m7cS|<{uE8Nd}aC$H5DcfxJ!b*d(h7-1mHu#O?(oUYvP@G zLU#x`)qaT|y{nIo0ln9i_SUSj@p)lk=wE;*-14LuHMS{%f%%v*jOMT*pz{&-IMbB+p) z+UCyJdC(AlTZF}HvfJUr&R5UP^6&VrTO@SPo5--ZUXVa=dh(?@&_Qlbu+Y$Ea}!Ij zlLRME^vfE}f=?c8WnMKXCDw1cD_6X-Jxg$yrSg1~5-61QBC?wSdJf+b-ax-|QIFsZ zEtEhnbELg5gGo(vnIn7omh0bf9>pEl{fWis!8N6sL0guPU}Lk4?>tXXDD>L;9c};= z3zZ`j++Ec~D=2C0dOzmwA%I}x@?*UT&=mHp@i(SCb#^Iol7#l+=k@g~q=1Bmtx2?0 z!g5VNKnJ{sa9om$o{=G-GgQyxNk@h}11CW4RJCVFDuBjXXHG2?YaKg|SjU`vQ`Thn zl7`!er3oxKc+=V<1IyT4WL)>9NuwHuzU5$6=71sy?j=COSuq#V9wI=v5zSe88Z!wZ z$P8@wK9YsSY;>1yj=P7x6>X)}g%qEqUq(=n8+{rdrJHw9m8fN>`>*p||2JRIT?TYP zeLwYIDQ{=s*Agq~TP&MzdO1UzL)f87p3+%G135_Sg4F>g{9?Nve$B34%MaUBc>J z@sm9}XZltzDqObvgBE7kqCTXsNoOm1X&nxV0ZK&JYlM{?g{g*;i{2RAa=~yBdFU?| zv*E0gY+&MT7W%e)pz(CIsz3>!Yl*3K>>cThRJgL|LNBTZrVCAC%}4BzQ#h*|%Tc|i zw!WBo$xb%>C<{>x{JR9=(x|=<%*-kG3dd$w1a>iE;r0XD$syE$mow&5(Msc!Tr+F$ zpH$`V18Wj9sY>Agn2N?gRZ2CyB`X24J}7j|tFx!O;~ga=;+F341%eG%HXa`IyN)g6 zz;|d+yVu{ zTO&^O=3uK`VQ zhK){NjUe?6D4Q~CsLX9e|6bICz&n-@zGroaDMiFKU7qp0+c+4;pKc0wwaKm!)8S=$ z5m#a%mKY;rPow)Q!`*%|5`K; z#rlZ{BYRvPkNRleu^%9`h5vo0+7;3!&Rc^TtxZV3y_%Hv+pp@Iw5ftL*pz;K9L;Ae zW^(%KU&b6+ga&X#*#%Ezv&utnJ|c*T(?p!xwg4IxA6DqX@VUlRw?#TP2T*oR`nw0F zIe~De%%3`l)!onNq3nmhOItqY^yOxsHHlU7uXFcnJdUs=gi=|hMKbbV8x_*D z6;&`P0_Dltz+`Y~)SLayc8JHBb#2Im=5BE!2gMWMUYSz}z92EL!5fe@7bw|^BwtIe z>bZ*PhMu{BOqj2d1AJ@;7|fh4w~rR7-vYCTH;nF9S%?xc!7C&i=4SOCB;rIF2ZlnL zu$)h5WH{2KVV(ynLLHARM}^a3q^+QdS;q^g$LAW822P zZ7ObiB;aDP`zF;aKL<_jov@O8C8F!#D%ICIih+8^u?bsG5Ug4Ap-xEx!uxrCHO&v! zBfqcM@-V-G^?=S|6KvN;)h6T5Y;4+H9uM|QHnlHViE^Nmtpt~DV45&^cm{(a3(_Xp zv|mO)ErpelSSzjuc!`kSKK!mI%uAZL_jU!@gS!_6Zb{mc!qUp(viuj68s}DUbDW>o z_C}!K1yH$ejQkIoyhL!+OwQE>%#7Z%uud@e7z>&MT|B){>kJN3(}wnCZJAj;w%d~u zbGY;93A+yoAyi_1Fmg2rFzS`(X|3U(1K1NNj_0tjPq=4A$BBC_Y9-OhzaR!77I15!-;~{ET)h~0SL7-Q!;CX$qzoA;aUtzK$|S9)7xA&mCfD6j5M)_o&U@3*^gTLh zX`x4!?g`Jw2BUzJye1`z^{JE%iq0xO5-R2ZrKb%yvJGLTCVsmjbglB+W?du|%x0oOrEJY!F4sqJLX$j`t(`=S1nu&!gS3>rqhjeMG6d@e9bYmtOubN7f23M4;7V% zB~c^i*5SE`t0balkC-4DuXBmi@Ru)DfY0oxY3&AXycd4oEU+Hso0Qf07&gAXYgH8k zOWl8BnBYeD1V9uMh{blKb@R`-4=OyD2(AC#>Z~wGSmc^+;Yv|)_e(jQqtb^g2 z7@EU|)P`xYJjmh>ev-JPj#{e{)?Hc)3W%s{QIH8j`Ajq0q5U;c%|eS)Y%#jsC-nHs ztVQHGo?21{laM=?&eZ2pG}5Z?5r>`G>hM2OOP8x2AUV|a-2?asM1xl^j0-zz2~gy( zl54xi_qoU~nv-0B6P&94=h@H+&p=q#C`aorWJ&L-N8XOHHrhlRigQb}fs`+m@4qX_ zuKP^)ahW`-!18u|g;G*l;y-1p~)lB{Q%efacX@<)2+*-v`_J zcwTD+J2MBi#rt21*}`EpWY2w6Swm#>-nX?3?fqOPUwe_v^=4kG zVSE#-vo~)KQh}|ablHSf1;Rw|@G|#T-M5 zC+CJzpvi7;Kd@O~BTf!krakReb?ZczO0)uFvfcf}&;R}K!q!{6 z$l?J!z?l=i;1GPGf;C}o@{lC3KR+Fe)XB<3gq~JB>_yU#1Iv)=pORJ{7R16ix37Jw zo|^FcH9R684K_Z0tT$0i+wDVEvofFlatH1rMg*dT`jhO>{H(kJ`JP7^8#;C}!9<&8 z@xio3d=+tgiys@wk6GtmH*2I>!!Kg|D{wNxoZTkja-R3Mlgjn`YO;{9GtO004azds zEc@cPCN1X%Omzo>=B**hm}0|jzDSRo1>^+R#QQn$Jjco{Hy4Upd_kRK8F4?#Y}{b- zwR8`gKbjnX+HvHoer&XKpY0i3Z2P9Dn|CjhK9?x6f7=jzGQL+ctiMo(4W7-lRc{d; zT=JJ~^YN*J9rrB~2b{-NP9?{84S5SEOa)4wVS^M=M5@C^|V*ENZlkd{YS(V`ziTgHZF- zMw)ikq4Xqi`@KmsaI-u)dm<5lkiYGjsqcXzoq%1+N9Hl@0>!))d!DnVbUjYgxK&4I zg8YY59`_T+U<Ky@J;y>;sz;8FGIVnj1@ z7eS!9TUyH04$RyPKVW1)EXd_)mb?{n8LRDEuV(JX=z$nXEoD?6Ph5@}h)b3ioumIT z=xUFP(@v*|9VqWz?^Ri+wEm1jRExyGyD;!}I~CD|_=CqQ1N*LaLJhBMr4V9a>PKyD z>W9zTKa1>m|JX}}wax@Mx-^(kG{FtnGk8<_cRfsyntXJ^6&T@^)7rfDNXY^+&BO%0 znbib><% z{eEryiPNYhk>2mKZmHP0UkFfw`vkfv(nCby(mU_#Sb-DBubEHIGMxdGU{3h(Hw0t0 z_^h=ZX7@&wvU+;fHYDUJAEmV-oc6z&y6{1(4z{xWChi?R|N1#j_aA-Dhye+6F?C;;Qwv zOcTS6TIrO5&T(Tn&43dnU-?{!NSNAA!{z#b@vL*%$5WMm^;uekk(ByiUaq10H6Cqz zXB4%rlhJqE# z&=A#xEqc;XnetC0(9FUsx1EUliTqf1uJ_a$w?!1CL(gbV)LWxsRiMyBy#tUWO}GWx zW81cE+qP}nGds4uW81bpvt!#fcC3B#-+SMC5gkz-m7UpjzN*gib;g(HxFi7gdMmZX zA{#5pXv!UbE^Vum7-}4sW^?>wYK04-ep=zqYUrJh6ONeWnX&V4OqAEqs=IlEdim#p zzY4iM0%MdJ&nB#CKT_;IKe7TDb(HaT;~VL36~@%txYqn?2NGm7+Ukx zvLt*Yf^?FWQVQ<)lQ5lNC*`+p`H-=09ma_81^HM9?ylo`twTW}>nIF!Er_}nta%YQ zi%>A(yYB^)m5lDrD}(qw?4;>@tX8}3Qp&bLQuBWQ%3&5M2mERbOmH;gj2g_-h#k#wa zKoVtggcxmcq?TBO6DzLIHZomP)V(v*;zE1mxA}+G$YF_~o2sF5mLZrQAfe}`NJ4u9ZE|UWA zbE&ek`Cp;HWb|J$oXq4!cwZfYc=c z8Wn&3V4gAtb_VceZipsh8XY2?KSg_>KsaJJ<3lAFM<65w!z)n-`)Mss8N-8#G2g`P zmPdIfL<=EyAJ#da-&fq920j4I&{tM;T2!hyR~1fU-|4Ud_00SPtjmUjPzxF}+P3Q8 zJO(BaNztLrzhu|aET~Pnlp1Rimo0?SWh8!cT68;v>b+m-gpz&C#e#y|H%D@TXpr)f z%Q-J*kc`40C6P59ZlHYGY7DU=Z>Ge;cfYBDki07vWzvfF7NY7s#D)ZwcVB}=$>LPp`|ZvVrPH*)bo5x|5gb%ofdsR0 zcKdevrsj?`Cwo_0s2Tb)R0gRMhD7ilnIVIb+y6Qe7#qOMooW1!={em@;YK&T>Kz+K zJSCi;!U>@kfd~VefRFshFMmoe{XzwT{swx-u0J zcQ{!bzb!NGL>j}apx;KAnwV#StZKw+aGT$*pq<@$9PJ8WRekGh!Ra^Qxlgme?SLwh zkBk@y?aUJ@f^^;$M`!-M_-X~g;&a(`b45g9!z`mWVkP$?vM0>^>sXkrk?#! zzjL?YLR{HSJy3gP|LaR-k;9^!9SJ+fF1Uh{8n%eiy6AHT4u8SNZp0CO(#n1xNo}ha&NQl3Np$H{W{c z>-=8u?2~h#N6n+NhT*ulBz_zVXO+@mLL@4N8m_zVLH|=eHo6>e-&)Fjc~Cpt$DdYY z-NuBC2$6p1Ti6If{*F1hQdq`CDsY}bFtK%=^!=Pweyc`;AcIH3NPlp{$A>TPY_=dQ`@jq>J#53*di+1nNqc+RgoRsUT@dG^e1C?8aaT@ z+c5uSr1lMrD}DMulbU3Dy!3pHC}5t4^`=VVF^T%J!lhDGTv#&+1tGt0cvJqiAL@a@ z8kzHNC*S;7Z+UjY3;~U(Gy?dopyRVHKu|;SnvZv-t;j zS#l|#?A5!WhzXUz={B16QsRP?F;X zTDaSqZh7Rs4MQ-kRg+!L%Ydw2rmfs0E(EGUKkFgwPea%7+z>YY9n!zAEmbix0V zYz731TrxFMw8>_LxhU(kcn@^EDP^hJ#yH?Jmh#WHQt3)bL-|w?+b(QPQN!$6!v|F- zgk7Yna(Z6knxji}^TA96dD^#b<6fqD@B7g9Y9tD5o#w>Qg==d&bYN9}KQuNf25CEk zf8qP^1UyzW1Ogj0K+`YQ_{RxYBAsOAeMLM0r_51B^hH#UQPhjgR zZ=)w(Py6cvO%6xmb|gi9I|;A0Nv7KvSv_eoDVNlUVSnt@{dxw$68z`mLGEB{d{ zgB)1KeXnxaE<*5C7RqkWnZquNp-;V1rqy5ReBsZH^c}vnaoeI@p{pq`*Y@;FKB~Qa z+Kmc2^;PCo&N-@r z#BIpr_?S*zA1#yqkLTMryQ^7K2D~O;q8zc(;KP)NJ(Y8q3OkTDh3yV-Xr^G_`?gN# zoT{GhMzThG~uncNmLK)eC5$ay{MT$Sc4q(oToxj9g4&SsgGuF1U`7+ZE zVNznID^L>|qSp3@xRdRElex@^YLn<25L=OcjpZ;GAOA)qi?}kyS2{z#Wi%pn|N0}< zTBh9Q{sBA+Z)5zs1$bzrTJ9G~;__(G3E==6NX4EeW zK4I(Z03^FoV7Zb7YpiK?on-Mw4MAB}x{l_tk*uzdlI=If&=pKF3i8C+DgVU=%^x>c zY9x84TW#Uhr)qeJHb1i$0H~}WTQRfETz-0?5A>!_vh3v*ve8V$MM3e8$8$|2F;htg z6E90X0u3~uu&rBU!YG43KfS0#i@je81q-p>yh)anKe@t!Tk-h4yJkgj77uI2Em4Yh zXasHk<`G+^((yHLoyv?XOlMFv!*PESnS;o5IWR6lh1XjbB3v>2cdqD`y+hiPbEA5& z+KI6K-=CWPGTHM3gj7N{8!H`p>i+dr?tO!cAz`(|*3IWDeI zYMs$NBU-X)iyd8dQNE2dnTV8%4`ZQ#ceGkA?U4n6qH#gV$dN>cB=x4`jEd@Z@x#{j zsvj}xL6UsK92#l3Yfw{)HqQz@_OI2>0y17g8=H#Ea6-vpr(h%6v0?0`W~j|WP@oAS z&M1c8O8(5Rj0b9}-o25$(Q){XHnoam@oARh$9mh}8IDCdj3T2;QRLx2C`$A+n@gzg z)?6Qvq%R$e+<8B{*FBxsi=rMlXFv) zM9YmN73BPL;4^Zm1WUyUtLeZALTaFI7>#0Rw8LdQ6B;P09cH&_vs)1~q>~ZYjJ{Eb zQj>+g;Z_bgUazJV4xtVdSiL8}x9dG25I7Cn0DjUek4{-f`}qK&g=pNU*3zYWGsK*s zBa&T^I+Kd6q>KO;83ZO|Rm39kSkfuKb<)Xz#|Y&W$)I3V%MUHg(+X}Y#NP!S)zU=f za2``vKXHNnYX>~K1d$456s0dKJ6W?AyAQ$iEKR;_sUx-)dHo(lyz--VoF{x#H6(p` zORIhzM}7&cZjlIT%*|v*C$)q3ix!rJgDYoU0|)o?B+tzuI_b57f@Mz&iNtJlOMZF$ zG^lh5i7)u9hT1?H4~eieOFzzS9^-dwaSe-R+2V3Z4vENGRfYig$*)?@)RZ3w>JnU@C+_Xb@nGNC?ewxT^-0{K#`%2sK#|9>t?t%J71t*Y5Rr z8Y}S#aPTWXiJ3DKzaRYi-6&;vSsAtt?zzvW#kV zOSsxrQf5r9ISZTprgv!~wDu{*N*u)((W820g@bq$y%TbV%; zkJe?$ta+BK0f$txLq$Z&u*HdHP#>`n_b9+eB9{;wtZ^;$%~!~LVw^Z5;x7Fc*2o+VE4aYjQatcu$ zyC*pd0AA^?d>xC1a?Zgl+?`o|Bi48xlTIzU+T{s8+2zqE)*RFwT5&?H5kXbCn>T+QBBDBlFgVS+|a{XShTa> z$ji4BmH`r6sy@6(>X?ZHUOF+U2Km8+(@<8!)|BIXqI24VM}j6ieR3*I^_B`Jv2Beq!xT7+^$b+V<%pWNI4;npR^T z?f5w^IEIV7MP>QVkM0RVf!A8fk=?^-wabgjLWM~9Y>gLAqWb#qxy0b#tvrtI$I>j@vy$l-!su0(Y|}LfD#r`f&fr zlisA_eHPC*9@^2^zTE+(VmSruj`ITdn-aN5DobiUFB2!Fd2~f^Z6xG^HdVHgLNCap zCNGGyicQ$XgudnmQ+m5Kzdf&d>_vTg-B@H^#hhmHwJ4U;deY&=CcM0F zEg`Ij4{1P05xH9`OxwR*H4v63YM>ZHlL~RET>B^mXLQAs$B{?V*B2ZBrs^$S$#6YP zqoQDz)hItt;e%GHt;ACr!hEUD(uhJBqh~FZ1&5$tnOe3{GA5;&pbu_uE}O0i8YGod zL|`i_i^soTz!{Ul;M0?vqq}kkS!m6tIpqDJWv#C-*OFpKDBPEAIna!hkD`XO1RLtU z=y9lci=8hAo$18O{LkAB&Em=j1gl^)UZivr)j{R{w$2;G(8Qpg^pflrjgWX_)6@Rk z#iusA;~h$QTI2iSN}6oBbO5o+Nz}Sg zeYaHS_(`^pBgZe>%m9d-W^S0+MJm-oNKj;}*RZw1c;7G@KA=HTZT!QPP=#t({O{Rk zG$apY%_FR_A!wWQ&U}isE(nnOtQ0ZihTbo1S2Oq)9EGlJ5LvRRX=GJ~jcLxJqkGXM z((M~^#HipHV2CS2OAmbV$z>11R;8aTt!h^4fc1CSc^2R8BoJ;bkbs^=FEnWIlOwLd z1Mc6Dg&2ucV7D`6PEh8`+97M8H!J5Z-)E_GKzCgZ6^}7p zwt0@4a*mHGM}|Z67~qFsX#38^$h>AL3;XK&hn(=bwgyuz%JFf!ff?{7SN~V{59q?R z)S!nwcYUwyzS~Y5mg3-Tpv1AZI0-wDsbEiwZ(${mAYis}y+&SuH`(hxKOekWCr1XM zHdY!$TB1eXi`_Vfcq=j4rEBbB(NTea0d8Db9bp?SWphTs0(5|HV*T{7cV1;>YXR%b zJOc0U@@|EsY`=TECqJ35&}jj*(OO+g>SKXuVF3ERW`=;-R1M6uO&6GRug=GiLf~-h zJ+|bJOSC*`%X%L=m#WY>&>}GDIPWNd?7bRKBV*QfMS#}AqH?h&%|sPJnBojW()?nn z8GXh`cdE>zzaMm)JJULv#O`Q2*VI`6f9W#nmyJ44bdNE%-H5Cl50pdb9WI8PMCQK|DUD)F};}!*AxX)yExO_pk>2n#c-6td z1oy?+KvX%#g3d3SLpWvr`7MO%!v{W(hcn50qTo^pFXa8nXmstIMnhOKN=AWfKO}F* zIs)>f1wpV=ta!~mW!b6KoO$jqohvhrYN+yjQyab_sR4S(r;NN`DOx%i`*iycX{KKY z@)rLZ;%dx|C}BS*`LVmvs(Jpb-Y#6v+AQ3BzxlDrk#}81+)?i9Y$gZf5*r;1r9Vq| z^Zv5~k>CAuj|t)gSsh+welO0SSfL`%c>rSQ<20&8=}X7uTWSPT?fm-E?T>+!a+hvx zl4BviJh!!biIok_TywnUSR;Q7dO_XgTgK^tTj|9)FJA}#SU({{ZoF463I-(pse-KF zyAY}M7oiI8c;d6$zWJhk4D>XdfV%>^vWGnf$qL{9OAzglB*2G^cS`BJ=SZ@0FM8sE zlG1}~VZtu8d;7ghSOVd__uxWSLfv^LyQ5rx^)yjpk+JLJEK*NhbSuZyex4mHh3piG zp`JF*@YFhiC$!=bTb$9yvzBg5htaJ?yr1ar!;2Sze_{RE#(6h8PfzOmEg=y$U*Z^L z5dX-XR%y5g zsI7;*F>`HAaQLOe^Ek~HXIEkC#ZHF7bA5pk)aucmmc#AjLDA2RX23Dl8Df8T*Jo5w z{$BaaB@P!N>NKQIZq)sq(*9@2=kZp|I);UgCNS$u!9rSJf}P;Bt-xPu96BGSeq{qd<) ziW>VkS|zL;#!b{QFC6YUoZ2NgxQ+vy8fBKLVQ!(mj0eDw9>F z)*`4+1oLMoo+04=??r;_y}qIzIvg94lG7t+SU;?XWXs5fuwf>C;4D2wHut{JVP39m zCP(_IR#=K7pV%QrAMxI1!p{?d2f!*5W6;q~;uGJG={V`x&CtrBOAmm45MLK3ofA7@ z&0`iRaxfy3d;ej^t5vzBl%#7HOTQRjuYixLe@E`pi$rDtk_!IhIHF6J`FLx}f(y7G zd|E4&4MyNiQXD230>KP>J65vTdtW&hj=f^lczpN-jC;YpZy2$%EPp$>;IR~&WK}l7 zsbBf5APt3SB0@qy-U2tY=9>qo@Atfi3iAa&BCd4ttzNT1C{ldcSDJ0ojwTe^N*{8h zxw4B*v^`|h?-VDUHx!8S+S$(*Zy2aSKKaj1jdyCpM`bQsHD2)OR}!P3uwHPH)g81# zjM3xo(u#kw=HcFz`WMQFx={iTkA z?l5*UWK_hkR(bTkHym35l}C=SFMncrxarfzytbdCtVx~-xAc6sT8>0__; z7)>ta2>)AekS6P52)+`8as*z;IPOt4^a04onl#FQZ@pF@z_*EW-fuBQ{)qanNS&)r zVn=q__hjbzf5a7kK?xIItlN9>6d!fu&K-7M?`9w*Ki(k|;0j6T?E)u;uOSdOP;p0R zf*zu%bM#%m#5I4QH`^!%b z6p!}90MDx7^Dc;moCU9Q1@eUF&<*+vXFL?oZvUYG?|Q>3nq;Q68}bG|)LMl*S*ymZ zhKr~1n8c|pB;>{2)T}gUmqj>CY&w3%>?N;%AHP3AN~i}`G_$$=>}R`^`Z1rQ`hbv; z5|WQ|!P65QF-cNf#(E@eAfXyX2zaoq4U`(Kty=6ar#-?nXZ_ob;u1+Tx`}30v;7G?!gTTo4|csqRSOu8`rfeX9uIQw3;ytgSs#CQJjvlqMmg!YvjOlSYmO; zjdvRX)~Jy({SGxZ$k8>@hLQvQ%tmuup8nL6r*j@FgX6*yCcPoh8DzWs9QV>v#pt;` z;7E4oBTZK!0F#js^HHg5CYCF48dIvQc}ngN%4DOv{WLkU zJc8Kxw+pP1$Jd93ap7KyHG2_9|FC3aj^?v_$9&p5t$g1~+Sg*A(W`C={}H?Rg6Ph{2B?GqXe36q3xnMUh2Dxg{}DzC^#+_ z(IPhiRZK7@7I;S#?76KN@Ar1Aa%$E=a#aoN5(1X3iHr=ym8MkJUQ6w7q`b5d$eCn+ z_M386er>^WSd$O~Kck@f7+&^88eBvmbSFYrQQj;HVwTJTLoc0z$em;AcW#GX4dAng z;VtoViU5g}E;HM#Vt~w2dv#_Y_jzMND9!1vvE-6cK|GwVQzAm5jAJ%jmWg9x;9QNG z>C!G>PizhK1kBx_(GU@@dz?Rtez-+g_5QrPfZ8c`Rl|#W&TDUcJ7vSfxE-!?Ln9Gv zFHIy{(IVH$I@Dzf$JD0dcs3(7&RX4W{1YhuPeG0cF4zwEh00q0nC_RZ;H)wke_G}?-{JHyDCObMq)AQFH;rXU62>9elH1JJa<2 z6wzC(6b6?R6oRVR`hCRyVP<<`w%_+g=7L0GNwZbTx;hxkl_cxibRIa{shnwH#G7tT zu8p`RuqmA3%{I3R(nqJgIqaweQxmd+D_8ny@4e-Hs~+PSoBPCh+0x;AI$T;8ryEfW z>tqObC?O)7A4~@>_UwKVipcOo^5}O5S%k0$dxt&?Le>w`v9AN8y? zr!KA!ZTX!hsuxMo$rY@UQl4&;&6Z8jbCMs3VU~hDTjvbLi}Qr2rYv@2AWi&9X%fi! zjjytTX=NGG-d=zfnv)Gfqo*{ggWne$78a33yFG+`-=p`XtcEZY@l(lrx%Q1mA^6pk zo?%37wy;u0Oi}26f@m~5qlaKxr&s5tZBz=ewoxLMNKRl-Z4b8UH{}Z@UkV;=6Dtl3 zU5n#{ipdkY^iEn%ixBwkw64doK$np58 zgEfz+M0XXxKwh@Msm+IBu+h0bz?ouQMviCoK6@Yk>M*Z2>a32};&zj=_-0EygHkT} z*$^PkRWOf9vt7(ElPuB$4s48C=;55^^NMBaGe$YmTe?Ncnwy$3hYn#02#T;`FDUs= zWqxcgy6}&_TY!@lHzCPv#3KuHl()#Px7fb8!b>v{7BGZmet}E2bk(?Zpu3dbos6S5 zm0Fsu+*CXV2SqyJo}vuwZHCFxa|pZ1?A9*J!i~Ee45wo7=Q))vE&&;BMmxwR`$T#x zc;%hsGyf%gdf_ULlzthwV`X~APHl#Ps;_Yb-9-|RSI8!6);Eo1-Xbq0978A7@9UsP zl;cz9h_2sx7eeOM%h&9a6nGJZ@k<$xyiv?@I8%wJEY;fW<%x6xQ@pyP+ZBecuKCSd>WTcQ>_L9>mJUX9HcVw0^y1 zpBkED{EIZh$k}D}iP)wsq1xd=;Pr$W&13l>K z$h&i80`GL=SJ zSq-zVBasoZ0Dl9yi&(EOx>8>^{}Rl6f|K?XK3}e3iGWHE`|)8-XfwkqzSv{5z_joT zc+Fv}43xx5A9sSA)jE_3nwq*B002BEluLP)$nhhDDYLf1+N@|LIJU@WX>X;hV@>$L z5Z!S!Ae6g@pboUI@wTgPpxY0ui-0%;W+qz?0MN)3rOL>#DT435zWz$mT&KCc`Zg9F zfe0S)tahanR?#zIoR>+m^8ah z;zs&nhKj<`NRyl*XnuI$KCxGSZNXo&Z)1Y$+nHv!ZQqLf$5R>!0N&qt*(p7?y7hTg zznEh&uk1MgsC|{I)7wS!Uh6Xqj7Drj-;(UCo)TGKSfSOwG6miZ!yju<%aMxRhQBKxNznOfve=w1EVvY_ej4U%_8{-(;(lf zX+Nhxn-Z?RFp|cU(MQ8y%wc&M{fYpS&~PUOmBG3yWQiW{bZ^!EUrXn5&z?w(SN-Ub z^hV`$jHE#>L$qA|F}iM;&o@gr0pTVF_HEiuPEch@TOmUxnS&SAunB{Sd1->LQs%L9 z8p1koea6A~|0JzMe2B#7ds1BU>=mWxJmq>C17WKawHQ+T|H6xfMu=MkKyKe1V!!OH z6>|rOA~EALfw26u86{Mh&U<#?ASX0iqLMe1I~A4^!&2-U6~#dD7`P{`q4jLIZ-o8O zys0cqY5e>6E-4-hAd@p^xWjtrsGmUiIJq(KFmp;DIzlV3aNNC~l8e^qSP;YS zjJYzzy7#t5UiQ~);K0ZsroKc7d4 zoFyWHuMUzt`@L$bs&tx|v@jXj>wH+HqI2Q1NVM3QXmBbw#KSChY)6D(U!Z|1V8xF) zuYy?#+6SP>(TA1)sD9J^$h`uo0Oc}HMMVAkPo4z$?sRhHH zRY?R8l}iDrtKozuE4VMrKh z%4RnexEAG{Zaf>S%&M9fsy3x=2(?Y!N z9t7(=k$Ah4UzM`DjjjuU43tGb{v!|68?fk;U5zR5G{aFlD=^;%sTn5l9a!9g?x;4+ z#=}pe=w|eDJj&__sC{O!(T{nP)?UWVi+tq?%DwDL>bD5S$ufV9s&G zs2bLTpnK`DLJ6u{I-?a}5|mrMUGVA(8K1wPH;U98K7ds8zxW|J{e;yLD3=Mgk>)3? zD6mi~b0$1{ie5WU*Omft)YDMNpnyiG((mH?xOCwc0u6go1Aso;ybr-ji6TG`dY2&& zfS}Ah+r_wIO`i?2l27@n)6hzhmOcF`<8i$fINZHjO(R|9>F7!B3%|rV)>$W08KwxO z+%TU84ifez9hGt5SwfCZ>DVDlXC6LaFfU&=M5s-%}XXYbtCV7s1Ti;jmx31 z2Rx+>T$3eZ`+G@sg!8W=!WiE_&}tqKt&tKDs6YDgbSKOqa_dU;$AhPQ11#^KqZ@0h zwZNvUlwanJKwk-<3f0nPz%eopI3U8M&ZwsPuy+u@ijJfKow_zj+HXVv8)McbeYi3} zPfa~6le7Ccnb@SWky|lnm$ODIIP`laqE8Z|*oYIzEwp<80F3M>*6%;Drv2YoZ=$AA zXcL&SmO=n{k#+zMueXIH7OkjzjJ|ftP%sKl03hJpxwme+)@tVd>S=n8?|cvsflaZT zD)R+zfLDNx8ayFp=R&S)LNEtu!voUH!7gfR99$z|tG2Rfk`Wb^$&Kf0`$7Gr?g2qd zrf^d6qSaf=`+>QxiwwI95eTL0k%iXLSZZ~@Kae44(qft8SMRRM;a0G$~ndS+6)Ih*~k&EMq5&aJ1G=;&CofFO&B$0?LXUY+&HTyq32)Rfj^x@93BopzCG5;|wtRVzn{r=B^ z5@d^J=c=Sa^qL*W`kCXx7|x^)MU8f1n<5kX3;b-kAN@z&0M*&uW|zzYm$g~0sE%Hi zF1&z@!2Mj9)y_edCiP$e;-jnk<#Wt`c}Irw8tBf))lwX)%|?v3#o#R34_+J56Qxre8xtvZEY@_|9@op_p{f z_2pDTKs3TPl@`&qKwP7Rc3iof495ng)h@y+a1+rleHKz+7I$HveQ;hCEz4p?fZTW& zhn_r0l@HdfP`;9=$iE^Go~ZyhHi^VYvL6mZ7*B2! zrmr!`^kTS>!itC1rWS^-Q*>{Y==0@htK>(pBtTIo2S_lff*Z&xvu}-#$L8vosd_?i zNtDvefb=@)Lyxom@BmsOB;x?+$sJmzI{Mg*sv1yR9E=RNQ9_{%o<{5eWW}Fn0UbV( zBT{&H52r=(Z*NBCj?9bpcU{+F>^7y>48EZ8q!^r zO$=#!*P%&HKsh^;1N=5=daOjDOgh&5afRG(IAQQn_Aa7qp%xg2W$LK(<=S+K_JY+M z^IY@bzh(M-`YA@4_84HuV;HDYoWF$+p- z=WxLQ;6jzmro3;sD>J{8GYx_(wS$&DBk=P)7SslmM+$Xz-hm^uy=`WYcM2R`l0Zc$ zPiiMcdt7he(@fl+RoeZ&^jGvYF01q{e~0wf z1TQwFOFmarmd{qP$i=ExSk1o)QXSc0tXsO~`qmy*dUdMGtGZi#J9RuafiEUJ!~OAhoED?A_oY6?6B07=6=`>%~}-4*TWvVIQe zN7erSz5$3YXC(!2a?b?#Gjwhe5}--_(*(2&0M-2&(?lp!*fK{jptZFnnJNGv^S{@| z`$nHg5y(xb2tiut$#_D`VV?@4J8)x}?qNwcP=Er%(q3^ z6A{({=eyInaFDsi-_JJXmiCISYE}I`V7J~qWm#GD*#L#w5UM|D zBj+oU{mU>~db@kdzz}>3ETxk>T`e{CkyxP6wW`iQ?|^HQwP@fQ43v%l(z9%eAbd&tQjhhd4R-InL}+v&7PM$?rGFa`S-fA9=yH$aKWh zbPor-n|e`0t@QlwgCm~ZV!1DP&y%Y_f57g*2H6seNhLwL#jnr3V49bP!h)-Z?Dl(@!E=Eh*?&h!4SVRb3v}@t(}`BuDzZvsHae>*ui}S- zK(jQ>|C5EGgi_S8djPu=n`W;ZSqjD+HYLw`DImpE?ERg=GH((RV_1<`II@B@p)B`= z%D8!Gp_>u1Ak)HIjZhS!%K(*x-RL?gbnU-9=&=<9Ka^hR9%tlCICZmdZw}c-y+lyN z&X!$qiB4wG!N@0ahl~Wnyhxk(&>w+CicQ@uTY$jdZB?X4` zK_(v46v~PkN6D)C!Pc0_<{uxTaC)NsZmj}7#^V@HXn1Ds94e$~n#-~ojHv-!MAhOW zFKT*-C84eU1K^zhEKe?ka;0HK<^Gomh#LSfi~x8B#Km1WAOM^--b_gT226CelsYj4 z{P9<)B0y#Hb3nm|`EkWDr#}2`KyxGaqexbg|sRukWpiMQffCOyPr+~#%qLT zISP873QT2|;XN7sHcwdiTmJkhAcDOKw;Q2ycZ8+#(#Ys zeP4wYbL{=iT8gPpTTBA8fc$4NgQ8y}UDz?pvEd&FmV8*$;~u0VkPET~hQWfM9{>cd zK_38cS#i9OlcUr;@HuIkgW?H-U2q;xZVVu9@e4z7>jswnjnc6QZ9H}LyRlal603Ee zfgy;r-iA@aJqSMWso^o0wXhb5;s<-~5B977ANzkKj5G&K@%jJJG4N46QEpC_c{u>$ z$Mh$ioX+Z}3HYq?6GH3VrTW0`Cl}DMe06{)B}f2K1p)$43WjZJ43r{7U&M1?asfKE zia_}wec}Y&i9Hd3agL6%0ziMp0RiX+Kqg20>emni2Gk?QRX7VmN&+BK9TP@ug6-j! z#mj*g0DztUvXC*LTxD9>|6LdXQd>h0_~{Ll0duVFA3+L24ftP&oSy-qBtbzDD1N2( z<^!nN0Eo%pV7HC{c8+mOAU2$JKCA0y0LZ&00J}iVNe$i@sRIBvEQpXu%>I=zc}IY5 zq4^6O8z$I>h_zaL2Ge_=+1yoF0gwWhVj?OIW=$VlC6Yu!2qIEG7XcZ^ZV1ArB$i1W z0H89I^O=xNho4(X005xT!?N&lV&~-eeu8Ij-NcUeV5q}ADwyI#C@%31~Q6{LiH=|=Rwm1fPgZG4fOIPP1auqz&&_x4{wcH zzpDj+g`ZRXb^S^LN3o{3Q9s`+h%Rp=)aeaE4jG0d?o6{L?@ zdbU38e65F(Y6XqTS2#IB$q!H<3<5|`5~j^r?y0IVLne`UgE`Xvm~L+W{OQ{j%2cuJ`7a;)--HbG ze}6>(C1ivEps>Qur~{F6hpQ?$Z}ER~R6D^$R$}!HL3Rd=QDnZ3L;s9t`0W(7k<=3D z&bcTMzGwORS!edhj4TuDys$2kAXmoU9|?w-^N~!_u0nkqcmckxwB;Ke7naz|K}kP31SM-b#^SaYGGH z$vg8&k9CupH?EmiNt;t`Gfz9XgZ?Rb-w$vK7QD2^uRTniR|&0$<#Az7jw37Oxs{^V zwD|+gC9I@SqJO$zlCS&Aha(@oMN=EhvO+A)6bwd&Dn zNd1{=TK{dstd^aB0lc9D%=((OU}0Y1F6j=!=~e!aTJYDQf0rHr3$YOBZrzjuV*F<| zLT7|1f1_05yJQQDmD5s2QzKt6?|gjejc7hq2wuPS^MYICx`1*;&%CEXOJyO1Ff zFr+_djL~xGH%`xQ$MG#nIit%gsq=FA42E$6yc^#qIL}wL{GQMnr9X7n=?Ymf4* zg|3be79ELCymhf3hBN3(<=f_Yf?VG_xnnkn0xsWwV))M~+}S*#p||k!~$?f}j}9 zu2MIS^C3VMfoHI+yEt9+!@(^GwQj;5Qn z(4b7`)r4DLZF}#>zE{QnB4g2&;8|w7L1i-~;|<&;0PyAj0Kgznu5rvyS?z!G?GK}1 z{+t5=fM8-0{%&|og#*BqiUPdDmjDP5_1*!%&hQjr`6tr}VAof_E@(mMp&c`B0Az&F zQ=TS6`+(!A*apx!-O-JpCxS@n^qZ!tSaGHm=^Bw4>8Fker@^r^}K zlX8kSF`2@Ef>R)V_NY>35$vmAH zwg3PD(%#RKuo9h0882~NK+Xyj0DZgX*3$m z>8q>mqob>Cd4rjraO1?(7PJcEK7kHY8|{D$c(9qxE;2E9bHW*$Kb!zgHz&A0L0yrG zJ5-lN7HH29;BQvOxV=|m3dD#wQtVa-;2UW1@o=bjV9%E#%>dXR5a2)%;EDem@P_-p zX#c_gnev#V9t`TgYrwwpn->8H5D{%X2w6P*-rf%i767P-8vvN& zJOJP%#?>RHoxbM=fW1TV2V(&2o_@?eyIdWB+{cbk=>45%2newQaG*Z}9>H=<5%vGe zC;n}>IWwDyNc>PikwaoOA)T2w-5>yL+OVGyuZ7b#83H~ zh%mn`w9gqm0%7k>boRZa&gBzyhYxT{fZAfCyOFoW`~tKq}EmW--7|> z4#g>jYmrIGwO{;wb||n1AcF&aN1V&f`}x%}Azzc|Aut*I^&|j_83)b%SD-P!sd97D zH5Ep=sm>L%7-MG&8jC)Q+zxiu?Zkt#ZWeDj&H-}s}#-0ZDxQf)S zwSD1IQ{LTIH%2;c#x78pyOgbS!3CeG*FxiRc0NYOXEdp~dz2$UxpM-LP(G2U%mOGN z()v$rT~qo0vHoYyKc+rI8OI|#;^^ae;!kTa)lm_f-I4>JwPm>_guxbI(L0HMX<+22 z`wi%U5z7UJTTEb}L5u-H!dR(xmA=HnP_UcbPt3D6VPGk!mLB7jMbJuO!no*s@-WQ; z68u&1+{sGB^E`o#GfC{H3m?ZOk!Z%18R92{VN|t&Mg&8@!30WN&C8oMq!+#_4)Dht zF%}s%{0N1Bd+IwFrG><+dshW8UZU^RLvBgaIiB&o>v=P;-i4->_BThy! zC4$2vp_gewDKnI=cMYl4B9PD&Ao*nI-2sv;))Zp^d>X{kJVY`~k2n9r(*8@+{zo{| zzU9@^;)rk|zxGY2cU&DRd_JG&G;pM-wqG<%YY#w=v(2XPdagM6i4r9onRf?JOQPp_ z-GlGwFNkA^D(W{Y6m{P811DF2pHktnZsV0WW_dvdi0#5XNK(IZe}-&I%?v%A45((d+^)OC7J%f!4^XCts*7T39ckI$zzTU0*&@yU3U^_CP&u7C&{rHs9@`|EbaEK%X_( z?D8t(7qn)FME4c7RBwk|mi%F>j_voz10w~td;f|d&1~0%{sz05-9M9faxKsI?H)^{ z8-AkH8MxTBAK?IkYX_8kg%MtFkx}*yCeDmcHIK492`ydIowzR*FS3C214ZO#|HKjg z)(=S3slRi^d?pei@6b7I=?cqQ@^u6;>;1>)>X0M93!!zpQlrxBj?Z8@_B+)nnf~(a z;K=gyTXHT zOZaETmKlsk!pJOMahnAR>#epc65NZ`#^w76z*fT&xAz$I(Db;1vCp7E!u|D0Wq`2F zm~BXQWN;P{P6~bjfHi>O>#gG_nmkJwNEB60)1FHzW+!RzfQPJb>0nfpDo*Vo(k*Fi zHv&Ai&mFuNa8FP^L?V>MTYDHT6|=umbrJew7~5be_IA~AyHIg_R{V29#pNL3@sf>8 zlHnk+d<^9H0f`ZRLuk()KhK(8fF;$G4wG;s|AncKPfB1vnk`!)&>a>ZHA(aiLz3Us zx(B(f8Jbb74Y4Ig#++TzLJ5z)QYvCBG&#kJ+{p&jy1mR!9qQyso6|LocF8G~5&&NP zK<=mkEXO&@GuS-{+NwCTa#&6K<{8bkG z5^$gOa11Fc!Z(cbz>Pq-L5hL%gzf(kKhJ~X!->&%{s%cSeh<)kEqQT|!!Ha#Wyb*k zOaNR6o*w`_;D)A%~`{) zekYQwF=Y9IF!v?Qm~#iH2K`PAwyY7@f4m->&e@U0FF&wqDnY9SWdjRlD zkh|*_$#5BY`>(tE*WW??hrR>43S*N>Nxw&Djdwaf)1>&pvU1bzZ>eV-vy+Z1CFbYt zZMkvP(W8bH(5$&*x#QixS7EKDv^Kfr0RZXbaBA3pEQHC@xpx$RG=g^oPUkd3avT7z zz$6&8JYX^WK0=Na%!0ZH98m|dB`%&CKp9Al&bb)Dl3NcQsW>w9zN6 zA{2jraL*Hw?WAw#*l41s5gnG~C#4D`#og-AmgZGAle)@!#^Wqh;Gz4vtR<5(qwz`% zKdbN;w*z*}KUmlod^G|>TcP?Wl&w&B_ckLAX&k2HCwxwZKed5FfJefLfFbqZPnFfE zX8LDKIw!xjE8#wpeva=g`Z8&TMtO=W|SDkqekofp}uC5htl zAl?_!n>pYACje{lUo-8SgFXKtmLwLm7XZqw`-1Fxd`xFFt>P zD6=oW)??wRhJ^I26(Fdj7wj?`RNrDjj`LL{$6MYd|5@mtUI#ASw48|xUIqY0ql#TC zLQ~4WO-SQIzF1mRY@gBd`p9fM_GFu5_eMhvqMNtWq6^LYE{4G!l}AG|BUsJBvCtr| z;b{gfc5r!r@UNscn|`SLE(s@}2N7Kc0l_S=0ogzb3zS_#J1(<%p?V$Dzk0LuMc&QP z2XtdWTX?Yf6B)iqS0pWlxEX!M?-l0`6^)qkhq$nKH;)qDa$yA!Ju$0_%s;=2Vjd*hC19Z?U9y{Z?Ott7=7vlF$0cWQ<#?zbO{JXjHE|hfStz zN_bKLi&7t96q{$+1EpU6+;@Ni&B+O{)V@5?!NFUYL>6Nsj+3`NTHFnc->?4B>E=mA zV;J*C9eH?+z#m)F6SI=94{!2pzX`-*jGq9iT@@n>?-Nig*pbPx>h>plQ+SP#Fb2r0 z?A&II@U3)v+lc@m{hyl>(2vGi;I4k!B9EkEeDEk_<|04Wc3m~IXy3eVttKML_Lz7CjB!9IfZ z01iJzG>rO{Zn+d}9CaduiXcloBEi8TEXh!QK|-0cMrP~c4Eaj2fP6bt5VK4eCt7r| zT;G^sCr_aJQCgj6CagQg`j>N8>b12}=t-{wFEMYDk6mW16H-xe z^Y2f=W>68*&V^rLrxr3e=|qXcJ|MGvLr<#nXoF^g*}XIzEn;X}g)(ZFG#A;;2| zx~*|uc~~#YSH6;fX(JOy+v%jHV64!YU^sXsoA&>Dw=6}!>#+9{c4lp$wM>8sD1=3f z%uSHgeuUaG>-5h7((WSSz+9N~{zg6&|LtGG^J@nw4R#0&=?logv(XX~wHU?(TFJdK zJ)BojpJWSn3wi*{UXV3~AZu)0{?)htbIA!nK-|?j`2EMQ|C$GrXzNxB-UmR?1F(Hm zJQgEBoFAL}`O5aLioEF#m=;J909~HN*aNIo9f?|U2%2B=u6UcbzT zkVGKqdr6TaIYM+lF#6fTlZt&c-*6j5MzyjB+OXk&=(+${sA~!Lm1l)FmX^u|gEIKq z{36PrJ6`}Y4+thmyAF!_7v{f>4$`jwKNy4jNOGBMr~X-kF?$WFVy|OF9pdxP77&(l z0weAXao=uBJ`LHlb`j(I0ASuY!c01xh=6===>T%C!~%)XtgMcjEci>~+*2a=YARc& zVsWi2?wsWz(sDl-@q9aVKar4)CjX`I8q|ctpoVZ^y=myd4&9WM+-w?vfeQA5+l8dh z2VydCPuXWKre+ZBgtD z9I5dqP-YacdmZkbIRN|{Y%GXYWI&h{X@LYD%_xA~82Xn)sWl|CALI<64FFBhiBwe- zh4L0+Q&9+>U7MDWEDK^8-wgFCZX$=1L;eyTl=s`7nx$vtArFrMfJ}@Zm^HlXD7Emt zBW4i*+!r|1Q+&Z4PXZwDSO5s0Tit|4tj>Be{sphpi%Cm}Q-G|Sb_k*g6;KED7VvnH zjNqX>VZHynbSc&TX>RcD{~QKqLi}PmH)$!#T%d{He z%*9dvv*mv~6$C^Ns2L!D>vBp2aQ@hGu=9F&d}VVry#AuEak>VTY#N!T{j2zH(6phl zE4!NNyoV0PsFo6@uJx}K7#K;3p@?d3zhu@n`6a3UbdmcX*ov>ME)iVf#Fq36U$Vgy zs$s^o_+-0+iAe}L2qNf)oc^7j6g@of{u%CaxyQl6meErnKDE(RCiU$IkmMD~Y^NTU+Lb z87HEkOtS5aP>E?E7BK4kw3H1y%v*~oPMSuu7fFz|UH)9P6JfIl+>1u*#ob-*syrt6 zb>wh{T$$&D=L%D<#J{(svl50FC-H9ESrGlb8m_gR8vgo4Sa@$(H01W^%VyICGE1tB zxGFejg;NPcYS>x_uY_0unvhnZ7*&1ZvFx8$V7)S;>N38CUgueLhvvsaX+c7Akl<#+ z{?wGmL{k}$om&E(fl$S_J9%LbKe&MPDw~y%QjLNDEJf(;i^l!0OugpkbEaM%fx{jI zJ(anQX4vekrIwN6Jh#wb7M9U|u79JcX$x!EtMRjUNnDTupsYT?u?3)A`0s0skSTeq zh(0T$-6lyFFR!f>Evu-5QM`Uu)>m@(dqY z9yP%enqN1ql_5KMyUNGRw#WqN?DN*)BbVwJO9cX&tJaj7b8*}1eApC2 z2W%y|EE1k>&WgVGNjyR~y(l33?f(Mv13)jfSz-230ULm3d(xD$o4mP265o1R(B1uoz}V6upQs_A&{jPJVJRc~DC@wF6P zGnk!5cPmr1)9Eahf9K7Ijx_486A>DxrCW}7=?Mar?d55UoS2S3@m)4=P~m9`Q|^L1 z;UHK}()s@pP+=`0x}ayE%c+4+B6C23a@;RMFh|fGU`jdA(=7KpSamMq3CaLiLI$Ah zhXa!;^lcXdAj^Z0Y~loNEEFxt1M$LT9RuJGyd6sy$Z0d2g65CIQHJryOwu}ci=GdK zGAp7Rm8q@FXLB6(4J&(E(2E@Wz@UlOK(U&vJPs(^T{vXQpZ;(Qp`NzkB5xoC1 zqss%|rGv^ujvD?2>S1lf05egnf>^TabcjqM0D;2Y_golkH_{>_HxNc^#IUbUyoB|d zFW(@Cqfa9KCuQEGySpy917bt478?#OySKlozckXeT6ncC6EW}A!vHxvn|Ee z*-8cumU_m|qf}`Yb)%Jdudt*tBmmkYIuE#+YeIk#b3*yyhvK483jiTzk8uu@x{XpU zcQDvY^ZUfWxb%C^9YlwDHc$p1cnGlVfD9`K8TS8Bo_{O?O~l0iS>Vh7or?ciAt0>j z2UBLgxO9wxDl7&-u&V%&7OJSi;sy59hEPL8cuU@B*SWKy$L^SP?n%>?)ZeP)xF2!| zQyOzEQpBW`W#K2H+9#k}aA#-Sdyr+m0yMks_i1_4FzTQ&eqdO%(J76x*gu*c-c@ME ziDm+KHo>PA#WZ^mG>;?wkkUYC6G3SIhtm8P67Vlqi1PavBOc;^mvF`~8hW+?2+Ul4 z06$L+K^QN({h; z0e}2pQq=`}mk~hBkg{PyJg17%QZNqo!TSHDFc3h1 zy)p8ZBLE1F7z4m9`ey;MF%uACumCLovh_L)azBtHQy&P4m?V-9%g-Q6gYGv&LUv7b z3%#~G#TSo6JpqPJwj>c^Z0&p@2EHBryj}}Gzd*qMAEx5RiV2L+ z3;V&5R6Ro!0k9(kH+cYLlYY%8*A4(~ehoS^;cG{}_Tiy|YqJBA!a#XQQaDpc8Rup& zfJC%Vm&3XzhbzzM-zl%9FWchdyhA7k`Ais`f2Jd5%b#W>bMWmp&-Q$YuEHF7oKG{n#0?CFt?-WW7FAx??`yPWA zY>%IA7!Bgq1o}S3!Dpb>SNVY?vYIe3$Q8Q2qA(gJy6yZk+&7Y*Z_(c;3GP5eAnF>U z!OLPQrDG$&;o-(Y6bUu1Q^1$}1>oCkcpE-{5p{63ayCi|T`Iv9KidD%$%2}h5p+NI z{pv>kdE~bF7nF&HtPEc>lCp?I_a{Y+V{WFMb4d{3Vm3 zE75NC4F}z5h5k9x(y~T_`Kq0pivBB+(pnM>q^Q{V^XRhwp3>Ays}b54NVP3z)dDD| z)UH<3@9%1D_}c-uyl>+J)uq^^|`tdP0KsH}d}^Re!KFox7Y^VOFSYKOz(fmf2C{Z{`X!*QZQ zRy)YI3E@K}k`Q%rPFR8wA^yQz#pzna2A85)6aP)A8ryg_@btsPU&8RC&c8hL100%7 zN1Th`{EBM_I#qeygf;7A5%KD*?y@T5`FkT>b#rV$ty2nhpfy&7*WjSR6SJjqnFeww zQwy*Lb$Lww<7vKe=}M)*T=I!tZskNqyY{%q>J2Jhx{4JY)|bltgWky$-7%fslw~={ zJUugnO;c;>>d$!m_L`WQj}9DCgV(g>C2cV#-bXD;F?9O?F;htt*~gpMUz=5DLylsZ zzPyG8wTTadVo>HZLqpZh&UJW7*7Y3KP%6)ic49FJ0#`4wadQ~?v(x<8BH4L&S}m4N zD-4In^@7rkrDcVB<{wRn_?Y!hXo0JFOfo;ZN%U$qS`jV7u!?#NYrq$Xm%1jisGV9i z^ZFRyGUUzf%EHN*#(S1ivmg*#U2C7_QJD_G$x|Aa>YSll`6DbCkytcLQ~JDQg)Uy8 zOVGdkT1!BiwxU$?DsB7m>u*W0OHw>>W>m|trNqswo_0j_m2NjQx$w6MmxDqPvDXiL z4k~V~G@k6er0n;D$jLw!qQ(AH)gK;nIK#;eg{5H7juPSO0t{yq@og%D)kd(g=VmFq zZHXb?{gVp*nS)(~Y+L=T>>S>3J%{w6L>!6ER&|RJQ8QL#2e7~0^xSYA{bu~vVd6-O zr8xC4j!b5kg^+&OSTWYPnNDNOU0FQIGJ%m)>@>C>l`QNp4*SE{++fXLG9%JC6`S^v zne;FBTn!97E=@nAAo@NhoC#wPy2BLC6U|2DY|)I9wYGh3==&VG{_33Dh_+Xl@-T}b8fJ3>MB_Pomh`l;gx@7uQE?+1KD~Z(W*vf%5jz=6@^79JhBVV#7Jt` zt{3UIYnqUUduu@`I2&Bp)#I{Ew4Zb|yz`+FzKt{xj~^y0v%ZjPB)A7R{X45lg|QnQ ze_5^dA-(&?&~5Bk2p)G4_`?oye)u3JQ8s)#ek#+v*YOih>1cF_|8-g&;LWpYJonHq z;D`C$(m(Jk9iw>5dFb3&*JixMLhz@jH!M>Y*3F-@K{D~>)P-=Oo$Z5P56Kk0Fs%|g z4B&Fr%f;mpG4&3 z6>80k9*nC!EE|@FF7h+5$!J`)NcM??T-GsVMj$0%b7TMWmZOt9YaXF`1z6~Q~ zqkOuygaIQkP9xx=v;-r`Y<1nfYo4k+d{pa#dS z{r8ASo!6R-B?p;2^g6X_m$26$Qn_z%)Vvu>7GoeYBgBg#30mii3caDX6#=nmfnSG6 z8YYf&LA}NvdcSoVYI$G3S<>~wrLm~`VJQ987mu98ie7Iyv4=-UL{)`!P%<=_1}~!h zY?Z|q<8f)#EveIFO;%kyKmS^CC*s(NbTR~w+ZfS_>oc2b6O3j}I|;9uXuDvy+dYq> z^NiLTRwi)R?dCdVr+ZRQ?i95RJwYY-R1)I~>p333NfV1cPw_(^R8iGPLU(MPBYREf z6!=K#vaB&^e+K0CN;5qH0|nt3J?E`2G=&Ad`3;=`UbgThqHK$u!~~l;!tk^u`ssrd zq60!}W2SJgA#8AepmWmOSfoY0YJ2Fxzl}6k{MZ`qq{`IEdeHI7;LP?*EB_lqWC56#=hKN<7Gfv%EObjZ(x%1yO!jL&>Capwm9Z_Mf=P&5)~r7 z@*^3_{)!?e9r~dmZd2A)OJkM>f4qG2HisA58#?+~w7ekW?U1XUQK(hJ zXlpy`$mLbD-Gct-i;@*TCmSb^A3u~;jk`@>)5xK?G(A(NeiYB!A$Di^*KcnkdBo){JEDR&y4lQmk%zL#;cFu^eia9+#xMlZOkG$dG}m z7pYR5K4uqr{hIh4|CsK+BpZT{QuNjJGAb(|i>j3O#cN>LN9#M*`0gJnivzdd*jbdP zerK{Fnq#r}e&344=|9JwJE9|XDiN@k#ZX@_*_q8U!^#u{?`-KPs4Q!Cl`+n+XItk% z$wGPF2>)hh;pd7i3H+!}#ZB?m3D_R3AOa;0`X;y3tQ@fu=X2(N9?API48Q6=iBx;16 z7`WfhSo#b`tMy1@lt%r9pO~MDS7AwG6}9!jobW4>qKgu!=5rpD4HOTfd`;bY+Hr;H zXR@Fduk9?Uq;0?Px;b>rJ?e(d+MG@FtPnDX55)zKTmSKxP*MC8`>d(yLaIYo2IJOs zVxX>k0WDS!{#%_*q88=ajche zMD2%=*(VTckG{%N*%)d^M+0-loGA8S6VO)B^+ zx1REHP(QDC14~8gfbeA`iQH!+9L`}|!W|1`vdAr>k5Wd*%>FvTvNT!Oo#agSp*c+v zV#?MJSo!V-Ltei0sPyVMvt$}iV}-UbuPUK5nV$g%NqH0EuX3xOJ}x4ejqL7}uK&re zbMedAd8OPrSw33q^0f+z0ptjL?6T?cDvD+}ub0e->A{3avaG7HVz+J?LSP%q!>>mz z&XR>ZJvg?gsHs+OY|KJ#A=nPP#<9wCEtOWsTC(gU1I0+{4Gg_`*x^?rsBLsCUv+N3 z3bezPo9b|%sD;Uy@EegK`GxRNYKJQxEens$B*ZS%--b_DO(owfn<}t7+cL|>wNma& z`1l2cGHa~X$+kT%x}G-Ue6>*g;9u_I=LNju1gN;7@pT{8!g~bp2VG;s?$o2|(*@eF zv&4?ZxF{i6Jwcj(- zbqF?=gL^)D|9cj_OXBuJcu;aAI1nQ&%OP16GW=lO%B%~C^!jl~py-=G$kQJ+8LC5l ze`V*1o(@YtDZf3E9B62A132<pWkxKu18{z5forLaFXdl5{#YN54uzu~Cv;nsZo3gU3?U1o7 zw*JFT)LcX^2!U|?-oByuv~+#FsjF0aLN9gsHK+VHnm4b$$e9yMbVj3-NQv`lFQl_C zyr9)P%~nhdXNoJ6y77b*L;y+UGT6t=^ZfbpCO%GM@jQuPrq0M>aoRSO%Nqc#g6RVn z1ghgK=R%wReMzYQRemLG(wPS59R1!UiWDK<;)_mdKvMEWIZL6q#LC*s(z1QzLElWv zq1?*Iw#EIVhg`d_e8l2G@Ek-m1%J>WOpxz+PXPEMPOYdY`e8}1J!3{8AIc{4f=HMb zjtHkIV?aZ2MKFAfO|uK8DCF7a#9(boXPJ08bTX#nP^^HZwLS_R2nG1Un?$vNpK-wi z8gCBpNTcgaSg|s35N3l4eV!-baronU2 zoQ&>RR?tf+6y7l$w3{8npSCmfHj54?y_iXU9BQ$MboO`iH=$Bk@GTDK*B8hiT4o5A zarW>N`KyQ?TIM*x&W`&f*gyarBBX3u}6HXC!kn}C)GJjbr*6I4BCp-IfLProggTyh3B=4|<+l`Ki2KkiIjvuhx#F;>K z&*Ko=cbuK+mt;!dG9c222b^|XG~koz;*klqpoyRa4>{-Wel_VVmB3@?S`|^Y8eY7o zqH5dkVouyhtefeI@8MeX@wiNF0g8kpICa|mU-1o6{7@&e8&vbF1=&onD@!Y2X(Pa( zcdZ%DBB1Lg!`PuObLSNiJ40Da?jf#r%S@vf zpq3{N0Z=)Mdj}wXP?H(u<3ZH&Eg2mwkF3KGud=HAuxu%XE0x~PBJIO z+!)hBSbNUAm>BJSQkKLuVz2&znlt~;k;vkX(1+f z$n$Z|l9KdZOymE~7fY=7$fR=NK(Kl(FL|?ak^g&;QLUh9OU`m3@1TV+OWmY1fZ@XX z;Sfv7<*C5`v=d<-a>un|C;mWJzV%XHHSI^633~&fc7t2@Hvf$ur~eP~DW|Tk&)ZzB z2zV-J*c!Nfg1`6_;E4MTXu&$gHkC=ut-m@V*ld@16PGnHQQx1dR8e5@; z8V=8)ph)4&8!KKZ3&GCgG94YsU@@F!DsnCdK759qr$)tdzJkSM)?u5^ ziHjX$BTKhbsx<9W=2cFIsAnO-%E4H{(yR2Kcqza>xwplfL!V)VoMR2kv1jcXT^Gw9I7;8fDoUQ%mAFe*xq*A;G{xO>y z+K-yYAKwFN-zCts-p+BBORnT2Y&AY=PtS#`%BLAz$#9j&+b%aH^>{?84P$vGoseV1 z>Fc{p1{02$GNbJ_Mt8v}(ujVhp2mFiemq?{n$nsJn^OC$a?h^b{n?y9sO#pH|6H*z zX0J~_unT@hwYjmpE>9Udt zNePtYuzFh6oHr2*-doN5>-IqApLJ&;O+z227lh{q^_-%fW#%9gFI$(va+?C8n&xOe z%-#J$$hlLt)+}R5E9gMt(nAud|{dq?=6Nr+)}eDXvescK1w3`gPC@^h*?+&A(8&{d}nxS?^U(PpZ!nmW$P6 z&{4zT{K_n@mZdmT!7_CGrmwtW#Rbz(+npBx6CL>N004fm6+cQK}ljlKuG+Nx@O)ySK?LdLxKy%CSvFv>x3-KKi3K zL|y$He$&S_UZr(qSQ;)XnyLlqhU_B27k)yQiM>l%jG)!FT+YJF=Y3`FxbdlzO-Z47 zQ9V?Th*A~DE}9BAF+{>D2xG|kM7Pa8CWD=;5Jcx`GU(g1A)XK^ac`6lL9Q+FL?IH= zt(}ps9IV5;jy$awGw#oX?rjO7XMYI3UAiYm)85uqyb2LW*&D`uFz?nZ{R$C?Cp-<X+eJD6~H9Fm>#N#j|JE|Plt5cXE< z7jIAdx`Fj`l@?Q%Z@Ah$lOM)zDkd|;fyO}PX<6e2wXDJI7Mfp<<|V+h-VLAt2aIqE z)JMn`KIe9R!(`feCwlkh*THeuPibKnu{X20FEuh(Vevf{4flDTl0giZBM2kb7~Psn z-iC|1Wfuhma1DqvYDC;IO_J>8q!)-Nx;WMEp7?nzt(A{Fth^*Mtu;YvDEC9&)-z;_ zvjRwm@40=q$78q*O#K zvpHdyA?1(EnC823e%>hZpmA~H$$wCmhyJcU!wG(;7t0T3X^l;Luy@}tllSTlr&Lu0 zMUwb|G0Zi-QS@4?edWxo9`;p@%-*1evt%op-5~gji1a8zG_DepF?>R;Vg1(t3>lm8 zYK|hDFd`Gt$Pst(V$m`=(_bFiSREp}5n~xln|2uQp1hhFh9}^}W0x+0LPkWLbmu=2 zaEnJkRSpn++{Cr%VkmanZl!*nyJxczaToDCKPNag`C@yFwgrE$TE(OIF5mPEgUnTu zq>#&(tFl5)E&{&;59?(egX0;zZ-2_2&*QI{Rj9lOR|->&KsqBnULt$6wR4L8tie}1 zF@jLr?`@>&jULMHZF$a@rc~+=uQ0x44Sj-9cl33MPGnC(X)qj? zVO7LV2U91-$+9XJO(OzAe|#MYi|TP}!8$HST9J4U5=&pK2q=~*LNZciIBhN2wl*;J zE`QV)sx_TLXt<^M$99&7m>`lJ;9K70wJiswwA1dB>jWh_1P=0W;!~2}BAQ-&`;AUJ+ zI4O4`S}jS76)%W^@;n#0PBC>2ae3R%qt%2@AO5UPBs%l6QqYWPkn$|XOURT$FLyO0 ze!_Dvt+z3kI}DW!LRE6AgZJ=+x8<)QYHZ^n110R+AX)7N4;y0uhIR+ z9|~EYlOofYQnv*HvE`8VI|F#LpeLji#_kE!;>r+tI}Mx^p^2AIO#^%8bdKqD{QCx! zE9Cm9exj~?`e5j+%rHyP$XB)9J&e2M1iNxYN(1kXlE|^H%by`3`ZXV8N!dLE)Mux3 zV^#r#;TOHEGLUYT$2h`Kpq03~0Y0Rp}8_edk#!!yj6_?-x<$4p)0_XV#Hw zQU^YYWfp`p)fLYcT0TaHn-lhzLQuKB16jRG8<@?reN_2`+}ZN<1xRzfPiUbwDLePM zy0)=)sU}R=%g#7o%Yf=Evv^}J{A3;4pZH?SZt=+> z>eS%%USc5j4ZO{leS%L(VEWjj$#EOEf&9#!fENA-W>llPUD#yHwSZzRILr*xGA-4` z-u)a;7(VPS&?!kpQ<*R%w zd1DZ?Iie|!Fp9zD-69-S_FG-&r)IYx>ckRjskx_)gr$DT&?BZI^YyApPfT3tUE!0S zPzi>?i&<#yu}-$cZ%a@a$9#aoCUo5PR<)(ePgmTXg~`yfc|Wzu)U>?DTa|0URVP@C z>yMrpg2qV12&9KgJL}iq!8`byR==h6 zj%0Wie_b7zFEk^HeC>RMDe7m}qd`O}bBR6B&C-$G^Vc>c`Sh~)WQc$n{}b7@{|Uk< z8OC$)Iz7|Xy0WZhMFMry+_8N1H2LrENZ+QWuIm%zm20=aY4{AJxu^K!;@>9e9l1GR zZFLL`+0kTaK2{ux?pu9nY5qCO-?8z;&WWKemJ(Fww zf|v!Ceh`9B2VuNlVB}fw5^W=rz$!PbdHKo5>GP_7U+Te$IJHBCwnnJ95>ztd_2?S| z)|=aU{)j&m2Y!bI4dm|U5lV3IUIis77*WrIro)h5VifNjLA2u28p|B7<{Do@CZgsl z&u|Fk>{H8nOg!nw(_1vYV845O4D!Gj${R`ED6sPO(w-o2#`-7A7ce5UG7oarpX7IYeLEPg-2Q*g^i;N6F8G@tOx?<-%Ibu8S^ZHzyoRW`1X2x9^-u1q~~ z8IM!tP}~jHGc}mFY<%qt3eL^J^bkDpw&{EA6=G74$)!PgFtAg;_vWp;(jV_NR`&(@ zM`lQILd(2km6X=to#QOw%Db+hf#q^%uPL*BD*rW6{v&LCO-IUqS2b5m9lMC%JV3t< zA53z&Q+XEpE>oEwJng-#e~*m1itB4E(u{T`5qJ&_ZOMxs{%Q^!zr=;gWF6fyN3vV_LN=~j5AdiVwGB%SlTxW<=S;J#Bks`(eiEm; z*W5bKN4lni>!7I~O6&SOE(c<;3xsH0vq>+Wqny>t3mM{tY_+>!cVx7}->TBP@vm&! zH6n+yv`&^x@91Tc`uP3PdyM*TyJv3(eCHk zS7~?Ib;d5XUhW@6c=|MH@%J1Ss51ZA9@$lrBI2m!X{&f8s(irz%IcQS<>%3lAOJN+ zC_C|Z2r6&ZGL^p^Z%li#GPa#%DR{Gkx{$s0!w|@N9W2d z^8o9-?l%*n#5cUehqWb%M)oX*mt+-L0=DpgXg$3@j@HoZo|+^|IH8VHsOxpPP0fDMkW_51l#k9>}7`ohvUY9Eezh%6y8*+KCjg;UrcDb}@g!UDGy@V=l<&V_TrZsDGvhn!4L?-`vXyr6V>GoD! zF`Q{~K}X{M6$Sn%S8Wr^@=FNi>-0F|$#A~PmIwBD6cpKACtk9b7~U<k5#9|)`1DC;P;L_%n55Fauh21{y({-D9|umhu6igxoYB-dK%z7V3Ezs$4i zbs@*_q@A#8g;LeZ4M(H{N-MBgK*jU4PhH&p)TqpQq<0gOv@i&i6~E@D|Ec9Vi4-N1 z^%tbx`WQpIG3bo??fo+i%T z2`SKFSbta)w>N1sV&=m{U`hOjlwVDj3bb{Y85{eA>|V~2IIpsFDc4CkPXM7i)_)jD zhI$$JaWZ`7)fc0ou5w|HOHhZzblF$y$;CCc;SB91CJxodtt)1{s9>{#(N{~_UV1q6 zq-W-@yT6!RC=c*{Hkobr9*4pC)2Qde8GvqQ*ru&pZNe*WiB{BrZm>X^U5D0m!5)Cp z${A`lP4}E)S;GJ8c9`iU=iwoh`m@Yj3!ff^b3ta(Ai;=zZ%9hF0gZz&b3@P?5{GC_-wh5`<<6T?lqdVxCbzt0g~FruFgGAx3{q7I3_TG0@YErN%B71GkEuCpG(~+4 z65<{zxCJ;c>C))XK4E;hoU&ec@kFwwrzZz)kz>aIy&`sVjs&E`jQ4O#ea)#4lQRhL zPH{lcEgP$N%tG*!ZveW^z7N-+1C=Tr55WaLiz7Q454T>Cc;&p=k}To2@wZ9uX%?Oyfo!GH9Oy!Z@L@s zsGr;f&R%wl(L9>rc!h`$slap^%@HuZlk9$E_|VamBweLAm63%o_YKTXmenU^5O!{j zcnhSw3PL)hM;D*y>Y0y6tmcIJQ@hCJ*P&;|)8U*_dMK}N`$a#YSg9z9Jj=-`G4DE( zlU1R=!3?x-PTlF`cv-*G8UR^LSzOZwo6oWtl)LRo1f|spF266l7abvQm*P9Al6?05UN82%nGMUv6|~`Q@R_ zze_0KU7d))8ow_;oN*+Bm%bF{7!fo`(~8dc%ReH#!-bpQNgdR#G^U12wp``^)v18V!!d?TFam#EHR&HpK46Cx{$IPc6w3&GhaolsDjl2?_~~T}2tuc| zu*?vbN6o)DpCx>GFJ7b5Qd^RDSh9_TNk=djKzZXC4wiwJC-rZ$#2amE>vOgjy)!t$ zl%d)P`0WSw12`)ee)aPAjYYdRaQ%5FA~{Z(o^Q%(N*UQTla)vW?B8b@J0T(-7aH^qcr;r zSypR6<#2zpf8f*0U3y?56)bkACC!J}Ufzzo_u*nJFys^QVq0GW_frNPaRW2GUlf zRqj^Zy;0|wRv-)`mT*9oBPY6}E;|$e_{SvV5N=%ggP?SI1OmP!G#sBXA6gV&+ zvr5N5M#PV=oVG%!Hao2=HNnMp4ihmO_TWzPoV3s2!j6@TOZl4>~%M63f^R6J1X z@3Kil1NQyn@H%GX^tT3xM-80Ln}Cy_Je01NVyI4Oa`~*Rna5~HtOV;<-NEos<>mNa zmtEtzLW6qC2kep#kUYVu=EoLUZ1g7&JVA%KqRGoLGAK8WSI**WI4>+wJXJg?mDbnA zq*Pv(axhBF5SRV_zqaNr4`{_!dS=7&xZb1Vn4~=mdUt}2jaR>=fZ2J)E_3W42?dx> z4M~<&V)wSd_<%u{?tib{{1{Y;6VMFoxvA$0NTD?m{2% zMmacxP2_fqTV<&kNGfOF`NC3Bthut|VoKShoup>lx!+py0 z#dRPun)N$P${z@@Bod&Ys&m9o8~q9s=l`cx5#X!qGGX!Em;q^)LwkBw_j+b!GJI~% zBx2vCmeGAWI<<1ow^w%%$8PeN+xXbn>&yiy2muM#ux z!Bj$)q9Vb9vlgW-8KSJi`Dj(U*Qxhe*Wf1?BQX5y0%=XF$a4eQCZ$17NHT>iibua^Rs$Su)wp&PHe(+bmBw>5tG=rG+_ zO!0R${a8D+kgiDx8Ou*vZ}z*-?XhUywaNIMJ@s^Km@$k?j*olWe`eYDoACXIa51G+i}qn#^Gi77({W{C>A zGpLzs5D;#za6c2wWZ*D-uL|^6D8WL$xSPK^mLo=l_|%|Zhjt3YAEip5KMO<|ub=wi znLUpac*k|h%DZf=GRn#WnH>h=1}wjf13S>Tbg$8lJGu$f>Ac%|e=S(pPtH;e@B6VKQn<2Q}O3n;JPWuTN4T~ zr=*66HT2Iwo=GM_$1dF)D4pSfr*O_MAWx+uyD@?(912dkzTo}MT?B*up-$4CLd}u! z1ezw@f{6t~oLr1cDdiU)ElV0FciX`mk z2fC3ARrZpqh5hGy(F!jwp;DByLJ=IKA%e!_oweC^eVdeT2nxzYse_8auL`dSnZV+Z z>=ZuAu4RTSG6E@M53wfHR~a(1G!yJDU?$3RA@h#o6Aw2H375+7F9-B61tc;ho7PyF z5#LCl&hpdiaFWwWAg5jVJD6G&a5Lpee5$0kKA@-qpKTgy&n==0tjJJ?%H^i9-J1WU z+rM>EaJrReh8#k=pB&LV|CSq!P(&TW-Q%$fDLI&-3@^+Rkn=WD&%&{Jg*0gV^^d^b zgBRK~k9?|`LQtbz)=Tg)QJmmCdy=lu!M5J`ZyLsGF!9w^G8H}feQ$Cg>Wz{<64|pD z^)S)UIjA;eOmO{&7XM6rD_h8Gpbp6hEu zJ*2mr+6(EW9hhhn)98d7b4MDKLCV->MqU$?PdU$IR~Jf2w7|oY9{I32W6Q+wsgVUC za-k|N$bxr$lC)Q0qQ4zpR*I$v#v&>r0<3aVbko{fvnbiEhf9#5ed{|kuGrm3LXcyxVb=Zu)q7X!KeBA zP>cl3gqX)N&MBtO+~6SZZw~Iq&DUVFst{C}yjzb<{2rNZ;({PChUM{?`##Cz{@MnF zei-(A{G&XgW~kG&5Kj{HkyNWyd&tfLQDu=})ATGG9KKc^Aq7Kyuq|WW7`*QRyEM%L zcp64Hmld%chd?-UG700oT@kd;ADcsoHXTfTH50K6hX@&yNOg5Xlqn!g=sM`4DG;`% zPYGjUbXI|gs(ef*TeVQCl&yX7>d+16m|Eo*@fz!&XD><&DG%y?bNBgHQk_n&NN#jI;3o)f?IqJ{a^_tb1Hl)Y7)f3x@8;To0S1`u>g~P11 z%uKObN(dWm_J=O;>HCV}2;p()u&+;7a=uvf$N9_{3E^Sh2fZ*Pm10_~(^W=`*;i0r z$5~t35C{wk8~TqSvJ%^W_y%?Pqvk7?BevcLH8YZbYu?M+APC1^KyzHb=jS@z004m^ znVs@KsWz}*mdML(f38=6xs|=Z zYX6AkD0TJ~*@T5Twa85Vmgo_F$kgfi-eMnE-&}y6jK947p$2l1=BIUG7ku ztU;t|C#7<{m$8#q6oK#vrjF*J1|rIQg<+7W8GwLN@Wulu&eGg$H68#~f`4Fc!@T~g z$bMqnr#318wOIrY&9GW2lo!Bt@(b_Z*Uc;;Zz+6XWNoqfz%MP>J_Vhgk=WI&lls)R z*J6KCX^uplzHV*{fFA+E^&EL0#Qb!8o$f+`(wkKrh>{K$^T47^1OOxdSH=O+n!=Sf zQ8i^j{)Jb7BAY88X_9sE8l-K~u>|Ii4s)1JTNo|C+ z04i<>in8&k5@jYGo82rdm1wPdSVMps0}zLF&b3B05z)k&cUHvkm@RCdADHUyHlrWite~0RXo3@6H0E z_+d=mCR^FmmjK|a$fI}UZ7NL&-0Im{h1vQia1(LlF(>lI#OR}&&OxPvQJK~WG zPZwEa*e%WFV z`~|ia7=s5a8#w~M_Bm0ff9FWYV`7@|!!_xU&H^F=mO4){;r&VL=H&NZpM9O@4Jw7O z)?lU?HHF75;kqD_ z_Yo$B(v%%k@D2cwRBnd?MTWk=ddR78@g{ErbybX*)?Rj5ncacbxEX@7&Oziw06PqG zxA`B~&Nm7<;q9ZEY*LPfKmun56C|<#)dAot!y#4%o)S}!GFW*~fJEHoE-w5Qh?T?s ziE8)n73Br>wO!@%H<0v6z?^=C=P^ppocyEB>o-VEN=)U`T5R3H#!o$fpa|yWUiuV7 z;YR$V;n@kT62D}HkE#8^J)gTFseUMgyjT*90fP7U9fG_cRspOlGoIP{Hx_Fix8evi zElSOr*;UdnF85}oZyA1yZe@G2HD4rQLg`Zh=2J+D^gZ-8HWP_p%h( z7c`3DDg4LKw2iSgJt3NBfM+ty=b5+ zG)G^rjp&J&M(R(URdf$~i~gnU0|O34(gSb}8vqTa*FUZA!+*>r%}jR*mpQ?pLsG!v z6ASO%ztWl2kc4de8EWyosfvkos`N$G{Zp{3h#JXwBcqyo|~H9op4j})gksSqR8%#ak9D=tT-AzP?!Ci;{! z5)n5P$}_BW|F}PkIE7ti833S#0+Sul&|mY+u!7HcR%NU+otO~ZEy&R4l<4HRC9(D} z`T#bg_|KOT;36o5Bc{zXL|qsDEE1BWs1=1^V^k_YSwQE5$dYx#&|q|Wkn+a+#RX7|_JAWW zH;KZB7DOH7&g}C&zbJl|b%ieu+=Zhh5@9xE-7_BGPF<{A+6smpqdub}06ObOOC499 zmMG*b!3rXWs`mmf>8iU?q-1#U-zETn%yuGl%pK4mU2vqmzJhVEGbP|95&J=Eye6G`#%7 z3;K9AGzoHb79gT;a}yd&O~_LPatfqRNL?O`0N!c=)A?rvdImLQ?Tz@s4yH-$$YKm6 zqiI>-`Ir)%+Z-_lLUi%Ezu0^wu~1iGR{+8j-n9&Ks3;SThwCLi)gkJ zg`rwJT51L^^+6{q^qga9a~VG^+lZAw{`MD8U56BYZ|@?hPtyYlnI3ObIOeCsbv2EVpc$}d%Pg!0R;v$S_0-!0=JI}y!R773p zr_qYUo0y9PICyjMh(MdKH$7a(`9Sbfojp69D%XI#$362dkTW&)ts4+w_XHr#wUUQv zQe*J~cG*WsMpi~&f()3^gqK8Lxn-sSCOn08p!^YJ%2XEaX<` z`xB-U{8?9{+k4f(Hu;jDEu%5T)p1Y~(u1sO+SNH%+}1NP5Bb6L3yu*Zot$_i>0ci) z>7y}T=@fw)G>z>FYp+7x-+QHOJrc zeDT=kjk=$1g@lpo_L1mC{?LYhHv9^IAOG3aC`GX1s2z;Iwj|@Yyft$4T)&_@&F2bI zzsAF;2J&)!Z(ZI@nQD|;x$z7)pHOHnUh+N<{3UqLQI~W2?X%5HX?Wa@n*h&N=U5pe zF>!0iSw=Y`!Z&mK7fk4^N+yFC>qJWYU4@E{08?XDT9K>2ebhos^zxZ*yEYR!X*5N* zu`*g+p!R%>C|G!j%q1CBPm|U6fZWZ2-MnYm5NvQO#5Y_!DVklAMFF;w0l|RT-Y9^_ zXc^(N=$)MI@S$EbU{=TFt#db+O9~0ZQMXZI+G4@sUt8dw$MxMD{dt9e=9B+=9Z9&V zPm#`1{7tfHLIw!18FCX;fNb!sE`AyxvWL{W6=WIYVQLU-Bw^+$rnvFMl) zs3OMR*y3$*8-y~roxgEVPuRU#%+)qNzUE_iP);Ni-H z%sGDVFB&>jNeZQ0At4m2{ZjS3%#nweaxRloSTe-eMZ8fJv+4HHj|=`+z+bhtFU+nH zD!FehWvV7f<5XnsyhQ3g3>g@*BLlSZIvDuoY91S`#Lpf8j^Spmz%FF|%>Kzz(anEI zZrV&mWae>qTm$CXcnQ?N3q`BIF%9(IMDUCSYmC$0W53DO$y~YPqd^6YYAmSQ45oFD zdzn{lOK-jDy|wiWxxEV(97ipbYZh;fHyt$r$X4SUG;U92(|g?GN{w=iW5h zmVy4oZq^q@QnNkU)&`uof++#+GNB~o=kIO2o5erkfhDrLm*pFmrH9*oHVO z7)ZhOUw@2WsvebK6aQ{6vVW7u>qD%uTGYd{o`*Uo(4*;vi}0#7b(*~u{9Jgz&s+EJ zT*lW$&kTfYb1oMs5k5#HF$1u`sR~R02yfuQ_12RN<-Z1!clwCjSq>K@Oag;+-`^p> z-~JXi{oCUZDVa?Ys}mXu z|F(cfS#vw1U=+W6q1f$4lbJE{^k^S{;U5Q}W4%x=THr~frg%%KrusFaRqIw)xhoP~ z+oj&F;TM4>2H!#x4SUrry`!3RYiA*9eg>`R;mrn;S0E_vpgT&&3A~Zc#ZL01#-Ry_ z!RNx9VYP}fKH+%mFG}#rpG)bXVJK{$DxfTM?J|cZeeML0jv#cNN(WTc5c2dZ5jg2Q z#QY049xE%deV_ixrsL>Zi6%%S27k2CE`M5Bh0_3W034m*Bk(=2KG~|KiEp7c$%uqA z5H3TVcIix!-F0Mu8J(rmv&TKPDp;!Q`z`!u9y5&${kJGD7mwYb!avg@aSUS9!!^AzIIRp|P|yDGbJ8Eg|qb+kY5KrukS zN9xiDKDrP53QWX#p~)5*C|nI;?#MK%CVs%t*TLYtigQW#NiL7!<;ROm;W8cK!Y@rFSzcqXG3+s;lyQ9uoeIt>`e-?=V8oWINMcOFA9n zSx>z$8y3TPSG;nwbu^i!+9ev#Mj+g57@X5-hMTmmsL>(|x~hlhh`&#AnjSgcm|!n@ z^SKZrFTw+6=j?@FTfLbxXE5&_GqAJdXfOJ8al9m8H<&PLDql7u_ES_a<%=5%JlqTH zyq(}i48CL2EQnHl=gvhVj`I5;acB%eIovg@JEe7b_V~G1*5?kd*+z;$^}k-I7xv)YEF6Eqs;fuu=?%g#UH>RXf6Kbpgp{p ze($Kk>lc(#@@pU%{$b=D@YZ@5!JQ$7^OEf4ou-Nn{mOAib0;ycdl_p$>D1=g?C4Zf z;oAR3SxFuR-bY#W*xCJxtw6cGF#2|TYQK%HESDoQcAZ278K{QAc{lN&ZY zNi(b6qq}lm(tRi%H_11su$zw|Aic&D+P2M+jJNUKvfi^L3xV|tvtm5d9?gFQ0sF^31?Pp9Jz^ZeY;q=$Jp;9GcM7lJ7wrY!A!!YQ zLHn&o9wadsj_(+Ao_B&S^e|?e*md8lI%Qb{e2z;ozdIHboDf|{Mf|(F4+&97ViwY! zJvZtLrXu6cWRw})kQq{(1OK*7q~TMy^7{`SpDW8%>k`IJ5VCQI_;agzM@ROgz7=lGy7iGCgCFNknqB6P9CLr$JE(}8t2ft@?ql|H-&iW0hXNQ|j{QlmJ&&CXc$KSnGvH(4DC7{D?6_XhzAB`pODP|Mq zA=Vp02K-{aV+IKzlr#Ztc=|3PY8N}S`=B_oiCjFW!Ou&ix&+DR%FYQTmcY#%C`>t! z+>4zBn4#~#ZeMye&ye&$gOR1bU@NQ`=l|?+e>VTJKqjctaQo&PZ(t$%wcv!)F4nFzryFOEg>tn@i3Nc)vce>* zP=<|2xkiNO8$1l`prQ}nGB?eEe;+(<&9%7PBa~aLL`yh+9V(^i zyO;paxkqfTrvOzcjGFW%cW~C-P5@RbC8RMx0j9)Coao~s1Nmmz4!^5nqr28QU+I`N zBdcydD%n{QS!{?7y{T;xkzO$g&B^NK?49>m$64B_*%qRSwd%dB+gnoz&r9F`ER~Dk zMrWZ3Hg5c`u7q{pqWG0Z{6zZmJ80oi58+%Fj-b}K;L9x|RdU&RP=xsW{ctxeS}i8# z*FfF}M3rS8AS>QWFGz8nDwX?y4564R?B@cIm`(1^{|)g-GVDU&P25f;%EBPK#e#IT zP2C$Nw;2k|(G(qnr{_}{My2}INPQG|OaomPv5@-Mg76Z++;Mn34Fb((^&_(Ku;_}N z$T=8mf{C%?{h}%>r=bWRx*}y1pC=)^=0Qr(7Gch6NDy`Xi#KKxU2^$SeOjC^b%oxN zLp}o`DYtnQD7wxIG!{_M&1Ktx+JuGpRb)w~s z3aqmRGo1(2*D$1jU5;p;ff<3o@Sj!i)3vRO`A^q2`x|u8!L)zk$J6k$G=3iNq~f;9 zG(b3NZTF_)I<=vW#m+e7frWav`W@Q8;9Kn=nB-$CSw`|C9W}p(MHC-gv}|cDgB_rr zhcV?)v1O~s--A>H;oZ$M7xPvJOqIzBLbx2PbDLnr@e^`IA2>%5FRjipe5$w0^e2$B!KD*Phn&R{ za>Iq9dw)c+BonE6h8FrK6RR1EpU7Z&oqgfRAR!9wnYDCdd2Pp86q)xrnFo}(Kl`O# zhcFv3+O6QECg({62sP=fkk|2K`(_2?t<&R|8s7yq+hdId_Y{~eDd83F*dz^={@*x@;V^D&!$B^PLR(zAU1oa%}5rGO{ z1E8n;kP2@%DFDnc5K#mo%HPtJWnMic^KESp)WIc!D~QcyY))~gR7s0wjix()fkKvP z+1L0f%s&oE9lyRP4=aVGONvusR(x6>p)$|BTjDuZHR=vB;9reeE(TG>f<#hv%``#; zLh=&9=}f4DkEu$eV}8d}p)eRS1Bsnr;?S#~d8i7;^;4nVllL+a`RvDRjQ;v0TU#f8 zplJY(VGI-aqhArB98q5pS^hlLhpgrw{(WmOpq5qGNu^W1wAaiJSB!){tBDWJ~ zO5{rLxyfE`Cw0GM8iPJ8Wbq6P3AvnScEcdyB}QX|6US5 zx-?71O_ha8$`EzutFr0@U?KlY_z9MMmlY8Z+MEV1skdrM$X2w4uRxfD5;HvTR}PrS zUC?lRD6&T3g>6!{f41a`Gi*D{Cdgs(WJK{6s-~#r_Y`uNPCZ|};)kKOAaMZ3{w~n7 zna?51l@HDwrKrvwq%4K{j8Y~#1gHe-d*f03bQp*Wc9v+TdDz8#Fy5wwkw6y^=8=`S z+^UoIFC7mjL1itr8Z3E97Z&S%c-gvSipGZpm}50JaSG`k15xu)UE&oE7lip$+qBem zCV35>i#jDlfRE;Y0Ux@@h(S%^e&@B3i(-g$(%HI3=WlbBL8=GvIIeqF51MsdtK-`9b7*uyOZI`l}O@0XK|pq#%;8_9gsoQeLgavpdOoGPKBtc z6M_M)VC{^_ld(06`*y@c4-j9dlb{ z8bCg_{up58cO|^M>^XGG7{yOQ0?;bra$~N6n~?b&=6q8UT$G_pQM25U8bkwN6ccC% z_r@^@QsT)>@h|;xkKE^zs{3P0w;1?Nb;`ZXsNC!O>O_W8M> zcPa6NMojFm27)coJT8Y>A9|iRU2PYIW};I(?Ns8XBbh--knM!u>;}V8C4&7nsfwy8 zIiOPi=WX-iY&KtxG7TU+X>)fBtg~n}?$AYc&M7X*QRHNsojMvoCKd1-sl*{G@w*ih zCkpd*X}3xXusmvCr*OxGW*(Z|`<*VAqX;L2X&ILRH!lB8(Q{jMXst>X6lbeFco)@@ zIDwvD0&dU6jO)5Yiol!e5X5J|S&gdk`>r~D4TpSpbpy9aNG4vGMhp#cIr zY%#K*hX2pXQREF!3=Go8bn%0s1$_QY`~Q$%t1e;L;xvIlkh7(m<~3goKqM4N2FUuz zH826d&4KcVlVFwKTr~--#DJ_c+%OnQD%aD+YE0P0$P*M(t&g0?~k$8r0PuWa0tPBqeZN09P>K=H@=h$aI&FWr<-Ht=cErQL@XCDojP-BQ4JIZ7L0cl;=yK{qd+gIab% z+Jt}4A&gk`HV%XMK*j402JQI>c(77|lxRdP8Vic&GUtn-PT8WtbQ!Z9YRD|hY02F;e3lzLOFL(A>0bjMgzyq_RDE`Ds7wT z0lC>C!{Xkvf)11<49`Bd-j)>k{L<^Qr(-$M26;`Ywzyh_iJywx0?Kv%P)13T^0=j* zjyb_6lC^O?46`eNKSOOsVH! z%AO#F2NnX_U+oR6X%Y3vH7Ngh#oUxqR|pkK8AND*x_NKTU!mggKn|F0NZdH`^=Ysc zOKK)3Mdz&LHY6PVKq{&+k1slcKX6@<=D%nXOLRU~T&}%=x)@k}Yk9SArY>%KR_dZ& zopdO)uZ*;MmNq*?XUVI%S~?vo$-i9eN=WJ8g`%ZTk9@SN@f~mU#hV)ispS^{kI2e5 zLTN+o0%gXvBfi-d}KiWh(FpwGmEp;NQv zuN_A5Zx4;5uM=kc&6Wk z6xV3&{nTXA)EA2xGPxrUOB2(KG}!CgCkY`W{du_H9HXu{`pdkSM_}?RE6V5L1&eG@ ziJV>n44dROub)(V8_>YfrlY~z&}7@8s23DWUt4JMVKK^MnIiYQf#+kBA>TTS$s!uN zY5{Cv9h`q8IR8<9jP=QI3=eJ!yf=z-nk`hrVZpQ1jRKfBR(2MCaYRy~6%PPKYl!daAWC#^pPE~U%Q_G_ z9^KSq?I(-6XIB(#uWonovfr`%l@@E-dZ91OtZz%~|4a8GZyICP#WJ7Ez6q%27s=(F zNnsDAbj=JPe?@DIC{zcn#hTU+65I)24a@VP4j9#`H%U-|L_~vdAN(W;$;vrACa4+l zWPiMA;~6k00{<0%;4vHpq#0G0qQX-8)<`>r$VK$B&apFtra|ICOYRat;Q~SO71Cb* zMx@Gd(aO;66?K|#LCv)nm1oO}K6VZRxHao(=vU0khW{fr=f(#KgIuKi!YsBKzq4v< zhr~p&KD2l4%##*ECQX!5B#^EBvCK5|q=frd|_l^`O$O8b*FYo53eH z%jpcKDvh7G2BD{<{9Z>2Nd_oW7P+{PpkDCT)e6^w#*fiPG5lQ~xYnzRc(@>I2uIpz)Bkilo+>&>1ErIMCPCh59o$(QfRJ)h@*ae zlvz3nS+!5}RRK6FOOBqqp|XLN(pv_k3N%ky(S1+fNokFz6O6H%7dSo9nsK9M6ZCz$ zfZrP5j>LpK+?z>vkAUp6LelTuE&-vbW}0<)5Oc2z+n%n#%pQlQuzxw}IA>^~J{a7x z+_HUML$z+GnI)SnGqo#=Arooe+VXZ@k$NNeqL_ZY5E9xx^EN5jS0dM0BwvMedO?U^ zbC*$3a?0&2r|82BXnCjS_z}FM4W_dz5zGYBeaWMw0X$fM{ShYYMYvi_pPlW{uja{z zmtJ2VQ7OES_9~AX--l`CJ(*}UHQRAj!ti?B#c!^OH zT6I~)zLj*uX$d*NG&GB+f;aW=daJ9Wm%a#c4}Ep7AbokQe?KCMsw+-<>pWfOKO87m zk+V~5{6%;&@dVSY+YOK;rRFldNW`sfloqyJenmYW!Gm1Ov^ast{z~QLf2BJ*OJhTS zTPK*{U=#TRB?}*h-bk|%-U-uNZ}4W3A-r}RhbNs*cdv# zCh%)lOwZSQe*=1rpUZ%zF$tH+_clkD2C7@DsV@PAYYWtUba#UWcWw;U$uxaO_(br_ z9}Q0%v`zFe!(%Y>;SLE+gE4`|+ae1AsCRKg+p_u6nZXYq)g^ksAt^!R;X~)Q+h1tq zQE1Abdg*#@4}E^eGgHvGv;+ibE{Q#F*|SeJ<^p*c@r@TfL+CxaiA#tybwQC>MPHDl zL^FvmS!Z~5Rr-a?+8#fEZc~NbL&`$y&$xPV{fbzHj=lN{wMN4j!lxGwdJQg5S!-Y@ zl#@bnlKQeB@W1p3Ds%4n-urge;#@Y3;7(iXs|?BUsJR=wmkWedpq?suO+GHDPmuIj zA=c-n^5DH#6eUPg?CjrSM@Dh_`@re-@!F{&QXok9qibd}o7+c2qw6y0>QY2#;|mfS zHPGcVzBcCCAXNMQQT1n}O336Mvq+%HDF#)PAG2`x^PSceBGBobP^;Bt}o_G0GjA>Mu zdtS`HMEp^qutn|<@H3C!+p3Oeh{0#pB_oGJWKdu7W+P36r*kbKWKW0_bCv$k0vrUT!4 zu02<=$5|ztt_Bsf+R+8>6Ca2RouY5eQzrkPwocBTa*XZ#2W_t?q0NfdSvqGn!Hsk) z_yT91(qVmrquQzdH0n{$hI~bBa`e!WYUCO(l|GuPh3s4by}y)+H(Cwf9pAnJq-=Jm zRQ^I-QHLbdgsvO6A3TXwJUu!xCe?6|VK9|w~=2c;NiS0+j|X1xh6mV21JvEA>R_D`Tu{#6v}Q0$rl z$YG9yt)n7u1j`@8-z%`ALsRNQG=%qoAFtc!vkvNQ!zWnynquTxtdd`0$CcLN1&j2r z_e^X|3_><1CY@Q==u$0uWp#9-A&rBIhJo3au``XUOlzNDX z;E*d%xfv3JwZO=a3w=j09K-fqjL};#kj_p)X!`6bFr(wp5B{XngcShTQziU<@sh$*Vea7hGZq1_Vg&5RY^!`T zAcGd&Tl!zzQlRW?*EQ8lE^y2;>fkF_UTWWhZe%BAe)jGU1||JzUb)4cJ1oKqFCoBo z3WYp(&^_GpCytHApj>8{fxAj#P7{de4W5`TD`?SlNj>tx7{mnwSdgks^oNxXbL#3f zOsyAsi_78Pe&d3b7y*lY84-m*no?(jHQk&^+il`58mT2h&R|KgBk?cmIQ$m_NWNP` zv>D24;f@BCk6alFyQY#>1#LbjU*s1Gvaa5_2%-{28=N_MMPphZB!qlf>qmze-e_ur z9EBb4-AW8iqW!%B8KzhaSDl~8rVz5kviyC}K#__t9O|~lO93ZG(U8Y&LgfVC!D8u8( zd@j=G8~Ag{EG!1+7-3xY#Ig>MG!n84Q(Wu_PLhctQT3S!aH*a@Y1|w-H1qW4*jj!x zyY@Ev40z-1r6AKL;1l!L);f2+jnL2msUCJ>UjMi{NuSV(D;A}tnGZ9+5%3_JC0OW4 zQur>e>PRZ!5k&Y0-u6WQJaA^a6oLwF&rH(Y{{;!~pRTc)X*omE*JGn8(Xd8dwC9B#8RyXa}FRQqJ`XSs>_FR6W7 zzf5gnNIsf3y*g;n@@K>*Ye@u%W?s(M&P1k&J(}O>nDoV^x}i_pKeU`;PgFxx{+za3 zqP{fwX0w;OCPj+i5ERXUda%-CLlcxEqhRux9GwqbIve|&Bq2>tMe`2I&wX2_i0+pZcrvPg+7W-11s2ZYiD~ z2{~d2ulXfzG34SHC+D_siL8FwiuVx`OX)p~cH-6S6ecaA`D7uZ#e zG$Qy(u`@wZ2Ug-h5>~SfZq_XNhx#0*uN*Oi(2b&}n<2O}tD0j@`|fJ%N9PmX5>_=y zR8pkgE&m-ve=o`*X<~d%0h%QvSI(|dsd#d*hb2L}HS8%hHbUVD^)y<{td=n;y2$bT zgspazv;cPWKFS^5awe-N;>x3t7rGVdmlyz(^yNi`h(-S>D&3##x6tD1W%kqlAh8{QT}GFHl})U{@4 zAd>bWQj<;$q*r6|M<}e~uN(t{sbj-*T=s6z#UqQDg=_bOI5$4?qlJDMJH*qZG2s;n zU(bJXP(xRCI#woZs_2#}MSvFnxYY&2QQM~(Lj21b!_ToGNKY}F>?k|N zJ)8M;?<~OY32vu)R1K8Dme|sU1U#zkao*(-%{kw?^zH*u^zEo=lYpd%E^n_tx2KpL^Ec z>lUV9tIJWBMiSw!aw?QU$Ni;<7IWWP2z`67)~>q`%GX8fdewv4hK#QjHut<%whQrP zbiZ$7SVmTcED(R{?7Z||CfkcR>87pX{4px`_DEiV$MJ6YYS&L?0!9C{5GW>794~0# z!j1WmxbFr1*7iohY(Px(ZX)%ejfCKWO!+cx3Dl_I15=L3EOA2y1?o7#75>!B+V>V7zn zoa4GIj~t`&Vzm<@w!K9@J5%C%8T`g=p;edo^qwpsmLeZN9es~Zv|Sd+YhJ;}CCc~& z4y0)hEIhmQf29;SD{CKHShbyf1pfqU9prhaBv-0YzU7gIvh`iTQW;TgoBjQk+$ zeka7#{+$-{uIVreDYb>zx}?sXBH1^C2U}u-LE;ZD?JH*Il0km9gZ$VuolI)T05Xrm zCpLGOAV|^>+)8(Nco;UWkKaGeZEzNhmj#wC?Ss!;54jbHGbPvi)w29 zHAD=24}8%&#n7XLtZ!(1OoyIOnBz03_iwGnpL&dYIMvcKiw&+vOwRe06Z@l4Xvh9{hv?WP$PPeAXhM?N*siW1msO5@#-e1NYVYkd>CY6;h&~^9|_fs+LP+zCC*}r(Fi4*B^ZX8_CH>%iqWFDV&|E z$+{Q55p#grA>~>9FArq#fY=2mwa;o`65)e$NTO2B@Tf-+E`IDWcC6UN9%h?vO|roi z*-#d`Pm(?KahvydJtF6k{R(YTiGy?#Xl@O#BV{fz6@5oo%0|9#v`rmeB7%B)tmqb! zwH`cH{WOE6?imG>-5uEy$Jx=2-CIJ6g+piBx^;@+2uh-5YyC_}MD`LCHo;=!vPvIU zF;vWT#)51|%xTWW5t^`2ByC@5TShN2!wOcx=ivzL_XPq&b>EZ?&2 z^mE(IU`g^V0nybqrY=%Nb;IvhJc0^Z>f}hAdT14YDzi6VuoT10wx5?2hU|#ur1oG8 z*{(`5gT!7{LA;-dIbJ%1@qPqVnzd7VIAiXem^6abgewCYp)I%4t=W8f52h^5T*R+j zSg$vE1d@qUahAp@D{eDZdFG=uNWiL5x-iVJX5h2y&e?ciaFSfeVRc89T~ZdNmBX0F zUWewGG*$genCE83@;+;Su9@i&#m^FRtdmmJxgSQ8g3YTzkWF*Eg>Nv0h48+t=2PUm zTMhM574;Ws9|Cbcrl9rsKD+%fPN-_s#i}}K4(TzyE9f>noS#22<{lYuF*(i7YbX#n z%fW$KP|Xrd$0PEMn5SR+#Dq^>R_6)l(_B}z(V2mmg)1~hh2AqoLSZP(;q@7PCp-PZ5b;8;Txp{aoL{5I_GCCyV(IG^XXMf9kL%WygxMxnKNi9|B$>s zxanNvY`w;BFLXI?kOVt48kyfltHYxT-X1sou0^2G21m?y5fy~{UG*iwi2^_9=9jP?R#i!4>-Psre4Y5S(%vG-dQqhj@*j{2Jc%YqSslym zcAV?AZ}WwALg4SB4*g!AnbXWPY!+;nl{G3hT%7{1Wohl=|j?%+>?uFLyw2;P^M*t&3u z$8@HRSVNu?nmV2BFdXFfiqL~|JDQpS!EOEfYg;XPrswyfn@JuC`=uGPk5OG#pGO(0 zWrEwjVlBI@h(GhSakKqRS>~LAbnq5$aCk~X0-L)&{#s3#nf%1sW!j6W^Veoz8OJ-? z)L7m6dm&Q^Lu=owXHoi%cZ$Ki6fcEe{`VL3=a14*Uv8?MTED^x5x<_=(cSOK?J9pb%&uG+U;?0yu)-qnv0&-VS-ZthH3x8U&Fp1=TGX_V+LpNAj0Yns~tk@p2dU5Z~ao zBhn)$39e%Q8Eg4dU&TX(l<`QbX^;31FBC8OzFiD>hpB_##joy5eb|m5i{YxxMZd}q zZV@PFmWOHEDzf?HC9?Wc5mv5LCeX@m4--FYpBJ}bSZU_f@UV0&XKM&;?zluUWk-M{&7>WYODCR z7;s9()Fjt7xlf?K(TiUv&k7yeof8M{W+i18WyCTeL>F*{C&2BNBE>b>H8$LvwMd^ zGl`ZZgD%lWUPj65CN+N5lP%r}gbLUe2R?r${6+l0YA-BgOX_UC{DI3N^^yV6oa#1s zkO@?M`axwG6g=%kcE24Q?Gxj+NBL~Oz7ynqP%%%(U>8ZrsYv}1E?2K&cD~@!J#Ltg zvfNRe7srG)TUWl<&`#U2;QAKAUsp}%L-P{ZO?I5(!g(@KGVWOAfGI6-#&{GcE2)NGOH6lgjUTl(O3hc zgBAbT_Vt50L%=1D6q6K{+-1E*)`2Falv`d>*Bk-fr0`-XWX0O_&R_m#&L9hVxbN3_ zevyiu6(ukT_|z>bOB{SWTI6-Q53^T`o?FhK?>6NI;h;}iw$!dzj?PScsqQB!4hFJX z!9ol4-N(x%d*Ppu(@04nOGoW~3ACQakGc+N3sZa+#uDRZ!(_(yXgWvY0K^^k9wP^zx=cJE0KePJ)`;~H}U&9@0& zJd-OCTzv+^6W?-)_rluMm}8M3>Xf7CCP5 zL%V;%UoRKK&ngAqzzpi;V)is)(=nNYyVbwW%X6`|-=cMD&kwS9Pg3pC>5D}fs@#@r ztth{#(y7zq;^f|jz%%=;5Cu2%VD=kIPo4nPvq^^l(af05yZy#LV4iT+Vzf$(ORAh zE$BrgqRsTr3pc5qx4lHF&hfg~DRkgQA#1+n?%4Cj2sCx!iWBx1jJ&XDdDX2So z)0^0=D?Qq*3~_%%2%IE$ZG(o3eS|lIznzY+9Q5eZMx8P1-4=kznH-WyZ{dWLFoVh! z)3jD6+opEf9Xb(R_ymJ^brc!-1F1o3DEaVOELT26gD|Xy(U-0jMmKyw45R3Kx=)Hc zD&3?vf@I7&;$i}_Q=Lf|LisCP|Pj*s(DvDVOjflQ6gFpYHY^+t)ii% zg0Ui(tb`Fp{Z#3u%^8vPNnv96T9(dfp@RJog5$?PtdfHkHo_A;q4jg!2)@cnD?hn1g|Y1BQ(!2m0VA3ni4PH&H~5=CbyK(AMiEQT88 zWmk0B3o@y0Ny)P)Tyr?7(#4=eHorZITcC2ix!}nm^`zLC+|5ok!K5s(O-E z14+7nw3dI}0VL@7%1=3p<&Nl+4hy(UYC_7V7VJsRZ7H_#HYosW24yvJ$T4IxW;aVX z&#@F!orlJCyv))HmvV@r9*FgR+OkSERI!7mO%5})yP%S4_hqryG{5it+p_{_!zXxk zsn>5(iw#;11*jpa%ikoFIZ@kX8-k?|O{1*N)+x*D`8RiVT1j>eip;auMGP8Qa2g(; zUf$Y=0;~hemX+0ehWY&&prz+=K$}um=rY?6HYwX}YPsVP7_7V&=?JkgzD|~=VOK$p zlU;RO3V>01)II=lPp_3Xsm z)~)fPs2w^LqB~H;)6(q&cQ*yIk;jzc7cTB$P1oh*ITO=QFS^CAUO^-wjBGaiW8v5s zuj6IJ8`CUl24T`NeUNZU2fkqj>P8*#dAODbgROfEmZ?0e=wjDT>l|+-ouk-Jurq8n zW9Oen8HF8GdPTN{sz2~~NFpL%ike{uHo;J<&80ehbLeiW$+b7Pm`oalJWUwIrRI-om3_E!ax1(Zm!c2CoH3!3BdsY2(qEpz!&-#zzZx#y+g@+TSIGrW*g@GZFB4Ge^2Z)a*#S>TY? zt$j5t0tbGu;j8|(3GaN*Z%$Bl+t0M=qVD_BE&}q=56Z*WmaQtY-6Kc|wB`wjAVnsY z`cCjVqgs2L5<^dRz8N`wU8s!fi(SBEnb2dd$Hn4vUri#`gVw`}?i(iSxaj!8uS%#2 z^LO7v(o%!puLJ32^`_G7kJ;hClz`ahp~&v6;@^E%m8I$8aiURIN$I~w(;&iKhZNt& zVEQY6O-vHlA2E7D%RCNHscZyEcRA4VI*y6 z!FKld!U;mZFhm8odf9ct#G;Az&;-9JW=0#CO7@17sK2#)i4Y`)^;7*Fwmz{}^`4QQ zfm!I#v2GkORpc&Y@AL1SN_$2WEz^-B60p*GYZrzr`AE+wgQYDu$2tNOXPiHOX#6`q znT|}Q=g8~5iWxiv`j$pd)@d&LN%H%?97((v8Q=!3PU4m;HDqmzE<5D@EvXgjnhq_# zNkxqkJ9LLG2hCb>DX$?|V$W;m%;b>AK=E7>#p2d8I6yye*kMnGXb7jKoC`U&n5m>R>`_}@E*-xEC*xY!`y5M73+&m( z-+D}{riCjM{}th^#4HDX3%5Z|)h#x3IR&fZdLkv=4c^QwGKf3lv@*eZ3R~+X4O4>O z+IG()=u7h0eQii`Hygu_$8Ez@sXQ)thE^B#I{lc+<^A-()gTocyDfE;`Za`a_M3EM zPULtMBIeQKUYrSDo}03YQsHJl{+xJHiL+6&T!Ir~4+i^WSp;EhpQ$oFvqskJ==nQC zm1uCW6>vQ!6UNunr>*QcAv$7mSAD{)L~)NPd!pk!Fyql1JH{}~7Z6@_h}7D_&y5JJ zIv{vD#biy5B`p@fd*SjrX4X0?hE56VFwMLEb(l8DsBTJL)85rVzsOQn%lm7l!uw_t z^5p1bZ_`bQ9gi6juhx_$dn^z?f>!v>FF-|g0q2`m`EbKGC%MP6+p;Lsx(|J_+4-|_I3wJ6USVXJahd93X1!uZV zv!R3isIll$T*?fH8($bqDjuUIu@RT#`RM&6NcxyE_>`Y3>3 zSxtxiL4QPdY*Z-4(j&GfpBwRAa7a4j&E4kuZFIhzgTtNtv${_F0e(-i3K*{~YN+vK zN-5M%3q;n0!2A$p0=53@)O$iRU_4r6v+7m&NaEbjb-LCKCJ~C~6Eh=e`}a6}3=%ny zb{%ZtFF<9IL1~Tg!aI+a$f)Vs>1pCK;pWKHw;4S?m-P90i26m~8()+G9?D-_y81+_ zyAeOPQ&#u|xY316!3YG;+0~dNH$@=9~10QbtZ8UQ}FM4L? zK)JxWeD-|qAAwTey$M}?A4GL$qJ1J$a$-!+6!-~7WguE?wk=Fq-*>)ECh3vn4B+m*uOd4 zY-NBl$2v6yrd-$iGh`LhhM^mWq^7*l&V-rQY)aGUXU1JOg>D+}hz_L9X*6qBtvRSoJqdempHfYjdg5o@L}Q_QEPHA z;$+GA)7B>XsD@gHzww6j4{O<%1_F|TZ~X3lyk0uTz>==Ke7Hf_3YBLbP3B;k;nPDh zM9kz)Z0ykYhj?q&e3{qNmrApDkf$)fhu)>_Hh*3s<-`mRAAD&uf6{oKd$gipW~B6F zX!B!mFM#=M*f1APkQ4mZF_DtI72;8}icCkHV#||O%vt5oz7JB$q8pmd=zVSejc9fc z(|;r@03f3LSc|=LAD*cCr>(EN7XbK42mp~zheg%bIJ34fn`k{pGf_!<(g~<+zTg|T zY*!GTjt%6zMO(XY7+iu$E+XgEVWiq zyNUNq0+kB~>U778)#U58r&{M&^ZrnqJ2@n=vmbmG7;nN7@4~uFQ+c7w4hhr-qrNF( zvmM!smpQK#^ND_a{`J1vm9`N8Eu=@0^^Hswf;NesJMr}ce$(gqdOS+lz|O)> zCNZ|?t{~h+dKTV&NN2;Ev6`|-)`Ji43Y#KoO3N>3hF5*#D+BYE1i#L>k8V_j8KuUE zyL>l};zZ-?n;ar}UhB`Njf0XFLKcJ)e|0I;>st`Yss`6SEEj0Qwm0j+e$|sIrd`qL z9^U&Hkqxy-IyR+AZj)>+^p^7ZFbJ(rNw?6~-~|tp-1m?6lja3PSSNKYzgcOVw$xlH zN~=0921^~`olIEYsgF!jUb`k{r5Xj35vVR)?wULFzM*YyW{TDUb(Qyd_|~tKtDSA3D)4mzjxr>Z4RKi^t&_9 zqkC}9cCupstaRQnkqPixrP=_)+Eo@(eNC@B8`N-Bx4nYYVQXxi3&)Uw8(~Fn(Z%DQ z8s)Y6SOvX?^Ic50Zy#XV_>#ciS)-|{7CX9wqZ3FDC>7T02%k_YDjY3OvoNu_xRXe! zHm*v-qzbb=bpN!j&2uea7Hm)W>)xd>WCTXz&`6~pF~dZqOF(a<>_EEI{dVWt01pR; z?&*|W&N_Ry;=nOz^`3|ADk|U&G4@(8dZ1E)I4`H2& z{dfF_TAoDeQ&={#2>e{@_kJTt-S;KooS^Ixq<@qMfY4QiG@Rmbm*`f`GH0_gahEq< zX4Lfa%zcAA;8_j1XAX*}jW;>S7?;pa>YV`YB9Yr#KuTnzwvt`7-RSx;bwgtxB{*P1 z+FNsOjyoQE6kZ^rll;ZB9Fg-s{?rk$XiVTTq*KqBNn3uL=JzENz)v_CuaMfYGjB@p zcq>=05t0_}>bM#eOcp_)F@@Ke2$B@GlqmH;mmUK|Ns2g=uwvy$$Nqe|!nkIl6~S1q zvdNn4?8BVFEvJJ+D$a*q)G-z8FC8hLF5d$?D3bX_7t{Q0{zsxfP43mASWap~TOW`N z0Juu{4~K2!M}YPy^3hJUKL8_5HdplW4kIK0p;SuEzBK)=g!+#zXUSR<<)3}Xd-4-d zGN^dAhrAZHGgqPS9XI)R+~ogVN-xHC-(Gb`tI}eOZP*{?4~8Vt=LZ9yg)Vm4;-A-v zWr<7X;?X>=@q#kvD}`5GgSyuNiD14R($N4xnF%3;42 zld-|A*C{G`6NxB80xO67L?q2!r0!jr z6F`-8NNv0nX__6}w3n}!1QEtneiOI_2}4e{;E&54Bk?3A+KgQ4nZX_W{%DdYgIo)N z_w0QDoHWuY8T_OFzuIj8NG9E_*Ol^no3d#-HXvG@ zYDbnfmX`juJu{5xvTe=-qtE46Yp^m|w|%X=IfLt9*^hDWYJQ3w6&~I44upEBu_hwm>#kQVjE6 zY>lB!XNzpx9{}B&tp(2k?Q&~e1#y{v^739t^&a2CY1d@qk5zwhSMSP19Z~Wpoydi6 z$m0kzD4Crx{7oFB;RtstDy7PtlV<8z1VZLgKu8Px8xlGipRPa*wSBh<9Gi#IPJ{gZ z9G*nvs3B&p^aKQ8MvJm}F}_p;_hooKiIl>+&m;vbs~@piUqq){B9AY>etnrh`To#B z2RIi8V=~QUr0C_-=2`Pa|B8PR5XM70u_xeV2EW=X#S6vc|8;rPdgC})pv>LJqf|$r zZ&y{L6kesBYc!E&Y-U3Z%EeaHl)#9?$4oObgiM^n*KP&_6PR(C7eRrL%q4W;|K1Zw z0P5S&X*P`C571<%;7Kqer0WI{2rInH2H>H+U$G{d-fQvy7E2fc8Ey)vX@d1({J~Mr zwLzJm8I+As)gr8T=L|zClUYql*hz~5H(Oxa5uP&PW?N3XPrpo8E@3c}UHH#@G?ZcB z7N-ffn@azGl$)2IY#Or+3YcO@E z_*iO3RnGGRohXE&_p5#Yi+rMFMS&M-fkHY@1jAzp^@PZK?}lwQ6t3ocyHB+)xLVBJy9Sob8Kd_R?P|z*7J0EN#qz1 z9t=4Da*JB)F1AtrVtV3%pfie)VEROF9}ONXm`mqZGB|I-tI9auyaU{|n}oGFU-fs%ToO@3K9o+A zybuyQe+5_Ouil-Fk)HX^n75OK;`-iUe|={`ImeG-QP!G9wTg@3gBZn1e>Fsb5h)#( z0^qTwNtW&Fn200E_SdxRIVc@js5w_?3LTnDAFz9?p05IQSv@(n4^BSS&7iA@fopk+wKo-0MS?UJO*1yky*)7 zC)AzO@zIT5w@Srt_7km>?s&*+cl4;IRS$o+-VCJ>y_I0-TFM#(ARIhu5C+UDw+`<&~-u99y}Y-xIFnfP8KKoP&rZiYhfucJ{(y z0*OQ$4=>(a>U<_Y;C+arRIvdxrBdWHI8MJ&wP)lAa?b>U&%%h2Fch+%RCzSA3cbJm znvTIwLM0O#3X*}DfORwd`oR0ng3Cp-XZ}sMnfL}(rwpnN^jDt;5AmQg(xab`^<-oS zIlylkUGdz}v#TK}s|XUG4|njB;cWRlvT(QbPEVs)jc{NsBX*8sc%i)da{A}4V6e30R3SC z&2Wq=?t6rt>Mq&LidzAtE1zrPsAWHM#n))w1}XTMyAe@cd6{r-iHp=M1{N=UIkQ%s z(=2kZHUT{2vYbz7vOBhVO&K#UCnO7qac#e5&9S1CF67`Y@+ysaQr8bUwLvQ4==n@tQ89Ix#bNNqtnb!oMG3vJKpseh;xCrh zPWBFvaLSD>2rS5VpNT1ws~HwO$zyy7(jmqd;KPf7_=DH*6LONWmz@)8=wjr&wfcn8 zVNY5EIjMUqifa-k=2WwsmP<@OnWJBQ@#PS{m;acgKVoFig@_rVf!uhAeF_ST=um;m;^HX%pVMs?2Q-bK z1C=^YHol3L@Eh0at648PAALJy)aIie-*zP-pg#ulQxu}-^9J#KJ33~?jjM2Gchaac zw}{M!UHt3r_$?+vRCRPAY7uwxjx6fs?)e--_Ga|>*Q;8o`pp`Xr0h3KI$l!SPDoMl z*ZC+vSL7hu6`<4L^*VuCSZ$1_O4XD>at~da9HR~9Z?^J+3j~Bd4F2G$Z`tcJ{Ou&x z5Zmp8(ns#t**LE@zFd2`-)t_bx%}6j0I>RxpivW)yKya8HM|^{hV|xz3;eZy%NuMyW;-u$6-&&l|0U;64 zut66+ka=ulg1?7#r=vmHKYDV(Qnvl%mo_Yjlafik-3HgH5~y6iw*v?m0+Z74}v$QoO$%=H4KzMa_ zeZs!1M6phO0~9GqWv`eo8zO;Wn8YEN`AgT?N5k(etgbDp(N)i0-MZ;Gn@Y3ch`?Ph zB}VO6k(*y@rA2~!PJM5(z$pQhC=sNEeV;)G5>&GzZSj{Adf2L~GR^5w7M{}7L@m%F zVGS5i1p@$Z@{a7}zsN!Yp!rl|9@d;APljL>5ngfAq zK^}6)Z|hdeva=Nao#OzC+Ob#>9Ij)05-z6Zmukc-u)UYk7BM;lBaMxKpWt1m*X3-Py{E}Aw2t=G0M z0uaqe{$Rvlm34@o<)85}vZE2BBSfCA7r-I|?Y?)m5S0A`>A$*I(DYC*0N|1R!-W_G zAl{{-mph{WB}S-T5@9C)?Bo4G0gvQY+F+;ML$X&_^%9)``(cW11|hXSD0TpNGE%h5 zTZAL%NiJPu_3F@8Jl@MaKR}Jz3E~KP2pM90*D8B`D@mK1+9ZEBp)xq+2XdC$RT0+bNM}nhN~HJ;p19Lzo@NB*cmxFLE5= z6_K2uEqEFs ze*jQ=7uy=WcjV`LNB$E%VMO?=#B5&h>ta#ItPMiM?+=zw!eGJE)u{83sQwXIs|-?g zr@$e1EWf9ca(y{9Z)n~DPx;#HU>Y+ZO?`&JYHNzz3d>+&4E2v$QKeAl(*FIlGphJq zo;)J(arUd<@t7*@78WCxsx4Ax@P)=70^mc4*OghVSSC{&IsL(#-}r{2pvQ2OWjG&YJKD!ocoT86L^ z>v=UqfEN^jy|iXd>|xQdHhX(?CGTvLS2V~UdN^=aS?Cn%8>VS=1XktwS-(Ka>JQS5 zoAo|Kd%U0qgp6+rvf0tL&+wJtQQuk~bdki8(@4xH{a;mi?st3COP5H#zgr@?c*PTC zV?HL#nR*nq|M?Tzl_pbCCUcGcI>dV6fx6_}gi)NfG~=UlbX;4M0(YeIv|9~|W}7u` zS1iKOZ2mzKT3I^vr_t5x&!am1PB3D?rP!g_9*L7|xw5il^Re*=@ovWB9BVvxOtk;( z8Hn>Y)(6E;U$)tX9}ysf5U(v%%?aE{VPZ9kEEWMEHwlB3Ugft<~ z&u8&>bTm}`4L)ReGGq|1hTMHS>9)Mjw51u(+Be zhrHYQ^CcxlhLqi6V;gko z*-N5GEwDjHSsDZ(mBG;=ru+0KkCyquSpSee6h6p00!Nt{BOoNq-85@TZU#kJm0KRK zn!vTi)`R;GaGmd}MOC^kw(S*&2@G(gmG+IXdRGQgMWY^uAEg&FaGiqxz@5+-wjGAz zl1kb81m7?ie5;&XhTG7iw-D$3%b675f~;X&wU}4g`c_C0U4W|P{t!N5{e4xSsY2I& ztTMqo!FL$5*71gZ*_a(CcZ5S+((zl_{>JZscQ;-kn!Pglzo}QDRmQu5!jiRciRWfI za>qIs|EIG8WML^UpeN!F^%8T8NeyEu6h?z^-ve3S+TBt;RSxuCRvl*lBPJF`*^r4% zrp0+q?&6UETjB)lE-U$G>yVrfC-$FrA(>|jFP-~e6f25YAtC_ITo#vC)xq`{esq)B zNp;m7X(f9tLsv#lmDA{`h?Ln-1d>`5IBl^X^N{Le0mrQVMZas(;5ipK$_aTEj^zWn z67mJ*XxKEHSP1ystsQY$RWk&hBOwbQlf zdbP=3byV92Cv0y|FF7C z-8x6=ZJ*;KZ(KBUe%Kf0$4Kf6YL|eG|HBYOtp?qzz_~l2dnC|QE4L%%@doEJ$VlXc zNs^3P^|Fuz^?^DjefkkOywHvqq;9(M8w|)*@U%;V*kIzYzU?u*#!oPCItxK`-`onS zDt#wdI(`_U<4JJmuQxEXUsqJ_Pc6y5?}KdPA;)N8s7=}d+}_7W5Gg2oC+a_}OOg(t zr8}Ev%tlh5pcaCQ`FhWu*BeAqj&-+o5V$LTzF#^=wax}dCff+M8$i#(?7*|hj(iqx ziVBQqz-ScK2Q^KxLVspteU_tuHS1p4O9-m>vPJsfHi0aGd(3UA*#C@BYRr$_4HzJl zuC>!`AjfqNFtKM;h$(A^CM18g4J?6tb{7N)L+7a|2d@*TB1D=I_F3cizH;&0;CXQNlsW|000u+A^Hz7eWy#r=7Kob6`iw50OdfBJbCMB(}Y-!w%a>+aH(!)gHp5QC+>y`oDJq@OZcC{D1tR zBFG;Ak)-_35b||@PgwZg{~d-0;O-!N(*rUQ!T&i0;fGyU3(({ObG$nM?uXvsfDSzX zsMz{n14sbQ|39sbDjNL%Jxf9M?*^s_0NyRh-u(~7diVGY?62(7B@u3)Tubv!P}4z}VP1IConqy_VFEcPdD@d>-+N=1Mna||S}3h(>0yb$BZ zv}+krxLDiBP4)p5_6wxlf!ZF3ay-QlM}OSFa!w8QIA+UBBNgi33GpEAf3mg!v;v}G z@hcfn)A3v-{viDV)mBVVK4kcv5AW|o-f14<(-8pm@mRNhNk-MJV}w*^uKn81%_Pauqcu z&(a%+;Om_o>;30%agdP&qGgWBK-AZ|)hB50wQcy8g61}@00Zzxep)m)S9xd`N!sv$ zD*#jaPsq^hQ+(u9-(3ai^?nXnoa84HdrP4lGUne(<>)86;`v=X6i;|*0((*(z!G22XiD7uMvD>q`#%s&SGz>VV?RDme^i zyyU+`0gGci`dj%TK_O94?CU8m56@pRvpTo}88RT(jI~k^QGIcpqrp_uie-8u&vYes z#xxE#@+Pc+irhy?NI}fEzrh(j9m5+5omFn?No6V~iu1N(2TYS~7|g9tZ(geF*~N=_ zd=OCkt9yx7SM;ZIk+Ew|tX^8g?iU_sNoh-as6yszM<{IONr<9-&jK;5EccQlc^OC( zuR}A8?IP7_29B;_98tG{#MblH{%6Xi4%lSA7SV%@mYb|{X_cs$^Z}xxWjvZj0+r_l zy;~LodsnrHApw8HyHkybuS%xg%iG4g*h$AR7_?@7o{G>i3w)#@lXqoCcG{mP+^%Cw z3Ps0#kcBD+ZLl=(LWPX#)*A0o1L<{9_2qo-8x&y*0ik5;=u4A8Be$9$|kf@d@lNOiQC$8&4w%YP^eL{$q} zNI_W|tRh`q@CU`NqD)4~Pk*HDC+2#8`angZ*(d+a)%X4u=zrc~YsTL%r;LPTS|JY?l_3MXPfUAzqu^0hXh|zG*y0cm zvbrc*p49#!EL^S4XjO>AtWkYB?2^S9*4T6Qq2%SETXzfTlC zsv^|AA(D!4ZXTsQF2-HO`Z1S30DSuAM$v<^ujT(Aes>)vMTt=6rzJa1?Bzzhs06`I zT^#P;)Ys*4w9?7U7e`bNv@BqP1sXh8jmu%3C1dKzEDhJP{YuGNEYKL>2yvI;36qBD z`CzQZVKTqA{K(#0>AMzvuTj1+HVJXO-+{XW>RtH+L2;R6oamXrp@-INUx5{U-zMVL zfZ8d?vkT@Lc-(2aQD_OMib<_15s*(GZWEtzRPPuJ?dLk>4Q)!zh;tzhRgnX!e{4sI zM-5582rKd8^tw&?S?m;ek`HH2U$0W1ljH`0V2IuFbG2!uFle5n53(`|kwC`v^<0Lr(V3NNe>Tpi$@kcPKaI5PX254NoNz3RQA~&gO;Hhem({ zaucRa0I*~n078eg2@W)+>F2J)F5r+d%;ggTEQP9^bg6I+#azh6J#_+Kk-pMPZAFR3 z)Q_BvM05Fh5FR~qFD=v8lMkoECI+&`#RZHZQ~Cp*X#P>nO#ni!#hUl2KLF7VC~zk! zfdBdf9l=-cHL#OkKsez5&bu1|(%%iQ{I8RKH~9ba0m-l6_ye^7(D?ZNBZwFC|GoqU z3@|_OT_eB?Qorl6(xM82PlQ3qXxT9Ws6cBcx^WvQ2cXKw&p-sk8zS1Kkb@L$0+W%I zHTrdck76+BbzzSXHg*^^!)Rwqiap>31UoXfkWLM68~9Y4#~A9LS^xV2u_eD$+Wwu$grr(n$JF zU;c!99EX^RA0Ia`u86ih??%L#t>XK${!4^H3Z49OXmj}#W6OEhw~6~TPS>$%)ZA%i z3qL<@0w2);k;`SxD#;krl^(wAbWvU$GdxoY>o29EbuzqfyT8ZCM5aCx!Qlp7w25A) zulB+75w+26S*4CgF+TJl*)MmdiT>sMD~`m2JInzmRy1YoJl1jU-{=u+RU}Uz_!E-< z=gIuTivuf!vA|@BE=$bGmUUJcCCoWAuR5hKug|EZlP}Gv%pjQG7R`k@Jc01qOqC-d z4WpC3%)6)njRALO(*5O-|7_s5*<+fWYI5n~$krg-;fWC*;R+Lb648%CNzW&kok$#> zYGj^Zn{bQw{1aZZq^V(0Xkxgy?cX`Sz5a&#=ATN9lUXS$?n>K}Jwm$F^xF)XB#cMU zBV0gL0zEx7fx5?KGkGEKy=e4@1w2GZ1s*FXem9MkHXLjwdW~l2=m=l7Fa+rq4sK1a zh~BS))klX#HI;9&e`nlkYHA-uk7;YaB>u(HB5)bft&sJK5A!WJ3xV7sa?xPNZ-}7T zEVw15<3Qed0CN%tgNf#S3KtAIY!)eFZaB2liF7X)Y45 zx+O?8sEW_c$1$S#?^=oN6ht*T3C)rffAO}pa$1iUw0)?Ak@9cLm04R>-$1Fzt9ZbZ zJ3pm@XwkFpwIr&m+MvK0c0a6fWV$EKz%)`Ab%TpqlljXWTc`;7j?7lhA^eqMSYvTea#l*vnq zCb?wxBJ@7j$s8_yC&r*O(d@rS|Es8zwRDt=+**t2N^tczNSKN_;{@kg)wZBztfIumYREcLlb7G^giyr&Q!)hvm}U~ ziXm1=$BG$wj;3!{Y^2iVHfrkW1%v)PR?@JR*n|2X^po?+pPyQt5D=XM5YWtPT=Iy^ zLOq-C;~JCq3kB2*xDZDO_2wR#zOR7Xocg1C%w)f~2Nf#NVi!O7varwFvJdKLoWF^< zF0D0AP{0=;mober?~etQ{oW8Wg49pH@Z_{rehhD@xpEUF#uVc2cPcCVKkD7^KR6g6Cj=()4m9q;YES&9Bg9TN74m7*24x9u?CgE`V zvY!b+(taPauR%EwO#ch}l13rP#U4|E1S@AU`tYu|o$1&NRnom~bZD8^nz}38V0K( zFvz-IhA${E07!T9-+C4W z#=Y>wF{Rd>oCMMk@qc=mFve#VJ$VVadn075;;YBc{DYWl6k&^FC@>8P9aJ}}@|O$i z)wr-3dsSn(o#%We=lX6>pGf2YYpk>$!_hDz}Ex40I{gF6wDY`zj!T^}_S zcr}ErEO!|ynG5~$Dh7&VRA5kRS3Eku&{Bzu`y2COr5vuB>Idy)aKeW2#8zGlpe2Oy3K03ptkf$^+mXT>g|y0umlcv%x}2~!0@FIQooEfOPL=BG8g_y@*a;T$*X!+dvs?gp?#G+r~_GC+Ib<-z9$9+G7%<-X1-=VEF%30Wz^atkLpJ=QG= zAMVYHoC@+zTv6|>T#vqXD7)s!C&L_bkMBKO0kxTD(fLeyk>5E1j35<57J7vm5c3KPTbichoct6xVfrPR2>oSG_ zY-89P%(U)Vq4*)DPr$pI0DlwMKN11a9RH>+Xr$5(iuO$OdyYQ(p%p(Hd{Wvky4L6F&R5tNVluOT4vkGE1& z7kb8o@7jEP%oQ->o$hpa3$`6o2-n%Nrs}jD^b)aT9@a=RNw4@ z`t<;4!5km0Y$=)in00?oI@BZ7kI-p_6DeX&Wk=OS9Y*d!Pi71a%LSR&D!AeO;31O} zH0T!KO^t-`@Q)Q>JQ_qz4gkpL#O!}dpdjEzAPB-+-2ZFj09>LZ7XZjjG6;Zdo{J56 z3RcS;T? z7wT^@nvpJ!Dg@|94%mYPV1T%w_WybJzjglqoY9>iO;BV$=mL5fU9t~m5y~)>Q(r|>Nn$w~I~XCvQWpLY z1t|bfE(Gn92+X~cXjTB+1E4Y6^Opv2;>f?uL*qioodxA%A^#<}lKu+XY0Mmi%=NW% zv0dN~GcP_Knc;5G#n?y94VPpne=%(b4fd1bCScs_&r6QJ%{r?zLufX^7l0#Dmm)&(wxh&=lfspTi?bZJ}WQ-w| z<90zR`?qFP%nSfFD~{(+4**y^(vX7^1)BzliiJ$F>AwlCuPP+YbRP;ExgEQhD|>SiS&0wn_u#lxcf>hNycA_dRQ}#+dzc>@G}ZYA zt3|oh|64n#1-=neD44OvgE1tq0~#N+CuX`KU*O-B(<2=Os_Awg{j*FPhTz*S?ARp` z&b$^k;-_|_T~T;uk6?Yia%imfTsl-T#X}=x6=pYE(M<1h_Bly)%mlqISA=rDLqRkL ziG)y2=Rp%}l$p)Xr-p=VaChX1H;jCob@`ie#|6i!m`KEzjCeGu_IGU+P49UbP`>q( zyXC2PI1P2iqMrDZU~Jiosn^1Xn}q1`!(4f*8|v>ud-#uqFeu=A;czhl{RiX3V!@sA z-rRUhhI>_O3C``)ZuFqfUKIqw);Nw2s0=Gxv6Tx2#HF=t(CAmITUBdLctfNi3h}KVsA}2_;)A6)SI^VM?Sxm z>LmGX>OXPdTiL&e5)*&{qXn%PE#IMO)!Y6HV}JPqN1g4A+GVy>gP-V0azC9*rxFBG zZ3LwH5(sx34$VugaE0YY+TY{flUp2@ZhGIE)X>*gAw>chCrKgAl_|aBEH7U2Ffs8( zASY%un>ytC#h5(q;L>B0?OT7nIaKhCfo0c&DWJxJ!}Q>u zCLS+r(8NE$Rw>i1yTMcHiF4_qfaB(M=GINEpugBRcErU}!9A+8f;iScJ^fk-L5f zo&(DjZxP)!0$k>s(hP~{1nBVbq+zR_K`5k~P|k3*tg0ZlK+C3>MVb6|G#qRKQfA9Hdz(GILtDJ zIQiy4kFflOn1ix(k`|Q!?%YWMy=EsR!5AMMMX>xvlX#d=S45ugaFSDpiHMz!pVqh2wM{r3T~f%nUGwg00a3M2N}+L_+BM zM~x~A`j0@w5;TUa7DLo05XItuivEZE{6}iO-Cz-gQglfTqLEXa7f<8??uVVsta3zZ zmdN2jlnpi~0DxhMpRNe`K?gzNU!Xzaf9pblh+gc~E$a@Z?0+>Bc*JERS-Ju!2M8&d z5K{h8tNxOrpAJ;yclAJ>Jd7v9*g|8K1Gd)cGpYd8ag`KJBH-Brpj?Fk8a<$@Wk3-U z)*Q4y<@}%bcn`{_{zr)dAPdQK^>K^o zJuaYIwcvtk*bOW-@{tkpWa56Y7(9S6BMc*9p8O-iaZh4ifc|lpVLK-vkgJNvIX!8h zSew=Sam6PT?cOrP)7Tk5$n=NB#TXDsQ3nt}W#CRik;Rfo39#H0o6xWl|7E2)!mDwR z!$QughqSj;47HLKUjIQklCs3S+*`sasY3d)uAx{isNqUH zoBBES6$vx$!8oN(S(pDEYRo!0x!Lr{f=;xh19dr*XHgNy9OfH-j?zH}FuK=Ieh>?( z=c44^gWj{%H9`bDmV@NRgK;WEg{<8l^iUlG?h*~0fOWjA)vqH!{B%mwWSgEXKgI8$ zif8~p!IdH`l4p@Qko@gca3Y%3ZMCR$jhq!E@}u8{ygLYio|7Y=08PBK0REY$@S7JR zJ1_mGV~y|7l5l>6Xp21bPN8xFc36pt{-8fk4R)DtAnobj6j!u!U+ZMKm8)A8H2DAOjcG_{-B@)KVRudt+vJFu>_Bn(UkLfAZ3BV`c2 z0D4%7<`8M{*bp)3PpQzkmhfOjQb(yb~)XS>b1b3tU}2DU8YoD>&nQco@34cEg ztbAUu^+yszHIqC7)x@X70UQaYICR@f)SFuasAhfRS1(=2ADtT51e2QU zzlo9D1U#2ps?&nm@KL#cBJ$x!Aqlq});5(1y!fna0QP*$$8vLFZaSLAeesUkj>c7} z!C5Mo=DVB+b>!RbdlJ9iUF|)j#F#7XCmo~Cv%3(<6n{}axdM_YE3jjXkkKaBnb}0S zYaZRKyrNF@&u*-yF|yz(S8@mTpXlcCWu=f_GEH(rEq6t@x)CkozM*)ov|>Yf63RaU zuh&7J4~uWn&lHO_d!hvN0>i+e#L1U$87bNAKP-`J5i(c>@^HV?Z-f)=cgR|W9>%2_ zV#Sd`to`Bag%D?ajVMbW(J37c#)z0?j_J1##$M#92`Z(&0d+!cr7;JDlr>>V6cV0`{9PIKAW1K;z5Bwamb5UsG(8miTFE$T+= zMn`Jh!s!*=`}7}hx6yDIBb7xk>(GxbG{JGPot05!&lA@WJwZ||pV{s|j%)xElAyMH z%#%+cW|F!2T=b{y-caIA+Wb;}Th(kwl}$O`g{g*34st?h1b%!$7>G&%R;NDxDGmb` z244beAE&0L*b`@l#TQemzH*2T?CMqF-d9bm;+zRY_lAIUeG-F>JtotKi-O%{}NXyhoj*WQ%^W76%iuI-#u{w@#rS+K*CB8h1?G1Vg-fSlAZ|zaee$1eozp3=KuEs0FV~^TlD{(LCcvCs~mF4 zpy%%y>VhmZ2mr`?#j<&Z{`V}Q0utG$CVs>K?SJM2$7T6D4F9H2Bg$?T`#o)Dxtoh( z+4ORn$mPxdbg#bXU@1W@cQxOB0I#PPFR_z<9i!7+x|2uYYoJaQNysIin>ebyJ8O{a zwn-%@pZ-+7T_e+d6;=9X!8PiL#xw$6k5>lRu|!g@`XOT@X?5!%S!||3W80T82!^V% zlS;m;D{8FYZ8O{6&TrUF7Y#kHSJ1`3NFG+Vojj-^`s%C%D?l{!`Rou&$lI4s;$DJV zj$w!Pm_q6H-PeZngX&Y14qr8cf~U5v64Xe&TZi-Xa;J0c#4*ZMV@p?$_g($dP>1+c z&jQxr%g7~jF05GyRtk7@5JQ5_u){}@Gy?#iDlA;M4gHd<@3Jq*nmulD$P57Wq|pEFv3?5~w? zK97_T?`Oi|nnn9C#pyG9QDn1AXkpt3e{JKt-YSuc^cH1M^x(n~h^OkGXtI8Qg_f+R zeaI0>~G`H|?C_EPG&kL$EsdUAZC8LDHvXyz`T6WambUU#X6Jm=@CqkR!PdWl;m z_Qof^t;jAbm-$QBJ>!@BD%{I{~ztRgWlueC}tr_zqqeLFt zHOfQzPf3(zaj|iG&g3@u1^{ZX-aAY1=nTx9G>O zB7gsBDg%ovZ3!$iV_tR)6_-Fnsn6aqqi2tsYQ@hVzr(b`%FGSr1pW**B>RC;byj*j ziAhnm;2Z5*UWeI{yrfElbD4u_$+8k+i}5${Xzn_2uMw@~;BPCLb9f_;{`ZU9 z-nqYxnEPm1VP7#Mc{R0{Izm77hduj8&4qWpAAXdA-qyNjf6cpdflp3meuR1{DJLe# z+YWW9Vn43n{X9)bzzo|;ox?6?%g?UwN~Vg$-B$3GqD?Ef+Nksqa+KB z)Ny_Rpaf@qVx~Uv8;7mM=|IyDe_|9At#D);b~f(-2C;)JLU@U3QXS1`6UtJg{#LFY zadX2-Fn%Zu<5ZFGbGxuL(&s^3GP+`I7VEP0j1%XEm6M;p9yEDZNcea-ua;|G#5MUJ z9xU{2*a=DJ8xnPyBQ>Opuo2za+@(xGprxXZk@loK)v=>Df%&*`bcFZjlHI z5te^bF&*T~jwvy3s%%{(wGp*0)OKQP3fNwXEiG8^fCNP1s^MTNJVeV7*T0^yB1lYp z5w`5me*3nvPdCk63=mcP;(!HRRESpcGtk8Z{CwHdz9Yt@_EJi2!%iP<&p3af=+xH3Rdn+`kraQlO0gK&g72)+4W-gEjpg`WoR!FfIv)kd${Tl9}rwKeKG%1&EwO-1xtB{9yeLy5ka$oSbpO5)CKwBBX*qNE_0>L1R{dx& zeP+2_q_`&Z*NerQ`>9KfkM^KH<6fCqa|}vj^z6FZUy5UN_Uf?nh2BIkpc#4LsHEUz zf7fa(JCY!_)6Qe$_Z?+U-kRxy(7!ngu^JD&CnGv%iMmz`JavUN7w#x#p~2V3VEw>TN?6CrHmTwBgMspMRy8XdC!vt)xm!olIf|DJWe_9{Ui)zte#kF{9BvW-(aj@89)Z5KEqQc*|$^ z#^ftyKK2!P@y-&TwvROHyDtrd!f=ul_2jQI9EUIpI>#Wn2_fZ|DM zt8G$exy9Z+Q9eApeo#>Kg7@p`j$pA^p3D3(qTY*o%&v_Vmo&hLDt<;@h_~5(BY$*v za!z-R?d`uQ6`D;`4xbqr!_I<7ww3mvtVu+eA}WXH-Gv|eKw)u&ay<#0 z`S4o2F(q9m$N3Y zS^t#XT*s!$dMK%#R|#6E+(yy&MT$s4OcugdzoA6@QC9b>jwsBxY7)!n?Jq{eJbTi1 z?APz!!A%)%)6ne`Km~Vrh_UKf5NRr)XMTd7i0U_%JC&>-@A|F!gECD!OP>GjH9H!d zQB!0k@>ifhvU`Flll%g8p`7TxC!02Jl?pWvjA^Q1U4*iy<#*L231t&*d<4~yR@kh7 zXmX4B@MGut2|tGN_qlr8qUd7TIYC9$!To~E*NX!T0eF zu~>?ow$$=1D=eHRw~gnTSHWFc!`^?$O>nv5IR-`OTxe}9e=?DG5@NY}@~@(Qd+Tgg zJBRIiL2l4(#H6u$^#*%x54&6DsDD^=*q{XNM@D{ML^qCGB@eUFMg<#WLt6^9vCrE) zW806nO}kR=Ga6zhy0l0?u^T^zhIPT~KaHIsqdfeW{D#oJ#LZ85Y;}(}(4knioF%;q z|Jo%#-I{p%;P@@$-f}Xoo8o;V#t)mV0qu9Y4bzH)gpprrW;Ac?!#}S1k8fqFFb969 zf?Ds)53+1deQm?q7FYiix7RBXO~cBt>NQl@*y|hOr2Otp{?-GNYA6Si#C=pOy$^_P z0cRY5lI?L5UxU+CN7Y_}FUd+xMrws^lmg=T9^%6^;1heoM)1htb5BP1TMT}q{Td~} z!+fOKz_ic|ja`D>_Ex1Acdb@g-8ItHitije3aPz6nF*$yc{6}kpQlUF4Y#pnLREY+ zV)-gQbVk&eOf@2`X6bdq6PA}j>)eqrsa`|)zV~hM^LRo2AFGguOkP^Y{$nGk+Sc`A zUvIlaLpL+t^w(%5mM^>;<@^nGn8%vasQnX4MU1rl|8+%gyxqMe< zQ^ifeOc+blINzJ+%XEZ%6Q4!=ndU4qKe)cd{3<8SOrzWld?UnnLwDj$;FQd=wVH{T z8FW(aL5hBs=q0i_FyZYg72@pcjsdlk+tB;&M$vXt$z(PU)V&6L!b09R%uO1YAAeqL z5KyqAp1L4dB0ihM?9=_MftYL5SVW79{eIon_9-3XWTB$#fP7|STELg6(Wh_khf>CM zLZ+A7A)Z;9VpMXFKbf}$*2S*7XZg@h)`8++Z*90r%c=FYvZ)+K&s?hh*iZVU5%$kf zmu|IxkP%hq=6&F>o0`B^!XjiYi5+^&CKfXf4zAY3Rf&N!JLJVEjqHYrw+wnMD_JiN z&uhBW+eR@+d~ZtBQLa!`42WFzww z4U$+=q3~ud_v^GfuGU+L46j-$_}x-qo-OGm$M>33lf?5sfb6DEGRM311VuhyTd(G} z(^ecUz0Hg1*?>C;nV$JIzDY(~q(uGXJBerJX&V0?yEgCe#7f*{U{euP8J8kdZtvdf zgVc94pBJPuXs6Sn)GBdap$Q#xXr+?UEf7n6c>jlA&^;PcPa2g_vOkQNJYp+im-bJG zKxPRoi8C6dYtgTP!DVjtDK1MjG=UEy9kgE{YCDKnfez`H)4c^U)Q7V`;t2C@<(7|7 zB&wTpOGD-Syb;EumGt*(Vxk1GOq_Aj;;SfWL7F1QJq;@2d-5smqABCjEl7lh)RrXO z=q`==w;(n;SD1$n8IKMV==ON9c2r%IkPL7r&k=!d420yohz&OFBla*Ego$5B$-{_KhYErQbKQK+@H&CT7Hsx;Ay@32K#&|4YbJAfkLWOYejv8 zz#}dZU&IoNFFiA78jLpLP7POKj{Tq-!chicQMr`SxPp6wz|4icT9;2(m%g5etz~Lf zlfR(96T^uZ+3%OUJ?6*TO>cNsOqiA109p`T3gWYRGL_mC5OA*sr9DGBoa%;6;;xK; zSxdDMB?c9?)kd$JIEk|*cYn70f`Q+c|7kbDhT`F;n?3&a863h?&p^saPLuxD_D{Ov z-$AaPRZk(5w5-juJG*5^(5utA!))6YJ(B)di%rZP6Zm%|lQORfX&l9$qdAnvwfkH& zc(K!KA1;2M61|)kGmZM9bWX(e)`Po76G`C?A_>1tt)`4~zVZAYKdZFog=v`U90&)se4S_Jf#_` zBYvE6+_}sO;IE(@+xev}UCy}PGsbuvUj0doz5=K;LHYf8N=XotE8&#jQC%dyl(*FV z3AT^cxtH%ibwRtlbmwOe>cl=hbY&AH+qNyS?8m9Rf{B&O z$0J0>U^rhA6rH;zM_G`Pd-v<{i0O}!7kc)!Xg`N*45@js>uAH5=ab3JG2&kq1GsX7 z4~$M%_mA?q)WiZrcc=G@Qb-l-BsuN4a3B>MD;|Z%o6)lhQG$%q!%cPED=KKv1zpG7 ztl|S53Y(A4Vtw9+wN&+x!eab~AUfrq#Q|T^`ly9Sw-+$RTg+}9g6*WQ=+ZOdBp9K{ zDmn*Dv79`P`g?|;0vM-Sja~Zy#OPruFY6KZ$tNyimh>ue(~E0#W$pTHiVbP z>Myk>_#|kA@NPL1#6%w+5R@uis$N_+|vn&wSzk zbw}W6d@&bJGO(CQxALbZp_I2-=yL3MGW=Y3u`$@`u%$D~!mlaNdc}T2|WYu|Vviy8b zuL8jW@vz31R-@h`D9-k3G+@C)n$uN5A32tND-bLWnENxFVejKB^UEFXf?%{*=k&%& zn{}DR)DEB{Mp&I!WC6p13;iX9x|RmTkcHtIipk~s@944N7<*DR&Zy#>B0PfyN9gbT z2wze#=;N|v6UTPb-TM|`5=gV=x?)qYeZQ5~ihuZC=4YT&mnnQ&Fy#9yCtoi*G-ih7 zL~N4Tewni}q&ONzw_Z1zo;7nL#tJ+Y4BHgJU*M~o&L9qje)3AWk;=PuWf|O-4^=}L zZ8)WRd@W3;lvhLr{p+E#^G!0BU39sm{I8*=^aQ7BlSQtz@h9sbhDs`3lOfQnaMLwy z_`2myC|+yy59%=2%bnV`H`~J=;*SBM+Y-iv^EHEIjkf6{(+5=b0SPdY-E+;Jxn6Oq zeJTD+)~WPiD8BQ5^#33!b9}s!Yt$K+TIDC?^!aXSL~!5ISAId79%^o27Z*fcqf46?&R1OI2o8^bV`W+60Z`{#+)fef3m4S!;wm`^sL9lAe7d`!iv3XCkZ@%rL~V{nD|$Fb_0K|TtNJat$Xd` zLUkncLJaO8UGChf?#@(e??SC##;3K6B>YeF(PCp8C4YxRw6*Vc?bq-_yba8dz_o+rmGwRHK)g*l zD*F14y`RSZ!+EnjN?BY`?I5E2(i&Jgdc!E!Agw0gqkKaQ4eULM)H@*_(%6`q_PTE) zSJd`in`P8d_=yEuJp!Ck=bOJrOy$cJ%ajePFo0iCQvAjYPhV$xu9>PXjR-M{M{(Zfzr%%t4t1jFXTM|hS%@*Lpxq|-m29>JS<9$i)2 zAGFpN7OHT_U>C31(*#E8T5%tzC~0P{ao;nRYt@~V=xJr@%2muY1ckFz8!*!ch6F%& zBwpB?FWk13ToW0_kubI{6`u%1yS;$wPTtVrh9R<2J97b%Q~lB@vX(0KNiP`Xdrq8xjMX zOP^Z!;38<&7-y>~K|?~j1=7ROu!rJVrquj{unNJ6 z#lG!zVT@x+`Q|aCb7`JcWqd^-Oet1=x*qAN@?_VRhWf{e5B*c;Z-RdO@!fVpr+9e5 z&H489!CYJd(|h6!Ek}rmji455KSi#cQc&mX%O-!5R3-!oZwg+h{Qy-->>P}Jk~|ULhdrqkP@&_^t(uD zSc}yVsYJyiMAzq1H6GhEX-%!$w-Z^e%RqVS z)-1`!BmH=T@cT$m;P__BjM)FY0hJv|jc9;y^@a6gJ1Lt=I{zyy zKKh((=;8DBbcXU*f=MQU3b>Igj{%&rJI*jg`UZa!Cv*o+bjxW!?gOm?!z2t#zA-a- zX08?6|^s;r2=gpvE}!jR8`pL;S^EIPAp!wlJtK=QNA8 zK|-KWTQco3=lEfCo+>ra0z&>x-vy-&&i4po%UFba)HdStg~H4XSwoxEEVo%Rcwt>% z8r|UQjTLN_a?#orO}EZ&+q5{wf=X7mXMI=ZE&6IE88pF9xz`ta2guNOlb#$hw8U8x z?qi1bZ#hnM__NVyq>J;>(R6=cWFBP{aJKG*Ve5CVEu^I`XTWRDzr~;x(0dxhk37J? z3KKscD)g(Pz>Pb@?V4a4zLabZ`4keB5TfP?dc{i=TqOBimhE&@?ZMT^_CfEKYm9{3 zTau)&m;r45<7RC`wt^z&# zm>Dd@Cq=#W*XW+Bs^M}$Y=jJl(sJFw!G)vwZ$=7ZEp z8cQ-}d2;h3-4p z8N76K%`w(PhVfOmJkNA(n5KTLfzZWQw?(9tiW(UYZQcPBw4W2JYhzy-3uJOtwq1%> z&o{viXusJL4L{m*Kz5!ZAmJGCFMqjt5~CSCYume3_~NEd=!7fS*%xY`nr9k|vNH zZ$Joc4rGY$-p=O$Z1V7wDN9$t$MhNgZM8-L)?2-7slaUbT2xAIVdw#wo2?BBYcwmz zADAtXz4SeE!&<(W&&zerg?B@sdgcn)ng_VZ`n>OI0G!Tu*2~PEm<5~uY=(`K`Y+=a zBeAe10gA>eTl0F#@p>mFhoxRpCl~IrpZ3vr>pX!_7jT?Z($g22o9F?5qayuU0qYzd zcNGFI$*i+2#uUaZdou<;>`V8=!0%CBmL^xy(xetRwGn!=d&PG@{b13KG98yuu>`Id z!UJiWHHp?sI**&4Yms`4(L#;qv^M_;A_U zRomv8`cef0pRJ35AoM;L_U^V7{>Q2<3+o&|;4 z1MQjd-C^&@hV4%GL&h4+R)U0t&3W4OZED;@JjlEvN6t}WrSC>B8j}+Aht<7VD)Cip z7z}xF`336@m_r*+w|%(7e1@cFMR4KN-1KdTkp)38NFHHZv0mus445Y+QV9N+FK6e!zt&JQD10OB_TeAOS_*R;@-Urow%3Ts4Bx#LOJHQN40M4U zp`X12UU&_J_AD6}lmjFp?ov>x?eRx+j7Mq_F!bO48u(hw1~n4GN41qcmfsur+_qNt z-GiA=uCn@asGCB%!$zL{Ia|p6DZ37^92! z`#ef227Fm#=WtaKl;W%;Y+#_I=vag#c=|Dh8H zLEP?s$krAP`+7V3ECJ@pP}8kfd{kKjFCL`4+shs$3f%;a{8_Y$;h{?{<@lul?IImk z#fk&B-kCwr;7R)Bv!W$|*Y5h1wR|3{2;UdB?Yw=8irBo^_}UwJ4M6TMIC@PiUx@kN z7^A=7XaIR;Si|KLrosv__(;d&V_ye8<9M*sO%SkD&uSg7;+bTo!O6Ry@7S#rK}#L= zXDfs>tdI|_^*(T*k!n6fxZj9wUQ*$e9WdKG+-r?)zBdNHsoe?!)iTiejy{#qyUhMN z^*c?CEwuc0yO<5>ItN&!T_D8V*i@o}>hXljv*7gjaj?{%_oiT-I;>o4- z6~^PiHw=10`tjAq_MlN`Ow)$9Bw495Ose)y)_B?@yM{*dA+qb4(4?OM4r`l z}W~vk5xPpBPt+zo+M|wtiH(x!SXN|Mtx{&-y7dcd`u%C)V*)9*!5dv=TAAVYI|9!8)DClgRr(bLGbO zc`KK_mcH5l=v!{<_8Xe?cm`ax!fMl3)E~GQXS2s?HZgdV7yY9IR9hi+b2aHenk>>~ zim!V{(XM={#?IR4t1xGlt0tX;2N9+o4P>WuYJLO)5-t)RO_J|^N)&!joElFal^gvfW6eEm|C+A$@azZn9hqt48`FZ(_{LRMh_uZmm>Tf`%7R^hN_!U+I? z7f`9BAs7nW?qS~2o=m``1z z0u0nK1&be|jGsTh%FmK)Kw%=&1go3Q5_NB{Y5<0NM33j6nr7x(VlzY0)E=Y|l z9hAO^M$2hHZp!QsH0RZ5q{=}XfF&?D!no+O_z7nnTbs0R2BuVt)_5VCtJR%Y?wuG- zGJ001S0{|RD)Qd0$ROnV_F*oGvUac>lEs_Yz zP&?91hS5ALsn!ktJCK`Bd?+Wkb2vN zD`JR58x&K=L~kBS~V_$Gl-VT4C@GEDX zX0Fyp++NmB8KSP8HAXPgf{RW2BHFwaLS41=h6P~VgVOJv^^WKrtfS4wW)~xlMjf8m zfWC2kQ~O;kCu;k%sZrVW)xJVJewz7W7PwxN+k+Z6Is_ncCg_3!N!Z5s5hDpjB0juD zMN_jUxya?F_&CGH7{>pN-|VGMQDFzDtVDfLh(iFG?=b*7!M~6SM8%Ggj1Bz?0FWO5 za-Cn393!Dz6K!!ufw2fiyFjZ&+yJ1?AVXyh(&Kjj>G8pIb^DJQ;hLH4B|$oEUYCB- z@e!zQhNR?$1c^w46S^8Jt9zt5fc6g~_y<{VN^_TpD?hcZA{4Rnj4F}u^0g8v`k>=pHl)0P^I2I@Toc&?3~N&b=^`RuHs-m^nX+ z9;e{|v*b`jJAfig+#uVp7J^*nbFrc}+)$l@nV?WCh~vDWY7Y_*0?y;(L<=E<86XlB z4FW)4CKD8)nE{m{0Az#mfra1rpTP|coJULoP-qYa7a$D&3!B9JrSFSepZZ{JZ(F$? z$Ds;DJv+b)oM{rYw92Q(klOa3HAY{WcOyuQLz(I4)qECeDXVF|J(M2izhG8oB_0-YkgwvklvFJz zgobhIwz5q#WzS4LVOc&Y^vWhMDH|V2=;ZigLD^?Z_zk!+Gib_ zjxea+^zNv;Kfck^rB6ww`k7NiW|o-uBy_59TmUrydGanX zcNl|Jn!knlQn-=j3Ua7DUtFxSM_nGcs(R|$dfwOKCYG{gFc!(zSAFmGk>1|Xt2?j< zZ9RH)CHF-?CLg^Q!UT$-%d8YI#GM|#=O(tIPKMZ_-)1=VAnK~Yz=Q$5{jBh!@hvz< zwu9%5)i&V=_+cK8>W+FayypWu+dSXG?1*VMNTwi}mUP6jrT=&6C-f_*-=os7-Z6Fn z|0Vd%wUC5uH?C7u7%m&()HUX&2TunW-RXWCPfhm@^ZJFkGK|FYGc^3X9R5?jRVgdY zgbfgA{S8bXTjnr~j{dd&OdG6=*q!G1$Mr<;g+)I${E6kLJyMo*Nc^|m25SWMl>2~n z+wA*ep4v06X@-(y8#7m;F|>@u_t;WS`A6?B4Ywqh-t6I2z@x0-v3?qyTYoNpH?-Cn zIL9@BWE22TZXaS{Chz)%sIuCSFe-d^NKU8H&_xmPLY^+fB|e&2^j41#Lz=Oe?G!c8 z;;>0V;Ku;pdJ>9?K~iwNC~Qj~Z7{+-`GOXK7xDtnuC|u?1~kbgWu|Tt45tk$Q)Lg4 zDWu+5A zhks(=FrHV7&|$nLKH|s>R=?b>xJHO~3#!_Y{LSc>Up2v@scS4CADEN$WEcN3VCTPFg={FCtV=Ovf8*GBW0Y{qE-1@iGR-9iY zykaR_I2fQEa9L2p#n2W~^I5mcrAOG`D^5Q+zVOt+t z*OZbwP@)Cy->CLTDu0uZ>LMMWL&9J3qmL#Z(XAEi3>1dK#7tlUR+)f^~WdQ}raz5P~*!DWg@ zYsrAtML-HMXt}2rlC1lC@7(N9p7^ZiE$9Wq#W!n6iw;sD1@z$^liOifU%7p?Q5+6G z^(uEgjre3!ryV0Pp;-T`D-X+aPMK|&BvQcAj0Kv5C?(dT*I|NY+YUEf->X3c%>+9zi3YoC42wbkK!7B5cs z-6ik2Rq>{N4;wsXqUzmMu99Vvi zi#u4%dn9;&RwNlGN0IbAhM{rhZB1Rj%z{eQ;wdBA!lKcd?UI^PF-DqqxfZMgb6+DKDC*6&Ar7%!8y2m0CVNbaJVPy)O%0sbP zO#Z~>mGL$3NmcXbRzw)yLeY0VtUz7by_2_(JbA0*k!%C};7BnYqA2`_U|@f=xtHDV;2pr&>^;H1$=7k=YlwgA~K@ z>`>m#p~A>w;ZotVgB4PzJL##%29A5I${jT|OcEA7 z-?F_TBBtJ0A0>~+y35E zE4x35wl(mg`r#WQvKL<0)mbJL?YByE+mweA2%^Vg4CqeE8hJz=N9gc&lxM2Pv)Jx) zVeumxB3}zTt#OuwZhWCLLCM+6H~&nOVPmbmU-|N($ZTM!xA-r`h#xehFYDRwK9}Vv zkATR|D8&S#0B)O{M5pv8mG}V#YL}bV9M>UzmeI>i832d|I=0?S$4Jyc^wcWIdE~@N z??-2ILG(xI#14OFP_Z)$(U0oqPqd|tqntffKOi>~9p_>VrJ8^;>V`Vx+sBVya?`3@ zp#ZHOOwUV$3Jw2qelWSW$QoI>aOMD0xjS(HnmMH*VFO*+o zs}Nr?b64v?Cmb^7rr}RAvG~ZT-B(QURBt~!B=2z960aRG8e#r;E-^(UOYM!D73xjA z`A%6&T#R4;BqeULft`+tCdOFyz&)u-ot9o@kyF~TR;sd^1&=3cgW~xuYUZz87=}H6 z?imvELTczMsu=8Lv66?FZMuTGIn_0;io;GwwifL0j5tA%&^HlPp@L1GoeGjT()h2K z-H|yly8w+h218=#o{aeZ2FW1H?A4sD+dA^CTRh$hVq6{-kTg(Y{~_a5l_KSGz!Jf) zGS~^=T0QP{1v5wKa_utq9mAxCi+Q9!1kRUt#H}stzEO20e2c;h*lkRWk;r{XpzHls z#-#Y#b&oYg{7r_Hg%pa21j~+k)FY(Us!1!S|H`#$p`706ql^EhTc%O5P8#0FMo3POMcf*VyqtHugZS zf$gJbU&5&jBz_R#y;PnBlllSfw=@Im)9^~WAnOOi@6-b>0e6(x3_enA8J-hP&ns>}XuwY*rJ*;)a?_T)oKTV7t+yc^EO*>$Ur|OtH`JFnYE9W_lM;YcU~v)o)AsB9%8Hd zYJGj7e_--{sbQmXZHtt(3+r)a(slv*+4Q^X0)@t;%1$v`8}#QnCu8;ggx9ZrT!cz% z>3(*FP}$E~Pv~y0j$ClFqNN)aO-dT!k(Q8>u((L8Az!D7Ua#%;Ouchi&8fhb%s2J) z)~%8^jxYH27AG(nbuCt!DpiBW?@HfRZQy)p(|4l#%jA{AQ`<=@K?=HytvIFIDPXyJ zrrF{WMVh?#n#DWG&Eu($beY)9ZkHma8X~!**{~PB%nGm^XbA^ko6gCK)kW>_3`fv+ z{A4raVGcKGaF@L@r?<9KVD?aXQl1&{u~?tor$<;k-8>w!PDb+xIVKu^FhWl+xOaeP z>CTRmJ5y8Yd|-zCg;q_xFw6!=?Z&HUW}cEeQaVRwvlP{9ijcS*6^jD9OFC@i`zm`_ zBLzrsf)M6K{K;; zQRjx_*(9y=pYcCvU2qgXX^NwrAUk$)it}oxzVTe^zJ1+*ba(g)yLMyulOriU0gqp& zCKo?y+#USD%ADK{+n*1aQnvH$#oMdTW9MPRLa{SOi$}tXz82XgpFO6>wEFRdex61$ z^!+OT9&C9v>%>mgBuWG~J>zt+o88I$GN}3BoMS(=T-==Bw_JzSBQ09ROg8XUOVZQ_ zg2;nqJ-o$YH$fp#UNZtF1tpI4x`pgvBAEQ?8PHFWO_JzN)f3cWI^idE>jSK>wu+kL zzNMzzHlvfOhF|opNVrowl^7Y@IksCcOUs&uB(pK@eU%;PNY0Me;5Y17w`{AJohx{# z*{m5ZJbE*0`xz%2w5X)X^aIv8$Ud!YjKvv^$9gOpNE`mJ|hpJjCjx3(U`w<|D(bZ*+pC%0S;(}`2CWTN(8%s+V)_^>ag%Q5)~sy9JzVSu-C`@lcbn3@*!X=D#4Nc$ zA{c`S1r<8F{WV{z;Di&`e7}bwE!eR2Bfj5fGX&KegG*4)aT`);`$P)jMuqm$o-eFB z{rH}vcm4u=Wxn7RryLWuL~Ys0*`OZKkBZha$jqfu~=lu!Qp?SkSR zRx+cFvG>KX5el2=C+cZrS&%eYIAvif3a{th8o#lQUdb;RoMQt+Z{7tk2f^tuYYLs? zlmzZj{IA1|Pg~~B6SqCa;G$%vI2`%=9O8yI)VhUl&)&94mZ}jP-Xtvg`STGu-kq;_ zMo1VjfDVLkhy2xIslm>%}oIO6sWQ6u{((wzEYZIHg-MPhKSz$Qh|M|V_8bx!GK9F zr7YTF@NIXKjm3ZjK=7!0*%JZjDA1+jRs||?QDEEKu27Ww>CX?2kzj!ZT9m$mSyfn# zyrfH<7mEUwS@w&4$3?zQVcKBmiTN^Q*X{oKZdS>b_|F%H14lhFjSDtK$t0&VHqkYU z5~kMH&6usN=W6%3Qn)630ZQaNHl_&EBv_X`$IBGT z&w1-1N1?ywb$%BfShRtPv7WABS`~8z%j}o^d_#yfF@`*i=XpD63d8_Y4vGHj{`fz{ z2bk-?ffPl5u7^NI7>!YX{rvq6Zvy}z3nS3}KXAk3ckxa1@9!)WjrHG`&LyH?zJPLe z&F>SSU4ZVY=+7Cwg*kvE1ppL0?{PgyE61X(A6(%8Rlo53q9t-yt z#&vT6_#f?ndZ>0)E3I|B!{1M~125r^*F{$vx)WNMu)Kh=0rea}=LLqv87cz+z!IqN z9{xYFnW~l-f$WC8p-}0s<7q^U>i{;_CxPP$dj5Ag1V%sb$^SeP*O>uWl}0yBhd@|b zPSm)u>Hr1QXNL-!i=tcv1U=I_!MiOvJW42bSfbRehWgA@6a5t{;yaLZ#G1NDgSZm+;%bXqG8}ag@ zcFh45Ezh_z8HOTt4lxTgtZ3%ZicW?_wymX#f9b5IL0uqpXb9+ijkv^|^a3-F`9Y{lyh1r_0 zUvjA3Idz__*e-?46jEs?2m%JbJqZp>>uCJxeW7x9=gY^^K8M<%Gn*9Vn{Wqd2*zYp7GpnanIQM5^JYJY`!)0MOHodoY}`Hh<>= zAZW*+kUMg@_x^KZJO)3nc`l#Itk7;SKDGcDm$#yb*M?u@#Nvs4mWaA8*623FjeegS z+hVbh_RwHM-bv^P-K5a>Opj5}*1q-^*so(OBC0*%mVbiB>RYF0mPH(^D)nLW&ti@+ zh#msq-i%1)Z)I<{7Ksm1bf3lWtygflWU#EmUn>53eO;Ty{|G``gmit)Hyy8+=Mk&; zwGGsr;X6LTU-SF~a8H*p6qXyypns^&XsSpXBPuXFBzdLHihO(U8m2?CHcGIWcw%xP ziM^KF)!yX77%MvwS}E_KpvU_^~{$EeULXcAc@FiF8<5 zNg+;ZRkM4-+(qk3m@jat?B2tG*KIfMwyGA!=cgU)6>tv>x~Vq;^IkZ7(?u4FD;?CM zPFCwrgFL^2GsR0HieA|B@kD><3e`f~d;MlswEp&v!)&ZoQ{L$uj$GX%$LFh}juDBC zNRscA`!{Vsr#LyJajk+D%Vet1X47WkZ}!Dg*ah*emIp`v*=d5SuN`+j`%)rrx^O+E zR-$w_J)(RoMI;`V$&kWH;qWy5 z2_706Yw4;!_yNTzc@T?Sp=aW6P>W$Z#B{YPd?5uJp)P-7b>Y;eIGex$*F8QlKo!4; zpLX1P-N&s)-%&FCd3um7p~%nA?We+43JGyngChNN+aUEGA3k!rZ^sKQvu(ZkBgqef z%~BlABBY9nKjS|9QYM+ZqLmDSY0^|aU}+G13t^)nmvJ7QEvyCW-o!eg!mavz-vRSd1M#Os08O6`RFmB?A z^AI5(Hiiulwi5$nkDfD$m~sTWk}U-P$l z!n6|L{{)VvDJQE2;=w432>gRdO!jOMTaRPau;#KzF7l=~mLF5xjz@tG!C&gE{LAQ{ z?5&8OXfzII2SCoEfCtQK@JSU@j=*%mq&n6OQ6T(H-7I$x8-=G;sLWdDH!3;^{t^v# z&7P_L6$9=Ic%GF8v827JJ|p)C>~&@vZ5*hUsAUj}(~)8J#PRZvHKf7Qs1E|`@u1Fs zAG(8Zur8Dppy1KgtTYTsBMRVH!RQVPxm>S`|LS{RXmQpEwpz{0`kto%uuKd{p%D+r z0dPc`!(GA&Z_vB}00G&YV(obRoKc3y zu`gRZVNT3vUnOpmTUEW>Big9TYd!UV+6rt3NE_o5PS9J6=>6ItmwwSgEopVdigEIvwlHAoU5W6yz2D1HUdhz$1_Mp@AFWm zrsiiv1O|80C!^xmO}B?{(7)0b>p} zH%dZf62jN$x96pXgasuD05Y%CLZc{imuYHa!f{A#H@7*#**_CK`*xcO1UZ!Q^pmUjs7s@32k$Q>s*F}cP2;bb2$ zeR?MOszHZM{8ZT0@f?Sj6CiBdTp~MGesAq7m*_}#+>E0N?QdoBO0F>A&w8iaYv>2R zN(soBkEZ6%w;&V1@QS>q;>cOsl!a+@eQ;$ZC4WJ`I7;b5$I@*+tsb9z+WcwHEgOky ztagVfj`G4^B%fE1m7!I5WUrVBfD{bV#)FrMm$6n)?^%4|i9^~{=sx$1e@*Uh{8fN> zaX=PQWKxCi_9T!0ECNj_*)1g^v-13F0br!XUkvfL8uj9~l7lbQ?Nb2!Z|2_M`m*$; z+MM$=%*P*}(|0>)o3o5iH$k0Urt~$7dGpq`j^Ac&@B|I{6p5}V;GFQT(at{9r&H3^ z1XV8a-;hAuDpABlFBN8$K-fcfaGL+)o5Ey-WkwbFK-GV?vdO_RfS3J8_cVaN$~EVR#8T~# z=WAL(tvud^Xz4(@96IfQ=#RH19%k#1)PLctUZzTn+Y_{G*Cs?P8IyAA_M1IjHAa`6 znvC71LTTwZMC(VCq!c8alL9yIfNja(YouINMIhLddH@3bqxy)6Vbi-!2tL1U@Ol;r z3KPU<@{@?!CZyoNZT?v3k0Bi|>>5s>S@q++W)mRMo z9-M+20%b#hUHC@oF^6fSe6$!G)`j9bvse*T4swbGK-IWg5e5Y6?^OnDb zfq<9+pdIz+wHVf9ouVv70GG?yf+0l_`MVH%1S3icMwGwME=G=jeel*(0D`|nfj(gs z`_~x=APO;4JqHgH(`}rMC{Yv>G*0J>3%>=yQQsr#Vtkrt;Tf7G6di z8I1?cSy(H?9GM-?qft_rRCzKSUebd(HT;>bBm!m6iKxX#Xrj$F^&b(XzjtgX{z_h7 z3j5WM?yx`ugj7!8DZna%3m|~JxA0RwdK{oWLN&7=k}h*tb9~%qwgTIv(QFeBD+Zdw zF!f!-)Hm^;`jX;*e0HU1;t>8iV{7aqUNaS%8k^inSe<4?4$6kTp+#X$PscQ@p8l!A zbR(6Qnhx~Hkv&H*!c-gt+Nm0R*;*NT;e)GzmAy@^u%L-WjhtmTO^F(ZSlcOavW$D- zslM5F>yHIzYCVIPHrlD^OoiykGUGNqYrcJxDhVa_$c~%MIiB-zI;}^T=V(PU5PQv-Z0E<=@vs3b7k9mAGEvuDa0h_%c1{ z$BkV6eaf*@Z8^AodiwioeY6|XV8tDbvowySMS~(+hPn)+f|&zIP;V&P{lhZ(anRV_ z#GV)CBycW@3L&vDX=~_Ds_3>CfTKakkS5z-ZKb*PFX0S0}oYyu3t`4uPb_S_#G@#AF390#NC=U9CD@6E^cHME* z`zJK=+Lvd@RPW1uVL?{!ts7CM36_XJyK7on{G#q{mZ!wYIPQ{jrpBKw?x4o?#hR%e$(@gs*^MiMHss&7Q$$6)-5v^2 zYi?d%c6|vJvE-O%x0M^LF?mVP+>D5SA8TFl;EW|A<-YoeS!Bfb3`9`C2aWyIhIc>q zAJZY`ESfl+yl#V)cYJh{X}-NZCfziQ6>qFv=(j&ER~Wnh+bxLw;})pE zyHc;bvoOPJwibpMs2NX){t!B~d?{0lcU;NZpyg30LS z+c#Z;!WbgI^ez4`cvnInbJHJIjv1#|m%)4=kA9}ZD#;q}p9~bv8QQJj%r__^c({q= zH{Qk@e#dKeDw?G%Y~w}s+V2iVROV>zwCl9anHnW3%WFp|9S0J{o;R^y_(0YDlnt<- zW}E`o&bkj>4HDfYiFFy4{ToS({zt9p-$qaXh!>+rT0w;=BmbBc0t7$_d4*B?dT0!xKh9cAZx+MFEU5bI zv7NXv%`y=Xr5)(Q&tO2Hosd-<=6#GPr<5xK(wgYM4|xMb^QnNKQUtpMR;49dBXEDG z6BvCA_PL=!Pn}sB-xZ<{)!jz&4ofPU0LjV$e(tDa0NZ1iTqha~2HvfFab8Y2W$; zIPM~WhIY_7gL4)@*~sf%S>Phz0(fB9ifL}Hw*j~&khb_{O!DoXaZC$g)+E*Qtcd@X zk>D6J2P*hS31Oy;A%OKNCapb2M}u|ca?_OmxAOX*vBE$1K|qX?5U1ZiH(6PhivB7C z$gk9R*rPibxqcsmk}N}0z%&^n%aBJFX2}ADBtVSKmUa=qU@TZI2~_WxTf>~6f5j<5 zFPB5<@7|+9K4tbxApWWG1Lv>;?|aTO+q)cyjl$P9-kyg6I}Kf9Pjd`alccX8`cQnB z8#}*r_Q7Xn(Yr$Qjn)9pS=d(NyI0V|_bT?zJi^!S?O#M5&kR`(XPEOJ4~vn-;(WNBtlJa@7kO-je%i`On`DbBHojtT|}DRDfsd08%;m0o&}h7C&rN= zXgUvO<>t5E#@F*{jU+^@ZfA$gozQP+4_rF)ZgcNYlb);@TvR07^vyJ>swxq<{q5PW z4w{S(DoXKQSknTtUMX)m0Hh0?os?KX&*@LKEnNHzSMVg=ZCHS zT4^&2z-V}d0s(;HC5oGJuEp8_*gj+nrn+j;wk=(Hp_D!5@l zo14wd;;D?kCP#>>jH>eu3jbraIZNrp;BAUojp=Rqe7y~yux-i&m+6kxn~JV#&SRU= znYH&e4%_#FV0i~h&4M)wk@bP+es39ngf=&bvR>BFiBoc)lh+6@q&_mKU}`Yz#!TuuY@M0psTD!8>xW;HOXkBO zQ3+GDkCs@x9Tr6tuj~T5Zk`1AL=BF{JY`NRTyj*(uz9EHfB%uJ+U#44Gn>79UwtYA zj~zkIUwN^%eB5xUtZFzZdeex#ogXxGQ_<_xszF* z{%)aXW#mE!Z)m#bE?cd8J+JTQ^|RTQ*%Az>yuL-lP*gLV3#q3Vwb&aYTbDVjIvzRX zB!y7O^+uNxWt^SkrniW`w71mkGyzBL|%2u@okPwLi13g)V$J zMoWR{L50N{e>DE>zk+yZINw+g)-A_+Sd)_)O;f=|HR;2ZVpCgY=878m%t+22EFYQZ zp!x=9z9jLKeI4#V#4T5_3EfC(3M}oOwgH}$`SYVU2TvI$$+UFC~|*6-{1~J4k*XiT;u-2Yh>TY ztJk*CZn;D~%3EgSMdZaDGX#Vhft3P4Q7$tCckj|63D?(YqZ*(8v{iXyp#fTVZeMyc z9{B|4CPo{`T>E zzQ%gaKCX2D;Py_*h^XeJN8Lw37cq9_8q+>*|I;EuF0m&Os4!|UfpONI-p2wB@pHiw zUHP_HDEg{7eLv}KWT zrUa4Eh2%VTso(59Rl;rMOMtv`)se8<-%Uae`!XnYsfTn%t=xG=&%fh$Y!KU}VSI`m zTCOQofncu)8*GGtjiS5_jKs?YXD004vCBn6l7+E{WCAhhXzx8yk}wY4hjQ^2nI9Zd z{VGZfDVTJZze8;pV)o+1f12QL2M=5TDw)K%i3@)lCyYr_N4hSffCqmHB9kyiusR$7 zeA-bY`Nx=0m9Q`4y+&#oXA;puNULlVhSLkGK>$!{UI1@+81> zRgqcfc+~IfNm9I!nD_k&GlK8|p{d@0`N-`XU}YA}h=G7GVZq<|o{IPXO^(0thkpr9 zHA1RIE=r-&mT1D_&%@eZSGxo4%`=O0HyaBgt^f`b0DDpo4SUG83@YM=+ERo_V8BWv zKq;D4s+({6;yQ3nrTKxQLG!)hiF)pVB2Z=~+-Whd&ytcz?!fYK)`$eH_p|Za*&1h| z7L}nl%C4WMOQ5|X2OG!vie{cayI{LNjsG^fU}(@5eXCe0YqgwthTaBJpzX=pV(VHS zlluyPLSp%60F&v$NG0D{V{_Q%RivZUyEV}{Ye^*ZHAY8Zg9=Ojg{=sb53OxiYYgNNv>2nvoy04V*P!kfSY7-{ zL!_oc%p?C12oZ=}on*5mq|T`d044H$3Q{4(DKOEkcdhi%cGhEk2lA==1QuPeVZzGE z%;g`AeMOQc`aJh2J#@JVu)R%Ek7GE21XEvXYzlYQs@k4n+uOfzUfDGq7A==1a9})r z868`-8^h!xcHNVv0F-9Pf|;2>lrU-0Np&qICLN)IaTw*76k=84#$??t?V2!l=1X`x z2-xd}cyk*t5o=OT@ePjsOdJn(^@}^$dMHkf8Rv8#Fx|Y0X$rnS-Tc2pdv{fSaa4+d z>|FF$x#aSkk;go;U+bsD#HI!u{p~wls}TAONS5N+ITi|5{heEA>W_y}snE~3C9#h4 z_1tgFbzcSQ45#C25bGMDBrf;<71W#GMe)K2G0P`dnls3TzA^tg1Fd4$Mvj2>>B*0< z=_|R78iLmj)=1E_6K|M^gayMi@olDT@I=p z9Epw2w`CwhY~83&)jT$$9j0Oz1C@8i)YVukl!EtT=)sZq9ZwXEU7EJW-cm*JBz>Z` zFt@l=MlE=m%C+7Sui`Kp8}9(68SGha!h$2Ga7L5r(ycuv9K$E{bh5l_j9+61DXKl_ zO@p7*47pWWqYs9A8zEKr!W3=`4?dXKw99RA!K39wBi`AAcEMYstg>F{tioPREb2Hd|Pk~esYz@%si~<*b)_Y$UJn|ebn)q z?D4$sa*=Wy-}Tu-%flfnmKc?O=C^2l=ViM^LuAFyGZxLJZdsY;kvY>*2j=UW z*DoDR4G#GLQ-e3Rvp#TE6pFn|d*#YQq^UcZ(N2=esxz<^bRCR5-Q~WW?f?0ltrc>A zE8Tm!`6?wbZlQcf-}VRb`=Tg2a`k|nS1h}CmeCcrq^g(~?qg?&kqON3>|VkI>>HJM z)#@Y$jN2iUWDK5hf#PQ~BspaxEjRas_b}XD6Yuh-8eqyD9q${rC9rTaIjLN^^)J$* zKE8UIq)I}nY-C!RlQ-2A1~a<;7~}4xq8s#~tD^cmeND&RSZv+9Xoh~xu@*_u8O zeUdQr?Cz72m;G@(QK-F5v#Nc((U@P>rC`@wHd1hHLFaO-XGrcf$i2KBk7$YS=hHq( zA{y^6i{hZKJs7RTD_2ZjK$az6e;Pi_X(#wF~%!e)&QOn81lmo30 zyy%&8{}y=@#@G^z0w5j){W`3TccXOAE3Bbi4?7h|N#2y~#L^VT9w<&F#-)_JTjhL> zs=@sj2$?5eT}X!}#Lgz_@Z>m-b`zj^hr^@hP$K zZ7&xA@=Az=Ur>UFTL%~>q!!15gA3rx zjK`P+^GL+x88;RRSR&+E2Kqs_G;HKn0p2RzV%pL^z%#lM0AUOeZ$ITb`Qd)2WU z2alYB0ecRt`4jQ)IHX4L&L>0gum+Y!De3z+?kA_Bt;WnmUY?5%=dXFc_6xP9Fgm`6 zI#i?vZ2%ViJZCR2Ne9VAn2Z~X_I8AP@N%DZf@I+?DtcLfd;qMb!lz5K7Bj~T|e*l-d%30xD5?|((|3SU3&3ZX}b z7Np$mriZ@NXH%|FGvYkIQ>O_PXMDJxadSe-c#hVN|80s##b|F^ky~-X% zk0p@L5NhAWI8aKLf$mDXKXlDGmYb?2j*oHgUYR4tbV|K=6+yEz-q#4jG}o^&YH}Hc z3GrNBlXsk0I|4XNGI@qRUa;#>vYSx82t)U#3+B_8TT_ax01p`8#=EWabGy_xkKU$R zqKRw*IGOeM6_d2nw`2Slp6XtrdyeDB;8W&PF3VM(S&zuH?abxg%-88h1fmwhaKdjn zJlbcp!XNaVU%*-~v8z_Tf2?yk(VpYca2jDZ&>Nd)6P$7;7wTZ^T_LIziWEG0Z<_b{ zv7iEsn`1#}z8d@OihOBD)A6HUJdROh2eho0>hQFH)2&ATN^VmtPA zErp7!&!h0T%;h(H(7lmCzuI+}eM%3Bm}V!cJBw3^Kd0V|R%Cs^&t~gWRnh4y-uPJI zuE`+?YlBgT=>u2qh;#P~azCm8WyMlrb0c?w?riVE>zCeg{5TW(Vcy(Ngvy%Mz_pj; zDx)DEpx@orXhk=;om4_i-#b6%sL_`3uE^~d0Me_B2FseaT(*{;`OdIX=^|`Kyl-?5 z5=X}BYHHMWo;8mIS_L-x$JP~aKGIiw&vD9WnTrNtEILT8umk_Mviu#)^a7QIGQ%k9 zeoikVBm-t*g_eya7oXNuE1ES%TZt?HB2|JojTgd4G7_n+3AVi%IkoSobv7sQNRmvS zLXN|%YK@X(^n_9bH_5(6WvV0)@O;@<2MyX z87k6gz3YDwZCDpCju`PhIiDg4utTWDe^G{Foljl=M^$znL*rXo;+ueD1%<{YO&8x-^av~{aq^FZK+E0Q3hx$!-v;xtV$E^ zAn<9M-1g73fzbHycP~|Q`~t~6S|@7oZ_*2dT%moUTyVK}Mr@Q{9tg1R-{_U0t6(0l zgOQ76#@~Io%ygZ-BqJsbs(SDswBwP1m}u#maDEN8_l*Wq*Ll*h^(HO!#!2(1wd7$% z51w%`Lo%Ipo%-=LqTa3i)BwPrYLCj{)ft9?Gf9T(_3Ws)$uno28#+P@ydQK&@r0i1 z8yiN|qp@seD0mgSDtt5Ym#>cmAiL+L4rp@CWHOlQ zeq;tMe&(6~8#j0%maW+Juuvn^d!qP?)SdM0iPtzKl;RpooFI}Mvj(60G4?mj*xdIW zUFrkCnT?(;Q#z&V9;Ej{(>f?OmKymewqCeoQ1akMC8&re%b0Ur*$10>S{r|mFm;0{ z|1#IU;Pj-TwoeFeX7lY+rmz~y08Z?9OK!-Yo?s}ztjIsyZoKb=R z_!h=W4q}>U|KEJw-*Hvg3KVuyWI@5H*Mmlj)}C*y17h2AEkfQ%xb-G|1TF zq2?jiewJT1ybMT`0V0#i`XG&upK$gOq;>NRliqwG0hnn#MpGCZA>_;zM)fG^&|p?i zJ0ZBiPD)txPi3dY{s#v7+p*a=Zg{?L5O^$`{(ymWY*U9mMLs5J7uc4ZSW(4=75|MK zivFDJjmpT)MHD^VDi5~U*M}fh=?;^Mxx!Z#hZ$lH7b}AYHfG`$)x6Oz4A`wMZVx_j!`-5FqEBLOm!(Bi#Y zEj^uE%g{bx4&x$q0wB1XFN72TFqw6KJ4R%A^#yrUf4P zaDus?x2PgO^|JSv@rtm}{qb5#Maz__QL~?th+%yBT3AiiJbRtT*lHtqt4 z0^TwJesA3d=EE#|V1$y1G#X^xKQkfigJ~Mzbk>Ek=5S@++s}GfKltI)wUoID(0#Tn zi>E#13f~0Xmbi06%^{{N6vEX{w`F@LT4MP7qs+*UMNg7Fzva@ap^tCc|9oC7Ajn3c z4o4m~3|pA6lK0!b6AR*(=DJkcpB4IaXV*6R#@%|TaOg8-y}KYHnDpqA=$6>(VR4d? zG?sjL;HFSrORAFEM4F2#t-V6E$DO1+k1rv(P{bfiU<2USv~WUEh^No8VAnmpAi@Ss zOk8`__#VEU3+CW>C_c#JUft$o+*>sGa{SQhaDqK?&SCTJs$#ekBq7sAVp;bViSD@{ zHjCDs#*ljlUi7`RCBo_7%jxNG_yT7il9%*cxxNZdq1>s^;&Nwoa!};TA0prnid+br zs?l-cx1?9kTgQ1eNQGl$n!ALFG*FMJp7yO;; zLkQu#AR8-6sZ4QfA2lOKRc)^M;(^GJ5!Z`DkYEyi<6Qf#bX2Za>dfOvsa_2Q*CmzR z^uloqnv~g?0X9C2ysR@QEys4T9#Tvc@`lh9aYo3Clp+^QRXEd3C< z0NQ?fYi-#)i(5Z=r=jE9aoWfz>9o;Q>G169_X>q69}4raDy!_%+8_1Q3hl1Y(1zAQ zgYAM}9YN6eq;+GnD3{Opd!`5*b;575Qt-7Qvp7kfkTi%afR9gk#8jqkIt zx9X+9c4xxScdXk4)xCB%gFH7*TIU-B)O&(7=a^j<2}sdj2n}9Y-y(laprs|Ni8#cu zd^hc0j-O$~{qDYNE~8TLoyS_S$c_Zp=wd>W4q%2S^4wXHP5n(SDrC%@#OxN&#~4ty z2sIojQB&l05@r8^hL{(x#b!RH?Sl0L(x4#hAPUPI78l);R*R~r(k5%ii76V z?ewEp>U82i#e8%4`1GiW!ttdzWmR!;JfGIt|Uj%IFSaqa+*)KZyD#h@V1008&}Dx9eK3(x## z>>?|GY{~5gzC`geIf`-2o^e4fkioqzq)-8Gf5#1@GLA?gCrB0_iqpHbZHr!&!uQ)O zSD@Xt-B@L(ojBofiii&yr&bWo^%medc=POlqNK=efI{Km97z!#Bf)uqdR}+xHt-V) zBt=D$iURBVcZ?!`zDi7LO7bo^<}l_q`x3FpcwkaV{H0V^m8+O0glD?DkNhr7B#A=r z2f2Nj9IVb}pek=%eB!wl#nIl$ULRWrLJZvnghvaoq}7WdAx;wG^~m2!6jz`ev*AM4 z9ZVhEMW6$*kT-!VfnZsH5*pJ0m}Nf`e*rp-LMQnD;rc@?0sttMTDZwRmIaP#u6|=G z{h|%jQDIj;&ij_~DkW8L!zd8Iq>eYhWRITq)xt210+Va?;3W-LXoA;4zJxn;5HcJO zz>ZUx4f=3bj-f3(6Ex*whMj~_W}UW6IyVuUu{UP5K8xH@H6WRB;U0YL;bL zNk+>knYS>TM)J+~d3Yr=mr}wt)~S0uuW%S|V&AbtY&?*EiRK7F0X_Ub?{~2Yt%>94M6gHjDsEri$>mH1v|9Z2cX7Sa-atz z)4$;<0!!-_pP~aA15%mfS1y+?k{8{&C5}aio|(^^&SAc68JJ!z`rer#BTOn ze?RXL?>b|F#inYcW^pKQ_sh#WJQ3h8##90`!9MvfVD;C|qV*z36lUg#jaz;WBqV+M z3s*&BA4O2_UIku5aT)H0x!!@Y`obV;F1AFZEbcHGp3jL zcomo3)3zp@Z4JAhYvNN{zZOoXL6Pv0*xLiQcxLMTb+KOtM78Uy4!9r9aAX;2%83Nx zyF0lTkRU_OJPI^H|BaGsBvz$2e&-h25-uMAj{iNdnlN?>f~jTV{}o0MU73<(qe6ws z;jfz|yue{;F6eIVYi8AD^Q8?FAUYlNA3FU&pn}?Z7RR?!?zZA7CNPSxBc&|!av0!f zMk7kefzp?_h0R9sVNLXgL@%cRBV79B!d4|`F3$80m1C6X%Xp+ZplT0hELtJM;hE+P z-iFljN+#(9mo8RbP`#^`w2>)!L#idm`kAbPHoJp@I#PD93Z;eW%|7yyi{BM8 zF0ydk9XFFjfiUc76prEKWFfTx!1Q+I1|R^y)9^QjONxRCMnk?MB4vZ_+_|+9PcKiY z6KqJE(h1sRV#y;!Hl{1`%gr`$Vee2W9;d7 zog7jq1^R=_sKJFFxRI2wvYXyW}@z7;)KV z<8#{Q$+xzFmy%0_C%x|&3<^`0)<;symw|Fd3t8ut*WR1%X49MQZV5My2#9n_r?;LZCcfz&E)U->v z4~4er3i6rx_dv>p`Zyi$#L(mp9REYMvW8oqVgwnIbXbkDXcTB7c}A-jawptACPH^} ziI@3>L+a$SsQOgmQr!WXv`-ZM_5<3%kCSo-y)Wa^V%Y0P`jxbNL%kc1W_P1F;=hgG zD7NLl`vFsJP~>6DY(EphzD^?IuF6zXCPJXnBU6ne&9pqGzjQ>wQ;Em=WX*>#=7y=b zw0mOq*Rn9C_R^zDs8zApn8izNf+Nw)G(L_SQY;Au#@$U==`@~z9@nPFX@_O7-(&$^6GOaT0GP>^cm8_Ur_GCPJ199yM-OR4XNmLgQyR##w3q24 z(3Jb|xwCJ1jIVN8`Da&-oX9w24_lAhYco=|!F?$(H|*30PlA2Tdfc)bO77<-Y)bt^ zBhX-(N&4QgJX3p?aa~+jA^D!sMU}tI(wt56mXIQ@g@Obu;D*fuzHhZ*b)mTeUw5jw zouL^x!mOM_J}@U)-dgBqw|!YAT{n{qrhGbjFq*nQ5yqD#b3+(F3bCU2UR~a7~M3hxWciuG2G< z!V-dG`su8(<;Gp7ogo|IXRC8hhy~X-K2m{WP#n3OS)Ttjr0Jg+K6h(A#6^h_lFOL- zf&gFg?K?qL<6({?tp#;F?p(X&>#EI!O~m^@t#EVO8Wwn9K6JX0QzMua`*W_d3dFQA zWcn0YA$YM7wSi6;3Z(;&%k@qASiH%9s7i~xf~V#zc?Ecqc$HAHeO_;k+sallnAFd* zU2FfQ5$t!A;&;SDBlZ%Nu}W)>f2(vv*|=I7Lo^a5r>+&elqR{;>f*}SLKCR}k!Izw zmmZ7QoR?|R0dsy+38rxC{SfPRJeT_;B6#=F9T$tuEE%s~>)IzAUm(3XU%t9a1>O9? zUk3F*>@Bi^G*Pmn;S8mUiiATVVPY>=Ib`lL_8vFIc)i?ZY>r!|!)`OIHJtEKjD5hP zXeI6oN4&po*JtQMOZ=z^5$!PC^FXeH58E{kq+MSv+r);ahLL)ZtzEY`-k2MIAgZL^ zo+Hxz*(uO*dZ2uM#^0fLL;8^Lbh%h20l{Y&ACRs7W=%1}-BZ%Uip2iu8uC5P>!Chs z)rr9~|8Rom(9T%pm1a|X7b!Zx;mhpd<;>>v$RnlXF)}(TMIK2L9oL~2RRXvo z%?!4lkIF~9coD^#=Af9SY%YB}n(?PcOo}8+G&$$3Lt?{aUcSG*}aE2;5carY6vb;QrRA1>zB#$JV!p!eye6e_^ zlB3CQ&oJ}iETgncPr*2h8Lpy@R0{t7T4R1nSLhCv7Fu`ke7UQt);lFh*1M?6KD<3U z%HTqBm;!J@P;yF!$kmm(Q2N#cp|g?Wv?nzNIEl<3_4c7l?%eql_M>@Oq`{=22q43a zYU_K)H!IkV=JgR%M`3+V*BLTh$Ud3u3HTS~!rQM*nhOmQ2w4DqDHa&+Iyh7q0Ct`w zwyg+2^VR*ZwY|z8_g=p_7KcAdx(o%7#e)Fp3s@n4f#JVlelSFrsno_wn*2CM<3b_scj;Y90yPoyc2VeJ)*_4QGhul5A>_S>ahTd z{YI}kB%rKl$XSI-4^zCV2w^W2)<-P+u{cgE+cJuNFx(~_)V2wdvx@gm=${Th2?L&` zNd$W+PLjRH!BFMy?Y8zAs+QkyRh;GV2B27$&3LPiWFM~vMzCSD8iwzq5?*)_<{3nz zfP1G#9>6U(MbKS|H!KdI3!0W9@K_w#1mz1*1`4_|VKXWhHwtfDn`MLsq>C_B3KV5) zqn=O7qJlYbIMr!=e5e8Kc0g2~Bf$6%OmYSNiQ@(U!cr)dTmc1u$uS7!l<@P7m3 zSC{=cNI<&^9J>0|BmQ29Iui8Af#Zd{i2!CVN?1K1OF;*4YLBdJ|+YDx9!8lqK`G1uReHLJXR#oC1DP&gCB_qm_ zW|!(B(KEDo^N156x>zKNDA~pkIKDgbqBCde*pxmtwcK4l(j(>te>j)_>x{{ZmA33GFK}*c%p~}i#nDcO=&rk)vG;^MPZEUa8xJrjFle7W zRdSUPbg2w1ZbPCUA7zH|p=e;#oRSowC}U+xYdaAnS&g>@^-#RA8urT9v2z4I?@}BI zxWb#)$-Y1)QQ=!z{7;n-Tl2+Efs@y-?4VyJt<$8`#m-AC0FcLntcv)ThZ(Q-x7$3s z`B(Es+XE*FQmIH4 z`k2DdfFi#wEi7}<9HDIQoi* z!K@(8xKswM&(`2l#qJa65K5Y2rF@W~c=%XUyolz`@vTgAs@odUHP3wPM*MDuEQW`q z*5n^ko}67II;esSxst+k9weJGxIpX;J;i%{Z37XH@fdUjQeGkSQNS^4oB!&D7iC@3qF?9GkKE0dx13}>kowVdgD~oc87&>I90@uIP z_1+`wY#Q0c#+vc!z%N9-^6%|8)}6aL#8n=Zfi#5+LDL4i^`usQ!=JWoEClFZJ{Z2< zR#K^xDx^%|KI}_TXCvHqjW>{v@h)662|B0KjtY}^v^Q0I5dA`%Q9+7&_WV$`Iqjok zg|O;b+MSe_m@@_DVq~Whs$a+{YkXg}MSb3eGB#I5tTkfYz05i+I_L0h+0iJh&>Wk2 zTD+$8(@By_sgEY@wwXEm^U!MiifS~+Jswh_?ydMYDBG^h*&3dG`V1IOut+%$4dvo9 z9A4t(PfekDHtKoyL~0Tbdi%=QUK9va+&IQFA_zm<3`w|OjG3fvOuBdz&+~zTLzcDz zUQG;&@M=PE1(I|08`}IQtS6-;gdNG8o_@#{kC8a?l8JBxJ)P`wg*b|sZE7n(hI;*& zMRVeg*UlS*CERNS@!Rh+L>2@%-vj1Pjr!y_AXS3-iSZ5+=tU3hh1EMdEM#up=Q0w_ zSV)83?eT_V#Q{^VY}IvIF;H>pmeOXZRag^KdygMoWcWL!m$d2{?<(4vg2{%*Nk~{t zK!4Sh4Tl_o{ts{qLvYDQ!VwAjHGYMggGX@NL2n@R3ku-wty=&9qB{UY2h_6}lJos9 zQ1cgrTl9cmB@eYIZb=o+Xu*QW^&ZB|`W7m{n)K%M3W>9>P5ChPRDXzty1O}`eLsLg zk0v=3>L9)HT~BhA2(az?zs2WWT`7?;8~xm<0YR1AujZ0xJhI0N~0^M9*p!3PE#v zunbqE11h2WM`7!Yz%Gj1>1tNG;R!$|4^F-QDihWUKB1$kZxI2J- zAFRhvP?Eo)nm@(<*R%i25$saxTdjRM5KO28!5i?eA%0lLa)S4mwMC;)OU4L+L;0j_&g2dK7#V$^_Q{DnyVTW|$& z1D~3-xTes+a(+!hNpOt=k`D*?Z?@w%W(M=9*D`%}iG!HY-_}FBmMtD(1h_n!&O#b& z6Be2#=x^(`>`|^QCqt7k_faRL#27G(>$krWMJjvS(VA)!Vjjd<6W@Cg0>v7^${e^7 zoIsTxRKOeBOCs8WAh?PAtqep2ajnXS8+EnU5B|N1bol-oTY%O4Z#YW+GjIptt=Yz3 z3cyFmvH_WsFUPXgo;UHD9-}bVKONE@5v_U%Ff`PKa-neZ-q2h2naRC}8;pfP@EFCQ z7SCW`CkPDgqKp|AQ?;NR(wK&hiu~b*3zCv4r|R+`ilX>N@Y+#sw{=y9)7s4oNYvRL z(~{MYNEB|Ti0=#-dK?j-3jo~3QKP6RP}Hlqd#bT*fY=E|kPGz$+b;|xXKTxK3k72o z(04#xc0pYR|F1YHvMvHbHbMFZvgZ6%y`w(|lQJ^eUiC+PUgz*?O}tntQ}G@mPiFNV z^ow6`MlvAJxhJR00a0-!zwYpo9A+m`#^6>4l#@wzTz8Jvu3{|B73;$N+eA>vJibm! zB&BT&nh#gSbA`396REh2_AwYZ%7%|*LXfqSpl6iN{0EA}(CvNIC0__=JL zq9(NEdq^21s2>zm8GJ1jDBRR^6odJ~)o5t>FcS@p1_V#nEI{aVDwpvi;-An7WKQ}f zJ+}f4UH_gAdRVVsZEIxBTi-f}|3y)cAT=rGKtL2WN!A1&>F_RTmsdAHdh78HScl+D z(|u3``9k`at2x5ihB^{q8@Acj5*@a#hfFs@8tM*U=WiFRm+)vLpVEHFy?c(G=U1lI zaBP%Ijtyx)iHD#waJCR}(5K+aQ{UP%4v+F0JrcTYiPS6h+M3<3NHpI_^?zp*ej%_s zY>uxRaeSmj^{mb+`;2mT6n7$EKsN+4kyO(*y2JjnXVa9I|FZ;Qhd{O@YC%Jt7Ll)X zquuI1CT$w-K7Ij-HycpDn_@Ln+*t|N7)*cRVeJ!i*=ac7#%{RjEMCja`oOyP2J7OO zW5#lQ{ZHW8;Cd*IiviO}rh89u0BJ@SVn2T^gtJFza7E!>XU9M_j$Dn59Ss3hDMSLT zr|rgNN=KoPhph^Fr5>_UkYb-JWMUHX@)qxQt!&{IOWrGKBS{q}S$?5&M3_+)-5Ur}u3)BH+|AHHk?>1J%H#n%us8+RI|CXZ;on zBapfz2l1o$wxrk5-l7a9FJZeCr&L(RVru#9$8HNxpWJ!;Eq!WaIN6{vxDN8MrUEOi}i89J5&@pD?6KlZkXh3rDED8s5_jHsyNN;y#BzYkjqOi z6rc0NqnbA>Khe{15UqV=J}IM4*t2h~9C3@GPgt8eenal2K37G^8 z^@^E@hudf6R{&5}F6Z)>kMJs^`?|!663s)V+TKyxg$LOm^2tS-!Em**aW8CByRJ=$ zRPaHSBV<0YC9(~86U@;a^@NTR^&~{EaU9+DM^&`vbo=TC^TOlUSNAo7vP4^#<9wz_ zuV=1XKhSOzeaUqvIEvCd=b3yQhC4bX6A}8`W$3eWqLG2!u3Pp!8`eJ3L59K|Z<^#^ zAn79etxV5K$sxPfAK*N`XO6@C6~Y>edmk33j{eSJuU`KiB#2Nh=06Yu^t}sY8=07nA=-Bw3>1`(sN3n__ak&fONfvOf@5Ve9++OPm zgApxL9;j5J%kwXQmD+mKjC)`nXTuRRX$^i0A>qbKD(9jcx zwRgAu$~@gx5EP{E@D-&VzFW(_=L(&$==~nn9l+MRVf8>Va>v~jeTPK~5V6&vUBPG@ zW>E}7JpvOI>`+O47;hk-nQr6W)1w61;P)u`UrGREHfX%xJYULC;+KnO6!s()2n2rM z(CfYopi0E#RH33h@DIFRTcj&By=^1iQ&T7x!;JcIFXK3%q&K;Xv9Kr4^cXRZB5Rd6 zQG0cZ2%W>W2c2puasz|=_)v;EH+oykB@U``y2nDK{33#qjPH&*izUJsKLTHebd@>r z2%7^Bv}4c+xpYAJ-%Qo7Y@*S@vU^w>ZFBwS(=!SSzh0oU-SgXL{q}8)*stku3DK;R zv5G9-HZnFPsUE)gRr8>q3X{W`MLbcBG>+6bhYifYkLUy4r>J(wSp6AOeZ6$j=CIsi zh&_7L?4&CI*B?BLnjBDsZam~@DkExL^a!799q*_2Ob%Uw2;jBuysNbaIcpO{=(p5u zG6s+!-I_z%5caXYNov}Polh45QM+7gSr|!NP0~P-J5=bE1b}%7yp10wwl?S9hQ4Qbl6BEH;_!qSTe>d2 z{Z3ORxDw=>dG(X)Is_Mf`mc$;Wk=o=)?Q3Qx50TI<-ke&MWQnkru~(V8UsFVz_UIL zxQ!;LTprkc&bA$dRFO{dU)wYu{_&cGq=xez#BDB^yIe7)tOQeJel^gIkK`ynp2$c0 zW?1z^AWd0NY~a1APpbCOI^~g_H-ElUAK09AR=9R|uIo{!#Q=x86RVYGi>YP{DQ61y zv!fE&59>Bg3pF5DCFZ%X>;idSe4-B*uH3!*k8)2sNEf3$Z*FWNC4CMDp1IYY_`eZqm^&9f)l6B?Iq{-!{ol>|d$e#kgZ&SN{t|IIF;^b+V^y@`-9ONrz zo1!3EFQ<-z(XOWGkIUcI)vt3Uw49qhIcB5&?s8bb zMU3g5kPs20PWE1%MpmNl1J8si?ti<*(V&~L6IYctWNl=lYggAN)ZkfO`+PNIOu`Fx z1A&o3e9y3(x%TI_e0_Bp_;C)%WfN}yj)K2h++n_x_5KO$iL6Pm|^=4f; zVvl6MB=VCnep?@v$iBit(PWq6&g0;Bo(o<_nPT}Bn1p)BL|dAr9&BUsOw(8OmN}n- zZc1h24o8yLCY@^A@U>J^=gMveTyFG#qU_(ANOR}GiMTOO?G#Ubywfqg^(DH}rI_E8 zr|E(0NR_xM$LB3$qT3au^eAqG>`s1vQY4gm^0{t}J~8*9!P#2+eetmu(H0P;}bhjFwJ3n|D3>30~;DP+RvZCX`Id6znuSw=`inIY{1tSU>uMmNs- zP0}>UqSQMAxS(d;(`uSV z=@D2`5=+{*14W6Ms|tzSlG%@g_qQ9}2s>^!l?V_N&*CMapw6u}x5OG4`>?o&*Shnw z(K7I>XS7UKT!@}Ro5IY&73c1fIVj>Q?~%gw8YIRPRP?+zuI&;Vo<8&m^NWe$yDg+Y zKlgEA2HhP<4NV~Djay=;k~<|T;xCg3_EogxAR@-b_}0lpfv;JJXPEZ^lP_{Nwlvtl zIruK-g5DqsaBc?xparao!M_d4uj1A*%F5nNqTetI&P3WZ=Gyk}nPwoMrRd;^$L4S- z2@wyph!Nu5lDalMiK9sAPh?0`x8@tur8tfieS?gZBiwL$f(|z`y3Wd(Y zgK$Hk+VXO-`7*ywn)LcAfG!S~QN1y_F8+=rR4q>c_ax?m0tHZQgKbS*UI;Dykrlmx z0p=d?U9J$JBD2_a0X^(t|0hXpeir|pgqksMmdq0a_h&7CgLcieXx2WP}jln5i# zowlrgs^M=uN>wSKy^SB;8*u9*Tf6gT*eALsCzfY>ndz|!Lla@W(Mpx`Jl}nXc`?@t zUu|1Hc%-gko38KqS#bSpiah;X@ih~pYqi%;?oz97>uV`&+?)=RxnM3%Z_nCAya^F= zUCWL5ne~QU%nP?|<<%DwtNuF4960hdudJp9$^mYHYTJS!2d{FxbPM$z{U_|34hC37(3R3=n406^Y}eo zGP$NNev%>wo@&Wd+aKFJ#E4kf5XmyJKavikI&3s(j~IIuvIc*6{EW(heUzL7D`u=WG$(GrX8!I%cts;EvN9Op~6mkr-B}Io%CMoECpV%gaUa z_I9zaevLFQpS=**Ps_=8A~jmfH6Uc+@L+EAP+*(!`Srg zh$%l%(Q>iyzS$!nu%}s#OLUnwv(R`7as?Ad!c8hQ6I-4(-sK{01~#_$ILd)8VQ{rs|UA0>!orA#r>L$BSfrdDM*n#4;3**Xr~NdB00P%ZA=mU1+}GLM#cq?&^=9-E>s3IGxTHRb^vg^ zdcfq}6N`9Py4n)_+%(|+JtWXd0u2**Qr)gnLUIS*<$5ip6D2vUmf-#{zLscA;Hjd- zE{X=Z1fg|~XQH~^T2x*FP2G5+fJadNNp@Ugu5tLPuB3(_}$TSjuA z3im)2enX-^b-mIUC!-Phhw4|m|MsJI27uwXWGF1N6Z%XGkb{7MbnD zf)K{})#D)zxX7wdY@XIo064;2q&W~tDu#V#MgX{uU}ZdqWHbI9RQ!z-4y6PMKwOnT zI*6Sq1h({14ah?nIvEfO1;n;*Bcrr|y6|~0k^?5F|5OHLZNo@_jjAHZ*y0 zA*2##dMu}JQP@n(;Rh+**;V_ijZ};5x{WtmK7%^igP}TLf;)b$`MizDd-v;zJ1JfO z`jQX|oFi}8jk50E0|2-i0>ID&r4VHVh1~#!{TKZBJIRVX5g>pRJU)B%VsOleoeHH0 zp{j{xt@D1o#_>Vc;Shd*r;6m;b=Qt9s;Cu&EWYx}I6$euAzd5S99k$)nLYI@_<0c1 zt?yZ8hQMA?>h^cW_*Mu96RcCZfVs+|4n=Qdpd7NPf6)^;%^b$_y`Nem3{`(UL(81w zd#7RmGY2%x1s&0?xLS^#s&a{a1te&nzm)l@R8oou>&b z4C~@tcQM(;Nnq$d1&N)|Iv_iohI`Gu9b)#kFsaYpkN6R3Wgj#KdrKpSv@p9`jY4Yy zhE}t#w(R3$J&fzMe`Rj`71cnkZjsKRKnJMV!0sS7GthZ*+s7)1Jru;3U%tM~ooZNW zlAzA48hq;4=5#^(8r5CPu~1e`bSDasL6R)o3?_NBM{^k#hq~#Q3#>%Y>RrX>i{=9S z)tsx_;MYi(>_tiX_^z>VI{=)nqX;qX_*^wMEhLD|+~v}l{(H~;(Shqc{Ng1g_yPX; z6%kdnSQU?h``|R#)j?$cALmHAxlcOoi_Tr=ph*u*j~#{3FRbWV`5(ysq)2Sn=?6ma zn?~tf#ORyWUpqe+0hbo!m8INk__TkQ@8#)}`}_HK@AA>}v4@oZFnMqZ&!*s&-8_pP zU%K6RY}9jUn;IElL?dF?{0&;_f5zhXdJJChPWw2S2x$A#9>E#Dzi|-edfO*1x8^xP zAfjsbC0dG({R(~@WfwG!E3d)Wxax+N@SXU+M-FMB&MkbsvYbIo#sVyXEiV;1cz&wX zR0~-uO!~EXmfYRN!I<|OEkAwz)uZ&MDi3GFf_43OzfZhtmeGXrt!F{l#!BCu>`C8h zbNsj)XHP90b#G-mSz)UVsjdt{Bfq>+`FYQ zVe>v=BlgG>l|p!-XSa6@Jr&FfZKhn{KM>)|o|c^GsmmdNn6j1T(zlf0<|ZZjZSm?x z-l0tKTX^!mkY9{1+I_7vOGEkRjW=r4Xw{9)Xb*MEC*Qm~B%o8aj=(CiCnfrFkMKK} zbFS0zd$vxJvY~3SVp^=b?si6m@26@odFq6b+Yf#`6+fNy{2spcK_Y3)-?sE?bMN$e z5ck_C98F3O)3H5{)AiRzW-$!aPiDK!y$Lv8H)i&w$1&Z>o-e($DvDyCKgX6rUK;*$LIMN`?Z*YOZ=mkJn=?E#CMERgwRE`@LAIi^}_NYk#oZ*IjZ;r zd|SeP+?TDqAdYL6%jW#$`1rr&#fj0i>7E5h4HdEjd|A{P!F@!65(m6`jWYGnU0&q|GilMrJdHFsS(5jyb(`g!a8{?_ zrcQQNrSP`w`*eW(G_$g2?4euLu#U8%^>QN4$67IOMLr!YvE@{V5m=L9=0W{sk)eKYX*%A$K-hJ}g>?e`nh1 ziYLerQ)IBKmhOL?P~KhrY>{w^xod>>4AH?#z0?``H5+y>cz>$(prF4mJ%u89VG>2M zi9o{xyUXv8Y{B2S5jfDjbrRM)#xukvkk_p>P#1F<=I0h=hPI%-qPKqN>y1JEYo z4sQ6|$ga2NQ9*J=UxSS2j6k70P3-0iWJ>l8^wBuEjR2NGVZ#8Y+NJpKpfG`695CzE=`a1^t zEddtCACCfXCoFz#Vn(2@{zH08ul_-;&{Hu)obgZq)X5{(LcWGcM7L~JU0Z??DnJ=g zguUg3-=1eTT~Uh!O0ogSQvhH`fcHVVOsjx0g&Ipd@GsK4+*^m zO49>M^B2egMfn>dvw!eI>*~>XHIe)Dxqt^_kyZxjxLO=ghXII$gpnjB3YF)gx1cem zv$g{tZY+>PS}Mo*q>AoahG;#HbB2bU3w3q6b?bqv6VZp@f1<6T%{yM+h;nHx#3)j5 zrreLgL%VkE^`mftp1tBhIsk6s7*l~SfUOTGJ2T4T2*aAy10fG0(NhWYVnFHy6i^k= z&h@4m9R)EI&`cge)T>y%Csnla*#;oKV24ToD)Jk_fLi>E63lkc zn~CK^ciDMo(j@oEi&VXv8hDbO`8(NlzeobX;H_*S=l_K1{!2<*MYJoL2FI3xBqDYy zxzKhgxW=M^tklm>1MZbKdwc>ITW(-HdkxJLrn^NX{2vF2Hpb6_@s%L;a6_#3wKsIQ z2de01JGqW68f$`DFF$+75mKk>>7&!ryUp620!&X2-@v1FNk%c52OBZe#Zf>W=;Jb+ z27vchZBK0zVEy$OfZG6OlBfRb7H}60?dlx(iwAe09dhZy|2Oz%nKiPDr^RfdXMeaC zT+!X>&{vZB39Z%+X&h0GKc^NPvYj6M;;LL2TduwC2Gn5f&As+HyPGN9@g+TB50d)AG?X}jzV|$25u)Qh`afa?&vcjgU>{Li9)~RcfrhTa zhcuijxEj4sJX#;Rddv8DEo`x;;vW-HfhMs-hipw}Bb9jpb2hBFPSDjMtCT7{>B}EU zKp?IS>(HYF2CTi0{%FafF6@coXj>yF%FnG|Q#QvuRB}i@BFR+S;cs#tem6H`=Xuf7 zcw_tnlm41gCtV-)@x9?_hx{eAZY(Uxt<&=F6Z2{}FB<31IEzF565$`wtS=6w4vPcSQ}9zmi87Rqi`o=-+*}qdn~l`73s6LVPcuS zZ4pfR`5R9~_WJvyq(*npek72P!KiZVl-;G7Ek5Q2a&dPdg%W>WzA7K!}ODTL)x@UW3jo4kq~H#j%ozYqfV@-R+OX*DNWY)uUp+ zzSCUm@$jH2s5gAz*fi(2!xkYZ0jL*OvM4 zZS|0uw%=0G5?>%jKQ~15wE%mI(?*;Gy4XXGT`NaOhjj1LzW2D9-(Tme$}in`<*1FW z^^_p|<{&1oLxoRGzuf6d9+Oq59iE<>%~PrE!;cxN7WXcs%=kMkhQ5w?vc52Ab9aK5 zoGRQHoM@!e9lpp*nBRYa6K3gW_^gqDV!lz!o?Utw?7n8?vZe6;i(fB0Mh1bm6kZ1~ zNgjKXsuiAjIqTypTamk;t?by;G@`DnA8N_J=N?s(5bG~(X?3=+e?w>P6T$PO*8(d01=)Wji{9qGo)h^H2*RnRb-}b;*w;#eR2*OS*V&%3{tOp8eF)^CpQXA_urX zVbAiB5gJfa0X3l#OM3hKbr5<_cargn0bS|y6J&U0OynIu=o_+%%d(o2I)%@RQg|~Z zVQ3pl?WlC1$+@9F$5g2! zC(7(N$gox_N-EBC8Mj1WBKJn8>+8mG3pcjqlJY8)B^dAI@3Ao{y&v#MhzB`J|I_d~ z$tSHsDC=Dr4;=>hy2Rmo*oCOOeRRSWMJAZ_$%1hq?<@@C0^(f(7yhUKFk#lOIGgK@ z03e6N6=4BABSIagB<^qo08oCf_U)l_o5fn}F zrvjnjasW^@!O;IjH~{+$YTyQHu>B8=_{-*8Y58wI?DwG7Ffb&hFzM=?IQ<`_%iv|a z3;(#9`9U1&kAvXE5hPw0z&ZgRnF`5P_&XB&^$Z;Bl{tYwOBkkyupFxx^qrq$uFAb|z_rhexDg#0eo_6Hy2o}~sJsS~=p2;U&GsWbVC zJU;>etv1DR8bmD^J6kEy1_e|T!`=L#Py&o@U7+moshY@M3<{7~1bZhEP`1Co6)4zm zl<4jnv?j5~+4~bx40)cncTfJ&JQ2a|RHje7KTU~`C{yOl4gdk7@Tv8;*Y%%RpT)&D zNeC5P_bWB)BbV9>9-RN?0HkLcVsnoh3LQLgbfkY+eQJkf7fL8^cW@+24$iH^rZyTJ z&ybuln5bTOmzVPVi2#L)M^uls^O!4O+9LTbANKqwy@9&~FXY3plFwd6vw4jImq4i^ zI5WxN3MWm-qwLVh@3LZD#3g=&Tm4GrRd$3vKf3jkF2TJw2c2nONEYI+8BG7P`p}(P> z?eN|3ktkggJGm59`gGl@mq^J_5i$@fFvB~IU8;^A!1D@06UQkZCK00Qr}=p3@IH0& zNC%Tc+YzHVxqhPNx}t@1Jf^^tX(-!jDMNw`!X33Oj(3+hmSY{uf)HUH*z&mryHQz7 zM)e{wKh-FlhqlXmkdj0Bggpd?IZP$>LCY}R6zU4L)BAGiivIzt9W$i@FruovS1nrE zo3jeN)vJBxE67R3p9AAq0^NAOJ_c&>s{lF zwQG>Dw5K@mwHDr|#ps`C`ncdfP7vNL`cu;d#Z>$Fgl$7Yk=)9&;87#m zWkY|5-ZaVh{fs_Ip=~eG#{FJ-2f)fBdgR}Iz$IU%wnDzG{yWqWZx63~9j zR5@l4(BbD%Di{eLSi0r$CHb>$2)Vy- z@)w!{i3UpRMG9J8mJ9i1?^&m0agfv{$aQ=86wPEwz|4mT>RAQp&7k#VrBTjYPmM9< z!h2+fDJN*F5UdQ}j7#9Ccl?>+z0+x&{mLKXJcy?igDnkZ=&C~cvMVa2$>LbW$Rv>8 zW!ogBl>Gq%tQm#yQE#c7RQn*zP^XM~Jjw(eg`QA4G#^%2$&tYq;cRzLnu7XEi_6 zw^G`~6mcVQF=j7eUUctMq)yE8GgV5ZMn~_o;S%+Wtj8n$l}n?T=T)BGC7yBdPO36Y z`r~FFwB7wqf^LjzJcDPk`|g+7drbPb-)q9*z&rTi5G$vVbcr$4GFVc;e5~t(_22^d z_Ih$B!;LS5?C}(t1?tY$t@a{jNmI#-S7g~R@9zwyygX>`&7HhUctlmwm0j8UU5<5e zla|C)y7FEWGQ-_+9UY5lf+Q;Dx1KL>i7r6~D5vPUh5HV$aT*V}0do|GaO?+Uq@N87URA5>E1VQPW4@ZHKmTbbO4Y^kqUK zNk4U0jn1P|8q@jM^!@{JeGbk9uZNBD&(j=_l#Iy_6Y1tK6iuUvpN`Vd(Z^WI$A7hH zoPZ>;F;HkmJp8FvssJCE^kynLPrKU{-JbfUT^9f>TN%APr;V(#wr(?F(^f5MCq+XT zMS^%E2sF0|7vkSMIyf<)QxbfV@>)J;-EmEG#>%$e!2LtR(L+Tu#)6?~;UEQ1rfsEN zZ)=)s0gA@w?UMHsEqN$S9NBN)_6T0sUw&Yio5nuGl=1y@$?*8S6n^p{*E}rL+;Qwq z9o0jdg(nQWIsso6YlZG?;C&%0O+GnM$-`GPyI9Tf{a% zpsCQO14?_u?Q(r|vEf@benv^5-$?xT9a%keX+4ZzGZbi%+I^Fs>3`qR&+d;p)0=sv zc>BP3o->%@`Jw!~CUI6SODsdDQ7R3}nT|R4eSWxbxiudZk#G4CAbV<_4Fr~}xn;h|yvjoj#4MLP zF5jW>F>Dt!hl-GFo&N#i{zVL6I3^mjWq|9nGf*9{BB8wS7Tx&}|6L}v0Ga@erPAPx zF1H2yUC;0v%zj|v?rtR(CVM$HtJ_4ej{=XUyQ~g6m6rZSjjpSsXu=?tcKx-Pr=|I% zix0Zc+lb)Y*nH-iGiC@M=`j9RqjBUL+o~cDnxdJGo!eZf=A!>ZGk%k_J)HtMQg90|N1|o?ty7+PHPjFt#ksc)F@q%)NyYgc z%>ZB30h9Qf@reEDWf+m0v;`~xiQC9yCoq0hjG>015CG3w0F8IC zt%w6JVR|9HI2WzAnLle4=Tm*@84kILiXS{EExG*=-|8koj;tHRtfYpx z7n?Z5YOEbtZ7{2t9i7>Gx4fDYRS+`wLBBWjxcF@a{mYH>^`wKD@+WaZ!xwx;(_B@f zw*-6yB#z8653&+k79AN0X(4&myUcrN?@w(*q>1B% zWsy|IZ@9mOFjQwGJE5vEu5&{!VrA==)@N~ae@-EB3yJ)sg&825e+)1!fEc<1th#@| zcI*v|sy~p!ZB-PQ^^B1=`^Uac?ep8Dalm)UJ#aRU83Dz!%Lak0->ac7)g(TG^2bFm3?vtuU}dfnoBV8XW-K>sis;#OZ0vP{R1G2bb-6$iy^ z$ACf$V?n@DKqa0+vUUG45cmW6fbnvub|`+6BiNt+#zJ+?e{RWk=VC{aA>@q5P_+2B z@(qiFMuC9Ot0i3|$}*)2J5@7bL?d73IRH$H5CBk^hG7r5x+0U=z}q3!2%>f{#sFba zf~y6XlK~Jxbe%8&wrMa9*n=m4ZcwCu;{PkEdMKJ6sTdL(VImSSY6|+-b#7d3-HP`iUaW0>Xw?ERGbb!)M+uUA)Y}1z<&?Z1 z3wKJU(gH02phE`AgNu@wzzFiEgbU)B#!%H@+4-Lfs+$OCO+l=^!2PfZG&kY7`Sd4WVD0q1thw8@^840>fDBY?;_H z?s^p{IiAD~Sq;=GTDmC{9`vr7nHBR88JeozClh=u2pQAOvgt_7>(42rRA?Z1{lC@- zVWy)d^I|dS^oZT^9R3Ok;#o2@J$YRRF)PZ=JA3uR{d#Fx*v$COK3@hZEJPa>T*=~v0{$Ok?;K`Hv+N76 zwr$&(wr$(CZBDN?raf(&)6=$XbGm2RwvDgf*=O%_p7Y%M-0z=NS(TMlnOV6aA|rkg z!5ql$1t|L5o`4z)XQ)&DFUa9%EU%rv4rx6u3A9pwR}Lo{GF8%5Ezt}UcIPI=_)z6) zyNC&JGa~-K))lB0H8}l^ktoep|CiWrpITVl9%Q6;s1F?_&^%uluSo!S%3XXu3QUDZ z54>%e7*!G~v&lkY_(X`vHu;T`YgU&%wCrz5IJxPbV=9$7wX^ca?3SWACkzco%rlr{ z@CY78bbW-0Cy+gnBtb%^ZP%7}&ipc_XQp~ODWxw>->E^CW7b+yxd(?-kHhRd5lDOb z06|$n?i7$QzkWE%YgFU3AG*Sz`I(RmweVNeQ#L&75I*+Z78a<-sB1OOeAXm_bu~XPj0wDI^+3YB=kFR-W*~`t zMniP+ern;Jv(aCnclRoa4s&TYy4lRnmMf^YopK)BW*i>vY53iC9+b}Kw{pyMF zhmS*3L*GB|vR~N1vDi6*fXnLY!BVv9r0f`P4i#)6>ktQ%eR-%aUiudn`Xh%6@h7t?5zf(@_(yN~|ML5)ze%-3$_SQ1 znlCLx$4dG`lORJwrs~z#`r_4f%)L8sV@b35B`RLS1OlVIc*ikFNA-|i3T6r5!SV4X zjv^IijY~w|8Q3jqdwIYyLx7-7#l9cW(#m)V_CwgY;}9qI$hypxI&LKgVoZt7(U=|V zQSO2&78CP<2Mz{9R{+mBV@_lrI`M3eQpM_*k>7=06gk7~!Iy8Zwsv4_!44h-ACPOJ zvsYPcW>p=LDvrN2UwbPwE9G?XnR0@jw;4wwjy2&SE^weKHON;{VDdT6&VlK+9DhgAJevC6ErKT>>ju04g=D z52}pHIQHW50)>!V|g?(6l zqeaeJ-dWs6HyTv`%7z1xVo2T;m^=IuA;yE5r1X4C9F$xYX2gX0rGiO#KhW`BL=F8H z7yO{du_poC!7n%`p`@N9ut$>LT5O~y;R`bWelaINeYyowB})0CCkgW7{HZo z$bXC3(El88Ig|kWKh2vl{GbyRzG|||^%FS(xa&cp|9$&EjXvM@584sK=`##t{^wh( zGUh%5EBt*NI?87!#z1n+;s4!<|LvXjY4seF+~|Q?b~gL975SuoxC!d%^|j-CI?8N^ z@1DP>Ep@yORI2nYQ(@!#94TbV*kUzR?&6Y1FCZ-SzIMX;4GuYdlyVaSJ?nr9uCd z+K|gK0)o->2M#?Ig`qTm`{VtM&}A-H6DYI2a$ZILoXF|c#YLpm+dAoz70F}>nILaZ zT>pWwt6|E?Or#yWk0zL!4Mg048YG#a!_1jA^&h2>^~nCyR=poz=;!qM>;xAI{ceb` zWh>Vb)3JBOlggL#$k3^1i@M7EVDYUs{!?1d=k+k_9v7P~_ZMsh8KE_;v?Sc=-PF+u zGF^>9I|*cjR{6}(F~ReI83?3r)t`p%%xc4kN0$_aV1w#39G*f@Qe!!lcVl!47vlyJ zOC9r^s*u?!;Wt~?s&Ztd@Xd!nDH)btI$$8pyD_3W`~r)f9qU>0@+1X;2)Lrft!J+` zI6c{&fLlne^p???(p+5mxm2ZH9^Xbxrl+@)L3pUoG0<8Ksa3sWpU#~k+53Qe#PNbP zWmr{s0Lc}9W6TaKj?G-%vNUw@+AkTN(VU}_{3rcB#K)S`mh!@<1ZjJaCX zpswr*o~rK1j?|FB{FpAj1dMofm)ig$+^rOX#xO2=M7I%oxRkY_-$dEnf3eC{3#|*n zWXGn$?8Z#7F@d>Hw^q4maPGu&Nn!H!`8)%SeJe}_mvH7rq*IdaL#-LD^ISbaClnSw zVc&p%@=ge8*xyL&;9}(3N?`~Stq-VyVt0y#Z?NYAmV)1IWt^&wEW`nY|?c0!W_#5<;0K@x*(DFMZK8p^{0QMnmL5 z*6bT{CU{GjuY%n*luk4jloEQo#c5eQ{gWkK`w$h~$)0;Onwgua?quTqs0qJPzp*Ws z`FK_nrCN*Wy;6@tQ`^7J-4O4?U!gfK?Q0sy`C?7zMxoolJ8#zF`T2(c84}L1|MCAY z+}S$%a94Ly{+4$(_uMIc(0uvy6^+hhk}9@(03Z2g$sMWW<~Zq7I^ni#~mO0Hl)}^lVafb3+M%_Aca@BzbuM@_L>I?1(Ew!Q?A6My<#{X=O7A^@&DfCTEWJx=HlUtfj|6BED;pvG_r0AL0O z;C)i{f8amvcK^0>{YxnLFH4=U1uHS=mE^^D8DBdf;|E@E=2(*fEHIzTtp*hY7|A5v z^^+#ri+Jj73Pq9_NcqFA%!M}(Y@t~Q0YtxVl+Dahmow;9t`a`y|^)Kf2pI=Bt zA<(9lzYOSqSA!ms82qi^00KTE$^7r?|I-y3lFxU3TI}2>{>{7p(+Y0$-wothPDASc zee$=y&|2v4Ih^tdc;x^XhFxN~kdZ`kEx5hO=0-cgJk0@b7?f_`Hm%CZF-0mir`wo5 zX7)J1DKwWFpwvR*32Qg-PkVyPp3h`10C+D8uwxvOFkxo@Az)&WM{o}D$Y(X^ryl?a z^=IGyhj8;>7P}ZD3>C6a5MPlHxMir!cnO-2BuI{19a%}LRVLVxOh-4DL>F*qDNW(J zIY7>*c8d5>bS`q%g}^#I!H=k@>ivD~PZO59H5rGkN9@q6Ytg zmYwfL-05xoc8LqjV{nkwEV(_Hf%eB#2d1(FhG?g4B`G?@KO?`5sO?Z@HrQ{&M@er` z5v;!*)qgeNFu^u)FaW=grbdhPI2iH4({9Z$&Xfy#ISm50ld^*80k7Uzw4^*h{5e-3Uq0uG0VK!cKQh?=)sE+)10vkfnhv-UzHl9@ zLp3cL_9d-Ej=0`^?eEOMiI>V;^*dUVXapAPoTN5@mCr%i00juHCkWC2Z`bDpuMfk0 zWz286|A|yn*f8mwbS|%Kbckm=Os^|M!aN%XaDxv@w!vLR2Tq|HNg+Rx{$2#39V{J+ zl@x(-ESJfM|1S9>p)0Aif3;h|0t){GBKbOtxqlXZZJdu-0KV7ni~C#K3OY41nGZ-R zVJ@JetFTFDZtbNE${~s=Jp58vnLrgURPbs91Bx`&0K^tLPx$c1{Q1_bEvwU1S#C$-civ57Q0Y|5MC+7tZh~`9EqF?)cWX zsF?n)aiW}0{KK~Cl)O-uuCmQ*ZJeKkJguwIU>B2~H)A1u@C%c-5>LNi<%+0{pKgVRoA2%iG-@^bn z#Srggi7n+N|f^{4`{qGp-SiQ;4y~^ zK2BaoLF3C|@}Uz>MfZ7FT}z-pB2 z_0w;B=YwwlDo(&}^!+a75M@4xsQJ@WNOZKU*7%VA#*TkLr01uhH=d7!iy*Zdh1K{D z_UvOt!7=f!!RK80zx*Px9S8D;*D3OH&HGa9Pr>q|?+KJ@Nvtl13@SofP}8@r<@J z4x{}#ICa!#u*5*mVFF&V{@=Dp0TZ*|5?utLhisy^M1_`w|J+uQTIN^y8iGE(-L0+b z+0uAPR_*%cK$sd`Gh(aY5h`#-?V@2@CWvM~fr+5BSjIDR6%)!8-F^R4Zl3D44;Ai+ z+x2t@^ntM1-)z~Rs3raC@QAPJUH;X-E3wMkwz96(n{kzE{zhH^lAz4@=I1iBS<6n$ zMW{B$`rhN!t7=&N1ZrE6*bK;mEJz=&8BH1vH;DTh`?X=OmHv z9+0lULCnRPA&&#sv1-^=j5HcITcbrofl#~`MVxUebW;`6&{rincM6B_-LgiuCu+de zE;;u|F(DbP{wK-E6VCZ+_iwcatT5>it(p)WuR=v7M4C+Hku!}LpvoS4LPH?lbO||m zR6KoBvyoPR-4Ys2LAA&aPRoFXhl@7WRNe7Q&2MD2k#6A$j#UYBe+Y54QD&I-5S-Wj zFn(?##!aq74tpc=B>LiMM*KmCeE=Fx19QScSQ(?QDPrMRoSWxr2?^OGwgT4jAGxlEPA6#=a z;}b9xppkx6zlN6V*U}mQ^#_|9xz!M-(3pLdXq0O$l}|C?&cdq@!CUZ7)9j%$hohrO z=#`jzOCLWisO^4Z?wU7)C6;41#C67RRMIi&;&BJvA%F`S0Du}rCdvi( zir8Tt1Ij=3pMYkNoKJsW((b?1=syY%mH!b?=LSf^1@B2^s1YJWJkjd`4d7pGid(j# zhXn<}U?hH81h|zfRe-?(ks}`9GpFDA?WVM1*8x*#5g_#FV2QQllwVt*>TU*e zk!%$JSSvP0P^dM+9nW0b76qUwC@kH?RlQbbB-|v#oxx=QfcoFQfPvCbgDm`0gj)ew zMxFVmL<^*#j^LmN0zf{!B>%zNghl@k$>Lvlo0#xOkOFEX*CXOWK(hps{IyhSJnY3# zoDmFUs1Sw}MrBSOTbwU)>4u<2bkvhu2ihcm8!s9L5S>5s9V;-r2SRZgXi8(o(k9g$ zhl@6K88Zk-laa}_f@dKXYBuO-d`C=_5k!2pIGqiZTc8F7>lS#As*Cb@>OaayZaBtu zjK}^4rh_?!t;!3AAcKrYGGxFnIr|1C+3F(UPXcFijYKB znw|kiJJTrd;sQFrgiP;QXd;UsOsZ2VKx<*@^fiTPw82P}L zK>IMT{k0}ozG6()A)Vbiu@ zUO)HUMGzzco`!)O{IxeUx!Sy6-EP!G8lrYXz>s+r7#X;~%fa3q_rjaI0DsFELZ9vJ zy>L{{)+I!$lA^bKEpE01+Z+!J1Kl;|h2~24EVL#cADGj|$wU1P2KFc1N+>1Er_CkY zmFP@iWJ!^piIX8n#;3Lpgeh5KUXxrbQ}uv$pdWXaF5xFn41g)VeJ-iX^B!39gJ_d# z7v-mslZsW?A?r@Q=YqVo;XvqHpMk)9{Z=bZC_EJv3jn_-4gwgIUTSXyV2K^j;SKp` z3c4u$0AX=Jv1UpdW2euE;d@AO3iu?Hdv&%-knZc?;Na5xpQ^Ucy$y(ta8B&$KQub( zH+oomnka%wa^^^GzDP0RdEu# ztb+%}XQL-JCPpFoMrV-RTHhRV5AEHXR}w0={*CNDU0(FSGO!v=H>n}7CW?B@2JNdd zkW1r2jzml0LB5a-%)2`r{NAw7q%FO%FaXI<+QS}pl$9Ffz=*xR*A534ic^RJkqm*z zZz>PmKH`){5&k&u)9J==PE8pVivD)@j}Tf%$oo*jlG%zW*b)F<0Qh%+pM;`T>~ATe z@9zP6%m{?w@8B~WhzkC>3C!YikcA*QssGs-d^Y+Y-ZB5%?kVv$uC_*zMf?mZ8Ugj` zh=d~fdl)t*51f?^0E>bX2pgn~li;w>)dg@~H3P)Ffi&O_Isj2LbSy}d7KJ{8&!2HK zL)P#e$9RjIJ5UwZwDM5P!Kn%vsBY;4N zk1Hfs8qp*np}+Tn0eI>fzMYldRZFEjh%{N!g@+9xT$bWq(g>vqt(f$;hw;Co_;jF^ zAMoPkeYKzz%ddHbhpNbp?Uj>7(|wGB_gFBd5r6Bgw)oY7pme$G34Z8&BJ9~Tf3b(p zUf5`{#ui8*lcIt)`PRRUK?|R!<1P_JE7y!^>)p1~Z-_cCAtF~|r*hqd)Rl8m z=u=1%ZiR0)^Ds+Ip~x0H3R1@6S)ytyACtK~L*;^cb|_+mmuyy3V>F6}qttH4lnw%I zrGKF%s!O4ckUF{FE>@|L5BdeO!S19RdXIVb;LnQNH3mEi#5-n3rOF*n9{r;@V4|f< ze;87|M^q5-_NvwlWJcRFlu+{ZMH~l~ufh}j>e7Q#!Zr>f(Zi5`S*7+PdcwPPD8#ba zCAW>R);oh=;Xf<9I_46Sb#0=_$L>w~G0!a_8-+>Ue%qq4=~dT2RZ4O;9)%1qN%jTx z6U(LR>BF^}9UxIcZbYA7ZPe*zY(hu>`ny!IPMU=RGkl1JRvAjW#n7sg;IO|Yo3qD{ z^csIuP%HI0P82lixhNIti}uf@Fd%R4c^U9et|vdZV`Divbj3S8Ru=fd!<&sN zjFi3xI7C!^`mHE!lJo6QWBfN)*02}KL!SNT5lji- zQcw@E^~?w(6dP6f+DSR<199C$4BVYVV<3lf`o-B_2GH&=Nw)LGnK1kSE7GSg1PD$~ zf=#IqPKIVtIa1Nx=Q%KLLtAe&XTd(ut6dp?Zg&RbMUbsB!##~-WweY=SgJ${KvnPi?)3s9SP?3;vrag1Dj_Dn zBR6X;>O#*Mk^4aFpSVn3x6EY1b?>1!qthO(&SLVVZg$Kwk1(8I5IG3;_R(xR+xuOi zDg3VAQlBOA8Qb#jU?k#6D%LO`IkG^pewn5ceh(~K`+5%;>DjFSD4X;D@Ns`yZyHoI zpH0``vR9OedU9;OZ25VEpSTJzN&n0Z_ry?5)=6(`I`8c_qE(N`TcY(ROc$CbBY`OG zterRIi~JH94aDq^4SCXz(b5LUR#8qL+CCcsvIWvTmnp85&iyVPgBm!b5$Q7)tNhe_ zJLEiYeaRS9t;s#a!YUmv&uC@Z3i-7W{&(ewe2OFJk`fe2#rY>PlgX{SwBV%#ec3{C zlOfz4mg~=iB<%rq8jB?HJI^Kxxe+lDTp4z(xOy!|I4xRyTXIC_587GIu zOK`mRwy~_x4wf^Mi)FYa{pP)R$p+=j-9wbX#AGy789hz6Qcl9he-^Dnqt88DTS|PZ zrk4t(sL8htjZGiWevBO#qWQ+XggRV&pU8LIraTc@R#0#elJT5z0jcF?DsEO}RDI6K z`b29HEE_-d-4XbiPsI1kRxa-QOs}qQi?@_sL2qm}8cz9&t0n#HA8#P$K)3Z3p8KY} zHTw&k76jLQ3R-=vgF;aJ;fxm(jp-%8D_j=kca-#c4{>w%grdtBSdN=H zpf*RtiNV{S0dOHj773HDArZykgfnS;Ul2HsDSROa{tla7+cFBfmHy4xP2zAg& zwj8`=qur~^XQ8qntOewqTW`m}_Jp`KnH@VjM^O^ItJM+=S2S7nbY9z)W-bT+XfL>) z&g7$T;U}*o1FNHTWAC8;X_p~MlZrU*1F8Mak68(d_s#FifrZb7_L|dm4}X#IcpV+y zNKC}Xoc*?4=h30qo2inFIVw+d-@SDsT{%#1rJO7R*Q0}*^O2`A78?T}_TX&vaJ}7^2S0;L&fn6f|jgWvYD|SM!8wL}Kcsh7P1s`7# z8|wH=t<=vkdwoLn^a#XAutSG52d#R-JbC6Ao9}|Ne$c=7P$1V6nnOlIk03>pZ^d`(Jas4w{z91*~sK~*Id&o-A8%GYzAYI^`M zjk_RUx_oa-rSumq1XhFU2hgP?@WKCd6(pZsAQ{UiITn4O2eA&Ihx z`Ix+}ibaynwQM`BuY8^_&}&#kUJyszuK z&5v56ahNxT#rmeLYau(RDN|m?#0R-9HMd+tE^zASz|S><3U&7>*TT1 zUr*+hi=(9-pmS5Yme%~i53}tuZ04*b0NTlW&7gez3-U&!Xd6%;a8}O1T~yYLkdJBM z3j(ZrLtRtWc5L5Rp7|K>5&6#~k}3P^9s;x6mEXVWh>ezu$%TqKX3C~vyZ~q;%0R8k z9sFmevO7TlQwb$C^EM}IrmNcIWGdSD{dyixqb#68YYc>nuuThxik&AhnJ$GroK)7V zrV@PWdqfadRjfr`iD0RIbg%V;vSAFzq)k z;5!=pq1U?;1zSco5g=FeONq@tM%^3VuQd8gc*U!**mEr>DaO{{hAE%Gae#aTs6LEm5LV(Wk5v$Dy8L{NvfpwUY1=PN~jzl!s)PLm5o>R{@rV zvQ(QcvB2SH$8QeaBfCxCO{RHeOh-<0ev?ZhUaIq1(m?vJ7@tyuq>#Q#B}GoSZfDbx zc2=r;}f z#KA761o0~(< zjVZZUSJHd8?k6d&U}8^lJj{C;Wbm|j!BbbZvYH`(hNjq8oJS*ccEoF2+>|wbO)Zy^ zea=ojgX~wkA=wq5T;AVehr|-n~e&rl2nv%`ire?}No&`I3l&O=>g5D)^<* z9-U=JNuZadXt_9}k@gsnUr2_BC(aJ-@K#ya;1%smdgOvkmsk+I&AysUoYg>=z^j7p zILME#i+{S^q8yrYhO;~36gQ27A6oabu~kfRfk_eC zi}xHO7Pn=Vg}Q8=Q?*AEClx$Axhc|^5vH?;Ti@LFZN)IY5B&2R5wqQ3fs?H4BoH-y zRM;TfjES!dmfg=pSYxl4X_L`C?$UN4PU2QepI=8a2d79I|5r)0l{WNU$Zz59Vv2@g0_2@Iu;ykOj?CugzT6lSWc|}$hfQE zX0#hajE`l=Ah&w&YZOQ0I*4?v|K^P((w~KFD-SDK~fyq~6x>M^r3> z&{2eNo={&br-d@olzg-vRp9cWufjdS)&7-k$v;DG1K_FTv+Xib8Nvud444M(VB1*J zC7>ph0MF{&?Dt%YDxir=vAiic`s#j2vk8_O64F@A886!?<-k%rOY4C)8^*MNjR3*l~Qq1c}J0_usWQO_vp5nq#BqTGC3U{4Ar6shlkdC zj+^$C$y5_fj8&9iL*64#wC@@6TPzbiUu@0T9Uh^i`GD|qeoq;RLOpWIMMI>F%|Il2 zU5-HpY_Iqa6SOSpT)#;9xj_ zYCi+^8;4lJfj;UP?Ykg40Z#B)?&7uIM!BE3B4`rJ0O8 z9=Q_PTJi=!WTLpR``bX_MF()y@x`{4c~%w@K;K6-#^S!+wjf$YhQ)A=##dXH^RP@i zD`<8^g;Nq{o(9ez;kfOH4XnqZvHJK+9jaZRD(!Y8&tznmF>UT$^;k9n|JhgOvl(ow zHiM2coE8*7?ctEmKL=|L*1nwr_<(|Ode=fp;XDSDcb!x|;FlB;;*|;qHm!PX58DK_ z7SvoeJp9bV2~112r`fpcgc&<2WJ$XI+0{nlT)Su^ku2uOh^)qzy3$+D|u zh@)i+h+U2<`9I{~ozDx(f>m2LFYGd${Y)UI4Ur_x6dh}D?J`R7?vXodGs)F+XTfH= zmhRo8(tC1(;`+`>J%8MpPs4`>jxwm-lM`LECBg2H}AQq(g<5m9V!Dwc~;@Q6(A5VTif*F zXajc7o8KpuFQ48Wnf%qN6K-L#0}JqQISal~lV`gN^rE;Y`wO{F4Z;TLwbQ?){;)Li)EMucaGM^^sBg3u88GU>^NQPvQ^l`DP+;h zZZ4}WuG!mQ2IRMX`ArdA;PpX!XY=fZ;L^V5mTK64qke(j_jqiH+`>(HqUGwBJKHNe zmtbU1k?X6?iXTM4rv#rFY7uhaFS7z$CtJN|nzGfh0TAk9=`-vNr|)6`Z{52m*QV|c zs1q)aD4>p4r3~91u4z9JljP%wSAVM>?G*?X2uz{ofTY~s7%@bvUsPk;s>juMYfu8X zx@=Arj!-i?`3^(Qguda%BB|;5>c^5fCE|r?A%YHx25~H$phnFm7Q-_82(W0*3|40! zY*Eg;1&a0GbV+FsH95Q_Y@rG4p6VKF?plK&hbEt%U_vd*T*Sn{N|hV919IWAj_&)s z4i)Q^>JAOaiV|(6kvWZzZ_LBYiDSOqs5sdcI<~$i zjD@L_4CZf=kfLF-j;|nd0GrErJTiSyafMoo6ssTMU@O<8yJE6020LFxf=e3f3M@5Z z-&FO#b3o6ZM%EAxV;f5TsPz4To197zPqarCVZR)$6S2iPEP``;(Gwe0HFtl0clS{I z2;0hgIpuT->s#_C$~{@TU=l{&t9&HW%Xw?_r|9=TjY!*b9FoLZx<3tu@qgHSjD6gT zhEFOx5|n0n3~?aSv}cK9udM6S6EW_+j|33>G;3L)yeK))M+tgs7)*s(+QMpccn)3P z?-S~zY^BYDuM(x>D2tyx&UDSSz;-$D5lheuoOFH?yffhFnp|2bVUvD{kV^KrDhSU~ z^ec~2pJL6>$`I%apsciYmlwA*Tj!2T9%D(rJAd@G=5~6@Xgzh!$qQ`R9hlkuOgfZ6 znUz~sy9MAhF&ji$fBc8GV$qVL?o8u5hLhoyj!*2&i$^v#i{s}Wqd6jZej`cbHOam1 z@{WodMhc2~32h0Tz1R8PT`LK9@af_1lN*PCyyR~2+8lq?icB?(xyPTs@xJfKB|Y)f z8AdRRyZ!n-1Oz3G@j@u3a2A{GXkaXvqay(C$G(Qow|d{5bU~3XP-VZ{$hk;L^Av#s zUx!KLXb!)FF7M)u#Min8I~skr)SW z@7z=+2UTO0ddcI}wFqsN#IYazNP;p$VQ2|S;ETicwj~k@BnS_TgP~R zZ!_%w3Mgt2q;Qz-OpI$-KK7aqvU!_(%Mi_B)Z;PK{qSmAF4U$7oT#^Qg13BrOf4g3^ns_7%C`z-c_HJF zMcbvY&7^U*62~C3A%#{*o$m&eVU7{8a$_uC6B|ZxjIO56A9|>Z+onY=`-Hm+keXx( z%nwj-!kSbGSEGb;tpz`R=NaLO*j*OVJTEH;SNza9-b$xwsxV}tWUY8LIspAG;63%$ zZtFl8*JWViR;+Q`d&n5aKPnHnbMqY71Q8e!lS2^)Uq1qRy5(!hV;YE;Cvyl;K;;h9 zmF~Wp`g#8_4uW$!=Q~#>JeW6uPJwC2hwVdapf63kn-FI$*ZX7hGq*-?vhg8N5Z{pY zRPzvQjS!q*HC58LEN2jjh6S(6FT%6>R8Z-Mqk8Rf_?sIv6g-)Q88uwS+&XktFG@6f z>^F`iQ*r0CBM6-n2sc?nWYC1$0s>Xos=J?@y`%mU*a+f`$Z4v`zB?h-{0JyY)pNRF zZ3rO7RE}Xn*%8$<3Z_$5!-$^OEkNx63h9)5=}$erdA9f*ytjv5J^Y4rHrbndeH!># zb)ad*s~`AS-fi5|N~j)S@wG6w1j6u4{y2~zA^Ti-5$Cer*~=oTqd(V?0yOzxLo%w* zz>DMq}k1OmP56R80FXZ${Fu|v{jM93g0G97d7>>uL7dp`fcG-9(Rk*5S}RSe8&6w zHf!a}Fh_@uGqS7=Gh==M^aS2L86R!k6c@S53a#H7M7GR}3N{ManiCbF|f@byqa(GvW_Vevu|z^1#vVD8PBfjq?2lmZk;25x%7v>CUNJk`Sp zo-3Od=1d3kI^_@J27XHg6t&E%W6*ingnXzuCT}}n4%59q{BSEj@q<54x_hbK-+A5l zL`Tb$8?w*;A;T$_z9@puC+T03l!znMeVyE;$dxCIr_s#~JyzUXLp-dmmBOKUlOMys zmV^-RixLVQxm;Ld4(}`6tWT4_x{JjiD-*-roAL}R-sNl0?$sq$9YmUf)YeUE z=$>}*1ZgHT=2tOVh6n0Rv*fX-RrvUa4}}6WF7vh0kyBj+++)_p?w}g&O`F@vb^6lv z5|lhFPa00b4rdVxcEuF(x?tkxWVrxzK5(oJemuATn%|9n>&0S9<5=FDPZC_?DeMk}M8pP!1bnxCbWHg1sPaC@1R?aERxULTtxccO1M=p!Cj2CF)A#a%B1+=1YPh8#Oi(cch|7M6`ZrJCEDA; zOK^j7ihDu2h>obAn>?N8fUfTsVZ;nzjzraw#oV?{7SeZ;8M(=T)| zwZyd6$j@}`ewRS$&fr9GZ}jGF5foB(J4iygHd1-YR8-mUSVc*KWRXN1uMIG~J#kWT zEG3TjvI%RS1@%MOsOtKkgrXL_Dc0NHgRsB>)Q=UOiCG+(iwKF|!V{rf%uB8jIIj?O zU!X8c*al43(8PZvYJHhbPlhjRz*5UbmeKGekUJhcM;d{QV?h!8(m5Sbl2@w*F+Rwj zuQLhEJ9-e7KmyhOF@CtX7~Ps{h`W?3U)k>;Xyw;Mr@NS)MbR}{##^(YT*>Xql|={p zyXc8lr8VTR*{#3_@_3(1947KhNMc?chcqo~eHh&21%@)SSbBy{`(4EtWpvtfb*Gmr zQl7J%a67ZUT(qRlI$SsHcsgYZ>tS2dMQ85VFNe~ua56(;ZEFu{cyV#=C?0Gg81-{( z8Y(Chs<#-Wp`(whTc1|ZLM^mU?TXEFVjS)K2@VRGm{q?Nt6m=V1J@!p=8`}^#-9mf zKw`&w#3iN#P-OjjC3Yf$5+kA_Oo^g|reJkb38BqeIP%3{>JsSNG5@F>sk zz0iE)wIFJJZFn%+j}q}=xN@w-CXP{8d9FXOk@Y@G^ydx&KGq&1@9rT!UO#YiBd2tv zOmyRee^pUTp!vJ74jxC&Erq$3^Bw}kGvMU5-}wZw zQk8l!QjMKKzarP~M1{YrdN~d-idAwg2b|WfJ_&Px-6usyxP54X$$IXF7~n~gvf89B z1Gy;&UDW*he{nxoCDI_&Pc&VX*~>7fA?pDMMSw&!T}H^7aI`jdGN3M3Bl=;Lt+mWz z4AD~2Zw(JVIpKExhUm0~wxr7%{<*Qbxa}5HJ!%}H@_ap>u;DnT<72-{!CZ4V=m!g( z(j!=1nZ5C#3?HBdta{4;AcG7rxdcB~S!@s<+$I?s?h|*cz|ZZELt!Hr6KYq^FhYQ5 zZsY6@2rpy0u*Nt)Pu`T;LH})+&-mg&73mNV3Irp@Eg#>Znk)DW-_)9EX7OpArwH?YL{Q_!pXn38=enq zt5!ZDJa}fmfv|&u##K?bEr9onW=d_GNtC`3XGJ@0`Xt#9Oe3IwPZHznRys}+2{c;H z0Asqsz&sAgz1hBKFV_j*sYz!e)%hgyQ*hE&d$wFkhgqDt9{XH#S zZ?X9>pUI%S{_0+{6-%9|-@cy~gK&v}W#Nr@S@7cNJj%tt`X&KXb8ebewl^R<99zdl zCRNx|*UJAw>6*9j%YZ#l<(8_9>y-rVM{DiO%~UFN?s*^_{EZV@F+HQ$t*Ug;$0ggR z%f@sl>XfHyC&Lscv_Mu56F+pNsyco0RDH6^P3YakaSQRf{1-t!c{Zyp;2zv*!lHBW zXF4ix{B4_85MUnam$m`d`40SgME9eC`SyF8hDECAB%2u2U)LHD*3q1Ci1__HKmEUz zNq(zgD3YVN4eq4XIf4mCMMZ4*!4zsm^{wiW#MxFNT=+{?ZahAg5E2wz)W@n$_;m$2 z_=W%lujqAghtkJ{B5^xtmFGJ|8Qol}sLK$*(q8 z!vc)J+}&7G%B2j<@Oq`lusc+Hf^~bqAKn?y-?b3a=8dlc%oCj4xH4EMY%dr^*4*0g z3^D|bYh&Ihers3BT3nFak??^Zt>3~@N65e%>z1gZYp5Pa+*ZCa**~$V9e&Hd(*!fa z0?*CaIy1zPHLx+&GJ}K&Fy)m(E2*6mu{Ug)5q=mpO#*QosMIOaZr>k0aHUuowAsX% zU@N-M7B2l3Gdg2Ext%)e5FFy(Fw*FYI7MS{{^e?o>N|)*bdkJ`lAieY6Orj(cx_~J z_6st@I;&Lb8+bjRF%TP}{WKp&5S-DXK1Ofg#U3}Zq`bQOiLb|??>OqOByL@4D;HTX z)tk19A9B51`pYB2K!?Y7qpabH`hPfro(Y5dzqACvN=q%WUw!;};1Q2DPGwHeMEZIp zV&Mz^h4^;?7UOVbe-`#G&+0m}sw3$7`TPs(M+tpXp{6ls)UxiZ%K2?oE`J@G|FJ2m zjZ|tQb#b=nUMpu;0HlDXggGxUEVDyFQP>97?>V!Wa;b7K<#uQdfeUyj`(KU6H{+@r zx{GqhP<7vAho9XS|M+j)xOoWMDI@gx>0(;2OngVGHInlLo-HAb7sQJ=@^;XLJS+04 z2r4c(9cZi1-zKlUpeqla9U5wu9Z{e&=ryDUtW?$a?l`ZhN-@n6+F)5uZTud&dPaGy z`;p=8GUr*~9AGpzpAAc+Unmy*%WS&X?Y$z8SXo9ZV~fLEYs;D3k1|Pw;FG@!4I1M> zH_1UC*%H!~WIe4B);)dw4Nrp}0i(5i$xvME8ES^~C#2{OHU<}qUM;)G(Vc-yaJ!E5 zqf@Wo&T~_O@=Q@q=!hW;F~Vn8N*&(wITh-|5Ek)fMklakmSH};D9=&43tc3_RjeRo zS#b41f51G{PaARbxBp5^%{UyWe8;MN%!Tfz$$ZNeys-Mx;R4i4v_`~b0CJ1ox%-ozF1lkp^RbU}6P+Qquf1@V zZ&}n11xoNR1L$ya+oQ0YbMWDgwC}dow#qk9$$w#5K}XjRH(RLQ61Hc@Obbg0%2XC>pYH2heqJ9Nxs2n5}+= zYf25N#qRuRY%PY;`VAm+DP#><-!=@}B^|xk886Wtv<2#~Uo-)u1$h@+(=XEYQXh|% z$PTZw(qvyOhL(8+=BClSzR*-Eo*a=Zq?j!8xJn(Ea@qdGLlrb-bVskYF3_uXjK-&&jI9lR|B4Dz7 zyvIS%5=?9)*`NloY!@_igfKol)xC8l{gv|pppe<_WRHm2B(oX_CM z6?rd%hbT=WA-wdn0%5cpfFdFSMY$>CJwEtjWYMl`NA;`PREd8KFc!G{TC3ZzF7n0tPwb#vKaRg!x?yi?9=M3`*PP;?I4R+ojt@04A(% zvf^+bixIT>5i@Q7u}n9~pxB^n(wSRqR#S;>8aGAH*Db>Hk5jqXo_K@rSdiTX0wXL= zJ42`hLSO$s06;*$ztvk+LxYyV!ek{k=HCWV#_lDuyx6maLRg`;YU;6*oJCVRC^u=! z8CnAodh$6VsX951)GdxM?cWbH{(;D(R6U%Q6OQzFMYh*i%cq)eF(cMvXSK{olHW|p z7*KhQWe`Z!5!qQIgUY2bBqKb$pI}d-spkvscHKt8tt>bsg3lj=nOieEkHNc%y!_vP z9LuCKS@caQW>>s+o8qtBx2G{dXyNuc1O--gHIzxQW!G77RpoT@*uIRh1dhm_5OkgT zYy|qcd{z80YIPeBxRoP^5>dIzHS%_H0v)_=9|Mze@4r8Bx5TtUUBEL_<8~6upyd-06FoP`7pAeOvxmYgpxke!*?*AO z<>$8dF^N@{$6b+I$Km*X2M9L9>05;PY=ZU(A}{twbxw)~7f%f~N5t=l$22k7fc;T0lMw$EO1$%1pp)?GoC zhRsBJaUJbSG|QQ@u1ghhC%LMPFOH+nDe`^%E{x(&BVuk<`m3yy9xRsPR<{OO5Qf;& zMk0p?OO~zD8$?Var;^Mu9z99~*U1YWXip%PwmH+xljFks*M>B@V;7`ObjhIPuYVq2 z8nncS!b6nJ6rDhBKW9IG0(kl5RJzeFON5h@8hncAWQ*q9nodO<3)DypGmZ^2KeBo42A zm#;)V4;|U+wU(DmvP+$Fr|zdob@p}`k2_v8!qG7a`i+;xsAYo57%pSHiD26&&et(+ zBL-<~WEr@fh@|vAMDw0iwG+Y;ZxIpqB>$P!Fg@72gkvFQZkZGEq98!6edk84*L!q#`;=QBA~fW6P<7|b2tK1S zl2`tgGj47WPT0Rk`H==5_#+9&6RfTYz@+vGYz@B`&t+z|4buzVS)56L4(P8dK8!(P z(BVrOFVn`%PovY^Kg?wB(QJ-RmZ--1+m%#A<%K(}y^g_B-n{7BmI%@wPZIRIJHQ#n zq7<3^A>cO52g$@a6~kHmKpMzoo%}X;LT_4cyy^>^JM7X>wzWm+wCB; z2z@bp%$nC9z;><%t-1;=TV@wWB&iHPrwJ}D30Er= zo#RmCalH+FHH)6)=z>QfBTuSEP6WJoY5c@$^L}u&7O%ip$v| zM+$5@Eq0C4F?|M~w8iJ{cMt#}=_a zUQr45p*(n835JiO7DfPeG>0nPw*H6P=M%t{3Zb4ekRmINxBXyHvcainh#5_s!=s(R z?LcVMx&Mf_DpBud;`O`gF;|RPZQfrT^Fd-}^L|6evGxAMe;bQA01D<+ipv9!cJ=VC zGO9MCIpkdAy3opE11$;n@b`mEn%=g7D%VbIQID|M6EYd7qyMi99K=$uSy=gzZUsti zG!;e|p|qKT{_`>Hq$&qb@*|{{7kCSJd2E``{3q$Q{Zp&#qQ9mQo+VIki!ZG%^HyEO z7`gK}!y!V5`nJvnc$JA~NRqUYIDr2%dVB?5b#wWh+T>>U3B2b1G-EM7BjVF~Od>6G|!`S+i=c%|A^{)5i>Y^1wzUY487b9`6Fh8PCt*+_ToCm#O9Iy z!!f!}_L(kDyI4-E#RejN6F?RKqa`vG?7s^Mvxm%i6jh+y1{7Gh3FN3m}MNB0N=8yBg5e5p+-pZ-uU8?>xfKO%!uq)`i;gpJN z!wEAVkM;MkT!`dzLZVh=)ytRE0-^v0lpnDO50_{hO1ws_+1jTequrd7`8~gmZU~BR zqUf?H6HU1po4km<=&0rYqm^&W zg0UsKe8K|v=YuHj6<^sj25GJR2gN~OY25*MUOfrfxI46{Qh(R%;5iA*Ew4*Uv#!%o zxMa5&aLOQc81|JSeM~k5HpVnUkf}*CG%H7e=xxmPgB!WaS7zjObBz66 z25Yt`yI2~uS^vDsNM)=BLmJx7%c3 zop6*sAwY%Bt1NGsxy?D~axR=)_kDYsybo|+sSqJ=Y+p_R5n$)Z)9`8CLHJ!pDiGXo zhB-(`Kx;Lw?dKe))iQ?}zj2%yFf2VUWi^jLFnr)4E;EKzJT((PcobFDW}e=NGjKRH z)(`;>Zvdup2noX3;earx#C$}dqs4}6zWB>F2}|NL>mZcGoAJ31_u%u+?@%Roc>pk6 zAk$z<*wKNrGmyFUj-hfU_QpSZ|9IB%D523C0L=o6r~RtYhVktRGJ(jw+s%?iGHw?C z`C)V7;@U)*q3(>wl%o-zBnsd#J=WZwIVjRsmbrOgYgVPE?bJ599;LKK^J)}$N%vGw zpNFq3_&qo~25$3Q^AbeusYqWc-?~%l+{O4@*06pZzmoUVV! zLwZ1rh$~?{KGd~D=RMuv$#OTn>>{&3ukE=Ha|ON-05vt=@X)TpA8(*uVL=%_AXvDH zl4Yj`ZkH0kv3-d=fX8o`s?T!2MWTpKshR{T$s_)ooEYtnsx{xydl~SZpUG(imR58}3!3}H}cZ*9*q-K&)#whi&p4axIk z_B=B!kc@I!(0L{~jL|{aI&bvFY&#L{x+(bVNG{$k0_;XDX#oJ#T7LBlKRlQFagD9YS$K}b~T|FV4& z0V+G5Lvw_${$ZvliIFC>;u`X_h@DLF!*nnjmviihp-mz2Jga9~^K-%+tKeLQc}m8p zoKSEK3ng>7!^*MXg5n7f%Nv5J@>FOSUsqBLA{OlP{7hjUnj9jX1w7P38;mse7*Wca z?BIP&APm&@MoMcS*Te%$I|utcT1=06)s!9?OzwZI*oKck8-SPSV zyBhD0L8FGwAX4-MN;M)*!p>_w8d721f5n`So??I^AuRN_sE7yGkZEYcK#cMRU)I)1GCL5-{mlG9G>fU^84 zaI76PSeTWbaM)<z|P8xwQ0@@8Vo{4~SQ8`bFM%xMiY=pev_DuwYeq`b+p6dH~=t z5McFjc@j)8`_Q6d@Dr?HxDxor@1#gQU(^tA&t%zavMP=9s>~3HE+10hJcSn7QdpN$ z`j>4lREyffjImCaa_hL9TX6Uh;Zo)u5on{p1NQ7$paRJcmky9dvrR5IV(&~-8V$zS{J$R_e^+s`PGm$POULZC->Ha`=vQAs%ml;Y{?q9KtzTw$d)Z z@^9(s#Td3%dzae8uDI_-hw8X6>+PL>fB*m+Okxum#{V6lrl&1ggv(UwHp+b}?o2oI zTl1JQX4Z+oZ`~Y}3_-e%I*@BCvxY}U7C-5kn5%yB z6AZx|TeUoTsdhcy;PyICD^K&tKFVVU(?*J>Np^Bm@AnY|0~iXzT1Fq@A$j`PHC6a> z06@oQ-}n^_4@B>k@zd|4;nwIaWO;-OH1lc4RuD!!JCB8_V*GB<=lzaeNn>wK z?A-=ythB0b(-JnNE5v_hSWBQ>)$88h87^y@?$tyH)z}3G(ysrU^kka)hBQ%a6AN%Q zAF+%L<>^u5k{(p13H3XiMh0Vh4$Uv`%r{HKMj+jGw$k6i`~ZvXo`Y=MPoeVlmHGO8 z_&Rh&3YbtSo#pAZUl|D>%QFHa*)OfMqsr5;M)gT%S}v(kh+;qy#f_p1E*$|IP+Xc-4wq@Ql7U2?{@=zE`Q&C|q-;s?zZbPPTK+$p&%u zz%)BC=W)PdhQvq#bt0ZB;LvxbdP-)7ax1nm&Pd1fcej(=AfgkX;2;343cfS#MVp3Cw>$evA(thIa<*nGI3A~|pDKY}r^jQO3Nn;?EGnE^k3nW6aztQc28iDM)l66HWPv0{b|O!sHG%kL$dT@&!HuGX z$;;du-Q(ykDJ%vLr5Cjl+rlI?3M}JAwf;t^a{5B4DUMOtSFMMtS|q9S*bB8(tew;A zpNCqZe=vWIoTH#{^DbmMy3G)>po?0aDVB+)^yLQ}96%gi8$gvGTAp^Pej&fD#yE^e z-*lyRMyv{>4S<64bvWSxf1Q#8orn}*mNZc!-fPg5hC-o^Gq1TqaM~o5JL<<%baGs2 z7c&@WBM^zZxT?hTBd{H8>NW@g4euoq;bN)|h@UhK_DG>HB*QZWvMjRBWQO67N4Sso zEzFxrf5u-d^{&r&G5?n3d8HIX+C24)hO{1tDUFwhltz(nXaEx@J&8knd%Uip9o`8R zU?9)FXGsY0aBla2uLjAg{8k;SF{olr4=G%(w(aj|P!O{4Z5FxPO}+h@Mo^4d*-xAb zMCTe2P<4A;=(;P^ah69+M6Xi6l(kSoHNcjw@Fm zS=8=};w%6{5_h7R(BZQ*g5x0FJXwaqvW0g2d2_&>1V4ovp8qDz z=E-s)$67b@5t=LTQ%i_TFwq8VkOA_4(!BlU6AuoF5X_7ow${RypzqU4V48D5beQ6p zd@6;hQoOQU%(0LeZS9d{Cp_{7meSUdRXZ&~NIq0$4@6~NC%@ytP{GA#RZ z*^)Z;vFNWNigPWLMdR_bcj4#dIlL?Lr-Bhz;0SJOL9Eu3sYFq zM;|!pE|^Lfzh!%Xfuy0c_$#Lu*Q+0=&;CDuJFb*{j7kOWm|ig&;J@lMtKJ#{xGy$N++o9@%ex02j z9GrKGqFoO$+2xg)y`JDABtx-R9rUtT8p!OBh_HC~vpZ>*lNijZ0IC$0Mg(7iAj{bz zfCKcq4`-HK2Mldk{n~Rav&u|ZvhL^J(`&H3Qm-~O7v3->hjV>=MtC;W#ufeROUh5d z0gcFb$GA=y^06T#%8z86=0gj70Ra*1E&RvD0-@6(p>-+VykQ$ylg21U?g*Yd8kRk9 zyZn;O|Bl9&DJEtgwDB|iHH%?HyErsh9}$x{pwpZK|L|0?I)lPkuf88(O7{?RJ|c6W)S@X9NOf2Ix+QviLJ%VVdvsu-Gq&l^Xf*j?P*m*F0p5NlNP zmP$X+?$~72B*NG&Ho1-Oa(D!0^A0g~ZBpbwxN1jyPz~-Pq*8 zA+I$b%GAazPuU;S(i&B=l&D7NE}m@xOxC0qa7{=omUSuHr$3k^o^i8u>?ds*;D_=W zI;*zu`%CB?OU>XMv+lhOcwlhV4HS$w?;fAs2sHolV$fS3vZ4D1jeKQuf5`EnnJlxWyYKB&6Oh)m9l^Wpwz$J z{~o2-IKv+_a&|{w%iDe$B5$ByS8Uo!@vQ*&j@^(F28fQu$9dr~g>v_J)-vn2q|K|z zbPQ74B9K^mZ0?b2kV&XSk=vGe8z;e)-4+SnZO?fLm=(m! zbSi5tDQaL3 znfyQvLCNENnUJy6O;&+6=Kt^z5{6`bt>YAo)(7VnBR)w`cm@ym{WnVz*Z2DMW^9{) zlYe&z@C9fhIgVnRYy&&nw1P8IQa#)7rd-WKAmxj;HND*Kxu zmK65eyJ(Y(N?D%bh+z)4BxGYFWfW!VqK|0U{K{EpNl$B|22>schDy8D3K0E|97Jf_ zXtO}!`}4f`pXd|NiE+9C`y-#o^p0zmR0*Ju?~%RkY-#&WF3gfMw2>;a+$Jp-XhZVu zeqXXW+)AUXG|0$AdQqftbA@{8A1Y6xG&aNNygIO0Bo^e)hI>9hO4e&5A4yTCLGHXs z_TA0HbNy+{!K5c`xLijxDzgR>!lgJv(Y!4c%iVp17R9FJlse^^gtCkY;x&M1WcU=r zqxx!GAU7DCyux5LaMF65QBKuhVS|Yl*{;4QBH+v+VZh+38ep<*6`Q72j~@-?&+;Tf z?>_53^VtSqA?ptZqlM4jZCluV?)8x>p)p27%YA5Bb6ZnFVLViWK$}OYq_VYmghBW! zy*_ss$!~SEtaI@HpouWvc*%Tc-mOM}3SNiuZ@%B#KBM|Xybwr3{q|Ja3&0O9Q|kmf~)sr5Wsa%T}k7-?EWzt27@ zr?aocUBxYS4GD(f=ZWTAtM@{;APV*E&k@BAAE4&paKCN&DesBl?wlCZyxY>+m4eVLqpWW9wBv!@HCWnBST# z=j}lJr=0ib+Y2V^w08BJZSB0>?kaM*0@~J3%q;Z#m#St>LcEoaB(Asg(I-Cu)iyG# zxQNE;i_~&R|HsY_^Z4(DGc_JYjHo@6>7ifZ5;Dr@)fB~9J#zb-dxcIeX8Efcb4Dlw zW1#|h>z?wdGw8sxb=oe`f2eV8-~}(q>&tkZ8_#$sI{p4smj3#&1d`$eJ?+|iV@V9= zw2_$AtCgP4x;UwHthAAYQ*hiuySZEoVz#pX5@$FEy5%hI3q5V-HXzHES_i6f!XRx` z4^mF%Gr3Ab5J_|g`2~)9Ydj}c;4#4FY)Iz>9y-&lh~`k@2=MY93&x668BINNDa9j_9%sE$Wgj7j-pA#Xu_Z*bWHbbHA7Sz z5z0^qVHd?udn3e|?yI-4s6Iz`%W2<$1YR!E@T12-hu+?e$gV7{caOEVqZhTk- zM7O1O1JV;LB_5K#PNh!LIh_{%!z2(NsbQ%Bk(vsu7>1&Y8vpYt5Z1>1DE~8B8QNWu z?gK{gOI%m|lMFnC2c~x?PmFZ9RXaCH4cJxs`@?ZH^wqJ6GS9uBkDrlHgfoBD zFTV`~@J_)g-R?=yf4Vs=c5=`zT!I3TMGV{%inT)f&DN2(I+$SDp5h`*9{#3kyj;=T z(Rn68lUPJ}&ej>}4vb8CmQA$RBx#O0;|ZH(S(d}?1_sOYH(t&^dnG)CO^q&!>nQx@ zIteI@BFPz!VIsddgn?2oP z-j@8MMgPv`)3+d<@uN54^YbU}eBlFa*&A9`#JAZ z2^boGHVL=?YeDkrxC*%4j*}0ZLa-8p+w1G|HL3ayl&BkIur2lL@x$lBKTLW5AX9|5 zD2O*RmQ9%8j-$mQu;ZRK2; zpmUAX7qfJ1GO>fJ;Iq`kis01#-~ztuT}ji(|H}5S)lb!!>0MobA>(#e3d%pHU(YGV zco{E<{;LVLNeB^+ss`I^2Mkk#^^*CT5{!X$fE$9N?CveGU*C?^RK0ke#SBKuelO-Y05elo-ec)rbdMZ-sl}7!1+y3D7-ChfxbJmcM=-I>=cR zQooD&FUnlsOssb1+FL4=YRK#@o1)3HNnWth%apo@oxn>>jQ?l9el4D9w}3Y{DWx7g zacmf^r)aOnmGO;`kHmy3oa%^PY;dQO>x$cm$Rnju9!YG9Ht~26Ad%)(+hGsqoAm87 zMN16o)&!e@;;0@iN)MI@;WPGd8Ede7u!ALXu!W7$(y-1&%9 zztvMM`eYu5zOLRD3180KEN=CMa5T_=?1zC;Z)w-?o}ld@Dsvm6MrY=dpdprjui?5W zNmH#M8NP74`g>$Z`z@pT8hzM4lG^d9Ys{v6{DjGt1TVV8C0D;3b`ik-Eu(mZTj@Ey znPN~DoP&&IR+7*na1DqT9k#3BgUk;ZJk*{`u`2~(giam_c*}1s?|?~vF_b7NgF7N! zMkJ~mTiVk`$c{rx?K#Qz^-E*Kjm;hHSY4lj5=;cBtJE)!SCy9JAt7aMNoMZ@&E>{G zHJ`UF2Xk)xsCewFl!=%2Di9-1~T{u^lotH{14hF9s?XoODr^|0Vo5y%Z+K$Q>e+lWw z$ta+VO<_a}nz#k&k=0Gox0wl9w?m81xHsEUMF=e6s3VrMO%M&KRzJl=kbB3=8iM3* zKQ^98>G@wHxR~?Jpe;z-**-}toj(cToWrJ9Olin+R?4@K!jK=WYb-|^&*fuphdnUm zcyh)%k2+Xot0z}z_+`sP+uV>HRvZSGGFr0wKlDCqQIXZuUxL~;tdm&R`ZP_Q2ZH1W4S?XskS^gq0B9G(n^YH3AhLRLTr%jiJ< zzwOI~r%S)>(7-NsGO!D~RNyN;q(M_LDS^yvL9>4||Aq5n#^VG%aL&Td5dfO2K3@mJ z$Q7CeyU-K?J#NRQRdu;(XA25OY0Pl;?2T`rIiQ@;?}_`>CV1j}C1Vm*`J?lA(r~^k zPA4$M9eK#Mj%J;zFe}D(#ufg9zxqQP!GCi4H_$-RtmS{Uj?|5Rb4MkiQv6EQwCbxK z?y8IyYo9Hs!)A}WeRB8ME=@B5zfaqDXS3Vq%Y(?2VWCYOf#@hsqon6|sR9s8>p=m3 zgNZ~oXIpUiKo2suz#DZZbL&}z>VvZRsMJU5a!7>Mr7gctAE0}=9(iUQ`NVkU3^Ug3 zSY2O`$^5k{e2MP^Xa<4PEObyqa)kT00@xpY)rZhdJhH0jv+XJg92vCNy= zL%=nIc8D-km5=ZmDM;jVL57rk4& zYb{Z&sj8%~|MFu5=G0Z9(+bhGxJ&?l&a_MU+duo7?X@3&C6|sH7^xOn_hNkh zJMC`q(&GOJ-W0}YCy**p&HBGF>FM|uJ*dYr91_5p&!qr}cL+7bIyWsg?KQxg2XJ%9 zpf||UMVbjSE&&K$H7Z>YCv4^2BtSrFSq~JVq(vbav4Kl7lg}pp6oCubLd4V|+n5OE zWuMB9gL&8j&M{>l>?#-if>4#-LmKM#;=y&k!q?imdZ_c+p|~L4RWunH@T$?<=x#<-cjVDLFIm%5r`1H6Zhsb%GHaE?v_FkpsLhjRgp1+C`4nsMG2<9QF1t z_K->rYom_+`?sG$RdbXN(}P+BoS4Of1~x=6!3c9XZf8+lw6|fL@A~gh%tm}<1OdLL zNTZ3oRN`VQao-DIoHfK|nVu^uAQeB~5L%3V>j|1bmZfS)KZMMc6A)g#NA_`o>!4*p z3$-!pKd<$^cLIJCqX#LQ{C4};7iv{|5e>7Xd(QUh4?7(~SsbQfeN4}|fnBoiF>cl0 z@Zi)tTLYv(@*E2!OZIx4Zoipndzf9EvKK$97DPoBfrCuQR%X4Kmt~X2h-P>8sm)6ZwZ;pma`q{Y>8lJWtI=MqF|=mR@B_ z;YJ4Sh!jjw^Qui#N>+GEALiGg{5;>Id&r!XS zA^MU*h0|I{M-Z2hG@%XRB5=i1-C)%KVV|Xr-$odG`OX%sWMK~x7}}kG^}mWdsNoDQ zpwDxtcLFiMmqX(TE4CQor|eYjd@h@?e$}E_6F=4WmUQcnFAsQi70btq)0lgm+l9uy zlPK-PJchrU#k=COZpNC=GXVoW#r1!Sn zR_z!ut2IjE_gBm?X6JPgZyk*7JhkR@m#0#5hP3Dxr+=P10X92*Y`>pL)&0*Nj{XEo zhnak|sTQL5mpBMPJJDUrT&d*nJ>asrf_s8Aq}KM0 z{_Ww(dPMur55c+{k>m%55UwGuzsL5T0?xLlrf&7Yyn2-;uw^&r0MzG;%8Z&sw#ztj zF8-w&bjR*5e_%USJ&;jyg|X0Y<+o9$M_Cu$XO$uyEO}i9T%B;&VTTy~nl4sHg#6Xz zjHt>XCT23`!pKY zl|y8tlY}jOQzsbw_Ek8O5R$Osq613>HH94lV%=ni0WRdld0-mAt+F>bxKCiDF*&dr zt|v)EPxiwG9Q8>fPOiW;X^I_U{6QBm0We5@eu>UlF}nFtn0o2XgO|K`Q3vniKFs16 z4;oN|HWkB$J~g=mxuUY9uwf~a0&E%*>NnbAN`0vTPog{1Y=YEb{bvDS?Sw6MH2E*U z-%(3v8_)Y8V^pk1Saa+0Z#=Gh(;hD}du}B@jFVjFtPk;L_2NJfvAMDw2qvoPNR5d7n&?6QH#uF+@?lB;}8DDhYH8&Qs<$GnQGQA^Kj zcfFAL*PlTmQQy;w1-K`?hGvL6O=HS`X^Li=nueBa-71sa8HZ7d>e4Vfr@2{@(>EtK zD<)z!!4a_JCh0G|7{4DUwVfY`X!Js7Dh|;fL4$hQN zU!#|7-JX5_kSRY}oslNsE`EB2hU8dLy8dv#G12IS(XWRnzTwg|Gtx8uYqPf+p)v2>!ITQnHtehp?5%ALSpZN23cN69$Fo0~vw)S4b=P~F1b~mShN4bz zGebI1Dev9R|M)Mf8!!(nXhY~r*(kfPF0AAzOC7PWuDqJfk(0W}aCLv%OfG zbW?eE<6+*l_a)hWFU%iT;mOam5_{p2PT@x_;oY^mP#h}<$s478)Tzy;2a)@TTvQ%lPWceCyC?h`&_+?X1 zR-oj`^*KgG^YJY)J+=a?*?m+*=;Gc-{{>>BxCIKlk&+$a`P0b>UR zcG+LWnaOK5Z-sfyA0rAam|Jwp+CxatGXpaw-5JI}!6ug2gP3-arS|j0@yJNrul> z>;Y^Y@9Y^gtiuw0Tyi2Sno!Y%)wtW@B`%G2|hA;{>pMr z7?(-~p)~V;A@JES4<)aEgSC))f-3fFahMlQW7}T82^KJ4bM`)g6^;^VjjrC-I`~oN zIfzN{B{|@McG$Um-dhU7WO{eUC-W&IQ$5s-{RwMA?(+Qio#BMLURc8h(P*hOqTX!@ zMrtMi)nW|_EBMyEH2<)sH1RvE4OEz*b#VNgMf+*M%1YLY;HhtUDOx_gv>z|0?MY@m z|8??3l5_w70|DaTeIl7o{1DB;HkCjnQgVu^p#yG9J_k3%6P)@q~u zDQ9?@V-zG@3aDnOC|V;cFH^iOMUT$baBVEN10iwkeoTLtHKB0@e}-|tNI9)5ubP_x zQ%BDX*-F=O!wEmosNR{oOs$fD->Alrcc4+s7zbCW+iG`dHweH z;)1vWX9B`*FOL)FAJc8s@A%X&Ak0wlAdM50kv!^kfa@PtRN{4mX7gIoH1i4}P7wKq zhyF|xgsgKlQyJw4z{$q{I^AAfpB`Shcox6qqLLlnR{TB`-SmNgK}TNC=69XUqa5)P zoC`W{@V|(9PWW1H4HpX~n8N6woKE`q(tzO~Bn`U>8w-;n{V4DFp0jlw^*YW4Z%Z)T z_|%K+Ym9&A{ij>dJ8g;Sp8xSiKY!8*&Hj&w^1AbZTtPGmz+fQ=jN*SC<>~#I6Ft=8 zTAfBg625JfdheL~As0(JUKSkCUBcbxTD6O-Uas{x-#cG*fi;Fa1 z&X@GBj}x8KS&L1;($?+(k#__4Q@kk{=y5zd%W`UfSF`akYBMiqpyj9uCE;gy+J9y~faej>* zMB~TMUaxz;fm1u68tVjivS?tML5|QdU0^*ey>A%mc~3Rz^GC2Fg0y*8nii3#Gage) zWmnIE_qHF*Z zlgr0~s6;c!+HeIj5A>JE#;2Q#p*+%ImSgzM(o0}1uuf$!E$~Uu*0ZQ6SDh;Sx9}Xr zZky`O(b8t4y+9BJ^f{2`MmkNBAc@u3Jq?8HXEC9F=JSNlfgH_$eLuT%^^=K(6#@ST2oTBrguCBQ`B7<$yrF12_yuX9nb8FrG!qeEWQ8OWkzJu=kOe<8 zF(WbIZDPQl5$fki%alUBjdh1xQ*%MHGBoS&w0;3f`J~&+Qtl%FJ!!4!mlaIwEL+Q& zj%hpM$Z%cn1}+VJ-!2p?kCj{!Pk7!zHF<0R_%gDvpQL;J;EyXNZU5Vd}*Ub;!w>!N!b3yw= z&qUU;|IY#+TG(Csvg!L{oHUhfo09b&ocA$IQ|`-Zw}mui4cYGou@QMc%!$MUpV#9* zfFPIZBtM1wvy5~V;){~hQ!4>f~IufVZ;H0zVjqn3BHL=!6^IXmLhGMc<#aK zL?$lRbPIFLpmww2WceiiB2U^3<$I$}3Pap=1w0Y_K9R(cMgsbr!d)Gz zgy4*{kyRe5C;LVtJcyC?9N!Xgw6!jO;A)isL`Oe0Ei_9IGgKO-dH$vrNPS9bnU8$p z^FkC#+cOU2Cho+2=N*RVyKsSagsNL&Qh0k1+F7o_*NMdG5|dtzAB>=16Y^>9oJ2VD z>u5uti!YdkU{|*-((X7Xzc17dRh#_dv+~bGo6jVSb(Zg*TXHx=OBlQ2JNyYRne`kC_n*=i{yxC(Y)-5tt8tHS$latJ@hGi)9&xL&aa8#rO7{ z;>`C!rfL?Xz93PRin_!uy74MRdQ;Nc9-3XBfBVYZ6sz^LDBjEWsJ`B(_3F9Lt@K-v zk>^;$hcsRjZ9oa^1;>|ZZz&$g81={dQF@S385b*Noj<+4C8YowNGl)A10j&Y zf>uVo8Dqz77^q#rlRymnm%`98e`QgicJBz+P!o8fhM92vpfgX<1X9L_Y9hIy|30nO zoML(BamRZ^Rm)E{u!>|M9&5>n0Dr(4y#J`nR0Zyf7s>Kt?ajp-fZv%rjO*vEyd=-f zjU*58k4)oVY?e7NvMW;oZpT@)x&SQ&lBC2aC<-B-|1lRvZdkM@brI>R<`?F?BEoL46@0 zN2p5W5^}cL5}CH0eOp)aP0eo}={yNX*|e(B>;u$w5XNH85R<9ST$Qq~q5WD&(L(FP z7BynF%&{gvs!I|;>Q^&4eKkNZ?9#(Lv~kSt9%J#E(bw9Lq3?kZTB^~BzkCD@>4A4i zUu5s$o_bs({PDsk-HqnD0|_Ys09VnM;lm)*v#W)&8DZa0B5)B7jNM9_r0NH<0YLVS zd(Ioe5pA35MWM`WUT1Yzf{kUicPcMQXqq@ur%VxmO9J`6bYT=89XWjdZg?$Evq$J0 zlmi81`N29-po*&+T03ns<%Mwqh>?MO@pI|O7O>E8Hu|XHk3;47?p#9%E;Q4hu-Sjk z!Fb3uyAd~00x?NMBTHL}ioNpS*7Y+dE&*99uumD>2Sh)o(aB*8i#k=)CQtV*<`%tm zB8~Bh8ifyLf*mH|aCmR_)vz97!P~{Fc{+x?p&F$E*N1}rIK$=7)R9f_J%rvpz7sg8 z1pG7l>&IWCq7OxvZr=~d4?~MU{&+U|itTd4%X?vw2DTX^4XjW~1thw|{Voq%bsqi= zk8jv1Rg#=-`i=KMS=>K$z-5)R_HwQn7`zU+1OPukz`q(<#@!E-R(H~}&Y>9Uh?4*~ z_5NY>Z;I8aB9g+h>PYJu|jIlBMJE7|Nu{r}#JDycl7JSs2^xEd1@3u30 zu~(ibb4%KpAUIjJ$oATn&-XS%5ZCx(J>LLVCNID_<4wI3M2uaFG^poLKGZE)ejU}D z9bBH~TCite5duclAede(vi#P3<>$wt&>mB0J3NhmX=~u>4821J?^*enDD6`*tcMq$ z)r_HaRSxSabWN3+C<@&=r;6Wohn$aRJ-kkq?%PWkwS!6?KYsiG%h++P%BeB&(KgVt z9IB6A)#rNPM9}BzM}`*hPyjEBSNm(NX_CUQoV`Ct&>g+?OP^9^aIXI1wAF~t& z$a(AUpVXcj2n}a42XSF<@zw|x$pS>q>>Wyi^KM_Z?x=Or<3x4D{|PYAO3=~@FE#lv zF-{4Q-YghF^X$~TuXR{WbQRQIKk2D{pc{)e%cfI3++%WHslN8hb4bR_%(HHH3~a!H zb2Z{8ZzxY%7W_~cG+IwQk^%ecfmGX2`o8jcg}=g8Wfh0k{Wr0cBW)%V-Vya?;zr|c zT0cjZnkk{PEKInf(8|N^p_G)+V-WUXr*4|0x*TCapU}_$eLXT4oK< z_E=PHc>fUv>INt_nn~NOdt4zWThVB4G>zApft=Ey8(fvB!wFsAXI?qbH(tzbqU(rE zXA>CSR9%GmxY3#=%?;Px*vHT(_wdh#I1cGYyDC|rd#M+$Fij;JttV`Gk_h)=`yK#3 zcA-_s{hT!^+;5-PfywS2AY7VPt$|yN`L+9GPzD~pMecl%lky>T9?Q#@P3Rta=LJQt z{5jtka9%<`_weA?yI%q3aCPZ1f6)>eU*7I7(QP*9tdgRc84`{$Cb^{SpM9Pd7W3%CE3u) zXk<3?yEGRm4c2NgYf*i&EM5q>e84X&$cJTPR?Z-hVd?U{~6!xjiMC~>mHD(Fk?I2oIsIbvVAsQjJ zsB{0&FNl8gXj}^3r1BXR)co0qv_WRJI63YiQQ0#x=eocs%eT{3d)~#|j$JNdhD; z@3?5Lp$T_XPwKk?cRB}X6mw}Ho45r&1ZOyXcf=DmbU1B$JG1!lkU3Frl{V!Sq_ghu zA^t>PCmhubO{zUA-W2_M`cCTrJpoHhN)ie8xu`MntNBIggm|KZ@0s>>=7r7e+z_;H zZqGShk2m%|oA-eUSA4&NXy;J6@)@KcbCClDnoq-C9u2JnaOaV>q+kL=Pws@D!N@xJ zPXTe*u-PB&vErW2Y?m*VQl0Ffmy24(-^h%++P53f^xm}oBDMuD#?e}ayZGhZ?j^x0 zylM+6oY8sHUlRjwA1{6T(I7koVS{=7yGnLzigUh(OxcvWB^x(1y6brH&aPs

m*G zjkW*S*S@A#9Y_;CRFhU$S{(%}O~jg&H4mhVKx5$}<`#V=ZKfC>r8y&t;Bd(;F8_2J zw~EbxO?yxNESJl6Adl7doAZxmI&>{jf_-$6XgN=hIlE1{M=SpN6U>hS6 z8WwL$ke_ZUSxJCh0v!jLT*Vi@o60bw?&1HNV+!Q{xSN0g1LXJFc=x)V^i6Z@nvo|+ z{wjR)1k)O4Gw@Zo zw}7#gXOKjG03Ze)B;k3PIPi2y$3gR<+R2)W_brFHuj@h;;|>*+!f-jJPS78!WJnt$W7emjkZ?<6SLv3(T_ΛKI-1Lh3?yt?Z4)v^R5RfR zQF-syajcX%`DO{xx&m-XabVZSZn4c(BZXoFGA`f0nNu`EZcI^l&Zd9SlWydqZFlif zAx+@O`dRqY6%y<5Dq5n1IO!^kqhg-mZT!d#@)LtESeUSW* z84b_zI_=Y~%(Hy=#=9)kcevit0Xi*l?iLY4P^475UtQ8~JwG;a{9!Lpw`&kBkowc)n03wWV3CVdm^S-v#cyG?pcBdkW zT$m!kSW|7(KF(Cehk!8BI!+}39YoaeOkY?QfjSIlo0RsJmgY+5l1Sdc)uIRPG6#Id zA+$e+ul>&wP z6bEk8kakQza=Y+sFl!igJ<%j*JgiPrWHv)(8}R9TB&vm>qm&fX7d6+T`=s~kEndGujFNXf zFSyhumUHtTu(4@GSWHW@@=8EYiX4I#uB-m5HfI#*(2rsNAs4g5=DyHFxr!fGxNZ@b zyEUlIf_b1`Nbg}_Rz}-HJ%M}`?FKSA^`H&aZBH%tJ031A?C5B8CwMaACP~ciC!`st zF~p(gv-)&lHCK;D`;w$9L5Gk7QNB2%e z8041Ts@o1KGS2nVT0Ch<^Jjrj%h1v$NrX??&^j=iw#_2rUQncPrrUh0-w@<~3$D4yen(i*$^Sr%GN$do)diD4va|$vZ4j z#c|d}sQSfrD?}iE=4|*APW|=c~rp_{a8Z(v#PAgTwu`l zllH?0*oGfSV9-BRVd#JuRAWHcL}~KAvAt(ktD$3Qk^isxWrI_EsRP04>7nE5eqt$S zGPR(V-cn;p^2Tc%p4pfsNtGH!Hy5b45Rad1Q~L9}?u*@ZcB5gXGFj$1G6+^=yV>6k z_W@8wa@hT8LpH#GxXlpz{G1q^xM>QVu}7>rld$2_K_+akut7zuv(MpzkOw?t-;*Dp z#I)B=(>X2-ou_nQMs*mN002r)YNKEC3=DKh(IIXF<#7?hPFbxgfoE!okyFf7^k(wO z;SDZ%no+)JmblQvU)CO355B zQxBJYemw^Krj{L0^=MSK^hU zjGI_u%xv5##2Qr5=Y;B=tI27|dGqSc|NFWFrGiWAX45flPuu_pO5ufEkz)t|?3N+g zh}iOD_dsji!!^2S-@7nRte$_YzH}2uPhkJIY%Hg`HRaDsL!eOlu~#$vOqk8XWQ!{2 z@F)`4(^ax}#*;4H4M26WhG40^$sCqIl9_?K`bh+D<^N1cL!5Jagth#0LXDZAaq9=r z@-$5>JAEGKwGy-2J26zLh{fl>UkcWMh`jj6fR<-Bxe0Cvf< z;3CGlV6y1_c5!6$kAq56xBjX#kcjXf6S|I)w~hwWqiaoayte~d?B%d&p&ZFHf@GTk z1lXjnCrH|AYFs^Hj42wd*tl)e37Od=zYPJl)%5%j>Mj zL@wSC13pW{C!u#tqcEtHr^^*~!Y_-^31_1V0e+TQQtT*BBX*@lft52Fe+UimYrzA) zhVl#wOpq#Y@HT6Alt($~b$m}W-yIk#iw+&e-*1zg6$KSh?)@^X_0^gJ;$bfg-H=fb zu15cbWCzz-Set0soMTKd5tQ=bHg}e1nROww>}R{mWYOr>RjjKwD{Gr-P0f z2G>dTgh+Ds5wr<)XG0{SF@CkzNE1F45yRz37iWBVbW!*K-&rTJc8fQj z%WU<%Kn~Gws#ojFVbw;v+)ZFl06V~EBXtye#JlHNZ#@cW&|?!9Sas%3|JZt~sB*UX zZ}gfa9~w#CsDGH+^6>2Q3y7Qfi|e{K)YCNdX4_ACRkjtKQUY@6bvueA+F}i3r7Aa# z3H@){>vr8%qg8g}sM_z7ezTs1x^LU3=lp|cxN_ejRb?N-_b?75u`JA6yZWug!s`%< zr}pf^5i0nOc0U8RXZf1XPfUb^C}bcxR|x(+eB(QqST5zgYH_1g;NGYNhCeHn3)m~k zpl$$~91<@Eu*)Tdtb=i3lx%b=OX`!+V#YZeeNwv5(d~Du7^d*hnAX?6-SP=&$1~1T zcQd6Clgxpm+R?+kUmW*bzM%@qT5OSTjhOsM-CGO}1ft=KO+2k8Iki?>fy%(Kid9U) zfdcoG-y>^dJneE%{w5_tt$C!u=%vQD*WP}a5yJwyC7o7t9thKb<6u(wtxW#(Iy02! z998Y`Zjm?B6OU)`-li(Lvul0>qIeATuxg6YdFuVa*KD{*#uuPofF4({ZbiIyVDOR~ z%`2bc;u6O8XeHQVZ+l3F7Ke+k)zYXwrh;0mpobmZfCivlSne_5uBi23)^&@1omLvq z&n-d_S!Ba~O_Pz@lbqEKl(ac8xFBv|A=ye|mhRR#5NW!>#aT~=-1SN9d*&#NHt-SIu+(-o@#BKYYB?pt!Kb zhXvFOUuh}JM(0<~Q8>!(dJs0gA&>zcKw8@@&VnX(!Px?(miO~!%8If!L|uu9J*XyF zd!^`x^|>FBj7~Uda`Y50CX#m3GHMArg= zSf`|!Np zJOS=y9NOj7stYxl+)>5hp9N*b@eWJ3r8^?@6UqqES>t({)ySsn!A?5S4;Ih~a@ z(V`zc>H6cjEA@KmiM@!6=2<7+-e8AFE&<#^G>hr?=$8-zCzW#^p+F3Eu4tZ>KtqDn znqX#cNjyFa=wAn~hX2%u(B%M4&_<0=xJ?ehZeq8B{Jp6{8Q5n4@Ui4$%ZRKT6B_RIiRIn2|9iLo=3S;1c1Rg_`l zYYj3hq3pzGdgrO1&tmX;h+b{SJ8RmPPmtBDxDW9^q1%x6Cj1$5B^u?ZVAADSMvl#DcPmphV>jt9% zhwTr313%7_B!PoBJR50Q6V$R9xH2)Eej(s&B*S{u^Qeogz6X!2fIu#N2HxAQE z{2-aDbUp&+#cz*irO9NWQ$AxuzsMN+-GMC2G4Z+D0@AEwFbQJw25THQo^FG<7o)`- zNN0}M(#OmYuPZ4O;A163OrJugZSu!T8vF%ueb+vPZ;nOXK%FdH2^Yr$CbVK87T2N# zXb74p@mKE+V8fq$$Qlx4+S)WOi0e>Y*>;#~Xb#)JL7D(I-k`lM;J_n>4;*fNsI@ zncqFjwFMNDp5v@uzrj<-eh&pEd4NbN=uA(@yajqnKK-_J;rTD|Ez}QaNHs@}Z7xnn zbWb5{&bp8jKr9UzyZ*L>z;Al4JnhE(kd(9ug%rb23c7Ly%9E{WG7&y-TRaG`CPV{j z;}0&gE1hm9lzwKph~2>R3aMC=x8#_yP-fMg+3dn2mn%^wrVf@Z8jBpgMQ)9SW@kc=t-^mYw)0u4WY~)**XeSb=R+f`I>07(}s<+8jCbo z9KWq5$V@+IqiN3B0J#+rMZvf-K`*Tb!bhcP`RQuG(PnkJ9nf3o-3l#bn%{?G&SYFi zxWCm*gav#E>4N9<^HsCZtBu4uB4WEju0|TpdKV|nJb}du{8DpX+#h~ z|4jtEZ4rg_o_a^{RG8~QT*OeNcS)KGiSh<00F^AfCYf2nA1}QvZ_{F$J%1d2&lGpP zwOBjwvcp;MO^;IjtTu(B9|Wz+$?BNw11odJ<0Ee+IUnC7>9SDZ;8zzGN4U!LcfzSr zZkdof|22a1R>-!s2?W1IZ)q4>jo7)D#qdj#OrwISdyG4KF?3fPWT@j=KIddaj)eFr zNtnQX_{hj|!(``tR&6SmADB^@Q8f#3(_FSA>^?fdJ|9C~77qKxk0cR9iPSXZe|c~1 zSF>X#gca>T;OJXZ8mvZ8J14JGD$@`}ry_GR8-7RFpuKyu93EB$n+~H1!kcMp;@O3Q z!=pVN`$aW03&6eq*E8mJBm#zGa>)k~aKvKRgApg|@+vUN@W`G?_>-0x@R=7dT;`HzmPZu|90x|*~)M@vBY37H# zaT1i?)lI#v8Yn`U`QmxIVReQH_}=9E@*PEcsF>nbfhUn~!|oCt$HRXjStaQ>@02cp z$CTF@(E#?la?{7SSKe-G2pRuX#GGnt3ByXOisB3bvf8u@C*G0NTU5-%W|uU{wLQpl zS(JXa%92h~_b9~FvNz0+#n0=4zJTv|B!HAn*aR4>6qPv}kwwVOIM#44vOdKol|}AN zidmv*N0hFcF>Lfdn-AL9q za`XJ{g!Hd-s(lGlu6SW2K*#(1w5Iye{hg?q>E%l9{#w4{+#82LumnDIGODr*LE)SaU4~#S~#Yn5D8f|5iys1?2ldQHgBJUs-(PI++FS$sQS; z$CM<6&g2q4Q|+#gDRsfA8e7K|rwWAEXa#C0QLCFbl5yo3d&*A1^Ky)y`6F>k?1o;O zjiB?0p~r(CxI=O%TEWSxk^_steHQ3TS-}l%$`8sR>w35DpNd7Mt~0gt`Y>8{ajry& z?&mV~Dg(A9<3!(1U2X8SK_(E&pR@rEg(0;2mHKuE0b&jFkMhtSAhA(SM|U!_7C;Rj z``Xdt6vCem3H6H@s&HqY*7{&BmDyalKVZ~d7Qe_>i?B$vUxR=;H;dn&)}Cq0vbh1*Yk2am!a{4L@7xbBSU< zWP(kDtO!ZGqQDuydwc=gFVtzOBeSd& zL>-w*J#41dUA z$aH4bF9mHC>LSHfi~{d^*3?$BtS3fx2t3_LnY}lO{(rrbYLg7 znvQ~IncP>Eb}D%yF0GUl@I_D#{2N>@!S4c=pO@yso-jMxUBS z;BNR!cfr&4xA`3NCTrVTH4HAP$NXiadkdnxn)WZ5)P63;;qt%B%5xNj|G0CMd29<5 zP}M?~{pr2NGAZ89a~ZZFq+?>NN&Ql7;M7WL!d?9L7T^6IdypXCyh|vSN~wsug_i9w z-G<-z(;Q}adrLV>`Djk9Ma!!pc$c!KZ73Q;SsLD<7ZQo^baY;p0}020{zXMlAb_ZI zwUTpZE*L6ibJ^&1x?C(^V57~^YBtTe_|>7_W-4Do_$#(I&3B+m<`PsQ%A0F(7W zFUUy$fuc3-3cdSLwttQeUfE(|z9g3Mc(i72-sF1M3g#)R6Pq&q>U#)7&qdWq_NhnS zqwoC^_t5qMOpG!d3HddurpTMHM{SD1Y9$`QVBYl6zKZU+ZX97RF3!UT_84~%c0JM`R~5LBE?-K)1E0861*bP& zP1NhGd}Ftx%a>W^>lvg~nO1Gll_l31c7SMZ7AFnvF6npNmd8{+rm_o^-VUBO9Ri!A$6ocElx_fl@tx6r)_&<9&~F%Ll&|s2CZid z5MEod7^E&K36#MZRVw9#n#6WMe0H?KETWL`Q*wC;6=2Tb#S;qS#yK?$1#Fc!W0zFf zKQ3K=S(=P@#oq67%4m`6w)oa;VP zUtu4oRVe?f?(yl<+ym$$nQa@UN#vts`U58DQb%vF;!hZ;zYO^+D?Pm9sxIIn6L3vO zl}j#c!`HAM%>*y#GW=*VLRq5#2=wCH4W45(`v3G~xzhYcc`}KtnoU3|o8sG;n&Pcj zW}dcl%|5puFQj-&!r;Q%UL+nZKAroo%dT3I@zcXFR2EZ|D10GxKK8{=`BHvOqDLz3 zJ(?fCQU6Q|c7FNH*r6k_DLfHyHNcz* zWbl+XQ2!XXLCmkm!N?z-S-qTJLI#0>VhRxupkUrug~Gxjsa(&Gn}|(OAXmQ>90M6F zAbN;HG+A~`P9HfdG;x$8%ErPL%NIknjFMrSxFiP(qN@95b#Yw4whI5S%7Y6+idUVyD66_@ zUls6P4;Lb4nOI<7ndAKBe~~1)%Tlh;O#@r&kc*U%(fWJkiny{l13qeNU?K+7p2*m1 zwdk#E{s+1_=hz!>mTAlxvnM7}C)Xchc7cNO%s~}|2Q*`S;opSbkdW3n7>FHIedczz z`l0!MyIn~HwWmaFzYw1tiLc*>tqJoDgQZ%7{^8sCq>5e4Q|6tI34}nQnNiY1_x0)t zE72uTfPG^(fXRO%|AyB}gi~_NEt0GY?D+#B3xr1e=;a*hYotPB4oQOx2HAWfVF|pN z(sk%}i7sw|BaKMOznp}x)UHULXZ@fu&>nfeC+=hXi^-QyWH7>cvL5bbqx9d{TDP{_ zbK^2q+int!j2$ucc6Fe)o#!jqN)!P{|H@3=>(9V~g{qtI3h>23+2{tpcnxo0XrK~F z3_7qU>zuDT>npOg8WpQ8S4CZS>*(g9q8(g)5wN*(`U2yP@WxD{ibmj@ue|AN&=)$p zSoeu*lmz-SWsAUr%Sf~~mA?8It1s^(Wo6P1ELv>8_d^Wl0C3@M_tuyr%6(5%icExk zhf#DrNla$ng8I(Z9r9gM<~(`5XI4QTqS!efB)Lfwceo zF*HjA*VsuyKY)F~tRzjt-N~;Dth_Jdy1S)eaa#HDBQ=AKP3j#NrW5ipPr?m9@oqGd5+;QV;ZbK>eU{aAaS8sEPR(w z^pG>~HkE+P)*!YmWqm)XMDS}b47_ShfU_nD8fG+@ijYf82m9}L3npIX8P0Mp6p%}| zpknJwr8znB4|+X=09^U$O8+t8#nPEWeN7PF4b%Q%5PZehJRm{&tdy6AyrYV?=UrO9 zqOYgJplJMiWASTN<+&NcF%}8^WZRCXnQs8q-5&UVOw6R9tlo}q@p1-rqkPc_00^Zo za%hoI>(n?9d$g6Anf0KtRKvx8J#S%-cinPCbV%LkyXG zKF%iWnDc{jfgxD^sPiie!z;ALv-MOHZl>l*!-f(sX*LHt1=O^AdwqDYnKnitdm+r+ z2~^lmD&hy1?~IoYK-gcCL@56=Qms#nFWTy+h=y0qSHiL}IAjp@&h6t*yO&s@>%nQL z3q|70Dk$v$3eiTPcN1MWUXPM91~EN5{VRRxXoKN(1W!P6tsoZ3(^VstoD6ILc zrxt2g_5S0UfK-Xw>E}=lA@RU@&DaJ+*d{OxmMm3w3rZD7UX2C;Yi-o+whOUe`SR7h zh`R~K*2=_|!v4evoJiB)+@TP@eSW9hvH(<9$G;wC4M^~?1sk+5&4CR-w zrQ{#Tf`0X0#NzH&88pt2Sa)!X{(^2}U-RBLjWQJfJF66J7k~yZt!=La3_RLigw~fM z;|I4PfKGz>qGs2=uMBhrrcKuqoaxT(y>q-S0HjWJAW6%e+LHjIoBAULsHVMi57M?5 zRS_5B9c=uJ_D8I{sK2zV36Asxs)YAPZgsXQv5HKk$kBPZm$jxY&*M-R7M6}Lh6dZL zd9>tZYBOJvA5t@88=R1@ASZU3o2}=iF7F}htA!cY7L6lJ`UAd3bf-*M?@7xt%w&Ms zkGUMd$JEp&FXtKKC3(CgTTSRQJ0s?an_^AS39#-^$q(uGVe|yh*Is%|P zu`_qS2-Z2(HNTZVMqV2jl+j*yKI{Au<~Mng3T@zv0rf;;q9&&{b&pVb;Kj@3StQaa zfAN9E9i#J(R<56LqdO1Z^xZ*92FOGLi2kr#X=uD_pFD4>8T*ACel42;S(9%TV7t#- zDiI7Ux@k8!_ zFG}HqgEK;kwfm(kS)K?%x0;L7rb!F`h+GNSjgfSduIysUgSJu~FF~VkX^YOE=hXGm zFH`x`0z62+#l2GSd_|$>-Xd&)@KZ*NK=9L8;%%w?L1R5xl@rmf9(0lnDJBsT`n2; ztw~r626$&7stb*6gnq)TMv5yQm%7{e-mV)D-6R(=>EQ7$!FMAhoO2DlKe4*#~Kl$7EW!aiFY-Xyx{>1D90nvb;9t|LbIvK8b zCsLZZzsePMFB~{<^Dmp)Nk1D7dWN>%Qv8%WnM)GDs?{$|DZn~=5}WSo<|?52Jyx9( zJlmP<9l#BA4pWoN4-1REMk5vu#Vp!njNZ9I!>m%e{)}6hlpgedVqaH}pK|y7$Id*a zZ0(v`}PMKVxYzb^-E;kg&5E*=GL2NySlnU)dAr z{MUKl&iHL5=W4OMVz1!%`6e=g0V9wYrs1K1sCb}R{Mpti*;?K$THgg%qv5S|KQ{l~ z12Ko~VxDk1BIdi%NWV_hU#@ZD64|S9Xf4!DF!ajx`h^sP`zYA@NMX;>eZw1>Q*M4a3x>X1s>=d)HjYy~nR z+sd`O9g6*sz$~Cvhy-{EE`Zkpv;p#!mIZtBE{~5+SeQ91#F=;PwR6A$8PTBob+lne zNbF+sAcj@OddD|} zMo(P?W;1SOZlccj?JiXx*0k6B#!zb=Oz+{;tj4{RlGIvuL&gWg_t9aRLX7!@NgBqX zaj$@Q9Q#|x|G{W?=yJUoLd?xEJS+9!x_TTbGd8a z{X8vwX76V)0{+bJO0v(yr6VE#(!ctxc^%7oC%5EFl#XXv*J@tl)?aL{dR7 z=Y~hrR|i>ks}=ebCb0o+qbBaglfZE6N!Lk9%H3?D)y#~yE%ZJMt;F#68y2{(YPL3e zLYJC6TAIC?>Iy_eg?yk@kPSr0HeZ=*8;TVLH}yW&b>f=A%0z#2%aqo^HX$U=X^5ls z2?gh2NXo1=Jae1y60E9E>~vQtW>oFc*R7#MY=_7b5`_gh0vL{Vstg0)03t&&;b%HO zsUSrwyoB%&hj-Th=#=xI&ml8I_T8&G1aRuX|EageJ?tow)q$|wnrU7VL+r#YPM&O~ ztbvPIS2<#U@(IG zyf80$&EJGk!6tVZjOU2VcKX90`;Exyk-0P2wvM!(?u?4_B19P)fF9fI?Gd${c2{;I z&eV^SS}4gn5cyLAH}hDV64l#>;yk;U*V zC$DH`OM1q*96Z}NP9*@H7>;bnko%UEwV7C##Ixvkg9VDGUD*ZNJZJ>Cq@ReCMDG70 z7vL;sH{H{`P-C7&&l&d*OKAJ*kwtI0xdIu6*~mMMsmJO-wO1jlj-DXTyqisAjm$*{ zW>PdpI?M`$Osp}G!oT1nuAVDo20RVM0;~3{>8Mm@d_HX#lEAZl`WHqIIF<+UHnUnGqwD&`1g_3~b;E9& zMFO*lL{9h9_l=TC95U&s@{>x3Waaf_4_NllPY!cW)e-B5oISICX8l((?02eoR7BbM zvz3a3{+I-BZ7$C2fUJ(~y0v_=)P}G)N6+Pq{(KPhDB;^-Lz7e8s*@yd@V0a{#tl9p zMv=u{qHm{qW@HIJQI{L2cKqU?y0lN_A4pEb=4LODX@f39b*hT1PJN2XKOXk_;w@hT zkDLaYRWXS@NwP+!vxV-hn5kJy&Tk~isI-F{0cy8a$F4M9rQv0HxG$xkJv<_b%E7zo zJUSEZw$QPyXOq)LvY{+-pkaAmc4cyj-}!6b?jgPHNBy%B0#>ori~CbbLu1NM?sH!% zeH0tiWy!t4^)zG!ziT-E5Q*pirBB=}IJcZ*uev)+GE%Gt>fIjRlkEFx?Bf@OL2B!G z?c1?d@mC2C7~n1&^)PWhZKA^&y>U|(Y1DoC+kJL^E2P8Q+FaoIM$!Y`mc^Q`QN38F zCF+Ff4C07r2|aK~LB^WAbDBJA3ex3Yjh8UH$IWB(*NmGa`Wrwa|6FvkMQOVKc0)qy z+fE)CB5C`a*U}!{U|MDa_miIfhK^^BHbD;dAPFRDQfM3S;&00gm1WlCmnKlthamI6 zph+;;R)rKpOS%70q~rZhV#Njbp$woibhqIa_sARBo`kPHPjs3yvX0B3q_I=hD<)d8 zaMTm}BPjmZL%{PBcC^EP^|+7199@7pLQo1JAMq~G6;-v4E^22S6Ht)}547`x>Ur1Q z)M=3zYUIJD!$`2T0P?#yxPM~?Qs&h{y@(<^t~A6e2n*WUq3ZzdB?szQfcS%QPhDRb z%bE?X3|?*J8AR)mxQ!j%W?>>dJ!UaAX&oLTiCWB?d)CD8Pb&^H*&x@EkG;4W+j8@% zV)aC1T^$s|d-wg(MA#mn=xsym6}^Qh0eB^|p|>bYLD;OGP>V0_Jwce&#z2`O0)kN8 zd5K^Ngmv#D3>CCd;liDp8RUb<4sb8SmAE%rlraR#g1M_Gf%m_S@Y{&ygD(nJzCG;6_PjROz*h!g&w87 zY`DzGHQmPs7_Th)ip{#CQ9Gu=8WwzoxstQ&epzF5jn74M@&AbObpRpGhnAwnRZ#L4 z17WS7^gFuxjy}*(Qr0R|ubm8H3Ff*Pjqb2DKgZ$j-rdQ+sO+nN46P8_JL3xs%jsLz zUdTe&jm5?3+-Xa7JtjAgbuyTIgwL)@d&n-R&6>x+B+W$e*sU-;7} zA@7$<|Nm=0qyPK~$AvHE+Gg!nXy%Mx?T9U;)z71{YX{Pdzae2dY<{85MIkhg8Fd5? zad|hduSCL3u1KX@&Fo@~MonC# zd2)ro})_QLhIjL}$4wyUPX?Lt(NkOub z62oS!m@gMr*SPOp5*eEZQPTV3oifDx@YT`c1cZ(aa-RUoR3w8F#)NxLk~X@L%nOvF zMOqu!;#3dEq zm$>(D|6l6u(7+*+m;5$&ZivJN6jyu32m;;c90b-c;Sbf1wku5AK^5jCY}bUZXcC2H zBOioCEv`o2n%8@$%=rTDA6{(Rb&b)#ZGssKY{H6PmS|+o{xOh|l#5 zaD~LuV~r{oU6BoIwYtvTSpAoIpJ4x?eWx_6j!IlkPmleJ&HuQI-r)~C4f!@ME0_umUGwQxv}VmI-~hF^SJ6zX)4RoPrxPXoa< zx0i1nFcK_OKzWnk0KrsN5{-7y33FOYDxV=C-e`5Z=hD0u6FUB{9gVblz=y;yxb_OEQxABF2@L&(zvg zy7QreJT0aNPy*q*W-2y+hpUP}&;BBZn^=ggeE|P)T`(H`4#P%0=>vip;@IR2d7*^j zJuRBtKo)B81)+4q>-^*Mx^rPaC2@k+fG1F-;U=n=EbYa?_2_2yFwEWkemnKbQ;&73 z(Hv9#0JR~6-&=M@JuL4=rR5k9_M75y5Y5i;o`wDv@fHv>C+$F3uXr8mBZFd&3qyL2 zR((RPU$^3OeZ@5$-Xr9hV^1i!0fd#ToLUn0+CGn zXZBfLFes9fMS~ogcssG-HaSF&eKt^~E(=MO8kP6E-nW5YC-dub#GplJ%z|DBYlKO> z&ExB0K|&hi_fnI;jg?%BP>}!L)LEBs2+Z}; zUWNfW3OS*6c1=#|gY2Bdn`HbQ%lNnxDSUTHVDa2Xlwv-Bt@>UI$X~*&4K0l+7%}E` z(qO8eQ6biXULG@|b82KrIWpKz za?z<@)itE-y`jL-m*XW}J_H5Kpn2??q}enznA>b^MFRS6rqQycpOCCw;UP0QZZ`}+ z0#9b~vGj{xQ&mK;SBFiR%(QhxtWn~!$MdBIn}vEH=)Hj1=LRry6w0;U zT$zu|4OcIU`4QYcCef)v^U{t!TNeMOF`IaxlTACxpo6MG;g`eLf3e(XKHWPq_~Jl) zQS~jA%sKkQ39|>&p50ppgjDap*0f)g)VfLYYx8aFFHNa`4ei!T)-4fK=_KJzIbY)h3NI0SS; zTZMO3!C&}JkK~!$;JEm(q^BUIkM@(_%>6ppkl3Pi%JqUZrHa+Ym7*>G3bL4_!liIx zcqp!u`h3b0y^S5jg>~`(wn6}?7VQ822J1jax1e5;{yd3g0=!&HYkgpobQFcfQL0SX zM4w2{>=Os(L3-j`V!wE(^fWUO*f!JQ&Vk|D#`t5pp%Yl`bCTe`+n|60UDi-f7)pv@ z(JdZBHb$NF%>da!8XsESZo| ziWlpo;>_8yp7JrnRE@to9n+(O)GtgxAE$NDeM`f9xOP8K|Kcf&u5q)e>;WjSS`{py zD{=m38rTsR!b!;MI**S%`-@4;b2IQarSoj&&U%0`IM6+*^dF1b8UZ_YP+4WCbhM3D zOlT6?iaPiuhCOPa&a`qxkzBok^3CD5KZZbk${k|Tz(z*05Acm|tAcLmdY!c(TA53m zZ~Z67;*mrBF4&q@sbZ!n7qL_4nuen5BJ|rQgy=^tY4f5$({D^AP!q){R~2r|t3Fmu ztY=f?R675WYs(mW6H3**V7AQE$4?mNEUCFK;`O_oCd^xN*IK@KGyVl;2z#N|38Ldb zP%+>t-qQJ!kUk&wpWwbTJidq^&p1dH8pSTf!yZ?Eh6@_Wr_YGViYF(mxv!-T_6KDy zetIMsDw4qM8F+h%ABvS0FQNSu3|d-~SDUt$>g`eD^!GH4&&qH~LKm;`R<9-Dz zAI+RjM#q5#IicKWgV(=9r>NgJ$zu+k~N^cfP*gcD~-V2*_k<5+(|tvgi!GbrcMoqdmDuS9?Mmjv42 zVR-gbC*eDpi^?m1Vw~Q)RL=Te0(heyI)B3R<=a#50*JTxfp%#!I#(J%qegCzj#XWa z05lnksyL8)CCrP9!*-qD1}HAS>_Dq1rLu)t83t>~jRY~6ANuSt!?G~{nZz9drvp7a+bj^)F6fXu1Mr?ALfoh)9%O!gUfztLczQ2<5wmI}IL$5s?6VBk15 zQ5128h5B$&s{ey8ky=X%-@zYZ2cG*BqJhzpW_i0h53Co;D0Au;vt_7dBu?OtfFo0ws~N&Fa&z6^dlAQ2_4_i|#BlOXT0L9o)QNm3;-1hirhaoc zD6^y9O&AH!TAc@7m=SH^h}YLY6gaf1!ICOyeN~uvse~k&C>YB0zGaaLqgt=n0N^f**!(i<-r0lh z8eHBq$nr~VuJJ2wf&@-~7b2+IsoTMN&WGDWA@Umq37+?gNQUp$n9Rn7eS4e$N@^=Z zl)(lWyYV1T)?4iQj5F$iNAy{taIzW4tu_@@P%&VnIWz~=Nw2uxxWzcdfi&AgT_t?; zwtdwyi9E~dk_?Usw;~u0;wL)Rps)zmhe^1da;NR@rIGc1l-xX6I1WWUAd29ryrg#! zueIrPGW7>I7Pb$Y<&JqXJbgoqe&9j%&Jn&rUarv{Plgt@71oNQfcpodXqzvFW_k62<9Hp7bm3ng$(tyhF6$PgpFUp%HB)1H@ zX?TiTHo=r;*#vttAXlR*B2{q!M6^ejmhGlibBjc#N)8+g8h7hFghJyEkXhmmAL)dVt(TXk^TaIi^8`!WPey2qBDLTM z>i~Vld70y9xEZc+L6{kBZ@h?2W}@(l8#`SFh>D39lMiIFnKmDnX>e+*@MfE)J&pIL z=4=^6Qc3c&q6)EsVb}qR1$6hWRRF44CIUPf5xint_#Je5tn+t^^Mp7D1#tKgjm?vX+x zbng$iT(0ZBBsqW`!Ua{)YNHs*@W;cr1Zb;Y5K69@Eyl28wvHN)2xo^&N*})?WjxP3 z_*l*FUq~r7+ERZgxq+s^t&D;*-&RJdrAYUq7ikslQgRS=`%Z5Bc`Mh3F+$t+FNHoV zDNI&-A+Ep|kbp44((!P6G=m2>Dm2S`B1lxXv&{=g!3!F$G2>JeI&5CYXtc!wclE_2 zHcx?gllGZc@MXt~2uHjCt3(qwLjIft<4UI#H=tMU%Vw(sQNw9EAfY6OGPn3r2d87& z#{(s%{D?R~P`Kj`8CQ&7uMe_4Wa;7n&l};D2>*=MC_3jV8O$za^e&_DzH^&M)XG_( zn6dMc1C%j6^R&x?s)izPGrzNb>)``_DQqfA`3<=nGzIe88F|Kb@(dE!q$Enu)!kGs znt9Hz2nBWYL%Z*I1hiyU9SMWRg!3rsy`;?Y{4H@oO-p{BW@^@gOK&Q^zXpf^?*uo@ zyDwwpK=NLEj*>-sDW7l1eT-h6WeU5cgl%gGY)PQ~2z5iJ*rGxiE@uZlyWRe^tmp%7 z8)+r5L;eo(r4nn$-X`v;+?Q1CivuFyZyk$yaNsSma156#CBd9L4(6PDXEvmIcyx=P<6pd&~9l-7q{~ly(r8oe%8%I|%ZBjN= zEUCgbp+v=~(vJ1PN49Jqa+?RC)g;E+@{Bxky4cTML5qc{E;r-*(YVc^-u$$1&c59b zw>U6#T}wFyJ7OD4@WVDHN68l!p!>qzpfk$Sm;Y zB{`&o^GMA(8EOdxAqRVO$G7Z0o;1>V;h)6tcQ1H43> z8OHluIi~kt$LW!|RXN+V@|@4vJQ<7d2?a5;BL0D5R{|7OTA#wo%&jGSP9>W5q>~iQ z_)+LuT3<)4iiZ$qu4?*W6l_hwx>ljuENzyqkK`Y4@GZaO^CrhPz~uEIo@{HFO%x%E z#&J0E?L6)`RJ6e^^~qI$)^oJdblG)7&~Y3@#2G7IP)d>!WR}Mt5K8aEeICS; z0jme2|9pQEb(WfA4$9uPr(I-MQ6>%6dewSt<@KEFG}#JF5jCO|^aZrIE|lp2us_uD zs&M#U|9YA5Ca4Um)zL2;9HN|btJ0+y2a~|_ou9Aa#}|vOm3U%GO?1Mih}4Lh9?M=# zf)SgbXO%}bj(PFr64rM880q8(A_sU>Y*&SiYTMa4vflRHJ!ax5izAkp-k_xg{20uc zCbReO9KG4?m@WX67ur>(s`nxzB!Yq@zGdje+_v&i7016tETmUMPK|q##1>_2|7Y zV7e3~5wU>4Y4R;_j+%3Z_}Mhi1S1K-lwNcz(e$FZWochsYA}t7it`TrHTwwE3l`wx zfM7#Na8x5di#I!nYb#X{T?6`wgCIswpVh_dfm7~L@?uVetE?JR>>#bLKFmz!y)~t`Vde=8t!N}Lb8;Lc#<)975Td+GN&oqX9vt>*TF3nqJ%%p8hn#tH#hZj)f z*{OGJWpshc*U)PizcUBBc09ELeiKc zy?f@=KUL{0ddFNd;J_mN-Trw6bX+f(wBjW_g-g??oKPJOGkQDRPv%E>--DlAfN=G; zk)q@v9VzI6nef-(FUWRGZxu;cyU{^+C1cfR30yXJF9*nT*hzMtJPsH zwpvBmdn==JLhZVbT^h+RnUto&8}RuV{t*RQ-51$ zjTrXLy&i;aQII{4tSDK%6HH7I?qeJRNMlEA_i6>Nz>wv70TE75Dc#|!fFyRZCYqvO z;uZ;Ys{dW4GltmIKh-xXmCA#SAj-_3!EXEWxB7EHVQtgNM|OirXs(36g|bA{+GJ#0dCk?J z2C+U4vb*2}4g=?H*Qucd00MY)y6q%ObV1a>cEZ(_IcrCwP`SUF?z8fnj^*_$Qeff@ z*rlzf=ff7|V%q53TKoEXyw9ASuOZ;`a?<_-VoO6)2#F{BhoZJ5AdelW8!FvV$w69*}R z<~6Z}P#%=>l6QQ{*A-+t8_E+6<=I^=J+15*>>^&iyq|4KFloQF&MWgS< zRyZsh5bgMcvmaIMmvXqvfmpCO3A8KSP*Ix^klnDKPCm%n+Z3`iKG~)UaDB*)Vz&pKdh6te2A_?f?$r@$71R1PLx1pkv2wIoDw^0>@Ac3~sS|g7dAg??FO| z`1!w_9;Y+ail~v`=4Fpw*EbDnX88Go@8rUm^z()qFaRMbz=9TAeyS!@nOe7;)8nkk zn;DnGY-$Q;(nT~)=itR65a8Po9M2NQt23gq>*VGOnPcM0xiM4bZ;2#5w5vYL3LqSW z(ryt0@?5@Se&9*)fnC#W_C2Z=@p$_IA(@zrSDa>B{Qh~4p5oqvc*q=HPkarSC=?=& z{~>Y45y~6|)&Cn|(B)rnOp-|ya44CahoPj2b45iltT8EQhLeP1>0&>Db0?Y8`7Z*Q zA4KHo@bxNU7O=f!)A5&rW52t{_Yrx*bDBU5wvPF}q{V8z$u!1Q#|(uu1` z8S;%JG+jXe1!$0;+)%5|VEl5{w03@WOibKNzvG3%&j$GY6LHc`fV&$U=#EJirGyEH zl>o18eA9eqHUAjvCz$sj2knYBbf1GUi><5Va^6_ayg$wn){T^HR$m}}U}OD!7%K9D zFp8tT7xmFED8D$CWT6uhpbtYw0lB5J_C=U#uH#=)SxJA8s67#%+}%{j!^jGZ6gC-DoiCyGq~Qe~*b2cv2oDzIy<+L%yR?jgVNgXfT* zXr$D<@UkD4hd zS^<3As0~w;`DQG?{>yeqU((V3h0=wSeC-^iWANDMSj}1+@x@aY39t?Z-gM5dWQ|6T z5DCj5_=^eTZ*>h#;qq`X6jEQ$_{O9Z*S3;2?X1T#loU~~Ov54GQhp>Y99Tmp+qs&% z_L_~BV5K&hG4QR9Y>`{pZLG%HHHibq*E!|A-O#xDQL~7u6E-fEEvoV0m?5?h^OOZgF_Ke$zf$+Pe;&WB{O)T(z}((+ z8&qdt2{>2E{V#25E?aND@l)ypHZld()xa|}92!X^9Makf%nk{>onZFW8ie!v?s$tG zFvi?aCs}HYDk*Az=-U_j%*gj-nXaaPZmd>@ovW{+~m$8N|)3iT2TNdkE z9MaBO>3jVWlHboDmGP2etv+|sYPvYrK30wX^NFCNj}ALUlbO(K&Fh1qC7Ze%m_jSm z#{;ND=N(TW;8@#W@$h-lCLO!+p}l+b_1~UH9hP{KB2J#43N7(pm}J80er0zIjk`WY zqzaRe1Q)wWMM@KS7aJgbmELVGACHpgJ7Tfj*RUs|o5Xl+^a{h9b>tiFon@c(#)SC+ zI+?QTlQ1Kws^9ew!87Fn?iLFE!(e!d3m~e$>Fpxt?BU z@BtEvYKa&1A4ZyIfZ!!X4dbnLG9;%PK5RL*OV;-PpekT(2jfkN%y2AWlkGf14~J1@ zrP(Q=AGWkqn7BiPOC}MF_`UzH!arwN+<$b=eToN{iCf(Kz%baf~C+2!#l<-+dd{B?+GyuQT}%=iaz0-BX2N089vF<1^tvV``WNk_kR$!BIMD zhDkfm6g&JIsG8y`u=%Ud6qr4e1hxkf6}>bkOS*!hk*2``g>- zZr^TWaO27A+ ze2n54S(!luJke_r%EJe*0`<$KtK9=?BO*ldwcx;Q)4L1ET*YFb7)q@po|cpm6|UtAgSZBK5v)9~r;$W7mQLZFqFS>O>uU9hf|3;sB* zLkQ0-cssA86cz-mghUH&cWfC>0p!@@G@XUBB%+T$lQ4W>&x6`exR(!1 z7p)8FIm+@pDB5`;K58uCfoY_;wG_~Z)9IsigTRuAy`bl0b^TwcHY;YyrQ7kS@$H(x z_jW3c+by)&a_|93t;=A#HH4TOsaG1g;tOY8>GjmSzXn1UmUXo?rLe|}Y3UafY_F7` zdtLgSit>>AAU_t3+u>Wnzw-pb;G5+oGko*e)MI2F2#);H&9xa zM`7pnJwZ^~7E~^}9eg?3cxtR0QTavkP*I6M)=gsp7pKJ#rF{l)4VX7f<6(%m>|6}O+FIjt_T}le2hUlE(0{(u3EWkw& z09lHtW`oHsA;GxQwdoq&RHGz5qcnb;%9VS*KGFq11S5JLigki zcjrruxuUCRIU@+(EG@k$A*R`3MdbNl8(0*}_g-)+(&HbXCPCIHLa48UQaopg0F=rc zl)gyBAe2?iyNSqO@=EWpx!0tFKLJ^+tpf|XOZ_vA$J~qC$sA8I`ToZ5@?Pbxztr!= zExx)Y!$e4s&8^_a`~L*JWDy?mqJL{*Av{et@h8v5hb2?Kje|s!nx%ZPJfwce?M5?v$3T_GSRP|G^flx8&;t4zzU?rE9yH}T7 zE#Va>ok_{{qzA5-JS#{Xy=?N zie8(mwpN4?vm<=}roD;+4#j=J%Pcp6s?;88LQ%e|q=nIL^Am|cGuLbafaxf%S-~l! zArseGXfa!)IBxQ2GG@Scpw>w>4NA^L77sD%olAwyfj7}y5*(zSO}pLH3U%A>xYIuy zxwcj+sPJ&6(Df@4JvW_ugXMxN6ns{13Dr~L{iXHYA%FU^7~Gn;Rpal2a`0~$O5}%^ zPX+iE<@;Ge3aQixmT9RNU1{DMwn<8U*Q9`*g?c4o*qmnf>&ld8iY~QZeQGjV3Ky!% zdkE>l1r4sVB_Jy2ueY5dmfg}y$K_9c|LXGlh_Yk(m%Y52fdhYM64oH$ zw+9Wb-!&4M8H@^BG>Q}*WXPKcU4CV=cdngtnm}?K*Q+XjFGj%y=Ug5exzn^#ppC$o z-Acoork`r+=@ampUj}1*EsHZu3?ESm;9vPGK}xlEeqWu}e~eFfqK+rPF=+?qJ_oHm z(vHg&sV&i{TT(F0{qbP}0q6BP>HGp^*GUX)oZg3V!by{X%2bi3d;JWxW#B-W9*w$n z+43+6d%Iwob-b)H@)oME!a4_{;NL<%5y!6+frF$1XT6LHZUvA>6K-bkX zPat*Aj0#`R+a|=4vCvisRKFuPz>5DJL+)4o1I>P>dPL#`>pe+W_A9vzD}fgp0Xe#- z33!gy5g3It@Av@ZE50f*bA9@Yyc~f=ehbVGLj-xk z2Hz<@&*Z9*~>&`G%-2;){Xvzn!Wm6;l4M!KE|G@ zymn+fAmdnrMt3NgaDx@jv;L*riHw9or6OxF|HKDjyOSD#w;89g)1UQi08E`TFfYEl zbVR!f?%B7SvTUDKdVLTH+q|71cLn|b5%}3Bs!TqsiLz@|SAtQq0b((i`+p>Gj63SD zkx(}1k7bCyLGCJSuQDn)NGx?O6+)cRy?<64Xi()|p6+q2HWbQ_1_J8YQ7w&sh0#MP{bt1oQA$Z}I{DXG%BH35{1sUOux0IXh zfy-vV`f?US!Sk)LEv(IyYQvxn(-2)66#x)nHc+ED zC3rx+Q|Zpwf|w(jimuneAI;NuuT@vY^^!)|ZT4KlS9z?>gBnDorZh^CQgsXbJtFb( zVFQsC(I2xd0|-nWOFUQ(383z5;JbeVGRqh80-aL@zUF_>^hbZnGAtjl4zbw6$+yv3 z031+am^yC>&-2_xTC3#TrUylNK;<8mT>gq>|G`$MjZrBgx=lo+1#o64B^x+Lp}z@d zWER<{&MJ1=E&HM=r`dAm5lz^lCodJ$F|^tOp}PnK`7)D@j1v^a(@RXVgv#8*LVFbP44J;h&J0>Z9JA;}V$8fdF}dJIh7&#gr|sV|k{VyHVrq=pn3JDd!yDt`9&>AuY>J zy`D49jUfjvRBvBBQVA|#4Ke?T#SLt-S!tN8kDB`$1Cny{gMQIrqe|F>h#`4?^>`fI z<{e%LjYugO2MetR;{f*R%!-B}_`2lPNK-gT-CiS^ZnhXs2~g(}TBQP!_Q4;ZiqLo$ z{fgn;yz`6PW&}?jA_ye}DzL{sKV4G6cetSvgKQAJZvE_CU=9Jq=N6l$RTcQN*nG!H zRK!fjl4o5XcrELU}$;`@CIjFn;cEtzj^hyrh(!gp5Z-g5;a%@~))*iQRb z5W^X8I;Lv*p>e(c0+Hn*xq)Znx64XTf$}4+brfmq{bQO!ZURp8m^W7}hq!LL`#ll~ z%BEQXiEqq^5a3u!0SksRD0rxWg>zF3W!|+>eT6}b3wbw-0b_n>uDK@REg$0iPKkp^ z@6z#P$^NzmD#9q58?r9Sr?G}ZUeL{|_l)D| zp9E|G6<*&#A254RINVTX#?%8f!@uSrzIAHvC{SE`dXuFv;jmixlNTnOjZ{^ zAoYCcY@pUkLLb1I9g7QwQI^A=d{T6^kL4OkPwo@Wv)08^qwxcZOKBL&xQa>)6T8U@ z&{#^AVh_x|NH7(A8DJMKC3K)Gy@u6Cl|deF^Zq!Dt{G#JF~c>s-&9_{?YMay(93G^XVh;(4O-MVKJK7=%sJ}n984qv z)_>1MaO`4PQnKOk7%iQkx9{N3^2d;@bTgv*uPmE$Q>tw#z~O0E6oT#NJsJ>>la}wN z^@kZ=oTEeQ-SRNS{0xyU?NOYWx3caBiQjD*YBZ-k+%|4S3Y;NN9aD9@!~Xw^H6Q_= z?yW#H=#(m_H5GR3Ph?A8tdP?=F>XL*&dt~U|LsL@be(8i=-W+nhp%j^Ei`~uZICr5 zl*=!=UEBo0`XKj|hKn!#GV}T+5u!;m94W*io)31MmhoFFu)Xkme;e^n(#=t<{sT<+ zj+dY+G{tjQ*8g7;H3a@wmfFych-hq_)X zHwWrvzmA=1hJwbScc)5m{QNq!$(@7!e-%E9Hg}gqY4X6`bmf1zb!IQPn?kI+_fa1^ zX_)9SBBI*Ve)-c0`m@aa@T(^o#< zzT67szm>~EXPC0DvqN9IM+;ZDue3ZT8CpJU_z2fFiZLXGqoAqkJH-J94L&Sa_F1$y z60k>om}$kJY#7q@A4?9~eL(i+SeaS``Udz*K!>XBKQCbQic}bKUafMyCOlqJ9egF~ zGkcjYobke^H#tn{c;Tl4tr;w;F3JEi!&4d?bQw_QkA*ncQ~`;44>&YDIMku|n<*ml z9&?qtUTRMZs2ZJF+w03>@8n;a?d9N96b$@F$}Fl;+Dc4u(6#mCM0m5ax-y89^rn(4&ym z%_T@wUx?)}K zdIdbm0a2sc4P1X`XXic7=$8Vt83>B)$w#9x3?K1HU}nPbZPL9CRuah30TF$8PMf za#vyN!g)@A{;{)Q8n>TteXtb1R0~;-On>jNEq_7rMG{kcCgjHqmd|j|ImMLVo=gTx?dc#!{(QZcJcZw%Kq_b89q4+en?3Om z6RaPlQ|)_&D>P6gW`@Y-|0522qzvQSM7by>_039omJLd2gV|qyTWmoOT%>t^1fQBt zV|u1(^bBH$$FKh}GQ-qUcTD*gOgVEKsx#2f3r8Uw!P`CORv<_m0~;+%8y+g=wv>*C zv3+Fpvy~Ol>e2+Jtg`+7?vZfpmgehg*4jHmLWA z(Iyik(HmRurOZjdcWQ)*@%z{4nEX;&VRd#E&OZB-Tk7Mm(g4F87qw9pxM5rOg{rGg#16csoh4@ssZWI74Vv;cdS*muG%|A-JNRzglBTrl> zVls>fKmZxw_lZY0mZ5wF2;b29eNlLyt<#e zU*!5uHv47$i1qjjaStfYt&u^JV^WMA#&nm^eJxX~uHXY^UN*oZ3}rIlz4MgTbN66N zjm-hg%&94iV#ZWb&^(iP(VUbABt3U9zIgYY^oMKN?rUYL&&mgXV>>^DnpeqJ?HR6t zD(ZDb5*pOe^%wnwCTvH*+G)N$g9Oi|EriA03|yRHfR|$(Nfm&|$sW+V{MTc9_C*fV zd>jYmX@m|T&s>fk&xI915i<&&5L&`2p^4c{TKr{Nv4MCklE@MRzr#?N!B08tO~!sa z&~XCO8q#n_1fNH$>q6L`|LoOP!U4Hx=bk7;^YvMqORXZZjUkRXNZQ_#6A_~_Y!3Ak z)j>#`xyc3C&Jo6}$CdekyV0Bt9~!O~ncjs5Yo2C_53M9(z9&(X=+|~bt$j^l!)Mm4 z6+L#gY92rr|98K5vfP;m6h4nGeDn)M$)b(u|1hLuFCQL zhAJXRt9DxvuCN9n2;e_2*I^6jEAFw~DhXE|dV!CJO^ZxTLlLATmtrPth}^35t8reH zu;70K{uT<$5WYz|W0?ajhgjYfSUo{iS>TD2?AF6WwvQ+=17r!EH696-iW)#>s`doT zNG0j3QyzRri;<)6$~3#aWW!-AnS+6kY=xmEjz{dkG3F&M`7vP9p?I1v{y!n%j3`Jz z%X5JDrTqfE`Fw=XI3-(Lc*CEj>p(pNB*45+0AM3WjH|vQY&PPe<0X$*eTpK6^m#N; zfF3|v`tpuiJk9efAK4@Nh0`~KrVSS#wen2PEu}v8mrw_BS^6w(nbxR-^b5KzSKY8{ zF{H3z!^Q6RWVN<4^~p3(!V+-$g?fFp#Ea%F6HqIdqoV(_ViLJt(g`|-t7oK_R5JUk zzOV|(7kLSwteQUd-}IkXMBW;ehsUh9*M8po5u#Q6pv{JTue)e@ZMh@Otf8NRNLkJx z)8P%TsS|JVzo7)2L3Y{7Z*GS6$q@A@vE#8iryn|q5p6OU0VqLWJ5@aqvzw*O?etl; zr~8u{g4x;&6607{pjUkPJRV>Xy=YZiw(<7M6!NfbJQ7Y&I)_`wM5qn5jv>!_x#Zxc z9^3I?jI-mM!y5uvaL6OJ<^RPx+hg>rk(g8T61h`{t`d6MF}{cmXpZmZD6Nf%<>Q-& zq6;&=B(>*Tp558axczE1jDsVyyiC>J2dE}1p{Jxcv#F4Jn4hm8dFNQ6q>5~kD;H8- z0`PZ_R}z50Q}o^DSvbfp=RCz;jX29gF@ zXqHY(p5K^~{xeJN%_p?2%g$MH1@dvzf4g{;XFZ&24BUBKa(2A@EnlZ1{`K|)%VpZT z-Sw`^2+FIZAMgL!oGQwEMb4lA-m?gAi;L7sF1b4w=fb(e$lhr>C>YOKxtn4CwIjZqph=N=0d({`_hwqX zWA3N>vNFwU6{oqyu4B13mweXooF*sYc|E*Dbhd!ZO)C2ir0+Jt+3j$%Qo^ge=u zW1HH)Ga3Ij8ZH6QOI|HOjjyo{Z3}VMhGFwkKUIu9Q&Ujgs|kstd12AfzI_%E>XUgx zs)Eb*KTe&@KBHc#_ya8LZ0`zsN=E`+*IXWLPK5QahozXulDah3Veyb2G)3&xLo5!7 zjrwMcNEsUC0il|WNIPSt(NJtjD!M9e9BbTErtO&M`lEibER@Z-Z3l~ICAZ1^a-B_7 zE-xruKf-sL_xR=V79`qx>Yh-&p6nPI$$?7X+ha8Hl~2?L%lW?B=%Kr21JM$9SJtm( z!tdTROndsNcc}AmAKu6q6cY%>M}C8! zb^xgCerMUwp#nCRNq8U-rXT4_^oKsM2x6CVQZA-Q5}%{>wx1kTWK0Z#5pe$ROmx+? zfDADwY2!5l{=^9T=EXR7Z9I7sq|qW+Uh)Ge{x?a`8Qgw+?t)F>;`U}F#xf1x^~}fW zMW90D(|@zLEi2}JkCIA}h5kq}k8ZEj62++}JS9T6U?;OTL=82Z{k(rT006v)+#uJ@ z4SUT3CcA(>kUfu_`}P24AI6a!RB_g{!>XbK_vT<_t}Qh>ZHf-Rc6?T=Ggvq18f>iP z7z6j-J6LSpYpXk=Y}uQx$spP!abuIl>8#KXk6fPU==u?s(WMKEJ|O^nL;U%t2?BHn zZOfg`#_8sJg7*re%j>Y^+p>}J4q?d*x?htSKUihx5x93Z1LHvl4M^A$fCYtUR^cmH z^iv17s30k>xa|z-|bumt1cPP@{ zoy!GA@$V-zG=U0Y#O%(V^%t}^-(RKVqY%`c_DmBYUX zHWd{{50uM7y6gNs^Rut}?99KxDK=&JEuf$9=&zN`+_LWI`9(_1=&cVqr@vL^&1(I2 z!bm~8s?_E0Ed?UiDg?Z@NGZF3pK@e4$dnf{CP6X^I8?z~#)-J!^|c>Z?G6$YBw{_2GnqPc4g%oN;S4lg z3ZQF%W)|9S?_K8e?dR@}Ukj*xH%{XGEb4v{{HlFAp%N_YD-COFv4?S#9#jq2cH3QG z_%Aq#{}j~l43`<3h{2Ng&6^y&k*8CT21Maj_h`GQ`}hSwcf>Op6_W|G_-CC~gxhR~ zx${mnzYjUuqlFmdNdUYt`DO4QO=(Mjwm{P9E)1bEKg04&Q}Z;l94 z$ms`kG~&p_kNKHstuhyNRT)o7786ez-&-Q!Xe`aMK4LLm8P0n0xlCyJDZAg$MwMN< z?_bf3WJR-&dZP->$-Un(1k~22mhRe9af+6=@d!nAq?`0P*vT+Tu+ap$}fyrbuqSL%5PoGcq^cWNt|d=UWK1R9p{=NekmTD zM4-1B{X#Rv5v|Sv6N6?=ZbW?S>t;kJYt_jl2ZwD$x+QswqCAHU@vShmRS1#^6R`i$ z`qkU9u7Mi&{-vHGBk^Y|L`?Fx%^_z5oZUOVpr+C`f!*z8H{7yf4LiX{=ATmY6m*J$ z{7;q#+|AcAK(j~5k!2!9{kra=bBh)=Sg-PPi~=;EOp^KskZq60e_3I2h4Zk$Q7Y&N znJmtt4wZO3NmW?B_2vvmKeGU$j-YJcmQig55yTjrf4zs6)lmTT`h41ROk` zY0q(#`Z_EOgjFAe)4T-i&gpW8XN*7Y)C$muW^o2B3}%#6tRO5arJD!YDHqa=*L+tA zNC@JFRNdHpDjK++EvjPIb=fNZm_mfFoj`>_VDl<@}*o;aEC_$YBry+8N?* zxvarDpWUOfj6nU?K5;RNOnnsO`Q{;IQ+?Z|i_UPqRPP?F&OhV;9$Y6E+8m<5 z{u6PKjjM{c9M)Fy5OcFZs!&Mu!sAPm`${XSJ?qGiBKH*ox?U>Jis_okFAv879j3mH zs*QMvwLe)?y)akaO+C!)y_;!BcYu$>mWKwNY+2e&0gO>6!o z3a3hZ<1F)goUC9#;I`-V>4mYOlsT)I-gLt@V*Xd^FGRyw2g#I%5x=Bj_)V!0Nbp=H z8qHaYD{Wf-&5CgYk^220wILsH5&g)lZ27t}KkiLM(ygD3FQ_Ffn7E(f8~oBHcuJDG zoQ+Otm-@NFGs6xkD0gQ1Tqg_N0N}h|G4AG5Oz7X|xs(4h$2$W~T;Vb^XK}yaR;~-$ z;2n?@zj#s&!UJXOE|RUeh|HJ;pbv0nWPKyBU5+v<>*5!i`3ttXk5@{|G z@ey(oA>@OoAOb^9{dnqhcCeoMQs4PI^;oR4RpuXCO+AzhkjYFLbbu}B6~)3yAG~eQ z07IwC8eV7}+SoEjFtm)6gnb_erL3=zTYy~{zfiDT`vc|@Mf8F(`u_aCa#^W2%DOZ% zzFB+EZPo+eU;2rPKPoBu?NXfBOl-yWVH_r9An8$p!lwe`7VQb*Is_WqBR;XYg`L?n1$^fe^AVT004nMHTnWElg2zJ&G4ptebzb0 zw=yL)4@8b(57GX5DodlNV*XDc^CImf%n9U?cDJV@aeLxLA@iH7M6PYVCyVf82$?d9dZ}DJQSo~NKz@qL z@gqI}rgaiQ+vTCdM+*MpBw3!oT#?#Z+?~Ej^PM0o3saK?S>bf)(_=gbP7ABuOHO~h z&yHnJvTe}=AiPE6Iq$KKh6>ZwEFy3y*M8eiV-7{?T?>?gI8DYPe&jx!2Etw+5{DWE zjL`t^z9{s@KL#C?J79nZh>)ld=^X@7`mpB3_0`7O-b#rbj+gKsk49JLb?$a31NL+| ztRfELPE2^ku@eH$M&}>&4>uI-AdSXQ5joe=`8G!tn z1>4w1Rt@YKGx4&4WQifE2KY0>dCn;!;`3>#yu^C|yc-+VPn5-E|KAVT*(n<4r+Yy2 zi6NkYk}Wxw1xL-HjBT*X7>PzrakLlB>B(2+V#nZ8tll+YeQFC&ibii2vgq^77`TiF zjDZ%Z9-_J`I3LfpzHBGYaOne`mrZC73Z&#ES4mRD2|U}zf)xyP z(N)N`1zfQ(fBY{}f8&Y(ezhkiSK(UMicw_Kj|i@T+U)f&E3}{CV&~{BieIl8Q`^Js zHzX}&6trTW<68GMS{aw-7i^XWlU(g-`h>lv3C><$FHArlN7!?62&R5I@cCMOo#DT0 zeSwN6nBU(itmb%c*~IV%+w{z4$?+nMDB1w?(-aDCz)^}E`KLHzZ^08Q0ru4 zpCT5MbV=@%+s)6L!ybk*@Iw?PZYny|-Ts20jXwg(pE$+dKE`gP(5Jx&^$h4w0vH-Z zz=7Z{G8j@nawMF#s0+J3%$7QW*MvMe{puCwMy!I?d2mnz@%FT|O{kJl zIsd3TKSF_)BT6bs$CS(t zRX+k;J*Id!$DEjj6{TZdR_|{k;(ONDV~w5S31hy_V#D|(#cq$c0blV#=x0eCzB3xS z^>Bu*(FVBH%k7sO7lHrZ4Ki@7C5oJJO8yzr?N>CDOie*Gpax^X@Lmv;T(JYSgI&3r z=abx_ceLlRn88N15_3vmv@_znevDOA9!hNF+1C}GaIDqAmXm1#)s`>bziKRMh~Ti$ z$jw*+T86q<>!a0=ApNRkg7c?@gyP-gp|7lauYWU$V5x!IvTqF$cY=<5vKDEnpF^@J ztmE1@o=fnGokZ`HjJU?ZC&?(OV8MOi)j7`l+Ac=PsV_j-#&xS6TNM8f8;~Rk0LNG> zbyv_KpJQq)+*+7BR}T*`q(~UUa~DHLz6$NOj521}@!pjFn#d6FI!5uUGbU`6LUV_o zE!FSId%0V~$(0bif~XPNipJmb4_TE)hIhDA6ZGNg;cUnZL^m5$XrCs3|;r3Xjcv60{EhH23C{R%`2JgY%| zXIN(Le&N_}My1Ww8?JLg=VkhCRduedirT1JEmAE9d1$;Sxb_K>|4ZojiJPA#QxI-F zm&cR*DiaXw^Od@U{e!i?eoGMLbZlekPPk#YewaX4|v#9 z6DgcEbS-p34uhf(rE7`Yvd}T+TKfIZ9%lq(S_#tXtVX_FHw2PS8u|olxo5srhYDxU zorz)yY9K}4g;LlA&`HFp1^O;TkkUPwz46~&HU}1M8$e1sVwc{rbrS9`P=r6PyTH}} z2ElTm{OKy@v^V5g)q?LFT8g?s`8cQ)Bl;}+Qa5l-zSbR9UDchctTR-(M73b2y;r2u zR~mXkxRUt0LS9w9X9cRNqENA`4Uv1mo zz}D}m!r0_K1vQEB1%|0Lt-@`&+pp2E7TAZjk1zd06~jK?prwCzR>4Q6@oZa%$95bI z=Kx1+!+*#pq7=Xi8hLH~g-!A;3ihme&S<@vC<8V!belSp9%}GLR__^7xRX{U_Rzgf zN=GXkl{IzD*BOSjB~|+evs3s26=7^1IP!KjugN$sKh#%IeHa;`FmY3*!)w&1iW;K1 zMoQ`xWF`I-MD0WBkr{m`Z=ef;Sl_Z3u`Xycx9V0)FAd=vEMih@ewO!IdQ0PL1Hns1 z0tAdw9P86?{;hhcdWVGa#m?8cO160%PPF)jacQ1w0;TZdr``9Mnps~}*+Fspib2m= zpjt28U#LA(!ED(c6?2{1->_F+dJAIfHZ;p=Gztmo*+Za|3L&z#xZUniO{E6qm&lO= zTh!Vau!Tl`7^1!t+rGu%ww}f9!aDc?xMJB10z?DVQf{@3jTLeI*&FS3FEK|y zFF!n^Y+6i58|0Ml-d7UM zM1A6u$bi2WD@g2V3%;o;yoEfUz08e1&BMc|Ui>AYBoCvG;Ns$mJ$vVREp2i`KF4Jv zRvLnJ(?{Vbcl7@zhkhQc+8HELT&SnGN> z=H`~jv0U=_u6$up{NMl(z#(-+q10+ZuH|hgaguAE+)$#T)9VsvM~4{<&h%|hVXMOI z`46_IHZ~GlL!2JEORUfL_eckeFljoBYna_MAfM>z5fT2!0EzWaLG0Bcd*7$QE#Fws zha@tc4n~c5eLM78BX=@Ef33xPkoYZx<4gO+aS=P`Ro4+m;%c)I_p# zI=;0TJhg8@GZWq>rsgeh>eexqOsZ}z!IOr=lR?)60}u`mY)z@IJQIL~U{688A||2r z6KXKoIL3am5u-`y1P%T+)^}-prUbaln2k1#DHJ- zKPbt+sYBPJJ478qO5w(~C)keqV-Cb$beA=oLXDUx!v!#lkd=8wL;l|?J z^-uVXB<)v>zNX5H%T<{i4cQyk+RiH1|4=;>Y*IZO_uK727PBAo7 zk&?V0BK?CI%E*f&kK-|!oeb81em20L$7LwCEOc$3}bY<;LYGN2&j z(xNKJ-XAr!!iKb1RVk^6xsq1qAObroSf9-bXHIhGqNrXwm&`Z2<=U?F^MR2=-pE){ z-C=f7G{prpDxCMNI9tkYPpP_hFI=6)oB`N|8$FQlV4;EkU!wCjNj^KsO?cnmMK)0& z&k{nC8&69aD6@3Qq}9Xmdwg4THCP-$CLxZ7Zg|O8B>1BIX>}V$-rc~L&xDWmGQP?> z<7f;FSm0+BEnILd?#>$;(K>f<(lF(HwCLFpwiOp`hEY-OAZ>a z7KLwT<}Vdu^`T?N@=a_P`Ib>z+hdYeLvs z36^U>m8yea=X+@GY&0p*%-Ox31- zI}1yFhwvWD8otINo))h4Jd<`h4hjngsp7_;(()`5+&&o7dI(BwDw)%DRN>Cdf>-s!@%Ee0F$lO z)+Ni)YT=vo?Jq4R)R1w}>K>l&%Qn)7X%9co)3*4&d3cnUos#b5t}9YU4x|#u(&Hlj zb0ptCSbQ5w2^5L@Vgzgy#1+k+{I-`fQWnVsgaS&(8&Y zWj$slu-i$Z+qDd7CUu_p*R!MUmfvARoTP0mIYA&|Oa@W-K`XqWo$4VY11sMf6JkaR z+|78QgH#Cgz*eBh9DG;iIH3J74(@p6L3VEiQRMqdKt01qPMlPuV$QOS-kRgqV!1o z8LZ*c23`@FgX!kGcEfkCQwuhBC@@|yiBPIV3f{4tYq>HghYTr`+4BhUW6x~}5V$$HNxYUsrKbI= zFz#hS#F4l^F}%;d{#r`aMM31b;S*;MqmgQb*cJd);iGJb!Nh)D5)c>2^?ggCgztob z#0@+%hd%FrgND`mi8C*K^y*;3M)8XAY|IW7hjp!r9!kKFW6zb1o5awm4w~W-vDUd6 zJSkQpDx&3mw_=DP8+_=Ny(~o z%agmD>mEDxhufw#JysaL50Mb~rRuE_AvuOa1puBRHDe*IbCTj4y&V-yDQK3Llp{7+ur|_gJ9FxIVodxWgHJxH zIbE?Jm0|qJ0%g^jtCH3K7W7LL4W=l7ve(6+NDe_WnG!FQGF@65!83&W8%Y)o|v*Y;7{ zhtF7|YTiNFh1opx;XRJUSDeK~dw}@w#;`HR)j{f z$fnzo;Xji)qz-_LQI-@@hK}IYf-51RBi9QE6OXRqSYpGsrDeFD@2h;K@6KRhfDW*S zLmFah0Akg8fU(uRdCqy%B{4bwON#eXt7*> zpd{6%#VX(cS&b_*+>rBB^x48pEo;iLRFvnZFGbi{JP20@i*-24=d>73ShR=R#cLBg z^=CFzNkTuaE#WMJYNB6SAw%Ry6Vl40jeP#;p!&50;>@ch$HGTsl^1Gt_}P0wC1-N0 zX%%f7nDIecXV?S4wu~yxwLX(Vy>R~|plFUIRemt0N@Yh6xcvrG~*Uwzn|L%{) z?VuQ|c7+68v(d14pH4JB)`?aCqAM;ZwY3`2yq zxwiIGS%ngw7=a)DgEq<-0M@g0KMAY=BNbu+u>p&W z@X6>S77)|ynmw$+#u^5Nj?{Vyw(^~coDS9k804jkvCk5ge*{UQjfO__>UfSCVK7PT z<&Pt_nmnGVHoM5lj%>27O)*B7g#htlAmpTGczu&MuR6dV6dpaPRXO)||0)Tkn#AB@ z60@+EFJ`4^zW3nCxu7OHh`Iy?uFdsMS3Y#L;**&Q#=;kjJlOqFPuPY!VVNA9j z%rae~WH(lilxA=3dlUt5$Q4ZO&ZDt1<+Rfzn5_5uV0C%MQ{T^UVr?ai%+2AE6t?Jf zl*^|pu4E;v7>3T$W{fFD% z-JVs|Z^5OgwDXC9VBUIhXnilBO1>%oc=L_r#o72^68~sPMy9-~r>*B&OLC=P(RzAl zhmud_n0+A&@4aSoH}%#Y%0rMdYWCMvA3QOZb9Q-~uCq-q=_npzx^Zf_^r?4x@IR5; zwo=;>hTxfQ-dW}`PnrxMb5&U0MVZ=Kra(qXP4(_9k_0p}fe^PvQi3@&odg~&i>m&>vCULIOAP0l7PO?UxX{4(ei_I!EzN zkO(6ofk;+)>E%lV@-7em=D;=CcC!ZJYd(MNrd{*^PIxAI=vMN2K-3;97|X?%!OSMv zuc(zR57D4m-uk)_;1|3m1+*$nz%moYu2wdrerg|B4;I-4ESgi^NIsTtB|doUJIqN_ z1p{3=jb{SsFz#D{G z5lCM<-kgJDVmQYGxB|ijaAb&+%z&y23zT47ir#xL!3kk=)4WIHqMOJ(0ilGmiLn)> zLL!kppJ8`YF)m5bHy;0~ytm|HtDUgP3R`OH3e3Ehiq0~*t`|?D$a}&c>T?50(z zdSPRjyG6)eGEZn)^uOlc#^RNDAUUl6RaB>1A!wMQrpr^&*V!4BNE~oYq(;ej>Os;L zg}U1}V;u!L&nNY5x8}u5T%<^KR@&v?KWpg5rkJY)>v?1? zQC1AwhSh_)o5K_voR=qFhd%n3DemmLqsz>-3-1DrO41m+Bum-RnhG14cY*Z&xPEfy zqDMBkA{Iw9e4984qmx>1LsC+`dhxjEi3ke5+*H~9urXl$xzwfH9vlBUqHTJv8(j8TjGmF`(&d-+eERBPy zrFe#7Nd->Ly)2)gR|oeyp~kRv&r$3XOVU4eY_Ltr7l?&pql zoC%0gJN)@4Z}g{uP+^_=CFM;&6mcekeAyWyUS*Fnuox&S0AdHOSIY z3M4uz1UuD}>B1o*G^N}sn?pTO;hg%c8Fx;#*Q3Fns7r|%PJ^2A0Rriqd;0PPBusH= ztRRvAxd27GvO9>n9v4;8fjyIki|d1OcEmnx$l^$98|xMsQnGpoM+cO{K3^NJ2h|p$ zgomLm;i6$tI1jkYTw^PQ$X0@J->z%uhZ-4AwfS`nAi+}|9&M?Tg=>UXy~isl$8&mg zx74lYP*8UR#~Im{CL}Zd{aI|gZ5A0eK5K%#S|!Y)60@yYUgxBcEyXEU@T&y5Ba}xsC!|w0&(WWPiiKN2nb^Y)5i>t{!`LNO(4Tol|fUcbaKtVFc4akT*c~_aKzcqymexe_3yoB{+aRiA3aJfa65oy zu!9ACDQJ3kDgF9aR7wt^8&(+O)5OlSJ*~53CI$dT8gnc;&?@e!g}diefr^Y6&B2t1 zdRPLL^lIBtVcsxM&btfm50T$Zo0sb{H7_!lLJBR5P}i_ZYtwKu2p%*4#1#-#%i)4$ zioj~5_{YSmlr!)TDk^065jkEtt5P67F6N`@CdHK7Dm zQAH)@X6{f+wC0UU;e$r9G9fOH6?H&hH07va0=zLL3`sW&IqeWPqr2J1}bnwhevp)yV~ znJs6~B#zSxc`Ga{2MC^gsaGRHQx9ZTcd$uKSRXtoBwqbY;SoGBmQYv~s9d{9VkCgDko)NE5vr`W5kUyeJ%?BAce>4V%{t>d<-1C8-xqHQoYu$E2x`~b- zum&q#E-L(=J5V~O#$JEmwleDQx7mo<7h1iS6@AmpXii>wYvCmxlZrlv`cNPffIm2I z=b!nk`_M2bJ4HZUYOA2&%0dd{7(Qp-+^1v!_LOrH4G|F2%!P^G5!I2`JJhHl1UgCY zj5vZs`ng}wGt0lr{TK-Cjzs3MmPs$A8hp)*R{{lt< zCFAf?ly)7ftDWV(Zf~v#5v&$P2ul|2lx)fqES&TI2$~R0Me!%7LLFHeaVy6n0y#y2D;f~ z%oc)aZ5kW3wUnu8B(gp!8qu1@38ALsx)v&-tBGD6O*uksXHs613C?I%7bz=m%gmzG zmtuLM$fox6nGY{*lUW)-UL&MyV@Jb`x!$P_+;HhFT2`fB=ME9W!>FusDzF{deTmWa zq=ZmPdJN*=S)7`zED`9(^SjB0U}#b=7WL0hQ{*~Yu1*(5dT7RX#>TeJ#n<*#V%+Dv z6igdVAuO|hM}-gWUk(U@G+>1yMK{V1_sArkD=p5jCS74JDf1m*^x$bm1*OyJ3ux)J z&eyM?=1nON#^b-tv#A3E^puarDua0kAOGFjTi)nLn@+I_>V7?EQ-0q2r^bv7UO3E8 zJp-e_0k~TP;SpZ`w;*jzB6)QObQp;PUs99!A>o!F9ebKn7mUz|6X-ZQz@Gk4nPKgO zY~%8$o=`8K@X*p-qwIER=zEa7Ss(!=ORiw_n(Z=RXyinZGIt7#G_{_a^TUewlPpxJ zIxNvz@0YCL$_WD3_2B0RdMBA->gv(Y?eJmLdmis6n>2o?9u1l<9lCW(c+B+y{v)X7 zRb50!ByKYdp=4SL^ufl&*3tdP6zl#B?8}S7WKp3c_=O7@=9lunY zTgqBpYpJdl%5lS)5?*OF6i_))klvHdBi8(ED;0Qq8JRe_M216wsq*hx4PzU%NdUHX zCP%z$rk`sF3hjy8<=w>eAdxw&D@O2vI9D!n@OU@scdqE~E&6RPYoTs{Bd|FFsrf#i ziH+6#65)oIY~p`da!gXCY^Tb_VQdzh%E%!|IhTgpk9`c6< zBD|YkO0~9={{Ez`LN~@*6$C%pE}-j)Z-n0VE?6tW>9rN^9mv0kTe*tJ_uKL9H92$c zMOSU!6XOiH(UMycgYq{@g#YB~R$LByFoRospR5afV@gt*Yr}1&2Ip9Hrq!JhF?wyQ zeQUYi$D`FuTxk|4s(sQ*gVqDa?wj4LU8Zg(Q(ONZ8&iEW=Rzjup#jl}YOP)|wjUha z*_69?9dGqCClHpV3LJAfV5ujc$1@pLgHX5xZa%NF;8^aQw{}A%3s$rzZtKClM}f^G zx9vm1873vKm3~f|VcL&5^U7=HmLQQ+-CK}Hvqgp*){o(l)c>|OK?iYxg9px*O=W!? zLcoAcbqJ*Abf{f{IEZ0I9wi)G z^|pIg|6GsO;{;^75R_D)Np26hH#*#jQEeFHLBxzVWaE(74t_qxDmX@b% zVLw#S?9Cj}WL((&aA4m5i7A4~L|+QWgUokK861p&xIrVO!r$e76+j8~NEk_Q#to2; zg&jN0ep?5le#fSCbFS&52bqj%>hq9G0{S&=iQEYzqL?J=X^fi3;FCbeel>$yA7Yqd z%-@eM1Gj@Zvl@%n_0FZj%iqfI6fz+Nj31#m2tu#Mn2BnB2Z3-o)cYn)`I|yI+dRMj zH7qf_P8P1;ZFzl$0WCV?@cvg&`2+bX+?4Fd{7Q*z6qINm3F7Wp=lKsdfsL~UU>^bi z19T7`>;nWwPfIpdG~k>YM_!CYda^bDN6>-D;P9So^kP@;8J@TYgObOhjQgH(IcQPp zmEg>M#wlTvY5&{NEp?y|VBuIPP;4H% z>6Mv8);DIo$`Blv=rEW{cSbY^7=P-{^csV~VI^dcX?*ai;{2pA(AMulDX#eHcqm$F zF_@smf(vj)Jp0lMVxS}*=7n3`DTOzi zcZp7q*0fC&n_H!VamveUDof)At1+ucTxcdSrgrPRCKB0BDkC{B(x1cR%1%jyfF|`Q zxyq3{*$TVJn=MM3imB#}BI^0cv=ND^0)}W^|A(_TR%}HGZdK=hV?Jm0o?O>^XWuj5voA}3>t~5 z$%`S56&&?55|!^yI8Ht8FnfQWhP@@lu?-$Q38!9kNz<@H=r*`$YE8 zB>I#xEn9uy*SfE!7NxD;sWM8EzMLW6fdFV)XjEeb_G z-g^;4Yz-A0=MZZXhSxA0M^-5IqGY|M(&#g{M2cveolZPESs<#1$DG!S+j@~)`r*W0 zQf~W~ph1ajWD#e7w#Fuzr;&0v+ap=jb?WyUW&_Gb%!~ZQ-aX@Q=2$Jn);y9p%IkD0{+OD ztNkSuj}XVixHUc+tThvtHH4VX95b{K+Az~e@?pb&_LiUX+UoL23aZ>@o;rKAy@UW)yH3tj6*ZT{DSB?Rw^6a*!QSo{ z_UAh%{`Y+7P#4`kl%BgN_Db(-h-A6Qzk&UgC2I%DY`Oe@Q0-!1yA(OU=tKN+-|$U^ zTn9wEv~td>e$$(sZE(-a5oD<=$K_nC`_RRrlI{j+f>i4=EHFes(QCX`@-aPWnJYy* zZNKR?OZ-V@hU~tA=aAIcb=gtO$Q2gQ9H70G$ZK9=BkCLm)CNtwPaIo(zx@1z098dJ zf`~6<@y`7pD$GtLe#JO4w}M9+idgIaJlZ^q?txVN;KFv0oY4LdS918wETsS zy?vpK5QPv2Fvq{HG?Y6o)zict0^X_s2uWI@C}wh3@f?MO>h0=;3HqE$en!mL+sPpe zCI@WcCkde24qwJ7h#(_}k+zfr#bvYTlOI7M!v5lPP1jpxV0m32wSl{8nR{67^~Ugn z{m2_XOH#<&S_m~Q01qkw0lLJuqd7u_4U!AkJ(Evx=-SOzVzh_Rpiv~5HMb{CJ|Kg(VyVxvT6KjYQeO@Q6sGfD%eejBJ zKO`W6mwhb^=j8`5(m1B4;?_7njm`VS@!kE+R}c36lVVV9nC>(|Ls)lCF1&-g0vuhe zxs%0hwV(q4O1U7iNA^?j=cJ!>AKu*6<&x?sgf!I1qMskBA6Ykd#kOg%eV-)cT&4T> zWApJ-J~}TaVk_v7_Q1QcU=^6!+hhBz>MqfC&-M~F0eXUIg|B>>!S{tstmfGyM<$>Z zt&arbUUPXNUBeSZd=_ga(YS!F@~b)T0ljgWnGJ)!H+XoOa(D3%UL^W-*OR=BNQTKB*ZBn zHR5xD^tGL?NQ2=gNON-%6ZV9^XRusC^d|Tm-p66&Q@B!`jV;$J8afal*|Rf}No$YV zrk820$}Vud+hCZ`Q7T7cc(mXglKV3(xP%@kan>Q+I{R$I6pX(hPY77R3=DnDy8dqAD+8|@m$nCKpub~Mf321wHte!p)lR z2lPILgXDUvBTv$J_>Iw1Un}A=hUIBxMY~BvfVqlh6QHIJDjApqL6Z_w5?*C-0>~=@ zWY^d+N?bC-P)%CChA~@NZ`?Yb)|)CAJOs2D$qcRdA!1^wi_xB?avV3COEpQQ-;$x5 zy@9y#hG-B=ktK@drI8`j^tQcl*%jsDTZM+7^aSsVxPPGRcLAfN%7?qNsf?2prtTDjzT!nhJ-HIbe{4_;6X;9cZS>FFznMd z@2Yo*oUkpP;foe8nKx!1Rl!Gwi0*zBF*lJHGi`AJx+=_9{eb-6agVVxnDJ%k`e3O& z9OUNVP>HvfcxJqBy00RI6&aweN=Sj6Ss)QUR7eDR| z8Ypi2h(ZY;d4$~t_X>yfS@zMH$`Iu)*O_lFdnGkjFqI_n-P61tl{$!dRG)2{7VMK0 zx5M47ZkYz%v>t)m+gXs#!Jk&1)B%WnG)RV=hnF%6Qus9325BdK70zST_%!-GkM;(~ zzxg$yFXDcjXl=dse3u0YX7@=Lkx%=6p_<|iz8Gw*;uyLUCCvcXmKTgi^NAkL)dWjpzwW!ulAjI- z7o6u$ke&cP_+kiT4DsEfY2^YOP0ncy&vWQ*yDv=blPH-z0<|NuZ~-k}vBH~2WgSYS zJ>EKDDv+;l1t;Y(!P-=7BV5Wj;fluD52@0)*NTrsGo+Eme%>!ntxMQ8s>EXK@K3jb zQ#yDh$xa;#i3MWP2Q^zt{28f=1!%8FCG0JUQJq|-jU^8;CClfexT0z=0>v>gGNdZr^jjs92FRf06x z+tk{uumSr{;!h005X5s^1SRcBMs}a}FDc-;(ZUb$rV8OlHSKh z9$)rDidnPK$;lc(rzpDif`~PE{wOuhP~k=yN>JE^`=Iemr>2WFZ8Ik_olkFW zuRs8N;z(N3f#3j%zva!a9~#PpK@p|tm!h1RuML%VKEQwegvnu~BcQHv@N4EDl9~`} zF1z3jKfO!H(S|Y*dr_+sV1%Uj8!%U7TA;qIL#sqI7!)`E87TGSmT?%VsOZ#9dh=Ci z81Ehe5q|V6R4+*blo{?#rl=ebNp*W`Eax9~THaH!TQF_(y|I>P5Y{8z8aV-?UAmMu z8fc{x;v((99>@UdG7#gGTf;4o{7Ed@-lYOeK6;tquixIPJ=DKE#H%CNmkmdh7LOhj zk$Ht>ptEx*z(^inCx~wuyDXk#|Ilp^;Zc&mXNWLF8=Sw75rBZb*#`{D&rRh;MFH+ESSJJ#(qUi`=VrfmeTfp3+pq;8 zse^HOB9>O}+UTFYV3KV?J|btbZ_)krmxIFJ3{gjF6adg+2|h+P^R1qJ+4pEq*_i8R z&frfGn6;IkIZL9hKBznjZ`evOdlq~F1-q_1A6(F}E%25Xv2AJ$&Rd3TPgF|mp6 zl!z6HbbVfqB%O-~cu*rAP~J^@_!4clkVPrPQ%OEj{pAhBl2_|Sy~`HFau=9<+*N)b zO*xk?i8@|#wr!aRbygRIANQD&d zHZ(VkrmPxEXS1Dj=baZ1JB6z#8ta+NTHnpeR?D~$FuG}@>D!Em_$BsUsYjGihO=XJ zIw8u~b)JWLex))@bs)a$aENJIE@d%HZkjduj|@LHyT00096;a~s& zg|%(ey!xNA1$QgW&H4rB^+nPw1JQsZF2$xuGp7mZS!)h?@@U70Wowc88dqyEhX}Pw zTU1H_8$cyCJ;b>s9oW!8g|d04vS3605o&!jaTH*NaHgYJHYEC_VkA3p!%98|0ZwDD zyXoYL8*2*k@*dt0s9fEFIS3y!h(Sz(R`+g;Kur07u6@2D5rby?vSoyq4Vi29^lcVB zMMUAIX_;YJEr08y7cDaPm_jf_r((grn{xmhd#h5>Apq@uLaw7wCM5F;Y~hUj@*PEZ z>7$Nw0*}mwXP4eq!IQIQg$N(t`6}XrgrM~HHSLKiM?Z*10W>8wSk5WhF?G<3uOY3Y zpo%ZVBWY%>B^nz)&0{YIC$thpSky?n!N>%|*7rMecM1S|hqeX&R)0XNOpQ{nxD*9U=|APV#L;UWV|98sO zp7a?YBO9}%Fp1d5B2tSj)jz;mt^Ph@|L8DDe_i^jdU1p1N!TObCdu=c|NqXE@F^Et zS}7ag002Tiy>CRD2h2IiqH$X_IcwEUPqAj_mVYq!uhpFw_Xn98A%_$+(lBDmJJX^~ z*rQN>?mz?E>?ZLe{8{!vP*NV3YG*j>L?O-=8xzLLZ%)!ebJj9$R|3bbaG-xD!z94I z+hgVHv+o(Y=Z=jAezHnYAR8)0QB2}Fy$kpz8v@s5&Lnvfrb?9r3^i{bbT7Wxpurm06fqzm%XOjim^2#>%eS|91+S= z@b&~Paz@tPq$d73t+WIvtptW4$4AQx)3{lMQf-y{LuaksHDYl>s%B(RU*p{Fmk^>H zVALw`P@1WNX^xzqXi9J+JS$BwgyFro##*W3x~Y@pO~INMsA>xMFj(_7zEuEB3hLC_ zow{dl)cXda+&@E)*h-tZUuU^sLeye_@C}4aT+0e&Q%(lemX!5ZiP*^FcgtPZu0D$f z^2jpR{#o=0PlL@odUP}4^uAoJTyIJvo2Ny-&G=t9q}3X9ejwqO=5mbj=oJUnblJJ) zo7wsO@Uy6`IFU+|Z9Ni{%XfGi&0W{0RK)0qpY1)v$_gkI{jX=y&+>=JfmD0j8;$Y1 z4W%oO=sco$c>hR2<~?3XP0Yvm_U!q-Zq8CfDH;kjgNa66Vf{XVFzG|z(&E#OnW_OE zl@c)>?drvqx11Qqd6$tt)=dae1-7-)1S}9EW6R|GK}fpmfHTE5{3f*xU4z{$&x)7kn6txh^Iu3Co_orO!9nF&J#L(V|0JWHO7cgK{fB|LC-#Upen z#iAqPy*)!?rp1N-VTP?4%y0(&d?{%@PSb+TD_<4c>K~Ewkqm4%_Wy+7%Z8Szb#s`{ zfY3U;-YKobt;s4-ABI`A_5{}>vIP!4JxM*Se{9U6Y#U%X))Q*=hm>J*l=o8AHreI_j8h|$AUu--@4th-DxGM-(4!|~I z24sXsdv>8XaKXy{=^(d_9K(AoV0y{~Fq!E)))EJiiWkFhFTMZ)n{ot+ge*Ee&{!OV zRnP(mLOYd{tU9S#^u6T3Y}xZACmpZmKIqThW+V{J-eol8V zKblO%F-Cb@B8y5uj({XSF##Y-KPcjpSbQeaH_i6Dwv?w;TA1OiBe--V)LHv8?lx6S z`R2cB-h{+&><5g0c09LmI*Q}Kp<<1eVbVwD0g-}8OPd$S)b5*_2&7h7&RU<0cb^5wVT;i1S8N>l zT7*PAP!(a4`rBu_z*NWb(Yqro)7t1td63X__orm`4;T=OBeR+zMu31ObLm-WDwCC3 zw=Mrj+>@@GOzA<6ZSaHVBwBm>Sp znYtzlHliE}$kB)gWK|%?0as#3*^VpQFthq=U(;TgEZq{qn2)P7IM=USns>4Z9uarl z&M81a{&bD+FoIov!+wK(vSuFFKj|W{mfy3cC!G$pTumY+uC6v%CZ{ZNejJ?-sfp}= zN(0GjDqw9JBM^pHxOcr3CVJg)X?;J^)CO+rN*r9l^S;^_TNzIGH5{LE9 zkHImQsLJdT*$EDp2gC=}8G{%jxbW#5;SKKrKWbndPA+lO_p>Rmv4SaP<@->wP=egx z4Z81GWE2JXm7f*oFlG-0|HV&;PctW~XXn|pP29JIiQyi=>`HZwJs@BYlnHZIZcslD zv3HVWmXH$}eyRn0YBiPyv5)$hEPVrz=g#x?XKmZI_txH9d-s;Nwr$(CZQHhO+qUuE z_xJv*Qk6<3$@KJe_e`df=ZOm}A{v!%+W}pKg01^?Kw$tTDM-xHA*u-~Ss%a1QL}c3 znRVD5rc#B|A2sg>UhEcErh#^aIc$#?yoVICL7y$4S|ScD^kr5e>jjv!B6l1-MH#yv z%boTg#p4M@0>8J5qdVXw$ij*WZJ23xoTS=_<=HQnK~=h;t5)1Wtt!ol(RY$HA&@QG z#drN0CwxF@s4L||E1WQI{{Hj*sUpx%hPRbo=PdKSJ*+QFxi;ZXhtj;_E7%Qbvo-Hh z0~YlJJ&T4qPB5-XDpa9E;}*1N=-~6vKW$~cg-e5O8}!uj1AcI(6R3Dq&F5XCQWHa? z-fP@@U1uZUsmA(*2bjUgp;DKbr!()q9`H0Mn`>GzOBbC_F6JgB+y=Aws_CX zOEk#?S9$Y@wUhX|v5qASJiee;hW;IivBC>B5e#ZF3i+#K4U&XcPVsm)p(#9dI?JmM zhQxpTO=arAH0HLO7lM7seDjrQ4%FN`Je+)$?RD6)l-4OQlRJyzAgmMfhOoavW3+iq z>#mu65Z0K~ygq#u2?aHnM}llZ;+t%Yw#UWG+uftjmDtFi~CS;M*C%6 zDG)8lgPk(%;n7@XachIBw^*NB8*cuByxl$yRp_1Jioiy5c;yHwqEhZfvWszfq#p;&+b*9y1-V7LEIi{Y+JppOC z;mZQW+${SOhq$+Afr%o(7wBAyPnf8U=kVg0~xR$s2@t-YXQb@vpz=`z)@qjr^ckF@30SU>ebRhM{ z7OBNRFmAE60YP`8S~oU~d?_`i-e(|hKJuQ%`<6U4PChB?*52q-maHbi^WnCr^(8;B zW2Z##VM5MmF%W*^R8d_JZh}j1NvO)_2hcz*drhy@w&K>WB?-7-o(I`jI8p}QAq`+C z6pmO5vJB=tib@Vk^Y8@tQ5UX{q<5#}-dWZ2{zm-o7wT$3%dSEmIJV*yTS8jNlI7Sk ziS?RpeRo5*Z=*f!s9Wm`HeV4fM zJYz{SzN%lwj|c-wKukl4tTHGpHmM5R}34ZpnRfub`ah($lXpZ$MQzz`15; zMd;1=F4;N``XUiqs8S0!5-BfV)X7LICQmRLwr#&lqKTE2;f8-xC^Z&7{?V`db1+O1 zdkzA$g=&Rd#5Gbr?fFZ8YqdbyC@CvD<%%8gN`Wu8@84@F6vYj=mQzoSwy$uArwnTg zjqHvOVj*o@hG3<>#{H08#bqxvW2)wu+Y^o~#8Gx$o8Sjvf-v0o=Y|9fyVZ0-O7S1G zKtw~akqyB`Yw+Y_0#xa!+%r{>-@#XQgpV^6X6kv{7lG&ls?91J^vn0+6Dk@0tHEub ztp2EU&3ANPkynTHu3o9MLLw^{$b`y2m`eYzCl}~Oh`+fWPf0oPiDVS%3nf(NBj&m+ z{=(CU#9PeEjfWsJ&?SEspAuYz@T`n#?Pi6xX$fr24+?D|g~=#wBe(@{2vs+czs*w~ zN`4^#vzMB8sOxb(R(>a`V``2Voj*umLu!w=3dV=v{#i1YbhJPfZx~e*z!Je}*%*!x zUptwk-iv|_A~M}iZrxujf3d-QSfE-R{$riTRe|7AfVbcPhRZ;w25L$z+b%2^f8Y8< zg*~DMIj5!e@!L`*(lecBx}CcWTI__m);9;r#Y8bOrN4|df!JQ;?caFBGD}FbQgdoNk7q+ zk{BuWY^yYi&bsq4vaNV8kjodQIpq;iH&lbvDed%OZrGKhQbB+VNCarUhzUxvf3rrq zWaspkPT_>eFv{O(%jaj$6IF;e5xE7^369<9>223opA)$&3e!Bm>p&1e!fxyL);IO! z0x|1~RmS>GWF)yIU@t;B;K?tL#!g@b!&eVMC3g0A zL&^gG#7$jkNu*MoZ1Q_jyx?49NZ-#9Hflep9^0JiaY*~UghV@;`} zji>ld1yy{Wd2OMnNlVwr0hrUQT0#T4#1=^IHc+~f?Z(|$j1Tpoa5>Gt%Ttd2hDZh- z+f{`!>@H^rl__O4JvBFQr|!N>EM`4M@2}4Dn9Z-rNl~X{Kpp=B`Vr0B3CEL{Auj8y zGTp@@4F3{OB`>IrZL>{4wP@u4RS=J|%JIV>V%f>a&-eM#Kj5Ll5m%pYu`eWZgu?q! z#v{v7*419HzZnjGqP67m;er(#rQSWo?C^vfKd4rCxhIlhKW?QKxRG*XMa*YnzK}Uk z#XSazkSNOuDh_MM};2%^Te6D&}BZ`Kf)#1M+FC zVXn?aD~qh9Xqc-$$gBA4xVWx?4*>a|PyV2c#4Z86w*~|?fLh*3jY)QpBj9%mEvB}?K;s9A%&`P4_tipHR^Tl0i7p3iIUZgXkB0@e$1-|s`Wt3l{e^641RA6$@C19Iqv zL9hBxFo^-P6isSuHSPJ1 z2j!^sln~D_OWeo<1#0=odkf8otWVrPTY%4xN`Sa4go3o?QpcD~FM6FLp(SXj<=%XN`Qk&UhQJ_76nkx|v z`R#LXS#bTAL>Fnx*xOJFjQTngbYS2oFz}nId2!%BbUvhmJh-h-<;7aLCSlU#8xZ;s zBe{0P%`1*IRU&DX$d^HbsT~4VOTSq-uy(Y- zP{HD8Whh6iK@QopdV_@qzfr7gUuR;E!zO9964lKnr2=xqXwqg+!v!jLou-qJd;d#3 z{kLIB{dt@a)O~-_qAvZzL*?)jH`c5E`OGqx+SRc&nu)y0o=h#*SU$Hnq)_s8O4=cH6EygW=2)) zK?}6{oIWQC%xdX*hy%?g>NBn-ZVWugB%0p~t*6?ADGHhc!(|6y5>m@@MS=3+qJ`H; z_}4DG3R=*H({Y_f=8Tx%v{K!7MAT2@Hx8dnh!eTts5gEMO@W$`Ro)DodUEQ}&i_|B42^bvHW<-Es2 zr<Ne&pE$-Zh z#K8qJKhX1}rcAz?4)Jx!5QwN0^YK?@(|&emuU82=`A`Bm8p$0!dTJTq(tL223j6dcyITcqxb6X$}^R;c0W-3EMC@ZeXMo z1&t%z4_nrA-uGHNGB_X|>*9k{#yk}|Fd^KBLJ}@edR`D;AC)-AR{Y`i9-Q`($h%?p z)KU11Q>$^Itm$;$t!8irE zB3}umz|&60YBTQaPmF%i4)y%Jdvn=8lKTkS4%Q%=R~_L)faBnZS9XZ#+aQ%>tFt~* z2JW0rEYNf-@!k-ZCkiGt;wU{esykh|07DzVZaXdEs_eAtG!T(zjXZP#Pvy2j|AWXB z_~&-OT#a=U%T%1<8)DlzxD_#fv<#gxP%_WT_^Nn7S#lvxj$^mF!}qXG)iw|I&@MmA zU5EmP$eck+&JRZ7di>x-P61_==cd*&mc`gE7|46TW3^~3Kt;@{`Ex`H1*Pa5uS!4s6W4N=M zG42)Bim9vYMqGOQYA7GGAsx?4($$hhVyLs+2Z$*UkSfa2cFDba#2E@-8apf~epV?H zF~31@hO-V1?HAvdB4qP82>kb29u9^7w&jc$)n$s|jzWcOxP*DrvtDihGFi<@nSX%L zOF64qh3iLHC*e}Q;Y8G1UCUDJU$Gvn!7~k98w_;pxkp>7UL}LcF0+rn9;ETXxdn7c zX_=_@Duo1tYR%CH`^iZF+5T-^{3oQLVnfhVSa``bPi?Xf5zhB z`{IP zJ-8N6#$`9(C|!k4vD>^4AR_ui*+)B$gNH4q?wTG?uRGo|eGl6_2~2DB?eUhXQ7SHn zY(oo@@uyh07Kh@=A5C3{?Mhfu_Yc8aDot<_7$RL)c%5!rb)0Ms8};(P~E=6V#D3 z@tQT9Jj!o$-*#n)dP*aqQMp-FBc5Huw=^e>Bk3(`J|)UUFexygLiZmJZSA>XtL1#4 z0;T}tJ++NORgM$!t=Chywe?E9Etr6pUXXzgDo)+Js>?|-(Pv(AF&e(3@i*8UOPhSk z)Uqyb7L|$Pz08t7cn+W`l`Ya!% z{oAYS^7790`=*);Eb2;Ov{EEIxdY^F`Th(xb|1W!~HgDtj$qS5PS)6I?TZ zc8#e84y~;|#7%>+;`U5T#nQ}FGp!a#Ug!)KEb-bA)so%U_ZDUVG2Byl8uQ&mN8j|3 z`qVLI!G7d!=!euQ!VDD?m@*~E$wKRq^T4(SiYf;}5R4t5i}Kib-J<9(ad(>E8H(kp z-W7x(J4yN-v2hKlfp7I~vcEx7F2=-(gvj;?*=M*)BM`T8GI##_^5KJrxUGQ@iIyw> z!CB0zr+IQ&^lL}rmri_g$Rm=WhGM^0T6=+3YyHG7wBs%L|EvZIe(?nDTqP^Q@LDFC zHP8%5?>Be!ti@Zfu4i+U#*xlS^lCC>^$=tVlRG6AN#vm&&Bn|(1OxC#Cwvn5 zw2S%o?hBVURt4wFnM zr@juGPUYj)mmN2>%!!qIKa>MgQ|*lGcqs$T5U&#yXmj5)GHjhyE5+V$d`VHco4a6A zB9NfYvre|@-;*w$Wk5L`B?pqAbjmV5Y&fdqa%|cPJ%RNL%QfGVf4!>(bUG@vSi0#k zO63--z>H!4(Izevx^LeIp+_t9bq4efD>L6;&cX%trC0UKdWRsxux^Og$LmQkbqk>V z_Dvc(`bWm12&96AlmS_Xq9+~~Z&%TLsqbHqMJ14hZJTWZKL1c^8JZ6kmp;Pez$Z9} zV-E8&3U!cE??cr&JojZTtAGio1e|X;;j|o`Vcr5z)G(9PV;*CkfG+wfxaV7uB%%7? zIrB=yqk=iLrXSWq^@F#fYs0Xs8B8ONbU(Qk|ILmzRD#w zzfJ}{ib{DJpKnBz@G-2BDPgD4$s-gT$Rh|ySBlOcozW`gpi){Z0rKYC1 zw}xXpv`p6hp8~;2TyX|p#QpupkVj60!r|-N@9nPyvZW|m>$W1u$nbtNYXZ z>Bh}E@nz~q)w!w?k|g=53t|SHmKkTU?SB5jkmsSXy*m<`{dPhPs&jbyDO+XxEqUJc z&B1Zz+8k5dFwy7+D`fs9wV+!2lpc(6enf(u7ot0H+Zv#>(8v4J9|oLnfA~$jnaGe5 zNMFhiKC@bdlW0FKMv(fpi@!FdTE_ZKw%0f5G>R1N)WYIh9FnjDDM%|mFTGq{oH8++ z0H;wG?3y7AT&>PyNbHa0O%<(0$Y$v`uFEBkYOx(K%i!@z&xsa%+sxo&w#%rdB-vTp zn4Mazfq@In&l#*STc|AYSLpwbH9#iwGaXO{Tx*+Lxmu1^iQH*hxHX3bxp>uDC>4TM zE~B+!s>}<;mNbx2(K91QUp|mAsB-ZqrV^?e{5S=P?ow`N`sE? zBlb$A;f4+N7R^6gOK& zUZRkOkDz4Tg|De-oq@cYxZO)6SAC`^QTwaZ1&1D7sN8_Iv88!6e*25NMN< zsadAn6mode__9eH-3TU1O-!jI>O6ytwzG#>nYun}CEC6glOlucHm6EDlQxFOd2QWx%Qg%IxMOCOCO)<|LF-S-xXhj2(IW4o|%0mOwWf^ZD*=2+nrzc9o&+vMXw7}!)o<`%9fIR9P?JB6p1OWadE6=#dS#e7~JfF_mq{Z#EisT=B(8I&ooTqKQk-bx65 z`jUg{21LdT#r_iY^WbjP6|OHCnT8qj zqkK7bVuA2|iXRy){nS_t<+a*LInJLvFBF!BrmlX#kZXLX^z%2uhMcIW4{Y0Zt4cGi z*HOe-i>Y_{?)dK&D8P7*bO{@6MNi&^BmLkBS=4edA1J=S>?g72^N5clM=bsgF2A~# z(_ayLTIT()kqrc*!-`f8+2(rB#6}nk7JWObzihkZ=~S61jo(s`JR9!y(kq^+gjJOh zZJARFu8`F-Dm|Vgx*gPCvSP@RdN$7pI7sh|U@JHV$!Gs_9ATVCxrx8`)pQcD6K{3V zLOYy;L{SbQ0?Q$Cat10+uDEWtJ?yW%2!Dzt43EsW&7wal(u>$lmb*uv-c7Jf=ieMo zYFQwc2($)5KYvo@`<&W4x`|?)f03KnkVq-F$RDy9OGRrbRU!E%8vA?o1f4@1jl^4- z_&t^1s^Y-|OeZ$%ogw1YxcHtK7foVOWl79sTxSg`9W%0tx; z`its{nEd`ic~F?IfH=bUF^w~B9=mR62Pcl5cz?EcCxx34b|yhv@1QilxsVs5-WIzN z7Jo9G@(2>-U*$9f^*-Z=F|qk8_Aw!)c%3rz>5j3#ld1w6t7vT`vehYl!KJ0es7yk~ ztCw2+Gzh*`Kl$xiPIj0Zt_MhuQlk4svRf#lgj0lJjbj$_x+`aqEFZ`wTbS|;Br1CP zw2{5))VZk49k%Pl%m#Y=Z;kAFk0A`zD`s&aNS0QWlq};tv#KRa8Yqyb44h$-d9BpMd|u}Mv2sTw ziP7#My?5^q-U0$lqsob=;4XWB?qqLQIlDu+^6FuQvs0o<-2)`<5)`Ef21AL}fQ%ct zhJbqBp~KV4*)3iEXV|Ti;m8Gx%e!iq0*JrR1u^h$B&NT8QH$551ILs>2>dI_*tgdg z5mK~3eRg$RGx1_A`&mP%X8fTr1N!jzhT}7=w?lVBRP)U`m)fy_;8`b zLfiY>5aTD;Y1$L3diGj)3MjpXs4)xCcNWbFa&tR5^)8t_+x_kkTI1}(qV?S!Fmc@z z&)_L6u7?2$T6kISQR6GrsklqYTCh@>&X-Cb!o$Km(O!8VB7WkHs)e>Fl4e<0{~0#c zruvNE6%B`90GC>Z)I5QG;#in-Mr4H-+EA;<)gSy{KJDMKjpP0l00}L>m9EiQ6+CUv z5&8c=h5~|b37a)#g!54LgVd{x#XKmu?RjnLpCaumB2!x z`&l|n)PN0@%~OQ|ywj8tttfo9&Uhn@?5rLMpeBjtaRO#j4g+1GlpioPf`$*x8Uy?= zx=1xZOi<7QXx8UrS(1p%3?yjD`?6^BO8{fQ%*T>=Xzr(ix4RuV>^8!P9HF2M!X$Ya zdX%or3A!=>IHwrLS#m3svO{yib+KrbKmN*B`wosp)LL&h-LVq9LZi@9_bcW#ksV`S z%2=2N6q#5Og};gTFUR*2_7fT++BS*x%nz$m*fhMP|6l4ScCrnpON#JIZuoNs_`r6} zf(I%)DL`UJ$4+bmA>+%QK{sBda4It6w7t28bx!%GY7QLDLZP#8@Pb+@#{hI`E*7pX<&Rdm+%1ju7 zgX3p-Y8c|AqBNHSBDmarW0MZj?!Yd@d#IWkGnl17C%wRq_*(n41O!W>_Kof_CpB|- ztw!S_WH}EtX50O9yY>~1^km|<7<&IwbRYn*ne67zGEy5}-Bb8}Z5inHA*C^*oQ-fH z{tkQZ+TK^C`zhusvg8-A67CksR>cxW_MX?q@a@e8Jvto`LCXqL`W;j=uB9b$YbNU8 zXgX^tFWHG`t*UA%i&p2Buh{iFW2#scm~l<7IuohenR zuygTY{HO}CsF(lA10d0?MeUF3bBj7-vZ#I1qxr$GB^L`lQDQM~b%(woHNx z)4+I&*ZV^!o{$H6d@DCKAw{BO_rTDUs`c`m0qx&^?S<|(zXpAjALy^z?>~3g3xEz1 z$)x*vhJarx1<#|JuSDfVg@p{f1D0&fXA4_z{ZAJ_?la!v8+NXPLnt_xMrA8_78%ul z`DfhXtfxzr;6WzY?5fipkt+LHBCYSy0lit3TQ+i}?7yi1xEof&c-bwsc(;X4>RxV< z(~D*dThK)GC7p;|ELmB_>ws`btcr*h67dWcflukX#8rikZFd&vg5F*L0Njs2XWlZh z$9`a2RxYL6k+cWbYHP)Oz+^8W6q^eCR3V^Uj%Q!q@q9Bf2|}I+-|pf)pXZ*`(xTJA zh+K9vGCl~Lj=t^~k$`--)-*lVd-Rh0T{x@rS(KX0*%W%#d&z$^fZ z-B}y0oEk?$kx$u{Omn3|bk+&WcA2+9cbBlXK{B1*L@o8lT0Jw)_&;>$2 zTgu7s=@km{Y4UbOX7!!;n02{H8X2<$FJ91bHtzTL!}mCDhw1-f2lVM<@#mc_aps#C zH5VQJ_)~B>koh4_&%}&8t%&H+6oh=?j|6p_0LoH*G_@Ha`NuVc)5cLmgupEpWp{Q+GYd2~$zs9?(ex z^^Ds|T6B1OtXCVOv1K{CArxUj8=b@;+lbMV-v!6ObJz+nh#2X~8jpZNrf5b8>J`Qv z#7RLG(oFo=ofQ%O&(4sb%Zo>-&~7!4tlzlggs>@Lgk^h{qbn=4k3ohW)+HC2`*f;( z6UHJ5-^kLzehYLO`HDD7%zoC~p$sg10N7TL0 zr7E*7Gq?ZdjI*djp10NYgM>1=pOGeyniqs0Q(tN)XGs7h1s z+fwfrNf7fPFUH!Lyai;$-bYJQ^~h8|+(j&p!qMAlKDh&rct7HZn>mU|v8ioQq>2P+ z@IC!s=r~2e61RM1JWBp+>&e=0vmq?#emZvy9?LPSKQJKIZdltXHm#ZU^_@Arvw?}< zj!o)0kiHW*m~b4@z(^J!hJ&H6q`Uv50wxFY-Q38i`mi1wH%!hsK$83_8|Txi(a~Pw zqq7hsZs5Yk!J~ykw6F-T1eVOb%M~ugKLmdV=%-?F7=Qo!41y9^iU{b#L7I7U-Chj5nHV;6Lg)nzIh6+(QQN{dCZ zDOvB1W8yl{6W>h0ywN%#uu0Au=2tlLxEYEUl*?5~5Y7$vGh>S>C@Kz8nk8gCMT5&E zA^orK|I6Y58P50y7x)+TJ*`B~)fRm>L%?U@3L}p0>N)qx=<6t_Bdd6M2@eQ2Rb1fk zn%42bK@RvMJ<+C1SUPvx7bYOctV`Cw6mrmlY|68GEGy}(2A|wT2ocmC?CcYX|6dh2 z!xB?$8RvnheBQ&9%b(u8MJ+&@)qeGcp@(mOrxI9MNrh|tgB5BdC&#+8r9RL}1V9X| zU$y&Wmd8aqG5|-n<9MySA%-6lUF>ve^uhzwoAM0ME^ECD*g)NWT3CC_T-(TbLV`zHu@8ZvEs_+dU-&t%Kf3h17VnbYt}u&VIv_E( z(iEw&#Yyhu(!V=@MR_#OCjrYbO~w35@5N}X>x?WTJ5*seAyG(07LV0mKK*;jJRRW; zuB|nqzz@;|iCX+Bc$grD;qNaimmXm*UvntR!2Lq*$qnaHg15eM*o;pu*bR_3UI{+D zC_ao3=>FbLaj`ecB+7rVN*h;G8_G2{uEk5!P3q zMNKRht%-5L!&wCqt~UKzNv~ekAI>+=VlXWGyd#Pm26d)%y5-u@G# zlY}yfzl!X&Hk2ouwIIl+1x~uTaWS`t*ueTG9fqD${}U3$r8)AY5I}W(b6-d75((Lr z6{SuGmr!{AZMY&wlm9Te4gc0=3sJjf`DuwGE?ZVO_;_S1ozm zW+x!VKdOHYIz{Vk@&uNBW?(A$&jU)1w`y@9A(jF3_4K+ZevnvyjjN%ZH!sqY^>cl~ zxwlQz01Hm`pFcRo$lViGQ<7r!Q7k{9TG#v?a9q6r;9uH_SEp!*xj)w! zNtfb~zfb0slvR92sSepMWtedZc_45F7`U00_&r~0Ovg~Z*?`qEy|AO-cT1~mt44ew zxK|V)!9JYuX=?p%RF0Rf=g^Ks_uUsIUE2)T)*lT2`fQr9@`l)ul;)PE(&9WL<3sU} zTjlC14ncl~0%L{jM{(AYn^VZANIs<)egmJRZ8Y4WE8oc;K%^#R$6W7GbMO+*TeCyq zWs3MYCTfydP>IEAn)&l6?&|;koU-u@o~VUH72rjune(@6SCLH*5QF>;Ynphihx?!Q zVVBWqT0=x{0WXYE?`;Lpj=w*+M1T|E5=a!oktEAV;M-`ex2{V%%pt&PSjXTfk!1bu z9Qv>dnaoG^G-3`4RgrVTnkWD9z!PC8)`8mWQxUoLnKls>?nw|ow3arV@(5SAfZE4l zGBV^+y?n5zrOe@HrkWpsC_{*X$CGa}0-DSG-^!fwJEW3vK=C`dYUJ+@P)%T>Klec< zuuyJe#Mjl9dMS!2Gx4RIMg}%wC}>z-78BqOrl}vch#vl+rp-=s-T?WoG<=cpZr+1u zXZ*~A=ODSM;bap==V=!&o~IPhq`}F&Tf@!!o~|A{G#cWX%4NBb$7KJRU54rrr|0%Q z#l9AUc7}3RbW*p$=c_`Lr0yyw>C`*hHN?$S&TF^SIn(YU&25rtE3++E?LJS{k8@W% zTfR)RL#v_;sNf`+&DfK0NqYq0O_FwZlr3@#MW}{?{hec#rdUxWafsi$gbseFH-jw~ zpdq4fehKmIPi(eU%UUe>B%$T_QZv-1=Oy7Ikn86Glp+~a0@ePyfrad(KUj9C%(3>GdLgIs&Gk(s~gPusNCVls`At5e_w zIiYa!Y}i{w=O5&TqhEL&=^Hp;d-8Z^Hwd=TG%fQSXHN#*drRJ99+bbw>cnM7Q0Er5 zn$?(zdWjcilYQ+OkjtF`CB$S6*{Br2{#Z|dREC)4mk46d1tPlnD@6I%@Ey@`c&6hQ zts&zp2H1#yq0xDit?YtYG^$@YyY3&<7%cVxV|mu2P1G~}gnyJrO-8X0HdKC-dmwd+ zB)P0oE3|m7RdQ1SL{nxRFQLUUcx=?j78W_EbMO&>BNBldTdM1)lzF@0LKZ6g*L5(lfxu3gC#sx>+5>+eJZ8PjV+D;lHSAX8k&->VAB;l%rcGAZ zFJHoQuz_vAQ1c?H0{qUz0#cEPWS*tb<>VLLI{rrMO#k-FX;t-K(x=41dX{SeHjPqD z-m9`|_N7FZC>{wT%+2tfE7YmSTD>Nxb#RGA1WJOrc=ZMUEV&sIK0hp@Ir zbe$&5wi&GgmXI%@$i8`LAP~s3MakL(5SJi`fW$>GofA1&<2uM5DvhVHb}>~ToG@C9 z2?%F#F^c?ZolHPjfEZRi{BXGqGGSTTm5WeTBTr7fvHkDxL{JK zzw*S^#n>f`Z$%+@UHoZzdMOfmE6u*~Ui)2~vJK$=%kv{l$c+u|({J#v3-PlA2Fbt_=&1`-0TyxmBL&*Kp~GV~ z7v}R@O@p%5;wu5Q=Fp&~u6%y~hyWp@)*EV_rD(%}MSI!Wqa4wl6hb|lrxSVbHSz|X zZ!a?}S@rE1m(x9}{@^)xK5|MOUi66m5vQ2{VdQ_>M)niNw{re(<^e2aF{Xi;Q2e73 z>Y`SUAA_rEBvO~PDo6tKybJ%f!$5>%E*ma)*RLeQ@vM)%5d0ctY)Ej@#=HuEdW#!# z?4gbwmy2Q9(u|{l*Tw?{>}aHW-2wTIRRBMp6|Exs%;PN<_iEo*6YhVuU4RzBXN}^CKK98tZQbH zH>(R{(6c#e({vc8+aK+HR*HUUDm4#Jm~xJt=mM%x$%-X$Xh90UezKO#5DOp36#~i6 zf2&>E9lTr$@oDicn)g9&t2UiwH3XO?EafA&PBt!)?IvVEsKvh4v>(XerThpfWa2jsyqDl6ZdmWbsvg}33Rp)909F5-K7b6cE)L)#;(ji>5^ zSGitFz$6;ahnjhg!}X~QBI$SJ(a$<>s-VLLYHPJvZ;R!2g97%rzWwXha?ViA+0wHu zrqy=>T-b}44+674`OR#h;?C#`C#jS64A?eF=dsZTdUn1>K;GW;G1fE-jtkirYZ2N6 zqzb7i@_n)av}$Lkr^qml&ql;R_x@pw5KabpwVCtpY#u_3Y$H|dLE#B0)#HoCr8XW% z)Y5GjaG8?3)lS@$p*|yG&g)%{4vX*jIQe=|1=8sW?le^lT>wJbom#^#KJ?x{)Ci~b z96_KunG{%2CPJKuh-b`vVYa0huF@K-=?^qYTMr{Q6JTH!B8r?&WQJZ}+vNNm<&fI( z9^8!-wD+F(Y4hwdBK`|W?1P1-u6$7FSS%#ymhG3#u1IKe{K5NUVTbj(v9JeTzs=-? z%5Ys6vmAykmG7yL#{0bmTRfu=k{kAhry4IOKJQ(2jOBlDM0EzFjXwE$SI+C3})0MU-%P6O`WJx8GR)$qQ;d0&to7#kwW5{Bc4{Ye@P zcaGfQLttv~n|pxLp?1al?*rU9Q2O)AM^^#h+U6#%E&wOC!EH=e>>`amv)-y1fJ>>` znojSQ?*jeISt3_y2K`8o5XmlilvJH?A!aXngtvma*v5?QK#HDn3p`eh3^$EF4~;7v zb#f#2o&5cof#6!%Tg^{qC)l7uuS;h$qOkKlIPbi4_vy|EbXdzL~b~eUQZ|j=(yFvhTPe!FZu|E zQ`*&CoDu(BH>PXuTH?QJ8a_?2sv;x}8-2IeDwk=qNZphI)Z^ECFf`|ro^#T=N@t+_Ul6C1bp~RR>Lh9>Lb%MectRm@DPPFMPNb>GMb|>zu1S9d#L4jd6~XB)>b_i zyz4h0w7x{HYHL)gLLX&_ZaF4wRXms6*t4choaq~!q})XI8!pY; zSd=lVx8-D`2|TCvWwfpde32suy`# z6K;&_l#O0{Jv3R%DItI67gShjWKWC5WlM`@_?i9l5OU4a-a;)w#uv`3Q4NI;&ZQ=G z7px2-V6IvZFSp|00>REMo-Ygn_yN?7VpsyZE8aPekSDgNC{^EjTpcmAB!Kd>8RhOC zJsW$<(g`ouH2*VbKf-8?fxjAyv#J;9{4V6q6~|%ztKCVAF80T;xdNOp9{C)he7I6M zFPe+|mC}ZG)Av-8q9nuQ4RT0SWp44QYBMOCsMNph4vnya%~lvi+GoER!}z&g`-W zW_l$uIs5#n<>kvOp;NYe8eXjm0?Gy3Hv#_FoA&@r*=D+%|3(uNIE9R@Xh9pI<6FS2 z4Kzk@*=j@4>XWYx{T!YiCC^!yskw$BF>@mt-5<^AoXv`xZ;fzcFckwVpr8WjRqJDS zih{0)T}Ef6jAj1;!NwUtSV$(=2D-zHKqhhD{B3-D$S}$ZE)PB|>tsi8A+yLgB^!CI zfGTli6S{O9%$<2Ww|r48-8pP11;cnFM}C3YR^`@q9qV}^q@zpjA_oK#l`iJZpgev6 zl4t-B-*_HF;&ZxY3rP+A1#i~~F&U`bZZ5k~j4bx4I=!W$vjYkk|K@SZJ;BskhF=+^OAqxn{ahlznhV0J@vj7! z80^iEXnDh$wcSYM8rmW+6d)`@OB~u73-8I->p40qEVy%3?l~@zz6iNRV)IV?@C4NxZlT z<9(R#*7_S#tWx*)dJMV_Ycgh5-kY{s0CUprA9L>Lslvrya^z`xa_t-5?Ul_?U!8jn zpn6#RNlbaNTi|-0N+Sln!GS zrgN@a{DQOne`-no-xc}37N!84<}2WK0H6*RK$FWW_#1}tzalNOMF0RFgVe0&LM&Y3 zfGpaw^w(~Z9&!kht;Xn)oRB8~!K`xbGii_b z+Fw%cIW<2%A@~DyGPB&sPB9vrYiXs%J2UR+C?2X7f&?!~P3-2;zC;PRSW&@(vp9ZfXYLAQq6zIH z8oXNH){dzn+~9VCv4^yc9D(PxNl7yNN#qqtIbl~hL`yZn(Nz4HB4U)u`S=4o_b}3! z<^>PW-D-*}dZO7kBI)}b)LVDH-X?<3|H z>s>3>5~=B;I7>5|LxcQ|G@3XEqI)zhikk!$)eyo-KhY?Wi?IF*p&V+L`$uaV~M~J|W&FrEdK8 z>5q(ydF6HCwLkV{n3Nsk6JN!L&H$U~5*Lb|Qahc2!eZrD#qvKU_x;E2E-*xTr~Gw{ zj9mo1$$bLC4lbWW>{j<#)k}vY=^3&W^S58(UX3D};6|#Ds7c8ewRLSwGR<{{qvv<% zWFGcbVQc;{R(|7S6mWySGvys#`~4F~*?&x>5L-ttR^om-2u(zaz+o1!d8NQ^h=HJ| zNl?To^nbuv^r-ZCN(Cqi5I@>moRTtQdL7m^ich$gsT$9sz3rQrO(PZU`8Ay6s+^PL zl_u~RXKvuYNZHD$MA38#`#0ohoTN_rA^By_#h8M3jCHG={GGCLfTyoE zhy}}OMpW)x%P$5sTNiNt#pO%EY{IF*o&SOY5OLjqJ8&b{hRv-?7BwGIPQawX5UadN z@n@(^g12xAUb#L9T;!h?0T2mu0IF_#rF&*c$tz&fA1@9A(D^aTQZh7=OOxvUc0B(F zloS9=xtW>_MG!ugr<}L%Zt+k#rPz#=seQ96h1X@((-_Ne+$w}+jid1dqkovfq+OL< zacq{b-Qh&N_ogUG)hDWjMWzwf59FEgfJPJ)x)-P@62V8PCydnh7fXlfPj;vd#B}?L zts+<68TmS-BJMx<)8hzC(9P&?MN#E?cZ~1=kf5u0=!cr z;p@vr;zPDcf3%YPg*FO5;zZLb$_xXJC>smV{Tn z67u*BoLz{cIN>gv0Xl5RHnT?0)R%_;%l3Zg8k&Pi&b!OZw5M{|a{dj@wW!-)`c7GV zkv}se-{ak}Jf`wMv<827s{AD-AHuo@c)jUw@p*z>PE>Z{dxo1}iQ_jdT_H*S&LE!T zyGG@0KC@AD?}X81hEZ)2d2OUV1M^`rkz8!|$t;xREU1Jm^%>hzr!}LlP>`OF;n7M+ zJqdd}Z#<0{-G5P8+$Qi{jonE{bB!64j({GiR_Ow|PvV zHdC`6e)X3p8-+8n4b--pX8?!9mT8u1v#eKKOhT#P3;ihI{%g4ECnq#fr}>S-xr~KS z8z{nXfDmnpJkZB01OT$U={mT;vQs`zUQ81JoKA;m1Eoa8_^DI?AhHC~u?Esn^KUw^ z?5T|bbY}XRb>gZ8pC#sR5?Kln3h0X{ogku6HuDZKO>+8a7TUm#Q0>-_8!wvSiQnMa z=7Np~PQ;50M*9U%H^tw6kQ^#u`z57G>^YcTr$sOG#O4oy{Pf+bREgURc+l z-_hm|q~l)vp^y{KPwI*+QW6*~1e0Jc*x#WpQb_F8jCrN$FI35MQ`IiJWVBh~wus=$ z?n{X{x9H}FIhk8m8gLW%X5a1Hvt>xJLWSu2E(m9LX4_^QSBn$365u~U#D6(?%Q``G z+1#)k0K&sITG1;-9R?>v-dWXH`bcBA4cHsB{PHqDqMwB(e_zjb)PTHl4hk9xLSKR8 za})d<`e>%@W-k0*@lr|jW?k8H@#7}7Z6h?e8!Skt4xqw2UEVJ4N1J@T21u16r;}nL z>UVElDeZ^IzkHlaLUzNUqS6^Wt;~jm?Uc*NgmN*WS}g2&^Gp&J^7JY$xeIKAm|?&G z_<*qR6|;G`o1oBn&_sfO_U*>;D)UdfE|MFB8i18zFR@$-)y^hy#WfTOn_J&&_K(+` zy3(JyKUo8S!xuRHTsOjJ+yVtE4erpEr9BP07XEn8nUXFgVs})fnvNi9Zts4KW=xzqmBl3-q~NQ(yvT`s$8WRC(YlK~2|h^B-@PKzc) z`h>y=B#9C}gX4HsYD5B`@Ux{Tg#T!hr0VB!wTp_t>HA(AL`170nKPj1I||sjiB84V zA6#GiEZc{RQO${0(u2`1UA>>cn$Pa9+&ox^d)A@omR7ETI2C2QULRX!VR*HfqxV~k z)8d@X%Mt1>aT+CR8m)5V(}{tZ9S#YRH%@jF-}nX*!_hP$-gP(+a-f zENA4?eqraAK0(ec6`FUN)*PkS$L=^!6n`++b3IvB-A&hE8zuH0`m*PK*)_%9q;gwh z^HyeQ=QWa-Y)G-^+W4%*qxhsNC7Js3;z53aM6YxLWd#Z*ZSd|f>BEom+>{FY-Cq9` z+}?PuJ;%<^xaEM9Rem&Sn)Xzm>C?Ui?qEpDji{GRZ@w#+LDrwEzIs+SHc9(+N72I2 z>MnNKa+e9B5t7)H`c^ebF!x4lG2&--&vN?=LNbU!>hfHjFQv$1{kw*E$BiDJoiSKz zo$n%hsxq5&A5b+YH$#Fg7ZSS&1L}XMT!ux)6toMMa}DU?!>!2U$c zqZ`eG7Gb?swX42Gl$+{BZjVJsvg)@i-oKE>^?pmfN;7}VKJ9Cx$XD|z&apuJ7F&y6 z=J;z{={?BN-6MpTG11Bktd;-_GF2*ryM`#FxNf(jT;kZ3-{2i$2Hzn`k&j>LU1pEe z+!9aNSz7^@RA%iZHd#4}cYG$g7CK_~H#ZyJlUhnwTe*JEwiL*lUDh$DfvgRgB=Wkw zkQU(D$H~;?mufT@WYD=)l0G@2ipIhD!ED9?-wTQ4~w2?LhtDlDv#H^ZuI+g72v2M1wW zR#w08)XE#I+cyH`s<~T!nTk{T>wl_|n1d$vI5^)eE#bEsI?Z#F!%mM0>Q2)_Mk?$- zyu6$2P<1`$xp;uk)depBh=e^mHA%OxXl7CcB>Oe=077?eOzPUD(T`!^ zjY2SB@jsu{f~^TbulA@4agRf^qCAP}=u7=2 zOECeRvL*ZLN=ngRW9{M*MWrEZ*Y@ctay-oom6#`TNV zy6edR<&5m~#4Zg|2E%;oh{i!mEFeJ9*E{abpwV&M-qUaW<5o|fYWcIsyl`iy%Sl8y z#)N*E%KZ-h#xBKCqnsZ0M7cwXn-_Jf- zC~&}b089@N4Zc{fPDCDj;xlo5f~9(iGDf5iOX8H8k_lr+B|$8zzmlZ@EOZ7{LfE@L8H6{V*i5=Q|5o+%!j*&z4{``HNWEKh?600cs(Go(;N zpGTg%;QNn!-WiJ~h#DvEQo`;NELoQo$p=^7FyIkXy|FOqce@g10G0%kvl{??2k6O# zV*o&vY%Uy&?y3B8c(UQM2cI<&jITPt&R~#-AlM!dtouK~Lau8ip8{A(HjqOzU%3%^ zr~dWdEkl0sGFjlF+3t426Z4{;k#QY>##;fi$(v#hflKrAx@ZTI;m@WB-?8y808Zqp z2W@$F|GUrToxJ!)AWHx>J2Q&Jv__eQxVx+0aw}*G3-4_YWTdK)P}$#hyHA-cmFPeu zOjlnm2#lja1!eqI4FEhKD*%u!hy&X5S$joT?CmKgiU1b+^Vp&KM+~)^DS#~qIAcIE z>OnH%|4GILW?XqN?_#tG_#*=_(da>JtHU$JpoWXoT$K?3#*{_%>Y+YBU13^_UhE+> zpx(XWF8S0__@FfqKjcL3-hT9n3&Gn?J7u$ux}_V1k2^o;_Z0d_$;H?cbtalX%BvjW zEDkrIc5v|aV=OES%vxlJ65+l+fdAEo2Murqc2gkBV8Tps*f|O*S=VUd7uMiJmV~>I zOCabMAn1{af7n+LQvetPfEst+)8@atF(7#6LVyOtB`UoId%b&(TgUAN^9h=)X3Pff zQD-7dCT;`3qL;n;0*P}E+Nz-#ZqW=qoOZEy*Fy;K>NUR4Jc}S?9dy_=kG=VrQpZsQ zQTr1qk^sdcICWjN0ItCa5FWR);&8y7%4i5JBDxD+2hGCa)^|kVA{^Qvx_D#II;uji z9$(f7_<{cV2scp#J_B_UfB=0tKru+b_Wu$9Nv8Nc>;V4BmM7*TAc_VPAg(z28FoNS ztGWKoeFT~ad*-|puC8nghuL~61~7Wq{TRZV%vAa+Wy_c5*szY>7G2y)AoA)`$u>7O z%y}H8Xo)}DnV$VL1L2Sc?qKPA&H!X29$jp`0Q4IQxCX7=5JJF61j_Q05^mwmD4lz* zZlOS&Ly&xFf`8(?fX7h|o_7K$&QEpYDQ3SY1WSU}BMX)d2fq+kc&C+~XUL(& z^=`WYXeFL^Fj32+fw89r%b7h|{npC*IzkFsd$mYnR!uU5p3gB54QNKc$Of*&4{~jK zw@4>*smcl?3o=C+cC5(Fd8krLe8~44b4Fk&68@}EJp;8B7{8q$77R+u7tSDd(L1pH z0Q;M2l!nO=To`%(A@f5*XH>y$+?lwfGkG$$LI}7Vfk`T6OP430(9fPVYL^1=;0s#7 zW9c93ozWj}BDwjC&RQwY+^`7OXP%pX>HUn5bRgz#J6%=}hx-%Awn0J{&;a}P<$c2? zz>M`|uV8$hX46VriE1SRv$?HWUP*&(y$D{r9wjfpN%=5SZk$N0q)k5P9y=l(I(Pe7 zor-{gYBH6}Rvj^h7|`o(`SR9UHeC?AHRa1%^wXGevZPC{EXelB#)6=}Ex+LSAGx9` zsY%h__kB2YA2NNnX(04jVelYek!C(=78o+4#1@W_s^*d>aY`F)HZjf=o`|T?Z~wVM z#y7R(Oy9)h_RuJv;_~}+K0W?N`$B=fB}p4wlh)FY2HLA@_$aD;SyXICE16nXY~(od z`>Cw9Hu7#WNVYXCxtGw+W#1UPnG~82eJUg$@j9ZJu|}F?b%430?cR)L-!JN{8NR*b z&O3gxdRn)0hxE?ADtH%>?&jILT`M~rFIt~sgSU>l*8)u2(+iCr!>==7byu)eJq9Tz zlqvlXd`w&4<}(UA8HEY12+k%E$cQ6D@8TFG55XalulX}t;aD=$=}d?+$%St^RCWa zzs|JjnRo+V+Q61qQcw0%;!RLnU2f6u?=&m)Kfkh_46d7Dhl=>qlX*9F<=`4&YDxvRH#%PsSAXjL@U8a2mXw~+ zkdS20P5D!-jqZvCy{n`z_g@xZYBrc@mR$YFSQ&-#T0dZKEN--(2;G^Z^1Bi~G~XU( zrPjqsJN7u;)BB)+U~H?AIASh^N(bI^VZFs8O`zi0 z>az31nYhY*8J>;Vm8x|5wM41C*v3nK?Va^Y6|qVeOObEGbHXoQbC|sMrDJ;0l~A3> zWF(GKnm{nHo9y+4^R80q&#yh(T+ErQnq>{tr^4DIaL`_Kad05MSFk#-*2@c(-cb4$ z+^!-PmpotVj_2`}W=?bGRfxM^JMai1MaiL_jIYqR&p@2kwc`(8sMWgXx*vlA$UF`W zIK3!)FFTFhJhky>QJ>K$r$&3w$yz@zRhO#k4HMWQDT5zV7w+DZB%lGn#Wf^fQ+wl| z_6j&G0PTfbalxGblOgN{M+Qvv!~kp@@c`XKE(H>z3kxGjM}p~4vq#GiP}pjt`s;BP zC>oX2n7MB~MiU7wm%aXhWdxDafP7IoFW0+-?|8wv&}(EuEjIKVoH zBVOg-IH1e??l>AayC1bb+C*PK08z|Cd{1$GgRL^moUC@}CkPR26zhMs1WAXC zB`zep7kkKN-o<|Zx+l{U$^twZBbsnbN{s)$Z;UJHesF^-kfbU)*WS5hFFUa%797kd zGyp*L6|=PvHRmGyLWTo>Wcc|Ii#VWi-SPKL@x)s1H?vUm3`f<>Z!6Yj+IA?H#HMDW z0DzjErV0W0Jj}gRiM*yxU5L_w*@}4G4|{vo-hf7lm>tmyYBfC1EZow1bu(}#YtlDm z_hpEWteqNP=x}PuT;5MZ!#9}|fERBC{ocEhp2~nAKC1(5E8YpVFk=>#gbzXaAt{`R z{c}amyVP=ukK&6PgNVXsS+3vG8f?(RZT#`^yIm6j)f|J_o0egvh1-7DK0P%sZuw^T z7#E@1&%WS3EvMPgO4m49O0$N(-Zf+&ch;_s&!o`E^F!TKdat8nCgf7xmcPD{WYqF~ zf;NGQ0OabjeZfKp+@mT&F!h$-!lbLL?w;1;*=B_^kED^MfK{47Tiw`5b`NAD!Qh}1 z?o>zawK)4)M&p_#V?&#@{$nb4`w8!U-ODD;N5!Pa!}vET)Ty5xGLF!S^^~pT-O(mM zuPGHrWhEzS?^rVY2)3=>x7Xj3#H{9sA*zSPSAsypeNEKV zgzxc{U<=M3kH{Y$G9vDN<*%+O)l^>Pc(1WoYIpo`BK^BH=hmyd-TdK^AjRabZd`6> zb$7m9<{kc0v+5tL9Z4R@F${_};Duto;fS{CKUoQsZwMmKZ5NwA6UQ4x$~JgtW4(YZ0Z5B5K z-2@(JafL(uX>FpTpvikgS)m`*Oa+bMGF=hYN&QfoT?pv70|FrV=G#X9J^ft(EbpwR zlc+x=AeR0F&0c#p04z^SE70~^0A#Q288H%o9wRRba)$gV4+C&Ok1sf}Anw<|_0@lp zA)(g`%J>Q0F#s0m%7n-$W?zqfbulCVnvyu6j`+`(<9}-X4qV!8{scCPjkAd+{y1U- zK=|v?-0#r@=P-HD{2z1#iCD9z2%k|{`Zdy!K;WGp1p`Iq?I!xh7*sS&M@$(OO?Kcq zzqF6nH|jrzWEYmqO!p~wh`f#cQ4X1Wtp7`lqK{dULPh6v=gl=4I&!b3F@op8r{Pv{ zz+65f<3>A886AJFH^ztTh4#P*db-l#!#bI{jtV{H?vtaD@X9TiiGQPdyHh4S?xQSU zoI$VJ>u=*X35)OyO>UVzeqYi90{|{ zXvwTk-rq7PI~bo#CPcxyJ!HAz?_G`53~!^1WSt3QyM7zBG8wKHPmsD1IGf9 z_(SsDc+FWlf0zBM#=n#q9PuX)_q=b=0gQu+2iu1M__!m#;)B(Isj+A3y3n3+48cyn zizfhZk6&c}ZtDWWJVfWtMP+c}T(ki~0^GsA-5vhT!Js15{!eY9!HdFR3xq5-7eVZ# zKbfpZ$l;&di!T1zT_4BqtQw=g0yKC(H#k7BME$m#Cyasp5a|Bf{3KBlY z!u?6uM=WsUJ8$F^P9_)zk3K zl2>UeeBzYDTCE#>^(syAU}+9kYCnO}Fz@1?$75cruL)E}g&bd$nSBDp-OhPRWzCGaNsv%)l1N~w-}rg{9Nx9(K)AewAhYm zt6->G;a9QyxuMj1>}j~RfzT<6b&)~V+Qc;2XL>O6pMRh}Jjr;FKYlrJC6yLwerQIx<5x(DjM54KTzJa3#6nEh@rn?it(xp!OU5hj z7{w}5oa4B9=w6uj(BIVpaI821J=?2~lvXvBcvi|73lq_i>Q8%0DZTy6A=~+lAG~hA zC<;#~aRq<+HfhPq_mca~XZm|_1IXs|L!Ec;YyuT&W{RvTEM`E}s*hEmHYQxnFD^!00_N1})0my|RR^^3n?h2%|Y zIqP~(+MWn4#%FemcD+H9c-02;kkwBzs4o?Gu!L2`*gP&Hgk6%s=cHW~+nM8dU)jgc zSiJkrww5>1A6^KCKaj@er^e9wLmisEB;18*!n$T9-8|Zq!c8k4KXG-EY^5{98lTrG zI3$>Up3EU3PkvpR727yAgqA!LyJY>qkchAK=v`6BxP532Su@5*Ph(=uHGoDXM#}8% zz1Usylo#aRi{&dW_gzO{5(EI?JtRM{+Vx*TZSwFrp5r`t$dxA%wthZ}gwH{#Qa$B~ zwFcDy4n;w+1)As->_wY!UR!zaOaTo<%=9vP9nRb#_n4ELQ+&Axzg0{+cl?!sSM-5( z`D@O~j7FNelE~d57*<~UWc{NrBa4xJkplXLTZBDUJJCv}M)Bc?g4%T6Jx^aDom2bY zSV&9t&#L6S1;sH(#-UK==Lu)(aJ*b;l7*JUQl^}^D|0WRzUG@baf2~6@exO;zm^xWKFNKTLfOYRbVAm3p{ioHI;kTZRU&mG zyu8dvlk_on_M^xdlMcRP>RB9^^dPPV1VV$63Xd`Z`r*wGQh;gq5X}iwOA`_Py4nUr zP_Pj!_f2GzQYmHtIIlpok&yg*1b6;h(&H^J{RRhAp#ca-#YGg(3%aWC5a&6ICv>d| zGf8S$BtZL%h`Qkhc77L8RlyAw$g^d7Un>B2kOGM%ZXT6rs!NKYD+H@R%g^f(QD3~a z28KXgsRZz102VYB8{sz)$wLqc@Bbj7)pa{Uyd^JgY#O=2x|ChJ&hSsjPo59a=LADj6tjcW3Q^ZD{>(Y9 zo_7obCB@{2Rg}1=$zO)qImp^t(LV_PLJh9Vt#UaFdDjcN{p=hkec>NRB|POCbz`_Y zIhtPp=ECp3Aium@X_^u=#FNI!;(fa-!7CCEr8N_kx?X~nU1fw^3s=3`=mA%ZNkip4 z`C=Gj@|A)y*4N^QT3@U0XUna2vbSmE6F0O~VAZybP6zp7GGBJyT+%)g8Q1bf$-eRx zGkvJk=58(iU9)2llQ?b5ofLI>$8g^;DY2Ldo`bqp&H4k@|*3IP%6X)$3 zA5rXI2@UC8c1mS2+@Z<5k+!Nai;ER_1rwEFdP$uR;ERg6Zsx06jCh=5*mA_8eicba&R6awPoH<*~C^BtoVV_lEGni|1@629zY(mw6hk+*f+O zcT=|T0^7yRv zU=yE&L~J!|lS{1L1Wm-3482|)jDLC8<$9^&jwRdup#&=`WRkY7)^GVaKJPQy`7NUq-u&Rj-P}mAoDSEn z%c7>#?q9^)yHH|Lt)V4)3qZ> z!a9e}h!q1DHbmU!p37>y5Uu|!DU4LsO*s`-IsTVH)`Z)!%C>GpvXiBI?RG}r_WIhs zc*#*h+vnaSyi`b3QwJ#R%7(nVcuHSBd+(3-{?2=|2HsW7momZ=@D7a^-Zz%e+)3#_ z)EZ@dqIPZcO}6wyA?*$b+f=fP8SjUKWTg>D^Z~}!th4LWboa?vK20UVr*_e4m3ygMk~aR~k%?sH+#ac_eSG~xeDdby?FVY6o%ii-eeA;1DYu|tYB zN3HkRhmyd1#O>Kgy*Hk5ijcUmOCQ}AsWv$dP3{rf)J!jl#9G z5CE331F)n=oT~1~H3bkNwLot_Xtw|nAfovH3z74m+F%1mzrzqp0t-;07aIZac36_w z90_R4@B&&!8Mi`NBTpkV2++4`mhfH!w4Q){D4tCXOOw|hBOB_?4mQHK1OTSsi@zdE zy{>U4q{FVjz6Ai#j{yJ>0s{Fj<^E?l{xdFr1t6ceKzV+hwh`3r@M%!PgXi2XwUW4Q zXrxL~?IM@pqD*Z+&_G`7-Fhg%DgO0p=W|))#emWvOYA|P{vhQTDDn+4I8(qhendP9 zchC?8FfW53GC>gA|D#6!FC37I$AxnbfQT-*YYbwI3z90Kt%)u{NS}^z^F`K1AZVCL zo5F6VlP}K*{b&z75VO^;Nh3i%N16A+`rLBHFB>zc2J3^cV4JL#26Z9eW}M7&006lK z&@E%BpLE05RC#zNUc)scFran;fDTB0!hh-7PEiUv;5qQ1;l>}QS;`qZD zg2;r9pDUgN?A4D%JL_L0YnZ!?E7fbn`_pSmkdoccL~Vts$Ia~GbH#@~``s(--8IhW zHUL(jnu9tGzXPbDuup2JW)~E`g<*w}flmnru-k$ZG=UVH>u4Ng;UB!`BMYr_U8(sy zfo16eJHUB;9|8f$K-Pc(<|fNVSjE6AmG0%ScYCuodRgT5-Gfb0Tp@?!(ve7=6z_MH z_A@A44B1FiZ*J-Cqpnb9_8z!|u|)Bp>L=-_E7WE$lj=#|g^vJr#ya|hg#d9mfFtO~ z*^Pv-VB&a*?N~ozqN2VHu8lCiC}*jnCVf?e_|X#12Iwn-`WvE{olyEme_#JwfA=1* zl!N*mB*Lo2w3~Ox70sFt&Z!G_f%INZ?Goo+lmze@`Ozd!03y<;kITyEzJ_JCC7V~) z$R@e;0`2-K1|aiOiWU^*3DBzQEWo_MpL`(oG`8)j*h2Gt5mqFAgz<8w?l;u%stF{Wvkhh~{MS z)SP}D%Oqz$wwE;KOQMbJnq9JJ&wXXMjEST+wYHqi*A~B5IRpwp#nA6knP!$h_?b$T z>kglCzU5!Znr{$vgcI%Q{fHGAa$!^3Gk(~_DH`!|5(?+*!g?BugP4*&y5WA4`MuJ^ z#{6}~Is-xZWAmbw(LqeKL*&|X1|jySAtGt=pFD)@p}16UdD2RGZ3pWWZ@dc``#=+K z{U(m*)dZ8$&jvvzF1h9j9 zat+`6vaB>lL#9$)anzgC@EP4`!Pkyf`lWp&@v$w$j zxx(NT(&F3JV_%nKM9Aq)FBRKlu&b=EPGF}S-f{)wlX6$6Q+j$ZXfzA29 z>+dh}@su?nXJdpzOE47_AT~Qnu%co|G*yY-gvQd?L87B2nW`1=MoF#+9p(h-1QbfD zP%j{7)a^`8AF!DCM;&djL2J%vO6wV{1mZ?S__@qJ=-El`YAgWISzOJEEqhHTaHeqW zoqWE5y!@CZA=gH3Fj}5pH=l^HIr7)#F27O6-M7;q5U2tOKM0ba7k@ta_&{Ou4}nHY zfUh{%d7hNMcm9pjyYxFB9|Hg?-$Cj6muXNL2uX%{;%BkRks2cbZUF2Xr(Mh#O#>E# z0k_aN4oEaeCbtbhM8l22YSDMnc%1~eoM%G$!AVr6n4SNBO`_l4Mc5_|Kw^dR$SAMx zxCt}azZ-e?Goy=kWqa0;g(7f!(6A>bKWuWmT3SX#!qSr=U-6yn_m5?aBg~J+&baCI z0bvnG^hZM?hu64hQkQatbx{CdP~YA4rHH`Fn&J(Nbg$>f*Ua~iZ<==Ndar2d=bpXO zOVYNZ;)R#<*z@61>@zyL#Y&xeI5*4>5L!mIw7a|u9H^D z$hEU|_vM$OhXK9At`F+l$?nE0juU=lD6q8;q7`+|wVNd`q*1Aw_>rw4oU(Rn)X>Eg zv;0g;?cTCZ<{K>zkH*$(Uz{C`i2{wKkaW#c_!$O~IxO=xUf^JjSEi zuIRED(01{lAfsHw0q+hfu2@v_bpZ~j6DINKp0lXUf0H9MD?W&*@UCLz~Z_8x{ zFCWSvi_!<66wWPVWNopp;XiNoPw3U&k$y$6!7R3I_lTK_p(7JPR?uFWDf&@wJHaB* zxGQ(^o1$QSLt5`k&JoG%M;UiaryJQT7L+Z?e-K6Y4d})01P!-NJdXpQnZqQF0ssY}G&>FD zA!=Kw_Jt8NC1`+L=zA^*7J>``VaRwiu>c16q_w@A1gM*opaRM+s>1-5WHcd*{}@2v zhXJrM#{p)behhE(b(<#u>!P#)!oWuXw1H^0&(V-D{jLRk_Jwop0`zy5m}V$*&pU}J zkq0*-A$e9fQ}uzKQfq*x_IcUQbk_*ovaJJ^k2LwD>vux0@j`w@+VjTN!ff!L-gwEU zJhxRD%X>wVmBQw3eeV0)n?q_X+QGZ=JlMNxOnkQby{;whJ~bH5t&R@04C0jQK^Q^B zAS4|wF9U?_9acL;E*v1-ot-)f2?9*&8mOf(m-Ls1ws9pVV}V6h(07gj;e&6aJs|+$ z|G^FpTi?@en}0+d1k|sNMS@xgFD40;(6dQI_3utPjMZKGR-n`tLUoueXI;}X1u_y^ z8+K$`SUG;zA)QS^os0Vwzc);{A^w#_5!g-R%pZbj=-OfHAD8fDWJ=LgyCG=Mc~(IJ zA)u;!YOhr51xCTXVX(ay7&5RQ9yCDE0^$R8$rJ5=TFDT~e_%VW0ba-k>YWQsgD-p+ z_~F^r4x#w2)qG9^OoQq+MiLgjM&t=#`E&z-iF@fRncLm-Ccwjb7d>8l6ZiuFc@6~_ zhJ;=u@CSh_n?ex40}z1w|7A(q#GrpSFgp#+J^XuH0jD)2b^AOEiaF7O6rxv727o8v zT`pB3gH@*WJj0511@-g375-lp)6V-V1mDK z5OSNB*l7@zN;Y@26pJ7LNe3Z;8!k^S^y~kZaSHL~7d=9F%kc^?Qed$1 z^OWqrBEOT&0qN7{0JPpq$FPzHAW5PrLY?P4MT4rn+de-YmgAX^h;g;yy3;LzBpvK~%4na0 zgMZUioNAu){;mzlxMc#~tzB$+%5L;8#;Qc&E90jjKDj&=_GeFdC)}GBqRH!?j4hb!*?HEPBSoXx*sclX7CNE04t+vDo|RliL~WkOxf8$ z6WCG{KMNh;(Ae{NdE>QTb9-Xi=Q10W1&O9q!@?}7)SH?-AN9-8G|3JbF5Cy&ZJpC> zjSQUh_!1Ta0~#TU*2q0GTzzittSgH?mom~5-rZ3eFN}GXCPa_d-N-J<#o037JeGa) z^**j?iW4A8vqMX*xZd`VVf?xbrj?RtHuz&$cTKc!i)H}n@y?(Rm5A*9uc`P~c&r3o zVkhTE_GSXr8l(rSJ>OT|u4FJfMc3LZI>$tnn;&n+IN!*6UfjzS*q4PjAxN*KbpH<4WK!VYa)%CXV|)*()3OW2AT9 zJ^4VxA9HMRNra5V*ug*R=F-j+VP6scx=QW5#DEVJeESv=?&E_zq*~A`Ti|vZq+Bt- z`Hyz&RXt}VK3K5l1xxX))UyF`jANH?x+8xUTyF+hlyVnjYBpQ@g8L^l*Vy%Lx~2j2 z&Q~6XL%HI{%57^6724;olCG9?Q=XV!BE-Ds$QkYynH*N$t`lEvpYuem#Lil=nlBpX z#uc|es3Ay&o#2n1ut#1A?&r^toIH@ZjzqdSziO8Y%qp~VzCx9BHF{Z7BPqa7gQ*8a zFLUw)$9!2FqeGL`uKS8}LtvRhS;rHr%q7P>k8UxZj*mC?rn^lg%3)XZ@r;e2j?f`P z+=^v^;k6q+yb2Hx&INH+)&qShOEcpLOdiU5^hHm5;D^r1CIq5dPRpw_wxV(BwT|MN z@uk!(uTyzeH5FphJhD~A)$s+1j|8_{o>3=??5TJAAv4prcB}TV`)3Ixv&5$3?b-?r zOro>b+*KQ{muTZPcDQgBM2B%J9pMHCL__zb37?kpumtG7JrpfsUa(FNj(TmWgOS`; zerZ3ZFp7EP(?o8A<+2U$F**A=FUy|eZpK41!#mHuvK>EC(2BZ+X>#N(Of0;RO3{$~ zj(@A=i@AU9Z$kbS0-&suSprW;*qq1p06Y@#)B^yGux{>;d|~ljepuXskVk|DvAXsF zfFypPP%chG0=-e=&rES-mt0#>Sj<<@5IKP15Doe-R-v;aSgKh7@CA&4J>Y;kliBpf`#S zT~NjR3ac!|f8A`=s{hVI>B0R4;dvX2Un*=su+xMs>lEA=l`&%MAhEtw6t=f?(HX6c zk`mX;^B}gMN*Mb50L0Zso!bb?u{;_9)k!v945R{tSOdxL{4d4(U$XK~6kZOhaqxIt zI1q=_A2R6ZX3ProMfSTAN zlFkCGc43068{fu{8N$;`(S+dA>fB$|`7cfUuc7^GfdBf2Ki|dEz(B5y1(s_;06_MM z{DV3&l$uz9(V?1`RBAsI`m413>cBS+yr^{)r$DG7bfBt=;f@fyz@uias~c>&4vBRX zD+mMtiDzX-o}wYlU{_FYn))Gts}T3-q?lmLm(G$;8}~tkEcQJR+As+1LPxV?{0kK0 z2j00MmOn{)?{Qj`IL>2`Y$zLS!wQ=Ku)m$!-$?qvGQ5lRV_Zh~&m#5EYqD|uGS4%} zUmC+CvJyn^4~g_KL8m3N;;HB209G#q72u`YBEj|9%KW z2l%2ORKd`;=>XvqZj%oKYM5s_^k2rBs~FHR-Xv_p-!Sa>8m%a`Qsqe(j-A$dCkcT~ zmYt>Cl>FL0D)&Lxv%aA6fTDsBo_`r)2_Z&5Xs^cyTGAV8vDY;#?K&Y$ZyRk@ z^(cF4A9CxPDIIC{ru4+&%aW^q0w_rr+;QknSwGG5MD7#mtgyIo-kog*&uM&|-mp%V zY!*t8Fl>;$dNA6#r>fu+68YLqrsz>4Uxe6}jLp zGYay2L^VT_KeU6zpjufnCsTT2Lw>+cUR#-+;GM2>;QR=a zpd0ux!t8X1n_IMmS_NlL+e>%gFYv9W+Xfa`uQi7fg-Gh-Sk?-+nWc?=s5XP@c4 zlRG{+J)3rs_b5Hl5rVnij~q}lWMATNu~5?@zL3~m{V6UoOjQ#7o3(1PE^#{~YylP)5FRtA--r_0W)VwIpeZu8qC*cYF0~ zXZK6~(>4GPyJIwhJdZO4u08R0?U41n$jWz*EU`{dTbQzMRF z*n=Xtc?>y+>3(pf)d<)7{7AH7liI2CMY@P-Dp-BaEF_Z2;cFy$za`M0yYXCbu9JoUW(wb=_x zTz<}rq4F(J&C_=@KI`^E*Hu>7yniMt4vv#eI*kO##=Js>W?OkGd~-+p-Y4}s#J(@0 z)iTa%aVcV?PBc_NyENy06$PZ(PK>}_ljFKd>Dv!2tj?IolkYosnxb=da_ zB^-WKwUK8>$^U%eXxf#mRw&bo=cMweIGQ&9E7Pw9!B0t_wD-m0=gCFHulVatR0XGn ztu{+an>?%h43B;CT0`Jk9O{?IC%s$_N=Yf@>etSSgzQp3Ift`kz}s4HCYlI+?sOJi zix9?9^DvQk|MnYeAqpMbD=#mR6HQxtJ69;=^1`H3-;GR%0IpHO%Do=M?d7fZAB&e* znV9l9gqb(KSEktU8|6G%OWh_$7X+-bY zRXKm|6Gu`syL?00r=%<=?~>cwMGq){i88n&;z@&;ZCuK`umM_7C;;h@{8`?Adx|`Aa zV~M<6;1{jn9MWSiXUJD+!Vt4KFPX$lhNrzIw9=3$9;nwSGsx|<#t<=I&+sAY(?4gd z^G`hq5@1;J&H`bI91$Wp&@d!m)pZL1Y`|CfY(aqeAVBwjJE%r;iqXSK(A>Wa2hh&G z?mCPFrSG7FBGU_6X1pGvwh3>9_PAet9w(W+K6#i^k2FsVP{>kT ztH#MF303V8(rzKUi!}z}TPU{75wr@M$bb3^goX;c(DXxN78$VK2fp(XxV&)AR$DB^SBNg?T&CRIvdtl z&G--%tTg~=VuX$W;F(}VAuw1Q4tOp`GO2Mv4KLbqftXG{^{SDl17pxD@kXWqav8(} zzLPt9t~zo4*C?MZ`~w08$wU4QL%V3uX(kvj23riaLVg5Y+OAdU1a+)>9%Z^!C*|#% zGmkvT6|va`H^Uvt->|B3{phf-j7n4CBfz5%|0bVVnf^ZZlZ3Kop&SYk4ZzBkBK=`8 zHUJk2&r}~8OL=^xo13LScm>x*3P))^jB<%OLtytSc&b1fT#*(iX3s_bm+cDu1#orT z&2p9m0KEe|w30wCq*m#S+;Z{6lO*0DrRxI@>wW5?o}lShA5Ihm(i{-=$ zO4Nql51qL7y=&D5%uPM1I1L@U^w%9v@$Pe0<|XJTtR5$Woh_ZD;Ed&tuo^JcCK zPVXn8hr8N-*k(}BQ)@P3@G7~-L#H4@PtjM|tA~7G?_P$bPI}A7rG_i>?SS(vNlW@T zNy7;dy26ARN8B$1&i&P4e~U`y6lG+r{^|44Q+6`-8;2|=y6j5khdeJ+I^Rc1R!BRM z%hJ)Yac>HILz!;DoGc$(k3JI_OGveBnUuW3gKwcF?;5))#&UO2)nFk2h!x}6rR)}VyywSY z;hMsH%yWg|m6D`8?X_Ve@zp(QQ^Vd*%8{{O41Q=pIVfmepGiL-eUx$bu)SdWZSdzI z0TUL5dQAyCl6OV-UcJ0;DV;t@_S9N@P4;HEL(&5pC%WUEr|tT=3$aIs@wV}oeD`vn zl;6xrzsxxG@FYLm(~)*zK3u31V_wW{{Eqz*ox;4iO^uusHkI=6^*xs0F6)g)?70a& z_=X#dOg=<}CraVyNa#b=$n`F$)oPH1ED&Xc`Xf zSj$9FpcqZxH_Hw0pXQw+@1$8vQaSF;zM@l>=E(n$K29d<46i!;7QD!4)MDEA^o3XE z!6oNfg)a1!kCKIb!feIvbG+4gUnMeFymZB=`FV!Ei-rqu@`!6oxDtx={-FJTjJ;nykk2P+s4GUZB8(;?POv*nb@|CiEU?M8xu^dZ_jzod7f9-cm4j^S9SI7s=KSZ zYu#(rTB}mc`5`~$6y`;}U!!6VRC4;hy}l*VncS}#q&{Mh-DF;HwQgOJoK1Z0rUvG* zjA0UE@7FTPQ>}c-ohgUHp-5ttO<~{l&(`?`$p=gN;Z{zoVkL0(K`4YtCHP6ODUGEq zy5+fk^c8#`X_f`>q@0C-zk>z-Mdqd<53;LY_Flds+7-eB&jL+BL^x{G-iQkK#X7yF z;W!oR#6mm}^_or1GU|wbZYg>M0uUKmm##bLRU_w{|IVF;qL#>RdsW6}`3Y)L`mEvf zp1f5`^L39ur`vG!<$)n&-yg|Djk5+kWRA|@EktG|eaA!`gUEdaLe#JA-i10*FBUF@ z>-^l$&-xUbXE!xT0~?R)4ZF#mtySQ_+9#7xBOni z;k_^_C;}@uvx$d;TlCU%oK~lYmBV~~GGN960qtK;kWc3_4 z@^czFTo>87zZRp|EcDvmnbLxkr42U!T6BxqMDbC)2&l+C?OPP%DuCqzGnJxMreWiac^ZT=3|eyBF~C=NS33nuW+w@ z!*5*bKRH7ozKQSKZJXY2VtCw}oHlh@7_`3!dlfts#lSqI*vb3RKDId$Rz~P_eS1D* zrRck%2je;3zyC-J46-+e-y}Wj=Wd@z)3Y@1V#7|7Gpzv~*H@}CwZ-&pf9RPqyJSx_ z`l6GGV{+$XnYo1XecQ`+fw2+JW7b5O)6Eh0I+S8rYoN|HNnZn%%3IOru-A6oLeUkP z&yQc1Y9*#D!#_$R04+W`W|9|ch`l`6oSVpbrx&so3X+79mBl`pJS7DiMv%yR@=fsE zb}l*{HvH=d!46U6ksB1a+-4E=spakrlTDPLVe(G#E`^rCEZ4z_B@t^tKd#naK=f(Ab{+*Xw?4ZM*WogkFzWT;7$v0nm4}%2<>@E zXpezghAEFzk-Cd*P}^d9PmeO1?t&U0nIFxc*iG?Aix)BWd=}}66(LV_>oub2Igtm1 zo!dqGRxqy7Hbt=*N1N`d^`8eZN)Cr3mBJ-s+09G-rh1Zr*oq3j*mKbl+E2NdSZrm*0@ITQc@?{f8x`D@SK zpDMLKKUm}d%xF+QU=hSDm1@KqM2rTbXOxxFfR3yaUyur%#tuujm9{bqf1K!Z$rT}ChRRa`(WS{({M$tCudi5$YaQ!OpxzcuzH5`oycy@Z?j$lA`#}6ucl9O-3B0~0)Zw1fm;7B zo#4ONjUbfI0hCGqz~of@yF|%*BlxFCL8LF_JL+^mJ)o#>i!@7I?}ra#p=;J*eNg%= zy9CshkV?rGB~J&TnCQ2G^!zXNB0DgL7XTtz`tzSwnP~hVOEdn~@xg$E8q`rJ{q%p* z+&|F)|1IoNXxZ+j`(t4e+c1(`^D}398Yd)NE+*0kcIZsTd2cfR+rtG2wv2E1 zHWT8z+&!o;fgomTwxn4);EQkNsw+!57U7p4-w3XK+C$2rI;i2;mc~R!YdODr5;Er; zVsj;RQt{TMBE2Wh4*_C~8L$MtTiQ_bFfsAzr%8NZ;r2LBpG*t$vetjVcE~JNvP6-` zx51bPZ71MXsJ#UUL#4m;&&!06V-tjXyAsJgLO{97Sql5k9HxTFxs~N!fVlKS19IEU z(HhgFzK2-nIQ91$TxnxQmic&5a(o+ue17(fwX7RX4dQ`Y8LzOsE9-%nSS5pqCnv2? zDHzf=sun6J4H``~@Vl>c^4VtRRQTcIb{OZglkp5~@i$oX=3^14e{l0ZcAR7wC5L16fG zj`Pc6R7Xy5oW*CuOyppepn-DY9z4j`ed(T)d|<|_sM)O=@Zwafrj?|}Tg;O3$!1-_ z+SpEUIxDpAv9h|?3M$UeQR)1BCvrv4N5p5g(wq+o;;LwSbr)&;Ni_{6PR3tMQ#&ZE ze4XOpAzWF;!2mdO0h46i!2e@&VgMR2{(h^#m{lJ^j?6l*{F`URT@t%jdjER& zfv1saFL-w(g|>bJuq}W0Yy%+Ut{;d1vX9^ePZ=Xc(_OCZpH<;wEla9sivh=}DCDh` za=hmc#6|M!dsoLg>dnf|&sSJTl|L~3<~)qsb+QOSH&!YZPrn4kPIUC%R=Qp`-e3Mi zD?}?+{3=PV&>VpHb!&5sHPGK!&4oV0>}Q2X130A4TI9yq_4n1Fm>=#584W!cNuF7q zzp;IP&GI?b?jKZMIf;2i4o6VQ3mGu~+V_H{cU&|`3K5eo>r)d(#)Bt`pdaO>QmFf} zaGZnyVezhO4c_Pl#Z!GXSIeae_#M(GC`2t4|8A{yE}xBWaO;0}m5w=0;ib6EgbY%K zf}aZEV+{s}Qf-czfC*Px&O8= z1NHDz0MK8Aw*Zs|``1}I__<)(HqhgriKf*IEl|Jpn>b(8d#h1G!kUavV~aHey4N;! zu}`yCm)h(w@P&*|WdUF@1_B5c$>K0UyzvxgpRpF#1Lgn#!hn?JPh}^#+n}EXp^12f z;v$vYVOz*_u%TFKFa*BWqcjHLY)=6ZkNE>p*8ovZ{0{>aUL7Y?BRKp75Z&Le5&%^C zuQJd{9!wYX+8o+!JrfTe*#=iBAPmd=qe>w+ci|iWvVhg2;wvuROX$G5o^R|#9gU%g zg<4$|uapnTJKwKt8bI=joSRkdg(b7Q?dL`&D*UL8z4F2qC27>#3CIpy1zgB9!1|%Y zX$}88M*>=7z-RsbWV39L9Ek(q*CPo6{#x1vu0B7V|96uWFzM3qf5845^$Q5 zfQN`Z7Xa}nikqxNPoFC$bRI9?Thmq;HSzeH=4kmi=@*vt-mpIkqVoBNeKCp=7`7In z#DV}LWI-LFEH-#zMq)MqfMo7iZLkJ`2Z%*x*aBeIf?)w%)6@WL!Y=Mi-x9AP7)<>L zYC-vdqY7NCf2R9i^68(!{O|aHo>38gNJM|Zm;UDWCZ|#U71XMT++eMtz|2pw7LN@R zOwC?V%w-fryon4{6|oIa9dy%-qpb-vt|)2YDWBF%h0L_FSI}ZGb{;ALeT;o zat2`HzXLF67a|391oi;d^$AF1=n2InDg9Ux(~#wI0Ni<*;}^1kKiL~V%Z1WkO#ipd z3Q*-y#|-Zb0Fy@$gdknW#hB@VZJaE1>f`?!7zHDF2IMfz=X|4es$ld-C-KbW zTR=}OgH8!Ns?Tzz<7FXJRsCWtP9w0WS0DU>jvHW#1j0ddb@Nrj>EZIc({6WbYO>N( z$cV=MS#~*g9JAC$DXY%92kfPV@{|g|^D=1r0D3#EgKnHpb4~mZ4tn&7N z$xf5U1|h8Tf97=7WdK%LP zzI3v!fM-xjnX=GOtM?(BncM*BWB6`kXWVOMa?STogX>>3mR;X1DYeLADO$x`5zLH@d0_R z{^$E)o+JAEGvd1mN`Hcov$p$(2E)4TmlH6@{W%SFa++`qrVB-PrM-{cwpA@L3(g11 zg7+!NfyrNmId;C1{!tqZkL@MFa81*(JjEg88>b=` zX!TPrY1*;0I^l4p3$%rwmUh2;N%2Y>^^g7`{@x!usHYz3LA|OU52?Q3*2=m#2n%q0 zLcLTnK;LLYy=Np9bcvKXT3-uLMi-Cf{ZP%H5o#o(?)6BFdl*-Jt|5Y|FEie~PyVfi z@u`i4ILg=Tb^T-jrAXpkw09y%QDnuJYLt9GnD1$`6cp~_dfI)UK?-O$uUUTE00iL2 z4DbTUf&C+#{~nRQrx$E64$yyUpoZf9{*>4M=y8~0MZY;^bi@kiD^V+9c^g4 zC)0m&1VRzQ9v~^Shh86G3KPfdw*mYgfKTV&y+8yJ7~nTD{qf>5@B?7g0RVsukQ_Mp z|7Y0*%qSwk3}+(UcnpkR&IK680s!N*J@s3B$8P$RAuPxZ#Qe+?=bxmv(=eahhp+0J z2|lfsj;}=FCWBq{aBL}m@>cDW#xTrN#WB1N%SH%w<}%Hg@K~^ z@0+#}0>WDY!uumS{|_1QU!0AU38A94|6B&Y--DB9$lXYi98 zw3CDz;-JBT099NE`bsPT7PHKLhk2*`G!u$3D$hW{Phoy&((Z%-BfjAKQEk3Jx&(;k zzYR{{@+w?ugxN=gt+w(qN1mwnCX>61Z{+WNxje;2ZcN94Wimfpv=vbnRCGVC7=vjY z1->;-14>s7{y~@$)!)@6l{9T%CE!&yk)>)mlchwa5R-cVnD)Rsn*iR~UxN7mb;YLV zk*+UM5oM4JpowN595ZT19?MYbvmc>859V4?)jN8SizQu#0FRf^8xkAHZJtDu1u@kB zijEc~qR>E%fd9X=-G8#RfI1^Gcu8!>4DbUgz`Oa76?AO^f6hUEzMc$o<;(lbLR~Ie2odqN z3YvJ@gYv?zec3`p+P=@zYYA;0CsXB#O!aD_$Yb`GoAY`|gkP^!&9Ihu8G9eNxF zSP$#QjVBo2wq(hemTN!I)y}e2)g&z*uOwN5(rGnBRJ;HdTk5pO1+6A?7$j8>q|Hy} z;MvNZV=v8Jia~x_C?{4v@}?*k!wqh>jl&=)1uxjRTP5ifgXzolO6@9-o|*Q{dw#i{MZ(LB|{$YqHvi#SyecIcX>V1)=U$^)z7 zrdslp`1g>av!9bR`3m_Q=hyPJyVqWi8*~7*Fp{cH>eaAycP`S41r@Fesn}_DGXWa5 z9IXNr+x>LMw>+=}NluLBcynj95Gr5k7?cb*c@+t`Q@y2jD5I@{6CFPyp<2H;HDb+o zoUH3ErSnHwqn>`pEN)s z1rz-qJFg{n9BB$9zsV#V5T-6rU(=*fSB{#{#LfED@l_7>8i0O_R{Qg-7y0%?8Kv(7 z*Y}b%7dMfRnCO}wmy~;y2l$Cluf0Y&O*vM;Kv{Imsl|7A9{VQZtqxTqKT0B)o5tYg zjUm5pI9YrNKD`U=iCRa;xdOMeTs6CRNG>8*kuWpY%?O75B^j`7 z;G}UBw)Xo0h5QaD+ML9bAM{tuqg{}^hziv&#KO^zpljkhvNkudkZBt5-Ca#^@Cs$K zCAdoZK-@e;~G`%72@qmusRcMX65&Suc&p#`zs z0L~l3@h`~Lmv1Afbiqp$hK@uwf`C7Mu87P2cuZ?H2>kc zFohz?6^<$a+DzN4|Sy(&jpU8I57q$zE{&G*EBjJrje=iQEi{Y}lB@2n~jHY_jtn zxj-8UBH|P=p4`kHp&J&~)~N6g{Ze#~$<HKa~BRKZicRZKOcM1@l0b z@&yH<27vLO20(0SKx}`A%KyR^koylDFn}T!kXZZ+8yF}z0Cb@hK#~iZrK@Vp|IHhN zEvtLq!Hhc-tJDzUR8S>?J_JJdlr1#P`tn8Tb1l5R`F!32B$H0B2dsTez;o)KmY}S8 z0*Muo+^GcrZubZnx)hRGSgeUCxd^}r+Xi4d0Kqu|!Tq5z|L**M79iHI{#^wkh(!V8 z_vg?8xbtACogc`4tRK`51G2yB{(=v(@{gtm4vuC0?|SH1;5fmYzC`?`i2dPic>j~I zfNnhX{JSRr(Es@(KW=@f%=^#_Js9 z2Twz;Kpjm^eMvXrwdKG5}TudW9W|_~cb$I^r&-7(1}P z;DaM_DRV*Hkx9=y0;{3TC&AYg`9QkVpvl{2#DJ*q%20sLASvWve)q-rH_BHeQ{dK_VuO!Irmt?zM^PCq2r2|PY2G;iRr@`UITs)-x{rnDw+O(>yzqCK$9B}@a$=OCA~@DR z{GN95p_^(C@Dv1MUIb#c{$Df?o(YD7!W8FUjxT>bK~E}-l%7AR+d#figa%$Gcf|}dvB(guYI;RTBe5B0A11`U z6g3nZg0B$_)gki7&!M7ar-~chm*kCgw#ZboLQN-rMZ$AVLc+3upq>2z-$b+@-f_Id z)&N^gKKNm?^t$CTGN?Fr+}@8M_*wot`N7k5g}wx>nix^D#sd)BNaDLRQSsV-OHFc! z1BwlLvav7xrC;EFFz1>f;>8P+KCavd=<)oC}8tYKG z7n^2t+m54#J7EBN#N~};{;v2H8TD}dVv9NSn^+8F;Y+92zAj$Icn%VRWBJ_$fkkVB zYvIhp$rd+Dqd8*o^tIX#6=Cx1QSiGeqkUOs3enG1&$8E#2P{_8qU^+_~f_hQ)pU6T?r_~?LD%$s6#**W8w~FK2?>K*#WCag0 z-yDO;ri2UrIG}q38P1+15Wr<@p}SP1)VLhe3^mn-qn!GSQ1dO7? zPOAx^3VHDU%{(Tn{1dpNNC!2uc8%HM?Th6vG6j22!xu>$%bd)BQA&s4y${5=XExn{ zSr0f-TPa7v`Y_;ro15XZ<21P8eGF&)wRxS=7w`r8NuTMZ5y~I-sx**C2tB6iUA=tG zq^*IQJuAepX9Xn$iXV3az1fMba<5+T86htWOgE0YU!Nnx;CX|hbXh}nitT>_Pp#P zrYkXZBJnE*Dkz;ya@hWuP9q{yP;t}3SX)!ebUipuMx~*MWI*~k7)gcuMupFp)qJM8 z6{R~|g$_E6wJ`WBYF8S~fz@ zc__l8R5#inQf8A>{v)GiTJ(Es~|~>7qM5hO%+2M zvif}F4#;5T)MpU2=Fdaonj-Ke+dW5~FbPT+*s2f)EHy1Q`UT``R@B=siaOIQSG@f< zq;k)wu~}@8WXG4_s+}N3s{2OYkqAmV_mJEtPf!Pp}4*}eD5DWtx~0G`4Imj<6VTAm>beLfIS2r|?}6?6%+46Cj*(KncuU{UW3l>5R*Hb$N>j=06VoS`;O9 ziMEyn+wdy8be#i2ht)T9W)n?UGIj%Ph<>o#X9*8$+HT&9Bcf4BI9^-lH zvmRv;9KfWy9Lual{yHMTBL|TNbxZ&HA^|doZ%QvV{B6G#H#+RgT;Q_NZk?*YWNBBH zD;=ChQeMA8S^?#^(R*u%2+Plm39MA?C+06sZ7a2Vv?XE$0$Lv)b!bg~YL3#I4^sX| zbQOz?-QcVE`cS_R=AuwkmdVuWskgSQ)!WB(Zyy=PjTjW_;D_|#mrCWfif}~aC-dXO zn!Xpf%Jsk6+|gpU?OMlDAUY?nU9aoG_j`iaBAud?P2Y?t(^M#xcVt?`MSz?a_YIHj|Ta6?kpj9bZqT6AnA z^=bUZJMIFK%H{5@AiAm_jM9Y+@lbDSVJtq?QuI~WaGgH|oN@Hyv!0KJ~4n|H{Z= z$AXv9XjT@073s&Qf|>!}PWKwBa{9>nO2N0O4EuXk%Vg5%r>KZPiGSydWA=a>VX_p% zH<&_-1AnKowf)IZ2s4{5h9Sls2(pV>iQYga<^pFo=C14V-Qz>r_pg@PxRX1$T};g( zxZsiM>ZZmY+32;cBwry*TVWchIOrgeO3dFjlfsVu$V??()E5^5KU!hWUa_lW@9D0L zoYE-)Y1@j2uedRdDMGA9cvAEwRe7(GO&On-Yy-kBhn_CB{ZLo$cUaLOG!N2r?4{B#R@-8 zgMI27OTOAFI!d{k&`d!^zw`?ZcTjyV#9Gmp3(x5}x`HH>YeNu=i+yfEM0&OH5#x=u zIJ8T@T``RBI62h}Q=$UWJ^hQfkkQ-&$MrOy8I+fH-%EdDdm7tSu448&8;78cZD}AcMLxVCRg5E|(xs**_48P9oJm z^H=i*RP{{oOtYbu+tkiZ-wc!1Cq2jV$*sHPmJz;*NMCV6NMY;nuvbltxUk#JtX(RFj>8}@4@-z`G*pwPzFSW)phRR83d=3ca}B9~)0R^WUPu{m9! z=PW-)?ke=jW<&7~bZeKaL4qs(2mwNjlTg6a>U&Tnm$lv(NgGz?9kY}?ouUz^lHcx~ zHn2ONuY^j*@z4%9^a03ZpNdYEete-2I=$q{j)(Yx*w8=rVbj{O8>;&FX1{ljFfQS& znp%(_3PAj(7UXGD^Yqn%M1#*mBYec+z>RAcxfrcCoDCvJsDi6f>0CXT{h&iHT40XI zIDzZ3QmM<}FhhUWU-g8;r9PRiXCbTMO7{THpT*^#Y%?nN?3#P8w5Gx_KkO*}chnvg zUFkjL@Yfq;RQBXRX#goW@iQ}%N+h@u6OwIs(ynr@yO7@^UreKrCos^@ze!RhFSrG` zVCjPrl{U*f8gvUk{eG#ultS`#-r~G? z`d7=1ipsvq#?Hv;?>3hQjno&$_!4;Q^A4zN^~9lG%T zTXz`?ei=#-KE}D|NGS&~Pcm$~&?koW8QKdfIGmYPv!?r7t5 z7(n86L70tJulBi^%=;Ta+6}-^DNAE?nAxDPb>izmcYLEq10^aQbvTWi4j9O-8S=tn zULLZ|$yYURM~@|C@50HDWrZVxo~ZDPTzuQ0E|xHnih}xHkFR)O!e||2Y^F$!1+K|e z@#vfyE+&cYt)(lzcF#C}XkfHC%&>qQ1TxdWld((~=JcgJMSunQz{)cS&gKBHL}taw zDa~|q_B7s1C=;_jwxfRcqf5P$r3gzgi0gZNa!cuVs;&0mu6+XAheMa~T>qE~a5Qv) z*s_=@r&7XO&)nxDfh^mCa`Ge=&s;PkVeH3_JdF^C*%fFyNNV^l@Y%>O7cloMxbdr27cSFBRDvmx1=c&CTyO}j|_W`uNwu`O^A0!0kIr? zqr?7)sJ{8j+7)^ToK!|Qqg#yt#q7IKQQ)p}F^>jt4bh^sw}yF&FG)gnOQZ~zMu)i6 zFq?V*<@09Q>B@V7%b@W|VH02b?8SGG;=7_$H#ZILeNJ%~kJnQ8f+|GB}ZSs5{Bj3zn9N90Q2xsUte?fZFy>P&8(;Hi~VM zVh@ZunU;T5z*_nZLNDTUMC%~YMN}B3YbjiwSM9`yH1E5dP~BHk@-6y&$w zSC-4pV!57gY*J~%>(HF0tKFHnnRx6Kkp8Q;f>G^;(gZZPQ3?4STz*cboqw#Mpwujt;H-jh3 z5v^Itu4PRV(%KU9=tDV^mEZHpyG^&6I+thM%LVAa-{<@^>fvjJ&dEVi+;8j!^eiP} z6C|g)z8t@-m?4uriMMw{k~F-VSKGR95 z1WV23GSS^#-9mZ2&(3K72^h|TFQ%q86K$~W)v^-Yvt|Slp%MDlI!wcD! z&(?4pLrozk>H#kBg_o&LnvL8#y(I56>yAn!3H)lm8P>wXVCsZs#ZQ=**LZDk-IfR8k~~@E z&GR$KT5uy&j2bMu`l7gRMJp6BRxX?}1s|hs#Wy)Xdq8I2AZe&vj!E}5svJ=$;_ zJkF3F%+-_z{=8c21~+++auOC<)nURDgsC7ao!{xw8f3%i>A-VRyd)kwJsmD%&OPZv zw~(R(+v;(<%oe?tHMLFeeQH2pm;ELmRP65V!_!z>wvN!F->iQc*{lN$kL}#-!gYd? zvC^P3N!Q!cGW`CzFY-qJ^9aa=3W|`}&r#g7>SzmQe~<*-T9ib=9&aRal~F?t4HfQH z*4`BJFUWhimlyG0V+L_;K^V_v?3(p<@KAh`7Xq4QoxUYsjcjl>cct9u3u$)$>>kE6 zguJIoU{n`v9&wd-t}i6dQ-_CK9;WE<0jo*Ye7@r%xz|nfo3h79drK?v`vQM9!Uxv? zU&rx^{%HPEV8b0o{3mr=fYb0nXb@DWm)5DRg`*049^n{J2BbJ^Ipp^4ok&+B&JXLZBan_ACfqi)>Am*VaP6D^ zpI?qJ$$X$*!JnLk2YjCAf0jF-at9Cg(m*;E1|*nR?xwPIfQh&dV`NDtoh=IGNl9O~ zi=PMngq6ku+lY!+$o2K~ykzt+@Q`|%mikSZ-lE^LaA&LJs zByESkvvIjDl9{_O71%j|*aj`Rz5XHVeA<69f(MlVJ8wpSY{Q7#tleJO7mYWrDHh#f z!OdBANhC2Pt*~h~1d; zv`GN=6RguJ2WA+!9@8np`=vbl@)SyrMh7u@(p(iJQuWB0$93@a z2~=9!U}!URdj}ET;%%!ATNnh7y~A(m(`Vbv{R`3g-bAKp~gMinhqZkcnRo zjWLtbtWQ`SZQ5=NnViPH1kU?2ueUZ>=6c3|KGj#xKty?3|K(-bVgqvM4XGa9@^0~- z_PhCa;}0CI0pVHDHxiuv?YA}^-H^G|oCQGl$DtlrACr(k!w^rV=No2c{BeAOF`NL$ zPrVqmKoJp>GbDWgz7s|XH(HsTrdGFBb5r;AO2~xK~+DT z;oFMvvOYY7Rz+>+4|BA?PCW+(tDw^fO8+YJ4I~@OMVOBcszK#!nfJ$Epn*XOVbIF9 zE^x)-_zi#Qn1Cq8fe>PUd9@L9=IZZ1W=r zF(*275=qM~xjXjMAvaLVcl|J{5+PJhyy;k`%*i}n5$V*RYC|7RlRBA?Ya4bCZ%NaE z)MmrqMpzJY91rm!C@w|vx{b;M+Y>r|8YAD(yNZhAZQPUq=2Zz-7uG#~O@>O00scLk zcXq+8aGr`oFJYYncHj8~&_PGo(O}|QnGPxmAd@DA&V1o03p;9qj7|wuD!3<2N*E+V zzI!W9!BuEwu2`_YZX3>wjd^qq^o+;Grs>M;qtTLKAe9rg7vjn9Sdr)1qF^W1G7wFv zQHiw39%e5fF(#CPTo&wV4ie(2E^o~jFlqpF$;~9s0Ke;V;!hT^*J*7`8~qovR!hGWPJtJs}@ZHyFT$y{Ie~Lcgb8gZ=GOiK6OK*9BQWQVC z7_{^j-}1Nb6pb%d$n1RoeQB~z%-kXq(<+PSTZ%pHfBb)ewC-!yS{V_xg!NmBp&(=IzAHKN-Su9 z7L{wE>Ly@-#E3)2Wq=`y5Om$uVS)gAIW7;0<4JXLdvK3Z4W=scjNWCue}Z9dd)2b-k?YZ zx+Hle7+Gi70(T2tVTmjirw1qt_J3A8Li!UQ~wKkK{hugtc742<7%DZt;m%=;R z@(nr@HPE`dpR1x?bf(h`i_CE7LwFdpd;H2LK=ruhoucOK9{6^nD4>(Lzf-{iQ>S{*e71keaz5b@lGNMX)*SY=F?y&xJeM$_Oq5hj&^o!(2$Mg6vq(~VKnzD07 zUlP-1OmNvQGe_B1x_;mHcQ3_Q};2pcnG=Lc{q0f_Ow-O3LPBij<(*V-vUjjoKk#2%{I*oy%pz~L{f;d8o1m@ zVGxJ`0Y1gby%+qJ@0(ra5!B5lZ72QE)o?o9k95~r0PT^V2K@Q9HO?6GFmAWE%Ae~)ORv%u!pQMcRdN^;{r+~s! zaVwb_23*-VT;T-n%L&uuqVn|S*wJp6Z1pYbouq9|3eWj;4{%Q;ugC7DC^xsKQ z_paSL;3&LY4q2epJ%gu3KSt0S{mP|Jzb1)iVio7y9>>)JWZX&&Q5HqmIyBJ(nkhX= zs%^LfW`;uyDQOa)3}1ev!lWqw&T<9p*qAk1J1M^v?^Sc_GuTXD68(zP{Y(kTZ~*Cp$#=8_HUbE*0d}g^dvhfdyBylm>xL zVh^mBD_2fb?hvhSY=R9jDK6~kb-^t)=eCER&JHdu-f=$lYc^nmh$*%$wDnVdmmYI_ z=pvp(4AHq0+zOdE^0IcpQ-p-fQpD+38PpOeDKW6IK;dX3pA5e36Q|C{8vyWUfOqOm z$9HXA3`+{g;wg(O!oL&TXuwY32z@)}$P18kU0brZ#bBYx*5G-fVLTpHw_y*Shlu1q ziAO7gYWYZI6;w^AFSeue)qaF`>g=pw@zIa53$ieC*MojT-W9Wt5AKlGN^^rrf4UMN zWNiM0uoxSXXa>*R1)99uY#MW z?>)=D0-{%&@baCXDs0ZwinMaWEs((c=)YVRRpLGB;SOy|<+yP~1l0e=4kd-5v=Iln z?8Ck%Q9D7M_mE$a`e86@w{Yd6 zR2@y?jg}&_N3wN;$h}1x+_-)F_MuBm5+trc5Wo~>80Ra+HF(U90r`;xWK1Z0{!YGJt z@gy73GgER!pSD4w&rye6!Z&~$4_b1(e8^{QYTq2NCRPEuo=hBjHBSon2KGjaN(y8< z!Ig2ya6DQBwD6ta*;cGodIl-ioS@Oe4#_gB00R7>i$(?R*>49nuGk`F0(cK*G8;lT zD!{C(=eupD1S1nHsr9)bh$%W1D4u)yqv@NN{Q3^4Z$|kr&1_{$J%gM)@sTepN$s4A z14vi{0}9}wT>KOUWAP}Q+J)|qlTWg(Ua;TbwLlI<9?}Us9VC}_U*A$z-OA~4Rjf{| zq@(dWok+WM2S?ld{k??yBD#wxC@79UP{4jL59j>+X$kV7gz1kbEJubRJ&fvkxyl(n zeF0O!%^Gx~;{oXl1{&7W>Q3Jy+(Fns05j9YF6nJUPESG|k`gVUmT|^;iQVhnHOiRQ zPM2gi%XYRBI%0KNUynhv;fH^i?{VXV)Ho9%`UG)U-J)86;N*>4+kEols+)zq;lNm* zcl`&`Jn~Uo`?KT?<1Jz3_Alk%;Q}j=UnY8-h7HNlmd>G|G6%zkDe-h1k`zEw@YM3p zXidY?R$PPb`e9HM(;hnYH)EGL^b^GlsgiQ$gf^^=tW;lPpG0~9qvn97a7H-PR{&2rhniHWslUi&& zDV^k zVwPU4!OMge;}Bb76lD;DPuIehD+?z;Ga_&;pqu$!*Cz zndndZ(A2BjYjmakQ~*YG2np6Wrd~Iz$<9=b3_u>N)oyd)C9*aUgx9J0+~TQM-CpyPiTTXUa)uq|mb3-qwh9 zFMB~eB^eL9JCh>-`qEhXyLy!JC%R;rsAqpPh z(;kq$Zyj(7oYwz~$hq)rY+LbCvZQOeu#2L@2O zK3=>T1gWr&(tJeD$9MbB=mo{hI93(>*=$?Y@RzefjzK?{!wa)k&IGs2ro_yfj>wyW zr|4zMYSsvI+i}VRTq9a3a?4IdY~A6vW2w(52ob56nAD%MtN1OqhMcmAUYu8|GDjK_ z%Sq^H8JUpTp-6kR(&oe)FHb8LrdDlDy=h4KzWSm#&~W+M?}n=H{C|wS1z1#F*FJtG z=y}> zyRKno&e?nRxz|3MwePjh+H27Q@B+{)mlRUOf8~1lA8vGC(j9sM*$oxM7xX1!OW;U^CQIcAO=q z5h=YEGc1^=6F$#{!6YBJ1ly`gek!_fhDYeE3T>S!beM9iiD4Cu(i zUo_;G!Y4Y9c=D3wFl#JdOEj?QpB%POW<5dY0W{Qlk&>NdC%SB42OeXH^wLj(pR~2QECWE`{r^{Y5 z8<@3&afIJGs)*cuv9*?Q2+5ie7#&5@=hs-t&xm;t> zr1KZ4);8O?czWgC?mcZ?8~)iqB7$M9{+tf*ew&5+fpFBgsd(oua##A$goW8_PoE)A>P zW=2ASVvmpjNhlIOdoOX0jD*bh`=3mT*(2H)f2i0~nS31y;}U*_AvnTg83jFPuyw_3 zaCtM2-e9%@eE@>k6o|gQ!@S{pM0#$@(E#CBBo5LZ09b6m{w4wY`^rxi+|QaOqHP{o zn|}vZD;MI{ldmzer|T?!a?lxj5;_;#qfTQyu*k28eYT>A%dMsQ;-p&(us*!#2l#*i zC=K_9M0sZ%rB}w7<4#lXa_>9(yQs&BJli&r#d#=pgTUNq8FT$kox=LACzdv3Qs=dq z@?)`UG#9HXI1w)@`j3bsI5lIMpHC`IZ$D3x@(R*(_MgH`-Yu^T?Ud5qbRVm?WZ@?9 zkIgR`Tz=3zy-|m=+?ulP;c&m5gp@J#xsqr-))79j76NV$6jQ#0vkpGl=lU7ef^mcP z;Xc$h4Ry7#Rp2}|1>BelV4gssfN~)-0BHsXJ1m`cp&LkzCkD5_l8mDO!6mR$z|B?y zSFX8NyO}79A3o>`65MPyKVLrVge#@K!k7z5y*+F-(ya{Dc|zd->9Jkx#II+?Z}IfA zF+?Z0uo}E-p32BM_43?*D=R3Rf9&LnoGN$QhI|O`_^p-3x*f@mqAi9YTknvZRBIvu z89B^*LK8_mPpgfXzi8QQ?Y-@>OY3OUmMI^?5XMbtHCf92J&0?=s(FH7@8KfjfRdKald3d>xh|5Jn6VNtgsz`&Yy{0pQZK6HL#DhUsiIz?7aPyfA&V@ ztPb1nw+`&Y=I#7dGCC63fznT6;=}eud~vMYMtNjv9NR6w{}CS}BlVWNEXSu^R_x9) zXd&HE=`&ci^3!7a(7;be_;^=;e}eq!NUIW>)Dp^v9YL`|IUD;)AZSIUmF67tvnm;h z%%m59g}6}+RRZW1yHUajj73ObI{=CNOnTu|d%S6rhXz`ryo5eGUNBSYf%lA6F<6r6s z5J(3-vFW1KbFe>J0?;qqeaIla+#3$cVssy0Jh_0r@J)G@q1w@1mM=s>57E`$Z?;9-o7jg>k@~?w zgbiaV!2>=rTw-mUjDAMh+X1)Izhq6iBZE2ZcQN&UDQTOkZGLfG<18#RRMke~;WGb8 zA=SvBwAbTKhL6;M+kdm?DE7ctRkIv=H0$E>v7&@TRmQG6WwGx z+(P`ik6H4vk@GEQr`r2j**}i91$u?)Z%|$8A8OLp98ug~mjRQdRTaUq?z@*Meisf7 zE{Oyp=po0IOE}L^G*#$4!DC?y-Z60{<}{WP#oA*^Xt#Rvww5uLjJp`MA$v)1Ru@4; zNi(A12F-2u$>v%AJR;2L3QN9pE@sB3_e~gGeWfEKr1?%?)Fj=`+t^qL=4^u?R@!E7 zsWsdb(s85U!KZYQW_;ZGqc>suc6T48yW*^$)R(-lIw1`FlGnepZ!;4R^>0A~2L-yY zZ7+p40_+tQ3!!~=DP?K76Iw`|n#pPpCj#5nws`%Hq{&=&x30YN+ccdDaq1n+Eb*I9 zc(g7o5fXU2=aV?yi|@Be_%^7V^Qcmmx21n5zhx@hdt=wE3{TjBYY5PYsA9k#R0I>r zD;YmTDENQCHT;m4l)@prUV;*esi)PamzUDZGMVLV{=p@t=mYG1ie zAf%Db^&wRMe!|x~6pJMO=XNDSRWDudVN2nBAV6^<0g6>tn;CY zGW}P*IA3yTWQV^6l43W^BucZ=@80aC?>Twv$jBf${fd_ktBX>RyemVBm}N!ak5s@X zsppISo=(`#vE&^0I!K@YeC*5+F|~6xHJgC%%m)ihEBKHOzZbkZKI#D}nDsGXm}pIo zkCidc=_ED~knZaYUMfkNEY&KPS;~}K$#poDNfW`WiW~3htbz0`_Vlp&;P3_QH>62~y0 z(|jA3RpjNpXaJ=Z2Btyo0GvaL1l)%-Q< z{#RO80>SWjrV0pAB`2O4!ohG$Pr>y_O;8znog)5LqqVu+C5c|;<3@hoYjB1YV13#v{$f5mRdIs7#H2u z!^i^V{|d@~Wn=ucz3VUe0UTR*ZI858xJ@UjzmCy^03w510VbOi1^@=u*l?mPMLY@N ziAhL5B#jsa`Do1Sr>Vo^X|2=nprQ1&I8gn|gd*={biELSh_#J{WM?cq`E}(6RrR8W zorh)RLU<9GYTq93ljVY>eT1d(X&9sO@Vm!j=PLu47{kxAvNlwJ&aA|~=!2tSySw_( zm7`6Y!c_bkIPs@y9CbjUq}6z|sp2y;WdE0PvgjhzJs&y%cz%mAu5((1-0Xpbh+wXV zk6zs@pg0T^@FOVTmAP=e)17@BWJ_R)D@tEfS>ev!^#OQHDbosPr%ERaesDdAM*Y%HYx$Ujc{d&= z=}8CxVpQQAM0&BY$nGoAP+^OFVV;n1`h0v@D>WbVB)!)RJ4{b7onaeOm{^%c*Rbtq zQr%O)|K!Djqi(80V@v-eYPDP`S@tf40v z7=TfN*wG;ND?x8X0DTf$Bo--5+3fB>9&AUL25|KiW!-pjvafRJkeP|~(hX`|AM1=Lkt zJro|spL>y9~B6xnUj7?Okw4Fky z3)HpmRrlMEi7E!kH+SZJ`nbbN(Nkb+ut!98@;>nAu^!E#`l1TLs?C8gTtO|xndx^A zvzR9<-`b(tJ9t=fE@oft(PI0UoXE-k7)i-hNDc6HpO%(j0=^!&`J%hJH<5T!ifEw9 zwwrNpevx|w=;TMdGUeUwD~hak+Si z0<_b=T>!`)$Ml}KhQ^CKmy==0>j6Q~^B|6GnB1fxv!Uu7qXcFyhd)L5bwe$Zc@|=F zFYl9#C*8!pMI{1&A2mNX*Ajm2)=JWe5ybLKj+z>6XPMuAizby`&$%bEL#8Exrz?>o z_E@&>n*vJqg5xZ=Yu&(e_jItF?=n}aOG#6ce`ja-yPbT-Xv}E*Gra7ytS_^nlbxx?XJ`N<3MJhv}fGBJ@nJSDepp`B@G7^ zn>}4w-Xqe2sBEMT`P6Nd;;@3RzLphHp2ma`MvUIeakmz;nEBeNk`p&N>#U5F1o@S| z>>7H>`h~6Cyz%|%v~_-^5DCSZd#W5q*YDMb8D;w!}Pi|Rk}zd1%+%}YoN&R%-xK%*F{1fJ~!~3jS)xBkChj;2$$O`a-2Yf zZ%!8^F^`b7Yxs``d$re2%YFV6Wo6C3sY?}tXl|0S=6EqGd$;PB{UGgpDDU%J>KN~~ z_HMDNPuPc?F8BBrOAc1!Jf&>?xVuK|^F1=ENsV{gn;;LjZQHrz z!LvK5y|V{{NlEuGG4#QFfJ48Z*1S38@GoLUwc2mK@Cg(y!s49bkId@1Acn;G0Ol*pFml3T>{jB`y&tCHKfuI~Auu?u#SLyY z-bO0CP@}mV);WM~QCQLxQq6Slsb%Hj+HP1Q;VC(*7W2;IFYiYsC+jnmcX^$s zM7{c%P7}1SDrBC^KXj6LPlipi#20a|9_#h{KTWJt^pcIShi}TlVA5YSY-)@rrLw3_ zdhu3V+QN_0fGI#FSAl5tF;ZCHpk+{qARx6)^Kg+aH55hqxNKyKLCCDtFPYol`Ar1SEB}L4flN ztMn;b(bT2`pgLXvfU*!w(>u_pBrT0-%O3^vW2wg8<3qAfvoR5P2OE?JWgQsD#lQ$i zd>~w)p#RD2-Xg$wV*u8gst}M)zepMr&ZAFEF+R|CbN}4Lq57n^Mm_m zvhd(?P?X58mTmyjkxgvUwvNvW=JC8~$L+Xk8y*qmM9Nxt#{-}GTqJPYj!u}S5-?7| z^FrW!Ajxc`=d%t+8~h-hnz8TpKo|C-oN?99ay>Ii0{Czy5fj`&rW~MQMlr{8vmTgL_tkq zz=KXl{Ba~mgH_L_@l&bLVhO4kUTG{#CN1Ioyy>xhPKIrnQK$SnD#8%&ezT)WS&9nl z(ctIO)g#WegO59Ej*=}&9;W*;LP_9T@$C7;q>BCDm?5|l<;{<>$jOP8VvYkomV${y`4D*J&Tptbs&jt!@&wb8f`RzL z78ez9o~<*x%J?<1E?tu?9|Z2}0MNvsTqihr#AmH{SVSS~p^L(41LXqE6Wwdd2nIC* z#ev;LfV{A;R1s^1o4}%VY*Yn$OhTn~Ego5m8NfK+8;XT3tm%9KV9tpH^XV>&UG+F* zZx8K)W0@La_Y_JfaEhztm@eOt-AdyW@x`ONk3CB4r5yfcxpjEoDK&RvpfvDu^5!jIIJwD4+@y z@S0ElBOtK~8cQ>hm?Rp*9}DwJG-wrYM6d^7GNa*ccfbWh)ZPpW8f6Mc;Q9)>>Wn-F zKtGLK$T$Jud{M)FfMujt4KX5NLSh#&BtOtc*+%!U{%i1!92s%FNF{UvBbC{w1hrf*BJ##-o8=f!|5fJ>$Ji##ZU6iy%!}E&l8}{1PiRKa>&y_2&ej}Iu{Sq z#-hTOU4PGSG-0I|BvCV;ZZ>yle=>2TKbbHX-poii#2b0FEHX{IQ0t9dn>(K567R^h za{Ab{E*rOp~nO^lBV|E_*$#D+Q@VS&-CP)OW3C)p*Utm~!nOVJzTU%K6~ zW22$$vR`#KWG@yqUJ5S`e(_{(P7Wz5T@r!AUiqOyl@>`7ZTcCg_;9`k>J550adAo+ z2yCHl5k$VKD}bv!aanncd9R*=UJz=W0j;TIUM;yP$h2#YnK*A^Xdh4QR(vO~l*4HW zvva*DcXjmrZ>fXFy#B-L3JE*ij*kjI<5uY{;u%bg$>QDH?B8w1d1a?9Jx^-QU2uxE zuNgM!$!nT_>Hhi`j|PdG?rzjUc=pY^(@O@5@VVg{rnr<;@)CCBX7RA$;Q&b5=g&r z*%tRxWz3X)tCt$aXy6okJ{)v|F~o1|3Au|t; z*?tKCopjiaQnq>K6a%+zgl!TJD7_+qMW9X1>fP<1N>x}39F|D z()-p+1r2}hb9+%wZw59WiuvVMUhm77u`Ud$Vcvc4=hJVL(&9Vb96k5_OYBkLCyD`e3Ycz7Qd(4|B^5Vgd!E zMm?WW!SV&sWq|0eY0y7>@7e_Y0^C6T-2jM=;7kt-oQw_ttm)R5NT51^gD1tM=&Bso zbU~cY;1eck9)RHsz@;%=`=0?KoSxF}a>yJ5?+#&73u7v32ZsKl?ZUP-!kG#?rud3;t zqVT8w`oVQWe>L~lyLrWRLm2&N0HSpD)m0IM0|q%X{TF}uyY{<*Oa#jxTUJTo2UpcV z;Q`EgFhG@g7KRPD>cnk;QbDV$yw7~EX2;+7!ZO&j0!b#~ntmrEc==pd)N4a#Jme>) zaF2FvzJZq|lg=$9Kih^|`uwb;P$9N57eyA+QI>M!v7LBr@ZCgM%C}4OeLz!^EOG96 z|L@QCPPS~`MYj)xXM9*OL6A`#*P`e9L6oC#8KnVPRp0zF0Nn5L?Rs8 zBwF$)H@R)y8HQ@AOVsmwEUHite2Vif?_~;owF0bPK8p029XZ+(l@NocE6{7AcP<#hR4}k4+lVqKq}&|m~V#p z-?5N8K)$$sXOh=@F#x=!xSfTK>bx~%cSwlg4FqkmH3I6%3KYU?XrTR~5j;1C{5^$qUa-Uqze=$jac`rg;tyd%Z($7e7_(p_mvP zutMGSmJeHI`ZknS7{#xDKWCxr0I7BUqHrW@_r6B#n*0hOuNWs&OVJtT^H!R~=s6oB zNth3|-(4G-di?0T7+n#TUWpKKBYtUSWV;!MSM9qARhW&@q&o?R+86l--H9jR=KQNn z!4f--3>22+T6*bX7e^FC@zlZ@6S%H*Cny>@Cumm70r}k~X*5<9f3dwZPPRQh4|JxD zjmX2g+I{#}e*%3(q6>9#E%8$x_FZdE5#ijFDe}qbmp|AgnYEww(ON|vOwNwbZ4bXT z(QE^giE6?O?|Gy(iec z(#uKud`1}``8~|E_Eo2X;<6yuF+_wCxZ|&hGyQZ+ugfx$L;aW6%$GM~;;`C7vy=0i zuvlY5>!>mozuAV-S7*ZyzJ2woFK@(nOGcpS(^svq$kiviWcwVO(ESQY}|?t{}RNPIqvXLC!dL zDLY7~-1xId$xMg~lQD{sjDuh1mM~J`uE&JXU2~@)YN`PbNku_VqR+BhKSTLd+!st! zLH|1<0_zorKjZS^I+)&V%?uWr-|X(Wglia=OMWm_n@o_lfVLwdce=&P9!5&;9Xp`o z*X#K^AHLWK<(Ja;71a0&bhZznpwcxoaYZNspb46zoR~|j@1cCcqRmN$9dkz zMl`2XJ$63;xeKxDd)L+;wiyv2$0aK9BX)Of(k`)@eB+@@rNEgJYNZS{pVlSK8qsI7 zu)?yF3*^b)P`Hi5jJ=-hSI|W>%M9#>ZG!*XZ>YT>;3o{gegZNI&|(}1Vy9oefDS7$ zXZPz8*?@j^psv40`T#^a2-?h;i`VD=*Gzd;5q{)#U15UXp|Jd)C%~zezz2DC=2j;F0Pn#|Z~xm|Z)ZVB%-+zr#tX29 z0XNjHe~J^o;Ix_wsQVO?5`#7%_EYPLnQy|e{uy0FQ?YT{6GSu;Z>4I&cp3yEp(8Kf zaYXZ1e2bpfRCC}ZC5G_saVrtf!wRI|EQP1uvnqUq_MyDNQ?<$+npb|g+Jg`vkBB{x zpTLt1`+?9YV6|lv!UhSLGuJFgDwMFos3F`6%&^lefD}E3_&L-oOz2hri|X^&?{Zv8 zyC~=wwdh{c_VqIWgkrwS|6vpgogEve`A7y_OJdKgh>uBWD_j1gn01Ub1K+kMI}B?h zll!Xh7ua#MpP&3m$tA|5V<3r?E(?k;(_c{~nJ}|MNu1H|U55Yp8YBxw@vIp0bfU>w zw?Nx8*qv^Np)t0{?sN*H_Umstr^{{BPmDE&72KCg()`vDwr8w7610_TrA# z>U{>G6N{JStQJHmcoQcy9KK&)ABX*6L}Gn;5JD8+#+dk%Wh`DmF&yeo9xG-cAN|b2 zYR-0wNOUjcek|v=&7nn1KF+W9vP~s;*oOlp7Gi%2#YQq#oegmviXC5^iHgX@$!7Su zMsm&$@Lfbe$PuFhx}Dy5N}d z8tl0|wcvsCH(6Brb6Yd6g-%ZN1%1?ogp!rw8w&c^)+R=F{7wh^T}2Zr31nXxCZ-zK zDOu?T5q$IoV9vnJne_n*($55a;WA%7{eS4qja7MUm@Q7|PykfeLRYYW`-+)j# zxMk5LrPN@7+`-D50V7%!#rvHmn94?sh5K`_8GFJ)dx?B?uSlhFn72Kw_{IQ1&6XY& zm1n;HGreamE2_u~v0xfnc>H#Qvdit46|*B!)h~^Q$ja`PNUx9W@=BOGs>9Oxb<2HR zzwcv9Jz9r&`t|nIVe)X7P&g+?00zHDHH`I(fvqzb5V9to`b`lG&j>EJcZpbk1zu6QzqFP{eSRX` zXVvnmAyRbeEp@=g@w)$DU}#x&S&+>2r+{u}0MbNd}~? zQ3$2Y8v_VTa&`njk_xW$neA%9S0w`V&Xj`UG^LBLegFqSL6sEq1K0nHr~Ov~Dxx`? z*ou%Jq!ewY(q{Kjf1}6ErtB9LSK}Lw`?Gj`YTjsF??LMVLf{Y%&Oz%NhWnUaJOs0& z`c?F-qP|lHW-a{ZDA_l!kv~32cCYe^P8}RJ)U@ArqF#ltIx`dCe~!R2y8-{?+i!H! zlLt#yqv!p%V&^}-p@IQ7k8R`bpbvo5i0%)jhuP+1e3*`kv!%i1cfY|!+{{J;*h{LR zNe+p5X`U!Yx70>x$Oe_$Cls?vd+I}gig7r7p*X*;Sfkj&B-h1@x?ymEN&l7Xnw?p* z@VcjQJx8y^UIdqc{&~b_`Yls)&s5fTXp_q|wzxu*`z&hqB+MjuPT>o2?>tVjU{Rw6S)bo2Jv>7RoX#udTSnI^yiSAOagV z8e&{`!W%2LW$yq4SP|N@du|J2H6CT`Zn;q>jbn-@^EOQ{2_iqycz;&27^?A_T#jrh zXJ914rFuRp3r)Xslu&!p9g4AJeWKF#URl2Z={{`S`le56VIxMG`;o$6Ym|%ELB~BE zfp>TMQXb_hB_3?pDmP&AcG*Ex+fL90B4>Psnks)-g1*;REMm#+-@L1SXP}1L?%vCs z=ZO=M%#jM~Q$(c_Szk@6Ie8<8r^Oi~Lhs8`uE*4;@(YIjoKy}8(^|>Rdl;#0n-klp zq@iJ-ffZRt=h|4=;Z^tyTm^=ZC>DkNi*wO>6JCvn&uguIkAX(@vkzE{0LvTnDhle> z3bCzw0S+L#*C;Hul+j-sKnZsJi<^Fip57P_Hwpq0K7=U(I(L39IZsAQZ!lB!HpE_d zW)5V0SwRac^+s`0^rxC}6y#0|5j|MF;d~zr7!eOe`F7|3s9Dl@`I7NaDzzn5@CE~e z*&o?NTWX1=*QMB}r`-%BZ0Hab9=amAH91yh<0|O4vWH(6FVxQqKE+!kR%%_!S70_i zbM9&1X6xZfU!{-Xd6|@pFQTu60Puyglt=+ctGjR>iug90IiL$K2X3YtB%j2R1M4WR zswpReBOIoFLcUXaukHg9$|$us_8CGHMLhrjQIMjze-SOPLm2l!!AZIVgh8qS9{&4f zrH$QYh)8gs$UKRshOoh*1vUlMh0Lt;9DzG6V96tMVQ~ z=YJXjk8!EMo(0?W1CtDm;%@xKzRSNx+#wuV5!+fRijZg_9mpy zX;jXqjpwNWXU(h5n=JTutZs64i)(+z?u{N$qwaIi^Y}=T2nIoK1$C+Wjj={T?3?jg z3!(#z1A=g`GZ5`->$Q%weX5fp7n|)i?4^Xl6R)bn;(eJp8b@z zw&bN(F>Hlr=*t&7zbSs&zH6wEN2nH6V8MkarD7A-{`zZd;Bs_OCrwqzMP{3ez;wjvc0pU+TK^K8DGVnnVQ_^qgWCJ-Qe(tzSkC|kKkD?WmyE{cW*;AZ@lzk z&y&Kk-&U`E*?PCG!-2aWyMPf>^|`@|Jw6vCB?2e3ZYI=g`9-UY^3NB2ylZ2=ZsFeHg(WI&&_+MZEHiokt- zLZZ!^h%^E}SbN6Lo{!%Yp9UTTAzOwO2t}--n?IBayf3iBBIgf!@l0#qKI6^a9){7Z zk9nBCaYDtzqhGQNse0A@-l`nm=OUNeUp99)FE-ezb^w z9deHC+CfuS-M93WRtHNMd1C4^uc33_b>;l?@onGn`eXIAUdD;JMFY-3n51thsPhIC zi_+cyPNMf$NPbBf&ED0f6H8)@^6B;$;sC*C?hjtc-6uYZ4A1Ks1%F${`P<;qJ~;bP zJ~N7ie8mkw!l77RBE!wzoBrRq_0Xicabr{hr{h32^etEOMbXY8|pWLJn3 zQsP(F*W@)f)5s<9dXZ1z{Rg&+UGGq#Qh19>E$no~zdfJNpURY4>&KZazjsj{_><8h zyYWjYS1*#iC|7B#;p;ecPy(CIQ|p;F zyQkqCnEOFgTm*W@Y&XhgwXxt62)aGUMB#ZIW-!8#l%<4J>Lq^>29|geXJCUw+t(@M zqpVOsei63pbPM~NP8AM5bKAU^rIGn$R7Ry>$~`b4-sCMAg$!AsaMU3DRF``qOh)!0 zGlSNj9;PK*qc;ojsjnGtIsKHz6J~I3tjT#MzRpvL0m+6GfjY7rQuG-AZ>t#MHKks^ z$i_tvT&2JPa#2tkjK5VSsB-%;nWhAmL1hjDB9mVlr1PJUq;s|RsB3MfVl@L8PN})y z@x)}{rUg6$y0I-WR>$elQX2J+bB`?GGe0ykik~<*cV_2+KZn@toIq|7egduG$}0*8 zp7HaHBfiqC-s2`cz}O0E8UbioU7`Ryv{Gt4)Dy(n1mffeasKTNDxC=P0*&D4ae$ne zeDQCPS9+Ma(r^)853UHK2vuJlkHTYyi`0Iipiccz!FnXz&(cYp)x*dW1Ch;JpBTgE z@HO%oO1B9&Cc>kZ8>nrLl3`e0L@q^CTjAq~@&-qy#wr-E6o^FLvG01UL~^VizmCGN zZh1#>TGXr?P*Lvy)Md?w)ovH9q{n91<<~g6YC^l6DXgn~0(+m&>!qx&|Upskn zm0bhH<3#-fn5GmaHuZb->I5_p4~1~X6Q)(^s{()4)cOl z5&6cGkzly!sjT8Hdb6ZlK747*FcgBye83$O$X6@`uOX`6#w*G4uL>Id*u?jNl@${u zs?q~MlZ8kbNk4s4MT<@TQHoXpvlXI8rw9=D$Z(x)&)GWJ3GF*lrQ3)OdMNY&>;Mq; zDu}ukME$o@W*vYVv?T{gmW!=0mFa8hv07i-cwH{{HbEVSK3bXtD43KCU7XvogCGa9@D+Lc!M=;LYR4W!8I|L zu~duv6CPolNG?%hv!&&k2d zF7*Od|IT`$34_-vTHGU>*{Z2o8QMVBG}s>7|*(k zulo}mBkLnvFFn)8rWdz{x_5gL)cn09|L+3U{MGQB2?D*d^$v zJ(Evoe*<7@lK}4E_=D0Y=I1;9m#qZ_Sy|QZhI@YzC@F9Gywv4j+`dA6+oA}4V;@eb z)Ox8g05}c<$0OgEoH-!(_Ey*@7S+A$?!e?QI{O?g9scD6nD)h~RB)LIf5-7dE0fPW z6&tx1+}BRh&~Z0qmc#sfY~L7LExgISLh^RF)PnRgGe_-rBb>iO+Eh5+h4>g~q4mcI zMJU!(?(}~Tx7-?5aA=EN@e;ZHd4h?^`H=HloM^CuI$4py-BgHK4%Uye0(IG+GNl=t zeX0@u-v)0XdW^o4lYi({Dpi!WxubJebViQBjb}FMWuYnlH-kAnL^)i7Jz1RdQp}0C z^J6KB_b%Z zy0x%?>@H@2(0h&Ci`P+SBhV%-3tbFDN9S%GUJCOKsDXA-q~BT9+#6B%5pB8t5^-p0 z)Khsbs$M41`q_xnr-xCtd4})JvH$EvpD!M#@tWVOOx4Z-Xn@=egm0d5fTxSzU0f6{#4+cjRf4clC0By3QPOFDW z3zMdWNxr$d^U}|uzcwt$4=g2ZoZkv8%)`SvO8z~M_3(;_G}MGO9joWK1}(E z5*CUP1hhXB=DiPzfjCE4EA}k&s}LSE834dT#C&9IO5F^Y8FLLg_Qv-g6CQ=+Qhh^@ zj9`!W?X(k0DYHpi^FSx-EJ=*aL?q`DC|eSwsODdjD+vC|5`uv*SUPAr{Pp$foqrik zMhvR)%&q=V7HJ@LZhWqs8O%%yoCZ}9J<=>^CYwb?@ts(p0grqqVXlS=G@#}Xf(9U2 z0dN~(V5Iu05n6o<&NTBA@~Lj9ua~f)cb%O?IcPkpm3fUfN8GhOf$q;&(y+gHTpSa=cB_2hGfhg1zjJk&eV%Du2iT|u&R zCuYFv{9XjEYuJJHlx;b^!9%`wm!scHub_-7SVuT4cX~|xGt@7_H0Eq0WzHU3vb%f@ zEt0vHJQ1JlH=Yp|(IAg5U{%0kcro}*hSd1sjVb3qF@0*2wP$O~Uo(?7^d!g<+r-ke zE9(2RppCb8V&{x2;~JToW09A{S=p9l(`H3(I`w5=%@lQx1)3-I%q53z|I)@u{`hos z@Zm9RDsTM=i7I5NoV;7!!go}@l=1rAW5amQxUy0A*D^RgHOH88yS3>WYu|FxOvet; z7Hzn;_o*P2Jb}{5F?U^#T}dIrY=IYJRraIIgOUND7HAx2eXaTGr6mP#3my zv(4N3@nM-7#twGXYeT=5Z=JWLLuw(I5IZX)$pHAES%bo^4UZ6QZ>@Jrx z-)m96-4ZqTXF_60{07+F@{H-ZT6juu^5-a%Q0LRnKj4C`n7n;I3 z>L$kU+Qtcl_jr7L>z;Sb-QEvcx1DSuUE-HLN>5|nR~pUt-`~Eq#nI0+p~xdfZPoeQ zeVa6`nuPFPJgZo(a@y|_@96Zre31Qw<_JAZqiuIIBtow-?YSjyDe7$+aXL@j{6UG~ zdQXOI$;2ZN`!XiX=QXEiw(S05e?_*(eBiMR3Ec{nSJ#^-WN%fpNcScvoKzY*K*Qy= zVo}rf--b)yRrYTTH#6jUF>WIMxFiywzq9_l8Jjl~s`U(9|G4=T?X1|7f&#o54UN7i zXs-C6Jf8$8Jy&7-wZ&%>2PH0_c0C0+_-|Gs^=t*@6nZ9__(VnA)VGsl`4bkz)M7PC z$4AKaDDIN{mM~>F#njrG7ONqEaBL6-tE`k1Q`CnTk~jUp<#)W)DMlJ1$clI`XhGFI)x@BCz4iC>#E z_7Tt{6CU5}Tp><1xVO9=lP1!Y`GJrA7D3rt>89Zn1!OUeAWP82>U$(^u)yPklTlIF z$qP%&nhCYH1@Tl4v09uJ6;YJPK8>dO?L2AvoC~3wG2}T!3->?JN~ii|Q6N<3_3$q% zf8(l;hX>>~36MA8atPVC><;_Ka-SL`c7+Zrm=$lI2jBeYJ`iS|S$+2nWA0CSB8caG znn-KEpX%kME=sl}T}riqFiTmU+Cg2Au0RYTJ_B!!zO9j*qj7P;+p2q0Ph z!3JI#E_l#-w$|6I1JDw1A;=7gv)AwJqYbtXE*LWwgZWLVdg-e%Pngb#p$U2|VfYxj z#;4!DsAEGp0RX54vDIE#C-~Peu6(yKbyC6jj9^mGzj0lmgH{V(`5L{bUjd>slYWTd zIs+2+aGx$g0H?M%&^Utv$Q&JpjWojtF!z=WYJ%IJ$`gn_F@rg%MHsBUi#cTf6}I}J z7uKMW0#A4&F_)1WC7d*gGF-yO2Bh<~Z-ZBWIpfa{UoX0YD$#?Qo>-e62{&s6w8^wC zn8n#>L0m&1-VzY+;6Hu&9}xe6OIdvVUD~a%5&+VZi|Oto06#Loe2Er?Y004_-PH zyfpv+>!k(nNdvU&?VE2%6R&J5aHSNGOVVQmCrt*5Z-d}$C&O}w`U$QZFA<8O5)Cbb zWh?>!GAs}PY{2R;$U88D914I5ko*nH2n}3&e!uz8nOfBo{1LG$JA|GaGF1F80SHV` zFlVs$fLkpIS>d^UN2@rgC9X~0Fvm=;W^mbc&E_H97bCW)^R|b^K+95Hjj%FyhyB+s zO4lbMcLY9HWx6?iV@5DRVS19yAyqVzWUH4Ln72xdC$rAhUBKg`0C+Ms5-?c zDiR4ij;!KBSadaY*5b9A|H)Y+QpF)eHeoguDybS}P%<|ZSjI^=1_2UCP=aKz58bcq zH|A@&S02*DDqR>-fZzxUSzM3$mkcl%d~^f__8f^GL_tEHAv6?49;^Xa$V{UM-(G;# z9(?T11fBV2E~O*E%y?2?b`T8!e#A4(11F}%t43r&b_4PZuUslw&^r?d9>DBFsUYxl zOYbvzlQRs7Y+#8|LqIM9B~r|PTk&6{rRvSdMQmDp@@`GvDTjP-iX1iG(HOT zr;^GK(Y!yzOt~x~Zbh+3ay|(N<}=0TZKzuaWfxRSbNQw4ikfR-YC0vnU6TAJ)-N@k zk439~MhwKKhQGqvj8**~Vz|+g7-cy<6FO-d@F-z&N(eP=PYRnDw#zANg^OoK!RitmK;@*WXVWQiezz-97GThR3u9h6ci9e z;G5+f?>X;%?)T@JXPN2g>8a}Osrq$wb#>m`gJ-0Dy^|x~OE0*;=0jqf!!Uyi{hj>} z&yoqKdVc%btT4{1)qM9Y8~GOHcDv!M{LyuEvsDjb+={ISz`> zNPi?vZkv3oHQC4Up^u9-GfzUtxS5fj_wLOt1Wa5|FQX(NoO%x9N!sNiCz$7M;P^&R z4?SqfMSx!L@Nv8j;>d>|cdg5fr1PG?;KHV_Zot^T zKE9U)5R6-!e#iSs0bIU%Fbm^)%8HKy0KR4(20-=NS*qv4$x>UZ40A8~9kjzXvodB1 zVh?kE2y-+rV6}h46SF?96|t1=ldPcPutn3l)6{u&T2eSM{Xu;&y*q8gmtfLO3Tms!Vk4X@Cq-tnot|<%g&5`9AaiN}i``=&t=yhHve3 zZIcEw^@E@(bMngd6u+$L{ruS@-?+EX_{NCu`Qdecgn7rFhxsU>9E!Cswtt)8-uy+qFJ5G3 z;RcK+UnJD^VY9@kx3eDei)5CSjA({8SpZ&G;M|Tkiqn(;DD^;<2zLku0Gh@waJ~j^ z53n^Tx1J}1pVn9Wz^Ej0HD@<)B`~z)nSeYy7K`TNQHU=VSrZl0>o(N}7sL}9>bLJ* zzgxTAT$8MCNfwmSmo`T&xPF)fl#j1?2&E7O-Nm4wK3n2w_z?heowDx{wLStIjF?Et zm$3kT0%sC{#?bNP?ncL8ROldvdgjH^JZqc?B(3vHTOOK~8# zbk8DC0`&!FnJNgiJus2aj&s9tegVS z4Dvz%zYip*4pQ*yzcgzb=ASCWEgZ*RByign2I099gb)xMGpL+m=;vPw-!1&noy&1! zcEsmvJ0V6Y*5vzv+Y~XEg0XcB*BT*n3G3TFV=jlo$HHwzms+Ys30xdGvTXO~hzR&< zxFwk+APScauRVJZn0)*)3Ba?Apip?L3LJms;>C{!0PQ4Di+aAatHuEOTzK8BtVzyz zr$lJj07&smkm7%7VqCBNuY<;hicqa`hIyrq}U3e1|bqK4swCh#sJnHM?Y-v!6^72T93vb+9eA3hb8aK zmr&MS0G0|9%Zs}Q*kbR*)&$Rs%dM%eVgcaJGd#Tg8oigDgk7Ka=q6;o_V6Hyozcq) zL^t;1s^Bzt`)1(J_SeJ{oK(bEsNtsXUULH`OqMM!1RHo>0uB7r`Bft|8%WmQo7g9@ zq#AYb-LdXF)Qr1QRc*G{%_b6n7E;IoaSl&(DQ5v~VqaVbdE5vDHt3J32MF=h*F3G7O0D|hsZqsiu%Kte9*@r6d_#z z7>No<34I!1L*&g8d!@}1%X}B7^&!b3U$mIdY|V%+t)#H8*p#QtWq-}t-hN@aZF?X8 z7py@$U3#!}X+!Y)3)FPc1 zPgBTiFkp+sv#j_dha@>AoylUA^)y$LQH=X#gF!nW?7b&c6vQNzYPnv8HkJ23{h>{)dNG^`kaa(;fb1i%9z1CBLrw19R!*; z+aX~MnxwD%t$E;tcd#fa^{niD=u$}P8S7GtQfc7bEQtHx@FA7QV3J?xj&hy|DB~VtD4Yovhoze!2K+skhiTbZ=?SMBd9R0UhsVSE1$j2eCo7>V8yl{C%yv7UYnhh;)4LeX0S$?vGc3J(I~;yPKgKQ(&KR` zR@((mauEcaM1JrmszCU&dG6C~C8`OsK*1S$F%8}q4~!jtL)>#S#R00oreDjc&#fI& zf=FNZ5dJWnVZZY3nvwCmXDvHD`I$>HzjBd|$yj|XV_nML2fgT_Nwb$}ZZwCPh89bh z{e>SQh`8Yu>$x#{At{s>#U7e&HrQ%fc{Qu zkM~o5eV_(k`$|RG_`tKX`u3b<-EQnlkHK3=Kl~^#qTx~7*$Tu|VOuYTuAJdDLiiWcFNHI4`qck~sL|Dq?S5;DQ469*tMAeRB#7i^r97khbcGR#Y(eTi z_@jkMQ}l8&?8fm4cWFvP(j4gC7|ZVGjI(lFydc+dGk3*Z&8aeP#1G)E-4rI~u(4{B zhhB~y=#8Nzc%6?uQk^Fi_qTdJ&)?el`mKqjI_i$2{BBL<>Q_y|*of}$$m~`cu7;BS z{ADghn;lVG!_m1R12IDSA46{3LO&g9c+1SOhmOirF+cd>cJ5{u4nOJA2{Joa{|pty z{yy?B&PBrcf4GHwyY*82!Fuwg3q?dRDNzH|f?j(Pc8r)QBU7^>Er&4J!qWv0zdaM)OB!j@e$i8C_Duq-B{(7y65pc*$eUvzNq_`9 z!jk~M3d@O{jX|~Ta}CBb|15k)V3yeZ;%5WBP$WkCwqb9qRsum2AXf-ha4n=@9tTk1 zi|170wa0@4cr1taQUr1y{SV<{0P465BO+f23jtXD>{6W!**?_i-K6dQ?RVs-egpgZ zYs7N_KwvRSh#5NX+gtu5K$qg9X+Iffn+c`iQV6Ce-d^f<>J9v20o_5(owgzw*r$EU zuIx$Zy0+PXqeY1#T_JHX7@l|xK4+ntcwA>8si%AL?PA|Dp&cM1zr~rM z$V;L2nKPQGSr^;c&O>3_X_-wR-Vg784ILF0a!g~n!Fo?nqT>?eE>#!*o)vM!@Q&*^ z0DHO%;MQ*C*CCW_{C4_rxB_SjhVtj?OE*E*w*k2~gILfdmQxWR(gN?XtK}~6{?{lR zHyhX-*eL$dtL2|BHZQ>`O6axN{j`n$-LDhp!pB)y^S}2tJ~FZUFP_}n48iesdXh4$!)Z* z$&GiiR@q}x7BA%s^{Cp66y;sU%Ics|d_^mpYU4i+-c2RKr6#zv4@LDvSei z%d4IY%-rG@Udb|gMEPPzyN)j^dSiW7ZqwtbO@+_*T}B735XGB$h~MJ6QE`_^qMz!P zTZ>3`#z8*LC#nxck>=k%EZ#TbSgyF@lU8tcqcuxD?~dO~0u)F4U*zJ{Aa0oZKHq{Cyc0UU zjQ3QNWJ}6V2*{lF-T6*pGm_TsPoh7D;FPT4ka)Ou=XD{K0fzM&1x6QU{NzG(`Ow?k zVO2T$)5_AR#&@QQD^kQC2OLKD*|VI?ACz{QKh67c!NA@@m1`EsYu{YUJRwhdZ~D$> zx6>CcuXF0YS-|?f%e>QY@~erZ1Gdi`?IyfJ!KGN2Gen=koBTH{$K;!H#?6mhWWLcQ z7C<$(=`hWXqe0C-*xtqD?ziV@62R|)iwtKXzcRJG-0XhkQM;{PeUYA9yoq0;i!pX( zuqrsk8Bis8`;^R^ky*M?WZycwKRV6eE&QVixw{d^qxg${PY&dhtjtpfuHI$IdxZp^ zoY3S5xmKVzsNo3Rhh{?$SJih-uY0CleT@E*Hbx`#?$s43(_((JkH0rzzWkRO2{iq> znPHq-&o03ppJOX8?jBIwNozetLc$J+13&B8iD0|K9{hI6NXulFCW2%E*-p7)VwyX zkMKGCRGWJF))s-tMx@Zbd>xz5Z>t-A8K0CYtvE=z%d1qX@P?Z24qQ{+@ueW}Psr)> z(M2(I;Vhs1Y6WYff4QBXe-7ZJn-U6O0S%en;3%VB{_jMB5V+w;eh`Fo93b8s=d}a8 z#4N`qMBX)XG{;lPSwSpPCcmQ6@(Jvm!!o9&`kl3Xy<4NFyq%+56uYZC6kUt0DOhtK z?A-WKN^wQj)xU3S;ui9HJfrRAI}ZlEMM$M08#_up0Eu6he66r9To-`p*6C#>v)o+f%_n|KZhch_2NrAdC9vLCFi=j(j zkz5)hXky&cNTy77u4WU}3TD><@X=%q@enVNN(@M4%|BHBhp2y_{A~`0L8<&PFqH1C z@^l*t>2Z)iXx7~~`fx4`MsX412%jFmiFsB9oKS&xAS5orXn<0Eg5nRKYxAI-?2oJy z^G~I?4%(jtH*j~*Y9I|MAPw8N0oq?LrQHb!hotypMt>gttD+*L&##Fyzv@3GGk-7; z1eN!Oy#c6`rBGX-zdJw4D_f(+) ztz!UE1(pP(bSASIhi78YodwkxYRav}H=;(u=dUou>6Um%!B>)hh{EX>T8>1zbO1nb z+5DkQ;msl;3JJ^s__+j?0Nu~GhGYh87+mlcJWUfyfL_B5X4WLl|1wueFwnw>4ZCcU znoIev^KwWS%?s`~qyG>G1N4H9{#>Y6oMPaq;D0MbA#3vm zDsx%aeA?NPlyxGKEOQJnMs!oy8b9{2Nf>#RF?Hu zwHaOD@8^8VZ>VoHU+Ty#)sdnNXHZysm3sEM+%I~>&7LTB?a89Hd~3>h;WI|BJNRw} z6i*XMRli1ae7sxop1rcryU2dvp{LsK2l?$;2=96G+`M*cNj9I9ZSpclktyE+XKAi6 zmDDbF>yDF)E9^$UYftJ8U`*(Z#q>6IbsCi@#KhJabaRAH2I}QCZ<&Df56iSw%g4+n z>dyv!P?~(wsTql(cmrEb-+VrAXX}g(&D?$O+eKq9vTblovt!gL6vQwuwyq`Gu0UgW zM6nz2=9eH%uy7;4?~0pK)ph3vQf;khq>@=`D3MUZS5Bohb(e4{Nrr<4b9@b!Q7>oR zftgnvrPJ@i2j&odJY75DDYK>TkLwam>Zxkoiy%5$kdX0{yuk!XF&F_1>?uQ^gxS*}M&UUzqW~t7bH6{8ck5T5_@IlEYnloxy3(b?AyF zrQ0@iiz)I(p~3h>l8_tQqk7n$924Gsq374#-uXc*zVj`V*w;8z5=173DVWDHs#Hr^blqMGKpd)SFh#m@Q zx7D{CH)RslCE)yBId0TA41dG^>CyKm*Q(@#W+W(XJvxI>sk)->fLrGb-I_SONkl4E zPdkQa7sCHi!5%6~NagaY?}m;m^2pque@CLWPx#RgR&*!iWSWNfO7j}s_3?*7m$!c= z;Eo2M^xQ>59rrWRK^<*TuihfD#u%#BhX;(fVl(_)d5heHND?9N<#5&bTyp7|?si%O36#uY|RF3AHz=xm(uNVG_?|L)QRjQvEvcUuV^>~8aGSs=dne0YjX3I>o_NQ z#+$~%VPuUVIZ|TK#9nVa|GIYTz7e1nhiRoMcK$NvevI)%rk-rwB-cQ5ECT1I-ZQ;_ zl)>Ng%p}G&pQ$?vf%1rLGCQIvnfrS{)tMZSbuZuhz zS=Io?$Juyr>!=?BMY?#PM27+NO$cWI`q|w?eKQi2aZG?WR2;(8?Gpy%??3b#1oEN+ z00=mn2=qV-&fGxC|7E0x-@c%R&^hA_g5?Sq{zW(dC)0rQ?WxYnj{MpM)P4YjWj9Qs zbbVeu<;TN6^uGx$+~@#^qmf zePJvD3D@hkfrNksLfgkgi;k!$q&*xza-&rJoHei%=JI13QW^{{a0G3*GU0B|>D6iY z*zt>PGg01xXa06Ow|VZgR5;s+-!L&TvQ|8d_Tmv^qQHR?%Bc}<@3V)cfI9mVD0l5S!ab-_j>fdwJY+B@77@04G zD16gMfX>E>`qXuywb5QC+hs@o5bL$t1^MCVaNBqX1C1hi@EypC8K(kv85mKVm6)BW zb6aJ<%LarnBkuf7TYxmUVCMYv>YO`98smaf+Y2C7|H2aIBti54MVb~0A_D{p;!^OU zu+b@xYARaM?B!b%!6}jZZXE!@y^uNvS6!;4jPPWD4gP(N=X|BK zt}SuvXys*+L3RN?iRE>#yU@w>*=Bf$K1QIn&zbBScQ`)$?XiECqFw zc^!#qlQj`AC=EO#l>NH-oxOV>0*;J1zmduL{5Tz@4M56iLq~+caR!>TuTFIz zYxO%1Kma0sVHRp-wS_B05G(ozckBaE{4t12)RQoK5(g=_hSp!2?v&bGTEA>jnn!U` zDcz)~w3Gk{h3!WnN1d&(wzQX!U0%IBS!${~b-DQ>6$Zuk(wHt8y7|00E7fO=5ZK2P zmv!a_XgYdjgz~#{=>j-aY`)~pL|_1=&Ec4=^`BQModyYR#fFoqVZeB_G8;>;KP`)# z8nA~izPn7ssyIAOh|TKP_~8PZ8VT2PA(=fl_H=%AuAgRoW(3D~DHG1VjW3BWPnB_;RfY~6%oPsvQ_RxNeP`!Xb<))CO0(Q0~ zn~{nB*yFQFU*5+hw=Am_IBJ+PcX=Fi_bWT=ZlS&yDjSv9fMWh|_PlZ24eyOZiaP4ET6W z#g{eR|B25v&p6gZXBOWNw`~R?UzKQg&nr>y^j%G*|5GZ5$0xE7w)+6bSjyqM`ba$o&E4hJVCj7MP1B!K`bFlhOK<0c-c&Oc?$9n*e!d?g zW;s@459RLX5#+K03mxLk*o{QxVIrOv*(4^ao<-Y|PqRM!nq?18lE1RTJ1)C8l43xA z)AsSK)6<(F&KI_5Yu55F*De=Ee26(|4ZqIBdq~i9=i{v;$d^T}_qLC+Oq=52`$<{q zaW7XgD;^OpYxlz5;4Np}`ZUv}&i*hXeK{-k#DP@I?gjR!3At(eE$2x*4V9P3L-FGG zvJ1`B^%u}Oip$8?YTTP@_AOtiJw)#OEXSaU%Mz|h(A{P|0wjt52>6r8Mt?(;(=gEMhN3yw$n(i=g$5N3E}ALNI)z2UZtXB; z62i*7O~rZQ3UTW!2||da@c2m?`sSH=V1 zZ()Yh(z|5k*8IvWwleZE7_;b|kuQTF0mDWQ{J(TJI{fnfxyoT7q0`Q)X%O+$%Q@fF zzt+X$Y6j;h%agC)gNG*@vsp(yqGC%r-8my|%^w|4Fx+y2bzoe|^vT&p3nM;T`HyDCtyoqOd~qFm;1_=MT8f=(8}@;6!D&Cmr{sZOc&k`R(JhBQZ5wGC<139BOO-XRnRjg*z9ty!5%W*aNiI)fE(&5!sciO$ zEQ~=FCyoUm+@JDnU&EUuy2~qirF$XjG2q*wSE$A(NH&V`rPbZz{7bDeAyHu1vuha} zz%3NWKtISp&Hsg~1ehDaNKKK@Dsp34=_|%K4oLVx33%)joBqLhq__hsun3T8g+_1* zi#2Hi_xpVqo^P8Ju@H(wzcE~9lagh3v&`6zyAW|fBCUFaZ%tk(23^c|MQCxmu`u=Y z>wE9f=@fXf*JmJ!r$aizVfe2Dt$hj zNd|mCYZd_ZO~(WHBWR#F-Ha#{Z$JS@8XB|)xfWQHo$nafU2Om;d#&b6jFsZD0iS`; zJ;QR|#?zyB*LoD$&|~X~Id^f47QVxL($GJdAeN^8YplP5a|*?3j0Vo5q2Xx4K^@@# zK@$k1Kh2EdUH}lU{z~C8+l?Hdm&=+uPe81-!d;mGMG^7Qt&F$L-P$dSoMZ|rEZ%4w zK`bOTvVHfkxSXVg5F11s)Iy8MOdCYcV2aUg05XMqy2@)y@tF{z+nPYV3#kMEU=*ZD z?;mh~zJADfzOUll5=WEnWo08+IaEHblzK*zXn!qAU|&Z4JWYx6%@nw=x=^-Tor|Y z?vnsX01$X#Rp(Zl29`0p@1#8&q!JOykKu_*UgfrnXLgA zj_8iZ24x;MQr3O9vg0SE8;>V)`@BoJ%&8Fco9=0;JjVT`8KrC|K7gUdwoU<1b$}(6 zh6JFZNC2HRM08RD@o2gQW2i!PzU%MHBek+FF%=nR?8Ptvm%%X&lv^!_>Tw~;qU;&& zkM}B$U?>QR&YJ=ED_)#spmY`WC*@M`-)F?9)yC(ihGysg2)9Tm-2b=c`@27q9Sh>#?6pIO?G){4OG0QSG!nuX?iV z!fiY&zRpC^10f>!J1bY7e(kMqR(2n=)4AR->f8DwDkiBAmAbVsM4Zxc&xf@w-kk4A ziLCdDN=hU|NbokjT*i$;HfjXFOReF}ZI|+l%h7g*IX}1`){!tmU$e;6D%KxJZdYzD zRE5)Jd?UZ1((KOspc;Ypi1CT(mAC(K;#cxc^a|$qy0vL4pa+96|Smpe1P{I}~OsjCkxb zW5qQ#4j3=#+h6g~8pUh1VNWyW`LOvQ-6ouewfvPkKBtnt?bURP%3^KJz{`V)>_`yU z^r+=Ck^Bv8{#u@XRdWjZ0K>9^0)*|e2+cmzK{FSOI@79i;<%GsvM|quYXXoE(gGU_ z3L0j8loo>7_LK3zTB7FtLmT|7tK>AM3U;6M5+K)V@oewS<|r!THTVzt_l5l$Y}E|L zZr0p>87I@vyGS02ig3MF-JF%Sa#npQ=SqC{duETXBvU#b^$WDj6{9m(eGjyYz0Z`S zw70JRE|pQ3=_y!=Bx3b8)Nq!5MfB)c&g>p$?_j z>Q&i93lJ6brGKkvsA4@DbWM~+e(zIqo(tJluE`i4i+hazqscQpjf zC6sp^Q}k1RiB!ERCUh@}y;NMeKDs0jK!kGPB`&+2r?CYO6XK9ra)`g$jy5vIXikKlosJ2I~q#sH5vufhl9lKfW+eT|Gx}x1PoEUFi}5@62A_r zT&idF9RE*_Uc1CYH2 z=&d+Y|F9vi>ptmAUDxM+HbyvSQbjSlDxN_$EnvDIu~}j=7i0A-u>io$Q3xQ$dK1QcAabNA@*UZ?W6W07PYFj`#ECLxAI!3;Pqm{i>MJgy5 zA39L+h_@`1Ncu)ik(58az8&CXdm+@K^nPoGrjhb_&%j3$T;M`FsYQ@eEZO5f+fV=r zp|&!9!f7@%@fiTvfZLkSBO*i#LH`VXBmnL+0LkY(2OocTtN-Yff1S{+V9(12lNeK; z^S{Euiu0p49>_N?RCSCHih!56l4hYDR%7yo7?hJI^bNi3z!aK%OJ@ zUl@*5gaG*VR`Birf*H7CJBP4D*nSrIMa-YKfUY3IMduep6qIkPiQrSlqBG4!M1!6T zg}?#H)4Ft`D<&eBG49m*X4U0dIjgQT?@MkIPrs3dvt>LfW4yip?Ec#t`OX+YgZKsM z5BL^5CGFyzHsdd1?=(FB9N|Wl8MDL@zNNTy*(k{<(hwX-oY65#7D_$x7_e%Lq9-xR z4#U&d_IOe!j<+g2E{V=EYjCY=MXTE zr7*~SFGMZ@G5OVB=Fz6aSd~qcaiHhL6+H<*Du7|;>1{K^AT(c+-Qw@+Fp{;prWZ_9 zRC*0WTLTE)IfFOM*9eEl2392tP)9ZxvdAXx(9Dg4~YI z(`E6Sg*A+ia00mT4hGf$xPm30GwJ^aFM*MX{?l2kui{L?1j&GYI(fW!jgOfM9lhNB z09dC%{w!$z6^^R3VMW0znCQJ$90x^7PeOSgK?K3L#gKU|SbRAOAmIK})=k*8BcK}q zJYqv+ipl^OVAAc?XPnv z8Y5-&><}C-2sA{A4HCQ0n6QNWl2#l(ncpRL^cj8!gd_y(5?wlpqbd^g;c6Wb-jUf;`W`Vj zdDh0w-F9O&$mOxR(!?ygEH<64UOp2gZadmyVV-}OzrXHZGH5=rhiJwI${3_;L+|a6 z>3*&RYF@v|O*v^_w@{O9?zm{IV9X&J*Z5LQLhzEx&nGuIpNAB584>P}KKW2*0TtMh zy3c5L@FFnDtw~*B5%IVqAV4bPb^%fHTP3g8h~nDJ!4C2ELx-_cwys0o=7-6Gsh%|xO!mx&M2XmZ<1x)sL!LBK@>6Y>*V-qJhau7|KSDZ4m3E5# z%=M;6>fbMEzHzyJQ3vV&9on)aBbo8+HOYP%p5f;}n@-k4u1=<#K=4;uRqB<-$h#*m zE}9Fq-XSKCtlgt#zNaP1#Jc?DwjP5su}h?`q{pYUZ;Q6qF3{P!IL}*MaLaf(Ec78z zuq1|7&Z^38dg_!GFZ_gW=u4nFi3_uT0Wxjm*yf>lG&j- zyQzuQ$RTL6Ls&Ioc-~XdPRR)R4x*PFwh%!Z4wd|~R+@-OS@lD!XRBV*Z^GOFm z$-T;-jaYk`{tX!OM}0Y5AJ$6QYr zg2Xv^*31_)va1u$dM?b52XaSFH$Ir&XWG!g>kbCqi|VA2mG6(Jqc9c z1uC2OaP)|n9i;#&bS;<69^ME)i+dSagdQsO^UP(X%YF@1s=r5KMfyuI)F8vPS~IjTbtN@oW2NM36DDbude3t1*ToOGpdgLt!Aot-#9= zE}2jE@BliN+@}q~x=&ch?>lXb?%1?xP+$o0=CBBt5E03;gO=?${$EyXHwcqSZ(=(bl(>;rmqjyc5NS{xhdCL zNTm8^VaA{DU%EEjMC2|elriQTipNJMaMw+?8Nb!$T5u{VM-DG6Xm1^!!-}r72_t6; zs722#UJKJur(TXmSYr_g<@*JTC+LtKQWHV2jX@hBg_;F-$tN?o8Bn6>Xp6y7#{fz? zFnC731`b;MOS0m<5eMiV;d107mIHXemU7C=iQR!Uk@2lb~od^EU)0Y7AIX9FcvqzLeG z_lp8IK(ify_Z$?qZ`E=%9dW|;T-yFGVJlMAvMrucsF&v?&gf2qCQcvgPq>wEa9Jxb zFsmYQ)Mv18iS0h4`_rErmupaf$ORAxuI4!2BRM*~8T)KL&T<{sQV`B<@7b*M>!}CP zTxSOqw2wx-yF_Z}@O%zeWLJF!1vpg%+Usx2*NJLkBQhYhiiELeGm6(O0(mWvkDhRN zh}yOP{@Un#4dZguNwCvVMymEH)`_`ti@qyjA4f zTJ~ACR`>?*sh_w35sW+$rh;ox7PL+g&tCAnF-dMxqDpi33UUU-Cgq9?)-l0_wb2KU zOtpfBKFilD|G*Z$&S-z%+>%nOuxK{N-k~!5M&qeJd+=$?GgWcXx*ew(EJF+3<()B} zC+tFb4*aw)dp-}PcYoE|Ke#+Pd2&^VPa(A7wP!>=yQcx^K`mUh3ikAKZWWZo05hLWGgM z_d*>BCuPEUlACWE?k%dY@nv{r-X5u~PG0^7jmo@LvGFMu_(*eY`y18i=ABB#0Pur@ z2&?7mo=*mW>pH%Ki{UUO}1bkFxh%^cPOW;V4_!uVoE3X48sXybz061y;)6xo(0PH+R0DIAkZ^v-$9q zhw#R?QX*D6smWncH+ygVtErz>Y~~%S@P5B|kV*ZEY%aYmSWn(lDEZT9G8ySe_GuS( zXYmtCP0cy(vA7a|P?lTTRp*MMMxvA+XIF^kqH^_)X~gOzn22j?>;;%K;>1-JM-5^( zYAZyTD$IF^Gj3+p60+|#Bd?aJY9|oA?jKgwidq*BZzn}_+JK@d0g`_eXPo$3Zm{iw zU=?@1@RwKR-^t{WxVf0Wwr*(vY(o(fE{$MLa3p6dL1!W&1Mb-hvnvMh?@zxl|MsS# z3V@|kp}?h*OoitK;M4eHAR_hvX+Gc*rp`eMHWVoL)Obmv0}D{nxfr4iZ`AoFabX}e zIP1gT;vSa^cl;C69=?JEs6f$%ONBYV#~_yU*uZ(~_Hn9#5g-{Xm-TGIrU)9NN$p$< zNL|3<+2itxc9@F;gowW$`}?;<8g~N8>Cw~DMN@djg*=Aj8od$PCL_vY&DI_K-t?bxsz~n`y(#~RS^v$SNT6KpBVo~mNs1pA*o(?A^ z;w3oGhNkqCaH(+1rYW~S8cx2*#pUvmsU{h=W!{TnqV=q$;-r9^si1os0yKUMh?4^4 zup~){8bFWf!|=05$zAJbVN9Gd3M>x9#{i(`Ip|mlQY!oprRO$%=S8$y<~3yHd@PPW z+`*$i5D4Jk<5RbSMmp1rOZA_qp-;2dmakF`d2+8;$})BkYFSGnbBII7@}g4W^a>fY z4oqx&`;a8fq@unA6))9pRhOm!CSNF~b15sk9M;QIiEV9ma7P+hQuR^2Or`$%bcl{BMz*EiCwVGaHda)6_ra`SR(euSROr=S@x#U>#&y@BcC#h$W&RDWq(!MG=A1cQ~GDc7c}C>fZ!*7zjYHerc~;RREjNQvHG^dFhp) z-Ed5eBpWuDPh5@_7?%?+4!fVq_(~h_TJ0wn;J!~OiM_XR>z$y?l*5~CDd3;AgGe6f0J!odiU+kuSkcu>kdQGlTYb#h7H8Db9J`rd^{(xPfPCVweuoRMl#KyWk_A=fY!T^-)n9!{S!0o9`Y4GZAf2J)?hy3SV)M#?tv{w3Zo!&4{U zF;6A$mb%O8TR#sjNF#r@gQQAFk1W@HvSYl#Zo)Q5!4~3jpH0UO&PuTPEYthU+&=oV zBQL}FKwJB3UmoJ_*Y!+;&RIcl4hyxNh%fK@RFCEP!wZ~VnlC)sn>?#|V5wuOYrBzd z*u`>-9%jE*p_f*uTfUmDoY{b z%yRGaFjFVvzgd~iuC1YtulSItaSw9!WN00(7QS|sW@e$|GW&(KID-5ll@C`HpmDy8 zsg?RAmI@x?sq3??fFyAEJ${AeQJl3f3+I)CrZtP<;v3>}58u79+@omqR-Qx%yuW!X zg+|q5opmxo{R5f5`1sx)_VPmyUDr9L*CH`%_m+$tRVffZJvAqI0X!$ia@6F71>VdW z0ZxjIU>~RH7G(ZW|2~b;^`T-($n_ph5`v5_wbYX#A-R1f52mC9o~z61z$J&FLH-$h zJuds^gG-;AKiWO0dib7J>Du9OfRd5)?*Wo-Q29-%asa}>;z34OWc1K|aZ0742Z904S!9dr`&K{gx;ZT0B~ zb)IAEC*HXmph|&21@-#hPltplyGoXSTofll=?ta(`gz-y^1+xpt5L{6C(Ei8K{YnB zIF!=0I8Hj87dDH~4E~u4f#*Ha8K7Do%nlvUU4`|D_#gy)F3&t3T%GT|t? zrF(Off9)siDU+1s2J$&RKB;SpV3=a1YG|l0+KyvpExxQdSo4(JS1nJhHJ42f2`^)#6`9c{y_=1qA?P5S3{z z62rm}$#kp)7<`f%(Eky{{J)FUiOi&=dTe+w0E04R_=k|^VvN4?ckmpNVp=V~g&dO{ ziw8{YWxfKq240Ah-+wON>{6DF&DBb@Be!c8(OV`?w-`6da->=`3+fcyzMSV}P1O<% z&y=aZ@J+Gqi|QvWzs^qpH+A;iuO=f0M$F;lvc1|3&xo;F92}SZmgU8jA#SZc)P)J( zVGt!yj1g)Hx#4lsjslQ6))qTE3V!S=5+F%b*QM?PUSmM!HX-@;I0W)Hb8J8;nELe% z5KlPkg<3yt`XkX~hY8N+I10l{Y!L);0Ia&0U%=^b{H_8MELF6!<3_#0QC3VRKP*ZX zHUCCM+V8X2bezlHV;7;}20J1f$>*c4-X`ckQ*asOV#Wkx(6YBFO3-U=Rcvk2Sowsr+FlF$Mj$nnK@ z+%sK7)hgV`MdXwCy^63L!jWjYu|@G{$;HZK?Yu2;i}_*=ZE|AbS}r`=;~wld6laHh z3NniWI5?&tx0TL$(*_i6BuNMV@CgG$MG)+{*x;_ARDsvh=c1E|iL$$UZGdrrS1cQf zhd<6cWv9a*zHEHpVG}bx!v4wZZA_-%_d7-;eO{{4-$u-;8LM_B=QJcp%=eSaK6c`t z$h*h?G8Nha(G9+yu<$AhlA8yOBNFntKqFbki47J&0R|{QU^(mTp2&tty>cN*@*o8j z*0(nbj4K0@4LayJ`~gLfTYo4;@FM@5f=W04+)hX!M-s`Z`$`CJGu!SPK+^!_zZc`q zKxvNHg%FaNyrpyGpUz9wjhU4Tu-7{k+@ni*D>24zs1jnUW#%5&l&s34$|9wf7p`Tn z?4sejk;5?%-Uu1%>8XqKO4~rCx>QN517}kMg=FNPYZ#0g_lzlb{loj#pcgnMT;(~J z@s+zndj$nCjzLCUj*v`1IvB167XcZl02%m$l|TmIY1nhh|F>;ZRr){!3*BSBE}#P- z#>^m$HqrQ7WZx=+!Xs+vegoh_1yZ8$izE=Slthak{VTD|--;I6!S!b-7PI5B>6mI7 za;+=f@^bGu%;1^gkRjq%vykfmKp=o{40w~)%?Pf7g+9Ule~i5aP@GNEHoCaGyF0<% z-Q696yL)ig;2zu|xCeI#?(V_e9sbSpzR&-Cr|MLlQ+3zY?CwbSNKfBAJy%0&=tSxq z{o`9C1u;%Z{0c(?13;1n(pn0n^{bLktXawLU3xm6_D}q{|&M<4%oFEmt zT)9n0E|Ua_$DRXhNJ)(%82nX@L9K{@XN6z@s|{9Q_yGVoNEu8CZWPOrb?{*s0I_JA z-l>eHfd?Q7>eW=UUj~Q^0IDcY!kOk0|JV`!S`z+WR1~hjFDFn?cOdaTk-{lRs93&Z z@(6JmAO=TaS;W5ue*nc85D1m576^$KGGMRs93mWpg;<*h0AYA6ZVDTxJ`s1Mr3KGK z4l;uhK~=#}9E57Ck+VYCkmuxbfGG>1IzQ%Ak-rqZ$1R~X$_SB^?I?i2Jo=CnW%4ac zI-OF&U%(6ySRA_9!eWP}?lb7Yq4?5QO}$2`t#EP~ecI>Wj!xX)Q`o}vLi2;<(c>kK zGTPv2WM7a=myWRP0ebn!~=!pjo&egHZo$$|?5-;9O$nR!@_9SXM>Ci8pqrGV zSFdv?DvfNJmzJs^f;Xj%coFzXes_s6(Kr)fdz)fo-9Aaa^$X9_0trEe1FEA4Hp%%d zl8ro`9ZsWu2JJhh{-?&pl7@qU&&!c9QOn@O%{??j=*e4^%$fzkw`uXoa{H~KHpy(f zB)84Wo_Kd2)dll$P4+~wgQtd`{OYobPo@_(S2_eN*Oi8r8p^yFs_A=)0uqq`M;7X} zm+H@Vqu~qaCNrN|fABNx`9i+=t&yEaN1`aIqNe95Qbpxg#?I)r``Lha95Zr(By+47 zPuVL*t<)JWQp)2nEuxH{R#HMS^N$syKbg`U#i&6MuN|PImkAOwT?xjqh=!9JR=E{p zx)?b^0~qwkx$e3^(A_Cbw5?Fyl$SHb+afw>7s72qL3}MrekavsN0A>)}2)O zyEAXckoM>6A8?a~h*gOAYBmqIQoSg1QlxEer@3^RRvG>Y`WNu)2SFy-uuVJnpz#u? zMPPXHI~I08V6Z z>qc-C;3mA>z-V;Qu9hbq&=rq~%&L7(@06LbMBd7n?b-Iy6C@Wd8~~jM5OD(=f@}fj z**F7LfgM)Hw;dD;QfoL@qNd98Oro$#>Es$%L>{O;3RCn~lbs7U8K34%1@FWrP+;0C zhZ1mCcgWR;%F$%vTHxO11BX@;gg{l*-5UU6PK4R@;`DM!?DaxR{8|t=!53E@FF^Gv z(ak1^zcq+|=++DQEGZlz$f-ND(4CDS*F{|IBdIrci=a{1QJ+h8hU{I}xhzmpSf-sn zoTN!nunC#q7ZE9iiI1U>?Ggkn1 zG#ZlwN6i+ZUhf52Gv`%21Q5uzN$et{D{>)D%|WME6~??j+c_z-UwF-`DWaT`y>Zw{ zHR1hb-%L0E`dJ}lO!#N)4fKq`7^3+id0g{IzrMdr2oMaE zJ;1n|Id1gI%r70WK{I7LR&pa?8S&J92jn!o1Tg(!8@md z)vNq|1^wM@{)pF6$4F19XjgVCX?i34FXW-2-Y5>qvP)sRuXH2` zpfZ4oh?saCXbBjn0QmYpOn~G7QkjB9j8l|FACP@p5GUKo>g|)rPY3{M{$X|!;;A)> z6c{Uzu~8sne-)ztWduPdMv@`|pE{F|0G@dQc?CZ31mF680iYuQCx5@%-$ql<&P9Oa z+2P3vLC^#A(Gs@Lep=uKS%(poxnfT@!6Z8+awo)j?Q^AJPa(RkXrA(7YjJ?Nwv0sM zB<;VxQYy}q*klJrdyf2=bfDH%1`Wv*J?*Ktq!Z{WlX3R^xAtCjXWJ zdQ&n1KzM=e=7Hq6|J7Lj1Gx{xcgFzE5E%ep^2RFH|83$W0043Q1B?x51`FsjZ{W7< z&3^@zqVY+KxZOwjTPLXVBy#dP05yRd%!yQ#$PZmi$KLdKVoytCSsoVSwql4CvF8RF zDG0O-OPg}f#3djqF0qk1FHdb#@yxrYU4)k3QuGt3V$nRHUiQJ zw7t3iRZ9LhjeoVMOlm15j`x451lhL(i~#{Kw*gm*!U?q?`iES~ohe4Zla9ZJF@AYV z0DWH%SQ+11L`Qg#WE>)HUZkAooD#%qp6y@fjN$;ep1&>reZcoifLGN$|E8UVK)3;j zjsR#HpK$=rHBg>03TJvy{&z3e)%nj}4odg=Z`uFU@c;FhnJwh-4iS(Tb#D{|IzFxh z11>wY9~>?yQU$lt37$&R-li#IyX?zifKM3mg}S^6e_i*8@s6paIpO4Dse=09A|=^e zkH#bhE%#4(RLiPpLbuvcs@og#VeZdM0^uo%Xq)&O`Ftn7Q`=TOV~(IC71=K<@#xY- zWsLatqr~A@wEI}lUnqmz0X?`ZVxCD_Y-HRmYUFy!wyivV4g8iHPZQ3J_QO-;ICISna^}*Mt z>R#I}`)q@b3`r1x19%~v;|IKA8}v7(9zDo^y7+b)01*Qmo2^lRE%S!ZzuhO{tf!I3 z?FxW@bF&X1zT88oW=d&IjJfZwzCA3AK-(sja0cAC`4;sHeb>TK+^-w6oLfB-L|bDj+`YwRlZ`Vna#X1HcgeEo9(Zt zNvYKOxDv;u)hk3n+!6o)PF4`rnv{?wbDTvj;yfV6jvWB@NCC5&L6D#3t78308uGjsa_8D>2IjJQ@?rJ;UIF5tfv{H^ofC+=^5 zMF6Q82QG2Q?f?1X|K|8_;@|kEV1Pq_UOYMK|0CxFj1|67O{CEywd(TDK^1Cx&%FYm z9eA3XFAI{J3U3JjTQf}u34(NCpwZyzWYJ1Fma0fSvk=pFDeWei4`~#pUV^@#?8o`8jkq-&9?jqu-WUaDR zholAcl9|s~Pd(NPmEzPtWd3t|2X!=>U!ZV940NL(+%FhM?pH1mn|k%#Ggf z2f^u>T%P5Gsm}**8Ug|gV*q6ppamo+{I7KXFV%lp@#=qR14xzcoaF(L0RQC%vuOG+ zd`1@lQg27m6wu)U5(LFw`xh^w>{3L8NfsFZ637x>28w497VFeG5seRiX!}^@CXvWY zUh$|>j~8^I>4s<33u13FWm-LCF$f{ZmG1n!LqucZ$SejAP$n4_3|>VlV*`O^0InkR z9(-J(zfD658UZkqlLLCgEFz#WjeG;324#R+ikUC~#1z~tA`s}2h8FPoMql4S=JJm; z29|L!6POUMgV{7%6_xK6?Ws#&mz`BTm$C-+T+4~+d>jAvmhtFu$!8Y&j@bsLH~9`A zZ~pu!gkKQ8NAF?6Te)4B&BS#2>Tj-Z?!o^%GU@B|&1ek|Z8+Y-$c>bpS z9+y0A>?V#KmA`u}7;8N^>AP01gf}+-N*+of802n@^%v%_i!&)g+yZHte>B=m4O^Bsg-!a63r9Uk5Lld?pTcj>RBCIGm% z3|SYIS(4a9IjC!3_(){MO1^AK2>ZJ?w{j&WTRVaWbbf&bAWl|eCO?N^E$mLIsttNK zFQ!wqSYIRyQSELH2~4>tuT$83c&Ing@Y1-pYzx_SN?9oGlgj(DEN;ugK8L`<(Yomj z6pnq%c=zjmUgxVqT0&Gs<yz+MobYqzY3n2SE%mkqQMMiqF0vU zGK(ja+255}T*RQ_&I6IP;9DTyS+j0TB)klqr4U{zhwRDQc(r%sIUFIjB49bXEj5Ea z)ARBf>_wN&xeI<^(sgDO(5gPvTkqiJCWjj7w?LA<>vUevnI2OsxrxzmwQuw1wVwWg z#&6!*^AWDz=Dt*vD=Id7j>0ck9d58xd@3S?YomO|U1rS6*9eM*Tg=Z&?(r9ZPpX3i zx$uouY1HPk1W?g1l5?og-yIMmj~4QTxVc0$6+a;_6;$_X({i#rjxoaBNqgsa^TAmO zdo;0D70i`Zev*PTOaIu%XV71m>)j4CZ}LARcA|;9vi@HKg3RQ zD8tdp#c}%ihGEQEUhGioYV|I-(X;#l%a!8$zd#B7Fr0H8urm8VqW2o_?W2^1f=*UweLe1ukt z(TlrW%zQE%c+hd%i$~pEK5z)5$aMrM{@7mxzOBzw_8#nm45r`{=F#$dqd?_JtApZ% zw7eaD-7R9ISQzrl=2q4D8b}y3GJ{db{YJZ+5G&NgEx2DLCi7wsh(MG7}N7{>m|Smu4($Ue39e`!!jR z;>j8ga77Cf!gTbNUl1jp*I*wKqFR9_2gNhqo8|Ix;~i!s#Kx@%X^easuHQl5PK_ytZp04}&^h3t>`8U@5-{6x;q zVKqfwG^fGCrR0TgvASv_Mc~VyWfYEcU3&Yg+z<^mbS_a82xP7b2iU=uF?n;Sr0y4vl3VB+C9WEM5i6q+j zuYx2^wWbT&JQ=U}4w}m{54^jX6A$I^K#V&(e8sk=iAIx;vTevin+=Wa%e9z2usM@k zHt?ysfhv-slov!q4pg^QaePGn2R_sW&2f`+V0XUr(A|{&;Sb}>)0hk?V#+8II zL;QLrEsIVq%EaQ~_yU5$P0FI;T=WY@P)K zKWn|BnY3Ce>$-?AG7vPkz(9;)olB^g$tT!qUye5~vbS}q7x_|^!Qef$HLH~*X2gxV z2wu9vrq0yY)qQy3pp?*v5VXEtO=EchSeU6BVjZm;}r6|vn?EpUPd!)-oNOT zqF0espI(&)R9V2?APMJ@NU(hYzrQm($lL}w*Ikes`nlnyV{=hY?mdI`8&erHwP&$% zlvfnw{D72eLGo488*x8g$Zvm=PiM33=P|80bSK*@J;7dsC*)NFeV8(~?g_b)7NFv4 z)Ex{bA~+REAvk_?vlmIwi3@jm>Rq3)Ck9srDlBJWt%UcoK%Lz$+>9v4&v#JNpGgL( zjYw~E34{Qlk35ulc)|M%q6%7ORg%7Jq+(c23Z2uE_h~PbIpqZRXj@(6NQRt1Qa8$J z2a8%vnoIH(xv!XsTNKLxZ|8ou5`A^=$(nKbrkSjU!}7s=Nq_ZkPLZcio!Ur_gcrjo z*qM3o&PU|pt{+1_Psj$)u6A?Wb|x;kBfcIX+DjyFcw?3(LfkFe`wYom-u}^_m4m9n zhf{lkAlJeM1bJTX;#X0v!h3Pp0Fr(q9ijl4DHI~5!rNrdkqSMX_}-;!)4fGP8YV{E zTU9sMCYNLDm{YU4f^W`|>^yTf5Ru>@5VWyXJ#fs&#szU@jI`Z+<3bQvOqjEoxCr>s zRSjn@A>-=^#u#PKp|%-u;-|Og>Csurior>PwfO}zO(WS&F}%xSkI=IrJTIx~j;9H? zUf?1~tgl(Q!e@zuhCb%BepanN6LZ1ORPA(OOHTN{FG;nz36G{J+s{~@z&(FWmnlDI z{IsrwB~>!+ic@AlB62KoQ0rh4L`V9lAN9&EZKN3aDwqSGkUFNcu(Ki}%QcAzI zFyALyG&|*!w>sfMc@Vdv4a3O1DIeBE@X?DpoL<76j1aejJ6kXVs2#WVnD`ru% zIBP8{NqsL#?T>42_EdNURZ`;&Nf-zT+P9>iBj4TA;sW9aHI4nkO655u)<@mnb`v%b z0B*NLCPZLaiBbyF-5<>5EZ>=Lx*!DT?+16T&#g;4zpH=Em~geF5$2tXNk-Flg)F)$ zI5$11`7*H`)NCfn+E*ntnM(2HDe(`F7u4jr^*oD9^kq&|?1^njL8)^X*nRCfk?~O@ z@i0;l_~b13pBx)|qqiH$5kgx7H@qG=WQ-F)Z7V@QMdX6sHtqC_Os@rhG^4ibHs%)n z^DSX!M~{meB5UWY zUosDYuYRIu@7##70_f`&$U^(w=zCt^6f|vJ%@Z$Lwejr^mM<%o+>c(AWyqFsgdext z>!BhHu^V9pha(6`fer3aA?LCL5DHtr_)aqkBqj`P0uFLt%jW|Em*xOa?q@44KC1wL zR&x}#8sv<9u?3O(qcaZbA(g+q#G&Q3ysrj0MLHQJdE_G1{pT~+az<&93OoEI5iXu+4LWEbxYq*htZ&I(Zt2Cy{iwvFe<&z21*0C@af9*-l_ZO*h}jz0+m_&b z`f!=z%^R!bZ@V;5x0$M9RkcF8A=cz34gR?k#ymv$VGpX@yfwJ3L2!E!=%y^MpQg*Y zS#M{=>9Y4Nx^Nsg#fe{$#ut^K7_y&pXSjKmQul_HIb5K)1Ab+v$4q)aM%{`m@bO}3 zn{Fl(l}}#2kOaeLd?PnZH#4EsVac5dL1`a0(c1V(l3^Oz92ULygPvB)8%mO?h2*Dm znB4eDu8Dzr+0vdn%cx|YmIfO!a`h!)Z_A|X!Z`ctMr2v!WHYd%m|a%?c%vF2<+-j+ z5kyTF(q)I|gy;h|gllu0kDzKK%{%Wy$4;1~(_}KA11Hw1J0j-mb~(`#`>=0Cx$wad z|KLtfe%fd;mXigHTHc#_7OFS#%~OuwZ9j2tO+YvWk96}-Mc&i|ibO zv?BGW>$1IqfB)k8jjn*Yb`;!Xe4r%zTjjQ}!3#lJ5e68-%$5Gd9W^(m&j9*#F&mYq zITC{BHqW5p;34Va4ZZq3At#r`_SeprJf0ngei%uAR`r#uHki4`2@Pl1=_jcMLBI4j2oz*|a<>>G&`fZY80;Q&Yp9vuWXF1t zx!vsTBn#RxJldxXT693JdP+}EVA`xAP;ye5!&9)z5TTh(tMpkx%7eby3#n(hDTO!)1U0Df#S94F(2E+ z#lOciNEkjAsU1u1>AlY*I484m_ZM}Dbc>{tRtL+4Me1yeSbp!^J|qd zMf-EgV_59Ree>ufccq<4MP(B$=FN$}(Lvw?GF^ohiaN&t<)F}NA&;|rGWwN)u_Sk9 zwMgC%DOw6GJV;i=khpJ|k|~5R>8!bi4%_BNMy(GFLJkND1wWL+dITyAN>wv-6(pk9 zz`)9E1Qo}>^hYr$hGs48v@`|(%&O9+E0hN4~D4K zhKap<-pd@}d&x}wSGykGNOcO7afzE(lH#pyYo@im&J6_Y3L`cw7DCQr(6V-Uf2Ha_ zr!pH-_AcgKTIb8ks%NQms)c^Wz||zpt*2^`gF$spyHYyIN*oV5plq_EYv}3Zv$g3z zK(b4jIN{gFWxJ23lS(x{n|JkHaGto8l|aA8e^;0WHwDGU_HvB?H#e@?5(rre*Dpd= zKlfndG@mA`M#Z&RPyIM8@_rb8;rjNiwQ0Va6^oU|bbTIMf4g?}eoKXTHg806>T)4D zSR4ovY?WRU^$_EG18&}XOm~wqAU@mHzSoXO`#W3^LJ*ZY`;o|r@&%9;71C#$R?5<;2zfuQiv zFRsR5!Y8@NmS!*d+=??$A%lspWxx}8LbVGCYnXMDAXU&`WmO?iMo!#v6f+$ zNxzLbE@BPG9e-eCkv_4`JoS8`~Ah?{PMJbJRPzLOT^<8dYy*O#&RRHgFHDq zfFsCro_`Ljp~r*8@=5j`OJI$u_basbiz0UF3#B zVSk!oa`rb+g=Io;aOqB>rB#OoVoz(})-;K58eK=xm z-`G`(#>|3n-!e&DeQ5Vn+;+0DQsU~{A-Mko_u$FLDW|naiR@yT&6)7!=@P?iWHCX&1bhIpzUx36w)DU;MCSxuGP zSIP6VBr2O7RYn6JK8Cwgw$kZ-f#<=1to!TLZ9X}#*X8kyXorY9j$tRZnkcLtAthe>acnI_a%eBrF!LGH z)SJ!;?aI!Ji~ZMH2tp$TfVATAfa7iU*_m~xk6nYEaQykPr0ARJ+jUeV*T-=$-Q}8_ zo*0mTHJY=FP~OM!-lXoXU2{Fdtl8O6AcVOhhrMHz+X=<4KVPq@}{KGU4pmoPnLPxT!vZ-IwW*MZ7DcA%Sl zqOEzleV^xi;U>{>Jd+IRdt*~J`>W&X30HRSueJyJDp4e%^T~p-Z0+1xzxE_GLztQD zu#O(vC(C?z(m8*Ur`0t)bE)J~zT1My^`viFsECW>Q% z2{r~`#nbbXjIQuf`h1_kIB2KJb_l;=JDOMK3TStRU&lU&!DV%~%V~6EckfF-zf{iH z2J$O{_Y6y)!E%e)?Pnqf%Mv6dk3l2Fb5)2hPl>2(^iS&#^>~?hb$=elIzH<6JYv9X zTZ?;fw@f2UDd3)~ss1>|*9=3zvr*4AQjKzJn(a+v+T z6D6i8#~r$LNj!)N0R*)glO#<_D)$W~cyuB#o6#&m)*n+?-asKI&$9dvBU)i{^SDFG zZ<#gX)e?h;n~I(LoU96)5t9J>^%;kL7&o8Ho zM?FCkX+LM<7GI@my{!2*pNruts%v@6!XmC}9HGm`BFYhK7ml>y4aXh|Be`j-I+Pnw zawZFR`clBtl!#nhn3Cr|+SKF%{LFL5P8l@oOy(%+D5fV({*?7T@AH4`DcUy`{Xvlo zWQODNqgvDaa+~~2L;OjZ=$zYTQA8zkWB##Y(iR*zA6$F?8DeiKFTp1QL+OQ-fKEda zXolKYimTW=sN64gQNQ`MmIC~o-JLQ5V#yN$ZTtyt_fsL%MNp6JTBlkt%NPbE{YNDbWj{s(i)8wRzlfySP~iXLmL!7%R`Q=(`D4vda7jX4SF_+p19N+$v~Cw;#U z>%La;9)!Lk>N=Z#`PR%Jg@&LXptY+#OV~WatN3LL^alSyP^#pRrmfPPd)0g0lPAPGW+1+A>KEUhdC z%*zg|YbwRN;kHNX#Vgki_)>+6oh=YsV&=!yG4^9|6MPAWV%yL%)DZ73N0>>LsMZrb ztBNj-?Q?M4ONExACvXk88(4pTyO>|S$*j%X=G(JZUq3(D5J3vy6n`97Y`}kt6Yg~u zTokc`mtt8?z-{_#yMwzuJbhpFb8LaBi=>by$+{Jj>AEDCqjNwxO(LKi)uagL=t7`$ z7feFTNDb*O+9JzEhcbW~e+)n9B!%~N6I~k-XXTGRx6I6DClGgr)@fhT5})&w&oB0? zhPTiUFKr_4+3tP-j}J7LLu62QciJJCso`cQ4h7ew_l(=xa@Z++iU<&w>@FL5Y zhe;KU!?+x?H&KPfsmwS6Xb1=j#Bv~wK~k??6xdWAckI@<=s9M;^Px)ag?*h&8*g2| z1?g_^>}LRY3bmWsgZ=uNnKyKd3dzotTk350KQmVklJ{10^QSurj(~Dnqc+?`i5lx);QRRr+)YqDT$be!M2pZEEj2z zE+-P@)QdlvebTpnAtS-bem4SH{F`wxn&Cm|x!y_!D+rEDxzdxcV4qa7RfI=nkrfvI zGPX4esg#1En=2}wqq=Q~ddrTHMN}PYnKH&f%Y6y$_W_BLk>ziqL4&C`e;eP^Z?dDZ z@adBrlKAYV7-_AChe|xR9E{Qe8GUccb6kn_uoL%iv~N9oMq3|u)?is?l^m&)$Br=t*xkI%{^F%bX6xE>F@u;W zc&Vu(2`Fwygz3Fte=}W#b0y^Qv#-7gcn7?xe)iEuG#YG{6euw z-!EBQt-Wg>V^CU8bRXoa!y)|8xrDftxSrtSnPu;q2eOjeu}BAp9tEm#pR=VcYeXu%Q-ulgX~YV-4p28HT|T>)Zyo!JNr;3i%&gg`3;nfd(Ks1 z%DO*a?r97=1@Gk--5-K0eLLnWHNHG-RFNvcrGJ zo#vl@6x%Ve)0So9mX)B;I*4&jNIMHX{`DZPUBZpA;q3GjfFh7+%k#zD-#l(_`2*Kk zYJmYt6j_8GbXn=sDM9ZDDOhM=^TtrRtk@;T3ak7ePu2G;^ym?j?1C~7ZSF8ujrChH z6Rg6I`(P-u==8Q8`;c}{q>g*8{g!K7=!Z47W!Q&?CwXJqK1;Xh=gx_{bQlv!GxW2v z9}ZX97@oiG#!`;ux?WrgcV(g{*jz;Ol!Dm5s^I39x(FPKvHBlvwX_N6d42Yn@F;U= z`A&ML^%kzRee^Q*iKmcIcD&$#Tt(L-8Jq~&>7ZkIvNv>4s!=t~GLz^A*!0{wqb$SKCD8Z6&6niRA6rA>+;thRO{2F z4d}EE^}E>iFiLRn^df{Fv#HFyPak#4sNBCzbv{HFOp3Wn%BpZ!MPwC%V`~1~J3e7G z_J>GDIr7RXn_r{bS)4T7UuLCCvI3a!mR@75-xx)8@*nzvmq>9|V^Dq%26hWt<*V}4TYrwI4Ais+u#nsiZnpwQ*NoljUkgA9jhfJSsG#Oz`?!1}m~mut0a5B8)DHQ8%YF&iHq*5GzW(a*VP(WYrB-(jG<_R|X6#G(AaRK~xz zn(+x#t2Pv|=iqwSi-Qu<9YXanq-t_u+^o?EL#gwj4;>vXFVtUJ_N{o<;a_r$tkeL> z`9P2Jt@O(L7BZak7=clT@XF_G^R@ zHzbj^FlT}R#&z;S$;H6M0y~!-Pv-KmhRe#D8dtb$5rroz_hgCIt=RIC{!uuI+2#+E zUlE^mWK9tXXJC7p4jJmgT5O$NHmj%wGF#o!9Pa((t%cfP2GFomcbgAZbp1K>{-!H9 z54)Z6qsU~6Y8+8?N2^AZtbC{z7)mEj&I9`m10b`0Z5~KQehn9!?o7%gTf03PKSNqa z*lE9B3mZF&hh87xg!F7DL&h|g;Tleiuos*IKJaNc^V8zhOUm-K1iAFnO154*v}r)5 z8fUg>zR*I0Oht`aUj^V(99KdpJomG`C0AT;i7U0$5JlxXs%_UuQ2AL}O;n>TK9jx8 zBlwHGlq7F9T`cEE5K0Ni|9pp-(44L@D#U9c6yhBergt6b9d#h0EDvT0psMlr0QD?_ zww@m~5$Z~mi@NW*6iGF`Nyg20pk6_fCyF>x&gu0iBICA&4XACz@<@OT@FStGV63L^ z!t==f&E^{V6Z#_Fo7OdOIcIO7kT3iei={H&^RnxxKrk;4sTYb`w1U*yFZB8=jcIC> z$)_dP>C^EH8fH>8i?``}6($6}Up^1B&W?j3p%mr5ug}rlaJCI5Q(T8IyD;>8h6c^` zHHPx4!vRdeo#!lyQmgwj!kj6=RJr)}pPfe(>|ajNtBu>cm?#Y)DyI>X8O1;RqCNt1 zuyM>bijw_$xcAJ%{?f?QK@I@6&tq?ca&oy}f zPeMjIw{)o80d*ttPgc%k=_dYnG122%d_4c2qAi1NW@2-0D)^vG+q2oO&n#FECIXU> z8am&I23Etb83ttF!54es4Tp6Q65mH*8O^x{_Q~yg5$@6W`x~FUN=z-pBue|7Q>%#9 zk`K(P;f6lj3nUEHb(aq7j>Vp?q*7{PUi9$u=C&Jt!3KyKI(0pb-%kKSXxf*{M zghRHYJ?Qe*C@tQ_&L$7l3|dioCt_K;*;8iYns4kj{l4%(H~bu5O~c$>V8go>HY0U9 z!Ctu**ZgTiG&>`?XK^Z&SL9kar(MEJi@&VOb^@>hO`Yyv;l9?I&@Sa6%4vNtJO>FR z3zeLK6~QxR{&P`VSkP6hca^BFGs{D(vh3dxk+u{xfj#MpV#{wz7EaXS+`1`|0 z&zZ(R?F;fxVFE~wqaJHSBTn<`!laNp4DNbKHQME|XBuQg5w7q=)13ezDTBd`&IKyt zn*7SS1`4=~?1IiT(Z$d(q{|#^`yR#gfp!81KSV#-^2FkUUr1(uR9_r@E93T?zjGT7 zr=fVKAH2pq6-cHaBw*8B@Obv9S7lL2xGps2smnJW0;E{zK8%+E`|C@z)uMb>d^A8*hKq7 zal8acr`5t!v`XluiM6oNm4N7^)A}sxl+FDLuorWtdMLV%-XHZkMETd+_KJpHmmMa` zBm5o0>eJ{rSR=R$~NUVbC9>X~%#p+0|O;l`Ly&)5%&{;thJ_Pg7Y@gUPmeeylYc7l+Q=|0p( z6f=SGYO0F@@nY*&m?d_a&o(CiLR}sBOYG7{aIgGYAf516GV4;)0CKU_Ofo{fAKUh^ zh1(a}FS1`Xr0<9(BFl~3a=&#W3eKiqM8R?6ksuKMSbp*hn3OB5#&3E z23IE7?0Gm4{k|+XT10ScI=mopGR*@_>_ZF|NHlYx9U2?k|c zm^1a-KuD-CSSux>Pp6aPnSj2655M{zHI=u#Y0vPs#2KFaGZZTrL7c>A#xqAn>M6H#n|B?<-Btafq=zgb3Z5QL}FXR;Nw zjL2#~j_6bnsrBSYg>b=oOT> zc%dsO)ea_{GozG_F=)e$N%T7zqHDB}r&ZhVc6U(SD)ij~h* zeT3tY1s`!e&3ckKb|lh+LExCiD)7}{9bf@hS%hpxBVvMqeDLI#C7%D3vQT7kAqQj3 z6>arrWs|8tj%b^l4R${&1(goSVjou{2V0Sn4m0l5H?z&;ON)L2Z#?YA z#s;5WQh;Nzd8t$lT~^`!Eul~zW}XAJzFN?h!t|tW#NRsBb7(6hNbENVDqg&sjS~8L ztdgs~Z((eNJ>_w9g^Asml}L`p8t+bpCi^yTD*#Vwj%FL_(3B;h_B8gwZ7sRS+|}Ah)}JyS#Me($SQf!H9M-GdS{5 zukK3~aYG4P4-h7|k}Ec5b%X_JU=;t?Xq_~cZGS_y*3Z=N##mlvRB1Es7?!3mu&Y}I z+zynEp;QNiDe4=v}-jeUVKmHFEtl&c^rfD$mP=`@Sv6=Jp3jNHOYEg z3lV2nPxH7Xl(BGSu#QZ7Raxl{T6U1h48q{u^x37CvXj}oFwkm-4xz5y-aNt$tqrz+5S{ME>PZc6`2hbl?vQEGvdE!7f>hSteo z!zi~7vEI`7WGepDe_|5&#lZ+_^;!@wF{u*=Kl%0MwUSrXF};=fytaj3yMvV>gaCeS$Bqt8)0#2rak-I#Mr-`aIxiMnAW2^krzzdJi zT*@mlMv8iE0;Tvzk9X(Zy3@S0GyS@K2k)JN#{?Lqvt#`Bv5eStt$jjf!zbIl%*J#C z#13Pl3qjuW@?%}1A(%CiHxNh$|`mc}Off@IYR;%Im1wJU=u1N0gDu<~yde<={7 z-VzfUpeCVM(F>z5o!O7_JH@EYnz+hu!#(n{TivkC_2d$huK0sGa}^gF%(dc1^yBTBqIU-NHc}mIcUD19~_BI%vp!3LBo&_~(5g7Y6qJFz1&3!J)K; z;N4_gfiJV0!D~}-JHOqK3}DJeg|YUaA&!HCUCHvO8HGmVLuIFaN&cEwjb@E}5Yj>2 z^&kx~mGA#?uAHI8EuMvA@8;sNT#e3C><3?y^`+Aix5Gx=-4(*``iLD)E}@TkLT2Un zhk@yq4(X2*`cYE?JiM%jEvZM;_<&=|R8=+(>*B7cE}uYpYuArd`%^kKm`oR11Rr$e z5C*$tg#O{EY8N893ea}2=|HcLx~1gVqtsb9_Rv2Q;v>H*-&j?F0g(BLU#EHuh$E+| zbwo|`gsjgkN^`#2aK`!9=r!T<4z9C`DHMFum zn+a*E>X7Y1f>J__P*myfMB=;9ozr_sV^xac^Z)=-T~^^e8KDs&zY*GMkK4k!xmZt+ zoHGSDT|_EIGvU`OSD7K4m2jW)CNy7ibqf%z9G~<*B(O0qr?P+9an*lah`DEAf|)(* zv?fc(=5rf^xhx(#y&7%o7%y9e&d)p{DMc&HXX``kjK=tBQJZENpvGtF`gynZK}L(e zIUUR1l4nXmKfViSi7b}XxeQ0*6YvFqw~D5d?0~@RrI0^9`&O zJGy)@LeQ{mYh{jv$5~unFv}jdnj6mf^%J!WjD7hc26b`^k|R8q&W!t{he?U0X zz3R1!fU16Sr2!eL9H4Frwfg{^2&UMJB(G zx^%a*2!@U$0_B&vDU!JKIO)eSpesUz_trmmJ_bd!g`^Z)GScX*7nLq|^%V!68_ZZ> zhwNj02pjV&L)7!Tz)Pl+0~6Furu#rQjxc)(g1FDS{ra$IFZI)4T?VpBE@v_0=hu1p zM60}3U9-@Kvb zW|g>OJzUd?>b_}Y-=c{}6d+avEFGTw4FB`Yy;LCak=an+FB7C)S9Yz-s1U5mn`C^V zlJEa31rj#`AF?BcCDzr7W!w0tud#KLOps!M=2oO=N%xcn8947Zl{>ipY`W;t&Jp)a zClP?87}-_PqIqS(Vc3x7k($Fg*Y|3Cd#}msQ8}8{VvNllW2U9KKaXjgZW*&v*`~8M z?&yUVC>ZY*r>Zy!D+jF4SWI|5J^@STo3I<^$ma^WVCBuYbIPz51C!g`C4auU1a_=W zTCizVo$AN2pO%?IwVGtk4vT0n>ffaH?679Lws_JY9;l`6)E!qc0fGk@nJuiVsq56& zS8Q0)ARVBy4WfmkFSEwqMUott_JF42T?vlvqO{G&(Om^*y(8G;BO<5MO*1!{mfW}pwNq~FOB-q5}dDevnQ{EY$n0l}3`JL8adm*TO^xMqmjnJN*r)}z^h^|l5 z4PDtv>B*ER$is`>9m3p9imR$>$iThpIkoXmidpaHR-Dg!mk^L~iTrBQG4klVyBNA8 zB?7gTn)HgcxR8uQp0oLOf~56e*p#PpMgh^~0)*2ZRIdL214KZ(zY_xraP{#rsrL!A zp>G?nz^EEiLu&fF78eNZ*%_tILyr$)N)U23ft)PMWe%k*d&tU98Hb%I1H-#{X01qP zXGCQSgTDpdn4@o4>ugS^(N$DlMq;G~(V=(j>ckUd;#%`Q+P7+gXMXa&mn`#CBoeu| z%1xL+1}zJJDneq(_2$uKfit49phrY%n!BDT#>WPY6!jXqLzgMQ$qMU-E!Q|53!I?F zg|jXPvg%L^59@e+znC$E9PBQptJ7v;DbbFQ%&+8Pcx&)ll3|2Eu4kkB#rd6xdv};eFA@!xo7~wVFQLz!>~&G`0_#F){!IL$!7O<3L{@KbDsA^@nKkb?%2-9d;A;AxrxU;QzOktyDnxPw?s=R z+!^KaVF}nN^H^-+r>V#YSz`Y?>GWX7@C_IAfJOS@Y~CJ4YVdmwdT-bmH`2L~DIHvM z+|Do=Y-_^yG#vm?QAHY(*9&4C zV@I}V2OO321;V|zFY<&p5}yV%IT4J~b?Of?UnM;UMU1ytm z=pUr}6&penwe%qBrcdm-aNr>TiHbDS`gG9$ps3jx@QjQF7V9tc+;-j(AHm1Q!<|wLL z!|nJrcSb8Iyf6we^3WfvPj(Co!yI|Ealm~x8uo_qsUi6ahJ(X;lz@Y)~A z88-@N)m4kDLGWQq{Ig4R*2K%JWg!-A)MG%AAPxk0Nys2Mf4Vx|h8BoTqn>^RwL76~vYPaF~ znA97rm~hu-U`F9^TC@>Dksi=1@YP4R8U0GFpbmDIF=f;78zR`atlwUNXxx=M=xC*I zRsdE*oj08U2ezv@P7o;?bi78Q6`ef9h;wdz^I_(DqhrnD{Tg-44ZAzx=%ekWY^q#> zeR>BKvCfGG5B%b*k8RWCTk=zke-Iis1OTlBU9e$J`M(vcimgwma(lNp_&deOGy@t4 zPSSz7QylrEHmS+FI-Ij03$XC#c!x1+1;)NXDt3OqwBso<)Lx>X{HScp^^k7$1JDhR z>p#di;h7$d8fH3lIj8x8hm0v>K@fC?`Wt807Y`U(x$33h?;Z!+7NNcThJT4;e zTt2{=yiG09)ck1<%Us&kctV%Xo=2+#Xt!g-3SW%Ys)7y%>RQ2Yb6zMs+H74DP$B8t zWTjIF)25TpDHXsOO9*zdG9~c*-|cb+`ZS{uKe2wCUSv7oSFB{2u=~!u!kkR-6^&O) zT-^ppP&+yEImyv4W3TEt0rnl5C$}tvPlfoUTAEB%wsXjP7N~&4P|vTo6A!ZJS6xuS zM4KI@*GDs8&p}FAroQaKA)lqXgR8&mgZ!%hyP`gecXlvB2n0_}^IdgT>U)ipd2ZlC zc{QvUbxSz!{>wZy_MirBEAJ;;MhA_o^|?=|f(&_(-+zD+l_)v?Q&#=j;J^H)fqmg{ zuufHa5cAxHJ9PfP%J`HRwGz!LA`dbe zhGiSoW|X1abkU$(#55C?Hwp^F^FpuTCVDr5OeV3_{J=06r`|}_kq(S{hJOjuvE2&F zoany}E51F)8DVpu0qzJn%_9Yal&m>gM8P7j%N1)x8oJ(A`^%WQ@BWHuf5}RchAXB) z+mAHvO==4$?_L%nm&CB_q31Ex;&OvU5IZltD53>@y?(frio-34yrC}#J9-!KU;JOw zCDnMxv|4>BX}jpxksmg-_~Tjk#}#;?0qE4DQk6p`4VI6)JDJZoOHZWQ*x)jwj$$`r zF2v(xa%;I`qdVyvKn=`I(=pSFnJ~=!X~gVHri_Xu^=$~3M414sD)0OSd$0W zT^IwUo5ioP53=u=5q->D*tV~`B3hwMvew4{Q#x_b{#EpD9U^*D8ja5MP!4&;}l z+e(DtKa_1vzH0|56q1A&=^6XrAW!~_O_C6$r5jB}?ZaW^B%t82Xer13rAaY*#s8(p zDQPkMD8&^ue*GU&{^cJ2i^xOHWq*!(bI&c_%$cAuGr`w=#Jy}|=^h!U+2x97CsMMl zRH|m0v` zk|~eE>G^Grlt_*tm5*8tP)pl(1`|R7)Hj24<3BvhZP-)}wwAShjq}a7N%x^PxIE z3rMhV&)u{zusg#jTB7=+3_pf5+2-<2JJ3+7$Inn)n%-)pk=q55FRfRYvF!gWeG{w-$9Yv5m zUfPd`u*GYFRDJ0apg1%=&@YlE`pFwsS;)w?!EUUuSA={7&L~F$d8g)IQ?))Dk!t0< z;|xnQ!f1WXJZTvdQ54J_6myT3!=N4zkJl{{E?gjS>S%P+$7R2;r+kWTv|soR`dpz9 zy3@YRJdAxD{F;HYxU_tzR2q-rbbNw@U0_TYZ?utu90vW zXKdS0{9EgRaFUDnwdAJ;3sMw{0pu#(uA%pn1MN4++EC?$!QcP|$=2%rd5BGmq^2JR zESG()Jh!C)Pdvl72$Q7!WnyjfHeQWIym9`VFWe#woRq|aC1z?bvM3xMQHrXKIS=*A z?P^{L3nI%>&`P0%3r?Vc!{Sd^O1tD=pid%#K<)jtbHNw-xt>Hv?}j?7Rz1ERB*&TG zZ6!&TNC{~m5-IjlswUZWN1yN&YcPBGd>*Xii+H@3{C)=yU4O@jixcY>xF&&LZ7i6P ztKzMgp7G|+rEX){`H1LLc&1UwaU{H{^b|8#K2iV^|9c&qc`9gxc7@d!yrA){l$Tti zi8Hw7Hw46cm}=1{4BZ_^FHUXoh#7|%4= zubYIpQ+F??T<(>pKV=M70c@rH5ZO_(Yj!-1uBlCs2Ere!8U4UTk zu<{kftFkelS+~<*L4x|~;g$nH3?JrGM+#TT?;zS}%rnv60RP<3PR(Jvl2#O~)^n1) zsA9>*)nSI)Fz8CNg`@CvAxlZB8|ukN)4+%VJ{*m5uP*qJ?i%|cWC=)6EgtLoSrc)*oJs&glL%k% z01L+*`2Y$?e!D@AxfHQfug*l+Iu7tD<6qEcrAmt@!_7%6vr@;iBYQkv_*e1abLetG zC2+41%Wx_caeZp|%fOSHs}>4F7!wT!)OH@Qkt5wms1a!?wWOce-!$5Pi;cL9&Ae5K zgD1W#u3(WmXA^V3VEm6@IJ%@s@%)juEB?u=`r^YPu&T?MuWzg*gC8go?ENHC!W>~9 zP1^NZnFVR^a^zGbk)H zU305%sV%4BM&PizOGxMLXsx@%o1-w&C|$$_+2 ziv#FajHcd0I!R}A#zV2n!l+cHN3+8XQ#v=@`QRC+ zO~DOWZM+$WV)MU)reX2L5_fmJfT3I$v>G$}_;xL%S|o?`lB*;Ar0lyTGHj%LY_erj zH-7ps5bejNwfin7rgf;Ls;@}p1$m2ap|sFDR|M!Xg~Q^#t0;2033~gL%A<*!u$*=IkxcEogoS%vD}Hg!?S0& z!<1~JuYJm*D*beaImn{kfv{i8t79Md(a?(-oRC~U`>gTn$Q4RtaO(s_4}cw|mVqAc z`jTVMMUTj0fGfPk{#2V6qj<3~I)@y&qXU+Y4xh+7Sem zmd2fJs>_J95gciJ1BbZ zH+-jsi5H8)@`qtx+65v-B^@nq@n2^qrUnTRi`$!PU_ir`hvlVtsDqsctmkSKT;w3A zrB#6qIWc{tuFy35*EVcqL99~E=sc}UCHjEWIY{q)Ott!hHA+})L0%W;kXhc^756PL1m-%{Z3XP)H5j3iYx#1 zG7;hS*M2WBc|wgUXPgbgY|j-*TnhNU)r0% z=)SHg22a`UC9Knh{Qe`LhkIyYHWy4C9j~>PfV{iCe zyk-K@5mm+*-Nx=A7;Muk_?YvVmri!{B|dR+DCHj^x$(`vpwuaIE+(%>ZLfoc`$?m{ zQ<<#izVK<~;=C8nttzsJpwdCEkLPu+ZwqgFn%2502rW8Li1cWHng4XsuPoRQHH(}7 zy=#evf)h0@yP9}%FhPHJR*sef-V+qmUq)OE7;M{Q2kg-Jw4+B8DgMr-uWK}6F>B9l zVT!msx*PwoRT+qQCF7h}gciq)((L^v+YO?OHhuZ!XF>T4J(a9$H-P|dHfzdKn5^J( z|H_GaNSA_Zi%qf&knYXl3&Rq4Cc;_xle}mRJF#Vp!V=Lm13zqe8op`AjL>TbDL|2@ zLN!-gM%0bR_6AMptd_I&@Z-L62uoQtc@9(De@#Q&sGK_V|LVYM_PmeJC4k*`kSL|y zX)dUWUHXG5eNa1y^ny=-Egp=5V|Nmk%qEAQ@N6tD?UX1s+#k`XxVg37MnNHKrkTgR zzuCjQ=Ut#v%sWe7<;Juu19n;`(d{*Z7#BVfD90NuE)sL}b73?~1L-4x$b&W{+0#jH zYhndN(EvJ|UeYD}Os`xh>?u#vq(QV5!oil3NXiiiu?jsbK)W$f8Nt7;dV`B7RswAm zTm#))5%-T;=`+D6P&|X5P*;O9A7H<5OauCFYGL;gbRVOG-b%1i_w@DS7=`UJ(auzk zXI2R|0h|LuvLUWk|E1zCHtv|H7HJwYtUbQcz)K~03x<$P+s#LDZ(lWl*H;Lu(*E=rjw4uHm?oZHhafv+^w$LB`{4H8DxZ;Y(hEAB_I zALt6-?dh1)zwAPi8WLdSKY_Z`@hB~OT-$4GBK<=OqN@o~O_YWbs$1a5N^B%8izbvo z;ijD9l-`!46J!XSUY7tsI5Gn$OMY*C!u zcQkL+8vP-jevQ(lbuN#VzIStiHwcExtc3=3x3oeTAf56+uKdRXbKdroLE`1UR%JzOltsG zvQA#!KBV)+`ORm?S>6L*n43uF->Oz9ebMWNGqTFmQwcy8$l4z+6aLp`DX40KjmKLb z{n$a0BGPQPz1OX+wly`1h+jTIeiTI|T17Gr&sb^nqG-MXq?V5)0G;99k4cT@0-{CUl8~HV~AQ zf(qvr@uMk?6iF;3kY<|ww>_3Y#f;Kwk4;q~p~WFi_$;lI#OnJrwW;6t+$l4`+WDt99@~a*u1_G5(zz2u) zCq($v)s%1q+X~pfqm?9|2}<>`URV8i!{uvCWmCa*O><}987E3P7uOLNG-$)2Z05VT zW|zLZoHc%C-cBn9uupY}B^AecC?LLjt28s|o;fA6LDFw#$|qWA46=4f`Fgz!<28t1 zF0`8=Cdn7S+&txe-REgw>j?YS8-bPg_O~nX9}dUn!zX^fbasq8A#col&CvW=V-fzU zj0kUwx&&~pds(DI=gpVIdA-nVQ@xa$xm~gj=aBdA9+wSFPt4Wv3C#%=2s2zf(RL+? zKY@LUEd?{7y!b@6Uf%$%g+phlC}(r|{aEm@4@k6yQbw_2bYKl;y~r9>BFwUir` zUr+j??tTm67{ovc6fGP-(yoZ42m1UJc_0LE zM97QojiNE0mPGLiTw>iW7_da+hoQ?RBB&B3@TTA_vr8^s0^^a##H}Y#i3PU5O1T=QykD7ix+i?@M?;kKP(IIr1E#1>uX;Q>gS;S1P2z-MB>MD|7vCW* zbxz(-MfMK#%ebEWoDLP&*sacsSjK6G_A^dYgawpthvjifhoycS^vrofqpU*$b=-V$ zicH0z#vw(gm&A``uC*n``JR5q$&0xdeN2@|T?wXge0PRg8<8lgy+#WydR*;~1jN|} zbv1(hwxvDJCK2&C%(3WPXwHf;PximSO+htxDgo7c9fc)N$zsQ)mcYUZ{M?V zn(OYp{qwQ{w^{@j76;yRLqz%w<4d6nchrAzarHi&ur!!Cy(j5YW)&APO>-7q$ zZ^74@Y9L$x{;ak?%>Y%!Q?|EEs5(`?ZFuCk!bde4TA{WIU7sUrH&eMfTN;TK z4@V}crhA#&uOO}g`qcWb>e|N4Gr^-|&v4;Z{}dsAQ86dhi={YGt`kkP2!)W*CQH#0 zB*0|Gg>^+26l@7|Ii#U`)&Y$Y6uV72Q=yOWa27TvMvmr5w(YoCR!ydFLKA>Maxu#k3pTZ z{w^BWP0&7cDsh&$VeErH$y_29JS_Q~rXycJ`5TA%%vw5HI1_xBos|YV-#;rbsfBOx zoNUYFOS}BiPhA(`6PXBD`BJN4t@BwZg$XqqAh?d35&~eFuD^bC&~$> zenh~RnVmuOCIpbWPn%x0_8XJ+JinLYz#Xunk*cHgS~T?rtsBDc#N%lc86-ZWXJ{gj z`t~O3(4XmDa3Rnz+tN1$=_UGeSQ*6gKo{<{;>KOeC&EQ(y_hVeD+13UW*Ziqof& zZ)fWx*VB9DzSd_d?jrwlpQvu*qSWLb{+mzSo&J^!f`_zspg~cf#>0#2;z@=OQ za=2C?#lVMdiV@9-27x0#u`f&(pX6zrUc8(ufdHf5V3(^~ENsyy5VtDoqQtX|Z5W>f z(VyzK2e!mW2`Y@Cp0P5oke$!VT2Zc}b}}&HQjBnj&FM__$)-??%-;lKt9PpVOW))jf@!YN>JpIu7TKzfQ9pUaqsGQzku@lY^Wq^m@dSqJQQ>1XyK_l-!aJh-bu zHS*rFlu(^(PwTe~EB0_NDqp3hIeoP)0WOF0lj(Q;Ase=UQmWC3%t49bb(l``Ci(i=3R zRyh7hA)oa4;-O3qPo`)1LC+>rr}oRms5MY)D}s1J zTe@5GZ33jO6e(u_iwYp%WLBzrddA5d4;GS^lnjC6+I1-Ccjn((X&i!=fHY!C#CvSnagTce(=$>WxK~tc&L*I;v{#ohjb8&}%%GTOBu8G2 zINr*(oayuE{YL{;9!%nkm=7EBF>qctX%TC-85J~v>P3X1IU}9EUS|Xqc$QZ=lNW53 zG$dK^MJV%^7wg*aI01I@+_wH6dc58iz^b6g@-#(6JKD1TEvzz4 z+{BJT<^jN|I@`*?=#EM!S zH|0BzN&>8OPm76~O(j`7y#=`G<6E_YS??pZ#IlKqm(1m5WvW$oCk8zJ;lU>()N35i6A zyTs-_%>V#P%94AvCy(rXC92@r>AIU&@5K-DQ07`iZTXmXHD>oA&hOIVTk2 zSCx$O<(Gg$wBOG!Psd>zJJx|k)p5+~(@l=FmWO+_R}EWMKbzsJn`xCbuiqNw^qE7e zxrSPcqQ$&=oVn2NXth(uCOv0~tpw8_w2*f#O(wIewWhk?JYCNZ<`yvkzsqw)g8q$}%Xa)EYXgRN6@f|}7r8EpoWf5_kDK;> zx{)~-Tetz^Icd&uiGRAC0X&gx6i!_hbJAChPlEpZQ4C))^mR__J=Y%>r8lt0I@#;3 zE`A~hK#j=ig|A2f-Y&o10C@7yRPP`XD*GmE(q_&A_*+?R*P$6fk$th7+p>nf$qgHj1972nY|a?jL zMA=+=xMnv(BHthA^b3-_kj-$Ls?#9eDLxCQQ;o$RSV$nco|AcRA6hjl?TrT#W<`WP z=g>=5`n`&+pLhM1R^t+7lw`5@c->x$f_AEgaOa)@`K6=!#GP#4lsnXzx@g!trz50G zjEIgQ=smC*hbN>BHH{wjwCksToAZa3xG?g>mQUrJLYNK9DbVBaajI~n<%da^$M__l z*&<(lG!rjjKwS!7iduAsR~i-#t3ZmfRx{lGwq924Af{*=ycNYfs%3_0P!rLPx5Cnh zyi^{=MY#cv#=NYTBpz;rI~=#VGfSNe+$fS1J+UVXQ`?Ca&9SOV^RK0-o#Iu^Syda3^aH}0nSqE^-Fs09h5*P0v2FAd|!E{%qtyVv(mGM*#X;F$D!jmi|Kg9)nz0J811Gt!b2aX=4k-T*Jw03VG7K z>0g%ZLoC6yt=O4s*&rR?m9HC}S*`D<2^dG9cuY>6hE=FD3Ufq~Guvdj(4=MJxWwYU3lfS1-I!AI4ROnbL&5TDFp(#|37<3Cu1s57ezA{!^g zM$ZpsCy5ljx*9|fDxAs^)BaI1wa!cnM7J9l>}ox@<+uRpDM%AX8Q z$&%Ys&Le(jxoP0@%AF}M(+`0}Qf}!7sdp{oIiBCIo1CQ<(cXzXYOaze#tr6JeZet) z6b!!DN~SYzKA|3Z=#i(-oUoioH03N36zF^#>=|#`v-S5QKzU(rUwE8-cX|E)3>^9) z8Ge;t#u&!kFJN}DQdA|qJ6(%l(*9hg%dYmxKyGq2mBuOe%03M`VC)qdG#$yioW`=7 zmcrE;;UTs&UE!9@8vfwfWYGpOcr!-tzZXFWu*h!4OyEoh3nEEE8m%qC`ZkA^6=77@Y5MXMN5~bekptF|{9J!$ZQ9?-bo)CZ{GcR7uh^zyt#=_WtAO$J zV`QAIZ@xe<|BvodPW8!QWZs@Fs@uV}B5*60F1KkD{MzjI8E}+=kohQ}`hCX>v}|L; z6ZavF1S|HV^(ehhVP$^${-15uc0We3k#9k&4kSS7ABh3 zuZnBkaM~=bx1L>1$3BL}{frhvh^)ix3Fqd0&E^M$0rLehy>Q_bjl|`-%Q%o(&TgmO zK4o5LKwxN;xwIY7A)exYk+i<^tdA|T(N52U{*^w@2rET^2|_@q>nyBCsPjorwAXV_ z3$AX1@n)7!GsuOtO{$xM;M%HqXm>5kGZ&C+`$Negdc1{)Q`?GMc3GC{j$QFh9JOV2 z$Lde%6{~f4Bd7Ay0M3LTM?7p=^7VS#J7W7ceqh}0Y^jm<+Tyfh+34FVr^HA~-?4p~ z*&uHSf2FmPWW1}-0|qwOFY#o^4`gEvqCaG|4%O2eGfk`ZFJ zTbz=b?$wvr92P=pLppJXOASzo||H|7*|3eh%^@D$`YKERf_l7u7f$csIBdb zXbc|4rHL&r*dy6sy8R$Kk#*{Dqln&(Wjh@d!x7n)Pf}!pU6>X+Z%>4XF`QWevG+Ib zRex}!^8W`ic%mH9vpByD{^d*07B*-o1LF7KT_}9$QD1bU#3~byE-1nM3*9w|eicpY zWfC|cKv|F5eG3hz`e_DCVC8)*qLa%_?V0iv6v*XzT-sX8ccQSMMUjMEH2DgPGg{_U zT`90wPKyF74uE!Ah1J4W!AS&-flt&iUk#%1#p|^6wdbuqC-=h_vdba#AxM&H=CbWP z(n1_}_zfviBdQ1l?%jmd+ogpf_BUO4e6j@(GJFuC9ZG}e&L4?1dHh|YPt7T!N3LeXf z#RXcAHlBYe7OL5+8je}Z_*mspT^W)uh3}!|PkTnSn|ynEHR#ZfeZZy-bWwxmrdkEb zm`&(@510Sx66NP#H_t>{4*{Arz}TUp6Jn-<@g@1%R*4^Mp+QIB9d?nFid2yiNxoX&~t~>#)TiqM(P_)o#>zh0cMNju1s97(`;|Fn~xo zlOG5fQjO82z};F1(f26K+`3Wc49H>ps{IlQMv0ead0JcWOvSz}ED{6me%bVI{XlM3 zRLD%5(A!d^8=tbk<-!;QSFH+H_49x*z~&8P*6hG6C+a2ZMYQ!yN~IzDk9j|m-v$(n zR4zc_r!EpXxhX$T;KK+tIYxr@qVO}Ab2RCGV9b{I*+!^Qtwvxq{%=%?Xtv+Y0;|2Wxc)?Mm~;HhgnEWheGI7J7m0&476 zJ{L#U#NJ>kk*n+k_v3*HBw9+@{vB3A*eAI0+j&JtV`SJa3mOkhudD4g(D`B%x+Ik% z>?hMT%S-?%YRXKy-10vfFaNT3=vHRSbt!GyiPuV0zfliSm_S2mNmg)YdY#=`z`PH} zW<afJSC0aU$*nQ-C>4NGgG=_iS9`s4&v8h%53Ib@^5Gp#CzU=2yy<6KR zx5^wk_C!lBdYQC{j;Aeajp4>YuN6{`cTe*@lH#KKbM zAc2%ANv7Rvx;B*wXj&A}2G{tY=^NjdbEmIbC(DMpFOQ#gA!(pmpPF+{M~7ZXdKK#z zfLGws<3f>Ia7)Dg@M&7&n2`kuE8J@P5_P-jH5F*=>|@*q=;g~r%FPRWcoDQ{Lg!Vt}lyili{<+xky z+eQt-RqueK04A1Z&wO5eJ0qRv#a?GGKD%encaZSl4y;yzYYG$ybyJ~vm+>&oObbja zp)|U%GgK!j=M&KLS7x^MIp)(YF(xpQehdszd%jc%_AJRUkP5>RnKehzS`#U;Cy!JYUns^^;g zFORS1KIo!{7yuVx+j@$Z$XVq59oiY5TX2Z*Vyb2?yD8=EHCc4ELq+V`8lEN5e<}1d zTd{=x&&23QUtvVOBHovfhDY1~rtfUOSc-5QCl_FcCffV8hQL)WeU7^GZ)KHqi8QGlBiscFI*uYH4TEA_k@sI)RWYICGHWWh zFcCM=EjU3e8*?=u`uu}aF4MHCpE%APP}0NJZVKKI1{7Vo!fq7KJ5V-|`y)WcF)F~= zpLakz+a@-kgMz>3_#Oi5S+FdYOS>J&jL$QoB6S^ncU|?6EQ6}foDp*F9 zDrAxYQdY@B*rOr6nI+y@)lD-ZcnR#9L-M2Ey}f}?Z`feIeM6aZuW<+9tIwFI*7w_u zO^*)R^>*tnM7ZK}AxcieDh3HU^WVjM^_sy>Uopfa{!9#h{7rp5NOTMoN5y1gc#R z-pz>}a3={~?YVxknoL@eGtz^dgXvPBcmBk;U&uSkm#+i57~q3jZfWp6g>N2s{pn!< z8t@g67k~qhWWa4+kcF`Ha7>)fFbKGB(XX__b2)X)Lv!yLCTL(5urL2M52>G<;SF%w zX2D~n8OnKG58qse_gP~?JQ2&1G-uW23oYu+ZBmQw=yl73+BSK8nMXVB)WmAOXcM7p z?z<8tsFD{fA}JYW zd*&_ch;_M-C)tcjYj%2J4R!xlFy7}~i&n{IC$a8ZiEvWtC4iIQPxJwjBVQ&bcW6iK zU`*NP(&V!Tj8#Ae%e0T(^`ltLiiVNZ>|PbmOBOnmRuL%1k5T4QEa*uz1DE=>@|F#Su7hKAEmjD01X`5 z?#SA}bzCD0)JPU9c%qFtaDu}mp-@q!XHICmk=0Uhf)H2n9Gol1{=gZq zRF2ITa)=}I)c9;kk%ZOJGp*0y!Zb{v~r>&Mk&7k3KCpueHS#vCW3D z1wh@gbwXKw*VcamzT6E*7SIihq>Jq`t$g>qN*_HjZ8L(q3isX2R^K!;if&KD^`iKB zEri%NA~o<@MfpnLqA$T&JE&^$drQkd>a#I_zu$}|b_&m{BZw95**qV={!`ZD(cLTR zJr(pSG?G&dEQbp5Qu2{OCha>yM`HR^qB*ggCZ<9j+Z?heeRowjyxB(_hd zsqR#D9HO|yU*qhC>SyyKb-HFk;ORN7Bvy2wczWLJqc(3{T@&N=K&BQa=mg6rbVlfN zBQBvWye{nre|iCH&-eMK*||m}%Z}qDrXX;vn>wobsr*kj>?736#iK`h@Il9uCP{+x zwURjQFcQQazU&7=v|D`n%s`$Qf`$)#?+m~49e0B%vVXk{X743fsF$w`Ik`{nCL zUW&Z+V%yv!YYI_4vrAdpp2#^7; zo@C(|Eid&qbS#fiPcX^+aoA`W7(WVX6YYz4^FwyAyyRnv|JD(@nw+BDdX&EN@qif| z;4|PHN0>M=a&z_sy(b!LBG@=vAxx)T?N_>TixXNW{5%y1{^NZFv?P-8LK)lId7`L<+ z^+dd$21`r^0;@NeAO9n3rUifszgNI>FGF0NzX;628TCu?kp`N#t9%13_LqJ<<(spP zVZU~|T271gx#*SAPM-=!it7$~EyNmO%FT6?)}RFaF$Fb?W%!1g zvCvHkFG1b>iAIRE72DDw8JY?1mnUI{TK}|cCVDZLb31-~Be?grFxTO=_OTqueS~jS zM+=VvOZk|c`XEdqka0M#+54fO?!~bpS?)8?R8X&!yk+jb2HaVzNqONxhUm&|ga6Hz z+FM-%joX|Ied2xYm@&`aT%8>dsphChFcNh)VfBa^VY-Hd^_8^`?q1Ndsp7(IakWx7 zfPA59zKbOw$R0hd=EQ1?q#z$ z`nfUE>T@=K;5f;RCOnaG7G%sc%FBoKAweb{udWW<)=BsjyUOy+pa}k*0=Z!$y_z3u zIaF4*r$pP84ILCZHq~F6$J4LNx+{x5VE_i=MaM1geIz?942_mh6<*#tj)uKNouZIIeIRRRxJ(jEj*Q%YCYrZw*q;jwOH-|Tp00DAzr8SN z5EvtGBr@UP8v1Y!5ngFGiL{I+>Oq|kH41D?264D0GXS%~90FT6?8N{$($*u} zna`{C`X%i@)S4yQ6Mo8ZzTOvo>ckh(%-eSIBf{&0Pw^|ncb*ChuWCD|=@$Jhr+oqn z>x@i8_C1^ol$&N1BgY4^#KIC6Bu+&dysZi|B3PvY@Ta_I% zVk!j2?pDEVJ(D4!i!@ucn7cQCmS4%9Mo`J3rOX2Jq~Va<_QVAsb1d(^c+KN7c+T*% zXiHj=0>CKbz9K!#QXcpJr5W{rCO**g7zL^7Ch;_6JJs zoF?a7oAxrR6+zN8Vye$t)OfSNGeQx4z00KjU@+%bQR(|<4~+Ua^91AtCrO0b8S<7n z;>{XbE-Gbh@to^dq?(nwq6W^2UUHp+@t=t6(7o-MjbGoHUB-ZACRx5K&F7+r58zQ%8^K_*S5sjAX>o2<_(i?040^lo(ki40cPY$t=%om^B4sV21MQ(0 zQ>WqA5h5hmTL3FS)W7&P)Vvp2Rz<8*4mNYO(88w_eLh$p@tnm|rMOrF1?fk5a`MM2 z=6dVfWZvOMS&SYz14+x#*8pnEKDtK^T}3k$IiM8*X(L9x>%l^$ilanDy5E2Y>dxat zAIQ3Cb;eS(cQ_;-{OkW=z#K$*Dnf7P@Qob~lDokN_F-lA5Jld9;>W)@dRp-=kM=>H zt(Lvaf)9+<5=^H{hQEKlg8uVQ!ex7blfkwwf4j&^ZPI)1W6(7CwP#ffst)GiAb);U z^@8B_$bOvabaY(=A%fT=IK-vOEV%rkeKDY=kzjdQM~iNeT+N;Rzx~{dzu;Nm@5+&w zm-V-v3|;Xi=}eRlY`=TVWnRAx8lwCD*v8;l2fYB3f~c%cTEhSAg;V`NtXzv*zo?}+ zAhH0MG)F@?v)@|}*ycERb*O^1y3?`uO8XPWO;Ilkji-6JLg8-O#1%`*yA&NS)a*Ga=|2`T%)einyjfM>6?L&n_gL;FLnKJFEgFbYz z@ka?)SMcP(x=Vg11e9N)Y;gDk%w(3tc>H)1(YLSPEvwnyxkC4o?t5G!H1cn{PN@9_ zjkHnV;ZLR9ENSV|{MX`sI|B7KA|Tv@#hUr5EL^I)=Mtp%KCc~v)@X-RUo|bC)5l`F z3)W27@3?8Dx}}fXiq6g+y&o6*Kk1V!&M$Z07HxdO$1OkfHi?(-PsW09uATzCv!=Kv zjg8Mwsei4vahBdXR{_S=vM+RE4tRLN^P?L%^*v-?5i|c%cIFFSl3&lIR%T2Vn4$`< z=O;YoyAf|{fd$Je$03@D3j1sVZH02&^*PGxxXTBo86d=Q$&XsZsxzUeIUY?shzece zATh}mRsX0Jz(Q1UdT48>u6wW)s(KN(#!vCLqrYU^rO~qQ>WLS3t*9HG3RGfukln;r zd=aul-&y_tL0@nC;OFt48FXz1!iD-Y4r#~P4}`3T^(EcWD^v|~m%Vn(_mT)$9K84m zjh{8`J)OaUfR^lnu;-RFUyi)Ujs%^g2B0HrWVV4z&8x`2rZ*ts9uttRa9rz95WaG1iq!!0s+JNn@9CBg6Y_%fG})?4Fp;OiLo zTaGR`?se#xs2oa&B7Bu3_+M-hwpC32*UV@EGxSUTc#|UTju?DgR0Dy@Vmd!iOq= zXEikBaG#1gLDA*R&3P)`994`zry>5s#e1vv3ZVQ=>NO&{b7{$bejjCJg;egYIaGFa zY^D$mpFHD`hJwB=V)xW-cCpY%o?Zl?mPlPjoEWq@w_F;?;J`AjZ;=8{1Zs|s;U z0S@NZC^QTQ($X^j83A}P_`3Y*TTW(u** z>Kxlj z?|b4V&~K2&y+E5FW1t37E;*iX!8(5}Jf8SJ1^3dG$2PV&&7o7n_1u25KBW8UwUjl4 z@7aX#KjGpM7AESDV*yg>GJ;yJvTmpUM*J-7>_MrEWs^3u!VP;z(A~wn@HfulYH6Z-|`sX^P za1t#{cjR;z;o>Fo(xNFH+Z9?*)O>V74e4W5LF(TXi(-|v@qF}KtY$(u%_-lkH_stf z5i-kz)we!H{Ufe9e(8x-#MEn?6@7T`;4!bsBwga(8#iToVd!^yz1(txpF!Ojzb*t5 zTc-y{AH@c2a_c+WJ)Atv)+@q>I1AQBoCNZXpGEMONILl_=*&2Xp#<=VFa*Cd*ymx{ zTI$Yjp`5lZkq6^@g4 zHyd(9eln!_$v?xD3L2s2E{Z=V*aGqNeg^4TRP~VKWWQsm0*cRIF0%EEFaiQ>?r|~k zj?@R5+M5bGAcRkesfA#Z*>+t0-~GUufuY>Q0A8+hyqTn~3&D9So2e{V^0vvi*{Z&Zhz6q~mY~WS5T32vdsk8c{ z&iMMxan+uKF%&Jx0hWO8j1D})bRtbOOc4&}j-D?bP(CU#Cq^04?lG!GOhr;oAI9%! zWZVg8oy>siva61>nqQiHUYd3NE80o9f1@H%gXSt3U6<*2~lp6i#SWu01*{)Oc&z$Fgx9K|zr$kH#okB;EU@@P^x@CS;ZZ0vh+x``;xBtHUp2#;U8ePMh6uLGlY-MGfEF48!dXgdG6A;z)~6FN_!VC) zZ{bW|a#B7+{1Zm$+$IP5vUk^K;kJ;@X5Zw(8hG`nv5Q=21hvVv?XEY;8Ck!eMCtsQ zP=F4k1RwhtDsaSyr#Je(;ocaCPj@--uN|cKu*?Q2wlm1djp?9(I9m9 zT|sp>ipoQqBlc@gbL9q`BY8RWnqX8R-=%`D_;mv){+1%ly24XTf!vun@maiaFKXm__tol6A{~Ez zfH6mP7j<^*E1z6YkB$;pH43)6g^I`7o+3Glh`ECIuEjywuR3{G)J{BM7n0eY2mV5* zIMomyHZJW7R$A2cB7HgwPv)k`F_y8#w-}A=K1M;C_Mkl@d`KNe3LWbVfARlba%DmC z$?eE+X)5=)1N(n&a?8A*@h70-1xl;c6Fo5r4~D+9TDLn!IE`*HD0KnXM_FUBP$N<2tw*G>NI`MEXccj?NxD@|oMl6t$&Ml~G` zU}SFyPb_L6r;XRlP2pe2s5Ff3pu2kYvJ$04m(p^tb2-Ov60xtTJ%%w~u%h@ExW^H4 zi=;iJFu3sG)+Et4Olp@a(U>5S17jdHi2C-aZ1&bjTIZFG@HPlgpkSCmP0s`!pDo(8 zeX_k+QO@NA@-9=NY76W#MN{`|X;OyRrH4@8MwWH#xFOJotXu%s*$8robEQn#pDbSD zq0q|sB;(Iqq1waogqo?!spSS|P&&rgn-zQ<@6RAm=k^f28Z=2|XnX^C-Mp}G&KsdX zu{*|qzCD8E3gsvRM?xb5V2oX*;x4!bC)x=>^LKpisNTThy!E{|uv?l}6 zw({TAThDM4k-LDtf~}ZCrZo%Q^!0DW?xa@yY(t~bR_nI3fz(+5TF>^1Seyp+qMyVq zc7AR%;I`;8Wb?-;0t0+V4(ARY>jd}qJ7jI<_A_8*WJcX&eohlS>z>Pmwbll&B9f#* zm;Rb3RH7R{gj(5{LCLlVBa zI+ei1KP^9V*Dm790(!Wl{;(?;C56vwzTj`%%^SWhuZW1Ia9V99vKMG$l5(ETD~@fi zH$UUdtg7E=vvobsZ*0u#FwR7>T+I^hYa{7EGt*#$HE8NDsl|*rE*ZQl|3DX+Wq5Q_ z3wAHsKkVo%<+VKequCYJvZl8qAviJU&KAdEwGr!83N$kKO6}%c5OU(QqcD$iX*tK< zM}>|Q6C8GBK3uWC{B8yeQ7UvK6C}}}zI)a732(E8y%_vKLEdn_D}Ux;-3_H)kKH6* zp!BPP<9-9!6YCVzV~sD6z4iL2X>oRk0gvG0uLt}lkEv-t9t}|8h7_8Ag_r?0HXKI~ zjHK1+O8|Zf$E9A&>=82HjyHahfZ74*x!|hRi2G-iiRI}f7rG!C>8Q8V#>GaRh=YRx zobmO?`qpi`FeK1=S&+UwV2-==BmEw8BHJ5nh*O`iFysMxrKGZo6Ibz&(iFdC!wCsx zRkmpOwZFm=F#Eg!55|vCYIdjf;7n&z%@m$iZUP_B(o$}ssa4kmhiQ|x{$h>UyLFy4{arm>NN?)V) zgIj06D=e7RK2^zu=g;U9dB1|kvLC2*#1zH2e~$Ucu1Ea2YspGBAU&$soX5?v-m^>c zeaiCYsA*3kR&6-{mCcRi8GvAb`K~vJ1#0812Un~^ZVGG#q{Q(_v1Ds9K3C?|j3}52 zE|rR2HD3wWlSPR}uYp~wasHp|DVGEsZ_e$~aG-tyF6`1WXNl7$`uDhv zRSj@Lf4lR%irQa@eRcC@mz(s33$R@a5FHaaa1r~r*c zAtHKq>BgLyDGh{lE_jf${C-L-SL@HsIOydmq2NLg8#q$F`e_vCy}CTDS- zpXA1F;Kl38jE*{}+9w6&rmhL%vJ5H2?HXRthsuR$fNNYXj%~Ci?J)z+$b(H<9A*mXU1F z?BJL=BRPe24bAK`;~{AdJbOFyd1r9`VSL%`Z`{D4cIK7bhH7Iq4O!?zaM&B|(_Z>; znA5g=NI^5iS^C`0ld5ueb?dg9=5$()@K)-?D?W2L-eyIDEx!`iNQg@SrHArPl#Sxx$fi4|wA=UWoq75%3i7-SO^^s}A|x z$4vc|7xYR7Uj|{>eR}9VS6^u}~X**wV`avkK=0 zVelFbwv^4uFYB(LAVvXdu_e!F2G^WcE$fa&ssO)UIuV~P55dy=$-0xa=B#vTlYxoJ zC|zMTQ;O^WaCYkNbX>3|eg>F}F&6@NQDpCn=w+Y(!ta^$0t=@jt^)ANu_vG}{TFwL zov{v*r%?GC;*j33Yb^;8fO~!Fi72NO2qx7FqxKs{hp+OPy+7a1-n0g71eOpU zn4>-9A*F*=m{E+C#Zg(T zsT`508>NX8e!;Ds^1>ov!I1ezq|?rRhKs!2raNBfoSuedPko2muy$w7TRua~Gq z4<)0@O=t7LNC)C4fcXb8YM32sV(%cHkTB~E`(qiN99_3sv^*4(DQyiw2wIOSckLQv z@Y{azUb_ISEC&$GgI#C4<7`0Z^DNrW4fo8hym;Mx24=4iP3i#E@4S%zPZcNJQ-FJW zzuwF@-d=j^LDJ+N&1Js$yTGk)&GvtTDW%XTNR{Ly-S z{*vGg%LEQ?(#H+V{($x8G!rDbtyYbj5UjI%=~jo~gs(3J9-yjxTCA{Uk7)4u#1ofZ zzdO!6cEu~9G7|5vtFIa>63v-JoB_X(Adl7&gQghkYyIL{jS~A0=B=f(w#dB9;0AIK z0r=!K__kLXB*;#({W}5 z+jQ30SA-8B^>!RpYK`esqD4tbQf7AaatY*Hhx)8N&2GAf%=OoCr1TVG0KE9?hZcF{ z%-{C|0+dTTKN*NybQe>%73rk{D%qDj(f`P2<@!}C4kF7 z>dwC5S@dZh+G1gKx^>SE<21Ny6e~19E~&h@Q*K{Hry4J?xKNdg?bXr0f3_Aflv`n* z)CxFVqleo6MMKr!nt{u@YjzdiZ4+FUM#cUr-2HtibOLFBs8^spqo37dwH_oqN&Iaq zP(#Ux=7giC`PFGNy>$D%sC0I#Z)(Qy2?v0omzF&p&Jyod+qGzEkK&5H?9I8-!iWq# zG&l!qQ_P5&h%fEQPp8(=Qa59s{p_Wj)-yx+EOzycjCDAQg#oIt<5}|-35>zjc&%yU z+M)<_u|zKPS(WQE54!?W4t0@Oc6y6-dyH%AL6td`G~K5d^8$P?5p0o3R3}%zL`Bbv zM2Q18f$lf@V1D&R{47|<)*06NL}KuYpRa5?-16TdO*@t(-_u{9eW9y2SEt>5P_JBA zXxdUcpP_;?@k!`gMK~}ogQXu@!2dm|WTTOFU%YEL;+A&GJYlc7ntZ<}IkgJW-uge0 znf9W;;J7EG9)kV7jlD2+_0-t!1~~ZdiC(6d&=$57Mo%PEuIjBv+!8(g(aZ z*B8Pq+Nb|Jrrj=-@*`W{Zu>hms@5G*!y9?}?v>18>Oc@Xgqkx=O$umv0ma?rMyF@}xx;4i`%c zL{X{zx)EOnj3GLBBuKUO;8K7uNKklC81H@HtibjE>^$BOX)id#t@GHqTW4nIqXcDj zD$>fE)#NA#>}sYXK^eSp5@17#%$Ti4QQ0hu3$y3|Sh3VVkrEhqRPtZc#vtcd%!f_; zHM#|uNs63B6WI%n6uH*AH)XLJ{E5|CLR4=;UVF{&#*h?^LPg8%SH>;NU_~BXy#98H z&jPBe=jl;*$17=AiODhxV=;oV9bSh#!f5b^w0W-(X)kb%dpA_9G#z{TlNC3OGy$ia zSgNo%Wvy(nwSI|7!HyH5G@wU9QZRyd2{XQe$`6qQ{~ZZTirVCE^e(JGA9DTDs%28s zPNbeXdVJe9yVkEoE;^aidM=M4BG9C1LUH;lzNQ_!=DwYmO72reSYQbI6;9O}O&5TK zGN2Q{|B}l&01K#x*~ry|W0hB!zT`CQ*B>mIV<7ilC-`quKhEikOt|55Dr`(<9A}3f zRexU~==Ly>w<6DRreuMcND9ywVl{Y#HJ+w$2nY%xFgphw=n&tA1jSD_VdaTUbK3H$ z@fYS{Er4T<;|_F*50_2gzPsn-!N~{d(hy zViU5*@$Fmb@N#oMKE!*OJh zuzNf=Rg@`YL43s^jC40Rmj1=&gZaQRE9%QXI%WXCff?F(^)tcxgH9YH%i|_#(uaR8 zBhP7f2u(Xa6vmrk1qLodf?UbW2daQ(p>(?lzT;cHY{dU9J^k zg!2$G+!K1>B^GX$)Ma0w(^=c&(AW+;zYUH$md4$K;khJB@F7(~rJ)`pyJ`&N3Zv*X zy*Iy1N+cAZ@Hk})6)m81*SW93#13LuTC&YU;wjX12=3p_F^pl79CGu>1st@|Y!3Jk z9XAoRMyR2!3$3j>Xm4P$cceEU&FBP}7)X~Tw<7CY1@3syyk`px;$#umN4+JkSdN~J5ABjN)hQ3lTdbz2{^ZVIFT{%CgxNI8S^`5j_t@GE z^%Eh#C?wKoWz|G}QA&B8i=)~=#=C2I%MmkGsv=dfy&(FC1I41?D*a3=_AeCa#Ewwj zd1H*(zXzG*w~%6*ex8hZu{+elO72#SCvQVp1|!*eO?W&kJ4D2DeVqJl$`LBKA*JlU z`OCSh zozda|-^})g(uK+nkPOwi+KF2}>+rmRMP=afSZGG3G~ar3Y9tvPlGOQf+FiDp`&`Tr zL<@<$aCIxO*vSa7mBu3_t}fH+51YfrxNaU_8ya(q7wq|W#eHE6YVE^M$&G80NHh(% z)pv#xpI1PzI~Aqysw~bGGJHIy#SIg$AH$(Z*lEgOLQhh?S#cseL)lv!86bRwpv{XG zUlnDKJ5iLBsb?GQG z0^xzumJR^4ST$(h6thvFX8!51uyVuO}vEH6ef5;^Zp-G(`2ohZIZ z=}w0p+MV@L8b206>LAK?{D~lLj=FSJw5?yy)aaZQnCWV2r8ux}@~<978@-tAu|ky* zw5mJi9~bxe?$$7t(08%!U}adgGhEtl_ncloFwSpvH&KHm7*iqvkl6adROiI?&-6%> zH?H3udDiF>W=>za*epHOX0r(ER0`}jb{5`XZAoBaLMb2ZeVXN_iZvauSE%GvS});; z99sUww%uO(EIH2Z9L7mp(K##t)I-p`LKS8`yvjWu?)3+JH8C}gPOFH5tWG=T&Odc} zg%Uy2IWd|($^D4j>;CG2S%S3u%s!tp(E%&U6gYo)hNIFIOBZ8N{0+7bPv0clG#+&X?O%1^F>Wvz&0c4QADrbkM%g!5`M<2a00=vr}o)k+1`lmorC z)Q4Rd09Y0d_N0LNSgTuM-zVu3Sv3fX){G{3Zqe;`RypIt_%s`t5uS*XJpeI*h; zPMi(-{YA)R)v)oQH}?99m_pMyVLb^jGSf|Ao#5qL;gM)S#a$)t6t{RO=j$Z-&MMbx)!aw zJZ`PyAfS3kgr8OC!ID+>tf&QSgr^jYTX}laA z%*2B{tgUFP^w4qbsn*Cnh~tsO+q%~y=7r9BUeCr0?)ImZPNF%yaC&F-(!ni$)0=)4 zUY(5kUX@O!X-7_6p*InInI)ouhHf$_&3lHCnMVjt{H6qTzq&j?I8(b!HEtK{0SP~q+ zm&XS6H-bCM2E z;@Rt!8_TqQCQj?>yVV6~qNyi*NB)-1&wyvSvCdG(P|X_XY3ZCa_J}zBy}9|-+lbv& zVGL#2rkHjLyA4brLv4stc7VQX(O1~Xy``KpGYx?L&YX>-n(3%qw|zE|S=0|!G9Wgv zMgqQ>+rQ#REsBL2kN|T6!FWKz&XX$}uG+(%IPRz>;ektwT(cgiw}VAsTy1ygs9(?` z7Gsnzad_$AqP)Ztzpjb>>pes5k^iuq{+Q$;5Iow`V$;Y&MEIiIo(Oi)v?z37BCD|Z zbONRd0Cn_Wel!=Fb2kl(gSLsI9pxSWzx=M|f~To4ZaDqWOeBd0yzKx5j#wsjS@M~R zyI=4Gb&6ngqY^wmN8+rlh=EF6EtL>8l087Tf9QXLzdZAm@%q;mm~1h&`alXLsZ9T! zW~$@3dS&b8;3?dT`MA^WM7#i9cDp6!eX)gYB|E2_rUI1$YXM7VdvAE7B-SzP*FG=F zG`$y{8yr#Tt}&Y!?4^eU%`7#Nq9PskLYYGyU+*SmM|xSSnb=5|x@?U^FuIQ|Z8TDz z6yAVUN6mx%ITz1=j^x^6#TI-pI26hHOTD1c$D$X0xCXW#CCm&7JqdmGeZXz8Yy=Ejst3SZ!+Oy~`xU7==5@;s4knF> z41m3Fvw&O_V}4;y?i@IBLZ^-y8CdH!DUkj1wn?;K28m%5!A`)|G}^2L4jCgPB`9%^ zcNo&f>6V%+wquU7# zFV}MJpnwHYA)y8m!;>d*L0fAOv$Fsnwb3i^1Ur}LqwutLIXFt?AB2Kx9mVdp0PfKi zow9Uy>Nsaay2IEJ=>Pe%4F7$9rf>P9v1d#Z(}P# z|DrGOWw~CppKYq4*X~hv01&Qp2RgFNW#1-e;^ZdC)_yau`Q`|6SAOF{eMr=0TJe?p zwZ;Tp#a)Dom>vyu|5J$>B<{=#k|_?zWOa4Ry5*%ux^@k23Zo-;Rk<<6Cz=`~ z0Tlm)uh3&Q$}6i^Ox!eV&(b+b3u3Rc4Ay0p`rr9J5(9HK#a-&_}uK_Me z3T08^Nrg+=|HYGYZ;$ZO$<9QXU#Q$ycS72hhWg;%#oO8!~p6LeXj^cT*!rr6> z|3x*YAdwQ<7AQtt=S~9k7$fHw*22i6lyUHV&!5(|rSjx-Z}mR7$+Piy7Jf}M&;EZo6Z4ULLAgPe zf3J1n*qT66`4;=}I4C~hblJBLE3JmghMb;|GLB6N{Kgf~+1!Vb)A6uA$QEW4<30IH zeD~yxTz7D7w5^J)CW(oXD8$#I0f#SwTe*hhU3PQO#Js$w50L;p=-%VcFJuU!U@ggv z1v3}R#ZTU=1f$(aFksOOtU`P?oCLIP=|wg41~Sfuy2AbbU?*A`B{WXD2T@)- z&(tUnckePBP1qC-Ud2!&+CS%oD@x|EPo9zr31rEEv3R~lv{MLE2cY=htNT3R zax5hknz>5t@#S8&8RhGHY^kp_#WxepPjtYhFldMOq|FyX5vyrvv(-Szo(D#)$n^bv z%7YeIv%h~gbPi96x>mZ|@wkp*H7liC43{$Yn^gYH%374r%N?jy*U5!)n;i6=hFEio z&+j;XG6j?ho^2E z_ldEzUsSVK=k;DfYMzeC%l&2g-EU`WqM#>Yn*+$WK!2dWW;Lg^P?%HD4<}rjQPTdW zz$%?AWp3A)AcgF5cLk8usYJvTlH!hCRA5%mKw;80E!CD7m`GU?EGY`o)${>-8l|66LD=XGCwV1D#RikQTOE8^kMF4w zzR+n;6VWfFPD8u-e76kE<8RwKopvNRh&Wj}-M+&82NvV5xB3-ne+nyZOUp)`mFzX@ z$j$d8VkAz22l`KWIzuu6XGV`V*t`9A^GWXSR9(~Kltg%2(a@=dC4_fL;XK?(jr(uU zVXFK=lZpvMtGjoFGjH>F&~RB|J@uHU0}qgh0JXZrtW1=YB07b#;Irzb@xtQnGs9bp z&QN!FkgKXbFV6Uae~!uhq$qr!A9$CKs?dS+w~ZZZ2PF#;PCvZwUuM_Q8zMl9*}>{g zX4z!BuS%7x%GbYkw<3 zVe`Fy~u5pW6dn$g|3i1%0zFY2(7XF%l=bFnaGYpOB?8*MmR^yOJ zuc-{q)B)7K6~adRL0XOevW>6M`+bwKEtK%of-i)|%d=(C5h^DQU7mk)48rIyxWsu< zR#I!aSkFyu4Nw5$Jn7(04xa_*W4=4+vsuqD`$xjey=6@_a{YfhPF~sm(48>`-QIu3 zPRPZPKPk<4HIius$f-qdP58Jk<`GhW=&+i%l2)ZdUO6Htk;j5y`8+w?dWFD%<(^37 z9hjrg^W2QR5GyQoy%@MG!GAvdv6#HJe zL+4hgXQM0U33X%5ISIHhmuN(3IuA~7mj9~$I_h&ULN+&u}Tx6fl?j9sH&In;lK}Fx0ajb!&}^F9IAC z2~7`7@e~VAb%F7dadBkcAmIXujGv-CAWlTuLfAZj>Oj>wsg|tR?7+N?JA)##-QPfn zJ4Be$`P(_qntPU|D_5qdnI!t9Ync@yg9SW$_>Xk?f`OqXs0XT6hUf;iOdB_w?3aJg(;nLNta{ABstuwP&T zTweeQYrg+3l{H_FW_Ytrf!ZcJTb@5Iz>mh2kjkq7`NMFjfeh4%!t91hl|HD%^6Js9 z2ZsTQhPilW)2`mk^#AJ}@gZW$1Zyy*qL@l#0zKLXF5xX2SMiZ^G4-okmCCDuPRX`- zCQM<~_IIpDdnaZ*`T{8L(t%U)iGJx94%?dOvNqUaGd>iu%*7XGbMF{j5J^ctfz7uc zk?`zStG8abx~yZ^US!x97VfD#^Fe1rvk~K z8!;@+IgR7cwUEY0Yo1q{0|$4i&Obf>{55f85IsGujN?ci%^K%Z-)cL^cTuMH(VKb! z9=uJn-HHNr5)N3iM4!?0_4_s_PZfTHljq~5CoUMlqGAUEc$HLLL~aAVh`R3zv(hh5 zWSx+TuzjJ^KuObD{^CLu5r+*Y?B4*%Pl{osAj|z`wMzA_ypSzYq^af_I7w*n5=ud)Sb^QG* zsz1w~A@p#Rv6seQY|v|QFB()89Y`2l8vTq$N@0w2d&?rOrS+*nDSa}evaXa1+OmRL znl3Q+WZMze2HAV7y?sJ9tV>$NwEZ(~&iAlmi*P5!<_AWq(U`j4dspTvOUAK& zlVkxD6)5TT@IIN2hX-B1BxUT}Mhi!KredG&HjUyxYpvIVfzwX<*x#Pmu0o%xzL*-= z{r`K+v-liBT{;;CozKn@M~^y_@~nS%xNqs57ygK6UC7DA_t=2a37g;hIXn2+ z$J?NnGIDCw*>>Mm&=sCBs-Vsb6c_7Pbx3R@2qy(QW#oej+0P<043oL%vr06rv!eeWl5%rLxUj+D4(f&J2E5z6DJZv)QHdwt30>w<`UipK1MU zU-3%|s0NtCsJ8bKpGm_`0!RT z*_t~c<-c2;Sul#E><($o9>fkV<(3M%wBWfUESe?z^thNhp}c9jWQguED<{Sil7R~1 z_2Nb1FzLU7ldIJ#xd@mPYWGOU{LzYy{`9}@Z2zhs>c6%R-K$hkI>!&w!9G%YoCnoC zmi3OGdV}gJHiUDQph9MwVI`85vM2kbs!Ez^F}(7KgTu8>{85G{Iq|gE6t?^kNWCL= zy`m}YO|7d($sD2&+-j}TfkMy2+m)WN|EY~?U2`^sRe)`_$8!x<9|-6_{~ri)s{W~n zrG457!R`CIMXSN|I<3?nC0~emxV{PadC)PhYBO#xn0rLKHoBG54AsWDDYjM4>MhH}xlP>|&zT#4 zibI@q*p-C^4$vF7+9VL{0!nZ^ToP%pA1zgXTn1PZ3sGMjuKmDs!&Ye5xg`7oQImoM zWeJ31?INT1r{3o)zBbzDsH|krzqnVcO#@Wd6?5V^Y|~?%g|cc*6IKLbWS-j@0u44F z!N3>&&;+yw%#S^U^qx(3s*Kj@72HkEWJ6{SlbWr0p4j&w7ypmj0Q@C(SoeqcoF%>_ zL6tcUvFnFAE-92wVjSBjKYg66zz2HkvB_f%55W|JaG;_KLa!rb)J6Iw!*+Hc@K)+g zvzM=K?qK-0yaecpV$j7aKDXOR1X5Cd>AQkM9KZ@)M39)93Jyp{*aIx*rTsZz#HU^w zvQhY_4OG+7K9El^Iau@y1F7Gr6`=X!tNm}SOw-|)xg@dchz;ER7pyiu|%bnaN1lwK>jGC>2DcAJAixvu*xj4G*gcwe2$d>Tq@O-z2Eu)X{HJXSJf%=04hE|c<(P1$UF{M<rwfNmcYSv0ix(fpnvp>Vt2{ceyUe^7@NmYKG0PwT>H#80 zJxlVXtjafKtN{J@&;W9&q3#ag#r|^pKZAjpdr{t#dqg(>9KT)aHVk;KA9KTtFV#WMACAh=51%O26>82HN1h9W4_Pb1C?| zjo?Q4qlmT+JuH21YDWR;5!`q+g=s~G=e&rZX24EFzQBDkGN`wPsZkE^Ulg&TzzqH? zKiNy!s4)Lz)_GW6U*s34oDGgPctiRJyu+?7WOV0}h#_lbK_S9M&j~6*xK1n#>tALf zS5x(1`9mY@h1n-I`#YY(^L?)(Co%9B;3mp{zipxJ-Yd{>T~7D3rtX#JMVCkE?bSui z2B*^km(*nQaYj|wmw0_WHm22nWwSPVP?&^U3%UCvf30v3>|OgY_xUe?BLNqmjyE5P zz!mAfF#(e}%SaQfO_K;rFeM0UI{gu>@DKn7o>z8Z9w|O1Qr8*1ErDdX?VE2`UAaG) zzy}J|zG%Htd;1Y(JI`Fb?rs`v{_yi6c=LuTg2h0p;ahYIvIYeO{Xj|cbvPPH!+cHq_?CYK5pB>VHeewm)!=yHzc+`PkTgY7HypTL1 z_SFT$%Eo$DIL}MBsbE}g8h#d~p8a~hOIgP34rUfI#seONAwva^PRL$ZUo zt?+DGo}6}BiOzjxtsNvO^4WBwcGnv#!bEP}nhE7l9JtN3RY-aB z|LO~x(o?=2_)<%hEJaaBE6PMW>}$Ho=9pEdY6ybb>Ux;6V)*2qbc78n;GRq6gPz4# z_TW$Z4{M|Eb3#$`AiF3dJO2^VH=(P zq#UE}dhuLXq=Q;-^;MY_lfR=7>r9uSn_lGrP7D5`ie2bfTO?os=0E`dpP~-k$HQho z7TnK*T7SeC;=mHurWLNuf0%naxAzBp;AP2#_1DHDnMQlIl}A)y`gF7=N1&f+vH$U^lCL<76G)6GJ^ zT{ro6!pSL@DmEI%7TO-mQC1F7g#qmkw_H@DtQQhj`+z#9qlN#0X8N%!f*@hG6yQ~g zk$Dcwbo!!}NVHR49zk?BzH%Jt6Vk=r$|Pw}xk%K1nFsCSG{c@&Z_=j@AiL{@UV<4w zo*^-}^5a4$a?>7=pLa zGubK?uSej}_{V7r4Dj7MMPWL|J@xDS{hyGEH12^}!o+p1# zp$obkZ%Pw8ZIUxGeN)C{!Q+m-4(Uyk=%odB`3*FfHT z)>t`}ZDyg6A53HS7GSBaMAToF+hvrZa;6YdkF?4vr?De5S`1iLiz4dx$nO>sl)*td zz`6BS+baCbRl2c;ZSTx__ssZ&672q}2Xk-<%ygl!1-?<-9Y!inaGL-;`$?WBiqI0T zY|twpwAyOQIHiv;Tk^GBn3*x4!5XrVgq5)w8X0R`9eBSo-W>kvqG}iGw7qk~yJ`dU z`k=L9Ew|79vn^=%oN*KPz0nZ};d!@QSX-5Y{a#BbE8CI{a>CwnK(DFYP z4coV*C5Ex6MXH37xzEXbpN(&W@he}xKBiW2LEnj`OgpuLWh3?bWvM5B=AfAQYc}Qb zZ>S;|zSqu!92WD-m$MD(Alw*_Pc#(Xm#gioJ9?l9^?4&&&*7+Gn#_4Sjvj?*Wc}f*)y5B-UUHT zyK`;`SP+MNAsbK%Z>%sJh{Y+}g%NXLk!e%Sef^G&b5~xVN$L56(cVQ6xkQA&NE_a= zWL43jMm^42@BoJpQavw?*d3g|u!qx``V_I`t-r=ry!%lTD3q?~FonLz6sb1YfSd}cXDr=0)hfub3 zhki#T%dfeq7(Nzi;xX}Fo?rD>E;mtAGt&YGY5FWz!A&zgvB>50xc`DtsFsaPNq`r+ zAaPdH=Dl^}KdMA_TzyO)lstm^#q|T;pwpc~xHnns7X~dP<{r-I-KLFpu~|(jYL@y1 zsx7tvLw|g62e6;|pZG2DNQK1KrgFOyZ~2DvxN^?$@1Ci*0t}t%tv4PtX%XvVbqI6yn;C%adDU!>!*iG@Fw@fw4vtxqsQb}V=u%pef^11S| zrO{$`(BBsG~kC093rAQw0!Ox+XKlsZU6#&UudEp+1=?XXx{uBOf zl7~`>fjhUY!y3|aIIlvjoz#%<(u}>zgsZ30(ixT&9INhmVT(oA{Vqw)EC2!j91zJI zCU_yKnLbEdm!Cnovr>2r281>#Z!Lp-uzLzcF*3OG-vOu->TCI4c^zbS|0dCX+Ndmzla`Wtl&tr+_fi;8Mt^Cqgx)omX5%e53q3 zn^Z$?lhLbBCJ-Di+5LSZ!XnN%8ZJ;l2Akei=_Ii+)CN8i#|P+9IGH8s+E%<7j=&ek zSh+xAS!AIEnpGQ|aI3IcQaw_S99Ywzih#zqC3?*i49+KfYfs53Z+iQf=5Ywmp@zB3 zI`%AA%i1%B{x|5-Y*kM`86sYNJ(wv6$F5*L{FSl)@6~qQBWjYXQ*pJ)?u1f3t!v3` z``wstcGunFZZ2uqF?AdE)Cyl+NM5diq}1vB)7-QOf=>whCuXH^ymJIecyRq0JYkrE z14hDt>K&g8V|~3FwnH&ckxIiVJ1*Jj@(A1Fr!S5M*BGDx00vIcau&eR=yTjcu@bKy#LUwz-UJ&Z zdxj{!3fJK%n^O>@2tso6N|XM06(7BN!b(@PY|D#0$PHWq#nP7W$DCM|XtEZr;r-Qy zB|#&*iy-a>-qUTXfR1oMJ10_Y?I9j~RFAF*0+R$P+JO z0LYT8x8|Rg(nYRvnoVmQH^zk^q!)dN)dUeg&aQnR-og% z4NTLz1sQJUWNp=-?W5_c)fu~w4hIkV+QmZY)I0huKRU}@8>}T&-UV;K2(J=WsD^Vm zwAq>j{cg9J>P#$HJ|TyBW2(mz02AxKhkpQQ)RubdLg$;5_{Zpdu3h-6fVAd8;1DKF zj%hE%oYD`3OKzuu^5fZ)swcWUq5-1!-k_(5$suSC* z=(1P!SjlqtvP9ZsS2D$(SyM(UCDkQy+Rh(gcS-zMpF3vi4q1{Xj7m)A15gzQDTzLo(U9@^- zNwd_BZXZx6sk)2jIcU5`#UtP+&qWj~>7(6@!wyv^TJ<(Z=QS|*c&Q6YF%~NwmbHni zve847X@JMB)urHSurx!G%al|{?&JUf0{{S*;efFcmm?ZlKiVF~d7-(iLZw&6<5&t} zm;QQ5c;Mk=KA9|u=yx5cL~ax|V>0jUncHJ&*@I9W`FV%O=Ic{#8 z0E71=-Fy*Wim*?7b&}tsB1Y%rN-DO;VK_f)^$Y9JJy@`xRW8^%W7?1X*Fe0=e@&7B zE#`eXiavh;iT0DrPv2-T3b)|Mm3ST2kBv{$wQR-32PwtB48|}q>fR9cXG#reX!su0 zp4E6=x89cXB|WPkElf7L%*056D8${_UdAwFG2j$h=)0<@gDf_DHU_k~xcDWj@~WA;bs@wu$SRfTb2S!o+fqPB*aV9E}aU!W0b6rMgr znUc?+_tcBf9^b>>ie{B*2Qt*-UJOfp|J6r*yRWtMmX6)Jtdvw^b+3JT=h&y@cYK~y^-HQTG#SLS0(kD@9?@}TMAuV^J|DP+ z+LU?>m3ODlkP;Fg5P%-NF;?8#OzF%*n7g5)t5-lQN%(2);tGom(00%gn|=^g&@;hP z!J*$>f?_^5gq#Oo&CpB~*i34g!{g6A0>`@j#K10nJvS0CJ{_$=t;x2Wyx@2@!8h zkERP>TPgQ-Pv z72wPxh;|fJC^zN}{K!St3|n$7_-lq*M$cTrp3A;za#rde_K#5Jn>yN1;f!uQ6*3EB z{wbC@p@-5yNZjD!Bux!_KUaQn3S`#k=ut+cKCf1au#w)xy@z5uSn%(F1!4%RzrX zQ5J82KovZ@id{5nBBGZT|(=yiU$@)Ar9S-FJyqsQu4m?6_o@M(J|f82Eu{#w$Z6jTE?v@C{9pp#Z^@@O#i9O1vN;{F&5eZZ zogMSe^oCS|t*YCsUCjAvDz|1?J(`zvfLxU+y%S9^rO*C@h^GXz`Ad4)xi~y#!mJMW z3wxGs;sz#ncIBk4q>tZGPD*}wsXPUf9MoK#Ns0V5nT=rJT~2d*%KGs?t!QPz=^v2V zRpyD4bXUr@3QarM3xgCqH?)UBrCW~!u)~WB@W|U_1S{uv%r3`xig~+{qWdV9V@&g? zLM_bLpfmZ92$XcIouQEGKMXCEv*6+}*tVx!t8H1cEy>yto*sugWrO~MYg?b|zizOK zBQP!()4&x&EBVVfjIrQE#i@Z3EZ(3a38Z#!)NEGZ9`rUvM1bNOx}a+rT?0> zI*C;L#k%cDjbP=6QMb3X#sdHIKiN$o-GfAa$bX;=V5P;pmMUkG{I1bBv~a^SX{SKo zqW!(76Rz_a-7Ju9__@~j4z|)X?pUv)^(iAXmw3A%WdloG_-K+gMr;M2p-sE2*kTqfN9j2l;d{41 z`$3{X!Y425qV#28Pmwd*9t#xd3;?ps(UB+LME$^GX6lZ^JWlDNCNrP`d7X(N3pC(x zRumcfxJI0j2pUpkhR0BMb=;-5Z3NRRe0royV}rOok1!M?k39u5Fyg=cXnu4hHnIbq z`y)5nj+Ec5v4Eu&^j${~1F+0Q!#QF~F7i4AZKHqit{?E0>UBsg{EaS)WT19P{5O6*J9&_8lR#-eEjSP%Spx)1HfG@ zmAN{_ul@2v8^7sHF`h~Jv}3-@x|jmw0B%HbX;DY34zUonU)qxpZHDIywlqnA1X^R` zE$!?qQ1IZHa5+A@oQg~N+LTy9Rpd;Iynfq!L-M1eUc^?YC0vfs4v?OG`Yt?rHhJ`# zlOY8a+`uL)KHC)e$U_hQ7Fv)t(vlG+{VuSBr*~0X(O2PAbAoU6;)&}jBk8w<1T>~>anx5RXi}MNH z=iZM{<`*JV(n}FB9uGaa89KK0H&_Hpsdlg?;Oh8&$>pC%`XOwouOals8QS+o@4mBgY)0ZwL6#&0A^Ea3`vxT`AD7=0~)q`XxLqlx5f-38&UaUjy=x#j*;k6w)eDQI@BYC zrM3=HNB~Y?{mdnyDsYTc*DxC=aofXM%QFHH2wfX+Z4p6QwCm`nT5HJ_S6m@1iNvL_ zMP`miK{E1Hg|w5|i%~PrVQ$FfY$iqH#`fp`fDDI2L+NjD%>F8hP~@lN_WYY!bbM=8 zH@~`Vbq8l(@}aOTEqV#u%&jEZw`%&RT+*M`;X{oa#_cJT%KsVSbDIa14D?>J*D}+- z!WWNIV&DA5<^7_j1an8l)X3+00EJOyGzbO9i*BVW;e>7x&&@1$+sL}?;KFolR8Y`h z0eUkctaH5giycV{&~yvfs}(K>RQYO}{BsJVWGA}RwSgswb+lL`TL^)XM#3NdhdW-5 zYHx)wKn7;p{W+OZ1BxQ#=LcUMJH5k+okx5fr?|FuAQ)V=R=bq<_QyML*xEe_3%J;O z*czV)2e2Uoj#tn35%F=Ghr^VZ9qK`cg$eIju;i+}8vM`yYcHBK5bS9gu^LZX;p(ZE z>yWDR?73sD9~py^bp3*=71ol~tC;DAhY=Tz3x6G`xl~$93$?@cFgP8D(`a8IDaOk> z=P%yu5@GMz=RgVOVNHW$VpH{xB-u{6~38Q3|M04@TpNQf$u3=N1wQ2nFnjSV`G z4Nrl5ey37CG@+uqB00r^1wjrTc)Btows|eOtg?ko|x1nv)a^o4Q_ZtdVoYi<_F>Xz8&7j=|{Uii0?v zjE-fmtCM^SxE1h!X*k;%b3^kmzdpM$UM^Q}kCpCGCS1#+GDa^$71qAS>zcPdTte{; zgZt2mRng2EwL779adqWAq)Xw*{*+rvj0KYOA6h;>ArXs=i+GRF30i@HIF3Iu?iDHa z9tW^UgI9bRhhQI0ODfJmpdIB~J<^nS&<0?NdM8=%tcC$eoc!SDg0zV#_&{Ri zN>Ak1UT+akoPR#i*!Iac^X;;>Vl&vR7`j4yZeptFWF>1vgk1L;<{r$V_{SCH&^^@) zO_#`r)zmfeI)m7}U=mx$FUA|CXyizqg2n!yfJOYXA>^@NoxZaEO-ye=8L^j%nX-RL z$E6HE#YtZ5F0l(PI;dGi`Z4IzcsEj)3RY#apbQ;imAR2#$NsRqz~7JODi5uThh3Tn zv}}O5y(5|{!G67R>jHgG7gM34M{cJ4XK>!>3}(`7qP@;XijfDj>{5vQ@EfUYj*8nf z?8v9>$g%Y)a(4_Aa{mZ;wA@d&-9Z)6ToE12f^ZDrbZ3lYqMAG&Z}pnvIcC-~IR z4OyS6`&t=eL1W(Cm5N02n`ly^!2>HRT26|91pJ>RiXU-G((UG(}sAq7_58BzzyaQ31=MI=H1TdodR6t)ro1$ zS9J%2>~T#0UA|Z*&2Z&2jW)hW3`|`P3WxBpIkvA|4K#Dn?l?LlLYNMfx0AkvBH2M7en~4-p(4)bh&Pe0kr8AKL4@MJBz~UN2fwNLh+ki7V5iG%R?k~7)(2VmO0Ga!Q@oAx@;B@0ZxoHe5ZFmT1JDYcSyCH$ z-Z4~BYEqFU^*yV9#!lZ9I267p^hOi*B)$iKt@_@3-n;7R@Yf;09%B@=aFPiIbv414 z`9U=F+W>-le&aiTF!q{H%|CPWtDmcC8ASjm*aL~bzr9~{KZ2$sf|CYbrP&O zO!5tzebjxmK+Pn=0=7J?4QoAH80GStixBfz~zGweL8)-4JS>OyZs zwu3(O>MQ<7{hebFQzbhkY>I5!ARJk9j20~VYGPvDYkuuFvk|UzzYa|7qLGhs=cfk)V>nmuf z+KE*;qR^MCn!vs;AA>Kh0PBHWZQ)ka2`J{YMR;aqbGHNwf2Lr`Uhj(Ra!#!QY@3={ zqE9doMDgkFO#kz!5Ao*N*}|sZE~n}^b)Lj!E#LCr-k`#swyb8UK=qwSrMG=cniJgn z4iF~DTtsEYm$v3!Bx}i^8$(NU$fu6`aNK<13M6BSP~tD}D#6g^-#28=Q!O@9*>ezd zy(TF36h8L4LEJ(=BSHdjM6entRsBD31!2YzE%SxYS}A#d;aEJ=2yw?Gah01_090*7 z{B|I$*+p97`TTxT>sb`pg`Z^<)yaYhBvBML26nJ(G~vnO!#5)qdrDF1MT4uZCyAjC zg~O~Mty}_HHwDYmy|^B`(~ICi^D`BB(}HYlo@{ZSSa1&sG|I~O1Hs{^WPs?ZyPBAU zzQ%iYQdq#vZN=)qAVD9>QtCrRieX;l>L^+BS?(aS+dzcYZuni8kl;Z!=i$qoM1{ZS z9L{gGi%j2ha4i+OV5K`xJ){xQFhjaS3x7zCCIb^Jm;@XdnZ%AT5X!hs%9L zF33T179djIrEUIG*x_&<38%u7Z|%G;)T3f8)>x>S9)@W=pFk-ilYobU&%_FcYThiP zP!ng{Fm>nWQ_Y22O#@`Y7}rz!Ko2}t3Zkax4ctEUj!Ixv7$2wuv+Rghq6T7$M7jhj z1Y0{D13Rb&0L*zHZ?o#YExrA5P{Gq#n3L~Aks-yipT;(|solp7&wTr0j=FSeFiH;^ zY0IKz!zf&WrXu6H+zM(C#V_`^NWzKPU3ymW*I^Br@?&?6+F!UGc7AnS`AQnlIqSxA z+0cR`<`Q543@n$WCTOqCi`F+AQ{qGKHk_WU0bOlZ;G-cSJ#NuXwhc&Y??KpxFp=yP z1)p_K$ah3W?_Z9cheEfCF8efG-@Bvd;^JPXM_JDg{LR2#H=Gvy&!v-4wJD*>ckE#t z@OYbXmz)7z43umG;JZG`NeL=M?c%6bZH!d$-%xh1!K1*BE zkygj$#6MBHF8Be_YLb^Lm;rQ$deyAq*%WYs{`)~|1SG$p!aQSuSw~@*%L@*>60gbn zd!!IJ>&CRJ`1O_P48GxSxAT6E5fH|*`A;YI2!M-j1GvP^;c zC{1J7G#$t_ zl4H`Lq97#_(@+2cH6ir~gQ{=N3I7^cLD72a-JY7|U1u3yk*{u(uu`FBs)^}v{$<38 zY9ecdg7jZ0)x0}2TRX}N+M&L#f}h%@-% zmeRK2qS5D+K)8@U&j6o>?X}wDRzh3EjNrRwMY{66vr9e8;UMgu9w>31Blg90*L(I? zN~!?zvt1Ro(&2uy0KvK&RF_tX!IILEt}OdGLMOm@LNR`=TCzb#od!$>d{-V&00093 zC81yoLti;Tdq;;bQw1HN?)0j-iBdi!eL|6QF0iwrjLEnj zAELZ%vV);4GONSEHHb9rJ6Rij7v|K9-~a%A0)>uPgGZ`K(tKNhIxj}W(_5XncYqv7 zz+HkK9jP(SozFddGq!Z}+#fr5_h{X{J(ZcFFx8eX6(3faG2I))E?jUWOe1=rtEUn9 zP>c4Z1ur}_-=wY=Nc7d;BC%m+9ArXjC+GRScoTk@iWbm&u$0HbggKY7c6}IW4gwM9 zQ7cqYkd%9ZoWT01BfO)d39{|?@;>bL%Z|0|b@wjHE=WAN zPgiR!(KjlD4JTvTC7QIC=Z2k>=hwQ<5fP4F`?XqYaYi!za-A${)Titkz-aLCLU)^< zvGogFu+<_S{0>{9^6p@S_6J_n4P-zm^I}O{r}1Km?UM|0aX8|{_om8~$%(6_!HElB zNjL|^ZonQHa9~mZu(}_(GmZ71Oqkx}7ZvN)*)--+m~U|Y?6C)gvYwg@cA6o_+Y!@c zlWetA%_*`(kP2Kbc0sv1Dk9;9HIBrb8T6L#+NqNY)^L}aJ+;PUGx;1g=*x548b!Tq zXvK3d!<-pV>Af};$3vYZuC_Fb(ylbKRMA5V)w?0}^KHs`nih+*11ub%Rb}MeiISDS zDV@3MK(3iY>xa8jXbKw9GgW_`ZGgCM(+b4!HA$pR*BBD*XuFYn7<+EwRs7f-^T167yxHr)Q-4S4vBnQS(X}9RTqe6ocZcndd1*w67X$#0};M> z@$$`^>|)+a3>!K^iiF$Xu%j4x!vB`E{!^6J;5VHsqb?qt$S-_cNv|)l&Lc}CZZc9O zV6XB>rY32*O0xCk(BbA19af=Nu)Y)2hg>fUQyCMzYB;$0@2UI<_B*h)VLw*x6n3a} zqtK?$N=5*+q&fHY74K)u>o-3L(R5NBV-_r~`VWnw%!iV&%c6^S6>WzZ0h;tU>wasK zBiKtb8WHeY_{M#(&(yoUd!n6E9WSt~gC{68(mD5~c7U?Bhs~&tz(&o>w35g9dgvp! z0TfysB%sZV+DyC0Z`)yH{Sq$VHJCvvx%+p}aUEgbqM4_P&sXGn912)PV1e#Mg!mHm zoJn7LZ3>-C?mr1z^u0nn24803hil9>+FS;Mca^u4eX7~#KC~|qIS}t0fWk^RvG~E- zeK-q`e!+x5eJLs~d1rtMs&2fn8sjS6?91dpQZA!uH=9FuaZ%)(9`Hh71YJ-BT@G{y z^6xzc2E&?kzR%y_$VRVGY8@BU6o%1fhDE(vEHNb5Y7Ln^T?F}4|VQAI19>cCZ$%H~R+Uq{>R zGf;Xwi=ZULUP0_hpL}UH5kCbHMWli`BeSck{2K0XN^lQAez@o#(CujAIdKY@!T{=R zW|LCkuu_jk>&3@nb@7oMccb8y1Iw9obW+x9}%zga3`*#Q#xD zXEu^+8u7UY9Y#J#0RVH!J*kjXA<4)1VM5lcHBHUh*Ot@${67Mld4DXJd+e34y?T6) zVo2(u9e=(tLLHbt{^=>*SI)V>l;f9t_2bcA|}aJA{+i$tT)JFEB+jW-N{ zNsH4YszrBGtNnf%-EqXjWyCnmsZ*Yu?9E%)GZO+G|6mq=h-3ixH8eQpxoUAq-tm@>n3XYy-`K zBUJ(xz^Pp36wMSN*rh7}u$%w|WkNBQgw6+z*N756-jz;h_aGBV$jyozj3JY`XwQfr zt2mK{XHyIg$+S7v)Bpeki*0AR%`-sS;}F_~MCp7ZP?Y03hT&)V<5^P!GAfFSZ<@U; zkgrX*yKpR640o6b4RpdKO)s2sPzC316SI(E)*hVOI`b{<-0bh6%K!izW1gAGAbX-m zK^M4j$tk~A%3?ek&=Yt&Qmc$e8Bb7w10~sY(yzvo5>*bm-&8@jxu(j*)zmG}Sj zR!IgyOxD{#2^*ku2=af2YKl-IGMHAPBjP^Zz~3}(WT^5DN;;B>JMWkU&|Cj7nOQ*q zJBn#C52{69?g$0EB+x55Oj)JI9CyQQS&6`Lm~g!zbE`_8dz z-sXpOPeXH88x##o>RPe5jqWvs zjC4b7@OqOMNFz+lcR86rHlhORn|m63Tx1#U@JR$PDmp=XFitVRuw{7vA1me6GeXlVDGPu>WgADs-zL z#oJ^29`k3()ozz%fs~Jb-maW+_1zrDtZ0koH_YE#xcvXw*fyr8nq>yko(~1CpwWc9 zi2Jq#)&wDe8=VjSoem48kMk71eDS0?`$iRfC1ODLT6{IHNXo0vRV{QdSps#`JRD90 zEB~u2=N=xG{vayz!SeJ@2bhiU5el0L;ff41((ujA+#GJnA)N}2fx8B100CH1{k!oU zXaI4WJu^$Pi^C{}f@bX(x}b*2w&F!<=>ah>FJkDnw4(2VU;hs!t_$%`TFagHGhX0u zh9|qntgH$cJSO^(TAkldX>ssr^yI=9Kcve2I!@oW?DCx}m5-;Q;T>Rz$T9b=0Cxu6 zx|A_DCo{!%xA!oJ*XEFaQdBZ?aa${x+dxlcDN-!EWXBL?P8!>-@4!WLS^+txF4^9Q ztqUltdf`yqrao+W?JC+^fIsXCXK-#sbel@dXYX+^*1FGe)!3#78P_%oKUqwe*=tQh zBP`tf3>MU3!-{>zwTZp|V+}unA>zCkDo!-KgL`UUj}Sok8vagla>v(^Ioi8Z3~YW$ zH{S*VT;lBM6JW0?LCz!cIR1QiNgE0|XeCNnah7jY)dOQ_P=3L<>1?IwYiV594v-mg zd1xh}F`iYP6SM$DO-{Gd{JZ2;um0ac`!m*~TJdAB-u6C<7nwQtKK^ZsTM0UMo7|yV zV~{^M5WVVJjHyUEdR=qY9t3}W9PvT2uXJV3I^1DL-UEM~y4;nWmTAbG+gb8KBIQo9 z<=SFGlW`&PS$yu4Pup@B?$H>{+Sy%u=8fnqS^<0CzB5clIWkG3BH$i|3}W_i*=V=# zR+pydlH1QSKAGF@6MH6GIA)3GS4-0TNR6_0PNw2^J9tq#C<-1OY@+RbXkt!Uo-SH}sB}ttkb<=a9bZRa>+UnXVvoz|l2FF1py=S6u`#W7S?bRIANne``U4BfX3FmZ0Buf(p5MfVz0Ot-6h|HR3kSCt8PS9JQ*kzx zp(z3cY;^)zKQw>7{{xu1=4QAhubP|eT>3-l#X(#_lWXzDJ4K_)aHZXNMIxN<>W)!Y z8I%}cbokd47fX*Dh8R8E8+2`FQGk{7Q}3I%MrmCC16Z>sc>1)K2S?O3ITa}`Y4(M} z`T?Yx&2^q~8#wKkU5*N2J4mg?rKG#yLsfhf{|`9_it38xa-K?8k^G5X+f5>b#8aW- z$Gv&n0>agnCF7yqd)XIf#r#El!{E;yJNyH z^Zn*nB$r*U2s!O7F2rHIS>b)L>D+z^4R)uo>({3k`L&jScB&Bhek(oV`?bNSO#W#Ej7I>q3ogD+fizUU|4wriGda}UkGozePcPqOX1-lwt z#V#d3kK3Cq+#+*nPb>Q!M_SqMH;})IEXy`uQ>43)3ft0oeT?1rxneegL;1r1q#3eh)`(HFZ?o$D%t+ z+A+7Xxf58JJH)yFu19*N)yLNh9bpdbHI&aa!$Am8xmt7;9>JDexD3-f%3{=Ay+p#9 z(w<-HaSU5~O0XxJiPA1M?bz|B@O4b{6~^L{NPECAY*m$-jfR*1F?j#d3|H4rEYs^@ zSjR)W6KZUBe=yb9Z22-1}@RK0eW z>H^`;IUE9!5$cAQLm=*oUhg=O{NG?E4apc~s7N5N3+?0x%X@`KA6H753&UsT;UKMm zmaj&HtO5i4N}3uhn~;`y;!z+?gPnXn$2i7KctV2Xm2`*OgoIxLv->yHmv|;3bO1&-~l-1j!4wL zErXvNHnPiumRn>S19N`!4tEe&;etKs?!#=O5MGi zt}EPyI-D*3rKA$6qK02S;@(&@OOn+#y!~;Vh-#_!_3Fp0Vf*YjyjFIA9oX^UiXgKK zQ1v$S4l2*RIVZ$^?A2CEx>1qB;)U5SFes^)sUKBv>`Uw6EfN%cgs>uwWi+yp9B2hIIgvcFrOdddPC*Oa> z$H-Te=oVkHv5c5K1=aOw(a;(~u!lx_)=%^s6FZo{YX(U1(fI>5%B5pkP)e#L4^(L$ywy-W>l&x z7fftc83z#Qc{Ewyz`- zL8h{|mRd3ANd>$}XJ{($WVB7g>(2GjjrqUPx{T%8fO`O^XJnZiQT@~+{Bdtkz%h?@ zh;+WCfA-!#xw2o5I2Yd~9%L$FH<@&yIc_gaXm{2#qJU&HTeRdxab5Z=kI{4Fug|R@ zE_&0c&rY|B1l^fn8Z#8TrZ2$p87rC2l!kWgOY({>*2k42H{_8>&9B&0zo((WjdLeyXd*kj6j3Ior*JAV z>I9!^+^vU*N-&bb8cS?%v*eZd9kt;!K@w06kQ~N#dEHHXlT#lC#FzSJq14Imv-DU! zut$6K=9!3in#svbR-)#Md6j*$W=Rg|!=h^gx#zK9PO0FLQ+((e^ep>S&aDN_^_`C6 zbM1n)3BqyyKdpGbpVQ0Wv)>so|+ zGhir@^}kW_z?LYluMC5Kv%Um8H{__iXRUc}-U+q7NEwAoZU6wN)s=3fHNR)|sRNEZ zGBOK*CLpHQh&eEb!Fq@z?$9>pj?8e}HKjGM&8YctnUto(a!I{lN0pMN5jAMqg z1jlahL}VSN?JbqUzY!o<&r6=}nJ7D;LKmk!n}s?BRC9BP*8SwmRx7=n$^ZZaJ>>KJ z+S*d}YdHx?o-*KeSuh-+oFHttIx&`H_6BQyHu<7sH53ne=*+;JZA1jlSxnF&d$@A^ zk3gdxcu#qkPbjf`A02bY=v{X3cnIH*&cH}?`?$Gc!v){lV#|%mv{_p18%ndaIs*S@prKC2SJ>_wStYPYh?xMZ>*TG1FO9O_1^p{LIJv<|Z)Kl$ z#144@Qr7EN2r-wSxExitHV&ayzNLIi=o>4Qlf=Az#I}3hA+$X-@rI^+y~jk_%Y3sR zqeX45i*Vf;PA_2pFWuoUU?z6xpf6;$z77s#IerRfV)4N*Zu+c4XanLHmYZimZ*P8e$8n`Gu&OB{scV* z{Z8jnYCu9ZM^uAET6xC!kEbh8_@ENQ<)9@yGJqa3^&#nrXnwAr3a-3Y(EVvHS{Tq% z7pSdaxWd~OU?6kCoS$EAacQd<%>F;0>KlXPHCh%aCW?B*k3Ko4Ow1=%p|l&cs@d3j zB}IL(AD<*_8EcgtK#++Gb)pC%INWFm5>?&!@kr}~642p9FO+Wax6pK^^lusk>nnLl zKZ_tQ?bJ;3nj#Dr3re1!16@DD4ovF7=g6e^?idRg!kDL6OU_&%gK3}O5kBb8LP#*P zm+54@pIq2`a{B%f)7PjL4sj{auDhl{?n$GM;5Lk(xDbNP2XyzDtM?Z(rxjyEW+%aw zf51bh&os}*6%8e<#qQ}}>O-c-Azf^WwF&uFsvs99hO5<{N67s&7OrBOCMav7A%a$I zTF}~Jfm}IXKP^?$RcRMOK#(n2>`TSgwn(%SOCM>YEh%EEkcvy|OE%+fo6>PN-j#Z_1OKQN3h{$vi3x0N1N z__aL2oo92P4X`_*&*6ijGy1x>^z|bY@Q#$6*@$t9UGk_m_5&J!5+d=wrXt9GdOiqW z8Ie%Ny5Jk18U{OyWTr(RWg}#`OtZOjCz9MfK4m(Si2ouP&>Wh+dA=K)qYrgU=s~Fj zZ_`-T>Zhr%+a>4jNEuvJ+b&D}__dDrJHr`Cq-a6d_$X;4zIY@@TJv%>al#S7p2Z0P z8PJt7g?WGqupsCAC#-^f@%xD!Sg-Fp)U_``UXN2HX2DQHxH|(k;dId`m!Hx?LRn zcEpb-3)yXgMA!0Bs`gpFX^jNTMr?ej`4cC=W2D>!;7GryxT~}*09!z$zsu}@1W3&v7cWsves|KhXF)7w-qgPF+}kwzCp0>$^}`lAHUj?G;%<;o?R6IzDp z|4joN)c=bmq!_2d>XRJuI|5!LvY7qU$MPa4%-B+Ppm}{xDTE-1{q?7$7nUxb3L_-c zCUE|cJpu|L#(yF{N~bO!r}wbW0TeL$2Q~i-FR1c7zE3bXA5Hd>QsL!Ke4Ak5sD95* zH;5u>4&olCN(|4+lBPz^BmE>nU^A2E9qId^g1NY=|8)6*?hbUJBDV=eLLketQ9JEY zLsEBL8QCA+yal(riD$pI0vJ1g&3OV<^y7pQqMupkI;@e6L3^f!YbkS0riD_-5yUNRu(Ri&SH6wldSxrJXAb{GT z4gAY9Lzuqi+GpfpOjo@hpUphB<fH5g$sTzFTR*ko=NVA?~KTNRIgdu=3^S?jEy%zXfHyfS(g0 z&D^S^Z>cx_A_f$5Eyi2$m@d*l!Al))y_#Ql|3UsC;W4XFUg&4dXpy&nBAMjYpW~#{PIozK26h5~&M4J9&h}Z9l|UpiSVl+Wxa+pN4EU z&@%(xcsPOv|A#J2v2eQ28)$dUihD>(?l}vXSpj?Bx&RgG6d}La7_&eMt}Ua(qg69Qet%En-C2P@}Gm-C#LA+CHqA;@|TERy@f(- zLlzgs`jdkpdNc;<`r}7n@dEqf6>)YbiNbN+1s8pb=ern~EJ-#HiEPRf0~;M;8}UQL zL$xNfSd`Vc3E1H#;ouICzZwLlJeXKR`5t9J0H6-5oe+VB3cHx)a}Bn<*S1voAkZV6 z{EZ{Y`U%;2BB|hqVqNQYHXmOYZPqI&uua4U#o<6O*3084n3It#>}6ODk_HHEa86--I$f4TJFwP5wGuFH#GrseJ0rVnm7iS#aRGvdP(7F?Febdvl_U>E z7JhIG0Zmz(eTGyZQhS-No}&wHFZeojH9|8xScGYD$G&D}p-nP4Id%tdyz4uy-9Y;C zX?L29bH*=7Zcp6Miu_ArV5i#2okzo@Do#xRB~^F`#*+e#~^>f&|6hdVn z1Ui@}jP1zJ;=Q%OIYGul$q=K_ZD<@jMebRk4c1nz_O2{5o-ui&+95FYO)b3HgxVb{ zHT#?cg+{}?TiZV*{XT`Ax%Czl%&$hmYa&G;igtkVNenW}@&CYUq0&UDp3WKqp$*oElDCvu!{q7x4weQ_{bWB_!!VY= zmko0FK7SU@9H$X#es9^VXNVd%-e-hSku&88xgkA)j0VGXbknS7biiA@gibKf(3Q+O zfRfH2cwtr85R2q0tCNVTWcH0q)C`Yem*kDdc&uze1COqO^?J7ov$%Z;rD&PX^A?-y@PT&D2FY`(`TG0(t=2*eX%SbP+{XzNtP6s?W|kKC>J4}$Jl=1D{anKu(o!AUxBoxo zs@UfY{$o=1CltP4SiKMmO!cDP4U8RH$85h4!mQ+g7j&H@YMO!Z2{{_b#E^34Bu4M^ z_0;(Xb*VMfM0=bmbDOcFk|}I`RPPc}NCW*QU$nh1i-a*}wjx#Tf^tqWukt*SKj5O_ z?b}N=5~7xBV{o={M>gu)e`Z+Yw~=@-P1{5Iooeh69>X}L=vE7Vz_Tl=(84$MoW zmtv?{Y%!K^)NQ!YE0wTSd7Kw!(7k0FCohxgzvs{S9)5JlU~AHFibNA#waotW(B%^)%lVRZ zqQkJ=@RyV@w3}#SZ@AP%1o=8-rAw`Y)@E&f4UH4NV9F}YSSO?Mrg8FuLC)-haA4V) z(u)gNkH(1C5T6iSQI*uQ28BJw`2XGD+P!#8N9+jKj-N1E}?)A5@kVypb+`pMo zYs5#PKxF=615YY;p%K8aI|6qJ8ILHWASFn#I}Clcx~$30A5MD$E?7dQ&97RV`6OJ= zU9gz9^FNJzDoM3d9BnY69xW0D%xHpd4BHLIW~|u1YB_4Hrog&tJ5TIW|AKarr9#SU zeD|rKJ!x)(!&8+sf%payO644cF-QUw?)V)Bto#M*knM3(qTaiR`35w{*;mLgS&}CT z?*)G1&4j_7gATKoz^%GofX5!e1;>H`cbS;1-0KR8pMZm4V|oxqD={wHl7jaxxBX7i zFdxQPKk;B?M4Xy61Ir{%T+2StTyL~w>C_CRnD|HLRZ-@Ie=(AfT1D4)Tr_(XI-N)^ zR3OtBUd-kiBCtn6^u{qr)5n8h+1}IA2Lf5UUVLCJ>qw`0KkHx+?>-)a3EpUC01d`V zZ0D7boaDX`q5jr+dFfb}>j2V0R?=9iHPaHZHfFYwacI7dxj19koKelo%Ysu*j!D>( zNVQCD@>KKM7kb9@&#U=*Nz?!U6VGAhd}H78F5#Sr#qWC+BGThoBe!^duEu<)J$6_4 zx4C^_&R6C(TjeyCah%v1gWb62Cj6+=E+RUOB;uohjNJoD6{Pkn(A%oaF&oFl8pmtS zeb+5&_Y1Cfd_GV+;Z#e=w(N&T!B(^jEB25A^1TV!JLyc&1Bmz0JUb3kpc^ipeeM(` zBh=&Fo_pSVWHeMJ^*J@nv8~jO)WDMi<1nNXi7xdLKE~35W=RC?veMl47wlchEX!91 z{r~B(LqGN@?0Emo1GUTR*<}^No2%dko68`NtGHahn+8gkxjAoJ4m~csLj!hgCjcua zK>C+V5z(%~pJrDhh*&tpRj!IjwV3yW6|A|{KW~h=s1Jx2o(TvV7%H{8VWqQ?{cCiO zyyNzTQe?B^_Hd!zzpL(zr{p!4GiW1$1<#y$HmO`qHb6o|^4V5Z32))gDGYImfsHuh zNjc8Hyed`h0;C{m)0L6jxaVW;s9p9i`Ay$i`C(DGIq?FI*KM%yw;P~@Ag*HDr+{wl zKKsY&@nB-1S6*rQlh=EJW3I7?0_Zb_F7UK$MQdE=)uh*!Y|sq)W5_;y!k-2-zVg_? zBqQ^ME&%D$mBO;;ca&_d1gnEPrc*bb%|?M?<5&d~jcTm(+8tA!;S&Q(2`bm5+575r zV7+-}gPaTHH!w)nQuhr4Fg)XY1{!d4tA^U0vJi&hW68V`OeZXHLZ; zLy6PG6LmyQ%$NXb#4D&M- z3flC=oA;$J5l6%tPGtkLR2p4LEcfSeHbNZO-@r|BOw@kCuwwzPBt%DJbdeY3l4!u^2o@S&IEjxHEz-0-_{r9S+;S!>ufebB%F#A?=+ZG=hbV2(!9tHoF_)ILMAYrC9$Lz; zSq?WJe%)#FHrI|4 zQ_i=!TU>1qr5|}V_TmZg(}#_t(}3zb2hyqwH2XpQH+jZ^rDWVN6G&s)&p_MN_Vl$8 zR&FDa?(s5D>525C1dW0n=>qk*049|FxK--Z@q~ zq}CIhfYOY|f;xOWvSKp5@h9`+=}9OxoKryr5@fQ&m+k+V!=%aJRY*Qu;_3Uon2R-{ zo47E6;hb?o<*5@YM4W@i5{M&*Rmrfq#Hxr0iJ(3Mw%wgATQF;B7uB)N`%*xr@h3J5 zIAJEi=r$cfHp-gZPw3PkS?M34b#TKp zh;x1?PzI6c31yUyOCN3dC$JUM_OrOdNi1SFH-C#l>5Mi%8w6?^bW@*@I*!DcG#sGN zJWN+tbBfN_5NKY0>AA=gVEo4+^Yz`qfQSQQ&2M5TMg*BI^3L7bM2s}#Pty*ArUS9B zBJ!8SW+Nbx-c9~}5i}>6{9l7Ec6RtBs%DOxFTO+y+n5|#gZ#A_;`gTR1Ak-z%??N{ zF)UrCwUe*_Yv*p;=ZFf_U>iPCt%M4$$XV)XPc(tBZ#a!7k@3kCc!2PuFgc{oxa}p2 zB(tl#HXc{iyn6aMSL+r6LXy5+J63ffLwm7;pk=;ws>Ox4GTDdDm5vRr290QF&GqII zzZa>)?j1#gGu8KcM1a{O3~2X_keIu<-+=mW<@otCNB^syW6eUaRTVhLgRf?L7V;Ym zK{Oy4j$Zx=!wyjB00gZ0{@LTQ|K33?+!pe#vsQ17mhagrB)i~ubvlQLZW)oJg8RK| zXZ>XcrXktjvX%3rUZcU zE;^*uPV4Y9lo7kdX7*N(e_w4kLf^ivXKG4eo8vnC5BpT4z+{qbfb8vZCe&;H$~vW} zQZ3l0F56Y4Usc)ZLU(#;$I%#Mwyr*^=mn^2-Ryt6^{7_6bm3*i)2ei)biKkmN3wx8 z3UPS?P16ofpS8;6ha`?dkOY<30B`f3srD|a)jyP#R6kt&o?mUKOdAMI1 zB<${Z!ED9=BN%`-U?8g~-4w0lkoP`E&r|Q0TbcTv^*mqe;;fT7A2uX}Z;#+dOInTQ z9z5BPX~YCHp@LuNQvBz)1nxg|^RU66>wPv7%%Xi5pBFoz`*QlttY84k^5x&yCaG~POE+a!WuUN->bjmJ2wd^JNy&0`Af{iow@>L^Mn3l{0B)ThO62@ zdd_tkWMvAZUu1wrU1#ajXZ00RI3NLydV-HQQ}A7qR&h-)Yxp)*xL00!YrRswcpx;mGPBlQ>#IQ2=_JDy%3H7aiBF) z*jc^J`xhrmS>$?^R)E|fE3IEML%~$)=vV-ym=_MUAxK+e8%}MC&jcjAu@)*>>j4Ci zLigj#Q<_W~_F*}lc@d&Hza8&;X`mC8ob^MFV)4#)Ud8gS;=AF&eNw@SeoZq2c?&GS z$MiF*bA$dvRc}<2MdLR0w1Gd1pu~^^c^eK)g2%N11nWMqV@G0+I#-+rn^hAn!VDat z++MRvf+1Mnb-Dlgo&ImvQ%7=#+$*@Z3Lj8V4PHFoJm3au)p2%SbC(p|k|Vz=_a|P* zIOV++;U*PRZC)>xXq0jP(cpgkDU(W<`}s5B)H>H2FE;Jao&)bmR7#lO!+XiMTrg8F zLxoV*j!Lc3Yz+F#wgR!szw!)SgxNb23>@{2Z~Ez7zz0`~JFB9T3J~)W)j`L;#G5EI zA63+b5C_>P);=1aX4tq-za%dfj5_>b-XE9$WO{#SndooG;X?9e%9!&DG3OvUFC&@9 zW|cFH=X}*IXp$vY2D_uBGB2Cc3g4fR9FB~)vdYs&ejaq;b1;TVyh`Q*tY-F7O&G<$ z(FN{gg?IJdo@7?p(EB%`uiNkbwmvtJ%EH63vhb_9H`;RgCn4jpYi;2+>jAMdm~x+o zXPq-;ZVun&Zt=#^X(z1F2NYtmwLkL$wLB~;NSg|&N;r8SK4E?4Pln%~Hn)52>Fde@ zy8&kU!F05sgAhS%UEc~y`j1h#Z_d`x#pcDqB%jbt0XgI-TETT@?6y@+X1DAM5>Dtl zp~bpibhPe2^)+Qx_qZc#2Ys&Vn;3B?GMqxbDBL0h4>Xo4<$%qOMU)WfPU1|xh;<4H z`l4bm`}xIb-s}APP}<(&!vYk0Et{a6K24lH2TSE*l^7n~U#<5f!4sT)4CI$n_!#P$ zWf>!y#yn2espO96El}`jS>i;Euh9Q-dWEnv%r9P+!Ot;^J6QN+vB0&&>QJk%Jg|=HZbW+_q|{qo6n-v~ z)~dg+VM$;{-z~X<)4V$Ny&tEf%n>-LS)8Y9SjvkP$}DC9tQLaoVb4{qn4BfLcWq;^ zm~Rusy5PVKo<1g|ykOUh*f^15Bf^Pv`K!+8h=)uHS70@;0Thx5ixr>jHq}M$N@zsi z$MJpsu^k+egG?&|LS<(4V-`V6P|CGa$)6VT?Jm_(BH4h-SFliUVo+zl`bB7L*qC!n z5Mo{vc0Hi%CH2Ng>G5Q?;0?}e=F-l2Ow7Y2QTf#h_)ZHpyx)nmdXHb17;@G>_ z30r=>IR%@OSdkXseO{99V-F)%#6R~IjIv74yocXD^mgKeuR{mC*}WBtHl@B_1E z?2jZZabhnX?h=q|WtrusfA5y_DY)mVgwApm6&i>nynnqSA=iMhVaQpOMIC9C)78UbSpMjNtS>!p&b<1^%NbWWjT zg?uo~ke8ze>VC81H6G)ZRHW2SywGdj7NKlttzLDF%z0oKev*i=PNW5#$54)gizGig zQWAxT=OHQoKbq4IIlj3>wOP=O{W!L|Y{3`PG^$soZR#E=4h}5m&=LD~8Cz>-g`@rr z;e4;!F;x8G%cq^^Xc3^2_=}woCGD(A<71~uyhBLXBPe)FHt4027(DRDR7FgfDrL23 zX$M6-o|PswbJb%{m<^^t*5|jv${K3i1B%~7xuKM!9UIBb^*s`-t>gx5l>~;}Jq2VX z3UK@j{Yucpu&}}?7M z^bQV+eAYsHi6==1#g>xQN}qZCT&wP5@Mnf zc{NN^vDf7rC=@`3)HuXA#U2;X4@mv22NYvW5>p zc?e;)QUT*M<@ViV!8N5?kE&M*;ZId*kQR4-dM}s1pZ#WREY?3E2M;y5hDZEaH0T>* zL+#-49R$|g{Q_cqSrVYi%Wj^@uqEBenN&|Q8j!=D`VtrzG0Dvzqn$wP0XOPMIY>;sbnFM1gxl1tvD>yiI%!`wq?F*ZV!~qM)m1 zKA?#?j{EjnB@m7?;unzJiU0%h9Nh6Br}eg;*Nb-D4*&oQB0B{TPkRDTac}nli({pi z{s;fXN6oJ>*WILZyxwm=N6&%KZSK=MR$(wo#FgBH{l$g?y7y7?6QZoU)2aHBLM_>L zh2TgUpERJ?1ZPP5TZjnC;1lCVDW><88cea$K{ZY#ZADpkJ@fpfeRVDFh-xB!Wxk-$ zj-5nA=0W_mwc~EF+K1#c(I1!aTG9RZ_miopBiWtV_}?i$^vd)ss{^|a?fg-e3%(P; z*FU%xG=o{|Y3{fMv>BVjG2H|W0aq#3;n5<~nDwrjnCM~Tg)-}5>@TmOzw1|t4^kFY zAfLT2Rq$VL?fe%&Ij7eRbqAU%v9%+aV&+piCsN)TsRwi(s(III16%_Y*<&c@fqj`6 zLZVrUZBGbw%hU4TFJEgagzLdXxv6L$rHf9`lAdjVx7SkpVe@Tsd2YAejkWxf&R)ih z3;ksdX~Fi#nJ=X>cnef^!Z3e1TL6PCGwe5^s;@&2Qgw9o+GY1-XR2jmC%xo*2i`@| zCw0?CX^Z=UmznK?Qoln2VMhPht8t*=Of^LeuG2|s{L#aR4_3et@-P!jjSlrajj`es z;w-gHvq`X{>BHunT#g@J&pn`e^*U44?HA`GvMXxm6@%n9B(=VNFSJUiYVL8?Cfyq% zh@Pv!YK9pd-R^O&U~)-wOfVllD7E-OP+?%qFB&*5;gwO}0p44Zck;Xs7-9|q70SMc zwids1kRfc1h|WVEm3|WMDa?rb)&eDAb9zQ*PF^eU`~~^LUK*&Ud=8bwfdAEHS<9#8 zL!kaT=E+l0X7>WBBW~8-^_<&4T`3;1=PV}nM`GPua)J#FW5u3}D!U_7B&pqKZ)A22 z#F)1Ns#!Z`1c5I-VkgZ{$czc8@reLj$Q(hWh+{SW`jK%omVkL5fs;$GfP3NIbBtv_ z&wN$%K%wYGGHtz1?Mbt0O@tWWmErH~!jwE}0IXD5oA#vnm_VJp{iK_$rEpvm*ga>_ z^G0yE-7Z-1#ht2|%TJ=~vyP=9o8mUaSK1VBmS9bipeg4AQ6&&RM~Ya0-*=HH&afu4-VL7^u)aV~$N3u}?{P;eNq z1*2w;qWN{9jSJ8(geLU(dh);C4^;kha0C@5@tTQ>Cy(F?yc0mK9B||tfp`CG1=j_= z|9qp@^I~>_X7onldq0fPgNvfVC+cf+?#8iS4e4SVcsCysX`#&}2S90G`%onH zC-FgLNm=00lLnj)ou(nqE|wb@s$ET&?J~eYYPZnNjh+jS)pjpjiEvm*y&XB|_c~dd zqw^FRjo;G`+uzvrNxv-`%^1ha(YpLMsQTYJ&2R#R;xx}rTzt@6+H^2b8TjV#KrymY z+T}uub(lb8*&du`30x7qIC2ZSt!El}_89_hQIRoijKq@6!@iSu5p62B7uYSQQx8_A zJ8~Jz;ljA)mh5W|eOuwtAR#S{Df)%N%_P5wFJ~xP6EOn4?igFa4@BDW-uTcDg(4dr z{K>A}^L&M4000Qpj9%g0%(V9yh+S zO_k3NRti-juzcb79z5`_+Grgt{fUIKP;&QHy=R%*aR7>}=LU!3J^MR+XHxM+|AS&H93au$^?S~=p z{uW9XmzdtRH9g2t^0C)~3ax0IP|Qjwj>w%j7zz*~m8A!o@1JCx>W!bQ#u1C&=|$QH zMEH)sr_yJ0Kez+LltdqmIzchoEkGe%=VKKh4D+vmcYr-fn6`9=ja1knR&fRE~0VaFgdad+vBT+5^0+A^g z9g9;7@cX&uv2(o-yW6F!cjnmDV}X=rCQ(EtVQW=jZcP+yVYZ5D^&Opi-{Nqt)}$Be=Ia=hsK}WM+{;7(^<5o0A%%9n+c_eMq8lF`%ZHP2EUI6l*<6Fx zMVybT41z#de{ajB@u?DuGMvR*w;wY26c1QLgAGuv41MaH!>DN2;a7Gxp2`N(7B6)8 zc~Ss;u^uS5bbG$$3#;XAM794GxQh!eA;t`_o9Zs?%6q-@mIoSnmzz`g!ol;mEM!EU zVIF!^rbx*B)bmJyPdd1l0Yj&Apuxl4Y%UNX8nDO=l(hY#)Q162`H+L;DQ%dxPqb2& zP^Eb*u%;R0;F_{LLK(t*Dm_yzm5xy8fH-AkCvnFO{S{Fd%HGRZ0I2g6y*Y%!pjk+! z%nq{W{C0D}LLtlrpeX%ciYA=@o%|kU^7ij8?*8{ntdEOb3rbuD)b_(Th3^-qJ{lhq z5&kLdI9KJ}rZquJxGCsg&pYiwlSHq}0PiSR7}hi=(!FDs!0`SWJY7=CA8gx+cX(uHP9>U7 z2l<*i($?~R-YdKD;-OV)!al6=w=rX6WuF2h#f#wLnG>CJf`RQRbz;O(Ln1gJ7Zn_K zC?lirJY>J|D^9Av->Ch4H=lWg#g+!CJ&n8}tE7OwOvv~_rx8_}cL2*s z&$7S3lb}U7*ZpJ^Ai^l1)9#8;MoSQE9$DZjyf5s ze+g*(1a4S~BeW3+Of+|)s*cJX9)>t3vh*P74{ayu`r3=I%8&wM_kOC!%%Os(-3$$B zy>wwk+zXvQQ_dKbyz{yBC1j+_mZf6RXXa@t|DLU9$JZMmuI%pmzGAPIVJiptAK<9s zhB0V6NW!?gKx=SfLX%*PgDUW?pNkiAQ0xoh;*W)_Md*%g=iEN^CA*+eXB_D^EY&H7Y-QC|R^2baYE}F=RS}-Bt2u9!>11+#+!dQK* zE-f^vk9LZK7uGvCEHnR&#fE9mSh&a#_9TR2-OC>4BT}@_iZ3mU2WaU3!~=@x zC@9komJZE1QLxQoSZX;osY*9Zesf)-`E*~d z_JOV?wC(`b-t#YNl-xr2RCtAOZC&o(%c+(h9Oat0nWMemhfLq(FB~x;&cfUwOJL6s z$yPc3G6qWeq?aeP;dm%AKEmOrZuoXy*WDLuAfXcHgPiMJ__C{SA3B4(;A>y8(j!1F zmt6|^M!`zqMF9S|jMq>o(KpbOe(voQJodDLX%)C+7yi;dk~{d65cc%H$9lve4xef`(#GKeD* z#wBYtJ^*N<>aWBnUn@Hj&8R-r?s;t>f*oXk;V+Q2Qw=R5Fe0{I@RTZ;J57YR-{(KS zm8{-8rsZGTo$AH!=|6*h=z;g|I6HVd-T|4)I_R6iK(NGKLi4!?%ru+hY1R0PpdG{0ra89s8H*fCRl0z0{$nzVfFTS{FoL~t znsnD!?Yx_JJ#OHnwCSc4&TGMj2wPq7mauw9F7j=;2?|tDPyhhK*d=_u;t8#KTKMvTOt#Ic z8dr*&DTdm3!ja%-#50#ANVsB&9U>1um502|*XXHLS=&$nd11ktD8I$JMRB&0td0+= zoue4-m5N$awsz7wK;RzFUA}mdaCe;Imk&!Vhki~(KFVmS2s&E?k!Mqe(NrekyVHU2 zQ-J#LpI>Z`b_WrlQro-mP04#>yZ9&SIRV!4NHsRZgc!6G-h!aDS!2AW;or^K2UmvPxDN$gKbtt%hyF*#pWk9{MBQ!hkB#P+Lj< za!EI8`qR>l-0amQ5ya7>Jrnz4x$PjS*M78&h_a+2rn{6}`a<{W80~yE`qQvTDb}>+ zZTO>7-S6^cO9bZVvq1QU(IR#H;Jeq`sLfipUrQaM8iFc%z z3*Y&^RZ<>k``6Oi;SQdh{o#JC|Ni-Sb`}-)HPsDifCm%CLEH1xRT}nF zV`P!w-^bso^Qxz>9#_Cg)-J@>m*{2HOHh^Oj@UaB?`UGLaG8&k^7he6PqP3QQ#9Vf z<&3-&A^|YeNj6Hmx-LUU-xhVa-Big`1zsSxITK5FT3@5dBmIITW}=ndwTy>6%-V>l z`1AkwyDWhQ5ED#%M!jgz1~go>J}PA01ULgS&3JWZPB2dY8M(o-nZ1}?L%-wJ3UjD+ z{+Av(DrukZOf&wk#j+g4Z`bcfxDnKpaTOc;4cuKBT2ri}ahQBp9Sfl~<>JA9?6Moh zCbY7lh=@~~7??LI*8gHVx%O_& zM07fc7V~g80AsVn&lF*gi-rrJ$)4uCTjPRQNrc&i+Z1?@~mp?$Uz~xr{{C?q?d*U61!EM=A%H1$mblCXV)4OAlCx;U`zUJ!ng9 zhU3nsWo7EnNJyFJZO!Pn$G>6>lJA^mFntchVvVP#m<^J6tbO)ZREgP!!o7%Y!p_FD z(LuWpkPG)(0P}oNqIF#=7h=?tPf=O;sNS<`d<`4SL&?p_uO8~q%PW>aAf;j4|7>_@ zL~hnwdJ-FyT`M4!R`Cz7F}bzXjph&tO@>t~uq^MR>ZKIy#O^RQBtw-|BMh~qg#mnf z0PIX!vw0wT*k?%K64&FZ1`*Yq2&67^gF)=z2L0KzK7QaGi z3}JI0^o2ch@d!L*cA87rhC|5$`kx4BFKE$r(;&)&zfGdhXdW%Z3xLblmfuag=Y#D_ zhQuT$Rexo+9S^$a~bt0p7}|z&it98d7_XA5A5(zW1^% zDGaC&Xx3w{=WF1BkqqQ!)yK?Ge?O-V@tHE=-1$35#hY}^jsp}wm^16U6%cKU@Q+g#iWLFBH`%7!`Dtw&R}*a`c$cu0gPUt28ertP$$cV)m?JX4nL| z{7T=YAAsjt24sb<0(+SJYJIF-$-b%JD}1&c_A5BWRA#Xoy31KErTTfnO|G?P|160B z!w)|K^_{DrpLO6fCrotI$*&T#XZ^QSzJVgphX1;s%s*!(a1qm@qRDVFaAwnI9UQB#zG}a;sc~^nA}|S%<1IO@Uhjh<*64 zeDxF_PqQ{oU&*fgZ`9e+7Wn>s{ib7E7<)vIHOTJf-Fo!Ii83Z}mGB%OoW=Zb?L}Wb z_|ef9f1hn%O)K{~VATy)gM?3ZJAFNM5jIg;9*mS8sKz`1F@(7G0hQopp~ZhUNg(hP zVsfwZ4#6FS6;y-?>@a~QV|-l4`a=aQr``* zGvdJ~H!SbvM~^kNUbu|sJ~nC92G-viUuQgZyP}Wor)uW{6qf%k{MWbD0woiow?xvL zO+s~#w~na?Mcm4~u=DxSRHEY#v-@yko6ujV-6GbhFLiS0jn%B6sI2o$#69o}zJ((% zN2dO6o_R7&&qLvWE@l3t`UUJ~x>t{+Mdz7|Xzxml#Dx9(cQ0+L}-SewU#^r>E{m~s zT{jCJ>8Z-Qx2Ev8bUrYJTG!!|#eDNQNGT3f`8|nSce|R3N;a?7Ngx_7!_4g>DROez zAIQx31Q8NWk<;H4B$f9j&1WfwS6Ja8N9_$Bk0kn~7LeG1Xy#;CR*{wrV+|_Eso7!^ zd^i;C*(j5{F~2wy0UJB43}?dm@9r{1f*ky_j9@ zAyb_NY5dZr;T-KMjrB8-0W&HX4s3q)wZqyy4c-aky-lB6wIuzkcEl*uqVnS0)Ze}w zbF0(bxQEbQP0ed%AI0mCe|R-8Mk?G`s;Xe7D+#~|E`x13-ChWQ)vJc=UPCj^1zmxm zy(?mBm!EgKI)$rhbR3PLa~R-P#klo+3b!~+Ipclv4$K^QP@^4>$*^*+Lsr0Qrim}l zDS;D5bWFyDM1NGi$vuE7^~Oc!3(A9sG(g&?y|PoR#)?ttQ$ChP-5z;?I0v&NUUrKuHIZa5iHp>QS(-00iOV9mmppsIUQ?Mc

_3u2 zGbWVERF`g}mcspfsBgjHV#e{bCR z)j5M;QnA#)Rw~#-hOoCp>`vv|2ks=mH9i&Wr#exxA;VECew~M2SJpoS^fx;flj(}($E9mnfROWi?<-oovW6@ zKgWWPVb(& z2OfW4rot*ik0ITEQSU9owr}LhDt2}MDa{C|9Wt6bA}8ENOxv8bfC*Y@D4RTvJ`NCf zO71(pTg;*jQT#bW;L5iV+H2oHTQ^K__qMcEtI=y~qHLG5-u~C-TT}fa;v~qE>!A(TlR-ikX)u!D*ky| zQD%c2j_~7f@XLJ97w4?ipdNa2r4T$b*8tOWC5&c8<<4U~42J|*-+1*2sZ80_5v(*N zgEBWG5^yfZk2A8B!al=^zNAQkrynhWs@6`Ymy_=K6AaXEacC!biKEQ0)NXkYpc=RR zwaI9Dta|a!vF^h`lq0uL-5zs)@Ag&VflwTRBz^Kuw)%Tdeqy`Ak#p;Sfp{di-Vd_2 z!;ZmsKmDXvHi=RWdK^~*tkbHALzm!*RByOtD2%<%;XYtgRSTV0q&s~$u48IpSYV@B znT_HPp<0eG0Y?0%pbb6KQPxuU;*mYoOy)(?=T8AAu_*7nHDWwsiA8-q-%zBTlk?~- zC}sqUbhIn^E*LOt_=tDqmCgCrSpw&kn0TO?D>$ zewJDuSHz#pwHu9nGssWw=Vpj8?%HG={85CNSuFLgpdqWv;ynX7kO*nf#9+bPs%u-( z+dm&uO@J^PyQNibE8vpc1!k$ltcE|ZuwdgYT&m54|7DB@cmM4B>$&Gk)}72Ie^HBa z$4DviKnev-cSP8Eg13^8buu~02=VdB3%SZ-YVx;9bo>M3ZC>+#SvN#!Mh9ubcn}*o z=K?Iu{Dd(sISVl|Axdb$ncQkXij!CrHTa>6$PEX)%gWg|^xwLJfQ4e8C4dga2s#NY zCWGqVP6Df3)|=}AEgW~pZ!!wZgM9C@9MX%Qu^(2MlJbTC1v46F{Q@~ZBH&mW)%YOg zcmN5$WV6uBWur>s3xx{UtnkwqM%i7DO<{az#g`!&bQxVELvV8C=tCI7tdreb_rCM$ z57bwa$bly;6SxMPDOkx&6&MBN z8RUT%xO4qM%-*A}p&3L*3`w5tW={*~KTCBIV_dM)7H3rWXGuy|Js-c$esXFpUf`y=ZDn9F&U`}7()zlR(&JO^p$)hJ zMh^aZeIoi-jX;S<#FyrM08iKAYu&~P}ZY_u^=&*Ct&P2Vy>TCntZfOO`KjjLp2jzz>ex4Wm# zeqGNG{_#DsvWbeG1sZKgBJ?(G2)TU<{v-1V&Hs#1DoS&N1oYd=JvitUBOh;G z6>20i6{A6@&jYt+V`a8;K+<$^4(FyNFPaHlV?TpCqj#S&O+}~h*+*SCUd!uGOFw6U zh{OAPCG!?~w;BasFYluh_Gjp*4*}W@7i?2W(q$)#@CB?YW5#edCWiZQwVNOKa1d(H zotj!C@+?N;p6~uXdpqZ;G&1?+6=3~{&1NALQu1YgMyPa2-I)9twuVlL8Lb)#pD3Rh z-s`u&i#N{mmm+luARc_ks;ZdH?!Apn0(}&~_R9Nu+e0oqY3QrBz{+JHAa<$igG#Hl z`*V`8io0|Ilrt8wB2E|2St!$Ciz&g{P3rF-@HRC9xuJ4DQK^zZ-q?0HUA(f-NWwg? z46zsW&ZlCFHDJrWo`vp>94YI7l?X~gewdu(auRrj+_To+yMR%gQQ59Kn~NQh-&>GX z8r$<^hDINRpfPvA534?nIV-pShP%T5qn-%vHJ;nqn63wopgEJWt8HrtZ!f_@eib6u zFCd#Y;T6A$>!Hq+uXi05Kl=1>bXQk*HL3(RZM>DB4DHT&UJmG;5?sM5J1G%n4DybC9E5g6Nkm92jPT@}0fdyzIlZSn!k@ZyPy zQU@elgT=`o_wsdrt(skq?3l@$z!tnM<(Ey~j2_wdAXv_^q|8`TKg+X@4i`hR-Ra-Q zQ754}rXCyhn?$Zx-oJXXSbsCZ_qS+Q9 z*znNzqInXWEX`<%MNEz70g0YPLuOOeIdbWyO^!UaUPHIk_AJ8=p-!$gUQvhQOzUWf zgTTAeCa`oal)aOeFSU#bUTnLQS&DR0GY2ZTUEWgzy_%H{Nv4(j5fUeN8Y86X)!iTT zwOSRTzb-_OnUGWV@d(IPy;)s``-AKpCigPYncABV^~7O%l{SMI<4qRJWmqO4_8fy7Dm4gF*cR+)_b)87iV z{JpFtFX^`C*k|nQcejXQyCer`G4if4h=-3p22@3%?Kdi^F1gXofkkDC3+wOV^`Iwu zuM>oEKOXBuXH-)=Jn!(bJne zN5W}=sFM9gnMKFOZDnD$^>;`^nIohW8(=4>{vjJ(Fid|bMUUn-NswK;Vmo*04#llA zl>t`-_Huh&_B{_KlM+3x&HU}r1}*BHJCW-WXf&|q=uc4K*Sqb2nTPERLTV{IqO~(`kNtx<6~d$gQWeB0x? zN&#h>5W*M5(@SNWG;D?j1Qt23x)Li`ko{L2&rs;S$OMn>$WH?W2-3n;kGu&HfBhaY zc;xFc@n*Q&HrYTGiZk@mC`He;7xbS7reL7ZT|P@gk!kK#q8#>5$<~cZfJ;c}jjdk> z0boD~Z(z7nYl9+Vk#JRhnaV8HlW^iuK=DZ@x>Q~^wWE`NKs+SoW6#UuHfLqU*GD9{8S z*br)98A1G~*|9TF6p;|aCZ}Xs3^jWc=S@$LsQQ<7!*rJzgcP z&pvY=%su+V%)_;fu6Xc-{Go)SS)sWvlNLm8m^&bu!lKAtBD8J+K;=jT@>x^0N-(9vGS0Wgv4jpX3wknsgM-mtx6(Z-(=yNy*B z^LRB`&~lk(w~u6EpMU@2sO=V)h?}BxIiM13p0fwQ4bIYEa36l0*xZ2H-K_m0aMWzy z&^$?b^P--wXQHhpTug1u({&d9q)?)|%cuA`Gd@FW7i7QBd0Ae!j~BV+=of?u3ioHq z0T3-Twy+l+9g3rMOY`x5RcWUA*bc5S)%o{6zuSg)IV5H1Q1v^8xgb!n9XXMaOi9Z` zBY1#a*>dc#eCJ*gpv~S){a}TGJN!e%DcBo5s}I%?d@e^B$-HTRpkM|p!5-~5?u!|z zqkZw6JjL|Iao+u8C2H}wJ78Kg%Wx4j)$OQv0grf(#W9Yh&_zL6;a#w7v4gywdl9Q* z>P)Q=`R*|7hQjX8`%b>>K^}W)y0A|23XEmToN86)kB4X_kHxpMx#pb#nf%5Nw3Fs1sXV! zqJtT8&+3F5Z>>9CbVm6KhD5XWz**B;te*N6WFjoayMQ)fpx)4TF~ShTcB78qIBh64zY(vylC%pu^{{pZRQzP~93dnWOKHL7F( z>BLn|;qEQ)Q_{A>!^@oo(?y4i3gT-``~zZxML*=Fy`~(`zSn>Rjm-KY^{+f_w>MwE zmvuuV$E;s5H6MQ=k+4TYh^d$Tb|%o(C0jnbm1c2&?e`(Ew94fpye^4xV10y~Y<)cd zU0@KZ8Nrq$|B&Bp|82%7gjZ;AqFvVk1zVHTv0}p2saL=&wMP(ADeU8iy?V+#2*bv+ z!*15?-#a~BD4B?7$=`;|ag?Z9^Q-fu?Eb@!3TD00^Vt3NxJi2I(E+^v1|4)G2cHa> zxsiBA@kkw28EOk|I-*jI*U#Po_Qy??uNBYv;p9(#s}s{|KJG^kGlzAq(Yj76WK3p| z*%6OQ>Va6Hh{Vt!hC6C(14y4JUR*8$nvSI|S_`kY zmuhK!B>u99^Mi^y%Tv|vm|~DS8k#26keH}|1hGWLj3$h#x2j$Qq$}>%{8ptxlBA6M zi@aP@!znLqwf(W7yz1s0P%t=$y0f2wZIPKfgs{={EDbKgB1Qc)KCb1&_C3`s1Z@zl zPHQAS86;jD#>doeFTEble3*2VQ-4g5uKyJu6g&aP=7+QLP-=ltX5=|d+Axi>V&?vj zF8K=N4)2*^%vEmXYckWlCa$kr6AN<$OuyDbB{4$u?|`T~W59Df(YTcIzc6x{cAby4 z3JnseDUvlAJ95I&huStypnxs2$Y9~y1qHEG-%|t#5DmZHu#wSI7SOag%+SSP=Y)g2 zPXo*H$)>mtL20w+7-)r>UGNP^1Bs)&P9asQH5hQX<}!yu!bJ#;<%9eRI<)22x7^|f z3mnOH;30gnPycCr$i4_ zC);4a8pl`cQL0I<``uv8P;Q|_-uM^u=u*i{`enkd(G-I(n;VK<-xXqv{xZ?C*Cw~d z=OwsT;Xtx0Ok_`RX%=kdVl@G!L!vl~$vFra$J4|xE1C|f*pGQIJ9AT)LH1DkfPQ1P zg$+D5jZwRIZ`=e+IEP-Yx#-Vl^neT#rjfF-A23W@Lk-ymD*cXTu@RHdwH1Xfp8)|0 z4{460@UBxs78E@?DnYVSmUk;Ob+Q5`m-fX%s-iI7)Pl$0R~QdQ9R-R;wQ=!pQG@L? z?rD$4kbxn#XR({wPD?_yCG$+brK9VJV`J1Q97(uTu_|>M$v<4L+YAADo4&7 zxZuuK!k%(C62R|zYeP}c3^~m(h|r0&_JD<~09^$!0(vKh<==?^pF&n%%rpI~1mDJ! zDn>)m%{DYJD{Wx^)gCK7I5}7M>EwC)nhcJ@svTNzx~ANc!t)n=h0pcqGc`_ssr*ezy`{e%G3XZ^tx@ zs6Gbj0_q2`Tg`2s3&aqW8@k=#LI*^c#w?tGSexp3RZ}4zT4x(}$Iqig`*QNz4a-s! zvP-{l#35^UIX@0fXY9KP_QS8h?M|$KCd-oVcpR@iPb*UNW9DOZZOLrtX!LeB2$~m0 zVLwHqZ&8qO?tG8S3jfU@B!8=r!W4ES(#y?@P$#6?F=i;zWOjwci^rC@bEie=<~LRV zOt=oHUJrS+k<`=VRwH}U8RY>Ja_H*Ig=bO^EGJ4 z@^O#mCpN+LO-gz$lIdHyQ262{A8h9(a+_q8az`4G>|Xc`F%n9~beN#C0zrS`jPD+! zV39%Qilah}BE!>wqJ0OjM2RO$QTPq#ND&fd!O0W?&fo(?>FzN#^;V01?i^A+WG{~V z&_nUAzW_{7+jR}OCBRS~S#WC*!p!-0u1wAUZC_LXo1|#4OE$f?VU}R(=9##)QT`_u zz$06$M^E)lB~tb6%WoiaP<{7vk;__t3n4C@{eO2K1JA55jiy!=SrKs5#WuRX=+TD~ zvjW&;wOyW2VI&dT~WYH5!#zhq9DseF;>!Z$05atU6hLuF=(ICq5Y@r*wcb?DNbqLR2_xK^=_t zp=kqicD>aoChOO~+3(5okeI-%393RQ3U_Lq6Dcm1_^~2GdtzEA?o_V-lDMs#%m8&> zvQoVj+#y%T_a;x0wSFK8JMN`Z=K0d1VA$kLc$0u(#b*>MROiC#`~!;uT5rHgM~+1pzV@ANB>p+iqD%5doK)!(OMnC{uK3F*{5u5lRB}L1FU0Zpnd8D>_dZ`I##BsG({J zxH`RDn8G$UU=%L;LEJ}?RH?Wym`aAL<>)isd~{2N&_wldv4-@8L4I4?z-?TzYPl~> zke?ax&_Cx0-usa18f=YNC8EzQ{^D%l7LHlfchQk(L*y%|kT6`%cczyv(@u zGq#y&IAlCfE62^C&B@+cF9y6f=ff|Mc$_>>Rbwdup<_oXL6og(YGb;IkuK(mBFb)E z^T&1*DPmHr_^-iN6~%;Rtfe-S8o;Kr*~)x786wirk*og16H;jTTv^H#YAc7AK`|)? zmd6>dsIv5ub;24YNP!g{k70Be{SHmjTx&ZGp%~$${h@ymaXuP)nvNR&=)lCdcev6X zHJQ9LxZPO>lDomQKGbhDg#=A?qzJS~)FqNV>#J`Hr8zE@Y0-tQ+8C zOPG0gjJv&k>Wvt0ug^Z*#XvjdT4bcr;g(~uv6i*H*$mw0V`_FnHJQMdx915*71EOi zOn54AtdzW{`6(Zg!vGa&Cs-uOHTZ{?GaEd&I%BSXL_xqyB)SJuM}0Mu9e<6sFd6PF zoi8KoC8q!elR&<<%i5k?WFd*2KBU!Lq{tofN@cc`9qy|aKIrPj>JPPeH}_=+SeN3B z|3g~UK=S6Iremeb3Z-h?`4*dwQ+h!wnS-g441p=S%u~=QyN(6oOyQ)9V>47ted$zc zuI# gkej*_~Hg%wEi>DW_HIGRELR&a8#cEgo&>+f!%Bpw!LYTDYnRRQZ!E#RZCM zQkl})m+VstNrCYGjRmGDAKEPbQ(&=u?Sp!R#lA;R_tOXxO3 zy#1oM1~SEHMJ}Bv5rK>!{V$@}fLLG3$E}U+6x{ zTJlu&674$Tf>n>16O>-R;n()%ud=y1cI1sce~VO*pL$94Y?A9Aq*tF=HXlC<{@aw` z_3ImHX(U%Y4=gY$mAkudA&fZ1wj_Gs3DhBDOlvry`zyH^+aLp=N#5yF_I>6vGXja8 znVc-LO-nq9C?=5uLqC7R)cM>MMmqYVpu^*bodAyh65*`Lt|}ObTlGTh92fAUTdZJ# zOLA8G9XYoMf+y`_HaCY25JRngxS2CI_XvTmz+x&JLL~${M-EhWb_Hk}?B6n;b86fvg?oO#3vEB#n zf{c5`$vI4Ys(PI^xt$E}1OLNRyuo+X=I_9vQzLQNfsU1~vvbad2zG2j3-qC~uCIS{ z_&HK@XA0*JJi!J=iZ$qvsFT+16$jDcDQb;<&nGQ-%5uX&1P*h-$Kw7}W`zqE_u*Il ztbqn?V=O~eX^B%ho>Sj={5t|51%1+@GhfL=2Qvl5;V3?Bd9nTcoN5&qfx0fHiI~Y% z1HkJJ3!3wnsKGdrhAG-4Jg}&jr_6na z6RTaHTQ0T8++mK~Ui^LHMxi&^8Eq(z8kLoQ`Poj{j7T{vf97Ilvr%64&o81;aBx<3 zuA$O-t%o%^nqf9j2bEKDJH9wDEJZ$`=|91T^AP`e4oDvQ^RODg7DB&TN3K7>47aeK zUVdpTGEKbq-K{nv*)|7ZiKZ3YXjM4$TyPZE7WXP#Oq$h_D`O4XAF>rjzdnxM^#S7P zNmSE;;dHB6IAqjqaa4Z8k_=H2NwwM`l3pI#gwZ((_#bTwBAZs=v>jnjV%x@d&aFs^ zI@<9Qp-G5@cbRv-1S0$H1<5VOm-A8w^rN)jxTS&xvTe6z;>>1o2?Ujo7ZIBLtE!J+ z&e?o8C>M^4J;4=*D4#uZeW%efD3|fZ$;;f-5D);Y|NaGx-?F_laLO{_4{){GsWH0E z+?a>_3o=uV&GZ=IkIDCgrAjj&BAlPAaBSIPp&9& zclSNK6Nuzn43N%35ZChzo24hF(Tc=X{$o18{KJr{J%W(Q&kU~13v`I|@Cx83a=jA? zZm0Aqdq19NB45LsFd^c{G;#6#EYkc0`Rw)_SE3qam~Adu9=}^-P?#Ctpc9e#T&CJC zq+tcG*NF>hp7z*0vz3Y)f~rr8-l^p#;F^l!IS`Mu_oHUHc&42@hxNAkt6pB6f?hJ+ z_Gy}}@2GMJ5pj`%Ym~IPesP$5XXrmmg|>7A$1weu|DgkwBG!&iienNs-PDy5*<%_h z`R3_}A6s@RxP!~72~NJ-JTmrLJP?zCBG&)KF`g~zeh%{}faU{s-oIfO`(b% zWW4CDIBUoFGkuS=`|7eA005^&PTofU>}}xT`Kh!Q@}vkANOP%g2ms}mdW=_y4DKyVVRflO#r6o;h3|Y+Oe?3`t-;<)Wgi}^- zEBr6!$3j{?U-sBbw}^;$wG|tg4HiPfvCeFD0+lCa!!wzMClS4C7#C`vu_&XZKuavX zzRHHoj3dfcm&iWp7~0QJ!d7ae858W5T*Cso0yrJ=lWpwec0bj#3B;E_--;iUGZ)Su z7ARS;)1gaTX4#@D1i2p7^@l(An$};qy9^Iw{Wy}{KTO2HNjzVI$=N~e2we48I`m^e zAObuzbVLy3!RtZtMcwc%A@`N__UDK#Z`b562*w_v?29eX%5V!UP->?-BPMFgi}GYS zq9*_3mZn3$Vlec?dPqg5;(4k>B(9G|%KYi6;&{Ai{T5tXoVN(1haRsmEWVf7N+Qsz zG_W{GvzRs^7uxP8kKM1NKhrao4Vx5f2sIP%2f6Rx%hx@cg0VndXG@hjKUt3m%YUAkG7Y`~duZ507*>v_=+qoQ7&aGf{X?0eM^ngKK>TwH%d^N2747J(?XlhX@rR&*`jJH&CEaMB# zbxwTV@o>GZxquJHJ{mZ0KQDo@PNf3?2#iHOS-YucF{mNJH}8MzczV z9$`CVM9{JccZl+|Skd%ttQTh>E7*P--njk_RV(HHuUU0B0C|JhX9rN{Q*jHsp`(k{Cd4wRK<66j2q=@|Ny+HWHW zBTsGzd>hu0Cl1d$fjzAUNzas*z`+uW8_(bfLYXLU(*kHXEl4v#4TskSQAI?EFL#qQ zmGAA$+_K#PS}jUp?7s|Z%fR6@(z9(;QOixqrry!)nKwcaD7;l}+j~`Qxg;>{b1xvd zbrBUXZQ{Uz50DvqIh#=E8U(*{1PG>gBXdQ}8p^yIbR+d2u-+l6^&=aY!nQP?H3$&y9~N*{P31xKlr9Qe#Vd`zypflD zB12`g@@`Cd#N#3M@;pmjqy3U(iSth5FM8#17o@XcfdxjJs=@QAJ(nTc*lWoeIQn;x9L{tD-r(+oM7lgsZ z+E3(9q1X9GQXB?|Qq_k%$J={ffdlK@x;@d)PgAXKZmJ0rrEM&p%fIqBV%}_;rsY2i zC6p*xLSc`{5nwQTkYM4_pi`|v3zUTnCOFmv)zFsASv$OGEKe2HJUOB9S9XPwo0j9U zjTNw1Ke=$X#)bm<>}T}0#A-GEc866kbt z7;Mnu6@2Rp9XY7JV3ZYz{Y~;PN}NIOgsAru6ppM#ly;q&BO>#BpoQCa1ttgRSEMWw z%l8heOM|YpH6Ddklh%=Z->37;s2rolzV>`Fge2;gxPwpe^t*c9rl_#;*ns`|m5~9O z>N!JFGet#v2o@a^O$n2|Mtk?zQ(?1%+82#+i$6jOkCcV3$!c27 z31OjPOeWZ$6wC==fM@Z}qxVLVg?1Qg7eIpYtoy>9YY+nx0@r)BOfN&6XZZ{B-efk` zv3`Fp-}R<8rtW`5E~BWk#!!m(_BtcUmJ{GLLoau1$_bDn$Nz2Vf28?ip;e@6p|HeA zmhz+Zaf7HPrugcG4_dqW?)f+JaZIQgFh|&t7rvgiyBi*LPt5!}Ar!lsY$4Jd%5vm|H zYskQHkpEnN<5WtHufT2ux!Ey!c0}ar%*mW$v*BcA=&-PbCB0Bud!(h=?uLX z>ZX2VsNgL3vh^ngB!O=~g4uNVeY@@198^!LIOSr{oV%4pfXlh(K{z<0@p(~HnxGwal9X~Y-rJBc> ziJU}}nPZ(^(Zw>_u%L_=u(?5M5p=(#9bYC@ZYX8;;MAv7xEpIqiEKk&!#eBN6#Jt> zuuXiq`j77TK5(|2nab>(g`*wtlyE4gC~GzeKdQ^oM`l@ZJ+^y9pOZK_S4@jZ3uy{s zZ0*3G6b}z3lTo?A+<22tltXpbB7FF`xHe>!fX^eA6UU2w$ePsKh1U3dCBJ$u57eWw z-1Hx&XfK|qJqP@T1yB;h*K*}A<&c3`cY+;oY|XjD@$Izkewm|y+dgqu=SUa~V3Y2i z_ytat0HeEl`5Od6BL;xCmNLc+Ap=1{dCQv1t1q_qyC)w!Rv&9~2g@Y;%puAT#;qjz z>_ZD!c4uF#N~!k6?6sH*|K4BNX0oAPbyJ=vP0e&Nh98~X{-r~h+x=p{ow*5vv|+S0 zMf)WkA8Gj78$ExW#8f?Vi;ptWGg$J_&;1fSkpVnbu+pbE=9u_C<~`F}RMqD%EAR&4 z{?=M>d#mXWuWpiBC~JCQIOHjPFCy61T8F&=%B~*0n4FOlyh_;9;>D?vYUz~01`?c) zUYv^!X}*^|9>>!e<(x%5YUcHuuI0Er8ZLr0fzZoep0KNXR@yt^7j9i~qr}nM+8@-1 zX9hlnB6m&F67q>u-w3R{990`B1wJDPJsoOSzI@ZY`b?bdRuct1p1#)z-8w`=>3;mi z8or+^?mt-``_DxYqO-;dP3igb$MSlLImt^;Xz}SRv2OF&z$!bH!pO*9(Bu$(*)m5D z%`5zU@rn{`PhaU5fm2@X4-M$8OfT>LBu*6n7Kp6OXqm$aaO_PIxGSsT;N_?+Jd1jX zTT{8@4X9^~f34m{%m(&kk==SB{NqE5MOOVkk%Hk$tsb2tqAuY=52~9ru1M}V-ge+9 z1^db?S~C9ge8c36uJeYY@kv^ot@u#Q8;biKh7eq)EHS4N5-6hRS?dint%0{U_8{6=lbtsfMw`{O07f;G>UW{Ji?gl=Z(3x{qV}gj-vSnY-~C|!lBx4kG`&{= zqWfUxbgdw0K$Mw+2z7vEDwBw{uliH!7eMZP_#ak6uBZq@#-3zSLZ@{0HJep$?r_$$ zBa0v6QwH;8i`aRM2UMcQBweVqJ^H)yw^Z$Wi5N8Zi-1{Wg5%Uu$if7UogrOOpddG{ z2|cfP@JXMGpT{S!l$N_|i6P`kD3&Pq+G@s8;Wad0i%oiM9JTaRR<;We*MH_?PS3zT z@hrX2;ctFQW-$P9HxQ3RJbnq%sGOw?URk?j4+>LDbI~#lMO5Y(6QWX(y{jK{t~;{5 z=Wlugmq?@7;!th0Ax3udGLWc~+y@bpcJbVvke3-Zmhp!P3Nr3-fsz~^hOD{IJplE= zrg_kzUDW-?NuvN=4vC{(i!t=`s>$WCT7Xz5VqvoXRr|?&B#0PRGDWh4s}xh?uB_7o zLr@WlwN>Rs?R94sUJk-6Dh1f*q;Czhsgrdr@hWGP&=qmBQEFDRqqK|WvMzfnr8wi! zV8N8!KFUpfy**Ziq=RM1W-loGZ1x9j zjtl;4Zq51IFLlQmBn?|OlU&&&1QsT8XX9*Fy!l()u0F&M~zZVR}lCV`5%y zd1|YrICzbq$DGW$=gDAR&KqnJe%@qG6Y1Vp1VxT8e8B7v&VX{C{9eaiDQ8-|8rRI5 zdy{Z`zX`FC@HyC#>A9HYpH~t-^E*zvd)Zq5HYaQf1|aHqhy89!Wg4F;{9sd4-O|R0c=knY9Kvld}#iAu?;vmOY1ly|0QZBR_?x;KaHTZ}) zwY0kd2Q)hiK~%_!poXar>1BTnu0#xZU?t9r-?j`DbqAE_UFJl-q@nsMGx0{JyPbW~ zU<=`NWX~u;n>vv7u8B0=L`{PeOg)4WzYM>-TRPVV zLEw?Yb937eU!5#hV8geo3F>>;6j3c_%DO7Qi1fFc2>eY{&_FEIB3`{fwDq_W(Yp8V z6^*BaP2HZh+-<8iuO?DEZqI!|%?>$T`1dH{cl(S^%VqR_`oo*vyQIYouc7$CF|Evv zqKiuo!S7@FB>G*lIYeKArH=g`Wd9uiKzgN91pqAi2*5?CK0m3}Ew`xGvo=*O&SUi8 zQck-6?p>{WdhnmwMc?vIPQb07B;)2*PG24{f< z`qtbT#D?B4+F{_z_TIQ2kB*w?Qr>9_qYUUL@ryxw_2zM$P`eup9lj~XtG%5!QBegg zeduPFlQu2b6&hD*iKEJYhKatpKU>%U8TWCGC&S*)RPS`2dd7j+ZmTUAMN9LP@~d3b zU|{8W3tR(MgA;e-33>@K>M*~JNibHSRLF>^FQC4N0T+N+0gsLaj=yF>QI4xP0Ko3o z%GH&?_CoZ9a56)cONel@44Jn_J+};Jt%t+(F)kH*q?|_}>c{MEmZC$WT_Kzls25HvS{l)DD|yD2%hGJsbq49AP`1VkP;B@~4|BSSp)G{+}R5(W*rpGUv;dm@ehl zbHlrl^$qG<#p8(kaT&9j!rqwJcbDqG7$NR}PbS=Qgecwd=%P-#`oa1l6vuRTpN$fb zt!qs`V7)zW=B2K%76Il?UqlxgCdik~aH?v&pH2#CErjk0qy@y$;TCrVq8mNO3t6*k zSN2Mw{h2&$ACoV@Cv9w?qb0T382vZ}=62lni*{!^ArB9FbY7 z80lga7kZyODjJGNw_BsCSc~W?beT38jXEM4y3STWILT17Ohf0leSErnExj{ixR zs67@Tq_RYYne z?&>M3A?TRFTYLsi13LE8QSWb70vRJ(qA}F*)gkWRZiR~dBNhi_m!lxL*=Pa>zeZrQ zQ1Q#O-3XeePjzKdRWS-$%xOS2RNc<|)g-d!6ghQDY#3{Csfysx#cFBlKl1!vy()yo zU0_RoNM(b3&y?`EOnIPAgvBkL(75L`MvL!e`<5gG)O?JY>xN`FssNFEeYDNStNqzz ziFVJDn<85g|9dbok1v*lEj{Xbv9FQ$zyPRq9l4eo2ApSW`!uv%#M65N&YO(xA^gwZ zdO$Sw||yw zcn;l5Ix64IIHMSnnvjy6m!3Rvptp+c8eODW7|XRGT^+QPBffrMfQO3j{{%f(skP$p zP#dqi;aNa|^;;C!TR$t8^_-^$(-VV6_3+ON-p=RtnDy#YqcC#yzBrnDsTyp9Zz&^w z=~F(;)sZ>-a5#1Un#y>zGV~2dZYI6Ld5pK;4Dhina5vaunYD1hftCMLX$K432-deV zo~&ab;3<-PkfTTiTf8Uo$?=$YUGMpD7KQ{Gs(uUrvxW;z$wy9VX`k#{60}Lx6)M;Q^@^F{+(}y$ z)xKxP2Qah(%94r*MQBnL90Yu372_~LEV0wQrfu&D0O@D%_xf}dF~=5bHUPr4lTydC zE?km=Kfxs2M``#PQ#hyMuT!^o9d~{zk)`VRg%O-IH>A8h+SZEa9le=l_@;klAxPoi zoOB`L+h?4i$-h+tr{VVTPK;*oW=X3bl&0(3P};phM<1LT$JIpJ9Lcweud65|uv3Hy z008j`Wg^NV5&Tm-fab4P2>6?Xe8@`e6)~3%e1I16=r^jr>jVe@>q82!)bKm0`7^vV z7WqCHzm~XmCVrs?=N<;xjSVtuz8C=ssIKOsCk8|&>)q)s)turnTOf~hf1k3cy&E^y zBx7CD2h6#Z`R3?`y}9iCfsRKS^YnWcC+0D4HUy7DT_Ou6#Em>h(o*-F$cPJw^Tf39 zZnLH5!d4qaZ8yA_*dRnOIG^S9`T;XSZ|< zrhx*BiU6tI2hjQGM0b;4;{s^Ms*?j7u*I}R^Gp@1KG6{yFOBuRxU5pbJT_7G0h|P) zVb;X}u2DroHxzt1^-L1#1$f~Qy0E}Cj3Sk2Vo?%W#`}+5`P^-7R?&kR4&8dfD z-0ZAmAG45Po17xrN1|a>g*BG>DNfMVyVbH^CTu-e0t@Q^>2QjjcXFNYcY$iKQiTJa z@Bsig+G~KNFaSU<13j?~SX%&|a&=ONv`VQay|;9w#{ov;7&zJcy^2if3&hp>UPb=u z7j7vZ;#9;l#SZm$1lh$%)sKGxm&WPC>U2Q)7ITA4cnx2I6d2njfs`Kc!QZKiUL==N zMTgz)5g4vG$-+t1;?kQSLTqTuGOLvwhgmj49U0^nTT3k_*O*pZUQTZ3jYUJFq$ouK zHS)`}ZxudIQslmc`?hTp-przU7RU|7Yp%!w*L&S_3cgc~UgB+eKgHq5Gs>yCeL!N> z^UAcQ{xHRWzUHTfI0>VCn?vPBA*r~oE`;&9GBIg>p<&ZnSatNvnT9TG&Y~L>no>Ft z_Q{Z-wrZu%^@~K=Xt8$zJYAi<{46)2F(-@&qL!#b* ze@Be9*yHW~r?&`g|E6B6m{p{8n%-Pg%Y}z)*|UxdaPA11$f{SA3C{&~Gau2l#-Je- zyti4SFUnQK>xNFJNhud$$6?sMaL|r>``INrG4;sNMc_f$=Ky7BPt`J=()lOK2ww7) zXR%m6d)@go7PnoO4Nv9Dt^+&FiSM_}0Sjdk!S!eTBW*w#NGzdB3*YLG$Z|d9caL9t z@)5jxRwkZ&XV_kXJU$nE#a}Z@MteJh3gLmPd%c*P)b9qe;iwO)tpCM=VV7m19Qq+W}$zNu}LEQfE;BkoIqT#a2biBu_J8aX}TzpNm*bP3wt0QU=HGev%b9P~Y@7&L zeVWWv>m2#laD&H4-7>Gd@-)-C_c9UH8}OYra^l^eJfr4mcIq;AyrDAkObIMrKO+D2 zO)8z!7oH$5^E8g}Ji&Q(?E&I->{#?$N`M+ak!a0?MTHN{Lm*>gJR@$Yq9~P;VD&62 z^&R%-oDGmX<^UFz@&O7H%-hxV$=!ZMh-*2!KDlV9gGGPD8SQbi^Bx}Lz6QCiC8g{T zm?p-kWc&?iLB{Ht_;s{Kw^1*IN?0flGR&j5g7-jUo@ zf(AWmzNoErp${}70FQ^&xh1?Gc)^5q9=vl1MNmrrUv0(f6bzpOmG$=O?0`$3m5UT) zGNH}`s|wyS{|uQ*z>afM-ktqm%H!nuxHbVUB`#7L&$b)KhJTH#SQikUCg@8Pw2@NQdf)UIwUWlM0e}zADfnuIpGJeD@wvic zxx_@2iCu0VQlDLW6;8&}6~i6Cis#3}tw+7Z3?-t7E>&G?uWABw;HJYik9HNR1Ly!& z0bH{Axb%C9vT6Hels@J-|5e>A?Y z{c}|NnE1#weIx(x6a-)w51lA3PZ#{}l`U@FEfXMM0Jc^)@C5$f77o?`Ou&uNyehXC z=DpnxgnFK6b2PNOMsW@WU66U`rg~vAfV}|+PSuVQCrQIG22S#aKY|Vx8oQ6Y7}%sB z0AMpB&gGJKKl%Cpkp2G> zKtF(ifl@dly8nlpV;rm*!~;T?+aoLfyL8-|x`A7vOz7R-MFr=|gvDt9yjCV<{L&AB za?Dh1*}dD}d;>m}nY)2EzgG<~;+kzkcmM#%i`n1V0V`BbF0Qf-LJI)c_IyJr|Ar#{ zKPW&s{@-tc0Duqwm5l!YQ9UbWOIzgF{9hKXV|BL!8SuuGa;g%~id`GvmtCq~ndQ{i zL-+u!bOlu|>mcqylD$~t{1k_cSJt`08d}m^m_x~S-yLoARzsef`0y)7=no3fTK&_NP#f{c0wySaV)R^@NW`;-EX`W z|A)6;l2+Dh9jN(VY?uZ%^EH=7XZxs=>^?Z#|9osAVi@G&gpS;YO)%tNsYXw?u(_zS z5q*B@Gw4IkCzxllQV-kjAEQ9I-ic@4lWjO7tbT{X0RmgBP*PLNcG)GcG*EH4#9eKE zf!+_+*7*xdhF3a5PCW^YJ1o|j58oWOf?6%Nte2TMX~a(-U4Ed~UlNLp&kW-Wz>Rs8 zU?FYC(aS*92@kNDCduK(!hzFfK?2#)PDVf#N<;_Ax{d;gq;3P}iHS>zWQ_8GDh?77 z0FwDeJ}8t*4b=b)y!zd@0s8YVy?^>PK-oT=;01aH)v3dGi|ItEZv5_87af$(aOH20 z02py9ej?>7X9w*fC;!F5bh2}61Z>C&YwrZx(mzGWJ zWRipPjpkcC%)y)Q)Kh6jPPdQ)^bc$LD9e}Q0)5Jv<^7zUV?Bxu=1Yy)>8!mmfp=Pt z-Z$!^yFw|s_JLn5^Hv_?A|L=5N{K5ZsX8PguqmYx#j*qUdjk%J4m4QxVH(@J`X9BF zkYjQ>oR{-Z$v+wd^9@L}a8XWAG$Rz9SrH>RcIo!j=Ls(3u#M^)ZbD0SfPzd2Nh>f= z7R3-)p9)GbFsmo4z5Vy{cA{o!Mz(QAu`Vl-PRTlk0=`t<@Y>Ilz~gB97%Cgdw4i;% z-WJUBbflhV(Sf&pM805sSX$47)CaO>uFA`RMUgLDx0YJJ=mXMxYnq7jJ^nuH)D#)?coa<3>4!%rbvXaVLeh5{ERW)xD=PkcTqZ_Als~RzO zUgDna>&`$fFQh<`Us>~osp#n9R@a?5aAE`a1;k`V?UJoTJw^b0i!w=9Q>GkD<7bkT zvXp;*&)U7(o+oq;W@EfLz2sXY>6_^{*t|%0RhLiJYZr)wJl4N@aL9g4;vYYAO9MHs zw%$^5#U028586`uF9Vwu!O0!oc2?ZWT<;l`sPag-KJVh~4l zsI|l#gdnm3HS|iF)?b45Kn$Hb&6E_WzOf6<|?yUE617 z=2B%nl9KKYX-Q$|MoOdwq`MoWr3DEIK^jDmMw)-{d3@jR`+lyu4!hTV_MCOE zb=KZz4nL=0(Ok)V&AOT(p?cP{Uu=foh^%@H5*Zeqd*o#}p~w5B&8cTwzDCV%C(D72 z0Sxf&@qzeC^5edyndvo_DJYs)BC1Wz{WafPwi{woDdBwL!WKb-E$eR0Y&)^_7WS!K z5U8f5J$iM18$^f7p8p`M)-)g7cEd!G zQ{}o2e8M_ArQvg`tR*qNAZTH^-;$j!;l2clSR5y(1VHqsOi#uV=YAqd`42E-n0J}$ zMa#{ynZavSJ575TkunU53WI+*dCzej*4RDmD~f(Q&f@3)OdNkzEDoUdN znY60($gEdVT}I=y^4tFA4F zgxW>3(C^@Q$y&uR_FOYUG)44S!(CavpqphJN*0K$`=(MDNc`3|b~QzfssRAXHCO{ei44J#IB{rGQ-g9503Z103;2%#%0A{= zr?YGei;EvTQd-!tXH%vnF1U;9eTV`SFk>-#;$F}Ujy%gOy!t_Nd!5g&+(SHs3(T5; ztZWftz6~(2$WSFUsSO7Pq6|_PB>+$J-r{*>OKF-*V!nN!lL#U1FJge%er0uCq}Cms z88Bb&8tLy^CM@I_d(1kyWm*yJ#9*?xuF`d%%MYXFNlZcJk;&6aL%q_Z`TR^FUrNv% zDlJ^5kQsfc?(4~Bi}XmiX7TjVnXH_-_4-g*u+cnE7;uiwu{+UD&vw9&6i=4g3TUD! zKN_*|I5u@WeVmKIL1q?~P-c|pW;2I3)+KkiHTU2ukdPNaj58#@7d~q;{^Mkv8Ps?0 z;jo{8dA5y*;kI&!g*@#ur!+TIvEhE8hSS!R#~bG^g0{QIOfiHt#}J3UxTB zTd_U4M6=XXV2~c!O>A?ZOpK$vxxAQxm65X|ad%XCbG#8>uT9&3ZhPF0<0_~GHsy;H zgVt#h`(3W-Cruq-|Dwk&bA(Rd6J__$5iov zYIc4|>z7B>oY?2)>is0}Wv;f4Yh|TmeNw#Z+cb!m?r+&qO;=h_^G@T4C?+#gt1O=N z;J3(V+Nl8Akvg@X`s#Y6Eob@{l&>;X5H+4uc=e%P)_+bdCH~@)6j)lhP%5|8H?xpm z?!}~R_GOG@nA*k&{WEG;a~Ko;Lm+vZuD_t6s0;crI7(k$m|Cp$dOYg^5Mw)YW@a%0{i4y0z$W8EBW z-5lm(%^Xpx_u6nWd%jwk!rxyGrt@gO`N?{OPKi>Q&Y_xLTQG%@lXK>2V2;bN316yF zXDW*Q@n*BWQ^|14NN?u4+&mcndM~bda8`J;SKyqiAoVRZGTWR#2O<|~bNbQHPEWcR zv%Q;6smPny4L0+-FrHc)V!Nwf3fF?9r0A0yjt<;eFpXc3$dOb&{>$g|NkRZXibY9@ zqYeoAQ{h4ZL|OnA?fV!t2L+I7|8bgo0LT?$0#QJ%Y0aoQsHHpf!0pE7Gr{v4C2wlq zr}W|?x{NqQr2T1n5e;wFc;7ST=#PK=q%)`7)+VL>p6NTy&)<#gN;nHECM9bNJ>e3X zggirUzQW$wnTVDA=}rg|S50~zr9+`hDFr}q*=`f*@|5MqK#~Bx%9_3MfVKxutT>|j z;1ve-bs?x8ucnfN_qPM*m!63r#4YJ&1CTFZZaK4_d-r1@v0CoGbqwzTxD}~+{MFu{8DJGk03vaV>BWKB+JV#)=AI=R zP7{2&NX+AoloG^ls>=e8=nYu#P~{-2p`$y=gvruEYm2{0j)BskfblX=bvg7!LIR3h zBV_tGIs%fKq?#d-m%vE^go`RZI2ulAA`+C_3I#phhkJu^6dk4i!TV?z@Jw<4VtUL% zAhQ1={F8f3gFn481=$IqOG?~xL2f00wV(a{%%3WlDS{`IDF8IO zQ8@rx0Ds}~Pj~ajBf@K#?0lH)*nee%8Y4W;P@(*PdP2Zp0Ky~wCtYd%Pto6_q&NU^ zE|GhK*EpJr7mI^4kP5qeM4sL-l0e_PrNro$T%TV!poL#M#@>oc_1muU=PNv+i$n)x zxX=DE-he^x~y@T{+fit=(4N&dLR)<&C-EL51bCoVc9r%X7?p ztqpY9onC2q1~5WnQvj~@RrrRh1dtJRR3;mUAZ9dP#lF3q?W%pPw4v%K7$7 z)9`T+UbL%wi1zJfkEt`Z!51VKsMXFpNGxky$d`|nSD){1qj-f;zupDt<(-*+PRSc3 zsJ=C+p$LK+E9#{E9j^FupF_oD?JxcJjL%;Vs7-xk zSbWk_o67V8B2!%j zup1W$`C!*a$u1Z{NQrDJ)d;r7{lTsq ze-L{PJj5sPp7ojEj%oA8E_og)Z$InsdAn^F1SjCb%=SAL4^4<4z@$X9h{<5@(Ofg+QAdq>)qe3xjiC^C7@m>Ili6O-|r~-vY zyx~F6uKg&VVv9`lMCCI(S8D$(^1i94iS0!Fg}Zx0+unOcVTZucaNGk0d&6-NWSHc zFn~@ZP)sWx8;<8dH_V38x5vQ9w$|#=t3d$Sq;(Z0MTM~e=pJ?sexMxveXYNoSda^S z198~?tIzJre^La(t&eB$zdu_1P$=Q`tM0$0CaGR9jTGzkV1_N6??eIFX1kKs`rD@zkLw-hX z{aRsTUX?`iUZ3&hA$)YNhoXqKWBMvZ9u_Z?o`oX2F6c}ijck=W42S`htwB|E-gHwE$( zo|=iG;svRy#O?g8ND+~rkwCPqsoZU~{UN8)J)Q zef#UrNR~>PnuHqmPjWxfAxS~h{C)-+m8CBKXrb#|b)h(?NBpF;IzEp{E9i`Xr%iV3 z+XV47U~#jfscATsr;K_tZYuMtlEA(GD+cMb$U=mUrRcM;c(f*u?MXSjUz1vLE1GG& za~sluGTc+$%5Gq-qBxUo!$M4s#+6SLMMk3VAbDlnWM2UP7 z_FFpSBnFzCS=y62jMpOtH&c?bAN4B+KQ^Q94IrI%s=Z@TJKbt3TO`a(A!-C!5ZJhG zQ72smKu{!V1t@6NsM})hcI>ug=d_(wwfn4WlL&Ok=Wb+nd|v#3|Kx>&+InO|z%YQ# z<)poyGIN^1AUv4$G|2mq`bUs;e%>uFSlN#fULgKwA=Mh(0K%LF31PZ zqji`T*&~q#4*63M2pG%>pQu}{msS6Cqi&Vc)a!koZ5n+2ngE3N<_muY3uQdFg7-HM zr>W>+hE&t;nL^Ju9b@*oB{{GcZBs0E9=qE0MFz%ch^6+){@N{~Pe6Yav~o{d?t#Ov>y5ZZiTmS%xN#s~48%qB}g0&^e z(wwhuKLMa$900eX(6v5pxHG{ft}0I>B^RK@iCwHyA`Vk<2oFAAmg5e9V7{U&ZY3e_ zh28UM^g;8Z(EE0DON3A$5{e{G1ue*Jo=lc`TX9N=I~``!*EqM^^CaOe+f##Rsd>d_ z#Zbs_@**X8;u!Sd8T;B$ZvT#$4*7^@7mXTIgT^KLCSVra6#2TW4~yBBnA}_NXhT(o ztJwaeW<8`|mNCQ{ZaH9)ZuNw7_4kP=y}iwj0v~O#!j~7}Jnq|JJ&A>*gh6DR6%vBT zXwUFlwxSXfR(yJQ5*twEEqw_uhIm~3@IF;$c8lg#2D>uQoVh-4%a))KdKk<7GM>f8 zyc&;>o}~`?{0-(-EkXwKJCMy5g`ftgnX8$kkP*X1mQ?_4r!Ef)lm!6*5DCh0V9}@k z_{e;q{}B%W$^79$7#$+Z!KV6u5HQCIu#er43xIbspoC9hGg?bnGI2%{(phT=a7$Q& zv{5teOQ=PHfLOp}v`87|Mo~av?mZ(2`Zx@7i9vVg!HW-LB~$=-A{lMn6by6JAmAhz zmT?#sN6UZhK|NmzfPSP7aLffU3<{P{N6sSxIZvoh8EhYi!K-=E4X0*63eOxCJtVUO zLpcQWLBjF&QO9Y4gouzVkyusEZb@ooU&2ru%z1wqLM*hVK+&E+TrBU;YP+#CH$X^6 z8DfM2qD@sj&oV{*;OYk!0P)4=`Ud6&WivGrHz@i|#$I}0X9pAJ*iApvgOLBc40 z&?c$t+b_7&=s7&}lK_aP8{Px9#D4A*gLf2w`B4tVCtdx|Y?Z<$7osbX;mC0CkA?Zi z#6bRa6Je80g0qq&w#H)T6NY1PL^FL~dCRFj+!`t$I;^#6>XNYGSW9_rjIsW-Kzo7t zH!JVq(q^vb15S+0B?98Wdl(EfvTI&XGi+=hg(Nzj8D-1Y32t z;(J6YBk#O&GvX}A^=Kz~<~nncwb*-EstKm?zE>X^seTDcGC4QMmkwyQr*%YTBSFTI z&HWZ@M!M6~S+zE-_<{VT-Lwbvt3UWmb;SnbgC^x@E?oR8pHDx7}X>eW_j-zFh;DMzwV*_o7 zpL6d((&qSEXS7#y(Pyv8{L=alvqRAWz0n^jRa;*ZgCu5Yrhhhw?Q6}FB(RnKPRN0e zZdxs-W}>xVHJe6l`j*sBkMBG-IKt(DA!e?77PqOJuu4R5T=9ePaG8r|!mYb`w0v9rB}d#= z(?q3y*FSIR+w9rh_FHoIlUNd|h(M*EQKZphBN}wi=F{>FNWqR&`Ca&<74Fm8eLWo3 z^5)J|&KVkwEGg{YBp86=pC*B}U@=bVYR)l(H}ub4XnfKbEQk3@x4U|9e}!VHed;Qm zT0(siLPzj^G;&54rv=ZF3EgzhU~p_G`+Go8f1_n_*w{x=mdI9Ujo5)_?EQ$K1YU!8 zyCyZ-6AF-z4U8;iC34)y9RG4ZeNtvDK>N&noO}p?w{aWZB|8GaQ?Z0G?pgxCqq7IV z-4Ap_k~>HdCjaOs1VkXFfxaULe*#565*nVKull(=Ms6@p7G52>x>Hw2kfqXO1_fqT zKx}G>Vzh$41Tv8ro{W$=N4w7nZeT_7Ml01x4>5SmF|cBMZJ=EQ_1ipfL^(gOrf<7L z4c{9F&0v-oi&KfnB;cCD7KjzMZ)8jXRBs3z`b}iht~srOL<2S!I08fUs}#q*^jSxI zc@4KX^&0HNGC?_h754vOWS^0Ze*nXti|+rM`a{R47YTpzgofWt9}^B8WbVBbF<(kB zE=d=<0c58$cPC$&0X`(qw02UVbw>#v| z=@Rug!}1_z003e^IsRz>iUu{7DS~&fm8#SJZ4Dad_>PJ~i4A)FGenz1>mK7cwGKv(}e%^-9JOaQz4PlOyY zgyRw##)3Qf{SgWyA}IhSheZH>No4qM=ZYKr`O~MT1*0r62yPt2w5~ZnCkt0|susK`q@RIMMJnCiN`X2Q+@VQ2Z#GZw@EzR(S~M59 z#GcJUeEod3QEr>mzq1EBU?1p+fZTp!=)oMl+feQmlUjSk}(8|GfQKaw{>`j~bQ^ z?tQm8zpw=R4loxnQ%nuWCqan7IYY?8}5@wbbgC$b?LyMfWn>D>r(-kLh8VOw+F zhsJro@LmHCT%4S9xOenh8aG?IIfIk!J!2G}SYP(t=UA6#P$gIOs7a?pSbh6W>D`CY7h!0rx?9mA@K-bd;-Ta(aibob zarc*ReqRlKpY@T)J}K$>2TH<>vysh8s^skCi$fa2Py*$in=fj$ z2xBk|4p{Q^N>UFP8}%8r*M_!zSMgh${M7SArL!5Pf!7i_p|SqC!DN|#E^|s&1GC@3@X9ouV)SNW6hVTplvd= z4Ad-pOB3*=JblP_VHy(ZICSwmXT)@WaZ3yqxfpyU^n7((am4V^J$pwg5^NM zm9)q-p^vFYXBPmlqIEI=zsg)kK`<___Zj4o7a{)K$`W&bsv!Uc;XeuR645`2$8DL9 z&U&ole*ydt)9_ayY;bqJf5&(f#V1Ks;@xG~-M69Ct z!Z&PH0AQv3z!PFO1b`mV0@#X7yC_(=SRf^|Jy#g3!O;>V07yvB0z#VT#Npro=^hxC zTo{&$|Js2^VGsZXdG)VwdMJ>S^CyEuYx?+~V;DN5prD00ArIsL$Vm9&8H1q!{F*gi z+J0B6f#}L~a{au%@LRro>UbH}RmvCUIKn5~<=eJFQdl5&TAc)bs!(bwduEzJKQ9EN zN&M(;z&=8tdpUyE6Lf$p4x{Lp=_3sM-p}3u!lkk}0zM35GYsR{UxQKqYy=!m)%F*k z3GSa1#_bC9ZxQSi;OkPvf&3(Mn6Ut^<4keqYF>y#8jrBH<}GD$HJ;4gdP><@;W3=( z$gLYp2TyY2yH7vMOBUE-DG%eicf4k3Hf zG!XWZ+|U#NsmN&hvr!-oQUbI5DzxHaR_EzlCHOi}kYg-Fk6?3>`PK(F68GVY^KC@C zhmJE!ACsI$Ay*)G2Euqtdw^3GRV^iWkHzf5t4w(-Jnp4d7=L>JBs;^tQZif9Ou{5~ zKJAv*uU67p^C3=Cutb?0p{Z%@BBu2qL7vXU8g{=KUGBa$S&I&CT`6anu;)k9TFK3> z9Bq6Pg^4{gQzR*f`6@T8pFxmI3;9e#`{&CF^nKdXFc7G8RQb2r5pl@fC`NHgUP=M0 zu~;TSi_Sq>4W*5Nx*oqk`cO#Y*I}?c>T*{Cq^8m-J2C6{^*8xEO0s1R`g4*mr=|lX zlh)PG))(n^)!mq|kCp4Y8bGqDNX-2vX-}-)K zG--;NSbo5qFFL9#d5`&n2DxLaA5_hcaod65%R(qVo1-*&Pvc~@ws4e&>-JVgq+uu4 z-EL1;U%0Cky=AAs9zVBGtv@nuMdST>)M~&(C5!rv;S>Y$ccN@0Y>GFb#GMPL`kZp8 z<|0C*Z$l_8Xi^S!8k?4Y#&2orJG}lAJEf~>Mrcd>R6hz;^UMXF{30B0sAp&RjI%NM z#($MK3jU~w-`25f$*C$*L|6q&<7woxkBlhHV}>wYX^_Zy%i^CKO&0kNwbz!R15yL} zH-EIF9=7J@fda*0+3W_uR{7rC;?Ra94u4(9<`1#pKk9=QbNE$6oSBGD96*Wjo;dlX z!!c;ivM|h5(fykd9hJ|UG(D)T2OjAZ(~nD%N1V=3D%iO1mHvW8$k3pkCQQj*3b?v< zOLZf1cvT>EQ>fR&Mg_Y)9;ktY8hCZ!g*YHT4p$?T>Ep0J+Gm@79ltoE7>`3Ex(1sV*^J9QT$-GE4>>7Rk&RJZGbp?{J_37&5_ z>b#irq@cZsW#RMXeRyVv@0l>T2nmFa6ZxvTxK*& zK_$B+Qhnm|;pOW__4MUh%8_^cv4TB#Wjcp3M(6X(&7KY3h>h|eEO?}n#4RU(bZa1B zM21M3CGn;9=_v_zM^^S1eXJ9B??FUlhQU!8Tn7qWy!66CCwPcrd6zm*`67LcbRizC zFP-4*)AQ$2<#{FZ^!N5C#;ni0lW`B{(8%DIO}XR-d@%fIYK%s$$QEth_|Ahy!-lnZ z*P7(gTFFl)f-ZOVV&9)PBAo~?&m0G^8hj*lS{iqx_-Oz?`HX4>>-uGYMW?qX-5B)P{MDJX!k#mIn z?+j5&OGW-G$y4u{F*S7>di&BxmTyxJeqgUr#NcSWfFEgfJu_BjI>#@a4Wg>EQFS!i z9dG1zgBUB|8@;rbX-NyFc0A-m@F$SD(g*V;@{00auP%|Rd(Q|q>O^X^Rkk?Pp=e9$ z<8pk_I{%;x%hJ1;~@XZL! zCwD@npK37`@&+q*)h>xv7=qUGDP;>SRIK05$h)BkN23U@uuonzu} zDGurlx~yIb00448IhC>hAMuH*1FWk6`ybW*!yw4=#4tjE0Cw7s$AZHW@;d;M4gQeW ze54=mz!6!Vt^D= zSs`hHT#y}Xw>59)DqLHIv_uYo=?#2t0$FHpTKL~MN zf9i%Zwy`z98vN@G!?Pf_{J}dh7R^9{1>5I=M?^gd-yy?ofQp5%jpOP>Ln1z&<&9^` zc~%8efYgx$8B8kNH1WutXW4aUByiZg zAZvi&2xbI!1D*oBdVByamFz(53n@<~`h^h`R8OguE)EQM`uVST4@{Y?=)C@UUV`Hr zLi6$J84fZzaE1F{Cpk=0LgCoN0pQCtLvK|@H-HqG0>vx=;G_X?=o1)5sx=rgn1QMK z8}IlJvj3Gpu>BYBe@eke|9<%utm0Ninv|LJvYV5SjYRmM&z^EOHUN<21Xv@$pvTQJ zD%te^_J`evfMKGeVWL_7uXq0+A&&_JTQXkge|m#R|0LaGa<9StaJrQF10<#h&sXu% z*vi1@&UlyXtFU^IGa!s*rjNXaO0)-$z66z*n=5$iMsO?(aO6$^Jh1iaUioAm%o+$B zb;T$;EXW67!JJ{B2!`fAmbRX6;D1GZK*BKh% z>rLpO6kNkmW9yGmMUc}L>=a;=w?BbvukrEr*>z0g(~f-BCt1pplWtsHXcr9>e4P1niZ)ML4%5l1x0UK;{&a2#dkO z17CQ%WpCvcI{%N(-2lh20LH-bm?3 zM|h%NX7sAKy~aga8|(Vg*CBfSK?kZ|_8qJgMdav*FJ8P}W{>7A34e7O<{C;P7*YOt z2V|&IQ$BV2&Re4}&Sm;rnVy^j4p5%IMlFT$bM1#*X48PY4V5C*<$wy~gYWGi5Z2w& z@SP`j4_no%cQAU6K=)3^Pvu49rLr)xQn+2B_o+%|taLc9*qW%vl#^%*hi`Cug75>E zb;IscbL6Vuxi<0mC9l}3diA3DkYD60Jfn}L*Mq9Z z)kX!3C)W+e8?LHB<0;@>RQr*i742a~yC*rqDLkc*tD=p-vGXwxdbms{3h5MD=r%tr zY%IMr__hC=ASr+P#|G|F|I0$G_iulVr_CSXXGIsi!%2x@ot(2=m0IyM@v<7-xL%-D z>0>D@NDlU@7(EooL=8icCQJ=rQ`E6zzktIGS((|(|E*1)|FfU_VeN5t8k}tj}uH_pf zhd-x}D$_@>yju3Y#j?(~bsg;P4n0hLbdITDVD82kU_oM^fU=%V7S1R)vRjYyE0U74!@kSsvAML1wUHK0rK#{Sm^X5< z_?p+8pGJe9XpCu>bZx)1aafbg;*2V4@QAgr>(;c0Mf;)C`fwS}Yrcv5zM|;Wa~lNa zlSw_aYe8%Q;zGwKlS*H<@Lu_r)1YGdNJzlXn+f%H25%31h6}bW?S#I^()bNU{4(HgnZqefA__>jlmVYac0Uy>_ki=yAifMnYBlG$1F%tsSv z`7%m<#yxt=JG4Sdc{f|*rwF@!9Cow;!zcOL7B{nwD2p_EL;y2r7o&Wg1?;e4c6;2w zzUaAq+tf_twOv))uAP#`tMOFaZjP?^;^RK@8)PTG#ttgHR{r3#Xd0PX17R7%1BEuG zNTa3D?22m6{thv6Po+B?;y^_uQhqltdwFlpB_*y7n}AW!?QH z4Mlj*D%assK%G!)g-NuQ;EMT%6=u%+2 z5n1gw=NA5e$(n{=dD3DN?6UbWC-5gU7^7S#=qr)%PRlWG36V0t6ugfEt6c-?m%~@g zyA1u>TdQt~J)IRzGH0S@)pxH_t%n;|iq$s!Lp$Fk-7{Ss!58j()d#X^aVgYs4J685 zc1_ox*ybwQr6~7Qzv|L!R5JBvP5NwRTx%RRZrmvq-!h0V&5WtzKb@6 zT~_;wY7B+Q&+J>eizAsUAsh|&&}l`o#fZ!Va=tozE;6Gm6T3$_rTWGrxh6yR`9qZ+ z*{3YDx1B;kGHtfQ^S2*WSe4dng4H$xDaemM9$smTbnbn|0*pNIL}txACSNS+-8H7` zGln0&z&uW`cpvGMfEysD`Sf#O{zv)qJX|}G;VjjL=3gQO$iWXTrZqkQyDiS&NZj2{0?RnW7TALj<^b0yvM5L-lPL1;wZcRhxEq%GDY5 zP7u?3en_s>aTP9@(0{BVeD4eUfirqCO!?~|`#4&R<{8COZTk#$VvpF#(6>dAb|?y_ zGy=*Wt^&kFu-*l!w~x`=qOdM*Tq-hEoI0ux=<~XuW}nLR_{yM^4qpmD?sTUr{T6q= z))us5$J>}bXJP+FpA_0m7HhMKXYIOh6p@P$+Je8amFMMBb|T%v?hmMfyLME{h`;s5 z#!GdJVoR;s{?IaRjc!Xt*PM-4%61EdMft!+EqM zWp~+d*Sz1mPQKvNF_RH2d3&&_S1Xqs0yp_N#qL=+UJP}RuB$bx^RPsulvWGh^@nh8Bzpub);$!Bzn%i*OZyJXtGE2s52JSEmkGa#vM zb}g>pv%XneN;Ku|-zdw~*-*!MD4KZgv>JlU-SX46Pt&9C%#W*vUsUK-C&TV(aZ0Sc z?G}OWP~v7-iQ;_;ca)1^sN`2HGX|P2A4!pfHJn!$>=tUYqajYO%nejilP<0sbO8zOY;CN9M)@|^KexD>(+4(L%SZnO-O%u%BB25{e zA!faX7a|X-4lWUHq);eFz{#-M`&rA8W|!b98rv0fnnxPWP)t_S&MtBR$}nisaduBecR=N6B8!vPw-8}fzA*C8jGGjv4^;0d?CAWjixRY#Sy$@|!I zR%&p5@$g#?_Kaq=biraM0@^)+Tg7qt9=!1pHLie(k7ij%Ce;_%yBe|YQMF0O@Z5%x znkVN=oDt9Uzh7+f7sew~8GkS!JE$>`4L*<{ZWHsdr)lQU3DLrfw0biZC+L$#I4>ED z>i8lL{0h-b>*?)==H*t;4_z??Eo{v#^8{-+FsH*r zeZVMYl+k&xGVpt;?~a@GI(Lrl+V9LF2GQZ_4D3$J;W1k~QTYN}MCIM(-{~KEG+o4_ z+X4TBr+kGJ%}!{)l)2;$&PVA7zKWiH0YB~M@~1rX^nPvi^}c#Jgr?qeP{q1_0&&#I z>+6Dcf8ONXerE9thYw28GX3FMd9itp$f~izS+L2BFHXG??V*(<(h{>fODfr=X!|9b zywP{Y#&SS?&FN7H?$^Pf7A2-D_(6RnA~tI6gl$|G1vzN=tqigf9##$9`@(EaWx|v2=dn!YpkeZ zhLzo8eZ1uQk@ezqcv$XJQB^zGDkDt8Viwfb@neEb zwh@U5wpo;gXK%9;3@7VfWbyzi*7>UCj7!$zkd2ULi2#~d^q{zmem!QE0|u#3kp=AO zqa-H^`FX|eLSN>)Ci(3OqwP)&M7ZPu(;rvT5kgGEW2Dg~V6PjvC7#>QqO=VZ)T(xQ zHg~_`wU5}5-Cm>qX2=-$&VTTR)K5ofA}HHkMr8rnGT>ZlI!;zov87SNZw4E6Y9NoU~*?&aQ_ncW#R!{Xz;1&S&@;$hsz$Gy6x-$x)=}F zLnpY6`$HS7`V=do+rA;>1gG$OB4(CyWmSYFUCX9S@*G0~JnQx%3o*-A{`3M1ta$?) zPeNMc+O|y(`oCFy^{UHb6GTc{3?oa&5e?Ib%Dm7z!`R`)is>Hn_2k7AbXtG<>lN4D zm%(Z5C>O-=3*y)nlg}rt3R4GE?DLm-*nvyk#!2fc6{7kZBcJ#(2|1#Qb3M2g6cWyAR zPQQfXb5la4ktbfm^9`{U>jH@=QQYkWF)8m`Fv*-XB_$jt-6!2duXNbY7X>~&tLv@X zZ${g)RwJrjjcB$K&dn8V9?GFiWYlr5yQd02A@#R@(PJR3VYWZ^y%utBp_dy=6N1Y; zWNYkEe6U8Wu{)or6_>yFDm%1+g~wMePk=8aOU3v!I&oo<1O3ipb;xsXD}+r|PMZ2N z%ZE^Cq2`Hul{! z+n>ClZ*%6(PJCx(TsJ*8PM*{;uEOwU(f8;_1hWIuwS!BAOCTC}!Arj|r~aXAykd6$ ztBzhbySK5Kd8;?i>swFDQ^cV<(=uYBLUShkzLYse9F$uUJ*$Y| zBoU;&3Fs)MKJn1=3p>eAa*R3KoxFy#tUB~HhudI6^=X4W)a^|c125LHj=xlTKbt&q z)%w2ZY&N*CFoHNWct%TFs3_GgO9eIFc`;h>eU-@F5X-Ni;R-G+m8XKa$f8HeMDONq zpxzi$%}H;LmA4hs3Qpu7;74*+*r5 zwBw%YWg~32*?&TcLWw6dei&-F>#3ySf^s|&NibP1k25BZ=*-bUfnm|}RuWknx-|Xt z6C!OO{t%# zyx-b0u9mI!W;o@#9k`8k1w|0Q8VhSES=qCntVlJ-J;uWl7d1RwgYQ zpyW0mpf7!>70fDK@ZOsZ^!ly4WWgOfYP&!(!~)UNtTy7?LJ`|nlh(Wax*UvQKmLj3 z?ul!KFb&}ePUTe3h(4u*8QTR(IwkXB7z^xO+X&dI5r z+S4te$~AJ}n89Pk5xPt2+v3k89IRjz4(j{7qN89i{YC0o_`FUTZFv;j`kj;W2UB8j zIvGQ(0m?uilg80D5kb6Gf$17pu0$dR=1q3eg@eh9_-9k`s^DHoDy{qV+m4?FT1KKM|FiA4IGgItjxxf+WnTLDihleKCHfxBJcE_k3Y>+X@oL4&Xk4HM% zu%2!cxnHi{t;Uq+;!BBO7KnXU`#gIUa+#|BgOM~)zLDyhX-BuV=RBp;+PJ>ueKrQQ zR9`RMsHY3z8L45+0DTbEZ??4Ix*&9jJ^I+9lIi$o&ilT_1DZMJlt?!@Y5nxeFx{}V ztK0!NdHG&zS>3BEa&PWI%(5o_e&8B%|RO1$Q&x zPieWLw%}(uC*Oo|;uV;nk91Q#i`KfZiYKx}X{{N2XX3CO2wP)EU?!0_#0j$-MtAQg z4~dahxrARO`Gz#AQpQ*yYj6gKHlxCNh?`4#p&3yze0qkz^0w^~jfR&2Q)^8KLz`!} z@g(9IK6|{QitMd0k3ru=Zi9&*nQca(6sDlD%#>*xYtdW2s8T=i=$%#hBG_#P;iF`JWR|^ENy1gO~=SG{k0@h<&;sP)Vn>PDULzS1W z-?H34lxt*K4?bH_naoB9BiO5t7Nd_>(H475F7!{w&3_zw9#wAr6Tr*}^|}9y{I-FN zrIbHmXn7#Prw~3^s{%V({$Wi{>3bo)_iyZ3+Smwcwu$aqk%>Hsl3kqf?<_`F!$f2^ zv3h>RC2B26h6A|`Hg29npiKkVB!J8Tf@;UuLSJ3lfoGm~a<)D4F z@s{Z++a1*sVnn+OO=v>g%;uV{Ry=cHo0Ej7n%G&2 zww!Q0k%e|_)zI6V2*gWuk!R0!_r!lH?p=eOxx$7!9;9f-VQ*twC8h4?n2wlxk4b}& zhpo7l6hKrX8!$7lmUSfWtimVZ{^QO1)`ay~2QDAz!(6Aut4O(q<9gn5ajJ(IK~Kw2 zk@77380eHf>k!lTH0XA7;_Wf1WPFd`e z#c+dHFYhcukVQCh44xo{m|6T5wv>c3dOA+{q~ZBC^A!`%svrjo{%d)KLaCVK-Oq=X z*G6dX6iOjM$a9K=CjmsA7p+T7Px4Vn&J?BK2*0?Hz3P0j!~3efYJ)dR^qMU;v|9U= z+BBz|ryQ!a$%xOF;~B&7Fvu2eTa)v1=^6d2GhS2>ykOK_f2$P7_jvM~rypuM?R>t` zVlN|3fM=&1E7Vd@>hZ%G%tv$_@`bfx8rcZ_?ela-y*o~_e;*Pg`Dmb9aJ+dJ3M5Ya z#DzU;*1~6mX4)9_hS$i(2L)ANS2aO8tBse4ma;#iyFN0RJ8`8Zjc7)6hs3#g(2`u_g?HhU&^c+Fyld#%UoDZN?Z1ncp}~E|xi6 zpzE3SRTX-zv+`ULp7<7cydH3p(6MsZ{plRk+fANbZ8~DOhm32Cn+T&*dw^ok_Bq!n z!+Cf-Kq!^TS6iHwJnhBgO6y=6R=vW3SBezkD^TZ+Fi3sH1G5jpva?a9|MHbNp?Z3| za*Wif>UOGdmU@c*?b96xR|b_$b_yqxCfiaa6k}{p<2f2L20P3*<&`AF(x1+}2k@$! zQgxoY$WB|lyr1i`67(#r+;uM|za7a`diV8xHyhE*oUP|e53c-fO4omV-sMPenO>eh zNjxh=wq);UsWQOV7*l#=asKDN#KVG$ z*9PQ^?AgS%4s+s%0jvdSlk;jc0BoEj?~)NaPK@SM0bZPY!lSkxfmBud?$)k=#wCT^ z?l$`V%x@O666A||g>>lbVCS4li6CYczBU>JY-?PP*Rryt0C-;L`kC!6t>R^uQfxkIev%WWvPhy}#x45;I z9=BFfTfR+>zA^rOXc`SSR`x`$`DdfL{jF(P;lfKiRj-adDJiQe>cz7|e|mJ)(SGJ% z5qq;6+zN{ibnXc?gwjq<3rXXD?ff3aU|Zg^K$YWu=04aq#GUgo9wG~s&TP2 zrMXnBdyAO5{ReLyv)UQQ-ugPwxY?ia3>T>Ln+>Y|W{Pj!ooIPP$zD6{MJiOXty`7*$# zbzu(L#J~Gk0KW5LlBvO2Wa){p_Jlc7{f~D&dF`cNj=!XN>Ads&7{Ph&6{#@kSbCVO zpo||oWA!>>+1x{p)*p>*;Cbgqf=ZJ>vw{On^3DP>SSU>|mMG_^C%2cs^0D*tlvqMH zcHXn60*7oJmCW!(X*1ln8kRbZeY#Wn3db^SKJg)+Y%Dbxe{Lb-qh~&m(RIB2{?!D` zipJ0-NNq9|Ry&8*WUfK%qtUs*@bX(}Gp!14NL!UTWnk^|q9$Azxw@039SZP@8m2r} znl`_to@LW%7RDfxZ6eod|JCun<0_kt0UEm_M_H8S%);}w1}>WgL)vdr2F@`Yys;D2H+)$txAQat z`Xl>c2Vt787${x#n^r<$dN_`yuj2c7vC@ctH)5OzHL$bzH(ek}eKljF@N|Srug<{;ZapLz_XV*FE~} z3pE?*i4NiQ$g{e4SOh=9d3IWLpDkgAhg-Ee7P$74B&-oM%=n0LmI=DP;PZ?8P`SGM z6Rm@2#wBQ%c&?_yIG>!3N{>|DjEcKLhfx4^wJdUZh^8vj&it}+7cj6r;d{n!;hy^? zsmEFLtvhv&Mf}pBfY#O0as5f@8;XKV4z*r+^l^KdgSr*>_HAWontw+)o9-;Ly*{bbl@)*LM4-?}n6I>9c7m>f z1mc~w@b>p}>UY*0{nyLdb312@&w3B*a>hFHmwzzf$EWK+DR`vRB@=ZkADXR1+f2Rj zXRjOZvUn<}1@~kv3}MW~S$%#Y0*w|WKF+VxY1cf7#f*G}Gah5UcMYLG68Vns#sB=i zz%nN77GL)AZ-)jXpm3wb{Y89mb5hW^v7$mow&fqjJWe$akD6soR|d;!p06dH?l18z zk2%+Ncwx~)t}`n7hwF8orQx6>^00gI)#j4nTud8jzsgPLWPiDjNqBGky3R+&stb}j zp)YT)l>k17JhmPZgotp z$t9QCA>wv)wEBwGV;xR~v}iY-M=%057|#LE!n-OA>*ncIPdw9rmK?#O(uq?50+i1ILBw8n`hgaRjKS}&H-MjkGI9KD`ip}b!vpUyFI%(KPr zL>YTE1Q!l4(?@!ql69ocQ+sgqI=IaWuU1+qKVPe&q9pyYjg(Kd7NtG2x=eTjAXd&EZl7;UCO8^e0fv4ceo|rUVh}4KRJa#IhTSGuEx=1*>oc#WUcF{5iCl)(1Mp-G-?Dl0lwWFuW zCqeB5Zx^A3qUy2EtovQ^jp)Ik>n$LY)j0CEpESW+rIf`;8Wt8lv4SOeb zurDx+eiN?|YPz-nq(Ml75>a`ADcgD{*ZJ?CqNoB6lb^3X3G*ZMB%6P%5auS&HRrx` z;k?vgOADEdDBrJbIAd-(iGGen&&6c?%yAVRE!SlnzRYe;C*=yA_)#wpBWUBMc?w3K#QPP2&DmiG@_VW~kV?%^v6gJw^wPQJz@uZR6H$x`Bb(3tRtwRX|?ew}Y ze{Z=THn$u2;R_n4N@HtUJK{Uv=qXvc-J9Sk5XXOgj4!gZavzCQ_-^pk?(ag zrkbRNwHtyvsVx%_(Z(mFq^prcfl=l4myN3tDm+^gr>|M5(KF{#j#-ZP;0E%6C= za5co#Z?JwuT*0^HPiZCGY|j<=(XqBy`@P4MzOFV@CtOc)=9-+)$3eW z)et&lBzkafFKO;MeEcJz{{a|T-qRNRSzUvOeMST8bnnIz4h@&|BMME&MtYrS9ZM@u z#F*RTF+cR(oN$8{5TZeLRreYFJedlil~gq>@jtjG4sU&r-12KcEBJ9wDpP+PP&t1- zToyvGK`zrL+DLPl1IazYsh)u>V03PO27p#u2pB$-5eEY*%>gE2$eo870I;>u{CTGY z{Rx2qa0vGQ+d;6uw*M2{0h4K-_9FnH1yF}T7fHi?=T_&~z#Y0(8CU-z4V_*16yhE5 zB^`Mcbflk6Vx`6tQ=__%i^{=%QS&Zj>c!g`QD*)se&j)-ygIXpVDZDpEJ8p&;wza_zJ&H-TVZqp6&2$(apOpBGGuus=g$O)jc%0ssc#)}g0f-vSfg zJz|=r<2Y6plJ4hK#nVf{SW2MbWty2qyBIs?kHX3*R$<7ikNIqu#3_T{*GU`KFqetZ zZbF9*Zw=wSkwkRo2AI+E6H9zTme}-gIf8`1te=GB5LIdF>*9KnC`0lAP1!*${zzP~ zb12j z`zjr%0u3*aQrt*CkHf*sOjZe>T)uKTG>AS{mwO>F3;nI(*`GJ#e{XZl{uy+IwPaMW zs+^$uu|`CG>M3iZUBz;C;TOxCMWnNfsb<$apEXa3-ipYLB)&Yug;HAt`+({$=5pWe zL^zTK7m~!a6 zpQ?l5BXg1G;Kxs%rR+bRv|jY)n&(>&L_N%Zm#?t$)s+hVxR~pcf_7B90@5$( zkZ2}r*PnT^4=c?D*;A}E6GTE-Ecf-#{pTVS9rep*UWYJWs~c?F1}kCXTqwe|7b&nQ zY{#rdcn5MnJlkX?@QwaN2xr(>TdcLO*_`!ny@-)HdT!@nzJ>I7-enl$=3_r;j?6Gu zxsR36RXX-;sq^rOw;#&XeXb7|8Rv#xV|0oSiMMf@1TSD)!;aO2=jEk1?wF`OV_{al zQFf}ehSKx{cYx~g=M^w$(?x-p}= z+;Q*3emG2>=xDTl?V?@ngX2av;!Vn|5YM;~iSm z9!GI87No1^b+$_VqS(Vl)ln-==&J#NcZ?au5HV3UH-n%eV}G-TAz6FI*@761MP!s(GA zJ|7+q|CnvkduYVzQJYJ1sqrnNC?NDJlY>X?S;hLp5L}PTv5=PM#L_>r3X_27j}~lE za}7teVl2V(q9(W2I0`0QtZY+f6nR{>RV^4(j@;d&Z|Z z6Z)T0`hX+%qm;$EBAU~#_ARh6{vGcw|Mxdq0WNXcXkR{Te-i70>;1!jA#nsr0#@SrNN zU;uyzDmVxx22r#CmB)Rq)cAyl0?H?wD1SPBC=D%9~EQ4|R1 z2O@4B`TVOT&D}6p~nCi-Dg{)E-ArZ zo{9XiiA&(q4B!39D;!_3nWJVgCvHkHUvte;F4X!LpMTDYraW%UetGH|+4JJ62cMng z^DCYq)?^3*AeD3t5y3^%e;-OB4TTr3=AIO|rxDqN{TvDoE|2A{`R!BjtHB^rjb@|C z;n}LKpg{=iFgh_U_-g>3k_axCoxzqnpB%m&e4(~wOq#OVvdC_OFk^xc~q(g76&w4|s}S1$e+jZZb5*3%a@BoPG8J$tcsNbF#+VIkvXUkd(wb{ zEF6`ZydJ6Tr?>L0d*rbh<((AvchMsLAo93>BmX1ZUm^m?PT+cs`7JV5FYaGQ09h~; z26J%x3XHHO-gmAb>FiDq4I96kF8x2U_N_d;xcG5F=&#UcB|zt6c9e zswgxa>DXu*Yn3S3`b?va6}8;&$RTX9Oj8p6*2OtFX2#|K_az%%{%lAO?>@#Gc{bBx zlpe>UGQOCu57-^S*5A^zT6P-c*YFEFNdx$*4EhrS4PSJ)`Pg9XF{^Ik5(>Wwf4jOS zSq)>vmH1JHq3cM`>CGU4)z2HoiblF;sm(A+DyimuwtSS|jWi%Tf%`3`8Fel>APjRoO{tg^e}$Fol4QT+g3IJ(RJ}Ty`<9kjS*~fZ?X9M^A1S#ej+! z4^c~3f%L%8G;RQo)L@lfzWcKkYi!m?)Hn&{V{-UG8>L%0BdIHg(#<_=g%@EmoGtXq zTiH2~WpKWAL$ZecW~WH3iFcAg<9N5jwE#H+@C(GP@?OmdOpiz!P?ZKNq#*u?&Rjm6 z4}CObJt>qUz4eqe;#QeFboEgzebN#1jjhSNI7&3 zhs7_aY!ea1B5|_XiH_#v0(*4cNR=}4(Iv)IEGh_C8;Gb(=FJDi|0DS1PBQ>NTRo8s zL76e;>*7{sv_VDFmzFa89@7BusWOfTw!++_`X+xGlIG@10;)AtAs5dzOmYEv7Lm81 zRruKpd&D2iDdp3iwo{Q|SmU=S%Pt619Gy&Xt$aN6;J1Q=SD3S-ibZt5a_; zPtbyGHpCQ-R<^raHZbv&x8m%kSC07g7@d{Cqg#LWXtLJ$a;rqtuRDnMy1OjZuT!Ar zl+1FO<`zoJUqu$Re7LBC3WyNmVgBu%wDjj*Uw48Y52i`!`c7^40J=V^`_UT1Rs-l+ zYBH=fmZpmu`b#uZpE0+68-AT2_Mu^ec z4xc(wrXIZg{_(8-MVj)dQs5LX1^&x?D6@_JqAYDI4hNono552}2)tzC1oq1FOF#>gH1Kkn+v(az*sp`F5 zk!|A*)IHu&nVW^ML#26Xq93>vWgEukjXCGOGvb8u~yK3j?C&5EEcz(;uBx=Z<~tob@pgSZ2&Fm3trU)nA$S&B0jS zm3tlGj_PS5nx$5TZ9|5x7RwK>Xo!66G3ePlp{^4y zmG%R2U>n;c-*eSTi4vHYh*I+1Z6jg$$SD;C=G6OH8E5QPeXL7Om6B78zWU43Z-}1M zyEBW6o#*<#A< zW%tx&ZxiC(T=Va8g;{DR?3c`++iBGA>J$(lD+ACF_g9;5e4TCkBRNEPr4`>;TD3XQ zp;^U*_{XflDo;#fPQ-uA|Ex)iwsw6U04^~RGFcPrBA zCZ9AFXeHmU%{Fh=hwnlf{d(mF*g~6dAuD$}>3frM7sN=|J($C9nu^-O2%{BW5X(p0 zRY1gwx26?APRl>%-fVLNAy4zU*3Dmra9j$heddZ1hL{UzSq`n)BrY$q;#My_Wu>|; z0u>rOu;1$FodRwb#yYv28Gjg`;wV&P47)slE4aLJ!w=n)XGH0paYUHiCC-X#+$*HL zcbRC(dHlTesJj_>55^7Yo+VLf(Zs1%+lA3Q3eLqW2+o6EHa&{%hCr4Korr-K)2K^{JkI zMJO-EH*j-bPCjdNTvBpx!>{{+K3LAOH!c2AFx*X9>_w2$twv%GumB1U3_-Hy|AWQd zDNABpY^rG3pLGBn>1K387)-UY-qF|41t7}-0A?B>LIg?K1z3S@i4!bax)dQKp~~&y zFo~|QgR~p(C+kT+1P?u$(sxxH@*-mloIWt55QlsrzQ#Uzbsw>smexmM7Iyts%4W&R zL}jY4Nv6)o9)l=*nBM@%sT+f-y>@2O(~Z4)eM0K=Ftd6-l% zVg|tBAnhGR-128&Xo*p(g!V&MJ1bGAN2Sv?PY)d_&!V@vNjiA|d|ptdQ&6UVl0j%W z*XF;*1u0d{R1H8uq6^W1xGdKFMzxOclEPYdEPPP`vdAN(WbT;M4EkUX*A40KE*OXx@vf%)-L{ zr&hlCFS}3=Q_!Cv&-W!YgI6$zq9fQ;uUQ#-O-}dV10147n76+6fkz@waP5H{%6Ej= zKCWjXfKmvG4H_5o|G`0#BH!9e|JOCUySRVG>+i4XVDaq7dHS;31HPS>049;U z(zw0L!BWe;ZoVq~mW@$r!!V9rM#>{%p2G=94!~7@#KS`@0-&ot$0M*-41$2H0L&7{ z0-6Z&8(?^EnRL2^5+*n88!S2MY9s^#^ME&`arNmCktpn=iVV2_ujs76Dk2uyGe z0IeVxj{i0;{tbpewikjs!D0qlU$Wp2p{=BU0MgRHQNa(8nYmXPcLxHVZm`g$&41pR z2WSnbz3kS7FrVx3?z3QVoV?B!c$o19ZKHxI)uOI>n|+6ZidQ?sC5p1na4gB8_z19Ft0LPL-Unyd2iSKq=&x^cgTo^m*gUUr)@Rgenzsu6V!9^Nww zaENb)9e_JC!7^_?|C43@XHpaew&)k?E1SOWUp%P&%%6>r{)7MTf&FXnIUF&;I;Ho8 z4cdqgy>bOnfwJ2x>{S=I&Bsz2-3)z>?nO$WAH+c3Gjb7E4`NB%fs>^q8GjxkqEb{Z_={M<7*tcR1x4IlhA4N?4DB4a{YMjE&QWR;|77Y6i ziVrA-{dPxj&%DE0NSxB?N-HWHc0VN``0k|)Tc1v)?V^O}X0$KT&qOzaQ-?sS1uOpE zA}00rk7v)c&a7X&hV?%?`|_$68MsfDL=bkvn>FvSCmA9Yw&>hH!Nl}RrOHR8NRah0 zpS>k|8gEqnbFZ4G%tRxw9Dx?2bwiUKJ@j6e5JcDz=CQM6IVG9dD`Q{dqgKn0#-tP3 z9TGM0um~i?-@E3 z-6gO`GnA2`&GkN}ir;=hPOGh}@Ff2IEozW+b@4Qn6t8WBKimg~{lk9VEnJXk znXI*ue?PkVGpoQ`jm~%^LZl#E^_6p;)py!wUvdCcVj6%?4e4FR%?+#51UGWLD2?~j ziX-FWC)GVKuW8GUx4L1`TQq{9(g0(}{YYF$i@zhw1r<4l)$>@)tyvZU%Xs0|Q!#Ku z;_;Ks1%1l*sgpiS&KkKdj4ZxmZpS?<)ji;HJ?fj!PyY3z)`RjJ!v8o9E{gj=-v@~;9TA7sqse3;dyAPkCbXjTVdGq`%@s^S$tIqjrU zHLX-H0UgtT*Y26r%G}eIG%6lHGfM@kKG(j?3gMX!;K}yvucY>SjwgJBw?B6&M{g#e z@%lljspkep{9}K4RWTS1J4OE^tYf3k`SBTatkD#%NOj^hZ0)nC;ZH5|-$X3q<~co1 zhanX+F~=r{U%po#!t50hX{cQg7`R6tD>7DmS)PRwFmftd`}Er*BzMWEZ>ukkG^!U- zC{kr`B)3+dvwk`}Iu^EJ=0^|c$$tNfk`6^f#Awsan>A(*g6ddF;Vkp23-c0Gjct&u zo&TaQ5J~`M&6jTqmN5XYI}(yKAq`q06>b#NpJ(_^A3npqzSA$1(r_wqI?^QF z^EgpbbBIR@7S|BL4+`(&D~~sxz6ozLB?7ROcT>?(ACx9(1>?Kv0q6?JwC-p}08&og0)P|C zhHZANis4;Mg}ul;hX@J=@z;a+|BI@C_!(&vF{&m8=6e1pLa7`8N{6P8u@^w}BnR9^ z+DQb`ED&-KQ84oq5(frYA7G7xMMDb@*R@xVAB+8TQh_FxP@m}y_Cc@q#9?V@N$t|R zqV5~6<2l^At7Z>0lDKA$t`QW>^t~1I>{XidA;JQvNg#rTW*V$Z{41(F>sxH7x@!sm zIqC_+n;%i@j_|>SjsW%{zg|Tl?hv8gjXTISb}Ih+dE592z(Df{@*my(SDM(r)HgWp z5dg|G3Ink%jk<0I%zDagsfdoox&sM!3OXZDHCJI><6PI4`}Dai-UpY;PwZ*v#j7FY zN_!MM&SmYl(h^8@T{H-oAIkR-mP9O~}>q8DBN1_%%3E{ypHKoAv)45o$j z-B~scweDTwxJ5QA3OJ2*e2!2jH=*IWYNQB!Fn0~My;d-$IrwZ50P_QbClgkK#eBm4 zYK@@v?g(^;2fob%jDyGSk}>Z7lU(TW_Vs~0M^h6#8S*9vZYQ4Ey1n8WpMxc94q&+g z0WzXU&aj51u7tTQ7@#8EBm#2i&oDiFa$TrgqIfi9k=dyspaq^~fGSaR5JL8SE&E;t zMTb0c8&^aOF??4?YE^!V#mZv}lM1c+**L1S7OOv4;3KSnc1_R_PZnK{fB}Hxc${O2 zlEeCh_y?uwsSrLaHE1U<0J(`Yu;?A2-VHK~b(uH2MgPCgubSy=XShXHXTz0~K5+9w z)_3Yx?eccMR+I&*jnB35ibf{`4|^q-XHxiZCu+B?8V+HxaE4&ChB9x|h%;>;RsGU< z7X zxJ0t9#YO{a(Qf~Kw0Zlo?Lep8@OpI%&1c3G2mjl~?yCZ;sx@@Mx#u))5rta0eNXhA zZOosFwuLvnV?317T5)0_q@S&C!0jbyAvchHNR8y8=jp`QGD~MlW|ZR8K~6vn4@N|H z@uwWM@o=|9Fi?|4=LlXgrrd5@*JVw=IePAtD8t}ba9d)Lv4?8IMY{8w%ffLg=h6qG z^#k{rFbqxqMTPu9=H`Ytxb0FCS*}#`?P{)x;jn?Q05y8j-=W?~&Wq(~ zWgey|za7R^x>X*gaaskrRNrvcehzBY5xI7H9zNv}0enDXoacE+Q;hLP$J0-MHz%LI zsGleo&yFHz8uSsCw&GXQ#1hFPKV^Q-0FuL7@)s(ax%heUD&ACN^3F|pBoG5#8{?*L zsvgIS-QtxQDmL5!Sf5IphmSd}Qb^cvevIW^haeq0)a5Q6Ti(a^-YB21aw}*F(mZBY zbZaJ}csLXg*EdLbshYs)skPcPJ6_+7l)iS#8O&hlSSc>_N}l0>fZv3?nr05XmC@0wb>#5U;e~FMHv+HJ!pS#-h0vsc(g7Z z6dapFuZ1UzY9I~+GnS%qa=I8!!C;Ki0I_lx%>%i`m!8kkgLr^bVF{UcF)A{Z_mUGQ z@UTeLfZw1f;4aN|+&>MOuD_(XdxdKt{(Ql9`uDLvA_5(_PX46*N=W#Z7nQ5>()^Fk z9azD0Afh*?61D(9G^Yj8g2P}1B!8MA?*d@I82|wBS97GpTHlK*7Oq_r1fBg!^^1O%{2RGzLvL}$H&M|-)`EPS?iLHelQt! zB#2@A&^9MiOd2W)!^x*x=-r=u6MRIQ2c<6CNtbMj(w0z~L3buIfFj;2d!D^|;6Uv9 zEKG4OR~jrC+s6LMJJhw|>obSATt!sQ{yV?irCBk5C?eM zkWFv5WGi(w_B@;K4>moK-t)e>7OvzA?1PwZr~!-e2n}du{x%*Gpw9V=I$K1HbTugHW`AdSjh_o&?M{{d?DKSp|-P zFHY3@70B~m04{9H42+`#wLC^Fg?bp|$5QN?H^v%L+- z+Ew<8F4^XE^B>O%M)e6p5i)L`FIR+zzBRI4aWT(&?_HRC#JEY~?8gv9>D2Q5<1E>b z@3)8t^r~D{Zslh1PcT{E!PQsd*R92w>VA9eBwHfXvsmzmULEC~U&@F8ViW7+NU}-& zRGk<{ivG-JSYTWk>!unj+0w0uVVQc-Zq0dBwtO?5Q58(JRPSmBiLY`pCA_L7-!;)d zy}q=_n>^UMHuUwvLjJICOsuhk$T|_VFG-5l+wWC0i~V%eNt)wjZsP1~^fgb$rBgL$ zS>7|-XE}mnSL` zMCJZCyXus~7t9dG3UlWHx-W_fA0<2{QCCB1x{j`n1yO0+^c3#y$-Jnz+CJZfP#cl)Q3%6 z?=?I-oT{l2r9t3}y?Gj3IGhVz?rWiF-u7IuFcRl6mU%g#GjFQ5>=AXt<|X=-QI7ex z^mfiB+=u$gaNo49D!#&UzsEay0UY^AXV+@5)HgG{$mB{zHT8nnXTK znaB#(v3UqD@$CaG`U;@J1KyOl<_Ro)l00KU8Hi8~pdnw%Lq4GC z1~mXtR)Hw@|B3Pr$=#nFi0K0H*Eb}Mvp*kT{J7{m`&5Y}5arT$B6$zC^Jio=U}xJ@ zB3ncHTy}h!VRT~}Q>!myV8U?1%@#&^5hl-Rf-s3rE;bLG)MSW6cZ_9XIuYA~Q~ffE zcQp7I4Rl1od>BJ8ET0-4lQZ+6hm;hdI3(9W6w6D5s;ni)zt*7r2;7(pMc4umT@Z3Q zBpUD5S!Y6uaf^4s(+0yTFGBy3*Su}oEicAYy|B4UB+K+}R=AcXRwUNO!;pX( zv9~iN^aY{t4$<%>8mG_}HbeSKpbNZl!1Sfr7#06Ln*aUG7SKaZpaHbi!9hgdzC%oH z;BoiH4JhaY(f~fC(@cd6+0_!^*HnmX6FOz039SW`7_{~JJU3X=tSt?j4Dw!YHQ?op z4M0qg?gxRtg=C=nA~-v7;f`7Wa2~-EP%~y9PBG6&bC2h)WtJS631~I-%e=+>r`7b| zBnU&Yf5Vx`HCl|(4`0+^S*qn8C16N0Y7Q8b-xwUp-?hbeeDNVCR}0|IebkDo1q%FU zPBD{-LtL9%xQ?x)X#lAiJ#E+h0LNz&CHol$J)p5U* z`+dvbShsq}s7JcwU<%%&MZGNWZwV`6NExXle7aZ;d9LC}B(Q__wabE_F<(CGV?uQn zbI_uxV#ESgCLzt7l1z8gbcvWHp{iVRwc{N^Jq&xR~3)ssH%meJ3H*j@#FI^|B)rGaRtE*TAs`(q~!@b2D$IUygP-5sZGCu5$W2XY$mwdTRWS3_KiK2 zMNz$9x}=O{aH>m@o^ZS{2lz{^6Rp!D0?l8Ba2T!D^%a<-tGrJZMEP*tBoRX-Y+H%- z9Es%>PrdYI%LBb=)!X_K(|fdd0*jBUv)3v}CLV_@Pd=$JU>KfnQ=g9`?49pPU#^pU z-oa!*w2NGd>wp}aRG)1h_H>7Y`Edz1`Fnn~!P;=%wlK8K(4dIkv0wsOO~ZV`o8Z!H z^-hq4?8{^m{vjcMRXzD@3IaX%AMizI6f@ux6TJAo%Z7!FQ{p!gQKR#`!RBt3vNMlM zMec~LhY->N-_LEt+CBV(P7;=;6UUH?1yX7cRhTMQ0T^4ok%SmBw)S{&mv&$&p5Sid zZ>zdVZL2cWL}j4!^E_L2YGCoSInop8CUNoJBeOZ+s#Giw~a z?=5$x6PLVp)|--|X}6wn{}*|Iy#h)fdsEKmc8(W(IDXl^kI^T76@5W3+HWsFY&{7l z?w*PWUENsvdcg0RB7*it!tr$mFTVO>&Ak5Jy<(7 z1*VuzB7V|119E_D?i_P6TT}`UB-sXH_tm6ebx_O!NH)bks7ZBrI=vtbakBZH9LV7M zhU}4(&~}b4jR(>%B#0oG<{KglsJRy>qFwU$L{hbhwUclcJn!VOu&^>qW{|~`w~2Q= z_A!xI_fZfZ^}yP!G>_;|A$4gDtb1=#Yg$r8@18>`w`2_CF%J*K)njB*m&yGujoN_H z<|6@CW@Ac$5EBNcp}9Oz;Vk2Sj|T`qbkQw_N-*_CLLwBX7h0W$k@zNQk;R z`p(c@;NVIFRDzQHgUGzkx)T8{=kC?;961L@uGEYsBQHCKxH|%Qod^J1w3ZNAq!S~2 z3=-%nbPo!}dWnMI*p?fPfa)d@I}uqc*Sg0nb{Qt$FF?cciyn$zJx%ypzR~Uzz_TmF zqbhslK|(vT#zfjhp4it1iNg@l=t&_ORmq2xB|Z!Fl9VYTQ>Ot74G;7IdA|f@h9kk6 zGWEzqpf?U>L0wP7d1lCV)$=h4yA4rkXmrxDgXhn z|AEIPjVzW0Sq~hvf`o#UKpW|o7)Lw0s=J{{7L;4tQAri<0td;lIL*>M>Am+{)m$se|R^8rO1$%7XU{v z^aY#1EB7I~odn1VY8E*##(abYl9>aXsFIST>>AU7cOka-sp#duIDr%EqP&hv!~yggUH) z9XYc5>*oOJPg^D&l$SFm^;w3UwFR|@qMA{PtZ4YSJ2vxoZ*E!Dh!vKGX}Y-WeP$wZuHvfcfQ1AnR~*$zmCsdi+w!Bef3%6hpjAB%EuO% zO$@=5=TS?x&F+5=5JM(~M(q&@4%QBx2`>b#{m;t^LFkpElOxKb1C(Ha}q|-#dTci*YXR_~9AD z@&0ukocQG0JIl&_p@&v+GWbD!dfZ@%I{uGRJ*fXyKs1nM&2Gf0$o>sB^DCI1<^?vC z?;Vs&^>RB%-6i~tsOIs9DoF=^haOzoc(e7Tx~T;Oy~B^Dh1T72K01Jj#wmKr&X27u zOE&LUQe{Hsr4cH({I2om+f^;Pmfu(&Hiap|UnL{3dtb$wkl@y1rSAYbrdv z$vo&3o1(i%!^C->*kRmM#U4z;9Xz&96e8&2z2tjv1;2fNTkP)eX+f2-5q@AMD#Mh)t`YL-q zY$DbrC3ZeKi~7v9fiDkPJ8~t$1W2i$$Y|h55NPk4(4TnlQ+Dxj94zVvpo@IaC(ZUe zJiq@2FZ#P3bY6m?Rr)E5-2fYA>~JkRRoRRCdIdxkHm#HdZoYlAL6Qd5gsaM(2f2Rj zy@y0rr8ufRm5JM0kiiYnuhLZJa~3}a&>yVMM@xzgbI(W=9Ck-lj4Pw=*M z{#qdG7F`}dI&E!O*@%iKCda90M3MINGDbhVAwY4|%&d2RJ^Jy~R$9N#_zTQnZX~^y zTLN+}N$23`55fF39K&(H7DNX6?0}jnh6XXFHlj|cx+t+^Fi@15>3zBE$&vEIf}5r$ zQ$ZW07dwyf-h1PZ1U?Peoc^Hi{Bv>9kzlJq?f>KJEx_97x_047g1fuBTY=&Y?(SBc z;#w$9a4TLMiaW(A4#A;#ON+H7IHg#NmqP#adEfJ$^S%Ff&UFPQ8D^NZ_Dt5g_uBWq zce5yYnoUU4amxXhoK4o{XEQlzSB?GpS97&|8T`q zVICAg7n~9t0^=kqRggMosy)~)6?~r#w_~JajiSoMy~NMYJ<--QL#<3$k?HTg7=scS zjYsRuQqJ9Jn-gI)>{9DIr^oNU$}D#C<0qRmk-2N&08cYZ=dM%hrY0}-5EdV8rW6O* z--Jb!l7xOHNfIZy&g5f3W2811#;IU2qOy87$CGj(7htM-VNPw@{AOC-onTyG*#83G zo4*_51n}&4oi(zY{>J7kx z$GiD7H{=R*x6#giy`uL>)Gg@W_ZiEU2R3!atjUlrgnO%Qy%o@kWdgeC}MGxPm>1WX{-WSO$Rs0|h$VO*~3 zG4weE=NfNl@sV5iS03Yijl*m97iex_8jUIxCmZlCRStiL6WZ@FShcDC$>S+Ezb(Q< zPAy_y?>zd7L#dW~!CVRgQRDZ%g;bLDEtf-4N0OK3f=hUuOf`$vkh;4DW?z3D<2w;F z>f>$|4Tuj1)C1xZb+ecdqv6XF6!ygB=*M<@;fVffpv~y!S0~Xpwh(^X&w0$+ z4ow5s`|o!TXhgGR81Eo2c~3TpS|lQLvM(Pu$CDMcYCJW#mIN|pmE6ksAnEtKL5TYsymYN;n|CFqJtGX7KBr;b_Yt1++pmcfhkF> z&o%lg73r&Jwb5^$({W@wD*nYQG68bVSv&=kgsSV^9SlAWg$*!&n`IP(J1pMp6qdVX zy1HL!=iX9R8n}iQTQ6x`F%Vz>blu4c(m_aXm%)v_iYMX)0j*$!dSj=)%gi#T#7RMg z@>U;aepEzkqZ&SqDu#oVD!2D0>f;(xD`&>1^}9&|dm4C#i@4Kg{3e)f*ZuS3B8N?A`XxW>@~Ny-Mfgb2!iLd>G-o16v=cSBar~M2*NDODqp6KTNhZXNhGn7`DIfFl=iXFuoMX|+bqAJ`ojA$EBSKaoymL} zKVx8x^gE++|28K*siQ9nSdwnADS(6St>gQNu*WstA2mPajptdA?!AsM)w~TzVjQ#g zCjPcitQ<*gJ!U9DQ;G#y6bXOja`fU$CxiS@XE3Uqh`ja%GjBdw+%;R;r{|}Jfn=8~ zNy{i)%X#r3IytN|RHJ=$1H+cQD^U8kmwEBG0D4H?>TYt8;-cvQl zbU2>;MaI}Pb!Ii4pRLxc+jYBE$NRjeN5Qr9gRRs#U8IPWq_XuRwtBlpXt}Jb^b&<% zfSjdSP?H(>!~7mMEh)T~t@cbo%3{hd0`UxvsMqDta?&Rg}98v7W~ zB9e7;Qt^qsHO-(MlsFw@Qq}Jo)#Efi2~s@Te8uGH5Jh92y`x76H&Q#VKaNw1xk<^1 zeyQIwC;DP*LXf#-#g22n^-t)C#};&y2A7q$WU+uut7J5T3hi#PqPc*)#Q0rhX;0xJ zy2G>Mpw@jH$0_Q!GIVR#`RAR^W)wxSiv?W2e*0tAAEfS_ZZrNEx!o%muwIy)t?+|_1O(oT#rF8hQT zwahT0YShOp%u9os|8((CX?$k&weXX#Hll5axmgA#%Af|z;1hGel7Sghv^SLMW2Hct z`F7q#>Nl!YXW`SDbxljW;BNpfe~4OrZF-gR`_AhfN5o0=PHbK%cA|9qf$~EklPHf7 zVQ^ajg=<)@dj@BnBjk+rQ?y;FEM52# z`MAudU#@C7WgARrV9yQ%Z{4h{+5&Lo0FSlN>s@xItMG;FRzZqujF2MQTd>dLG8DO^VF;Y9{i{&V@dvPHNLqIwD*sW08{K zGkZ&+$(sS5mmd=fx;vb*h2;w6x$z#`_t@+42j1|;&yQa0Nj1;cAYchi@`rbYs6RW& zz?j_Gb-;ci-${&Zd=bi$C!PM2icT($){ie9&C$z$wAfuIw{nj6X-G=Ico3O5B|FG) zXAenD!^VuLDYwF+IHMc*P>7ac$Sd{uzSJat{K;&=7u@ys>F+_VH(&y-SG56(N-iVSNn^j8@#AAv}>uzn+QLG6x-9x8OAyf!>6{K_QXW2Q5P$OTms9chEwj(&0DV(LPN!h zQCNIlREn!GG)=$uyM{lDsWwvj_FE&eJ4km*M%zBf5NnQv!Q8Iumt{SPE8O8$x~#v8 zv*ZnMHrX7#lFcecARL1)hsl3_XVAm3Z5Cp>npRVm@U zm&bx@KY44m;f>EflhCC*IqDTd@2-cwKU$78=)jaa=ZwLB(`PUoSHdS*{bJA&im~67 z!=ch4ML32UH={tz|QP? z?of*#vMaD-t8p=Sslyw+7In)ja>=Ki8we;6ZJ)0dMAArp`!m@5vd4p@TwvMak9wwI zMTK6u{wg~fKP>se0O%y%pk2Q2E6cy5S&i#@hE_AiYv^OPk8-?PL4@BQy4WLi_(}Ec zR7Xa^h(fMp>7p~w(S-Y+jaJDMto1YFn^-m_1+_)b1FMd4NcJT+!8*mQX3Gf7Pz#E` ze!yF!qWa1QG&@q+HH7O)kz=*^%w0|v6mH~mJP{|QVPhE&VdWgX7;XnQi)l3!n6maX;%uYv64r)h_Y=j|FN zs5KDR+;tBcVkzGbg$~IAFR_?{DI!^2kHj8D&cF;h%8ww$*dg<48qul`=&}-ek?{_e zcreKv?3CO{4QVT9pU`s(srwr`W0GyV=~3vF%DzDe>t*QKol)it!@FOZ<_?1P(HcME zXM0DpEmjX9&=wNB!ujcSRLG^W#WLNwN9)usAkn%3NHJz3oQgY1EiL)=$rf(`NPgqpvtLGET2 z`9Uaj5YrlF8E#3R7=09<{SJ&2v3NmBjN3jOs`@Gq?9IaSOeRE-;48slO`>4>V-gkN zo5^Y;{a6!y{A*J5(M#-uvvO6-)@?chnTDni4RKMt6CCCz8G)I;^x&xEZ3BOxQ9HP*`{LF?}TE+hL{jDcowy-+YE zJtvR&<{Jw3MNs&qcAM}#6it<#PzY|}CXbDsCEkkL!$*1Bg zF5A}JyatA^&)t+50{SBYu|pVJgJk%`gz#@vAYMte5y=y4BN|PS63rZYfxZKMxrd&K zOnUCg+)5LswN<3b_c1wN-+r`t%E|d=TdV<=PCGs*!_54>Fx;(4h>&P@;JN!fXXast z1S;29RNNr+{((Yq4@YEffbCq7t5YJ#)BP~Y+5+M8>WGH&-b=Ok?X$(MCfz#TeTpZZXX@}#{#}uzk=9H9%d#nMG1%#*c4qjM@f{{OgmR8ak`g+^TuH z%iet#6LZeO?zybKGPOP`7y;8g2Wa`27nV#aOEAo#ED)C2cycx&I+230oA<#P_{M3+ z@OxgSw9Y}+;6GMqes%MRXbPw^F~0acLU@z8%L&7>>4Yr~yA-n&6HP_3|LHOZ^arPB z+kA$btJ<}rXXt{rmnByY$-KVIfMJ&-!!8uJytxrIGG{H^^hRgUfu7?Cl89b9U96;$ zHns3YY~iJi+C`6c$i|O9b!gDK3<$?rQU zU@uN&RXayuQTMhp*4cD!F?K5ZArSvI3tBt#+*a{&a?-!R0Cr12R?}-?+Z}R+8m@7# zr{cucxkFG0i|V<}`Y}3?S}#{pSH3#?w39wBx&$kQ>-RL8^R*}c61fc2c#vhEeB5&o zb;zUmDu0_qWiB1v_Y2Fy=-c~gtL~?WUuKAY?Da(hoAXw%P~Xl64DFo!%2slN+!y@m z41OnMJNvrtMxHdhG4Ek$+0S8P;8;l$k*Y4~NC^4PRKCqxMQ{XTB)ofj0_`ANEdM3P zlc<<@E3Nsc@7`(*U8H3m}8J1T5f9!=A&;(XLghMF)Ey#ugTDZxqd^{nSN!yF%e7E ztI^bpZ4uecR`()6t(<)Aej`0Ex4rS>>B1jN?Ik-?j342ydqTW3UIx&wtiI8`8S@6; z2KhQ!`6}ZuMB@6h?{iK>igR~r*T)h*|3rQN5$9w@ym)7AzB}!o$dIgDDG(cNg8^jr4?UqMbc6St7&4*l@+|1`}>cik<%Sb!a%*E0ooxn$x1F>3nxw zggyWhi49U!M8Bj|2hCNMF7P|F?%Y=&teHn_vY`B^(KcZa+7k>o^`J3kLn(8M&rB7m;(8 zw0nm(^6V^b{nw)u(zo_Pu?1)%w6sStwbWw7sgcPaa}Zv=lXcWw@uJ!{);RmS^7m9+ zX|b!`9op$19wa^{w73d+J{@$rD37o7@+L8LT{UWb!TP-X+QEe2?Kf>1*FR_73P;}W zxA`X7y{?w&(_)WYnW}pZ zo-T>TU>@}Lu>ZJ!O!*aip+E0uFvdJAn!oKa2B{>pG~^n!Uh?}RgK|WW3-%qOl<6w} zH~TGv-HPN7U7X@<*nqT_LExRL9LuK-ej9{v_qjsI+mD6mbAH#g0apsBK?b=t$Pw~p z*<#jzM#%qChlxHIWd9D$jD%YR+#`Y<7MK5|aDGz60Djm}P9~kSKUC0Xo@)bG-{Spv zdINmfMUojHcxo3*fxqLU#MkMbh}DAG#b+9r{O`%C>?|}Ed~FMS_I`Bvpx<^62auwX zxQxHS$QuwUfV`guLeD7{w>FmX^m_4LI__tZhIJ=#J`s&fWG|8+e8=S z{073fWscn=GRH2MaTFu=^i~Sd(DYjJ*U!XOv7*5gytJRD1`6tLsq814Wq!-}#KES; z7HJc?{RO_ra(Hka>r|5W{D3X|yxP*SJm%i!3e(Hq?UCQ&sj$C(bLfS-lmKTbdLO$q zWpR2iWjbpeyH@Kux({@C=I~tpN|MA)>7|_710qmnS`JIAOv{iaK?$C@fY2= z{03eCW?kUiMIOZz9DNsg&lo|)JTw0=(}>=me`5porSp5@5kg}lbue*%x)Qo=58-pt zz97C_Xty;@sckMsq3ly|1|DI478K}BbhEI=h&KQbT2QPI1cfS2c;pQvK*=LL?Z)xv5gV?x>dLN3#UkeRTdxK{}lA>Gi8oTXayVY3vfwK%Hvo= z|6@6qG|XJ95xYUb5rb{yC@-dt>Ktxi8tD)-URY4;ksj!~hK5NXCz0+X#QA~&ng|dR zpbecw_8N+hQk4K$S?E4`1eS0ljSaPFig0`}ZBd=sBP9|5FemAmKxXb=SU~j1=5PiT z^Ztu6K=l5Bs-=r0(ttioM!BbbJCdF9_cCuDj^+K^ySCZ%xZ^Nb-7J5(6Vw8AbcE5V zngg#vIafxzXt+Adn-mmS-6^DYKRm|Hs#(LYmM~jWg0?||0Y{Tk>b$y;0cW%}1o$vT z!z2QD;N5LWVi1T+i6<%z>X%*p@YkpNLRyn$<+7yP8=Co3KfQJ{x)8#hcwK9*V~Q+UxER^G|F?O3xKf%tOp-6cfK=pQHn50n?Ehdj zK)~Ih3f)3e-j5fiEm4q@7(fh%nSfnrJiwCDwP4?Z+lL2aQ4 zaP%n25%a1$Nthddg_)h^5<@TvReo24%S-C;G}))V==(er5E)%?xumn;?aN?rdDk~1 zokUWC^|VCA|0$v5C*hR(XDml6Qr~GVcqHaw8;Cn{0{-NaA#hc9yC<<&q4k@Zdf+j^% zmwh|S(-%dXx%Mygf{3|t;yxdjE9f9sSN>ibP`Cz*T+6tyV@&Rh z5w};Y-zmxW!`M5iP8r7e%p%}JBV30VX^tXG4mtT8_7ZdM8&`; zyE*biZg_{QINg^r42m}7iEATW3eQZ^1_uuI4b`3j-(bK$d?Vif;9WofECGy#zZ8wO z5WfSIt4|ArL9KZp77?J|I-K_GT4i_RfH+dj?ar`!$OQ(54*SJ zen(R+R{H-D-UGk1e$Sq$$|j@@BqJ>T)nf9w=i4cz-K?I_nc^Uym;uh z_SqZN4L@x`?e6u;)V}g~PBi6V*_Mhp z7-^A>UAr%5vKrG^%P`-D_)|$@=&__V?=6TL*i$g5xQ%A$=`8*(6|8&&XSJL8+@doO z_@Zaxkge<1E+U!Pj>Z5{{{C|st_y>4VxMv0={TFE*KYP+d+=IZ zL+2I!gAZNoPOm)4<~@n^gpd!UdK}y;9+D@B1PFOHSR2ShA(Oru=QZ z>jjZ)ZCmVp`vF2{{TppekeH-|Xkc1%`l42?AYT`O{+o|RvQdoLp<)*7CuY7oR@NGn zI=UT1BNT9U*n?HfhO4&I&oMRQT8#P%0~$5X{k!&-)e88%o>BS3SC(Ht4b`OJ@4epV zlHXmGjFC|_tM8!+Pb>E23%K?7Rmv^3o9TaZ?GP?6YQAQ)q^Mo94 zDB9Qu&xlu3ZhQPl5wCCH&wU$pdg>ufk8i5KrJIcMx$buPS|6!y#P za+7oiWfVUfAXpur8^_V$kb9d%6Wv8kjQZSl@2HlGB~s3<#f7T(Lf@j}s{|6_sL~nnqpYzj zmT^9)&z2YAO%&CfOK+K+bon_F2Vf4Pb3oR{L**DN>EU}SRUiRL{G0j`m zn=$B8@dO%M!(W?8>ze9>3?F%DzV5IxzH4(IKjne<(Ia~ zg>xn!Nzq(Z^^f&73%+?fs`kD@RG3cHXv$$iQE0)aq(RP>w~lgnSsif&w$2DMXYBa% zZPTzf8a?s{S&DA4jNrpEivVo#-tb_rE$yB-AwR2vU+{%R62aVNUer8F8xk||I~o~U zdNK=sA}{=8Nq33!f++7F^3mY?Y{Bd`9IUZ?(kepIcfLEHDT0(0@zcC(m-^>CT-;0` zZK0KoiEk6+EURCtU!qJBHt{rx$xyBc_D=7fkPwkjF#$BkJQIK9n1UO-O}D4uTsUoa zA;ieCvshm?1*d(pfXFVpG7q*Wd(zzDC5l2;-wl2O4HabiaF=0&A-ExK6NS&B?W;<* zWc?GGDFISJWRmCy6-)mMu47~TYgW#`sDYOLq)-4^p5DwEZAPEDR%n$7goS_H0zFC6IFD~@u|L5f z8Nvo*`wpD}MG4?S)cvpMi+349DZ429}N9)3YClJ5qy?a zmX_NAvv_h zNJoJNP_Ycpf1hoE^cc0+`em060MLvgT}*5*>zQV^%sTtnm29 z*^5}CBqQxTL)!Zv7;>z&z&gXuP65Io5ZI9@2_y610K%%G@mqI+XK>KR6&NE)j_^0i zlCju|Bmr`vB>(5tzcbyg+vqSe14kbR5_c^PTHXb<2=Wd1;a55{0z5;JfK-1}MfyC0^!Yy_CM*WXfc-s7Dho)o1%U4nuD;() z-KP!_e|J(Pf>=%+SOYnfTpqX?5@0ra@k}oI>c3ijVuqftQpj@*i;F-D0y63~cskMv zHLFVB(u~5#Yc)t-{-h?2__L?`DqZ?56dpmDTG5)G=5T_osby#Idg=XhluvKqC7O?V zu%CIMVSplqSkTJOGp45ys(>S2xmOO1p*&i`Csx!qj{=4lYRysP>rDvrcQ*uB1Hw7r zQ3ikx@@oJNmo0emKjJ2&l7ZxnFdV>?sXFD)j8noBHNx7L`u#`j`nQ0Gxm`F)b4Xx1 zOEkJ1@vx=#G7^F*H={@tg#t9QuV>L`*6I+@o6~62gTOTN960%2mIhSCD(N+&_vGWB zSS?0y$!`ls3(WX@e!?)jc7b}7w1PhRVT~qY%225URKp&YK+S}Qla=JYKL+bU4i`X? zVgVmbAQ7SQAvH7q7^t^B2l0;Z52^r_Sez0=(wiZ3T1wy*f8vzWv)43>r`R^=(8+L0 zd8Sf{&zEJ|Yl-jm3FS-7d02ujIM?@f_zmM?Ai5ou>Acq$g253UIOQ@0#YCO$QP|r8 z#17GD&stt3hU~_vld&>pXKyMhYbT?tGHgah`#&RTva4rswWYi=B$t;)*M_KXdzI$c z^zXbLjd#1K8FfKGcp8#=Zi`mbqqXlIp5OaJH%)uXvF<;@azkxOdpS znDA-@MH@;phU^Ffhkx39Z@2X(4EX)=O!UquSnEfO@68D%bKuqiB?BdZP0E7tecFp4 zo_QkCsvwfl*D9sVDPiP{yTX4hrwYhT zN55KB(r7K!gHQv{0u5zjppAiKF;5_-PXJErie){W(c(2^Xn&_ve6LN z7rIOz6`CnuQrq0^Hw~VQ_E9qqK*heTc!kv{$TN-&y~a z5yVnQVBXi6fT}BC2NCF+jSN01zUsLyv6Y)Qkiy^1z^_Qd@9o|8FY8URm2QL+rOH4g zM=l2z7y)*|F~27L%t~zFpg1VzaS8yWA(hxv1Q4EaI9w6@{j>Z--vPi5Q&%hoMSv0* zL2CYh0j?-Nq;j`8G6n-Mq>cXqFaKrWe|rPc_?M;s?9^obw;!M#kOb(TWCeV2)P|O; z;V%Hl^+osrIVi-R=xZcJCxDbn$JGI$vY@$j{c{o)1P<^F1)vZBP7w7uAPG6Ob_A)g zQ-ZW%3{HibMw1N!%0kY3)nJ5wY6z6G_1V?vp&QOUA_aclvy z=RL)?b&%H{Q&m<^nQ(RHYMEICoYFI@S7!0F8f1rb5EB?U=X;^;u%VusAI~~zRYDYA zN@0YDIYbP=NjN_y_oNFZ-C>0{r3a%CLZ5rlZ_Dur&qHKky=k9RhGTrV2~_+6bVRKs z%W3i(0tao(103rr2LfUKh(;Y+!ARl>G>SBgZU6wfkdFKZC~1Zz+r<}`P+da-bjOmv zwu7Usx&CPpq(}09WWalt?l62iC|V7qeebL;mb%gxXeM5Wj(pFUL*p8Q^5dO}nT;Q9 zzjkb-H_ZB=NhNDi>2WlcA)=3LL_wt^g95A0>j~FV1pV&QNF6fJi39Z_npo^t3>5&l zBx6!@QgX?(MhXLwqVBqxCW%QgE(T-InRs^gm#n2q#$J_SWet!4g1b4S>s|KUsB&ayhnjE}^$#J0rio5Jh=uyvtDzDgkH~ zkvO7Dwm=2#f2zL#*!s@py-IFS0Ie4#{TEmiDp_&+q<~#I*hK%VdvFS(e!2hy&<1n< zpkp>8=S}fjFqQy%3pyw=$F%_6^CHk=I967WHBxuLOUXrAuaSYF<=bJm8bR0%vwXvN zIm!+AGJ;y6jcn4m`uGXX&R|@7$O?9Aja5bKx}Q!F>(qH==KM!2@Yml@uD*&KJ>j{h zJ2~dMABDMVDfuY7HkxiE!aw#a(g(k6VOHmyhriTAvDy(Q%{Y=x4{*pFpJpbZPQ15;Ivl2~wUMms%$^Fm#-`cT2xKe z2U+Xlin{e?F-8QMDHQmZB3^bIdG1l54dZ`Zr2VzPQz4hBrI~wtq37~QldbhbASq=! zkC~8(U5uK5jm6!$UQ9+41*PW)hC2<2R?vN!blOCy3%;O`^ovVzRyvPDgP%~Z(6Avq z8BPv6AGYuEFG@~ke+K4~5$5ZEUD)b+h?TZyd=}ODWxVC|GX9jb)j7)+PH%9pW$d09 z9ceTu>2>e9r0bYu%xFURe8OOD>gn7G-i}b=qi|lYJIvvw5>)x9{7bqUm%P@@4;?K= zDSMml?z?}i3gZn^6zaRm1;4asmLw(1s60&EBnWGSM~mI!cyJEbd#G;uIEYtyV60Or zG*G#ueN-6&N#gU_fyB_-P_r=PKM))VeJNwfPkHb*aGmBSx9$tqK4ZiSSdM*P&i29{ zwx7N!*R)45mogkIAScfAP>^l{%WdXiZEmOHv0eV*MC7n_5h zqiSX_U8@Jp#px)v=#?BrltZ3c#fJq4{6|;AWXl;}rTahMu0#w+IP6JN^}uk}%BT+o zB*Mz@O%R?WHQ8YwX6~RNZ9gl9d(d0m?1~P@GT(m@K|NfK$*sVR0fh)ZV#9iVhO_wl zLq9TXSWZa=LXNnIvTNX|q{xs52NhfW9}whk+mG36%W;xTc9#C8(MA9ut0QDs15dpM z6_n!Pd{w@OA+;qS+Re10L?mD$lNV>g8smLr%~I)gPXma*@@gi^2Z&}28EA2OJ$_=Q zlB$B3mg0WQ*z6NTwxE)0)AeE7DiVy~6pCCaO=|>X@p;tIz@#5ttP4@kh8_?w*Vi z$npUMqy;d;?vQu_m5{&zDHZ_$cn5!X%NCf7|Bq4m-w(OyCfE47BoFg<2f?y@{gr$z zSLsT{`Os>0t&mC6?>j?}yF;2NklCQ*1o>;xgJ}q~i5{;|^N58^A8r4yD>z@)pOcZO z=MEou*Q6_X)v)Pphb;7-5;=E%WY9EXf{kayOP{ zB;RE_7tzVOWO8c?F7x}Cz~BVm~uk6LyKf`ozb<9o{9#n5-#octRtyJsasza zuE`+$VfPmy7Tb?V-^P(=>x2?p0VNbG2Lo55{0#!G5=BKq)FivpIX~O(*#mmbehK2n zt(eUf`@UmQT9I?3&atKUB9tN;!ncUNFa;QpBx3o~9Jkbm@Fk>i$&t zoUQRx^4K{Ans6X9)Fu{xLB?gv<%nNu@*|#+7<-I1Vz%<-5#$%vfy6T;MZ{;(CFU_b z$7uGEXCj4KkaJ>+K(97NAc2?8%k7_UE9G#WuZ&TZ%W37_RUWS2IJA9PdX{{=YC8em z$<_=h*M_}5dgq1b;y7i65&P{xR?K=nC-oz0ytYYHw|(T8YJ9URLph5PvD1RRv;;as z0Wbmnj(*FdCwt@hZorHKpJ35Ab81mG^rGVB$46xM$(-T(R1qm@Moy#(Np!aHs4EmbNl>2Y(iLlXpsB z;%O&beAwvd6ejx1aOg*!Ey5+Oc&*dOZ{j3){VGg!kCjjjo+QD`6C*j^oQMqX0Cd5S z_LDx6?MWJ}s|oWswu-Rp zO<1o+cb)@i(006SCjWH zjvs!>ME@ozr4?iCTs{3G!B$=yUpJ0aTCu)xV`DJ<4iNo7hO{O(J#i^{A7S2*y!#6OX3gI22(omY>Te-Hq|jzW7uT^I|bcfq+O zb^u{#(B#qmKyroHPLCMv;yJ zg+s4V=5HKBE|6mk0JwZQx|$12PiVXVL!Eq39bg9-__GHpphHG?010cP*+|hLCyoDY z_P>MNU(5fmFFXpI14RxJgoDn19Rg}cT8}&fj{uHb6Dey336GtS(VmVCj-r6uivV%{ z*O36gj6hy?5P8{`|2+X9Pe%>5&iv;{T*FNU;8te`a?~dWdrq)T7W2>UzG)kEa~?Pd zUA%q;0Q0cNAY z6hOzyJa!tbAS>6LY?s0o;cjAX&m@X~q#|9|LAucJA1;8KfxlfCq$^kj2ml-7ub3B7 zA>SI9q>kxu$h z8!fN<#YVV4qBv$$sqEquMPXtq$wW*#()Mgltt+Tr$8{_Cf5rgX>JpnN^gk$sN2Asb zVS-y7y4=P|;<+qd)Izo@s(n}%?ol{+-n3}nc|({k_olMFOb6!u73lMzu-o&ux9s32iq|~JA z>!@)@ihqfZS1Q)SDjWMd>9ZUAT3PP?oNl?$CgWz7k%&MqI^@SNkwC@=wP{jk@Wfu= z(aI&c@v4(#61K+pi&riRWveCY=Wy>4@<@?LB;EH0h6>V)`^X7UEpn2Rxs1$`#Cx8;Q)HnRj|m zM7pM4LgE_Zb;csOQ7mJW?s(K-M{LS?kNBcf*}h0deTI`agszcj9F+F8wzfb#*cn?VM5`!yNXs7eU|M_7H1Y?i!B5 z%k(DYQQL_!LxX!9NYHVSi&J42vX~lwEqeW%4%|ZR4x!xKzjI<{K>ShAw}p}W;BPpC z1BEaJzM9K8=9k$#G>9(>W#?a;D_jV~2K3ro|MrPbj{Y4;-SG4922gx!&b0GwfkU42 zI8sP+XNigcV*3kw0>{_9?QmB2I>>!WV<}rBKd5K0{`jTW^Mb&bXdm7)K1uZa@1i`u zB1*=L6LIxED0ggq-E(idZ zNZlQC8tk>-c;kIvBs~}5IKwjB`UGF5Gh7c4D-kJU4IQ-%R-91 zlOI)J>qS!MBI}Ef>6)d?BaCs95#Tnqc0wm(K)e*!(#bmvyoU4@secrR^B*Z1TyHW= zfdj*22!a8?BUx+EuL}SQ1=D)Jdxca1t}4Owr#wG3wr27#h3<5ss+$wPue(%eFRXd0 zlBab}q_oY*$B?w1;Gfn&j6H38nhqYPzDc-X=C^&JYciviaj(H{MNQp7kWAhz5}LC@kOEK+1365}7lYf2M_OEGnrB7vslaX|q3k)%IiA&?4< z0&7c-RJ@kNQtJoLW3Bx4I=L(QpSzT>Oj?|$#8VP&jbb9d?`p#UoJ1hqL~33J{vQD9 z@BRG0yijXwLh=D803s*DSE2(2Z9ulv@`X^cj#sViA*eyG2tErpvcS{b&+zJ}UMMSa z(%Q%em!5yH<>8t7xU`6V?EqCAh%MEN#;8%+!~__^@vIr*Qqcvqv!4e5)i6vI5Fs%k zSPFT0$RVw_E|g^k#%VJ}RRUuFx0V0@g5&>WC{p_VuLGWPBdBa@40%YR*f0$&? z`akPK_E&Qybr_Fydl())#kGP*qqx0Q5PWDiP5UGc_z8)&Q&65z5T=2d@D55LMie@S zz!Mwwr;lvGmrPNl0)=IXxpnChys~4=x_hJ3fY$b1HAG& z13*xUf6Ovy|7QaMNeDp!z|6%EMkA&}_=|fcVQEET3x=r|cYUhwU_Z&DLcs3L;GUYq=j@OBiw<&J!8Gkkn9)OO!NQE~=8YI4`K=RU#G8jqn zUlpA7TV2!J@h)&ij~MG48?sPhpq$}x7d%!%59t^HUC)(ugizOr*PgEIac}vbRyUjwo6uK5Y zMycX+<%l&wpAtyq(G7i!xl(8WPV+mA=Wi@a;{Hd*d>TAWI#! zs#Y3xJj%{ac~Ne4_IOpMymf}uPW}qFv4hxG7ec}Bz0I4GdJt_th0oHef69S+fP8z5{+(p5{DQ-0Qbp4~1-H=eW zN1v?$sks>;9HqNB=F1uaYO%+GgN-2$8rc_hF19l4v@QI)?wqLZDyIsEAk*8Qr7!S1?g6FdSO4v7`=9pn z%2m=xp$j_pN^ocm6(_1=wMKVWtVWA6E;`|^@&q{5Lh0;X(Sa^SH570NZ_O{Y5GUs( z6ihv|=`AnqV!1|>U}g2FZD2AP%xN8l{$DoZt%VD|9No-TsJKu-o0Q3PjKXAjjvRssM6>+%YRo zOI=1}9@$%_HGGa);h#G$w-N)$t%t>?UgQ01V>9rTYD%A+E)1~+ON+DYo*6ZbToZX| zN^E$26b)Oxd80KxQzGs0($W?}6p^oeaJ|y>M9+(9O-J!HZOP4@z(!lZgOxr;v;S*E zN6;ZlojHyptx;(BT#l|zid?_f%@CVsT|07L?if$3a^={vwXG?FFMMf;4on_;iuR?D zGX7x>_r1jMy!FR6rG8ky)w2a6Y^?I;PSC=bo&DO+2o6F;)~qe?v|`|JFp%hJMI_Q$ zh8g`qlt>N|sJ@j#=;6{O+Xnz>eT=T0rRQ%nvT0IDMqjlP0voLL%pL_~%4?&fiWaXB zFmpIuprLfq*7W+AEnb+yz+WES*nbn2{&1xRC~QL4Bv?LyQp(?a;LjRnr2zlU7VuQ) zKws~e_!n^LHv!i}c@9$T7ITDtY>JvTX>EE@U1F+lsr1Nj{M9rfMCm{#xZPoJSriso zD@iXE(1$WA4{=92cSgllY?2~jaEE82#GbP#|8oVTN(J*pZO1gXl*rhpe55WI3fN^a zVHo#8#c^!^)TXxVUOE93QC9pK0daAaFNY?MLMsVPHVOAuWiTg8GNd-r%OVtsDI~r?LKT_zelE zUe>`#c!m!xk35+W75?SseNU&Q@a##Y#xc*%g-${LE7T5%BbQ7(ymHKKQxadEJ}EL|1z71__732ddic3L$w0>{== z5l1W0f~+CbZjB^lOZ7Hw9KBx~Vl7Mx2JbQMMHeFrxVDObNN_=@e6~t!|B(Bm6h|WB>qzVysCD>pKbBadlU!Hw{L{( z_{^MLtaOotS2=_~2dWPt#!y8pXD8m9FnyzWCnnC7(Sv~!i$ipNqN^f2AZ=PxwPG=x zup|v(9+F~4<#`#lxXa~x$i{djEj~(sUK03yljKICN)}<@gW0+UgK?--N89s&hxq1D zAsIY7UfWynUb&W9;Wy!Z>K=AsTaWZ-8VQ>@qOyZAjTCKsPLQyIZYT93n~$Cxo(ZpDQXp!; z`}t6(r))%#HV{u57ajbLqai!_(b=i&Y7Ur9{NVpp*QEW^Cx(VHqe>#j!G}t_ADV?S z<#N)em7Xj}PdoN9l`nqBf_QI-lpn1g1<|J#wMj0ya5+TBeQ6~|vS%;hPVUg)OzJ60tO{y_Rmb2;^dh_sV;_s65VyF2a_zQBCNc{Jr56G4f!H~GGV z9Q$)=SlDPiG8mUE_HQh3t5Ay4rR4N`9irGu|C%m&$SfBq|-wR&Z2RDgO$nw=_Yluvfo)0txlI5VT;(RDv9Ojwr zgU&rGE53%JWcOAcM|8;r4W(dk-|6)hRSB@cZgf8)m!6e8|H}km44ppFDv?{9Rz0(0 z%TLlQ8lh5U*Y(9**aXJF7}fH?uIkqPhEH~>9PS#qI{*MvpyE8||J5h|Cx%I;O~Tm# zmKKyMCesH#gNf(vbkCj6FwVH4s=1v~Ky4?;>&*#vnJ-B7fO6Xs@nyLb2~O~-UYarI zu#GVUL#GYrRVITA#`FtyPNEJ2Ee7m}%1(ekPKwf1O8udg`qoytwZ`%yKPqRRs`?!7 z7mh8Zh$e-Wus>Hiil2k5)-qqB^%rkqWq6zo;01sft`2}bFuDHlhn$D#K}YxpBz1BK zS3DFoW4$$o(HMaH05~#Ofu3Ll!E}hcg#RT7)&#boYJB_fViT4@2mbbF7qDxxwsiw% z0U+mDQToZiI*=bt^SA-aYXw(XAE3^)gl3&v1bEqTSbk%_V5%t`%dtk-= z7rb2-_k4epwg{EEyUOxl@ra!5DfQB?3@vUN+j4773gai0b*83Mak|wKYy}E59KIhc zDp&5zdy5&Zyd#3iQly>db8yKtjznx{9pLeB>LGn!xaE*H<-FdwZvem&>V-+Bn;Tq~ zIeY){cX&3UIbOi~i+)kp7Ob~y`d|dEzzD4QCxKl>ayv}iTqiJw0|!j~S%FS@!9zK0 zu>X@_nxpwzkV zP!p4Rr_qNWF}MQ@LNp&VwrN>)`#&ul@X;9TTyS5bqyYACcz~j3 z(EY9*02h{18&zb$0`n6*Ss#CKOSnQi)^#9ART2Q{F)X`u6ZnPyKj-7-`)dpFmcR|b zID|n+1{LR{{}%*=e^ZxXx0gv3)(X^p2fqnYYk&d;$U?Fa{BXABw6+77dmwM5Oc`t7 zp*#ni*#}VjjGUqnROqjMvI{UeT3Y-Rm)B%I^AMz0FX8duGAUwcwx48Aip|CdqFh9Th;Rcx9`{Gj( z!NCf(0(&(PN^Y*oeMJ$5Xu?B^a3P7)X`P6=Qr{w$4ko1*KOK?Vsq|Psm?MDI+}Lh17bYap7WZrXo|hq zsF4wy441;9`f2nM6TV%CxDm>JeF~cpL(rgM~$S4nnG$gkn>6)-iOb43C~r^E)I_ zf|q71N%Fl{majLWL^S)t7+Nx6^@a$-zodstXX#Tr%)DI0AAa8P>$Qdu=8UDO3Q4{n z8rk@$tuhvB?^eWY4dG)Wh>TUZy+|w8dEq1B%aaco?&Tia5$(WH5Ba>z3QoZF&bg@RJZWCao_jR4TpXokN zJ;Zgc2{I)=sZ2ZcK8&kYnz$QdunNyFFG2j`qdd0+5MzPuAg2;3RykvfD6*25?t-Y(`8;5;RWujrSC^WK>W7qSHARGd&u7lEAhh2sS?O`gGO+d?rHaX zm4&M0WQ7+9EJq19UagBdtg&Y<3@>8lV7GOb)T$c`cq#x=kpv9+NPZpjuUuq%CSENk zY9zo7M(`FNq;7bMb}>~=HVMB?8S`9*d=4G4Qbe~~*fW{?@I2lVM?4w>8`}7uh5!2y z1>q!FJbYQ?p_}moRkY$8yeCZpBkm}uKC6fH!NIsGkV(NfrmRthSv{tvMO zHjp4A1A4H?f;cJMl)ncSIK|3Y07wHw7!0bVlL4A(eGn?8BTEqPCWt!xO%%DqkhC|8 zB|h+0)Et?Aw_7Yg(46OcK}T4wyVp>e_NtD3QGs*+Y!83WC5!7Nb$g=dgt^c&&`vqd zU&9w{-~y%n|6BLC2r(>w?GeLrfBzVv8(<*+Q+0ASq&h3oKDg!iIZ z5rXE80$GE9P+Q05A(u%PA!7q-$5}V2fbs_c|7YS>7(16>iZg_Dl8X0IR>YfNvB7OE zBBFxds)lI-ze-1a6ak?(&rd;lN59;7?h7&_*xU5nL`+8Vr9Qa8n1Tg1#?*(kIh%+k zO#p<`53_s1rl%44bGfgl_J7|i0K5ak+zi7!`A_cEW~RZ>M)v}wbhG*ApG;EneW1-m zctn-h7B1KU&{rI6ygLYyE>_|+06UL`0+cOs(Gwu{f$r7!NF7mXg?b}meI z2_rJQ4^Nt~Ql>RoOp6pJ*)v@4BeEI*Mj_=2)5nK&#XM`4?tYHDjLQkq2Ql<`{>%c> zYw-vs>34-6-OXVZ3nshna^R%_IZ(sHO*H!#_XEYlaQ}wk{tw3Av3CI<=$(>RK-^CS z0J`sfA>*|Ul{S?C9*fx~^cn>B9+Nb=3BarS7X-2ZnzS2od4Gd;@f=rW^!`oJGU&VC zODUNJz6RhU*XaRz>DV>KgHRQ+)al*DCNFEn=lye9=2*Mm%)OE4!cGT$vt6qP_?CuW zko72KgbesaLVd&D?icS}=-AI0jQ>>bNwVwCAq$Qg>CV!p@mO# z#Gh2Iw8rBHH#Z(G2%(}ntiBS!`TVBbKs3i)enf14{QGZ}8b1W_Br!?;7UFkYPp3^@ zFYM@#M$G5L;M1hbWjyit1igFK-oDkUPv>c#%!@dtcmc& zNJsd@x-^YTapKsHE9AN4BI6{td~yPvJR5Jrd)lCk6}G{l%+to_yUX*vQVDYxu8|JQ zyYcnOJt~aGD-&>c6-({4f+C_*N|a+!=_JWtlVj*N_+wCtWOJUSe!`AEFu)*^{$W#A z3s2*%wa3w*-HJFbs4cS5!Ifygp>IEtddhQNQ?nhJfV8CsSn0MJs`!+s{duP zT{2@9fEpUomXv|A6)=DBG%OsyxdPDYjDPdqdvLi!U(LgxbESZo@y>=CmvE5MI*+b? zq_8u32eVe1OTnyo-+UvCK8X~}|BNuh%8WV1axh^AF9n`s+PQxvaQgVv$eWH+R7qP} zKzq4?BcQP@D?k)3MT-!FOHBAxLYV zviWBKK|qGB;Sh%ZY{M-D{`q3J;wzjUh`1Dy4tbc6- z2vR(t5H~XgO*qmUoBJXBQjkC7bn;eN(rqy#ha9jRsjGk{|EDD7cic| zneZ1B-FL7cHkjd;MY06;1)BGPg00-JXkK{*!ogGnuoEP|=Re0(aPMC&|HdYX#5y{~ z?j3B9z}EL~hhaaWA#DQaOG@ZW03fgruau`DD>U}BfRz#G^|Lw{ig_=u@f4l_?jxY8 zjQaTVV~2o%YqAiOmVEwi9U)K z_bHwSYTWcQW<{KeJ8C|=K^~;k-;*PLynj|memJv*owqh(9O^X@^yU-zJ=KnR%7CSz z6thxxtzU`+0m(ES~hoP z6QN&1+sQmS8-AMHJoU&At4@Em?jbt}X*t{Y zezG@2Pj=9Ovn{`F_@E|8nE`fAFxzH!t~;%{<@ND*InxlScszm>52ODdY@G+f-UFaDK-IV^3m5thsb)JIp58~czzzWM*J-<>2`qY%VWi35 z9ut2Kv-1s}Q>BdQP6}o-XS5N6e?X<7S6hj2 zZ!+J^|5<4uI{O8?U-*W&Z_24}Y{D+@II{CwOu~4u>t??-^yfAm*2l5NZo4+#oEQ!p z=YAcSj|JhuU`k~OR_e=VqI8~e`0JtgHK@m=$lVYtTttf|w!Z=XE5CS6$gY3ahNT-x zn9xe|Mv*d?EYqv`ZU?e&Ca4jU-)wouvaWeQd})(N*dun178BzcARt!aAKFx^5#4yj zV>GsR{7eGj=4jp?HSmiR9!c?)N^xsw)RQ1{ZhI!Vy)h=bp!iA9JxhSK%Fn9RV&+jb zb;9-H%ZCiNxbewEHGFxAYtEKb$135-<)2u*g5y(SUfM$?gl{6=?}s_?9V)-x1bfXO z-VVIH4r0&EH1QbO(@98w8{Yl8Zwy8M42}tIyPn%APcHerX{qEWJkr}CV8NmV{JC2) zHKrzFO@)cC(0+zU5lH`|9Kb3-P5zr1?vLU0aR5Z`kaHozYWz;|hmvYf{+qmx*{ zlqFA2u(SO~9|_qO@UIjMckFnzMSxLs@ydzV{dkcJ}*H2C&CHcH5m%t5GfMCkS- zPD4wM@$bg(pnymN&wgjRq51MdFX7{Qf3>rFi-78ilNcs_1%5`K#I zi&~hB9Pyyi?FUiHNBjq>v>kXlz3bk?QlWh}AyFlrTcU<(Obf((#zR*MSmrg8EEB=% zuwVncrxyD62_x&r3Zy;yvr{pYmO5Y-O_;klWhNqqzzXh69b^KZt_tInY`{w?7-{7& z(vJU0+MhyBh%tZn+n+US2`5y1695QdEQWk{9Z-J#y#0aH-0)635)5Z_oq6w_v*ZF2 zqY_4{X_1-sN7N}t3**CS+rs-8DcsZa;@61ZF4q;=_RN+`w18KOZYw2MA7e@bra4D_ z;|6!(o zJ!Aii7`Drh};Jrd%7)+Q2-h!5Q%%!dPo;W+`jai8Us?lD1Ts;pVKkp}! z%a(ncYRnt5fm}ef*$rn2unDjmQxCzJDnF?Ma&&hD_<*S4^4x1kwCgSs2l5CQrb5u+ zsQ{S4*X zo>j-G{0m4O9;BLU$M}){$E3{FKs$O-zZ6Dj45ydY#ph)}JD6P$;WkGBiy+0|O@Kmm zS2%TW)b6SX*OwpbE`TwLH%k~U;eH+OGM^~S7`8z!Ba_!aVvRTFtq3Yy9>RC?AW8iZ z_2rTn6T}5ajOF|1`cu285H}__+!Qat;VXWK+Bn&qzp-85NF7i4pW=DIPZ%-(DZhY= z1A&(apDkfh3-Vqn4`BZYz|DAK3q!4Nq|_EMCOkj%!D4Mp-`?%;*q2S1eANV~+p_wN z0i%?7T`fWXw6ry^N|Enp7AR8es*>772boG{RC(yw#N;|zjXEp1IQ)u)xfqB=9lmT+ zTBJ?Uwqxl!@k|ZoFT6^;2pzO7Trh(_3a^cVGi+?&XeGP-$2RXm*7c}!FHWg*;wU+9 zhj%t#?yt+T=;YdH5L2fM_rVouzuaHL*nhwCl3*?xl^8&++DuQ_m4XAX-%8C+;8x>3 zArmJvaY?E%ZRD0=kT(EEQZT-?0m+|w^M6%6VGo|bwi(Lxk^cB6mCuZUUW^^BfxvyJlOm<39wTY(%xUwb0Zr|%j40CF zfoZ=&EB*nE?oAyE}}d$8U_DUMK<( zC&|!z|Ba}nv?F577uWej;CsdAa2L2;d-KP0xFX|x=J<>i)z~`E3Ahe1{N&dO9CL?8 znZPW5&-}k1aR@KTvY!u)j)Zq<20b#ly)diQKQ*SO%bEMu5-Xm5^qQ?3PJjL8VXJRD z)bmEHO~2;&GadLCp%7LyCRfww@c_DEsaRt_VDA!QPR?z6QIGA6T=eGCO>efslR%!Lh#u=&AZzOsKCREm1a24GL~-$&w_#)`ek;ZYFgp#O6S z_QQuxF%muaxQZO{IsDSoRpx82Jbp3`R_v(+{x#smYgUvZ1?pYJ%2m8oM^po?cI^Y} zB7-Z7sQRL#;m_?SwaQFUSzqw)=Z|aHIp2neEy@|V`7%p?g1pB$Mluq-7(U!xM>ym1 za}~}zRACs*vovGEC|XSzSomcH{rLlqe~*>9>S?rJ=}`>i-uhmTw{;%px+OC1{n!q< zfBzBRxW#o@WFoaWypNJ$^(T+34I}4~+sW?2$jSNqt1+njYrM!0i%+-;x4e9akA1#T z>YcJB7ye2QnpP_IgVAjxF0aBq-1KsWk|wI%j-Vk<$6g-3%_x-Cy3l;g`h4Umf)h3o z@xbas>S-FXHk|%E+i5C+ssneZ)(R@7_@!g#Rm#F4C^e?y^i_-YZiF>*c`jfm=$7Y% zB7=S~!vqm^^oDv1oun1FD`%FwEG0Ef+N4A}>z#-q85u`}zQU*tQPZ!})6&&&#k2 z7BhOoDLlb}3W>Lqlnw)YyaWj$k5R|k)B0NVm5+980cw!A12B17oYNXYntRC$I@KS9 z-;4?s8if{9SVAO49`%VI3F(>Lc!{ZzY#Jf%tLJa#Vs7`>lsTuYLVcCkI>#_?m%qmt z=xmIjE?z>eg9sYv_Uy}luUdWFWuiN?7=kCP<)5-|_PopW+CWtkK7A2|nrriEeXiI@ zYniIzx>nUwfL{@>V#6EpC}^caV$qN- z;|&`8@Ez5Yq}+&&ZU5>U~`>OUtJ`84Yfd!v-a5*$}& zryTN+k|@0u>E^(|)E85o5uZIpLlSw%^O{kM$MJb@9kG(=FO(l=DoD_pE@Vuwv~4iN z=KyMxG`QYOWM(|vWBXQ1B*Vj>ysv^~URAlG7Gf!B0<9Fpy?e=XsPx1v&lRlssT`s79S`<%1YMl? zaW)1G>U=`41AO_@l^;Eh!Jl7|cY7fFI%u5Yc*^m?tVv9e;tjUI(gW)MD6_Or_==1Z zKIM4{H+c@~S1`S!2&x7_r0?7t+i{&{fH*30AIFXwv9Aj^Ql1beK9djbw-l^KTp+dC z9=lELv){z%`{q^&C1}z#4>OZ|0AkxGU%+N{f<$x`;xJ9Lwugf(=+?>ajU~QtsIBnX zKGGn>51CD<0&5w`h?IHvhdZ6 z1<6?ctKGAMU;7=K#+%0^#}nVz&tY39JbBbO!g3(Q+aM1a|M zR2@gdqb6f{)04hm-KUq389m?XcpO*5dESk~Fh04djVENT84y5QmXE3uWuMxZW|e|b zM7qrta7;Snf-U`gl-u?&*>s)uaBVz$KQJ@r?ZcvJ)2;jUm~2Ls$?p7~JLTJ> z@(rfXt%RuFeMNk^euW5EsV1E8200);t*Ro-OO~}J$Oo4{B;NFC5gm?b!+|`AVB33I zp zdq=2uAI%})|0<~Ei#|@lTTFLjS-gNM_8oOJG!Lf3qiyn6&=fh=E#m5d9o&Q@#ofxhnXL z(!&tx7dbp;HOcK%dq2S`Sdk3?t`Z+4jYSXdz?2cjTaD0v>rC2jBUOAnU_VlZA$%ys z2L-|8;y-h>@1g(Gvd{rFh3W`~o9q6OpM_zx!U63(cmfxuuq{x85TI1|jcuwO*sRSq z1u&OTGWXoBXNboh>Z-@2JEWC>h&Y>%DxkrzBq20&->;!zCmN4v@!Dpc3Twm z)M_k*fGZSFeV=HQN*VGTUEEh%5l4-WwN4gf-1FiHktl>E0!|8HsnfRESrhZxv` z*3ic+BG_kyUBN|&W+4UEK*{J~nE)k#Gw_Hig~ns|onK*5_m%p$hoOI>U?;^y91gkm z>Y#cfDs$rtci>3QOvtg;=|C76ba12hqooCWXwq`=uD_klV zmp%#;9#LF%niwJ4t81_59ck<++!6cuf^wALUKt^pB3NBH!3Uo7_!J~jvP|vkyW2Lm z?oG*2v`Ap_t5q;8mS~LjYhp6hW@HjjzP4N<0ZjlHC9@#MN>mAMYyd$>1PWgcc*1-R z-YoVnpzKx|1;AgWxb9%Rk?>Cg%OH@u1Er>d5d+u!;Rp(|&P2P9+rtW*a?3sbp%9TA z=ghUt!GqKPs~d=jmPM1+`UfF=qPU@%h25!YS18%cQ^43bLf_{tlNACOlc*BBe*9M% z+po%yvttKNIM9h`PpS6<^>YLl$gw7j36Nwdi3RRwztDEb=^``u50{XdgHq@BLo6c> zukK6WGt9Y?wute4d3w~tyG#dgMd_brdi%{!|zalnNV0K{-M6+pVY&F zivZA|J^*Nq0P74e)1ErAL#rQ{jl2&=JGi?Eir<$%T4}03r4c%WC@Mv2ug%4e=WgVc zLuZ!%2Gg|?-WSfYW&QRTnO>eNgDy@YvCMry$UFaF0QD{}h$6youN`FX6{T!_6t|u# z%tn0OkG(lZfP=pOix8Q2-DFs{AQ_)IRg)#a>*}s^V`Z7Y{5M^J{ztw9LReMHr|+?1 z`A@SHSnZq0SuKJdBwE9dNcMbKc%-Mf78Ug>B2dj=$h=$A(F>r_bxFeCJ#a>=v)Q#j%n zz;}Gq!Lw`8K+3J3@ZG-fg%mRPjgH3e6a=&y0c;64hH!x=WK^d*vd4P6s9Ai(k+#F& zf=v=bukZnw0I~CqoYLTZ@URrRfMyh`WVBpDC6;xK2MdI`p0ce;h2V_~E=}M!bKh+~ z_g4vWH*0=WaqGndZtD4(aJ@@#L-?3AhDffvb`=B5Vcntf2TUYdfeEWKC5Ng;;zwHL z&OACjw2pIeJzo$AZ>1KYLcESaY-WD`<`>NzZb+PpTfSVqduuV$^&pinCU^0eU8eq6 zxe0XMM(dZpl9VpHUwhKOxPZw{xHy2E-*(@Eom9~V`h@G$e$uUrVkiM3Jkt+nmBn}Z zLxpN{9Jvgo-{D?x$GHDAY2KIcSj+N8lyoCb&p1fLeEkdAbzHgGtLv-R%VzAj(Ax-@ zT2SfbIFLB@Fmp+{&vWqhDbW21HF(paZDW4%B?I@?kPfuPxZ51-r*mZ zUN;J8@|%_l?C*yPk1uXN#imiR@9d`}1VRgVF+aMY<>YKLRCo}?x(hLPTIY`*q($#f ztb2zr6hT@hS$U7W&b053br13f>0EpUL=WU2(z;iem{xjM?}9SITO&@sakv*ppr@y( zS8iYgyymf|*iP4&h&`e0xat_!%1TD*Wtdm4c%6fP5tc_3X@rkUqVx#~{-j2sOZ9SO zB!&DkJhxG;uQe=px-;9-rIO2mor`@EnI*#6zG~=>C*0;dE~q{mrB3+z!0M+&(_ove zBIsvm_8noIZnsO@pb7d))C_{(c_VP)5gji6y337e7BV1SrbPsbc$?H!`Rb6FBIgmy*!AdDJZI(pPo|-SnwaYYCd${} z>+D_>TeI~(wJGLx>QHEdqp6dy8247TUzZ;KeoWNWVZSVw4z9n<897I7Rm{$1y41oc zp!!&Tq*UM8bk_Q)zp)t;B2~qjK;bEo;emLEO28IUz$~SqW`wQ51)9Y$gl8KykXQ!m zo_uXitBDw7(+yke0qn(jD)kI&992};Ju%ai~UHQk1u+7S-?9ySAa-0g`=7o z=+!)y@Pt3xLroVm2`8T6Aj?!THoKgW@mO$A;P8u}8MGiT35FBjadG z3@xh$`(^km0S!cfP8H7>Kwk^V5}FO&5#G*GCNd!sPwFP%8Usiois^!0nl$~7ROq3x zIur)0Z_S)TkpiCwqE6d2cW)Kj1Y`UfwrawDDNb_qwpZs`4y{J5bdSX(QK@Da=jvV1 z+P=>^x5Yc%ZswlZRhHdnBV%?nD0YmzaO(pmKE-&rJ3e1TelpUI9KGOTCi=ax7j1|t=qenHCpCx~J8+tLFZvV9 zKG0EQ(5rxuM%(Zp(^;vh%X>_+@?R;?`ohLgV@*^8$39JyZt&bh(dLF*S*}s(Z6|=C z(x&@!-*tb!P1Q%;Q=pBlIvn&Wbx$yNniAPiZja!WTWc=D?J1AJu9P>Q+w5@70>of- zc_&^@=u`#yBj);OHl7yrhwIyly3Cze#uSWBnS8PrvuVrvog**^op{WWIrUYKKPl9! z5dAj!PIlE5b%G=4-G(;OG+SkopTtCbYtau<=E5>bkHot+A-!DkOP$-Dtmu3TDf^(* z9X*=yxx_pqhe<0-I4)Y`P#2XLRGcE8uRm<|&IuX|D zZUIQPoB)EM-%rj>VuOBj_}CWf{*=>iVa7cNnssrUGZb&x#Ud%jgh{BlClS%<@5Gtr(_#1@;st~m4r-xK5&m9T#H z9esYp@`_$AM~GGRk^>pHfz9R%#sgeNs0d7U0fj?~f1v-dE&QW`;^#D^nI6P@svDEA zhzprLAGtV{j8Xv5m+S@;#QAT1VL&{r9!Dp2?#*Fc|@)n9#Xiz3BEiL*9UK zLXK(gv7P!E>EkZ-07YwoevIzNdp#S6&Ghqks`Mm7(H?CF$ZQ0#S;Lke3qJ0TPDTnA zh-1GUd%zyD@H7(%2u$XWs)pnf{3cD{bmH)sSVZHm=LTbXq02gGE%ANGQOTsr(|=7t z(|LKe?{!Eai^=tfZF}Wftzfrx-_PCd3Vw@`V4rbsML7pIIGXNyFzaW;-&Y;E;HsMF zHwkX&_N{(sa!T`mFg49Uj8Aen!OUiDo+b|P7CBSg zRpqu*<6?--^({hOZQ(9VR_R|NYwbju3~_Z2qeq8_f~ett(e_FJvi&fT6XyNC`482# zsR#gaP9--1P;kfiCCr~M2LQH2(6c*G(h|G|0I&8EV7vYKTQeJxIC=;wGW#)2k$wo> zyxo^i<%eeq?@%{{kd1K3GvT)02J0=p2+2U3umWJ7>U~* z*!Gppt);5Df4Xo9a9~-Qrst@=39#BFo78a4=Vo2_D^Yg(DQoT zCOq06x<*As$_s^w)7`Leyk;RJ)_oqHMKYMv7dFuYlN6HsUI}9Aj)JAk-Whe#$S_TG z?(cm&<&IWa$IXQ$+Rx|XB1D$s{hNpcN6gX27z}ca_(Ngr{@9)t(LK}OwlHVs--7kua`iuA!o=@C zXa<&~`Q?^A(GAFx64sTXor|Vm zGn4SBsIYT6;7Ro0dLJSU>6gzw@z97ft&0hAa`MgCCXbczEA7zGA>1BZeTgvu6%3)e z=wzf;_Y;1V<{cKDpkj$JH*KH;+Bym_f#lBHtIc@Pg=X;{< zsPn?WIC-3>x?XDwLUg`(Cu&dD>XYZ)0)9a?9~r8CeylhwoMouLQF1imkUbmBwwBtz z6DAXM@cW(Q%Wu3#m*N4@rE!5HO03>D&RV}+%$@vBH*6s3HLf?c!t|reo_jM&;N<71 z!V#ulCeq;Xy(-5Dqa|FsJy3K3vl7i78i5-M3!`VO$ZrxQ-7$2a4AR$7#F8p|vT4!m zisRNQd&}^{2t>Lm{bjYC&5KN5361VKB3Dr&j5=4TE%}OKv4R>kRLie!( zoim0DBofE`_)zrPy+3!-sA2=$AM_DwEWqJfCp%Yxd;BR;Qi-~n&WsV=;EqbSpyIPM zd}gtS02fM+76n?BvwZdvas7|mCM|sbi=BWdKVJg!AHfs*zYScZ1oDK0h#qgk#>MhJ z3=c+g(ND*XkQZ?g?L%IHhPb#tw;~%)cLwCNL_gZ%WPk4ir8PdZOJO@yF2{fQEIV(T zsUR3m`@#Kpv*jSu4rJjA#@OfP-m3C98#^E1i9=I-dFaW%YYDD*Y#``TqyQRUO1Mng z_qJ3VFzJH(S6+NjW9!W-4w)r$J}-!kneEMm&4Qyk%GTKuv`R&YI;&DK%iTIX$KORE z{W=0AVLzu1J2a5@W+M6l8z?_q&LKP7kJSlJviBu-(0fQp(r(Hy2;44ODs~kTCjkC zt?9^mAP(80KAt7c=_&R0fYJOWGE=z~$3R-VC;M24cq$=j{JF2`0GyAK9zrVA0`Bsv zKgKQ^b5uDsIn2!V(oCs4#$z2_Y!Q)LhfH@5;Ui6Ql4J~88v3b8e#Olr{c=-47fMah zrc*Hbb}llgDOE(RO+HlXolp`=Yc z%I9_Gvy{&Y`5sIIAB2&u_C7l&6m8b8>wxPYST0#Q`wUnMnz`(6^p?A1>PZXO_0`)L z*W!QwxOR8*h15hWnrl6p?_)E)jznLgROf8_45yKEeYlV*=JEeA_7y;Jby>H!8*99A zcM0wm+}(q_L$E-Q5VUc35AN;~BoN$_;1--9A%X;lgxAS8^ZzsR&3pB#sHU4Ls`onQ z+^mA&YZ*@v5&s{REtB&O0s7iLh-ov!2%68+b@U!HsRq3T*`9MWy# zN$g_EpWO@Pxat$(*U~9C|4;g-H<*eYH{{javn7}nJpo&{tM5L#<(aoe zN4{k{wO|RC2g(4X5+=E&*nKP)Xy0;>6YNH~^^-ldzOpC&M?cec!yJXMcKwmW@TE(Z zXM>9CFUf@M-nViF=e^o5nw!@r?LT4mV#X}a)>db{mOXc3tR0Vzt_}QkVHuk~aI=J47U8ZC-G-J&8_UT3GVUSJMk*5$~rKLkHGm z9jwK>7Ig`?iv$o?sv@=nDSv;d)w;K&i$vAvkIcp#%8C1JMo;UiR-09VCdml8%YHuX z-EDM~N1`sR!T_(Eeya$0ryj-BUmA0qx`r1!RolM6s{35d|w{$;u%hc9aG|kxzujhd07oFVw9R#`TB!&-VL&rET9_ouBeMytbOT8)RJ8XOFC#K8>65~ z?iL$_w5@4;3VC(cTNrIs(Q2oEv~cB4F2EQ>(^y`Zz8MbI6K#pY8KI;}1@j#`L><&U zZrCfeR6MNyGN>us!|#?kuYxn$g7hA2I>Cp_!N)+$ByBCYRP&ab*^yOQ-Q58}LG!hF zp*a1e^)I|-0-oJ6hRJY!iWRX`Dzn|u>KYx4;}p?JDoQICCYv z-nxwF?eql@XL6PoVu)3x$Ib#Y5H*E7q$S z$y5wmsv+ekvt&Z(!*y9ZOi0L+j|f?i5ogXnAvI%XFcY4ei6-r{>v>9f?6IdOQGT3M zY>;=9XMG#D)<-)HQhhSwV8=*>!ffUgCDr9UH%N@Hz2sBECVMi01qcigtqMuJz~&Sc zN6=Qn_2SE$ceEB&?0JDv30hh7hL?NiC)Zy+n#E|o>WCZ)SR7v8&hMOcc0H3j(`a98 zVB2KxTDS<}&KQ*AZ9ED{SP&GPr?AkqQRvaoRogr(V>02uo=8@ist+p!3dp#T61!de zUx8MnPqrD+EKCjwB*qqB1MtFlP(F(D|3+DU$JF4Ni0~e^_>BOjCZGs^4=;uA{QV05 zL2%&fHUrEJaH5xO3%ot@tGXQW^8Ah^FAD;jz&yjfPildsS zMmIk5l@az~_s!vZF`WSDJ^%vSEdnth%rNHFB%1MNYX!p4wS9r=n6(&#h67exmINvg zc(4>~Pza8uw%~rr-&0rfQR4m=*kAGkOpjmyNdF&bUZVYZgG6ir9s1%$d22@AAH{v3 zkmR`Gy^~GEU?fL6gFvarMdtf1Y?>O!vHdXLA9|q}!CKAwgco&L1Qk<72K`fA%{YSU z=jov;t6}a+$Gz1@83{$Qt-%PD=>8+o(y{2DNGC(BGg+mLO)I3sj{K^ib*Y3o>F8zZ z^zGCPMOf2O?>SdT;mr?^^gc0=$IYE%_Lz<(o}|Okh>q;oQPMnW}+rbOJUNPCn`o9@5rkq0DeT3NQ5R7 zdyNKH?MUHxPK5xd2Yy~V;Sj$5yT$cSng0XA?~kZ*aO9}JzcUR6ss;^v3O9RDTN-3O z`vt^gP@8OG5@%i%0c*^5l9Nip0W3?HK}3 z=|=KoC@AdGh9NVQ^ucT7MKCE5ud}V(07v+l>U=g|Kc=)*Yj}D{4nK<%2&lOPuUPVL zEHLOC-SUxOK`^-RGoX9`JL+Ce6b_HYzPCONq`DqgHiu;RZCh> zqWohaPWn@SeJ9m4G;*Ve){{lw+db}go!!fQ&?l}q5ex(}h&)123Eb#0yDgwZ4K{}=*?|MTS0egz z^gUxb6u)A`CJqT*D0WUK-$uB{n(e5DXkm6jwn+VVeRg!01H9{TU=Hb_^7sO5ve(k? zCvsVQ}ii z93nBSz5h-Q!QKf@@LhK4pGTa{(}RdMeKVROR;33oG3|SO6QZ&e6h840?s$3$U}-o} zkANYV{jr#%5$r ze;fh-7GL}8DHRH;oYWfHed7AzO{0=JwL;;arTM|91Ay?RGKkdkuzPYpEtha8CVx2n zqn*1gDT5vG>SpMWvEEj{C+S1HlsW&Y=+-yFf~VEQVA_(Gs8{tBIGVznY+!|`s8e5X6561Wi8z5I^Xp3~is1rV0lg>9ccW^>%Wj`oZ_kH|`~}@# zBwX94EzQjLIZUG7CA-IQ;iVJYPBii}-@oT2a?O5tCJr^MK@hitTp@V2`#Y&WQM16s zUoN=pst~dkm!ax!u^nFX7Afz^;_$f} zR7biPWGt8~Ri-~9QyMyGn(k*LRTI)t1MxR*uenTj>6=6qSoycMbawaSBy~{ZUJZ`7 zIOELLZSw|_sJ=P8SYo)XfMxhSzQ$sD`awBsmTLnaaa$oSKqJm~ieOOz^d^Szgc@XU z?00H2h-CV4D3hm#!FaxFx6*Z^*mr=nX}D)KCU9V~Oe4;W(e*1KddMl`9wQ|Po=;hg zhB8ZmBT;5uwVjvi!glWd(amLF(@!x%M}%qvtWJ0BQIJbgI&>`${Y>@}rR-~7<OK*$fTW|%cb4DZKNH1>$= z9oiMtuV19|G@3g@5+ts5L@s0ELv8GIV}dHs6FrY#Q=I4#omJKm(UtBM%wU7u*R>?= z8=f2HihV+*D^j*0q1#}2;Y}MB+E03mGh}?@Hx;53ubsKLrB%?7v}Isy01rQd5~cDX zalbit%)h3IPv+naMNT15R=v>d|CnW^U?8c&_*haBkla~=EifRK2>4$_u;w;n0=l4230Nc;9afetn|rf#_+JI`L0I2` zKvdVNP7sVvw9))9oTnoY=L7Tz(X1eg%$V=7{fWbS^BfEb3qH+>G<(C$NRi$g=0eler9 zzNL5WkFV2N@6>2Zl*(>&$z-brnj{RV>f2ZU+LGIJwl!LuZ+r&6eRV^D;3 zr|tG3Pq1FM3S-pDvOxv|_V?_-jd;uk|vCMt{-JKe-eNS44>7zR%u(M zPoaCw$(j((%kHn=u*HYYD11(KfRGkgg@wkoMe%iq7G6V%>Vqw)LHrO44P^3cq6{<$ z*8>TaRSZln7hh}Uu68Euxnznv;Z86^^4+@U9Yd_D1?UId_N$e8g#%B6F#bzV{}(mQ zt~)xn0k1KN8-9e7_7+a(P!x=>5#UX%2&Vy1z0{XSvEmMKzhf-M();I%r8-(sVEd^T znUXO{{q*25#OC*bQl<6-wVZ)149}GDl90QK<+U!l-@dBJVa>9XBxn4Paqj zJ!^q2JK0KEug4pDgEgZ#TGn8|ou_P!XEHB_*kfut`&b5WN z6i$5NWrAi6f{NphcUVWsuWW7mmT8z!K-`yP@5ozZCY2(7Mwk+P#5+2kjljiAw7ost z)A~Sbbxwp`6^0p7$+pmfq;L=Y&`Zho`m*u}HF|#Q;9@8E_0127j%La$9e3p?P_{BH zSC{_R$?^Vt>Rg-gL!y~!PMih1yvQuiFqpph;0AK$zJ+f1voqEAg+MTbH{7+%7drtT!-G7nRgR*JGdwj5ZpTq+em62 zQG<&q7@3dN`ZEI4iKo)XR3%2pIB!cHC4`LZVBxLshcRbaCW_FwY9t*sG#)B~^bkTY zC1{z$akDA@0*9QQ@bR91dF55~(**g=;Tu6nP=NlPu9AkgVhO!T->U$KN92rx9fHBK@lZ7pkv^NK7?EU^lMQqJ`n zC4$n)U4sxQuB)-d-uTui-*9D!k5x|~jJR&~OY`*GKDtxcw_mkYCI-&Ut_gJ7-WE#X z@qS8tGYe=DY{giD}ilNbV z4m^iC;qF}IpV8Hchnp#VbE?OydusmvRpx^Epm!MSi|rLyE?#&NN&lu_)t9}i>Ca1) zLvB>>&Lb{*C8gOBl`e?5hN|yghX)f=a?7tp7wpF((}%2$R$rSA?s-Dfjp#>5`PsIo zj2|bO<0?OEeOysKfX9N`$}mz!YN-K>UetfJEEK&?t}zfaT_D1SimdMV3KK_!bqlM| z&&5ER;zS7fEd)dmbK;SemJhR!=y2-8%ag`LXZUG+WL=1Wze~@D6CzvgUa+&Zk)H;+ zjXdNU0aV~mC46LKKJ|Zu-2O$8{iW12HQ;fnq(0y^BYdvSG%;P|cXAKezOr+!Vhv*| zR!G}w+B_B=l>^XQT_RC;U$_ujLGABjR1q&-N8nND+nv1aPbrEd@sRZ>omF@dh00BH zJWd~XYYeH#cBW+3u9n*379b!iR|V{4-Q$sSO<)K*Kv;CrVR{)C3;>T*=4I#tpm_lJ z)mY?e%7k6yGb5P{*SA0oD4*s(%!z-BZUPSpJ!HxLi&9Q>__QK)f_L}E0-*43D}XGu zIbWEt*?CyNXz`-<#6q^eP*Z=tP4Wa#ZigQ9Ft8qrZEK^=sz5>95RlZI+#WS37Xt|U zjEB@n{u9m(Z00}X7oCQPYyk}Om878G#wvp2764j8+j54>_D7CV3vklOzukz8=8GXbv1gI>73|#DB0EiyOfJ&@%u-ra~MGb(NHA?eN#;q$ik4KlY z<)FfzrGQwWC;o;&Qr45^yiPd|K%*RL{L~x=gVA-7)j{70U$y|VOXAaG2ghac^L=wS z_K1E#(DTa&N|GAuEWa0%o8L@a#ma|7_+?lOX&y1YcHctTx66)vQm&tX5cj1pHc(9n ziGjZOy5z&lb-(U-hp}K(0ujVFtUPj^5$Xx@FU(F>+o$JQ`Ar!}>ue4qr%&JSKeqH0 z7+bl|wct|@WD8ph*`+V%W=BdM@;s0GsXKyBm)o(O5X%-6x6wMITR+i#tR?Z2bIKv3 zzDJJYL$e%)#0;O!j{sfBB#$@PJ1E31a9I^?gZJ0>em$si#_>XbT+z-Z{m$ClavSlT z4inZLZ^EyHm&c!7#fE7z^P>e#@mf?qvn%Fu5HU89t`KqG6{~@2D13)!KHDFy+v`y{ zvZS06;F!83TAe6JHw&(wxr9m1Rug{g^cy5!Es`OX|;s+TsH71AJ21NQup3H02;UDbB0R z&sb4oovj7YVMep^O+&$4Wy%zoD~8y(x~-=p3dqM{%;hrtLgU!hpddoh`Cp5Tg=FQy zECtU7Rk?iJDUD8EZohIu972OGwLBHz#EZ0>s)nw-U|HX&*SB*SWbU$J{XuVnv(9B= z*aSTsj(TM#&d&K{U@m~0zP6=Q+m$tmxX4}Q{5e&CVk&NCTVc^i)rYUEFM0#Sb4IO< zY(;oIY^xRL^Ua+~d0Cv|$wyXx5o>BPnk^Vs@z~+I+mwEo=v0Hyk^1xJJ>Y>{V{PL7 za zfhPBR*_GKA7ORChsM+|VS=I!^Mr6Kou85S2m!q*yU2I>@-WWFZ31lJJb`0w7x@7A$ zW{KYb==`&^mYQkf^N!Xo)x|Ku@7yOhI5`6n~b$ur|Ngv@UX84X)_m(nEfX|zrQ4& z@#LlVK6y2d(gzBMtL$A+KKFn4kRR2gjP?CPW48SMjWoG{2j68}{yunWHqa*?rv*xi z5+FcZ^SUMqcyXfz=w~&p5EWq4C}bGM29)2w_#R=fg~%Q1Je@IT`O9H-#MtkoO$P%x z++xg$4S$0#2`mn0_@=n(Mz6+8xAeDu4aS484=DGz!iHY&R<2DAq*J%IP$4nU zvIv}j3OZS0m!haL>$b z{KL87f(JV?OHl6tMsf;=*#n39pB`m!KB)K~F#oz9%3yTkBrKX2E+hG?KN%-ANHIHdw03Vr-nvL{1=CQSO6Hzj*OUtA_d4zow%ped6X0h2F-ucrzDqt_RiV(}*_U0|dJ%_ni}JoY1o zg~hQq3+C~0Dw{h#LyXzKE;OGa^e9qIKdp2ek;&&MJhY@FE1zd3RzjDU@R8#A4$VV} ztc$f#ExSD#HeGNg!tmQ%!}GaU0I;&*ID({J@&1EUz*)t=kqTjvYrZ}JdB1Qvunze8 zmm47%@fLV{`RidCUnixV>kG5}9t_P_fE92 zJ)_D&8thAsQ0~GZl>}WX!u0m&2aEQ*KsFLezU;V+3$t=>*C$%Z7)XMo=h&)WMwkxO zo2`~mok2!_X7Y=_ydo-HWbJtUDV^oD${k!-(Wg=GR@1Ku)pM;A^wc%ShR5WEbnO#(i=OD z1_{n%$;R0_%g5W|`LmT&udGIIlN#r@2MUS1uliDFpU1X{Pj54Zmg?n(N0(yIvFh`% zis9FfZ$L#7)mw_(goZ2+g>5?t9K9iK%N&fuN?uDtc}6f45BXOjnA@my!%r?;h8ac* z=N_d_Z6%62#1>pf9K(5d!A#zWqJ02rr+H)06}%=IyZD~)dm59Np{-Ys8&5pbCKw#px@s@XM)m*&9J*`!&%iWt5zyj+IBjKm@)c48-Aj_^T;$|Q!WJU8OSlbeu)tTF^mp+H-0LVmQwwT)vguFs?%IoZ*5Y}R zLpdc8wa86p*}T2n1u-oz(olc_knUyerm(<~e+#Btz>r>CtUm+d1A{s{a_4kLwywi<4l&r9I^XPU zI};bfWDe$5@w0{opwbFvjd|aT=wK$Brfn9W;nTgfjz)Hz5V=t!=slx>H7Fj z@+G3|i9oCptT`r8HAU6QuDQ1hsgLdwN@M*>7JB$gGrm3|Ytg>QMD&p#h)+?p9ltNS z-w-LO8=1DlES9xeb%t@mg3qs|_XEvR&uRNR$#*Up~$S2BxI~BS%O8Jgi=0Z~>wWNXX zX!ST<2|{bJLO_(?()@dvwS;o6c2&XrjZojAfzY%YLDTqc!kZe#2NQG>$ynO9t{>8j z^r?d}c;3$(C8)%NL~+>$jrLu?-ix;Ed`7uGenU!LU%eZ;C4A>;`S^O6`#WOza8qFJ zrX7MEzxES;i(n!7vb`3+EZ#u(=c|~CAv|%v8hc69*b}ZdDwi!v@s0579!+?JFf4sI zUvi|S;ny)SYZXSV-a}^@dU{HZRhw{ZSRdppu~(C|`IxlaHn4G&TckJ4t)t zB^=?n2&PtETYfC&uJpT8JNRnZT!z55Xu->)SQ)riY4=35Nz`ND%iMQTuN=_T-8T}V zUv8(F!DyJRw#5x6@jaK!Lg0{%N6}V2vJQ8Ij#opHzihJw*NH6W7j$Z~U&$VP6l&&J zx>{>}?r~s!*PAojIZMJ};uunSQ>|UjWV@|mac=h`Cv|e@GDjoru_s0|TH?*+$1zUS z)mA|7w=Z!6lrPQpzv0!t>QmuCuM9xmwGZC^$O5rH2>|f^cqzcslB$&e|C|tc64_P} z*w*~X+g-0}p1GDM55a47pCSoM?%wqQdjtp;*LhGR8xZs53Cg9--82f0DA%ozA$_OQ zlW|fXryV1=j#o5%Yajjj$=|Ra&%Og2YvhK^YmwQ~kTy=v6H}*jNvCMqZy5z#rxZU2 ze74J|Ao9w!ZVNFz?%1~=Ib_iHIw1fZspWHm*!*sF(lRH_mheLq@TeKYk|>g+7X4fb zpS_pWP^%AN0FH1Nj!^Y~5&j!xfb$5O^Z&hs^>Cpl@Yp`W5i)xHSd_f0*|_f-^Wn*f zB(5a6G&CVqwU`=HUMY0cfVWY&Gp9vD<2#vc>+5g`a^?>$CN?Wk!?VD?{;sfr4jj4B zfgNX+Ay3ze&nJ-7A6!v_{2K_`->mCCVvY6zO)Fpf@eLimzI(UWI2(`aTL`*DkT3%L zq)>|hLMOITxKs!>n#hcx^E@kRU$`4>)vdg}5g@wWvi2#(f> z!g2#4As`}+xht_Xf-=xby2v~2ePEH(l202azu*JU4=#}Use}3G7MqVCDfwnu`&Mj| z*;ppuTN-D(e*VybPic^AHWY0A(Ehn6m)I3X{Hx}SxOE!LOW@26>JInN0oJ3huySDN zS)g7r$!ZuOh#5J?XGj(s1uQqsu|*18Nnlt4Of>Ml7=%OkyXX3UB)98D(kyjJFFuGyTSNyi8+hm?#y;l?a#so zwZSphTtQ7u!VX-6Qkp_Ot?@gBZ@lIJqgAH|BJXpxwZZ{y>{HbWFo%qj`xkl8iQn0o zk?zbf=U8lxia+lh09M2!{L~JghOvVIWtRME^|gcKTh&?WEgplam<0efgTuIi!}w29 z3a;UB1}F>vAwT}fKY<_s-cqUjNv!VheqL{HN5V0;Bhhc=>DN{`lfT__oBGGRzVPLF zx|!6M2!p|p+HM=xqD@-13GM`}Rlb(szPmiS2|F5mB*r|c{F8eTWj1fQ_@Y?Y%?%@} zGkyhgJj*^jcS#4VoOz~usMa7GfDu3-G&gD_Z4;C0ed>QNEMr^{X){aGQ13;qOdXA+ z;v+ia`(v`EallJDGWr||dzyl%64giJ>NzgfxrbQ#<3a{%U=`I|z2(g`hy=mDgLCIr zdg2OISCl9ULQf3}hJ%O4&ZYlOYvF<8_Bc3ZutnBy5&@}14et{&dTsLQ_z+w_iESb8m_i1Ha?Zk#OINH|HD*NOGntl;1H;}) z70M*8w3D)Wle|a!s8C8iLtGY+)oB|03%nNS5ovZ$Xuzf`KQfx&N98-HnDEr!stIR zO)ZXEQX=-Xv#X^H(h5 zcR1oNu8Z^^ZIu2x$As^FqfBF$CV*W&u{XY8e`&}AHt}I$U|K8c z(WxK;Wsbv8mRE&I>-yUpxy9+0BYAxOtF`N8ZoSGgQ``Jw$0>sEnwhS8#ilG0dI0la zh5w$j#RihMa7q2?hZGu+c!@s77n)vuG`Wop2}?8_%wIWK}v2?`q4C| zr8NWgd`S?6L-NnVm$#W8*8ddF*afn z2HqhtcgzoeCpB4s@{HWhx~rdF=iz6O#jQ|^E!~=oMx<;79y{M?{C-Dd%f*%hI^;@^ ze{y{pLJ(g)7OiPF?&IBY{?jy(?E9N(NdOzcoW}1Hyn8For_um%G_LQ#_4wb$EC8A< z_zC_1%2#3gzZz!MDF6!G$4edF2QREe#+$k`eetlIQH?d@h$b8cS#H>-nFJ+XB9(ML z%VxGvTQxV|xM`7+_byC=A%9$E!|o%G;WiW~>X}AlkR4%BZK-_5jB;oLXfz=6j8??r zX%$u*lbLh7Mjt{pk+(vrE>H`vJ0*=4LFqmZed67gH^TIm(gt9MQd84Cwk! zK};=3{36%h>;p&k64$wK9TRrG=WfT*e)K|wPqa)`wDLaPQ4(*kjXAc0Gc}3;SNEqD zT6e7U#Ea6S#rC)n8-iK4Nwt8DIho0tAz|f>#;0OZxXrO`shon-W1N~#V|sod&TqOz zq$KC2@Hy_|o2qh*kj&Nw9hshARi!WxfK-JKX+G543`I}p3(r6>5@PuIMs{EGHiT3z z^K|1csFayc{p80#3!qgv$#sYMdTVB&$#Ks06J^zW18tYan>2k#LOJA9AdLx6N)~i} zVjJAVAz_b&F=_k>S%9fxm`@u6b~TZ^?ph|GUQqC%JpH)pnI}eZJ-hW8>o@7!)5gv& zw$0P}W+Y|A^GA0=7>dC`4TAGGk*aG+y}j4-o4{DwWcq!`x!^{dvw10BkK{TIN`8l_ zfk)$q{?j$SI7`1>lK6S3Lx%nk1_o)mZpO>4FUOyy$vfwtJ0r&k+0tk?pBtxepoutd!}xO7X=^Sbui7PY7qntLyANEYp!&KU7BwI9z?I4!nepRMPowA#mypr^zj@s_0VuWL7iju zjg{_ND*LvQgZ0RlS@uapi2t*YI?pucE8Afj&a*=7d&TvJA@M1pbIua*B*L@s?C#^J zMP-T$v6lteb&8mb?^H^QzsF3{9;2OHcQ{>E3#6BhwJjzt{o3r3Xqf2G!~`?F(Kf1& zcw8gc^yE>9%h6jR4}va!*7lmkt@krn2Bb`o%3OONs}ZJA)Tgx!5@n7RT4QSo*N@Ou zee|i@7S4F=wIRf+sq`_ml`m2kZFR;(T9);kjrwU4*Zl3XMfWS`$FU!m8dEoYD7!WS z-eYh`75FJoGmS=V<#3tvCC4bfFs4|7pQ1yHGP$jKe0gUxAQ~?amzT z_n>xhV_s$s!OGR~-O77pVM-0Zfcao!MXdU;0?R@ZMW@(MnU~~=Jlro%!h(j@lOsw{ zR{93|==L|x)T|TojUGS5hdB0HIUsdb@aa#mg*F7??3nI#STUGRv

  • =N*gHh-G~NAHUd4XnUpZwkX1pxu^ouF$8&;;S zFF5EIk~;BCfS%;t;Hhsb^(6|;q!3N_rKiOzJa;)3ai3?#IO;Rw+Q+dXFn3K}PfMGp zKvrmK<$1U1YpXkdPl;&sO?JBZ``lN^YWB1!$d7fqzi}vC#Tq+u4k`Bx3cuXnV`)97@O>dr zWP~?x&d?u+!H0)@(`unN^ghASUB{!kQ==C@i>yBc5g(rRbWgfB#ZSsxRL z$no~N-ppB!R5td7$9Gqzp=Sv0_m-$)wK8-X4Kb-kOi(<~N1E6p zC}Cvo2d4MqM^kQUrqO!twXEXthBl_g8W*wNVqPg*wBe>@Lr$kQUiI|a=-vwWdDr1A z8H*

    hq2lA|H6vOdAf)$CQ!|ShYW_v_LyUk{U`L^PG@xvBL=(8YtiRUreQcTD5?P z6c6o8X^_7Nkp zOqx0a-@BQp)oI9@K2fMsas}@u2*+S&OSlU2L!KOkCXD+kcEexBERqP8Oxdo5;}Qs% zc+B=wkdz>Du5sCHkwG;8)H`&Ids<`i&v$xmH$Qnx z5`}z2^}{O6sIQ`-Wwm*07Q^c=}jo@34?q51`!n#eMf_H)OA(es(BLw3&nEmmCCrDBRf& z!U0Ac!1$*ylD=^^LI7xgSK|1TScx>ZSJVY#V*Q}t2#c_q#T(D=OX(@KeHd<12sM^l z1t4ewh$V)uJex&klCrr60L&A@GZ+#+50fIu6y8}H*+2@4-r0+yA4+KPdwVM2ApUMp zA%Ilr|FR*$+JF6qPv%WlAGdPqivMo5CGThP`>)8?fGw<-un@tV8r1>_mY`;?OlwrS z&R{&X*R(xkCc~sLO0Dt1jwWlGLn{0ATb)0yE020^k!0$!_Eh=wCDWRzdkD7=LHZe?(QF1Mo44U_c1t zZ^01M*;m`-FZH^j)Q0EHY{pf zK$@*@yqwxs1+kA_0*2V!EzjMF-lZJP#w%R{b7cc|!f|NTcCJ~yl`gp|`F*z=m4Q4% zm#k8}C#!UqwrE?1TOg#A-Hf8Xc8<86{ClcrD}Z<*vVGApn#JY2om5>5to?ZueURIh z80v84qry82%JS1z5K{t25xyG$5JTY`u?|P~U+jW^qRVBM0aE)nRH8u9@0P(c_eW6p zKXKpFXhN#&CLeY&#;_26qW8kca&WZ0$5RUt>WJpyhmD4vHDodH;-}jlfrLrEuqDPO z6{ISd5V2Gjd?bt>@6$v}ke=W(?IJr@B+PVexJDbZ_o19WyyIzL;~pRKa;GJ)cC-t$ z>^-RAC4E08r9m^J_#iQr`?q*^)%+|pszUIBDE!F-&<+7gAFqHga(IFaH*Pa<+$S|g z+jesKUI~VHsV4~p!%cT^rPM1^c#P(+is!#2e!v|sLJaeX$(ZU6BrgOuv{jgpbq4{& zMnv#QHAtE>%7klRz;JrzUMp7GD{)Im+e9ppAS}ov3P0czp!SCTc`H-a3Pg8ktCwXZxju%-iwo(YJ>k^3=+dvu_{rCx80n2dU6zZTI%*a?9=a zJl_if)=jAsF=~ie7ee+TcE~EcJ(k;-p@Ir9Y#PH#F@@MN(NljjcKz**e#aZtp4+2E z-$B)a4vQYHX2tP`g719}Y8D7Yez6<*LK>xIMO^0uavV0TUN$khh$K(F&8s(yX4>$f z$^CDyTArP6wknX0EwB(}_Dc)Wn|UZ!o;=19pOXwgvEgl@tNY;+ivlGiWTzJ9#wD9TF`D5ER;~dM$)au$+s8WvYV%H+F zHX;(jgTuK;xNjWRF-?0*5waI|9lLhF)WIgm6{A7J5zSxp^i|G1^9os-<6n)hqGaW8 z3=>w89?uOHbA&DOeZt^;nbTJg9C+LXJI|NY)cetJ+9K+<_j4u4W2uL_yUPM-Vf1IgsEvI1d^?1rSzAmr&n0A$ zSR(1w1Y>oO?{K6p>dq65B-Lz0hb_PYF;yIg{RVS(Lr)!1<`I(04HB+FHPnG9tcg3} z%g?{+F>(|zlKDHuKbLlzue;MJ!bC6bTGBC2tudhElz+B|1`vP2-dgkXgd|T^M(pqR z4`6ceIt?t#p;Nz`#ZR(_7%sXud=~h8^r9nk_`dtGz(ht^@Utk?(;=Dx^txPqkD2#W zRu;XU*VmphcGFlrYl=XLz&n&^KEA7KFaLB{QpV_^74FX%?}(Y|mM(GQgKS|off65y z;r1_VLx>DT>w&0xV=%m_RccD>ELm^XAIMAu7U7^M(0AcOyGO2C9@Bq(lcS(~=l@21 zerJY7@&W>(%ioRfx#%T+D`~_qku3m;+<}1z(I5$Zy>c3x#B(0NomFBoVsRak8f`rY zQ#575HC`j_CCU9-Q|?UI*UFAs3Wz`HlX!WV_RhSh$_5)_AN^>eEkHN!%_v=0D8Jw=0G`ydd<$OHA!5cs$` z+DD$`ZkcYipm`Jlem_92AFhw#rAN;Hjkl;S6T$#u5*Ud8{vCrP*fd6xuG0;p5df+J zIBO+cy5%o)%!Ow`n7Uv40nr;RZsc0gnJ>swB>FahT?m3EGO^YYNn>fP$IO&m(D|on zTgHJtb;a?dy>m_~?Y0va2?YofG_6fhr-Lb;r&KBM7xXf6cKf&Bu(f& z*q8&~r4M}eJcfhTE8LI?tFG^96eJ4LPOQ2?bRoS{SVl9S{2J=!OQ~5OA$#Ip`R0iv zfV2(=6#)k|_4h0EpI7|<_`>62b@>nrI{p!z0NuETfC2EeD*#F>)&l_kQ7izFw$LUM zkoeEz%>{aOe$kXYlgjQRy6d*645Rs-SqPc|sf-~uB7pH0v1@aUGd>QF zaUs&9C!tepHG0%mL7N07DPkQc*3ykBFKtuL(92Xbw&GCyfkZakpq8Q)uCN)SPpfEWP2*Xc(5MN2oZdmwiEPi+zN5PzyBi> zyc!FYdTk3@T>U0sM2CSoVUSe-6QG8bBUMR4O|Wq~2LWC9(L#ujdgT%UPjCF|n)|m* zguhl-VD=hc+Q39q_URiAZ!3xY(>(tGaY?flSRUairTUL_ZUS9Mm2l=gfcV9RP6|Lb zJpJyXD#U_;K8$?F=E|Yi;mdY|t^B1_=Z=j02V3TgL0Y|9WZEc64fmB1X#FJTX$j_0 z?czJSax%A+A~$E-yTjpNDfgja#m3;+Y46RsMaz; zB0oL8*bDo=FIq8ZINNz!n6efO<7qbIa=fmh)O#+KJvd1kwYl<8i^Re571C~hgZs(m z3EvLeVV;%@x5I+kPh6DBkP0cAM(MqWBLrFSfSix&6eTk(ysKz4 zI5jDTUTD0F)UJ*0o`d*Z`Oo*B41y2FAGxPYKdL-6w87>-K$i|fBw`L>)*{7$7;S4r z;Gpw2q3P)jAip7&sUfoN&sh$)rS6jQZ4qiI=bSI+1!H(7Uij(9RZuDapnF_BVovpy z2};9v{DNXDO!M>O{SdXnUng` zUavZOf9bBsVRQiT{021<`hg6ZjmWm>6Vw1>>YErwnAlFXV0>A z=)A_U1;)|`0_M~&u2VeIO$S-YUP_>oH`t!7HcH4SNq6Tc(ky+0nQ6CzEoo=IaYbxOF`@zony&7HC0 zzIu3TsqzHL`Hg2)sQ3;k)nOp{TEW$l{EFU>g>@_Wf}&fRi&R=Xlh(X`{pk1J^F_4k zQYTM#UelHgJ=oZ2ijP6Rgr@^*Rt{V>ao>IiA+!;NOO)}iGt=Xsu2$BAAYJZn7 zO#S9ol2Bd<}Gn%XEr(qLWWOr6bI1Sig7UEL=-cej|Wf`nil%9Hrr@J`80=x7-HNd$FD z<$J0AcHsPbGpppEFqCN|{~bB+l9Da#Cf<_FHF!egT^d+HDP-5>NbW01GVktQcpbTS z^dalFtamR){TtkX9Z)K4JE;+z_%3!<)CQ^)`7o0$!cP%~V~1h)Yr&jCgxuRtPsCtG zo7!dH**v71wDcy>`r{zsovsy!qhA$517UK77RTopQY7X@ouO`*-IO~o5SEyGUJpB6 z;FPtP^PT+G({wjb^;& zXs7U~8C@(u{CMET1xqb8ItRUKLac(9j9YDCo5q)MI9`OHd%h$;Ix4gjUY z&m;*Pmh->gzm2eXr)wwOC^&=o3mYx9+9%lU0N?M=(kl%H!M=&|FK-I{`@aFA_M*~B zPh=k}G!Wulnnq|mGuGd;E*#|1swc4ye;taTe?hwL{L$6eK!1jp$HaEGE*#XR^nH&? z5s4??GJnYEd)vHyklUwOoAOt_Egk7clubu2%w_a6B8+XUBJxs$CzyK&0$Wn` z|KaN!gDdN{wRdbM9ox2zj&0kvZM&n6t&VNm?%1}SFYh_`$36F}d#hHh+H=?ZF~_qe z#vFPQ)xp071;+cnAbvYGeT)Ce4ESGjVFSa8nhdc6ox=86@);5R!IK(TCio7qRpbcPPNiRi4jaFSF1>+8MXII&nG_d)Rz-!!@U*NM&z@>1z|wa< zh-fs*o>5yj-#)?)iiQx9=9$jbEBkcO9goO>xI;HRT~Kq79NuD7FizCV#UButdQ0@e zde>Jj9G$hyK_78 zJukg#ouC+oiKC=$6vT0vqv%=MDGF(5C6v!^9wd}Q-|_Q?GyPdAb~Q1p3qN$v8e}Bwe+CCH9<< zRUARFv$c)sQ=0u8M@wGNI0gu1b(vxPPz@vHfMrM<(ymE+L89n(mALSddg?LP zcPID*zmKD!(Ou6@grLG{Z41~!^ZPtsHxU-5Y-Ku7)H-0fTxoDCOU6m$An3bIfHHiQ z>q*rVUn2UAT+BoPJ4fJ~GJ{V#TtgO=3)I6sapirlfb8$rfMsC*86G>>0VgP&Og93e zrZ)b@y7bC}jS@P0^H9NnQh6F0-fSv`A&UkxZHzANRru!5b>9ugeE0F_#$Q5F!KJc0 zw)JiG4_w2~*y}xZj4G|b1l5VT=(tDiSZT!s{(lxOO+-+vz_zJJA}%WR8Qzf1g?mufPo6|A$R zN%!S9ySW1jdWN$_ifTQY-YLCOT0uXG!$>7W8nmuf@xTBVB?&b&b0EAN;*VGB0!f{8 z!BuM7?~Ee9l6wAS3j74hj`?qf<$oLq6axS3XWvh_Kd>P&0U(8iznv05Iob~ZkW@q7 zuUOKoi-U8=sLBHc&AS03gYik5>T~K>UbgEh2ILgdSI@`dmXr?#D)ILhVyCUIafd#K zG0q=HX^1eG3l@Ep0N)z|x`YN*AZvZR4G{Qg!qnX5B2$j&@2#e zHJK3!i#K2cr*3UGUDd=eJi(3i>rg@U?|@IL-M|JrJSz2p2d_26VY~pyM$eKXr1R6n zpF*tUxb38f4Iee4a{3r?m%`3Yw3Plwf=3QXifA)P`s!3~1;Ldy*s>Y?kOBUn7vIPK zKL||xpT|E4(E2j~2&qaX_uQ}a(w;TBW6iAx0Hh3BB9GIMveKie@# z&LRfDpggCDYakMYUuk+F008{A`w`IejllW;jle(C0cV>u$iCBq2WI)Za>jQX=qU3h z7XYNoAkTROAXw~yiL+D(s3;xeCCBG0=|%$E?*e(f{H$?hjCduGkLnGp^6D|<)ddQI z6cm8A2{>L0@10`zeheP!kpFo(@40Ou3xJu9KL~@m6IoV9$?p^N7>buleiti_dHyBC z2S*KbVdj4zjxAX)7Wy;i7yzpMJ@O%-?AZTl$Oi5t|F8M`?^z5?^j&Jk@sKElH~(4@ zS%}-1ga{F^(b5C>Oa~aBS`@7ONM;k=^M_*2a_NQ9N^wTOB7@wWjmRFRa&>tvMJw*m zC|S20AS*)N{!pw!EdFZ`OU!wu4O(BP13Fd;s80d^*0(OB2t5FhmQ;Ofvj9 zLWVXIeZ@qn>8lEvFH^BuNZ!0>HwzZNjIJs$#})xL=Jo+mgL7%oFJW-(EhbkvqLiGx z6^8T_b+g~EJt^dZgp(sMLIt}FoI)1I z`SQ+W3YKla5-%fB@)hYFD@`8~Dz1QBHOBHq+M(mp)ACI$#=1>T2s6$JNQ=DP3)?pP zh5gfXL~kKN`|ONE9FqXZ=38H-`u>*xLth>0?dyg9F)T>x4A_zXNBU@gVE43~+lhrC ztiAGolsO;`&^z7C95N5`qOC3pU5W}gG>1BWtQq;%a@Vg*ovasG>Z;|4luQ?;-*QMA zupu)qf!+;4%<2Q7JGbh%Hb7UNM)bLv<(XLicLgF4{yBTf`u0vKISwJ~LCob@O2BSK1pRKzba9n` z0fFor3qKb6O;#}vA()`s-0z7wzd5IbumRm`ce9kD#O#+ZU5ul$F9p-AS(MxwjBJ0tL6&*&V zBM0^9!pF~EdY0U@Zj2V&!@p5n_D#&A(P}^jXRD(zRnu2ry*a ztQ3V~6+v_9D1&Qohmq-%pFAw6r(~(CiP>*IIS|3C+pp@rx=C-CE{bAMMvTj*bh815{~CQ3jjRR!HORE7Gq{G20s8iNFhIKA?T3aYsI>&8}wV?mgXCdOo=5NJ^a1Z6-XI zf6#0_HD4bntM?DHw+Wdnm!h)m3Cf2HG%WH~bt|={L6{a$z0-k&2k%RF3~Bf+1Dh+r zi><{+E5=KnD|jKJ!2%G>f`3THyLx}`B-|sM--G{m+E&%S zK=7ObtT4fagVNyPR33SS9XYl+YrTsGRxiok??p*4&fs~*L;YF+fSUufdb}LpOB>10 zkd_Ewo*e8{7)1mczT6Db@^DPNgdq1DEzS3Wobf62dzuO?*r3H5O0#xhB2jf`h%~0wsDF(yoTaAPs z>dXucvuXGt6o&Et2JHpIUig;p+wPzJzns@Fyx$$XZQn@3ffOWHHjY6@67T;dBM9(S zZUiEl9#DAQ2>|HRGO!+AWO*1nCnOwIr4bkkLy3Z|CBtcHFuyQkQJglYD?Wu z1pRzd=gL|6ngbY~mLAv|(Nxf4sIF$%dhE71P)6PFLXB=PT9q{>M@n~o0CFNn03gMm zeJQO?EilZdNIN{ln*e|~=gnDzU2ioc6|%XWx-Xw=N9%FRh`JE)ElLbfb`I=+F5>_8 zoxTzJ9}h1*f}q&WZ*fpFUxUE>7)sM2o>zYWyf^^J01Ofu5lA#g*tD!?H-rPgy$zX* zqlUOPR-*jP^z+*o$KI<4E>IqnL`vX0JlkdGuNNl)yY{!ZAOH-4y6^OVlu---5KVze z_;+mf*A0RbrEs#qch`Rnfvc_|>Z0tST0G@RsL6~vEOZF&x&-T*QXoxW#jw9Ul=lp2qEb-{r0=SOd~>E8}G`Rjc*&|`-)LAR#) zs{N{jdwn?p2}+u2gJ<4x`W3di#ltts z3f^m}x@J?z=UXWyt|3*4;_%&92;aj5BDk}5pxh1WL0dOd0WC(0gC(v~HJFYGy=@7b z2H{7^X?4FSuRsGaI}2uFqzxpwAqJ>Oex^0&gL4Spf*CdTTOoM}82r>6)z@}Kxwh1m zXkxlzmf#m}-`(O~wa;FaKZ@*O5xhFPeBuCtov3!;yMo(E3|wC>)nx_QPz#V?(wy6#s9jmQLH7wSU_(-$B_H&j&%(C<;)<A(OmRXl7ctVW@}6t} z)hzIok!x?(gqesTt+GgtQPOH6Xh=Q)C;Uq=H0<@CbdxArKgu$LS~I{58~a`7(6734 z>x=SCm2x{TlLqn)LK_;9((Y@BTnOwd#E{=mks1Mp!0H)>?hmb7F~eUY>g~?7O7Qv3 zht<#)mny`xn51E|a!)kW;7x#YTZ$Lm^q_#$8o$KYAt7Xk!l@!NDX3rZR*a?qkCvWe zx~@z=9!fewF2mp74BJURo)*3;@k<`qPah$*R#-C>$RqmQ%0GP!o`hE<{=`6o){uvY zSYVx5<7(F(ta0SLfWj8nToy$=tf&iex%jVqnz=dGB3KZ@JDPO`dyO88rGRG(z04Am zl(vNG@5N5t-$hDzEd-QJ#14;z+2~YVqa2~V;4hMyxl4wIiK0e1y}Bo#kl1)A{}!v& z>_Oc%*qkwoaPbd;2XrQ)2sGav2AE3oMu<6A5;l6eCCY=I-46UArZPqNwVY(=A3lzo zivG#X7H9#JDn7>YeE<5crK@Xr;dRu7^thX-*zQt8nT}d7ez#4$v|%|HFWh3391^5B zz6-{U$tMLeG>Q!J*@%~$u_ns3Gk+E}^Ue(+aSoPg6_9V@5;Ty_^lOU_7k<|I=L_bY z10s@Q!^wKcx#*jf{xj|#^IErF{6z8x($Fhk%-&S)l_4}Cge!jsPuNoSHrSr}+t#N6 zt(pV!2}nxsUniG5X}Vu9_7|H9+dkSW1uJdNrxIiJMSx6BQ?+=$ppZEAIr28eH9hxx zCu11NUw@9&eC($8_MA>1M2Z}TK^OxsL;0q5woqN;9HxGOkO>#rbmPPs-|6($EZ{rN zqZ&nlMhb5z@PXQOmkf6OE_UF)n>;JKd7-4y*hsHw3Hqj7XZ-NP*V5Mb>}Z1GFWv|j zR(s*Zs z<=m3(2a{yGw}mNSKYtX5sK$8DC`Km71@wC`)|`#OSusDU*0)Mfi_Y?Ju|uBrOy*+0 z5$T)gSw;5fa}&lZTjBMupz3vj(AWj`$C8Xy!zZ;H5Md>PwWviq2Hl|T7_)ve5r zf!tfO%00+!1fId*e$Y>hYaZJuyndc9)aR&xxFwV&X&9kU*10Q(4Yv7$P6Q(mu;C&# z)d2JSdYp2w9*xSmi84+6yN+@Li_&H#Or&-U7tYYHLiT~H$>fZb`1&|+))>t}M;rM$ zg2%p}3Eebj(&?6H=Ok`dcNgYqoF%s!0%!M+sJoA5SIp_dm?M`}w(%>o#z+8??WJ;I zF(`@Znrw}i6n>HnZYXI;uNc(P%4-FA|0_%KerPis^~D{&q?_*p#`D+7U_jh| z^MOWqfD!o?CxvzE&W=ufBouOeoylI2Fq8s=<+!yC%9oHKTccb@U`s#ik2FF{YXjzJ zzXIbtoqpDIf1VH*bRy4WCQkolzWI~atOj#=Bq2rBgu#e3{2e~_5&zqe{7tj!!&Vea zPPHB=P|aTJZI*0gboYyo!7)=CqJH~_UHlH^5OBX%m%=bYS+xtpq`E2^`--!e$;$Zv z6MTwCwc=j-ER+-Z2>p1bJwwml!G#B7>^q*Le;BIz$uZ7u7c?Do`6gmC&7yjSlr`oE zrXQ|86+EV)l*{Ny{i?1#qtTJbvSE>RSS8G|mNGPYpw!ZCqsq(@geQE}{Z}Eb28SoN z-o&h^Ez+70Su^byt}`$@>}gldf`8LSBO{u}XS_trVLM^MD~V6Mb<^I^iG(>`Wo2k4 zr)2ch#`QUp^_3scI0_C!6KDCXq3pK$F8Ik0h=*%0TE`K#ye_b+g2noI{K^GN?fnAE zM`VkWs7RsNq43w~9QzLBqO#|MTUK3$sv7&z>N4OSx-z2D=)r8&CK$k2(YR2IcpS9! zTC1LgqSe9FM&Ry#k$aesVZ{`|99f3M-y_Q_ooX_>OW`GOqa~#odcV8MaN5-IY67S0 z1fxH~0samB!VVdrPRU|&ipM3dhn2B(h%R9-C#R8$fAq+o`#$=)ffDF8bP75R=djcTAYtKwr>JdoZ&$T$Oal0?9N#~F` zrCe#+h&<)_Mptp7>W;Kq`cJQ$qZv4`A)ag*M@ty_a(6_e+s!+-c?$B3*d^E>0~wOt zW(Aq%SK=EAY#LNp4*BG7nMA7~u9T&??v_Jmb1cDTR{kJo4~p~W9saz>bxbu1vri_> zGQHg+LhM$xgTBA_*j%rUyC-5UE-Rhazas0|LAQECd5M_s;w3kD7b5UahBPkD`=pJ>%gNTbQDYXiL+!({o8_ddhW_&)p)Cq@o$$YO16u8VKCwVPfOR$}WDehZY%mh$0K;@PH-D^1o)$Ob9T$%r%fYlKm^6uPJQj#e zPiqI!@rfT$VDYnP5TsnFK$R(PpL2F=fIG%!3Kxi=YNNu&_~V}CLs zdIAR`S5`I&iq;Dr~3rGs?~ zc>{f>)&^O6X(89RWq-zXfa-%my^ANiAOwWTk+WT0b2pQxVa~v?;j^=B={uu@dMsUG zLCQ}D-GB@_)BJO`FB;qYsC-GsXwLcD9&%6o=5KbGx_W0B@Q3vG8jVI3e=Bdd1-Vnvq8kv8mPGvMw7$P5XeMzMp-R)vus-8q% zV0T3CN5d62Q{Ob1Ws#A|AF#VFh4&LKiJh#>29K+j4Yr~!t)bN8@?DN3^3X(Kja_hu zNXD9rM<;NJzj9v(P?Zu(KByS#G_C|LED8o3P6mn?3daYM?Pi!)_`{Mc`FMuHDgGQbiU=+e{D;Wz3?_qAFF7_p|(KU(aQl@~?3wxa#ol zvXUzEDy5>f&-zB(IEmuCC7k6rfFtA(e3@_s*Db*hHE28bSJ}lV8KqBPcn>XFjQnLq ze-GvZ5|o&A+)kL<63p}PoK=Se3^4V?mwk?w3v?^Y6k|2ob_+2V#ZFxOC}3NDyXC}p zPROH4Lr9hCUt52eQu?`&)R!IZp4XamlT1EP4wz@^;|tIfR*GVkJ*%z6XOBN)RLJ7A z%e4}6Zv?$-mAAd69u=pw)PL;Ck;RYn*{qJ|SLO7>Wa4m;9beVa5N1)bQ^>?%njoxf z=B>ee7q4l9!9C%iP8FEc0u>?d3!w3+hFhNdbn7m>c4r*!u&Kkf0wQszS1t^PPvTX& z+eiIFNiZW`=O|b8qb&T&0@p338FccgH^8-g0m*@qMcW3&U-uL?-TwnaVp zOjE;D7(%;Lvf7$i+KiDzA>o;_;K}%{#ile$SqsEf-x_<2TEB~tmzbw4#3*x(v2mg*b-`sCZ!u+ z8bOE)hzv^B%L=A2}Z_nE-qv>J~N6wd0I(fk@Yb%6A! zb#RGDQ0W5^k;#d%2T&B*84(fADrJ^yMe!UP2tqWs$6vuD^vkymSJc{r@h~rb%Ka2) zq3%4z1Z)uqT8>%?lj(-})*B)BOo4T0}VNV91kAXsSh z`I|;sS)Gv2B!;KF657Gs#k1^r2{!pR!0!>QH7GlFu zW&yl6NgaAEG@(oIsX3H?k*W+5NHkWS5y4r|+$?MluKMDIpcS_K5bkR&^VI@#(6n&n z>nPrvAEy&0jmwPG*BJb%Grggp{{-x6A5cf~s4Neve%?wC3h)`Ok?j=~AMAS%)Gla* z1iZ^bzlN>%Ma`d{;Hx0!<+7?V@A-hyRbLL-> zz_NVD#NJphU@Bg=5eHfMItHjpYLR(gSzPcoqP>M!e(1(}8 zVvA}2P`;b<`{BsuNDCHs9y6RPy-5{&9XXyQgzxhK?YDX8hGo6U@_w)ZXUAR8>3gh< z8g~=+w+bDR_wbZgo)g$>x`CCE(3Iu^A+Kb{I5h7hJyhhsr$XQaX|7%Q%`s`2_55mN zzE1-C&bl4A41tHfwC*n|k^x|$$HmtAcCdcC&eF}y=r(nFC1xTC2dAd_F!NWQRr2R5 zj`%O9bGVbEI(T&}8Bm6>MW0Ly5Z+l*}h$!#bdRJ?X)%>aiZHLKD13 z0(jQ#eKztwr%*(V5U@3}0$Z%LSP0}dEnlX<@uTJPZw)?0KVm(w?|__QZNx`Y^LAY- zo+$y=ik?MsL{agB>_%-hsST9Nnwlglr{h}U zn1t>ttjnu4A}g^g9yJZzO+6$jIyck$YY_vwWDH<5mh(7s`lG|peYyei=PC-CBs3=O zlCmJb#h<%-XX(J5M&LHg{<1a$8UEwX0fSv2Wt>6U9f}=PU>tZ66fD0}gWr#MaKrlz zV7LO^$BYUS3hRu9#M=q;WlA^P2<@?*H|-@#GP#+03uWL0#*7b8C!-y$rK&sJ&bL+R zLP1(7Hx2I1z@C;;Bb{G5+c1--J#L9W0viOue}Lo~PwDc^CF&Gdt-r}30h#c}8Y-FO z*D}nGL6_p$zbToMuDL(=yvH9H^|uLgXIsFxZi$u5>wo{DXE&1yvt3*u7LQa!} zBR16f0TW=pS<0V+{tItrSmJ;*F>Yb4-I&*&l9zI-%Vth_YVL<0{%I5*TdS@1sO*7} zF@wjZZqGyV3c?33d=K1G5IXF+IC~g*j$+N?cq5Pchv!ko?W7#{djYRn5_=4ux^C4OM z877cd4}UT?Y%Pke&0OK~w1K|QDYlpJ`-F@RUa^_kCJ0Xa;g#+UQ;)nhS&0_cX9v!a z_K!U+ehRMDHXJH7itV4BOkW~Ls!n*;RJJ-I<5;Wpl|7=QH3GqG+WmQYR=h%~Fbi?g zjAE{GxmRGB5DJ=|PS+DP1vBEtQBKoC1%JUY>1qGBw5yFTk(EXv0aR5YNU@X`m?%SA zb3FRj!#l{UVm|m0ESB(HCcxytGoa8^I=q_#0hAp+IAmdD%HVzS6B2CSFC@rnXC2OR zS>RFKpPWc$sfzGcF<(PvN+pt1Z?B z#+VE{wtuVAyuq@js1LpoL}}%MWYBsQnPn}G?Dq)QxSlckEv}-hK5)8wG?A~Sy23sTbp47impU*G8m^$zFcRot9GQT;whbSDQ8~jLj z-JN4Ur7#wvdySKLqHQSWVSV(Q#W9GN-?IH?D&X!-v68FU1PwknH6ZUG&-n4wfaEXo( z$PWqcPW!g7`)@tE&Zm+)_5z9)>E5emYy9pwDm13h>9D|D`hV+qIWW?l;uV%x^1*H^ z?_v&yVQ~xZ_tSkRcV;lR8M+I#pwIXdA(p=xV0=Gz1-ZsQscmTg;*Hw4(eYPyqA9(j z`FxeAC^U2LL!x;_Z!TA<$;i(V=jse5hf>7>4v17|gId(cg`tA1e zj46c5G!S1KCAkDoTR-pH6REylPL+Nau~eURv-j+fSVGEoc~@yFyE2Rw12+*GVLHV9 zMWb5szL@nnB0Rq|!@og%hGZ+a-csVM9^m;>v29j19x?kZqg;P-CSyV1n7GA&YHjUy z;}uxk%DyfPtsv@=FY?96x1fk=-BR-tMXgU!jZ7~@pCv48`7mHe=SRmllJfZQA-!sB z1Y>+L;UZW7JP1zw!yu?L-Lf!7*EkQo#u+1-rHA5R_C+Z zSK#0a%i&291vTg|Qxxm4l^xHpvnXbpHXKv?kK+$tRU)y^FosblQl5nS*d_DyhuMro9S;?9{XO{eC@I#&H38%^oh8u6h10eviupe13_OBxFX&QqO z8A}5XD|P!MxL#b;eioyhGd_co9X?#ggDH}6(0wpg_n!$95At_ToGfIzn>AQ82T@9B ztQXLzX~N5~(X0w=dwlN$aUI(}s_bH;*C$3!ErF7in|d=AK`p zmK;IeCsq@GD&wplsZ~iR+^5a^ycHzS$Q9=6S(_%nE8d{}_?NluBz$}q9VFXk#9LG2 z+sJ73dbaIxOVExn>-ccHJG$bjI}<23M9UIdd)lZ_S)%oRtuw*f1=7(a+`22%S#E9S zZJrV0XgPm00W)2NSYFpo8-9CUce4|6tB7VxL$;NDplfC) zEN?kOcM8S*kzfveFlyh>^)foKK|eHx3t~<5>&H+&zd;24u1bjJvZP||-UT}JMQuu{ zVOfqR@gM(Q$~oHZZn>I*vwL|CSZ3oQil{@d)}@k7r65Kzyj=JAOpusokv>IKpEPf; zm$Rko;&>&HsTQT{PUCPlgr?~ttMGPar=yq~|K3{5>xa0+lu@c&lzkH!|EJ6r zHw2Pf#k;)fdPuH#M18u5P3t0tX&BXTY8JH7r+GX?_dYt;*gI3WhbVm&Zg_7+T{ zpT%9E=yiG><$|75XTF(^jbiW|(Aw8nmM?`do>~;IrdgO@U$%DKU|f$0RqGg`30reZ zQ>f(*4e5ES4G(peg}T%(8b}!2N~DOwxG7;;SbMD)EBX!0K>jLtP&UFQ`BSJUg58^ov_>!cS+Ly^871QrylPQH@fUHwW<5S z`D`*T%MQe7;BfvI$fzHNqb=&MobVy{(1vQCj_oGe%QNj3+s`;?+^MWbT;)j3nF^)s z4pXkW^lUa9})`iv&RBDIEj(qlyVI$UyUzlSEBB8Y_Iizv*ol% zH)(7!E3pcGFX;x91*=m2vA5@N@TKy6S&U?|H0;L}J5t&NdaTk(8B!4uo1~q_+pLwg zx)`1v13>+_xk^}GjVNY@j6Ry_TA+MtB2q23@(v1$_WKd2Fe)$&4=#8A{!y-%w}7hG zN%e}@yI+*Nh7CT~$G;-1+tnel-VY?F)YO@RUfqUcI2^Yb-wLa}sm|TMIm4d=)7xx- z%FVg2Scm#0^?2SlH=*##ike&eYU0oFDOq)czb2(B7(hj_&(o}u@zgD<>VJWL=Gvfg zhdYxcnB*}$qWnD46s zw9Dj@Rp;0x3@+2OS9cfdBopu*tb^$u@=U5)ZLkM!NarD|6cjDCl=?z%CMsl((YP)9 zx*N7|@iuiXY!s-+RBd%f@K{sPtW44KbS}F;9s&IpH!Jz#dxsNvCSSR`MCWt04NJYYY z{nF~9zygKQyy#uqMhhl5J;6np{=?~e}DCUhVddZ#UE zSNaGAe!tb+rpU!WrSmA>l*ub}b=<&=VGb7f-6ufk(_bR}tYA7Jda*Y#(Y76}dA0}Egq5*9OH_=~1!qrlt>P&+*Ssxsdk)Mz< zmdA6JSe*dy^->?vL7}2|-aaXoJtcKcYXRN=b$BU6-03Z&gDo@?rcu|hNFpU(6)5c! zH1c)Di80fem;+Pvo9+twiZHazZJXCa?p;q3&aLLY155VT`!6BQSbpcj-6bKN`o>Ia z>N|Mu-|g@rg9zfh6sviDkA)Fuzg-MIor%?`5sWLlqXZAg8OySyvkfUraD&9IH4x&wjeI=1~*X5?NU2T7ZB zGyDVzF*TiiP)^DkbvH%~zM|(^D}%)HFhqDB&W6%_J=FtQQ{;? zZOMNfZ&BzE$k?wDIKa^>pNE+c*C8792NBx!-mT@q72j7>L2=jhqmD95>E}n5lH{1C z?Ds}H9L%i8z^7&8$XKVM++odSOQxJy_Mu~GcUooyC$Rpt%_n-b>TTMr-*^0=XZU`^ z{oVr%%L^<1O(l1u)0Uq{6TgHGnpDfkev{o8Q%4hb6K_ha=UQdl!Sd-TD2e>Y;wVE1 z(?gVyu(Pq%1yk2h(dAt<2UlJ)fM;RWe}+7_TU}?2r#F}%-t`H6!l4DMSxI(JU+e5O zHEkN!Uu`KDF-aF*KH&zBTkAAU90$ELeH{5J_vG`q0+U>zGO33&?a5w;2CSXyv)SEk z+QQ;;pf1`XM+50uc{Ff(7bUPbmDTFb+|-@fL#1Xwis#UH z*uE^Wri0=Pdtf$lYk`3mli+Lav`HU**5wSp9#ZYbo>R%@3YlQ9DS*GrEfS*^dUOAhLD@3-ZLOS|Sugnj8sEeW>NsC-g zuTN1V!qvo@u8^m=ZzR;e?8Jn_bq!cl?32Y{n=rFwaIigL_K?!%D6Bnyq9M-uN^6{j zn~LbsQ=XrkC&^in_u^zqKO*X3I)De$tGl2Qxc{)i#%&Km!~<(13O)*Mfbvb>8F)p+ z9b(n|`74f?e==)wNQan8K_s@7e_NAN9ot5P3-SwnxEqgyX`+!l!BX{?g&bE>UV@PT zT4Z69IAAEj9oKVq`A|aJ@$;PzUhF#Ti^S&?Y3EpsRt;|$`I;?`ChYTdai05}lt>Sq zq!)O)uu3e74CZfvo4lKT7IiQ&_5DLjAtmTn)S&00?1$bvT*w@NDR=nfLmF9~ocVdG zoYpywF+9Co1DDoP#FE&cyC4dvWhxlXK#Jyu{O7HCsP9yk{-6rbv*=nmw0nNStw_W?<)Ey*qgS2C)DN_wPIra5 zon}qQ3QY}HH9!dzHqza&jAwc_Cn5W~Mb?oq4YKf1fj3^m$K?@mw){d}U!TEn9aaTA zb)>Bc-ZDKWovZi2l!L_v*{WAuz*=s#s?Dx!aV&L+xN?w7YZiE#;q%V`*0V$WF)zXS zTsCU%A+d7M>q>Vn0iY<|zr$vRykHCJ>>?o4bcqynwQ)(0Oqsxl^Wk(WG8_Fb`=Cav zQou^kcI(UI@yxhXP$)x8aeC8*yr|u@U0Qm1{O4$*gh<7e3q{mjoy6A5r-}`0J8Qd_ zxXydNS||&qT>%^;ii(abcEAPIZL%1@0)>rfxgFeg(#M@mENQYA} z4~PEP2s9xTUcVj#8W&o;RSzT*fhUZGS=2-d`1ddQvuvB87`V_P!xrVT>V1o$ z2GtoHdfae|k@0eVjr}U#t}zp7xxB!Mx6fZ91r2w2JF@f-77TADZSa|Zz&xJV-Yg{M z9kLOYvT`FgfWxir@+s|17h1Gxmek1zV77$J7cHE5*9x4%E%BZGE}>pNXkNh{tSXxE zhWyx=Bu>Z?A;~i`H~6e}ed1Ia;Xbu@cd4MKoO8Co;a6t!cjDB<#x*UD5X-2-}vO1Vkiy$C5;kq#3;$W!Cv zdK_0gQJ|uj*i?Rjx2xHHNMj~sJeBfDi0KGWqLJEO9*qP2G}v~7Uy+xZ${}MBt_#S=|sAwp$}RMVM}I|FpY@?sHi!Z=zmHR2t|H8wXF?77`jI^c~z$c3$DbG8<9 zJfFFwga=twC_X-Ca1=*~mm(Er?f6~-C@EiUxrxTGlE`)1xaURk!(d(Rrs|{T6Tc7| zX|uw{V#3iM=$%!nhCBvDW?^u^ka&U0EN+dy*5hSe&+A}|f&bg;1GxMO$6n)8xY~19PX)t7RZr3R?sJl+=Pm%@Yd46df zIn572WKhdtT_M6ioha39ysS#o5sDksN$6Yb+sv@2d<1vkl1W^rKA7zJrFi(_N8YW$NSunvW`mQ)hyAAi_)tk&_3 zn7CHV^l9@t{~@;A@p!lzXyHuvHN7i_$UrT7E-`N{AMfC_*_?aZ+t=5~PMl}(hCmq6CRWJ-BTzegR3`0nZ#MZ08+gYjb;(H87i#n2#o}h1jF$XrqI&xD>=IPfjBe8JllU_W&1zk>9TL}sp z&i(>%)FTNjh_@(Ikx#4T6goQ@lf8tX4>bq5$V zsz9!~n6BJ&yGpHXn=UL{yl%=g_s9!)k+8sTz!mK}bYuLF_-Q-KlN%SG6O9lIkNvAHz(4ii9@*P`m976Z+So5|f~;y6h?I9^v604Ne;VWm31b5$rFS1K2hw68_2 zecR=0D9i@ye&o16kdqke55O)t6$&i<1|LMGNp>*&8=X03s~!>mg5iFWu|fx>0p9GV zOaHe#S^}ZowTEa9=W-u~Lf{SpD5X9Ak)_>w^YRlNfHV`8+}kYz?0pOVFg>XBF!`q} zujFCyB?-~Chdw83EkcP+5(Z_zE|}C8tTX&m9YWp(rfa+ch0P-&uz=Pp^K~`>222iY z-9_(7CtZa{e8@@@Hr-%%br-5P4yNN=CVU)uM1D*Gq?oKD_QZ3{Si@hwNG^PnC1uE0 z78O4YGi#I1jnaBXieaDoveH?4e)GA+R4r@N>%D^x>cVt?hjy_o0CQ`ho!~WV(ibdx3|GRfYyRk3uc{d*v^3mg@t9h;$`g9 zfhJW6)qAi~HaJ_beA4C4Z=<`{$ZU;~-n7vY4og*sz_jK4quP~%Vp^^ULad!^5m*G?6S0EWVRatJR z=E$TXSPVU!20J}wZkbd?Fr4;YI&J{~K4#b*4yF@%<3vDuzu!h^amlL6zA1Ca@gHi-9FF?@0 z9zoUEvq1+r!s_uh^Jw?`aSkwWlXktejVs#1Lg;1fiZV~Dr=*|pDs>gpP$J!nSeno_ zR~-KQf!vMxlu+_f9}r66Y0C=n2X$p~UiTs}g9fhJ)&<7y0Q2;rM;pB)hQMl+0#r)m zVWVJphO_BcnjfCesBSJcLka^Z)7~C*tp6x6?e*vjexUo%9HcABwl7M+OlrUUZz0c0 zlU&ul-zGUSYntZ1ub+X>czkBmE`oi`w2k6dC>D*7nz@^CshdZndO=?9*!RF@NU68- z5p$PM0rE(cTc~AAC8@1^=;gQm`3P+TR;n@H;@~7}<#n{lTEsoydf-K3*Ex(|UyE*f zHV*upaq20CDWc53t>=x0jHUx{vr_8ro(A%w)9=7b3T4~D58t{Pb9sPz&&PuBgNU$c zq2i&??@vG=hq>>FkLS)iKI)eohQ_QY)dL%V4NVx@UFXjd>t777;%{F26R(-8@c(6gV84dIm_(B8!;&kc;EWbxs<)<%UO7h{p){2 zn{T&t?>dDh{913Y9%=@@=C^f@JsTJN`_ZbqPjhIcbq>5>0_uF{ynG6!wr2*I6h6l$ zd0bdbcY`@gm(vR&1g-v+*@0~`k{Yzz2WnlHc#nKJjJ2FQ9(UTnJgrB{;y|2fbs01u zP9)w;4RBO{EY>%92P!qujy}aIUrGy%viBEK7h&0`9HTU|A<`jqTU^j5(y#bTv4j^8 zlunZJ8pqg1OQ_Sa)By5RgHIdFyN%_kZWIP|Qw!@7bkv?s5Jow544z5jtiF?V=|RJ= zzdUl>G1qK%&MXe2gQY;*fNFwF>H9pl*x~CDTAouDpv9t0g&TG-oM#G2BETH`^MBIU#(Wic;T)R+$_BSinCrBghHR*ez9ah zcA2ZffMDY_xo55>sT*-`-t#Bzff&|B3Yn3jvZ&`zsGJTYo9~$hX1;L|9#gK;AF?wX( z&S-xuigr6>U8HcH#mR~42;$(~Jj?*@TcxxXn{|@_wwD+7 z&?w39zZbJfgfKv%i-&~*qrAXmviZJ*f2JZ0Tsy&Iby`^|CDTQt*umz?Wvc*ZliJXq z>R(Qd-?pMiw@%|si>zPfw`ZUcsF>3b$REyjuX2%keRwOUtxy+`AuDp^Wv)Wu&?`Td ziVGe~Vqkta#hgnT^nZ|$L(XhyzECsNk#mg9K@E`-C3FlxqR*}M`^89B?i+IDQZM@| z;FL(A(bQ@2H`^EhT%*})_D*^K&v;cKY(=DEzoAzVS44A72gxKr(1{nhx*oIaae&! zU)JYOd_Wl(RyXrb>ydi^Mp|DU2#g%J!FM7Je2++YKz-PGAD@W$Pa2N^0Cu{1wobzKhamD2Xr&zg zA$-|tvWyHdxf;o#hMD*<4BUjupP87fr9pm-4P7kfHqJ~W#lf3@;ky@qYcrTsg)o&5 zNrLK>49#9PW2TM^%SbJ>!;qZDgwXA=D0cOeMaP}ZW9|wvl|M4d!pW}5PUI;k zJ|-vM*mL%I_}ImGwlGFuiz{X&p8J`1ZHEi(f;F$1RGo>@|q@d67WwK=^(AMgcF;aJ&5(fkc3fWj` z$bgarMboO?opnDZ=mXRlXm52J#ZI@Z4>TNdzxwupq&!J*7Ytgx5#yOCdYwdf+9?7K zSPZ2FjHqXUXBKx&r%(aZ3(q)hp9~qA{5?4ltBJN0{eP5#Lqrk3pfDMiO133@?30(7sQKbq*5fG~pot)*?Zry0d+ zZy25N6iZ%OkP$;YH~1xOT}9=qNhZLJ&6X$voI#fSgNv)o!6gGTLW@Uc@)03vw@inTvlN~6 zsuKWwML4S17U|FHn(20Uuvh(WV>6>zUp`3i0tDR6)Ed_y3NX>FxouO_`|$r}z-KTu zi(iu@qmmd{nn=Q5Q%V;mjWwd#yWQThPsJOaN+3P~lE3(^my1=XgHaNC?JTgB68%P; zbhD(_lp@27ni;;93~cvZPe7#q1QD7&%`9BD_w&yqezR$=8pb@)Hyz_DY&Vck7G)PU|-8tGU5a&(s{_;q`;$M zvjdt~(OjFPhMv;mndKP^wQ10+uJTCLCuo+F8t#?fi<9-{B0nUfouiJ;!mF0p5OJlF zwQbszYlT^b*B}aYVbZNEfVIr|tNdP*Zi`DKegq&nK7nR0$%=IB2)u4OSyNwVIMmMf zS>z1iVL;%#l}0W8LqHOu&qCgA44bmBd`Et=k0rsB{lYQx(HtrVdL0sK+4GZZ zPXh9M!uJGk@WS`iVVv0#f3C1L`yK<+1zI9Yzibs@nwtNkkYVhw7D|=Kti(XH9xZ12 z(Qq}=p$OZ?>aQ%}g!*Ie87RycBVak-r_$$s%`toxXpvq%qKB^)Z@~JL3+7z$fLmr5 z?~js$ybrMRNw6G?VcG)Yq^cgqY{@c+gA2?!zihF$bH95FcF-sSoC*B`fCH}5gZUjq zh;a$y3dD!#RRc^}C(u!>6io|D6KM5Kebf-_9FEjX^lt8%ty&{8nt^;7#>{f#x=*nr z`+;&uDk&;tYg{M|vYLjK@O<){4d9I0ul7HgbnR6ilx^1+AX#%S+kQo8G&3a%Y=f{s z=>O>;lLsgpK6Qb!nm<-kof~{QDgY+L9Tw=v08%OJ`4Rwv398LFw8Q6ORK2*w4b1HIq&LwnLb zPeJfNd7#3b|1;&(XY=IWF1mXVJLwwSbvEAR?!XJ$*WAxalx5w!rH#V=n3Le&HcNq+U|94J z9u%jLv8n+^Bis6Qz@p*Q00m~GyB0VY|z@vvK^r( z&&#&2fe=x!ug&+Py*0A8(a&32W}5vB(FuYrx<{AXmrePxo?qw)SW;xm2oM36pzv(%SY zPWaG76Qs77`?*RG5jZQP%D4(7iH&@AEgh=xw_j=;N~H;L*yWNdr8c!RRxE8wtT8?3 zeaIsJ&FkAy8%+O3>hLLMEF&f(40}aoqssf%&L4yETtleU*mAW@`TBTH*c&I>aPQzt zcFMLVIzTFwFMTC)m9Uxgj(kWG9dfW?VswVP-S`RngsZ3umddUTAv9*u<|#lC4JBYP zmnQT~&`K}=4Vd1)jND~p()?%v13$c_ z_eMmSo#5h=BfjgSl?;Ax=;kPlttFkxu~7bNwfAnU^Z{4CI~H2}(^M(Jb*r-S8*U&4 zRB}Hzx+92LDDL-{XFhe~x*x(EjQ(Zuly=2%TR@6yHBGx7vS-F?Xj zg^B#H_c@ieCYKIw&V8W5q%>lz!g@xGNn^le}g>4Z@;#kP68Wk!~dq9Mm+BK zo;+B|o1}?`7^LPXcZP2d&UmS|LML|@cJSseEir_rsjPXhhOtld3b-Ze_=R4o0dNwO z&#kv5+SV$RK7VH6$yH&GNc8^6Uh4Qx6_;U5OhaQN!^wL8vu@9n2Yk?!wjHjKeFE}h zxZ2gcEIZs<6U#s9f4^4&dvk9ogn8P9oKD?!|++j6Lh@thczK{P}bWVhK=xN(U6zQb&Zxn?R;{(HkSKC6I48uX%LGY!flC)r- zh^U;@#-^SSy7iaa>BIFRQB=<=`m6mZY;}t2Gd*ws01j*o`{Uzwn=fpOehP&fQ`ef* zdEC`qV4Q1|LlS9r$W#rD;%OIC7U~}t%CO!)7x}RDA9*yprKgGeYr${frC)__$O3gl z55ZXJGDPl7Dw(;bFv+KZ!G}ZqP#bQ!DUvpG>;d|?3o3lWjqS)wvPWzb6UljNX1Zk_ zm~P@bTDWv3uV-bLY90YOS(8eTVU1w*P_CJBTD!&UV4Pn( zO+8I%2tc-sJv&zXXba!(-+A~2atw-)``S%saX|Y3(cVmmhZ)gJ%IjWC{-(R?W&{8?qnDS)BU!(EdRInSVx z$pPJ3Zz1rEdw4rxkdoTEiyJyz_)Ob(-)m^)_vOJ5ia%UFbfB}lfVGnYb5v0Dmnr-( zd@btLQ)_!MPxQ&jLWf+GBsINceZh`T^DxVZ(-I21J+qUfc9^62X)f4BNirFD2_|bQ6|1wDjSIF*bdpqHcJlEeu z?j)u}iD6Y5^RMz|OKfk?SHl)-4I#-|;KW}Y01Q0)R6ZQ0*8r8o`rAZ%!1(I&>HC0C<3u{s>E!udiwtRf`gDtF3oOZZLadWHi) zKCj+NDMA&k&1R4Vs+em#RQ}`Lp7u!V>9*dxvd7V=qX{w-7&AZVjeath05V@EHkmA= z#mKM2I{LqGx=nlrRwPJkeg|6r){Vi*@)Kk&zIvysW0x-Mnj*j5 z-8OZesbCY$xA-<>ir_=81ZN_6Z ze4lIcm0djXg;s4CagSdoY!)f?yiL6Auz}eQ<)~#*y{3tN?+DX%Cl&nYig3xL!nLY- zRfg^C2E(}r(Q1VTn>&>;^ULLvR{gg(8L5%`Y>RA3SmTIQ0>-|dby@IS%FjijLnezK zOPeZ9umO)C*Q`?O#EW=zODf+lSGpzitV4)@$E%sz*1N2{mwN>DjS3gHVKk=%q*woA zf+L8BHY!R1nH*85jJt^v>}il#sz}tPWaR|&jwJhCO!~Y)fJB9iZ$&{UF$$Uk>%t}1 z<0sfw2=AND6WyZQ`?bQ)L%FE2)&%!urHL>AarZU5c9bg4ZAe*Zxs;=bv?94Qi1pe4 zx*)T+EVs;G1yG+-vziZPYa;gg2rwcZtbr4WK0fh{WtH0=5ueBdSnYIHnD?(hxuF=0 z#HVPt3N{o|Tzhno02UrobidtkJ(4&zN!I5Ay}$N3dLl_ZVEc%CA0EJhI8=gBfJwVn z*}s7UqQ%m+`x>4bYC0o*E*b9Rh?Pk>c|@DCfEB((wUZL;(Gl=Fsz={Q6w6RT;&+);8sUt_Yk-ZFZU(N zJz=$uTMh;s6Rqu*-3I3k$h^v~JHW+NWdncyML z!Q6`*=0vFmp?1WAFF#;5#e0}BM6IqO8YW8UJ&4YSF#b|8j%l*_H+n&HhnkE%2SBZ? zW7IHjAzdhqD1l*@e{<{PjZMIps9~*NQ6egvt>P4lzR~Gu&wR(V_ivEwUD-M0D2}0K z>b?&=$lSX;-v*M5mmox|Md8hL);Rk>S+UqFMDZ*59Z7`{WDGMPpL5T&d`!F+n;Ufh zKgy`IExlt6FKv*~g)X{b@EKyE@UH9jra4M=6;uJiG$;t>IadjV8jF9GEjWtkc8ItF zUcl~)+QF%)q9Qn9uu*^;$4Diu)ZjPZqA-s$foEh~pO9n?HzC8fkpFI0-H=S#O<{6V z?Hi>)!mp?NR=b=mh29L4SO-g^2)0x>z`=PEF@1j&-_IbgYiTi>t;#<8Bz}7q4LXNn z;lm6&oQQJ9ZHOZ1?Xf&U-{294k13QKnpqO?YI?@qDnoPrs4A1MQLijX(4LGhn9&Lv zi+&W3R2D&s1|j7bFmbGzg@S|Z+3fmBn6&{bZP^QBJlj?_L*Z?Xsm<#3Y?j;DiDit~Iskkg zE}5LR5ghtfFn{Fw?P4~I8ZQpo1c=~q&eIq?Qs07#AZ@4n7s@+ojCw$)JtV;PGSl3; zq)K#0x?o%tusk${714zS_=zkQq(&q|JzevA=e|m9noQoXb3*^k*V!^U%IFAxtYE}* zA5*_$#w%;%%9|gs2m{O@hV`!Qa!VF)M6H+YMzJ#6W)B~5X*86k=+UE3`~EcbYOVBTSVc9u<8bI1Cw>6OC#~XzX#U=5f>j^EjYRI5uHn48 zx2czcMrICglmpy{^&TGJ!9e7VK+=dVdRq}jX!^4=RDIw=sKyGCgBTtfw~@c#Se(*1 zON6aB%ArD*)n?ZIYmu>9}|~G2Yk&rl zDUd4L#^tjKyWOu0dgy(_Uig+%498Oh9?*?7QnzctgX(}tlW9)_uK4qrM$b?p5^Zxk z#OFfv6i}Kr)39h0f6cIo5Qgc-MO7B}0VV+I9iWkXE^fKrW=~pFH2Ij?UM7Z<;1s(4 zL+X^HeR^2p)7#vPPGlfdIS8D2<bS6)+d# zgzl}JRLHEzb#x9*Qnj*b$AnumV8tqXMN_-Rc1+L$=*+(ztzDMSh4u1mou^^vlXQl? znCp-#sWCKoVaX#QE5BpZRnqC&v1&CNx6?Z0hLxNr>+iaC6GnA=dw=b!swF&s)wg<% z!o!}E5Xcw$%YJSDrsw)M&@&9S*3puvT|dU=6~$WmT~P3{kX3FUGYzYa;y2QZgl!2RDwe5^g|`)gTStcq3dj$<{$ zx3;_~P~4o8=DI|-dEifoe*5 z=L{#$#=O)VDV${G^hlv8d%>;W$SzQ~34~6ZO50UU?is~cZ08X~UmI@w7_=2PEyU?i zIu?4Yb>r;v>t;dBq``XVW7$wC?OmI zzIEh0m)|0%7b;D()5)#O0+tjJO3RLzrnow*OyIPEVxn2LZQYO>_h6K%ZghRemf!+X z+~|HiUMrIlp~Lci8ElDJ)Rasy-q$e8M{Dmc@7`n22!`(ryTNV@ze@nBZn6V89NxQn zt(XRhcG@Q>X48x2C3y3{sWUwujEyAOu^k9jNwND%Pk^(9xFZY5i+x@L(~9?_>+il59yinW+h~a~ktPqrczb@<*-hlK#dmaJE;yXQRai>2uM&n-W|;Q#qtL>hS)lp4QF{n!I&=+UqW z@Bo9P-P9nmZfXPMOJ;Y&kX!VU$D)-*yb=|pon&yHz(kFF@eTucdku{5I2(4R9ZD*~ zRZ;X)51E#j4NI#Y-4_s$z?_opqw5nf=^azvL+_&tFtUl{q6gO9NpJsJQu3kbdbXgz?c+K&f=s_m;o zA#Rb7Fg33yc2APd9nZd)|8mR*!y;b4(hKAz&-EYl-pNAsbb#Nmm^ti1kpBF&V{=Y8 ziJRNS7F9-3B$OhV?6s|E59JaaLwSJA(x%b*N%nWi7g z$QmKQHf7V4RV4n>1CUd~U3~%{w?)n29t6CUSN``LhHsNcg$kHQBwAR`5t-WOKw@f| z<7XH?i7OoCcMn%0F|-Xj?{l0u`~%lf%=gM_X1EN~f-dpI77YzBzkhO zosaYNlA(Ma6WFQIjn?@bHZsofcb$IiS-VxYnd*;+j{vD*%?7`()?_>Aldw=A6#8pU z4H9!rmidRhuXo1hqhVR6b{p)7wJ;zu$6=U7Ff~Rt1gZ&Nt!RDm3To~42b9v4C)O?5 zP=>s2rT)`ygN>RQTYv=I1vJD;NUWy`b-ZbVF2xWBRBSZnGKvGE%kMH(=RUGOa}B30 za|p#VXiyR)<7>g}Zsbz#wg39Qm^?M{M7UN?Voy)))k5ef{DVk7c&NH($!zP>A)B%4 z=2{#v13l3SM>OE}&#VS(e zZbbeYRd}8zBm7jRUxu>+u+w6+@rt-rE26zU36ft^2O|ss3#E(qB2E8Ty9F4Jg3q_< zU%wKg&9)?|8*~B^D?kr{o2V%Sr|sfv{d;CqMhuCrtKss?w7OKUN4)bpQ$Hd7#^?XpbdV7s4rblf|DTyNk0yfa$(M68urK@Y1hr7HPGwtk znj1Q!g(K-KY-dWQpTnNdq$uGmSIL;_s3|tDS~bDTyag1Wwley(wIzJGbunf-!+>ILg?gMIe^O*L+8x< z>@YX?CdY4jSRY@>g~M9LP)&I>TiGdRHho-p-C3VDv6~1@^qy&LyO8Su_V1PwY6d*8 z!|E@q-_Cw*IX__&||?rxX0?Ui!U1eg`OmTel53EH+%ZNWU(w* z#tpbB?Dguvu^7qY^z+!^#AS1od?j?w%D|%?9vx9#$oJ(9rBTz_g%!hIE7}F%s0K!X zfKbjbIw=U$TW^BGAlW_zKp^hr_6VwaQrUDRoV|-EEkMGPocVXy;Vs~k?-dWHDs=u{ zUA+)hS$%>&TIsO(5Oj>j|J)s%qm ziVqSj@D2HAM}0AB55AUO=7ZP|?f#Vm#c73tkMA^mdZM3KRF*^lt0T^yID4}-cUsp= zovU{w?j~&|w4~qSXbgBln$6gCp`*16de}a3Dch$DyA0N&zkC zNUqi;kpkpy&^G!?#bamT&+EQd0?`maiT5l06l^_%KR-aTu zT#5be2c{ui{s$J<*M&>%?=Iht?=O(M$#o6}x9%%)UN%FQt!XeaXyC;zcY(-DqY41a z+CYR^?Clz;YNjK1c*!Hs8J%}NXjm{LK&XG2B0IkQ$~5kFp@Fn%5}#KpgT2<=;t!4T zkEo5LJ#-)I2ofCs2K$rbkt|%uUoOj9;FifX{?B@VIZOoi|Lv00;`Lhxn?fD<^5>B9 z?b#tnvtWejg&e$CwSWKzG5^g-XP)^`+zT~l#|g7D2@L_GlfjfKwiiwdM9vcmg#>rr zO}I~PgbL!zg4Rocr`_}*Y*>i%;B$%{VCpJYC{KrdZ85|c=_aq%SD2K%Td}p`F#4RG znJ##Cd*5fq)8e4?qK4DC$E3UL=EM5w(L($*&S%-cl8pVIb?jwmi_sIXKyIE!-kp7m z;`n-xnadj*onNqkBtjh?;;RRg+M6j^p`z!201SezWRdSX0%Un@D)p6bc&?}xQ~qBE z$`QqF=G}pucG`9$QE?9i{0CmNKcT5F9vw5{P?uIQCKn33rjojKW4KUpDkV^86Zk}H z6g+EzX^_)_DwPD+9XRqN4g*oo^>;RfVSqq@PcubV%6>K>54rQ9wrrMgIfNobC)I6a zSfaK1fDIBV$FX@50G7mh9u%e80P>rEaUaG^+P>a+J1 z#flqLY&lg+=^SL+n<4Bh+y{+r_e-y8_f3!iPQf$R8Ht*L?z@tP}jv};g1%c#jYNS000|I z?Uh_wEj|;bb<0JWgX1F8tWu4!3gjR1K=;Gk0e+?y*>gyl|Iz2t<&_C9u~Az7cm8su z7kvSZh*B*JfWI1p13ktfGmehod9t5E6Gn~bGMm-sH$FB{%V|V*I|AJ?&(-bz- zLKQ}L%sTT766M30ndwN8dA&Yk`iT$u7p>{TsJ2SdBteex<}qO>7Txo{cXe99v7*>_ ztfBEoYsC?MDp2{#j)LkJ=gc;4{SXZG)efAF76HnaO0Pw-HHoM^-`@in_kQY){jQ*l z6u^`+s+>bPTEj5ILymHG3CtWVeqva4zhNAj3{^o$Gg zINqyFedkaGj5IA1*vJ0E7KT3ca2m?7GTq58|0?beli{a6L_-|geTBay-EnXL;ADiX znTT1(0V2AXQ1G&8OgznMD3Lk7cSZ%rFtEV5h@Tn#}Q{UJv|O2LM8-8~{JT|6~(KG#D&T2bsz2O!eedfrTwD;%U;UG#Q&IF$R#c)4B4LO5WdVK~+Kwqj_dClmQ(kOG*UV zxa|4)6v}WxKxf$N2WD4}%j1$wikr`^9BAkG**DpUhNYZbQvw{J ze&_+iy@4oEpnLeJGB0fhCKXXh5?7o;~>AwO1J{cM%w)l5f)N?$>8>~2bAI}R3<(CQ!Z zdhY#IkrDGHp%G^axRp5vFzg~NM26_+2gOwa4uBOC+uNY*l!aon^6>I z9im3C(u?|A5h0j_o9Ny`W00yS!;RNFG_>L4i?a+aYNk>xW*pr;qqNGK3?AH6c0kLd zrKDvnFx!3M7K=P5#Cw#U61HO+B2lMI5Jip}B@$yr)BsKUengAs-GB zB@rg%Fd|0;o1FX#Ug;2*!}>I4B=I96NcycN0}!5@4Dp#{_a0FMJao}RZ;Tt-@(6~| zEuEB>DeSHDn+#h(@LeZ&>$#P+Zy@4HqcFB~%}DSqor zEy%lXGaiOoC|DpoQX@8I+s&kHZ98@Fvs@l~6m-z>-BNNt$C>8~ckV(kO&@5Q;3E`> z*fl2U;`K){bR!Q50Q%E&!8DDb&zD3d?M|HvdsI|NMQ&gL)k7+dK-Xh}?bI!hdP~~M z0GG9tdH_w$?R2h8`rz{r4k(nu_S=)Pv5QAL!}rXT?oAt804a1`D^mfG5AacJD^$4A zxWx6_+@tRUqN=IB2;gZ8<89jh8){1=7+LDm>zyOOEc``D;jZQVgxfOK@mdmAWoeOPoM+$~tWwnrPgwFr9| zo|9?1S98ABLw$MLi#l)&^QLY;)c!q0LM5Hx(XD3F!J7)MJb+k#U{YxJQ<-;8&?^ik zt4xKl*)hlHY?)6gG!4?9jDQ~aD4a18|1Z*&veJTr>4YUacoAc?xXxTKEA%F>-7-{H z72Msei1{Y@0UB%QGG`#jnjp}b)%+z!Tfk^;90oha(wV9J?m>>6S4}A5xZv{9-z)ym zR+)N@%M&!-ojzA>s@4o-1E>bVx9z5{e-y$i>E^h^YJof@mPfR+K+{MqA;;-nx-wjL zDD3_nx7WBQJQ5ps66?dU>kuV=@CW+YF*sMm=6n=$-Bc6n z3s3X)Ci2hE!V@FnT@64Go1PKj8W`pmo6NNX(m7_gdtv#^+63qxC(KtST#@HW@Xo6mfe z1K~uHrjSpAGbO`+nM36f0#>DHn4u**TV(IIa%PR z#Ljo?@8IQ$P|No1q_kpR^%Dch`yvftm2Ut5 zNj;*$5|hkNV%yDI+LA{{WTSqYQJb7hKw!^5An3BSCcItxLcmi2(*?Phy5Y9S*c%{Jfrvg7+b zB@Kv;YdXWKKaOM&hCVpX<%k^l+tnT>{c~h0w~Q_(c*_4gK-6~K#JNYzE?3P1|I-%}mJ$)idr zPW`xRriOiy@IQ(Xx5cOfvidcSp$4DfxwG5M5;jN@I2^bBbP7li7i)h>>y+!E;`M;R zvbkbTU9`%~8-DG`e8H@`S8*h?nldnRmh-!xmjh~(7hPI=ws9gY)gwqP@VW_vF&Na^*(~pN^kJK!1MY_gS8Qa)?0&5h` z`?{1y`ZtiZ*&pP zJ{$D2gMbQGq<4~|PHB&*mNH!`3|91mLA(|TWG&Qr;6-UBh&{IIjw+EdqRbnbj*o=I z&@fZ%oIAn5KVsoe&%w5!Tt_&b>Mk`$e z<1Nti_|ipaE8=}0SM8eNBY}fJuZ^1JjW{(=Hxh_L0$p95EZ10LUwQb?wfl(K=h?h=6};%B|QuBX#}INi)L3 z@iD%ns`%PGZ|lOna%Q3^+M^n>gRe+j0hk?3H%ac&&hN0Z7n%F4}*c+r&oET;YoolT7sI3Vh2n=O}6`@di-K(sp#a0uU4 z%z)p(y!SJl$n#*mT4)y4;e?4H9OlD$G2^l_x*DP8!wgW5?3{SN3IB@86_6eT%3Y0Rc9mA0K~Vc7`55SDmq%FJ}2(G+}OSI%yl$YVqr@v zy_Ou5`Hm9uqKoko%V5A4?J}Mg21lzYCqd++*Al#`$;!NqIiW%+<=tK7m;+mxfKFQS zo8+aSyGw@lR|r8-{`dQc8&^fu*pA99rfW}(;4HDA7@UT|df;~CGQB%^ytc}By0b*s zLc3qq9S>3Bp(tWMB*alTe)~`)>6NT$7%b zrPz4uRd^!0#~(rp9g;GH#h+W4OT)MMjouYdBp?ABx{eY_Vgy|}3$&PFO%4n0UL!On z79ui(?b}VXWCqQ66?!znL~Unn_`kw>mm2B?x&dgtMGvzqTV2bLA*LVMVW&NFqYen3 zp^r~*YvXv#a~o0P|H}_UORq)o>)VGOhnjoA@!1X%gZ<+U%Gb&eklT7Q$&rH^9Zua` zX^Ye+(ptZV`|XEjJ}fDFt6!D!ng6O5!&`UZWN08R z-+G{V=)F_NlkBgo2kkA(J|z-Y%%U^w*L>8>xX8Kwm3kpc!(f)sK*Np^GZwFMJ~!7F zefV}wi&#zLxX?dYO>r12zIE4N#2p(9egLn7gHhJc{v#mclw~S{e_t6MY22CU1w|m2 z8&jnwOKWlaEtRl@VIKJwuCZRY#z$7wIF!wCnaG7uOORqVOtMsWb0~$^rXqIY%#}nt zhzEsw>J{PDtdYy=l2yJ`e#e8F!m}DuG1{C$yNL-tt@TXyDxpRyT}HrrL#~`eSc(9= z-Tfb|rcytQ#yeI=0XogZ*pe%DhH#TDrR;~V- zvIA`7L&fW8(u%S5Pb%06-ZLovJOD)YW&byxT#x$+FfN98taPe3!jmo>9IE0du*X+p zIHyB~!ikg48UfQ~b#XGkTHz}#r9kL;n2ud^CK$*6;5fITaEagNaLW{WSW3F7aDYB7 zmYML4=umy424rMYpj2V?8ldL?`B*=4oBm%L2x=}m$xI=5Yt!)hxN*{fEFU|9vCVPZ zzCp+FZmecdpYp6VY%WlqE^hy+XfA5oz*~ysY-YdvAxw-svg1m_iZWam*xwG}U~(-{ zq!2BssIG_Trg5)47VgveeX|pbNYatJ_k�hsn-C=i<(+_JAjU<*fU~>vO-iG`Jh) z4C(w#-%hsX{5Syk2x@{c6?GNrsDGc8 zN@^-L9_Lt^^m2QLj8J41Ovl|`zZ{_?XchMw$m?g#05lHcZQP5oa+sVGCj}8F)A{=~ z#q4eWKSqvBG4P8+$%`eCBQfN(%{FP;pg7`GY?b?5mosq=mfrZH;*c&hgRBd;L*kvI zvLV;y^*(nW{SVyQIJ~GQlXBZA8F1Z^>lu?1XTM0Svx23Rt@7Qq2!~=#<_Z_wxQwQ) zc+aD4-H3m>rr)t!F^zVMN9YB+2CfN?E80)htU?|2Ps zO4yIP5hX=Ljx-Xq|oL#A)&AGCS@=r42DFNfs3)HIx0|u4rxD{<1^`G{?T3)9_ zDU!9jt7Mv?(b!jJb_A}{>(-fv2cUUimqR;nRZuDS-ajep#^f4<##0N`{n)IkUVj zU_}W31suoW`{Ey=E!2of2SUbgvIIIOz2};)I|}%0FEMWN5^ie&x-v0nSmQAPEOt z&gSdRQ7|6yl1Agog1Vo;(k1z#3Vl6`^;>Y4qK@b5ej1NeY3C!_ z6eTc9vvquXwiEWV3*U~JUnJT}W9vt(yjn%yaYZi*wEkKY8=&j^tYae3liiOxfVre0 z8gXgY;QdXg^iPSxVPAs65~yx;Po#=k|DW0dt!Y{xrf02t>IQT5L=|&cbzN zFEp@Y2bIe6D`_;lpW_xnKxRnMtWORbO{~v#JD>vQ^;Y-bL&~P)~f!j>JnL zvaeFzQVgdcfbQ=K4U((*z|=odG-tW^1Y>Mnp;2~~&K%n)noCri8X&_f#V>O9&zP?D z$D=5k{XR&S6&@DD6P~|NoZx7B$Vqzg&@9^J@)o=pUE-E|`=q4KzMO^l9vL`>h=JoB z>crH35GW{Fh)-_-wNyqEQ+f)hzECK@xT0QZFVDhVzH_~&W46HUrO&q=aw;rzkn^Pg zPe8E04qr1G@{j=>vi!0v`WG$?DKkP84Z;c-^Hetj zqd>h2vL%9&7&pk@+5HiSz&kIx#>yEXg|fUZI^zg=LuTptD^MdbUJD@O`-%qA$b{oE zEH8jmfFW=PN&Br@omLntjSsjv*~3j17ibk&T6P1`;;afw*l2qb#Xs5Hr(03^{4pNu z{)-y4xU75?J+}(9J`91&Yf;1J&W8di6zI_wj9ng z4sd8zy0OaZWBdVpUMS9}&Z_w;sN0yIeKJw}7Gc)3A2$Vy?!RvJ@7>DCARi!y^OHZ! z$B@ae<&784Aon5;UQjEk0t_dm1d@nR0PxKb@+~>+ITbBCU~BUcSj-8^bu}gSRZG+- zbzX21tFMu^B*fc$Kd+c45=`FXNu@=S(~-}V^-4cO>#rnCUkxbYr}1swWN_VAwujT> z4v6-j1u#7)|Njmyw*U37r+xwQQdkcAa*pZZcgJX2y`6tKdU;0EQZBo$Vc5Ba3PB|P zj;lYKWR%5}+h}=Im8+f43p1&-vDJhqn{}dgLE3txJsL4t)FOf#k#V@u=s>he1s~V} z=Q0-g@%_|;x?qNhkmy%RFarZ43mzWtu4&SN%e2;Ai)oRuTHEJ8j)j>!(S;wf3x3lZ zTBe9i2m$O+Ewd2ElFGORSo=1RtwysHignY&%w zvVKV1+h~6w;jRtwu_?q0yr9mFV&|jjBhj6*th2dcJ|YXb{p>7%(=OEncFHP`uXsKq z&eO1*E_4eYl+U}^=W-=0mI#d4fEU;{-r(CqjXpebNvD|nnemr3ADZ-?y+ZtECAA@c z!te~6kkXJ|HqMR&r2jZ1_vA_-K(?IQFJ=z2w6+Jc!lTQNKAX>Kj(F_Z#3wfPqbqPU zK{VD4b%trc;2spDi#Xh+n_8Z>5ANc%j2A)Eyoq(B9!$xm4qv|Z_Pi$yn_wBz1F+3* z{apTx4)E$2!g_a!@;^HUI3T*)n4gU%5l@l1&V7y8zjfs~ZTrdgb9>H?@ihb}3ukH# ztNP&p!e&tqd6Eh8y&*w3b^{V2&~W8w2SRh@NjaD{ws{^PZ%PyA#vQ1|@rsuRrE;{X zQtSBmz3s2wK3iR&KmSBx;Vm>VVN)v5nsM6zQ;f$3{I2IO36SVAbJw=n|H^fiDAW$| z3hLPs`8E2C7f7TxTMxrmF1YDLD&UY;oVZFC2fVY0f@ppOzxmdT`$I9Q{#yF+LR4{f z-je{1a0~43x!;47%kuGUTEJ35UCbg%XJC@fzJM`|$^BkCNbI@f@t`P9-~L<~z0L4A zv1XT~FySCI$=C^LSBGjQ1EKV!J3X3p6oWLm0~`Qv{!@7}!N0>Xq*p^8$$*G$Oa1PO z5rzDGzzq*Ld-p|po2_GN!t*J3O-nFlYJ}0JH?%y%+@J~xMVKRv+$d0NwMk?sT{<~M zN3-AvHULs{*?;8gH;RU_>#U|}%KsXb)h#4W(3k?C{90&FN+9NF2S3TgfU3T+R+WO! zQ#W=QPuDO_32R8W`|!ckMU5SH2x#!oocwJUm?eyLHCr=a?Q9WjlRg={T7ecjkGV8O zD0tWlJC?2jW>v%@SgZ1A#5M1%KuDmw%DH4??BP4cP1)0_}lh+YSRgds+uMG{=D{gCTmDHC&}OvKeS`L2YMv|stJ z1(t^CP@N!-1oWVF2}fqqxbW^oRBDC5`4(874He4pAG|@BmuVTDHP;!D2XCgy@TX0S z+tG)s75VG@v-O|)7!WTofb5WH*6KQG*iycgT^g6Q`mbo$_OPT9{@*v@G*AywQCuoe zIRI(suw7B%S#p3h6Ri>TBajJp2+)8q7eE*d5Qr`DrKHMQulz$NJsKu>wwM42P39MR z7An5D_Zc9(fCXx3Qw$6)fY8MTT0czC?P59b)L;M@ik`#(Qp?ps^}6ZP-qcPsl2n0k z4yjsvmNZGBu&v@5jSl!IfwlJOlk9%T)Pu&^{IYC>v7f?Cv~u;@VZVJJVQ_=?f;am^ z$`nEM#!FHrG1Q29R2Uz*dgd0)pY%80nikxZ7xH!GtWolkt=o}n*PBCWP?LemW%&AH z$oU|{Og$gamZ*2Pj!e9>mQ>VB8N)O3Z!1SS18enox%950fQiz`RmWlG`2c(Bb^GPO zsisYyzD2W4LZ8wXDG-N^2rckTon;3!(l{PBTw`D+QC9?OntCzwg^NdgZ$uP*nONs~ z4J`mM3`&^7NfNJFWNLUs=DA}VH0E!$8k~k<)WkY}MsLYEcLY_}`FkJ&HDG_u{QJfk zzmVJV+XVK&W4fNSfcQk96RYkR-k2x}n{M>%0ofWSC7tLYwFT-si5FPthPb!$KZ*Y> z#_Bu!RW`4fqWvBt>U<8F>GqPZmntH@MAv)Jv#x+u-R_|b#~Ha#Ecxy4j`xGoCz40( zV^V={W7#lAt!uk)HV~u^x&d%B^vu65)8{e5g~@tZ*_tZ{5L;!93++4={tCeId4_G% z*tiQ>b@V-$+jc5qfIP3>e4p|>Uo|0d>cb+}f)B) zHqK7`5U)H!*nj8oUv^rJu^Hn2n{>7;U~W_?5?LS984#BUaElca{XGGC72RGMsScpyHry1bE0gRu={FJBtjyM+R;r@o%$m z{4m?tMY(X0znS7)soTV*Q~E$d9}(aeN8RG^QzQSXxbD0b(f761QEgy#oABt~+@vN; zMJ1;8f| zMdyO5VVj^y*9)d4SjI(GlMd}aVl4+F>fR^q8nKO)qVrt*vpFC6bfxwt@G1GvFxu~2 zOL>Q)3C4_6@%3OO1}8M6v(AgVTBff@%6oQ1sdFV>eO)RP0*zZ7hLhK%>6kb=tMpROdaysc75WI2bhTAk!HDGGleVq{d_JJN@$1?qdD&NKsSw%qJZ z@BIOrmZ@x$D?^wdoCj9cFr)chwezFlEe}a>r z2m)bss}tl>q!`$Ly+LeGri26kI+;rU0kwH;v6VqffAUo9T;;fwxpxqO-`?ZoGSUfO zOsac924RgEAK%Rx9dhOHA*4VW>EpRcBX_MU03^{R+PbB7qCl4N2=j&ZWie2>7q&iN z#t6Z`-n(YwetY0kfmb;*R3%J2gnL$*wma1(fr6fvo!C6#XwFGE3o(6y!hAu<(e>bv z>e`n(IP)UyXE0Bd`_QD@D{-0BYhGb1kLA_?HQ5>sW)0qAjs`tXrT34As$VK1XuS`K z)y%=|BP3$V>}PsG95YX4B>G2`gEY!^%B!+gmwI)LL!7ymLVg1DR?!bo2G4qJAHNKe zU^^WQ{=#nf%t-emL1X24O<3}P z@Dycv=%fZtm#Y0jHu$TSB*$Oidejl2v5A|6!``1v)=m1eht_ohM!29y?gDdaYQ6uO zJbnp3gV2LrxRS2G^^UA%k9le;G<|t?OzU!3B9#Lg%kQelz2Ki=^IIZiq=HdM6K(f{ z=>q3FKM^ZA+@Vr8nZB+ocoR>lS)|P~zz17S2ugwP4wM>~Hu}E7&&$B!;{oX%V~4*e zY~a+%8M*1!IMaz+fChAM8!o}`ZE4k0)=8-0vp|`|t^LuV>wg_6&a~ITOv@2VZ9X}S zfFh-h^9P2}@;GS9NgKa8ICgaCyFoK`(AvQED<@n}t=S^TI+#U^#wvnjt$Nncx1R&Q1A^bHsP> zcwljZ5KOQkLaZOOBXP+uvdxrbv&MQt1{sqFP;?^CEds*WBcI96{2~UWqI4WqQ`DV;B~5=t;{5$%h7E^>KIRUpg`0l+n*&I_~EwwN>FottMXFgLpFXned_k7*7Qf2nrdgc-(OULaTlKS7C{eia1FsBbD?L&gs2)j@ZzV?Wl4=j$SI25EhJzw3mL4jIKxS7=LE08K zA)1|z=^Jh9m{)u~0S)W$OS(Cwj zl+TF+Znc{!=gFkp@zzGk45oG*dZsq$2<6#TAsb2`T4c0~BTiCeH>55Db)6Hxozf-T z^b}O6FDcniZzCB(^|6UA;uho!=CMN><89$vJF64WD(+w$%Hj~kp9=R+wleBP%)yBHcV#d|B2Tr3-fu8T=za?22XhKIp+HK= zE@nv)gZm|Qg|mjf(GvEnYn{4WH+X^ghg?GtI4lBEQjD_K?XATd3Z-dFBG-$RXqqeE zZG5@EOHp2IY%s)KwVO%(sKA4>EyPzko9Md3CSj4wkwf zYzdd69%1TFCs~I8@UFlg)g`Ube8?K>Ml9aPUALp`2?=pOK6(XnGWj__A-amWr!YKH(O?w``5 z8uVr}W|#cVM&Q(Wn-Fgn@GH_P3=Q%)NZ#QT>6bugX=|7MLcxVpuL^S)$y4k0;$`D= z@V}TAX8>0iOIB+;ax2CSG`GGP&!Us$N=+v<-73pm$PC{YUc}UFsDZ);oUwK0szwtW0GRn7B{0b4>4}=gZ8Skdn)quAHO59od>xZSIV%x5ZYk&O)0oC za8w)|H#$^ykjmarX;bv{?ejzdg5_@|p$+%0Qu`7!Wijt|sm0s1PPa9s<~;Q-k@Xua0F4D+*AImhfk>k1^wxy__pHDXx~bn>419>t>>DkMcDm1- zh$K^AQurX;7KVazBI2Dm(=vIbM$!_F0?e_51WfDY`tSuiKH)i_)JnfhODsbRcM#)$5 z@w_*oi{ecI(+#~pyiRHE#ejEP6VQ|^1WX)htNj-Aw(c|E<3VSA3Wh(Dnli)`r_(n( z+#+~U$hU|HwU z5~Xb>$_gP4;A2b^1ej2M>C#Kah&;u}YI))fpbaFF!cYlTa}Z;4S_~3~)AkMVtweJw z(|B{*0Vn`dRS-0`zNGT`Fh6qdD-WK?*H4@L{Qgp#t8oHKxUCO_Jz>SQL+GJ~4y+*n ztsiRA$gv;`VIo{TMJJ$-pzFGHZbF4#^&G7;T=?|TDaO=yUCTQfVj2nA6$;(k=1xBl zsGv(2iFNn-glJ4p|FLVhPMYL1K!rA{&XzzDrmbfS{3r7xPYofT1-Il5EYVSWfCnAN zVYj7qkBS>>hn}P>v`nOmlUBLd8FXjq^TCyes~yyz30#-DS(I{e9B(-rT2a*4kE{Q8 zizHqLqhDV_KU5vA2O8GG(n{dCGOJq|oxCZ7l^^?2Muhl!_fiwV`}M6@V5^Mz1Vf}r zD81@pG(Rr_R?M-V-v*AJ7fd{WE?xG&il2+(0FCDH4F{#((Gi0v!>#vu%Sb_S7XUbM z@xp2N!pb%OC(|GfxZMtsOP?P2mT0YE8dK~()J1v;d9&A@-Jz?IB8-PoLcN>D#|ww; z?p+Q8TQHpHqe@a$y_CtJS@*7FA|_hamuCWjn-`WL@@FnyzX3T=ynd=Eh!lxKMDYR+ECf9NPdFUc4diE#j|r7}lBDj; zy{5W%K5B6@V*5~rekSmZcc~I0AdXhC;v^z+C^RYDdGCl>=(NALee;|EL&ycTaI?s# z2Ds1-3rk)c0C0Q-aNG}{C7xsx!4G=4!06nF(1bS<;^XNv$nU$(TuWh55G=(<0!=;_ zS*0q--bpS~epKGjh9eOc8XKbNFSi*Kw3TfLApDqYdFkxFTPJ*;mWTD8uiFkTf`h_( z>s?C4J0BYy3sL9s({8pYdt$$Yb(YpCAUSF(j=5n5VtR)$<62&#`WW?mn@__vr0tqG zsv)v7wATa4E6ISlbz(25&nb?&QMSO(z`on@IY;?N=RUa0Rpc{412`gD-NlcHmYcZj z1x9d%nEVatFdofs{rbgC=9fwoSDgJiaL+uov7XCp4~9b5FYjg%w8biGsTPTnChGA= zLF#>U8X;6v>LL#}eDba0sPvl-navJ;HTGVIzT?)%C6i~K1fqiu)tHUR^B}m=b$>lO z)=8SL-DTL1Ro(dYBf>B_(_<_fKlwJs)gIXSTy-zF9+mt{sITyuoMEuFrqw-zSG`G=;mpb z)giHe@VGr(E`q2u6TZaO>Y`JUt>$+L|Ah!~z59vx!Bm_6^}3NlN3AtJK8>f8Gu4Gd z{fB?pWT#%Kq!u3{^7hDv)n=(I(Y5=1_Q%#8J|>p4q{|hd>2^WpygDoQ&h&igMe3gF zQC#oFC-;u})W#kez6McjQ^h^yUEZmLN%b!%q}9aEijwI_TMzhzLkI3{kMQ)k<>ku7 zEycS#?_AgBG!j!8gZM7~+(BXRFdc2SN;D7Gdn}rx_FF5F7s3?YVOBk%JwwlwJ8A-l zD_~s)l!-vltH2Tf|G>Zp?7d)Jt})|JX1&9ZZOAnHh8^v)O}JX0^Ieg=A#kC{s$dW5 zbzB8#Mov8sfO0q`(d}LB^cE)U=6%WCTr(%k?zAWAG7|-lBUXA}|A)Y&zMj1Dj%5?2LIT zw4cHWH;G(eT;s(fAXn3D?b}!Gf)6u(lgmkFfR|KZwIB3P%{ULyV&{TsLckI+GhKQu zhUyI4ht?BXYKsuD8YnV$Pb}?ws-qfR*KkILv8Am%i za}+8CWQ*a@FH=9249_mYl)xL4}BO9x@7ZnvXB7jxZgD3G_T2V+J zt^!59fX%w6uuS4{55x=%>I{sb&$>zh^PK5?3uFW7wt9ERQ3`IAxt1?t5DSoP9a*6L zmlosJ*pqzmY3%IP3OIeDbO65urLUdF^4`lZs?e3P_X0Czk6~K1KVXMDir=fB3(-{ohX3XcATIkC^XI*2^L)faQmGiq>+7F@!baI=>f0z>ZS}1liHjgY9E6 zEMAG|WlkQiqM0_s6yKmOnc&iu*biUa{+Jjx+^H|XgC;bRTnryMEhWJpCi%?!!4;MO zxnu#F!y%zR-*nMZI}7J|iL7rE;(L2x=?36n9JX$U9Xqhi#HPhKM8tzdHo)uUrcMY? zqXx;0Ll@Vx4L?dVM4bg1KmY*Bct{UQVt@ZjsZLxAOgEgZ31{~bu6}&#f_HDwXI0~< z(1Os$3G7w5%K=$Ll(|df+4U3ZqOkEQM8u8pke<+4*JQ_d0fQj`+0`JO(FPx>l}@om zQ{&u`>5z8WgZhS5KENs-=M{hWf2rmRr-y?6`-D)whRYPWYb}JD8|K?I&3{5^=2HZa zy`Qt0-~D(y_!N(0%*Z1kOMFY*wS3>c_IkUK?HhNsa0Zk;159>0c zbHeuBV~~wgfx4a?OFdN)*w;^}h^eI&5CIC*Qt&0aV6v&G+0_1JU!e;yso_r_+tsXf zjx16mq6u)xB*=Bqh{%vgcagT2T*Zw^k6J7mEv?W#7mY+>go^y@Wu@cL>A-HRVPYVY|fNSzAk^1{4H>&~ZGEo%)lTt<5<2Mz=pA{A!~ zWU*+F9FgQ{c4aR}I($IaoNV`_xz`U2Fh4E^B>um^yD>k9=s+&jI>eI(I*SYW@=swy z_L8;~QdqUaA6ohCugPfs|MAi`i!qLOYLQ*aPur-2A+CG@W>tL<8`q{YYok&V7Bn4225R)N<}B-64n4?JWn z!5%nB4d|?5Yv8Bqx!={NCOaew~unDT?>|hEh-MIms{L4#;Zr_=CiH zJ%te`04vnsC1*+yn`UnHI5pj64==yIWvVr1o6S)j4R`9S2pM`&iToW+OQuxKunbTZ zV6fp;$SQyOz9QF2xh#Zihxe#a4bXnk$NGs@

    $UWIiW$hvy!H8`P7H9!@1-)gs(D6TZ`4AdHS$7F|1uO?Nc5O#B3=Y>tgUv@JP| zUA$>-nE-DVk}}gRorP6Bc?gF^qE0(BkTzO8*M}Y=x@TD(vO}b34pWlaJB$A!^f_-a z<*W@QUG)s~TEKlO&mC6S1@q%F4F0NjQLn2B$H8~JmY}agz84FXwQrHk;#ZJb-dXTD zlCC(~9hCNSuJp?VDkicNWUJ;HPvgfW`IbfJ}&qGtZ( z*_1TN+b|J*`5|IIiG@KJ4x=i%ChR))?;CS%roy>BEUlIHA)R1Brsa6McJmN`x-AJ7Yg@iXU z?k?>yDB^xnFS*1Q6jqYJ#L9_MW%|k}o9sN5eWv6`hvTF=4&Klz+~{_UMptDuU>0dd zElUG2)$LHFa%`LPm5!M}9>N9xzH+`x92|?Nm=s5r_O%*ybBKehgh>%irz!+|oNoQ& z)0IKjE7SCTTUJUs#LT$kC|^@A#i8*mUcjy4FHHwI?&J+<$TRitvx7MTQ=p7r76U$; z$0xD8&miD6sigL-H;@gC+Px>p@Fl+x4)mQcmZ=fat6miGlmv49O9;kssVli8{RGzdm8hC9gnDI(w@k(Um&-l{2EaC$1tCWDsk&-H?(OFoQnOtz2$FkpWuv+ecVKYMdgTP0Pf931 zuvb?`P3#=OB^S}3Z4R04x5^Mxe~VhdA%mAI#j4a67kuj22bmk@>Le^Kbw2n#si0r6 zsd=#IfT2xe(yofcg{Uu|rI~s3ra;td0s7`q96kUO3Q)7ZuWSV-6(^W*=qc$VTNxuN{#yWuSYNz;+lWOlUPWMvB&$$38FtAGNL;vG$ANujJgIU{A8)-kVyd$ zcmQPYC5(bqAm{d#tub?gj)NLgi_5yIYn~tB@Oo@)S{EtiSAm7GIEQ+m*@DiQR(`4c zWA|_oujaYg$z`M2>p&~Juxew800Gf9nq@wuS;%413X{tKua?+s^Se#7zQ#>`4+sLF z+-qD2TnV3@W_*=N1v8dgvc^*p@ zAiI<@6>$vl`w$}`=+c`V_=L5=%N1#r@)1dyw6PkAr%pFF!*UYDKei-Y z7~m}DAuc2>qqn*n7%2cvB`(D7Y$$BGg0x`Ut7@+Y^&8;`tX>TV6Gs|mV@{W*6W8a6 zz|{8)FmE`a5h#U05@NicVT*Z)r7I)n;**e_`lH!VmlT(Rb_&WDQhMyA%n5C#cRP69 z!!VDVZ|L={vl_t2JE|BbLx3~}HotkWvc7S&KF`*O7OoP-w-4gTu+2po7i3copW4d| zqos+qbCd-w0yii_2knMGJag?G;Sp-c7xGhL%xqNLt+bA2)4n#jRb2zau5l{;*6)EM zoazCzO!90qL=%eovs2WZ;4yb;9Bb|8RMl90jI^su)zet+l1F^=^rvj_fLT4k&0nPL ziz z{^q*v9sdQ0*&{0#;Gwx_@;C4%9TaU-n1+*Z4cSnr8{3sNq0fB(@A}MzD+%ZiM6`@3 zj)aeYq-pxh;b-3L`ohAP^_#&zlIJ#IC`vA)nZD zp6G4b=eP}B@Z;lTv)7JsNeu5>9}Tr)4HH#9D3mxD900lT^+A~2^+vQeb zo64h#`HqG<;=i!>dm>^}ZR7(rivjcM!lcE(F%o2=AtCg2(UYdv_W(Y%T@p_FZQNqGq*6~Eo}s5inrL<9dZ58nbu`~h33spz7nj)}~xyBaQ8 zT^NU$-d?frj_PCM236KgPAuTbTk|&ul#k8N5e;#n6mNv7IFr1|7zni)%8b5;7zvJ} zKMrqnzj5ntlK*x+FbsYugg1`afTg+Glt$UGyL7{;pU;E9N+R;hsr5u}j{Zvw>IOCv z#W?h|0pacn=Io&)=3(auX|AAq$=Y(~PH^;;5|h-?9kKN<7%nx_FfyZ z`U&yk+XeHrU~KXoe9|GA?jbA3YndQL)PNRkQ*VL{5o|h4vv8UJoXy3V8?MQp9zDF< zlM;D50!fXs8itpr5ya!+G>n#q$QKiq2CCXwie@G81LPlsZN=TEpafH(B0| z2HgG}L!I(kHo)6+QnwF8bE+aH18U5`za?wkeouS;<O8zaO9*6~a3KWrc980gNPN zCC6Mu>POOm%?!K_i;87-+nzvWDW>e-jg#u&hOy_6Ex^{Jf63{;AQyH{TMOo`bWj|F z8^poyqLE#ga9Az85NLI}a#O^CpJB_bmEBVgbLAYA6UX8o8&Dnbdd50=J*Nez_#5b$ zsN9yql7~K(Xs3eTY!Gf9vVnoYMpi2|TiUOY5;^X~Q+ zlZ!0GMz8jBk=KW$U~KPlvW31H$_kpKRKkokd!-C0gu~22U8iVpyGR{JMNxdu%e^yg z^DF?HCrAde8F%=jY`14!Iek@jhz&t%3KV(`lv3jTCW2!!cfTtb$YL^?)o5*khcR(y^B~? zfHLSX00hToCkF){2?mIwL{+5F{QJRObl@En>~8D+)Jqz6X{<>P zH+`R<7|7ZVYfLA85^)(U<5&lp9B0)*Fv=#NG|4jQL#&2G=}LUm3UH7pUIj+ zflq!sJ0=M&>tTf*>pB@H5Fi|8Tf*MsURK{alAJV~A>ETB|5}m6F;8Ty2vKoUx#@%c zj1iF?25GRG!^%}=kerEjmW5}BTLqU#3_(|-BaZkU$F+Dxlg?y_*gOCGttSBDaIpHQ z!s+aCG@h7|zLS6NbBVrtwcigMB-vqT`2s7cM%EJ|l*=X3Dh_1WUOUN<%ik4aIx|}I zPcIj{m-Y$s;P_xXI*#MzJ!&-&)MET2^vk8b)1BxqA(KNw3qpR5VXvF_9)Vf=;~B_z zrU>q8Y(r2Xg+f*XRjMyiRDPj7CD+tFz+5-W%!lq|*97Th=Qk zjoWG#Y6ed6#pf3HbTcfr+WJ)v;OITe+o&^Nl{E)3PW05~d`Dc3M6?4W{FaB@QG{P> zET+PB2RF*Vr+W=>#mRy=+3n=9i38jOFiBZ#c`<`Ol`Qd~*&pS~B$ioSh+7Fdc#FDT zH9vS0=mrps!h7+U0cn<|RP^MZ`t^S8zjok0jN%8ZrBhef=gEVjwq z-*&~91B$5z9zGbMz4x}FKDIqS&i^IS7G@yQ#F{%->4cRXTXYtYq3>$0OXq{YQ}{U_ zz@@7vf9_{A&$Yh~si$PQ?>DwAy_Fc@;BXkIGA8v|MDo#%!GLSTW_Z&x+c02 z2|y&8IC|vT>p0A?K7_0G=QkoVxfTUSEY2I-=Xn1m1(1g05pnC!>Ugsg7)RFPtofK( zSQK200=E08W#fid9E+5a`rtRz#^5U$w^!utR77D3*LY=mHfk_PE@xxPqMUUZ5upm) z5Rd1riC0~Mq|np8!s%!PJ7qh#lTqnn_`>I&0Mtr3ZBgh&Yd*;y7yn&~CX&LZA`L+@ zL0qIPenlhZIoV2#sHSJ{qp4g$)^Lh7k@PORk^m(87tM%qPG_`Jmo{6>; z{svBMttkAX5A@tLiBkX0GvS0*Z+Xy~WGONbHbFycVxxh{mG2nV$$Xj}7Mh8Vi2C-i zBKJ@GK|4ERf>6#DmBriu&Rh4z5tSEqyceT1kCq9%obQT0XV<72AzCuxP-s5FD%Hj5 zl*Mv*g#L(l2^W7cjBG0CV{L zRWelH?iG^XE)xEdkTD9SK@-1CYT?RydI0|tRY+B3FgY?ni{;yoS{lH|{qd{IG!=c6 zaKb)6eGO**$?Ku)*R_7=?rbl!zzTk-$+^-L?OjQ7+FKZ9Y_C#c00QtX9y!0klbZ!W zJp|9Te(u!+3MZb7jg08Rj-|Y2AB|8BQg07ml=lVD=D71*MBs>5E{rQMFTCuj?UGnj60oD@lB_ikFaanlh4>euz*1W81V~w8RW3R|02)NiY z9+72PLfzu<0wmkHbC-Gko!oKH-NAzVD0M3|;3f*P=#8bmp9R^LD^~Rit8P@P<)8_; zG8xGa)s%hFomA9;iV-zUJ;dKs8o7dls~O{Exk9^Nsh}THRGs#?E+qHAEQ8ZXde6^J zjNlYvhGz{OoBeUvAwxtdfE&zAk~FQ`!4uioJj2tZXwKxi6r&Q#;m#-9l)Z3R#|VrP zYLtKg0Y0VjX8ec@E^eVpQg9(EKJqIf3NAZ89r_D6h}SVFt9KAuly!{($V3O2GB*9> z76cEiZEuo-zetN+D^5wpkXH)YPS!0)#}Xtr0cLy?_8PEV8Vi z9k;9ey=cv=TPh_|&!+pfJ&J!|?e~Bg8jwPpz)te6YtjuXtONbl_3JTKdR8yuZPt@x z^2B`)9q2IbfWZ^&Vaft^RV-nN@wECARx7*;X@vXmMjqU%$Ujmb7p=IZXURh}*RP*O zyFEjXMDwn%YPk!bW`lQmKU)r(Qj)0UjPAIh=Kz<&Lvo*Qx=}+mz9uPlus%P#xVc4I zsUIZa@33?_n!5gRYj(#47f#5Y<;83?MlfpX7Sl0i_`4#MY?Ww=os}haSztn zO&BVuQG0)lP=m1`d-`&&i<81Cq%Y=C>LHP_(3>34h69w_AbmM*md zXMqd%l$l$)+FgM(c`QYNllH?lwo2h^9=N}Q*wLOg3Q`_~Uu`mFU{1hybPym0=zVIY z)=X{D&$;zvb{3fvq4Je_oz$BFDbOANondzHtHH%{7NIOBNuy(WRk2{Kpuu;+ZGW!O z13XOmdRd4=uFt#mID%^m%NtTXQbzsIm7+zn)YNtmvFrqvw7e^*~Jyk|DqQl|nPQ8fRCi@UF)0sUe%!0Pj-r z)Z=f~N}ocZTo0H*jg_Njk<4a)t-K9CE<$BlE%H@)hmU{%W!OB0>0r$S!thlOdSmD* z)*Q@?{NUPsY_;7=khlB{O54Rc%TQtTKC8Zq;4r0FMMZx414al9U~op1-Ce^#87+&qC*W?Sy8tHjAd72)w^=j6 z+D+r$ZG`aL`eC2NJe&3buk?CG;Bw|}uC4L3lEqHzU!QD_cWT(`^mG+FJh_ z)OFs-pU#X+v6>4_{Y0{fzgcJ*!<<1p6tftaE+Wy|Dkleyz~Y{5mO#ge*K`Sqq2r90 zQ$!VlqBB{X-D$dQ(KsM1@~hvyYm@errHz?f5izNF+w4;p;!2P=`~u4*f(?Ds%@}^{8#fo00H!nAkESJ8UTioDLCK!LKn=6p&K> zd=s_0q6{yEzf1qN^KW*_C9NctaDO1JFfT-cMhaRnp!|iF$R>|ZYM6+Zj*Ng{=2tv} zGbB}QK6ey2Q*48qAt5cUiuuQ5YCbz5Tz1x(*MQ!ap#QcodvIe8Q@{5c;n%Ke7dhmUGb0=3~vXZws(k05Xx_{vB zK;|?(7OFo;E?;y@OfFV?Rn}ON2Hm}_1ffcn4ae`QV!cq4U1`4(qo+zxT=ie#c{HVi zTIKUeZkELYknH{PUEDy07D?#a(h##m^CfnnCY#F#E!L@@4b*T{;#x|5i!8`Y+?apF zSJwOvi6!+rHoWa8y=~dQg8rrnp#p|$EMZjv<959XZyqjGVMcbkcDhiJZVEGSZs9l` z9&;Ol1dT(}Lr;5A#Q^BRk$+xreo1*D9$erpRdq|IoPA5c005v=z`5s-y0Z22^P6_? z&oR5`x|_?ctBTD(j|CZ_-?$+oVA1n(Vy<8Ry6@HQz>gC_>|;VT^1HQ2n5)9@-Oo1Y zv^A{SV)n_PeXM=wV4;|sJORJACOWb-)Ig?KLg1PCclA^9>HLoskN^O@Rshji(8V(s-=XcyIYwF6Mhq_gzx9a;#vFZ#t!CyA=%O5s<`g3NNFm z7Kr0|jfS8Cfx``VqjKzmOJ$89)R{<`b7QU9R0a|jgRLvkHkBf{e0t| zLp>Jwxd|RsGaX4<#sHcW?$=5aAxISrNpQ=wG_ zb@l(zKa$+}@qmfEPU;WI{b?T==(iq?Fo?XJ4Ji;MeaRNDLS*q(Hk2~=APj%OnMW(q zr&CW3h_3s*=C(-o=mS$(+gYM!#b z$skL9LU_YqZ^2(@iqbf`pQN$^w9u|P>XppY#6dGR6=NlfLw6Y_+0{PMh`HdUIPacF8`sz8x^ z8@9Ck59PoYq?Y8y$Y6^Z2B+^3?tV}J&dJhc+24m|2lrUUo23t*eKM?B20Mn!vbmXsZorr4UFa$0l#>B;>cv0k$}1JSOHsG}#%-k<)sA0ekrETSL?APY(v zIuc9lN@8?vj!7p*3J1wDyrDuo3Yl0GmbVV|s9ss>lyX2!tu6Syx*A^MzbM)XnL^O+ zpd|!M20m>N7S?fUui@8W-!^!0dW1V^$#?6t%xf76mL8b^GS@(|M%?7?AF&@+7yroQ zTr4@{>627M*LKeY_#0eOYg!1hzFn9Ng5?#uvb3FuwTe+ISoq%qKuC*tQ9m`ItV-HP zSYit{iT)aPcGf-$DDAljlm%56hGd*2TFbpVKjaj)x62VjlP83@BAAGcyK=~rkdk8~r<-mBy^%f73e_zV z|No%4x!(fbYGItZ<%Z}LRvKy2F2n+9@7M)NDWHS<2R#rrU6XklNCym@Z^PpA^JaMwizE0_LJ)%LZH*k|7XjWGt$ za@zQtM7OxyEuCN%XB|yk4}DmPP5UB{BBCJS3BxmB1V}h%m@KMQK`v$zQYyviVW6_X zK~}H6_cDN`bDly)C2#K*TD$4rto`pX%$9wKzGV%Sn9Da`yEHkgLAo*SK=cOG_F?TG zN}8QehLF-@P`uO<=CgVltN)P`uRK5stzT@73@$7`>A8LCA5!dg#Mo>9s!K4 zg@B_}$nVY$9o2ww-w*R}mP2BLI{zAU8V92dfb+7&!*b)Tl2aeFwyIO>iLhUdeq$Wmbu8zr09gY|J`=)oXV4mm z{XPu0>ptF3Y&q=IJNoN7a8nQ8qFdBC*$kN3BageGcwJcK0}?(G4DPA-wX?`@sKFNl zt`Z$fCdt@+(erCTlzq4qPplqnSnKE~+>S2Q8(4uL(KjmU<@Ri<(T7-DDMZ1MPFOMz zu_$pk`+hg5{jL9iifua$U>}~8n0ek|J&jfOCv&d9VDjh%DC~t;^?b<=y)2HQ?s^&i z_8o3X!S{SFU3UZo*S|;hgI2rDYmNf2ERffPgomG~!%w%%E|ti!cifO3gL!71n1CU8Bg_kQ2Z&D2jn&cQf&iLlrnW=wR zALVP!)X0w=jDlOfNL2|tG6a?(yD*n79a)Pi5(^2cf%7~_oD@-|j&B(vUlN5*W)OFn zJRo)qZ;qY!T2yc0of+zhaWe**@LbPVJ&j;X(W7aj-ZI9`h8$uyUk~-8=g0H`wF&i+ zk;LcQ_52d0Ie%(Vw#Bdj0}u}n9H|Kjq2~0rfCFq4(ZO@hLU0cY2K*k~ol0nU5YNw! zn6o)amaV5WE_#bV7|a$=X))yyTML+Egkcc6tmE__j0bCPHgCcSmq4WdO3}4XA5Mow z($vOHAVj0B!yK^$qt4i7!au1c?)b$}BBVLbYF*`{q&@dPyX10&iFQw~&|%v5h7Yqj z36w-DgVm5yPcVeKRr!DjtKdz({Ft!+5_L$af=Va-=!^&GpU$& zdRQB2w*#C`DYrqwv|bjuTmqZlphj@vcPDLNBBi8{HacR*_uB!u>Ll>%Rpu3|k;usd zr#_5y$$I6fx^}TJUOof-S}G>^JP_zPAIaicCqQ`@X~p?l$b>aibZ%5OCd97Ox~AUi z#EhAKd)`g?PbW^%65Zu>nKL`WcM^#!p#Ud((hx3V?Qz0ILr`$T!7I|Wno)X3)@tts z!An!S(ow^#ZDHjAH*(YQ#w1-ZK=I>q1d)eOtcl+>jMio(Liks2i5$EGl$4Nx-=-L3 zciMg>I|}d0Jeczj|1CvDk}dAx-eLzj`f4u``^#RE2@Ww?j9)t6W(*BLLxjdm3$N+V zcY6O5ci2wu0vN(U&UpP3(1F)^`GXCd)3ty2qM1UgG`ZhXUW3-ns;Q!yr1~kgoeL$~ zYwA8u^1KdJjKakqIG^yFFjMOFuHy1x5a|pbTIhQyi%}iY)@_kHiM!x=c1dN4048`? z$g**`XG8KBRP8cw4yrFTLL8yS5Cc-fr$&^&SLwp zvC#Aup=#NJRj|Yfb_%b> z+FwQzJksTbjL7GN%9A8Af6`xHK1#)sk5q0al-*|;*`8$eC&z2PT`_JGM-D|l(I?ZXhtYF03$Wi{oBU%$WZ$Mt{!_vl4mIt9Y)her0>jEv40NQ~=4#p%>auh-Oj4J}P^Y=&c3NHv z*`c~CszYGJwZ<1|lZM1cx5@T-u%|sTM6-+~WA_2|Xx3bdlOIj`L$>_o^esj=)aW9PC1(?ZURqP0b zzL2w5pWzmysH$b1(lu?ZoB^{M-2TJi9v+^@Eb{de*DF>6Zl96msQ>?=+D6>6m7j%=FPY?%5Z5#Ygb zL0$#v6jh?4%rDF&G6O6mq}pGn4T80^;1oupIm9!ksF8nCPz709tF8-E&$U9cD%Vnd z*Z4b_Rk8P|VU05A5%TmVx>$Ma5x4TsutrOo#1!0vX!QN7fRFTz^n19(gv zZy)od;>XYIHTyFv(5#z#ohJmSX$%7rQ~VqRBUqA+mrQOvC_}HjtKK6lNKK=E#1?Z` z6D>+f4}a=1GbKkiCCQ0wn9B zdA{lYjqJJVGQaX|fViZ%r*yCuD7sLX^|$BsYbtI|jd;#p2O&28YyrKBA~$*=0yCW? zL7b>~E}vQ0(QL9yOv~b{zfW+KTzXo8cmXZ4FTkw}qXlqBU;^b;5Tg>`&`S%73cU;y zj(_E00A>_CV9Fty1cKU^JI&e1>9H10Q@>eUQw}*+0WzdyP*j91-R3J*2}li8%+kvW z6l-L%(#Bnhgv812Y(kVdKc$6?1$9l%ga`4X4V?d{2QKA*WLp;mUjllo90ULW*ns)~ zPn7-@)m3`i7QsaT${6S0FX|GLxUPHGdO4{ztD(JoM8f0m@LH4XO=>Xx zP&&zQzgedE@*u6#!EZ z4xs=~T0d-6rf-Xyn1?#iPjhR90im%rExBwhV%hRo+YMqCZ#Dn0D9EmEdRucOw z%AxL}ZeOn33&VShHZ@U8n7cSSmKC@Eyb9UB68Oe%%LLySN7o!HCf{&7!akc>0PvQ22_s&HZk*ZsfQ89YN^mhRx*MG1-L+IW>OYus@6<^J zg7&8-;Vy>gbZ?1xz3E{f3#>XK%|%62?>4*IRdgNxT`WN9U5?jM^E$sJ4rXctt(89k z8F>0UoU>f>ZkRqhbCE!L(Qi2L6f=^|&o0##IICDBr0(_^~ z03h>TsW|#l2%W&d(|G+W)gY(vXjVtk3sMN3SwhYO&CIAKJ8j}?4}^pfNh{yGum2=( z`P5+#a#41LVfy0vf{I{&r}p6i7N`sQ0vO%8z{>);XKUL*0%MPMsfsrBF zLy9R7#a9n)tuzpOB7wZM5sMl58($6w&9$qK1HHACK-?TYA~XEriDn3ZMg)YBfuPv| za}h3MKe=K$TGmz6d!R0zuTp^Rcj7KhV@ZcRU+NNc5++8~W5QvIp}KS9ALXM+W$g=6 z)w{`^*^);waN4jE4;A3pn$LUNsAO*mLqHuoVQ6E#`77tikXlZbP*0JB^Q&gI6U;o5 zmYcAuuc@F#;laxvXLW#FHcT35tUP-5rh!s_r(AZv86Up5%^7Cw(w2axlg zz|#ByH=yI=a`8&&w9XWxBaRG(Wra#;Ua+2YCV_@<=rdeJ zAug4V10?wx;pvMgUr9P7Y^I^AK`F0kW6sofqa~We0OD#+j@=clVp_;U(|^C5zrO0R zZUNs!8bCOH@_%ah-uPWqXHJGgLI7Yo@rmA;o@000teYO^+YWEeDwMj2f=NQn^q z(FiMtxE&p@phj{_ko`Qx4>YmFBfKucD8(a-=N zR7(X!WwF}(!9r}+m?{rWTktjG5qM+*t2gnpq7>jDkB_q8q38Mq5lfnxC{%O zg)o}1C6r;EAlrb*Tp6kvZw|D)Sard1o>4bpRRUJ_9_LXY!P|f6TmM>p6z>{lL_8M$ z-5WuI6xb{Nd6M>r^p5)F3!(|wV|`7eN`WM3<;?VO=DsP6s>^;SgmypQGZ%^WEF~q} z3eLXVx`1%R?ZH2D+cr-i-xNq=@=*6;bp@;H8y3)x2_Jv?`{Lp&r!77AFlqn*bwLq8 zb(U(JoL5A#*q#c01Q5*+0=-e*@#jbk~>hOb;>w@3dJt!N*0gj|I$ zJ)POj9Q^`CP%gZ{N!m+hSct85?S?u&?NblQvmwA#=n|@zI2gk)Eir~&oY>tVLGF&Q zu=7L{$^tJX_@$`cU<}{Zv6gP};U?Rn++0*t{D^O&HqfZ;+Dl;I697O+C52t*%jj5iL3 zxZupRk9 z(HEcX3Q=u`X_53;)Nxc{xjyq4(BX~yM?(r-nW@Rsz8$cW>efaAor?^47x-JCJM0uF zg1yQ50r#+f11eZM z;i>CzTe*ln|E-ze1Rw|X*trH*r&`W~)-B*!hj{M0NQp{_kZ!yfL#$76@*eLuD$C?tEeY}^>Fh_N;^FI)l+?G1GiP4|Y*pItq?d#;$3!wcODSL(d z-fD5SCRC#T*Z=zcZBH`4^0>%g000933DlC^w1A8D<+4J6{HWpkw|PbMy@pSiL8cp4 z3{of0%jc{}oW12FQH-yH*RB$TfYbEdztkP;2p;IWsMM;yaWLz#*ZtJhU)F;R<@=-o z3p^hkLS1L6>UIBBcq{54P$UYjj9Uip)(nhdPc)uCIY8&4x)zQ%?fT z0eR)f0F%+}oF3kPoN32o6KE`PWvfMn%@1G!wffsnw1LvQ{Hs#6$rG?^(r_%-iI2D? zd1GuWAF~Ku2Xbal7X?Xup*aZOZN(I^D_9F7P_{Hht9fVk?bo zX@&~qc;gi`N3&;4bV4b`@H!|%H}mz8dZe~&8F(lNCeZoAQ9as_)#M7S)B_aIfps6s zW~@)AAb{qb5AF)P|M^-r6h7igmea0helvq!aLI4)f%@|hyP=(0n~Jb1SZIqEJKYX@ z>d77l8%|Z}luKq+w9c4iYCP8LRG+IY`q55&ExDomqy3qrh|1pv8Ghby1t>1ih>ty@ zr80xD8WZbtQkAa17{vNiRP}GoE{}GlziHhtCpX0Ye%F})OBQ=By1X`%KPxF09LCvm zw3eYoPzd-rE+XcKP8~C2vur#N5dQ^Ox1l-}rScCtH_%QV`LpfJ`ERL$1t%6i@gbuWZNFlZWp5($*zk377Aa zeOIt_(6qu^po#=JFjZ%39v}r{Nu$bTg;(0(+KEPb(TQ14wSLZf8CA{2C=mp>H`y z4{91(fK(AiPjijX7ba8;*$elZb(67pYelNAfDKJHc0FBfW5(6Do1#o1@z|0ellpXd z;W)+{Zz1LdShEErzF-N`h1Ij_-Su}=*+R{eCi|>XaKZh1d8DRQXmZQ$b{FP=0W$pL zC&005O{T(0on5gj-vFjBUY$kB-t_k@Y2FM7$?m2>FJk0)0;Th>Tm%GPj4mN4XPI!| z%9C0vxU8}>N(=nuVe6oovrpzW%c(!cf4Og&l)CPcnw51pU(FpjCU_kQ@%L4$oSOMI zA()2AoeUDLUx43(UbRIKQCqmF87Qci94Owtei58$oDzd=R-kvB)Lh9mn*b2~v~&5( zX6PVp{3reGat1!4xF%J^%92A~IcTT$ipWdl@CM%8J)2QOXm>oK7|&55Fql-TlzPKp zQN~?8+hhH;cCTwlGcOYzx+=jY<5Ipv7eDkd0Y4l82&~Doma?Qhg$f3zRz;ATaD^m_ z{J0&nn0e=Y6JsnYEPDir`|ekeA}7mF9J^Wtzf!5f-w^aa`~lZDn(U8fu+RL}4MqaS z2^khCF8vQ#jeb9%tqBV7Ah;$ z@)g-{fH3B%a&|`kb-gd#L5D;v2AlLN?_-K!tz}b$JpjJmz*Qrb-19}&2@tO?&m9c7 zO=@vOS+ktg+#q3{xeQCZ`fvB zUM^jrBEFG)T0a$z7-+ttlg4TT9)D#gQVFbcG*3N8C059dn<%KP;~!n_-VM)(wig2j zZ_J`DUYk(TzApeUlf~7YFqZWv0CjfEBX$2mvL+lw`pr!Suo(TbnAz?W2n+>TN`xJER-r*Z}%g+@OyJ7BCpG z`lI^4FF?w7;zp6`By&musjd<0l>Lfwf z!i`i1lkF~9$xB!i@Bp&p`Fo@x$r>kCtD5JQeN>CfSKnA5%iCgola;WGBsN(uNce(i zgn{&T-!<;u0mVW$7MR6-+0<;!FD;Vy1R@ld?Xb?R+QnSA*>gzE2|!ZSS`78Jc7o%& zAw51TEU9H__!q@9I05-IYMmiTAs59SYPC7wp;{cq$*O#B@cvu;Ge&loR2{_nIRRl2 z2JjxqOIAtaiDGJbe(%1wLulOsZw??u?L^iLzT?O1e+sQzhgZ z9;njVr;P0bS$l2l$lTosh4pRe?ZhO&LM%B0@}BBh!WIYpQoruY)*B|il6d9mY5wDK z;Sy1;w&BnQY+SCq$K`ET~szDgBtE^>6=z$wUICFs6H=i8n z0nffvk9bjs5Z=$A+w3ntpvwi6^@irT4{6$z*SSa&-M~G{Ja~1l5d#UkL%f@d9%?3E z%_F$UP>v|Uf=JuMTX=Cu36VVC+H3lwx_rQw;XSfCQ$kWHRAw-DZWn9C9n7#G$Hc8X z3EM#Uu3g$4{IF>xCVy9ovlAcp-bbiSkIYqH0YSU3NX5tvOatiq9sL&h zx{X+!AREAhG%OGAT+EQV*JE)>HD9P|*0SPFkjE#E`$&%AyteJ4`(hp(!Q)+bag|jF z^00OghWM>w?#5-Qg|`mNzg6_%jJm{tsG6IJw;XuXN^RL!Q+Ys`Eqf*2Q>!6fG?4~yw>AH z6|iid#A$-`jQby6joQL;y@RE3Zw*z3{r+Wt^?ogN8}K%TVgPyHhA?1UE;88|XX``;?H6E0z?9$y@}S$<}nv>Em~K zk}*;%#jV09e-03Sc=|&TxR*XDk^u-?X@>%KP{ zTzu8LdL+VQ6TXz}WSPmls~7=cOb(118eyC?x+&W0q&Xow{N1QVSGLKbpnA8nLra4aI&{|JprH7q02* z2_Nv{RrHa6On>w|#O-R%nvB1+ZY^IErVQbb zXf68FC_1%?RGktQSa%f-iM@+UR;%(@BOVrxW1f)mf43+I!J&iS-0@J?qr=#f{?CTj z@I#dVlXYwU_oWJE1{V#%*&gmz1#LboGII)2LX&?lA|>&N%8Wy`?i@FrnV)h%Ljb%D zd-I+lT{m57eZ=s7+0?0V`q^91PE(&ueBk&VIk2IVjxU+VDCuH?>_a^#GtHY=AigE> z>$W0;$ATA*r(Ir_IzgSH`er4ea~%P)W@(~}rwqP@)-*b#xJ+PYjRD5qV_R@X2T@(- zyTem(e(2|QBR}zCYOV9T?Vp+j6K_Sx%wy&}=D`qrsg45N7IJPS%gUW>NYEL<+>1mf ze~?Lh92~Wer;1cPr|_+M!@WA1O-d1=i=PH3S((2Gr~m_Uzm<`fVel-4)N-d&Vv}1D zX1^F0bis1H?n=js{){ucFF$htc*%LB%ubzdN=04Lpc#V#z)RRP{9=bSf%iyt!eLO| z)~zPc$)-A@DC!l&CAJ&C)aE9$mqXEYop@eq*)H)-VoRrVT$kM2WvUYh;Ztqpa(CJ= zaF}xdlciViI9!50uBIrd_40&XA@SY?k&V~*@OFSGCB0+{{T0+L-gI72P*bE}jeEi7 z>}79aH%YFUGtkL6kNnE*C^LWYAaW)7)R(u_O6t~)deaWWi^t}I5Nhr86>=l|J4m3r zi8ZnZi5__`$ICmfJOmCbbG)q*-y>uF)b92~lHkq&F_^f){s905ZIbszqsUjn4HQ5W z#5=)SfEB8o8vq8N@NbLfzR6X$MB}2AqI_Dyg0;)DkUSB2Tj{xU>5XiIzY=*7^K9`* zdO*PrsSTWxT=GgwZayIZ^5l#wn7O&GyjAm)Bd1YHAAjtBo(puRL)8}_pss*6l?wsw z%z(&2fD7;-xy~B|IeI$S{>WoN6Z`*DO2e!8#_V8d7M8cJV6&91<;ttbCW$+9U;D#! zykn-QQasz7Xp1A74{mjMm?lBRy`O<+p$GuC7aWe?aH9{@6JNs>=Xi@ zK$g>PXYrB_FJtW>P4MrHp1YcD&ShkT68MmtZan#`E->Uvg9xqzv+EZxoHuFyDB(_C z7#gCH%RWh64HTMC32B_nIQ9?Nr$o@KSkv--;=;ZEZfH!l))IU@g^J48R$y;}&c)se zlwIdc6>IpmFMJ*RnGuv?>%3zl9!Y}#kJk&A)?ql5JNjPg3kcLjdFybd5Ireah z58K6N>l@S-(>6t9j~4Q~f5L;)m6?B?V*?(oXh~C+ydjTs!OK`$>!s@YsO_Q59?%Eg zXizogXGz;v40wvTg$t`gAdTF}L5Hyp?$q3|2kNHL^llu08}YeUZ@_0GEA>5z9C$Xr z8~$w&CN~Q#80UH;MssR-)+RFG6p{Z@exvUQ<&#VLXCW_OCDF^VkeEYKR83!m>ZiNk z&1A*&!v>Nta=-upH%AJtf#d=bU*_ZnQ%(LjDsCrZO7?mPfB%fcEV*p-&P@{q0L${` z#IgN9FJJGYC@Bp{j=&wgQUL7KJF}>YF`o#6?I&~K`G!1KRS@pt^p#PR!?L*j^WaXr zncte$cUM?bpcm@Q)Q~?BqCW3@W;fz5M-dgcqTjx^{#5D!onsDSIHk7- z$*)T)LEBlUY3mR9l_-{D+c}f3h0RS(Y9n(*{W*ryCMn???(BK|#3GP8ujBHi0q{jJABa#|4L7lVKgpa zZb?4`B4&VKxiA0=hdNe7{^H_BMN%xl`&hjh-cRBDE*-j?8%RgN??L0_XTsbmaDV-Olu zi)a454|bpuzv9L2SNh!!bf;_|F+tQ7Kqc&v!Jt=k0&FBek(;w!XuL}ug*s8`xIp4OtzchDPuWec*X_=0$rC?E_)f@ugrnd7@;Urj?VcNC(N!`Bi%a> z{Yu;?JdfbJ;iKeu+5&|jWU%Q+0m+x|q>MCs37`H~6R=wQor(l@{hd&|y77x9NfU%2 zH!iES?0EngVJc@#7Wy&X3|cA{$aK$FQv6$F?5zVLYRsQ9{h_0c!q}MiKp8v>^KO7x zzVj-`H*K!N{v;doB9faCx!(iGCqm+=)zOx7d%`yoTUXa$H-jFpv*ggd<@QOKk!S1(AEn8)TlO$U-a&EXUs}Y z>YhKi=J49D()a4dJ*tEgZZ`h09rzL7Tm9{VZt=wX7vANA6?$$(+r`KIuUHMu8@X>n zsU*4jB&|`ll@~rp>0P7ya{cY3ctvu_}vgZ)_qec`~O(%n(LgGZSE*m z-K&7W8%h>3OhI`5^oB?Oc)6Ef;*<-=Es5Grf1%zwb78`I2d=d2fvlM(4vUGjd!Wyn z9gH|~hNIIFY+_U&$b|Ard_kBo-GA#FOvLX@z5oCN00093BM<|bdB?9sm>R$E)-St6=iiSW7GU|saz_Hh9o=viokoQq2aqroLZ(Ms zueGp#&unvq4|XDAi56!4}~A6o5R=B+?Fz!2xJZjE$Dz(%tr9@oYH z=FIc6>_qO%A`e4nh;G00qJ}a~bsBwX$t_visr^XG4`UF~0gr+WipL_mAY!(9hG10( z0UwH$aL|zx7IeWI3k;d+UYx&tznJzg@p`qqLv-7^VyCNe#fgAL!vPT&qa3AKiA3v# z!2U~x)*koCzK&jPpse8?T>a0mD3i4CDR%sPL)YsFT3x3Yg}1m>tq8EQzY=QEmdmKo z*f84z=mA%@LoLi`INdMQKTi?r0G02YYI07|N;nAiKB)!X_c3T_3m_}kDVCVlV%6IR z%CQT&q#}xHAlqBw$q=#fwnRt%Akg8PtE6kdSzq>mic~#fU7|c~Y6sXQl2gpUxcX#j zEbWVOAwa%5u2i0)xSl8GN3x%|j6|yzwr+^Ad(AoG3pFOS#$OWHc_aW@%U^j2DtFCs zRQpK0ib82P%RJHWYNkSlv;o7;8VHuY%?*lC14d5@tRd5diN+;{OWMY_#Pc+WOg!MN zR7K`ORv9K#9xmhWKOJR=7!Og?eNWl>%uO;7mMxLACC<58rU`?LI@4eQDvJNnp|B{i zmymM=0Fr?9+Z?EwnG!kiOAuwXI)h(Q5b#z>{P{1(KJF_=o-eH~Ig39v5Y}TQzFpyj ze`S+xw5gulG7F5PqzWR1nIcRn{F-*K&#Z>x%#7+BRc;@3yAGGtLKZX2_SoP6S-ONb zAMm~Za#(2BuBGLe;PwVqF@8mBRao_0!2I`~c>mt}3EtiZGITKi3pD|K-As>%hu5K8 z=NmNikjP~^2JR&xu++&T9UdGuEPKLRLMo%4-L&19FcwBCaD8#RG>B}BbtOufV5#>h z8C)j6|3tq~!j{TMwVRW+8({)~^<1Vjk|p?Pv%a|55z~Q-^Jh1YR%fg&yHa}Za!otH ze@xxK>tllGT=li1w|O68Qr=W9)Z@eXi`ufiw^i}{fmS;ZqS@6rOXk@HMtW3*3lU#; z$<>XAPI-J1%ZBnIOy%}(v`Wy-@$F8!Bi+6^<9vx?g?6lNG#+Q)3qJpYW30A4B(fL~ zbFnsZF7gzf0rVO;S3JNtH!9efAE*DF=2|HjMY5Nr>=^3*o)6$K4>KyzRQTAe3bc()(6-TCZu}vZGqt>68xg z1%ZE%cdk{H*qgzt_CpHMy{c0a-T$G66B^daf+ao!hEIwS&yvMl75wFq2c`odI%R=% zf+rmCjSNdWK~b&b0UC%z=2q0O80PGC^0T5!EbK@^7ML+*XGk~J>jXwS)1>Fd+AKSc z{;UssB5nH}qdz0aXRC&ODPG_>c-sC683ie#ZfqPle}aB6S2QHF6na$iIv%vqXLkSq z0{}DroFnR-aiPPb253~ARR2~6h|koZ8{~KE3B;a2O9~WFlW%T$C5tI!QlXP`@`SP1ax%6>^BK};z$eHe!nK4 zD3vtEpUOAIC%1q8ME#LMj!6M~m3K&SHb%O++cNSa;VVKpzl2)W&8+t+s!5sav4&UiYgvxbCkQ`$cf8eWND0}gWbSlA;qrzuKeKH-t z7ihQcg97Vz;-L1Ppxqz&bsC3VJ#S`#7;D|p6X;3S&O3+3tFGWc$?EJT3mN(kGtF2m z?er0@>57Q{1H1kC05aE(TKmv2)x*YWMR5WfW<*p0RelqT>{XV4P`*b5C0zR^FAV9! zZq8rRYRh@v&LzDOz3^lhuKU%~Go9wo1Cr7b)&(dp87ev{!V62U=RXoM6q$T{ zE@Q&~`(q6T$i88<|F2m~rP$jZlNhTS)>J$#5iXX8{f{ONwOFR1CcH(|a)Gx`IPdC! zRwDPQF~h62^icceEt2_3)+52kTZC^HZcZi?&HO&q29y{ai1>oH|p}cSW&HG(XwJIpRwnoT`wn_w3__Er{nr~l1`cZ;G$**) zf`_6cVx(4*KOUVcEgDd5jh*sLjfi&h#oOIFqC6Jiy5+w;6cMwq2TJ~ZLqUp6_gkLg z--8$SzVw)pbq!W32+h zV?;oDWOnBL>unq58;~M#pjz{&tsrloT{)dbUBoB`p-iBk{6^~fet-S_px1rbWtN38 zT|bm-gBmE5*+SLqzZ%(vu%| zh0jRY?_m}wWF+O;3f^Wf6DR4}F}K61ILw_o@8{(E5d3=#fnoSDvJpt#8;Cq%bX_>8 z5dgg}pI3LR$6Si{p`5!jm#qjB6+&@KxbTd@(=Gsyv|*Q9JGLI8Pzh0;11jx(T%S|= zs}09B37g2#}) zg?}D$lo?`CwKmu%|5e)HR3Y^eAZ4~xdhJnm9C@QoBDhoThQXh~C-~27rY?-a`^NC? zyT4Q@oN7l6qCaUO`D#^|SP08|$uqS_W^t7EVcQte=uwLZ)f%whHbIS~FV8E`p^Qds zoJk?%99Upo6`>~M0%2(ls2BJ90K1J%oNsJ$a9emNJNebRF}IWYm4g2g8G`O*1R~0; zVqg6_FAg0@H;P?_$6qQ|%azv#AX4rT9QW3Z`C0GHB zH#C%ZeL7(hEzi)j1eH6GUVDpw)Rm`9{^P)nK6{z*I>6iU92L1r?d9Aqsd^PE-(HBT zYpraVZ58H4ZhFuGH(Ay~?FL?iY|X_0WFy80uNWAMu17E?m<|rb5AvMbyzxYEC@Yj- zP_L#N;lzGBEQ)b${we(n9l4c<@AbN*A2MXh$`=dN??cn+>>iIxe$tn1M#k4a_v@+< z3ZJmFk0S5J-5NyJ+a7D;+Ogo{TUk(OVQP$(Lhz0BT~b^}9_^todJXpk5)F>BXp;@cpwC~h zzO_vDB5mT};aT^ikN8^?Ll(86@hE-{_F>4v!^%gf35Ii8GH-~1T{RO+)h*%b&19Fr z@a|9_GHW0jh{Qjha&>9>6rqq7WXvyHwYr8}>uzd%(4Z*|l2ClRBWMeHMVG zGVbQoXp_-99=e|^r)_Q~BEtp6-egA{|8oI6&S!%hbEO66i%CN4T6q|=Fe5#HdI<0P zz_l%qGpgL1O9b8fHUDtHr-Ru3?CQVyAw$P5yB)gthgUpIV2db^Kw;G=>5^$M=v$S` z+xz?hB)UDBUUYsk(|f3{27UQh!%WrpZOoR>rO@qBH}WkWAECm|8NCz5XvI= zv{39-a*%{SL&ZYL$F5^CEJx<;T)ENc8zn0N@_xS$9iWY=LSDTJyB6BudYcWv(Op<} zG0Y|76TO{Vw+mk`rST%zSY#1~`ueN{ol&9`jsP}pN|e=-WFTg}nRRe0fX&=SD_~aW zzZ8`8AN76i>?XT^PvNgoHO%(@>8;1xl3t%&hpp4|c{Fkv>pSZRG*dR8-gh#A3&0pC zozxWY)#g2ZP8Q_Yv8bKI*21{EwHb*hMcB6#52?IRYn=d`s3?RR(jw3Xfl$%b#a~n* zJ*U_A)@B7(@vx65BGi8qe*B#}Z;-Z9`y2Z+8O75j4Bb@fNn~vlTj(T)xyv?NSKd^I z2%u)By_=1vwG(*WGdbui0yfcWbjY)0epOmt3`bbf;8MUiVAa!%1-ZTuP8%L%c3Rln zg|_r}MT>I60yZUx@}ry>V{s>i)ll@iUlzK${7`^+t5=uX*c!fFrc$ZPb1t7_ADedX zKab1e_wYaR=T6OmeZ*(@gD{|vVO<+qyxlhqu*5H8NX9`geKqNz7JdT^78ENsM zu#hv{fj!#>DKJEjoV3FL{jgZ^k=vgm^+OHdaQDY6Bd!B7-o;($0HV&zKf5n6jM>)# zLBfs)@7d*(LSSHYbs2`w2}Q*6B$$7zH#BX?E9r5cwNRzflR;MQZ2vny8Uq5H5eK>B zZQqDCSu}|VAnL>ZId+elqJVJxrCJy}KVH`^WFE)MraN|39MhuEo zbz?uWL4~{Ky}{Y5-YCCp_@arsJl&(`a<;c;-oYK!s<BPg&gZ2Z+GsR|RnqLTsh(W(lUUqww(Q{6%OBCa1?$O%qVE1;Z9KS+D7gcCQCOP z$#0KU$xF*f6cO3}CC?Jznf7)N?p{P%80)m9nZR}SL3L8$IiRJJ-zQHVb>{|YMmeMs?vS&tFifV zg(y_zlbdnN3}4aT1_q?HBg#MW*W$6?VzDJVv{8o9>hB#pR|-6h{KLnq ztnfA{Vto&tST%;yz~p+9w%x<~aN;3E_g^(+$2>h?+AkDjsg(VT2&Mh_htwG^4MkjycVK#(RVzcA^@wv;zza3e};#Q42 zuIXiqBN6Pp^A$Q`0H?uNzpOQd1%LcLUi9&j62uq73-7`+Isk=UKR1@Dar2pxN?aWFi`-3Ep)k15}MlX&2Qwa@Jc)3|7>?UVpaHqPzqA$tzXeFusMom z=|Gfs_gmv+S~bgN8Xn#2(~|H4V^AFE#4mWnb!{f7j78EXsVK%i@+p9+q9tcD5|dQ8 z3^0R1;`$DLr685H-@9&lp3g&oxOr9Z!1 zGMXA`r21W*E=;WM;|z~n#K7bFDU3&2Pa5)=OioI_+0{@0K{NmZ7(q=hhranX!~Fv5 zlbNVi{0ujKVK((N(a|$6EOX-V=zDHxTlH$d_9GJH@(d%kPUju9Q_}8V4U*sbVSb|5 zc8A>AMvp5?wh!V;Q|vK(*ODZcQ71+Q~ax!w_c>y8Xy>8jk>(gB0t!?Jqn{~r_5mcg#cy2XA(b3dBb=pb8Y4= z;QpytbcLJ+kL6Hx)42J;YGR*(PS&28@n>Z!rL1pIr*GK zBo#t)w>+*i8IB-oWQ`5uQr_r?=JB=m4&BILU}&lI)|-=8QBmxns55^;*Wp; z5g-vvBfA&PtnQ~h@X(%p#M3X%zImO@*@>6AO^&dG!gUm_G)&ZTKYzNzF@S(kmnxtY z6|oE`_L=Dpy^E6Tjz})8$OEt z4Ww^QUy0#I3gr~^T8(G-1kf(~s^Xw49hyojlefTvgLfkl%@d!qGNW^mBZOlo-sqw5 zqOK(u)KH+I%h`DR*Yx%O+{xF17WAs5#9rA#$bQSOeStrlNcJxW5uWD4xHZxtiBg&X z0IPZc00n}AI%V7r$@vsFLT z1aeA#9-c}}Yn$$W?Gw?t2z)e6D@QKJTML{N=17PGJRK5@Np5V!nk!=>nC+Fya=pko zCnd3wz5z3psSHLGmTs&egB2uGq{~>CHhYS-XNu7!WVke<424ntaO`CigrJmT8GuU2 zeiz*2%>_7(q)721+&VO(O{~JES9CHAfx(jsM=iZ-f8lV&pTLWp3Hp;>u1o4GR z)LeeoZDkULrt|t0x|@Wdj|G|8Npl=SSGQTKkf?DauhA zGn*hMpN8UgK*>LWHU?r6If(*DP{c`Jk8XKzj%8KA^-u^ICSSR=A8KT{;|4f(!06~Ee*s@(j!Hb;p5N7wl+wBNtev%~c`Dcxt64VO>JlTKHz5mdy&8g>4!PDN@ z@ci9M5DL{-!$U=nFJA%!j#LQzmmqfswMF_naUij|rQq?Vfj^AYYsj^{U=0>9Py+K_ ziZ%#l--lw{HFs{j_;s&KE=|d*JPw6|4{rTfii#VE#587U0dX=+?*VUeHG2<+5Jt&S z57}1T9Y^#6mdJo5^Et}fFP7rk^lk;j3ivU4D=yDQEWyk&cG7)l_44J?T&GZNtKf4P zz>giaeR^`nD|_=dOqI`P!8AkaqQ|Kc;c?F`iKEP<$4bpsn|wQYb2lmzqK)bdB?D=( z16xk(bT12ixr?svln~Ia5#NKvgrlt6z@!gT-Xr}qiP>i{6H;ZcKl1#!uQuFnH+Zo` zMj|s-=^?i;2T52#Q%#jHM0&t=C(=#I9pGl=5kYCvQN1#gE{rveXR#o(t|qNiQ0Pebw`}3(OcFgbij2=v zVn+82D?Zdu;s7@200A2@6jf5Ps-iW8M&`DCDKFxs<52!`5=wfdH{7y>n>l4ox#SMI zj;oJXe(z2WAw@&O<_Di5eL>%+RzW`x6m%UnG~>nv2I@_2+`3s((Y4?$Ct1sA6iSX* zv#=-+&Yft&M$GPG$n;|U%ty4+kv@U#?2R$4@wXJ$d8t>Ul~}gM54Z|Q)6=rXg7)TI zG1W6!NZxd-X6VnV`r2*myd8FUzP!ZVwTNVF|mh z-GG!MPNR2OeWZh71K6G|ETq!QnuD8TV8VJ^w9y8)*+Ix1cQKaG?{NOyQk&GM(-vnOA!w}6@^d_#ZFXQJK%dLwnDN3Yc47BH zvy^U_euew787%C51~dT>lt$(D1T-;+inJSdV$EF%3S6}bdF7f#p52P9=QC3LXCOOM4IEXqbZq*}vm}QCu^(Zz zjBqkOSttaeToNZA42e5xxigEzJHme1bLX$xv|po{{P%&x8OnGIL3d>fR!GS8TPBY= zFHy6fwfXVJQ1j!MVzv3PCW9#;M0@>C|11${rnA>j<`C~)A7Oz_UJ^9^q)Y4gXjUWt@$o{KS`IUD@q0=VkM@xE|v14QN;- zz>lU@v1LFcF>IOXx=vAtC#QIA?EnPSfB*qF;TpAF21J@*3Z@YD#nd>L*}SL<)m1LR z6NL@Gr`st9#b6E7RWX8U+DC*_#xQ_nrjXR6c_NzLUW%{5&X!z0)je5tV*F5-gQ-On zmx>Z&T%!B=5vTZx{jM+%51_xx2nL&P90Kwww(kCg@6$9dgD2X-_U=^;nW;fc-l%Hp zR5PJ2T$dIEL#EcAnE%eTq^t_V__8i*q~{pdQ!^K^1YhA=+gcE{id1Fr0J;`1wAW-K zzMv(5^fBB3MrfF?BkjAtYSlXcOc34iX_Cdj&^4Nl-T!$e!CaaduA1ILYVe0Ghr^YV z+8Np@e|yqW|6>V%{IO&_9UZeyGwZ{2F6l-JYnDf z6}HkP1G-c0s&F)epG|BN(@Q6j0ZiLEps%CT*t=(XSPa3h$n`&d!BSxnPp}|T(30>Y z8tkw1qMw0h4d+#ATtUO!^m1NEU{`EE^V6XaAN zLhD+Or*dw8WC&oGOB^@{b|~;0rQ{O$_1+*gp&n^^`0r40HqGM-qhomL7gkBZamT=X z9gJQ3aCLNgb~`uS$Uk^CEhY9t^2eStQ0;oO@lC2itfp$`y6qOE=PPCidrNJ9nVa(P znc0WL$FD#~OB>?@=yYlf=4-SuCU)Ee4{T;!^=INxl_K?A!`e;1r84)lgw!lX@PH8L zF2j=2;PD_3#0R&oU_~hd5bZ-;jEoVfa(v&)&zyBxQ?=H{IQW*Vh6h`{>v}0x&V2!N z_2iERTv_09m^ICZ2w@&|@Qnkr@7)^{$-5ymEY{`z3`4bHa?xRnsLsJwl73~4EEv$h zPIXsib5~3OQfwanBFgw7tOq3-Oikkc{F8ofib8s9Dcv5+R9b>(KFA!$I0Mw2B8>Cv zhCPT@=e71=Q;Cpy*#7W+Kr!}Y%8SEr+;nsJxqK=C^^+BWnwWQ)iNwdw8BaTfqS;K| zB0p%PKk|xFE@?gVD2Y+)Pp9qTCS2E%#Rt`+7tBH-WVvIX`sJoe0>3%DItV+xPFYII zZrsa9@14x9DQsOw#{*9LdoJd(N#^K{ZoR7tiaO_Cf84tja_WVm6KSfHbqTZB@H78r z?o@EaHUBwRJ9U2USO5X9R%@$-OwIQ7~U8 zfQ12_6NYM{U5ff#>cx3tx5rr0_1;hG=*T`e;HmFMk7@i%M}Q)i?BLjCfB*r|fCNe@ zUVCMzS|jbj43y$zt6yzo>YOId3Y)_v>$A~gbGO1a*S+BwOsaa8f;Jf4{yQxOpQk(9 z==R=OR?pi7)J%?;+Mc~iA-cHmQsS@B<>4O$OkVcZBek`Ez(ks0sajNNgx1i*;CtP? z?C2EUzH<=r3iEC(xZ`a2p2p6@kKbNt=Q5Bv;_?=R+7Ls83Fg#K1J9VO47w`7 z{8^w@L}~(lxg@{H@L45#;INvp_@+pjfO=%&;3Wdg3>^X`iXVAvZn#b8|oaxGO${`TOvnkYd-EoTHZ zR}(~#6!_Dw8}z8(53^|+D4Pr^W6&?~&s=z-xOpEArA$(t_x&QyHSSRROO6 z?fM~^Fh0CJ`K`tVZxBuGq>RhFCx^pUTwGF5&)*>Kn3&2FoHYB?cRz?cWvOVHg@y>Q zkKA;E$Q;~s9War%2o`=_;@aFyb_489=a*@gQTCHL64&f?>DYVwL8UN7J`$$>kSR0L z+V{d$AQM`6t!OcJ`7+-A?IQ-*(4CFj`=@x!qx&l&jPcCR=@2BEEOc0o0bk2qvrgS^ zIRGY%0@s%c4d^W?6u%djE<4 z>Z8BA-tYjV5s5k)c=V!(X>C!SC(fy3ioa_dmu zWVaItk^%18O@9Q8c-$&miBZ4+H_z%o0OeEscUZhz#t;momEnI-VJ)yoaT2-mlor9M zqPO)N%^3B#%v4QN>W)4X{I&%a#b#o#bZP?~7zV6U#^OqL^N$*}xignTSO^h=qPT8ah-9e0HD(VHh|MFF_Gg63SoQov0TfvvdG&GV@5s zDxlU}?^?**%Xn}2nZWSj@0%7oeDAMxO2>B)zh%_MY7BN)no~WL6C6HpVWbe{0Ne=XgR!1*r8eR!TN2rY- zj8j5YhmyA1O??%aR$4H+WDbjNJzW<)^W=i*c{kf%<1mWFcW&hZCb!@K00dGbumtoy z?w_Pf?>}6=-TNR}K|F#eY*q8lyoIF7#OUFwYj^4z)eV3mSY={a5O%;AAGmdaH`N%1 z*_^Gh{SEO)Xk!0$-a`a0n8y!c{hIR4Qr1m4$L_}rCQegkSy?w$^(Tb!*1+uveExG< zD;X|!LckKau;Br5HA1pWZ^eA*tHp{YCJ(UNn9UbjF3RCp zEqx^1g;Gm#_ePC?Rvz+Rp`hq+W);>d1tVaZ4~g3FdxF3L(Rtl(j(>-dPim_^5I1xYoy%39#%@L8 zEtHMwlt;fAw#M#7>bO?>vWAFF8u%MRS{htl{&vz{SwTay;%IhT^9;&fa-d7e?<9Yx z^PxL(gM%R!_C-MeaO$J@^i%wT6sVBvTl3Y4JYBnAOMha z`ayQ|mHsGl;Y{O2gw}{C_SSa52%|Cw`W00CUxK^ZWws@{h2hN68gOyY4|CZMW9U?HfFQ~7tzVC_k%u%v2VWREWnoKWtwu~Bk-rUcd8^owE|DhM5_WZ~>4C+bv zbfO(?+~m$4XCs-Fe(B7*^l_XX;}ba4iB8Hz!*MO?tJ`JSEgE+`#`#P)ny&`vTmu%z zFcwZ-gwgX*h_aGCFaQ`>02~BCS@~42V|Z4@_SkjmTG>B-cEkhFC=WPK5x+GK!#_TS z#iZI0BL*qd+^clV3;+oLE5Xp{`KQKO(RW z{FNZI|C21owt!b#tjLJTF4p|L#$Rpd^@t!0&M?Uu$qYZ2jDl6nsU?u`!(n}+n%<0E z%d&r|KH-cBaw)R>97Hu174Yv=m{Y!dPLHy#6)|UXa&b=qa2(34P{(Bhd9q+n*90FK zokP79000XDKmY&@N!pu^jl2?xTapqi9IxD8TI5I}W14(KRL)A~!}>8e)sK3+ArAUO z&O)xf_5v}(`areaWWj%&#VFJ{d*+D9-2p$gdOU3{mbp;w<$#n3v>)`{$#z49kqsKO z{M};hUR9oP{HTg25&SDhro{x*)=&6igt5^19|4a>=6JD6s@Q=#HHiU*jHTuu`lTP+ zh=Emp^bfs+K~=t?E=2jBZ^WN78nkVT6&o$XKwV%8>!~hrCJ!FS`-bJwd%T_tjzWS8 z#X*F5B^A#KjM1oh;2;eRMA6gEMGNV{006T90C~?wdNovW5z4)*eSydCpf#2!ZzX*@ zx3O!abb!1<9ah44ZmG@s_z5eyeV?G_F11l<3vlI~m7xdAVxUqxAfVeW)x4CDA|{%i zF8RsICpOp8)xRUKGG`t(SbGIHt(%VZC=x{gqLy27nI(x@e?kR!1&1B%(zfFEHoTP< z`>+aM@Y#6sg()Q&{BN_Gh4vZZL-%{1;E_C(_JRuy4p4OIS0B+Ogler((U1jOTaFOX zeqSh~U=K{5(pk^47-ph}t#QL5k>J|h_I`y1Gqe8>Ct^Cqirl95n}E%A#+L(db)*?<55GN1ws0066-60}^Zy}m44{nki-wonNue#o|XIE%-IJ``M@ z^>}WWu2SYJKb`!v+3r@~xslZ9^qLYndkEwD?*u9c1UmHqT;gFbHZ>`UiG{FW1lcKZ{H2-DCbH6D2T~%PsI{KcX zCtORn7yfSs#-XQp&AI00096b(Ir%=K6#Kb$>Uu-E^Zme#FyEZDGReBI*aVZIi zXl5n&(TD$O^?Mh}sy>fPWr&Ub{$BD{Fx{RnZV?}XZ5a#uNo$H-b$_aF#YfrXG=mlF zgFUg1yji7!A+6XV-YDk=g&$v1fpyYN^y@(kZzvP?5p2$5DX{|QiFGAQi^R4_w$NrP z48w&gekktE?H&k#1wViQ06p1rjaDdhBI#gx%cIX1Qedn}f7BU5=)}OedK`EgsEj}L zkfOzsI*Mb`Otkl%<9n;aE?_1%bOS3(e;az!teWiV8=(d77j(X{J?O--ZE+52UTA>8 z-JaPe`~!n6P2W6)n(8LTJEys&>3YbFmSubV?TwYkWU&PXuf5YktH{?P&x1K)d0bY8 zDoq}^kS-csc*D}j$MCf%-%7Y|6(dWNxjkf(70BDUM57-IGVauzpY;OQqY*n{c^B<1 zp;U`o75avH_K4O^_UxR?!=Hv?;q8DkZ2$lR0F#BaSjTY>Ku%6EUu^~>2ZV4QS9-Lh zpO)N+)6t#qrs@;&O2ZB8@U{b`x!BYEYsQxg(_TJ(`0n+teq2&@$Z-wvi`_E+Hcw;2 z7)>r`KUyC&)oI^q?gkeS^3m==@=5?l-U<{Nz>{ICAmrlUjpu#$og}j{>n`%^8rYb1H*YQY|^>okZ1%O(h??HziVSZZR)Xr9VeMh&R zeI~PZBmlUa2}G=9o>-6yG1?Mr#3_4o`v|sRv*;8#BW)AY%I{T+!dkS&l21xk*#(%Li@-- zmSt?%5eBZ-T%YD z*k6ik6hP+?!>cz4e1j_53(-Ws*EDUvFwWkSf?SE1RWy&CQ6`8*^K@UmO!L?E+Ou+u zl};2NlQC(Zf%2)KyZ$%3-(Msr1F85>pX3uar;4274UX;KqEdv93YvwqiM!!Jlzh68 zfxaM{7AOJR02Pp&Uiibe>1fEHT}cLJ%T)Fv)9{d^K{4&>l}or20ssGjyi8+%_;6D) z;*iX~2A(}udj`DKca)c+iwYi+)NJK?Cz~OC&_i(Y-B@a|vo~-6o`3*X;9Y;j>s6}X z_XA!+b`CEE9-VmGRd-3_E=p`YI|k(yCJCBr{lE2kWZH*A>6pU2Z755)uXuQn8-z~& z-O&LJ3|t?bC)oI>bf5uN)SuNP?;#H3*BSbHgQ}sOE8cVRFaANB7}NQhd>fhtL;h>~ zvmiwiRYa(|hhXFXYl5OqwBt@%`MXx1-dUb7$NFrGA1&JS`xul^iC*sE`Lq@xoaLE$ znXa){lNRCty+8pEiItmPR#}?KfBOP7&lA+6yga5+n*wX+cP%TXSg8eqZ3Jdb@)J~y zmPk-Rk#lgp0vZGVtbVAN+D_e&&y>U92|M6CxYxDVT!(F!r4Bjm&g{udSnLBO&w^;d zMOv7F2>@i>rso+jLu%IfY6YNCIN5ev7QS2q=awMRv#{V>Jk{Lfz~76qAZY9T?zME7a7$W*0Q!|45c1$brdE)Y9w|mGYLVHTz_rFg1lUmlGo% z=*v|00a_!cXc^Q_(1!Im~sZlw&dvI_Bo1Z4Ug-w0|Iu)u9_pjV(7({Y9O|yWS83LJ=uPBVhk!E51 zW*w$T!c6IF;sTf*yG_P%gvv3FQ*xR_+^Floe2Cy`>IhI;u<6-wQmp2p9W~Q}VNk(G z-oX}W;$QqN^|qmWw>w4(^^d7=pi%tS?vANE%RkKAk0$j+6LZuhvUR?l+q1T=J^w$s z4|{CkvH%cn*x=?z8-hn+O5XP4nb>1oRjrhTYFwp&eXr7pJKHjwytm z{EvOG6Ip=-Lk96-s+gF?V}IURHD7+f)%r53{f(Jdp?m7hZJW~*q5s5#2YA$v!d(UU(ppE#%dx37W?ZZd8%>Ir zH6PO5!j6U%0|S@yL2w~Vzc+obTIi~|uJRZ2wrb3LB2929000930GBdOM!_=WDOLPY z0XE+ME7C(Gf)VA!m){<;8idE-R+3{!nQZN(ov+8=exAd*osZK}=1ZF9e0Z>(TcGGm z0}c|4yb+`=${lyir)o2F^S|H#IL@3LpMv2XVp8z=62|}m@|@Pe_ho}Az>k*!|36ZS9chXtn&pL(kMi!(Av<{sq7AJrpsR!b$j6TAH z(w7%k4+e76+I9_191TW{RQuD;FPBe)aPGIY6mmTPVI}jIgt4>S=3J!Xh?N@?jhOVP z)W7MP?X7z0@Bm*}x{@i~toU7*R0tBdM;2MWREvHiK*v7-sh6@$v4M+vHJkh=!41Vh4__b94m7 zn*x`tD+WiO1@{_nr1}yyRbB$EgxNBA5wG(HZ_(znPk2XfKVX&wcAp2|YCukHRHZRH zgeAaD`r1M13?WRC3XGdOlZ)dgO5Gy5kq}|s+(K`(9!)I-y;8gL;^OK0CcqJZ|3wMz zIEQ}Lqd?`%$@S9iZ3SLd#?t%^4AoB_qk-b7yr@Ypm*<6ry#S1{PI1*2c}Wc0x&w$X~7{l$T1s;=*_0k z#N+9lV&Wf^`A4+CRJ9l~JJQ%wqzBhTeskZi>_+2I_@%q>%ao@B0~l`UzzFffeYYTj%@BM0VF3`TDW=_gkY2PQb1&(fm>!b_*#({%2IK=H*Ba~t_L`plHN2jS>?Dp({T2_T3 zf$5T)sL6f%v`JhG9*WmRd{=PrSvM-@vOvVheevgobt*nm-*_EltO8Ou?3e^znqh|n z{1dc4UVs1qR3HF(MWz0eTR=^mA4t2+ADrHMnT;-I>N4jDbwt!p25j2b{g@H{l2gCs zlqTiF?Fb3X_77xl%*9qzu3=boPEM{(Ag{JfJt>QRUKeSZQY#{l)#FQ2SFbbR4y<>8 zp~d`|3HM>7PVpzbg{9juWIwSW_$w2}(gW%W@pEm~!t{RCtGj-F4>g73HUt%l!D^6* zd^Mo`@~5PCN&8w?xu$VGTWz3x`8sCoh)$0147A>-sL)n2byHu3SDl&( z-qYQ^N0K*Gt+gT-J67Y$ujXP4(D8jw5bfXkncyrA=@~z}8QlW~xbe8r`m3oK!bd+p z5U%}ln9rCY0bAAceQwh-izIVQZe-vmB{4u7u>o9mO_DrbK*>=fh{!z8p-or;4QNWQ zAHca}We`Q})?$Z`4ninmm9{viU+&XX2ebxpW2*`hPto7U$tIdeih8V;()eJ0Z{VL% z&}t4MGpcf5>tLnCrJtF+9x{2(k{kd8WLFcSECQ}_$=tKy6lE?Tx8xL0Y*sY;-{B3EY-l04y$2vnmi-gx(+j0iDy{<1FAjR6Zwqm z$i*qhvQG5wzp(y)2S{y(E}lsQy2gM z1b6^NHULVuFcXzWzI(fWN`Kl)Gp36D^eorg^?k4J0$|gaO|P|mU!kF(UP2M3E%YuZ z1HC<H^P zk&**|Mf;D}ae3!XU^T9UCn5{2-GWgh{AL_g#`dF;vB5fWU0{>iH%K zL5?ghU5q}Y;0TU|54w43@x+v^AeG^DCZQR*&So8Q@9>kPuT?OQ1|U;CGMALSr@q6@ zQ0VemkD9Q#w>cVOlLpbs$f=~S-!ymWkuLrM7U^x0D|kejd2Q#%9R0i-v zx~Fdtw-)WDjL2oIDL_P}1~qGdpxdtxs!&>Yi88A;>u15tfb5HDiet#(L?gA~@Xl4B z4Ia9{0CLCx1YFQ^mIKus;Z!Q9ps}^TAfOW>a(Rgb>pe$Lp>=ym{DM5+g*N@_=m!Hg zMI2p-{(3mDE3iK5apIr)eU^1R8FfzZzt~+5GRWQwsoN-N!2l1tY_&FGPy#3ffBdik zK{nT{br)bTtjTDkx~{&Lpo+zL2pd4KIw08ay6Wwn&-D;~NJ+=```wS>aL+-RbrP74 zzkQR35E#OYu<=fsj`iJ@8eOD7JAOVtgBSXO^0hCcUSYv$CM)i(&Jz}31zgwhnhf9R z>^Ks^5_V!!-qriz2K`0j&cOfDuJLt&gC zYhwW9G1F<1&R|;Z6bMSGXlW=PYad9?N`ORSpPo;0Mx+Cqq3Pw#x$r-L5aqYJX-1sa z^W3N$xD=io90Uc$$9A#?Sg9LcjUJ{qB#YyR<@M;GX2*KZVTDH4Z77HHLRz(hD)k$YT{iWHcOj!9J zJ7-N%7)%^ZOISbDmng9}wJu;{avRfaDP+&tGp@n@HnRt7a?fZFQh!ogp86Dv-@TOe zrYPI?yjAV%g`j*Gw^3)VeFJ_AWif{hY*IoWdSm@@?=kpX-r9dVmS}@yg(EK(v|SHK z{$aHK+Q`;vZpNWHRz8tx;gpKxGoXZkn_V28-h#wBT!~E33|z+-DgD+G%aaGOf+71W zbl3c`7;{8TEYI7l%s2;4wI0hUG)|Mi*d$oORoG{}^e`@!Dknc`ew8o8W4f5tMX zKrga|Q~&@OfB*rCtF@E%6`gaN>_<|+dYlIIZ|0E+d*+E*tqq4n8vM=CE|n1dk(v*{ zk)J_em?pGWoo#bAdOIS1)2f#c;3BPiBS7t+Q3cKNBSEgKM=xN|*nk}AuZj_e|7%8%b)9!%R5f(x}efAeq&p_%YKKCdTZc5cPxhxDAqWc}DCOi}4F&;Jw zmOkh%eSsld2mMB?tN@h+n^sUDj5xQlkAQPRz9eSU<2>i>vM{C-B6E~_eg)y;fIji4 zCkuxF)cRo72XoTw8anL0Mmqhf+9jwld)qs4(sm;=?x4p8Deo8aOv94iMuc&grJToL876 zBDuh-B*yrCq|&2#N2{BSc4nc3KY-9#s2+%IDsv-3ap1+ic4n}vE&%7QX0M{9z21zo zZ(@y0h?PW0sD`+=hRlk@8;l~_zq|G_J`U2iOhDwrpJtgYkNzpfsD>dXb1s(aC=}H< z?Z05anE;g<%7HveYf74W>C^1P)_J@if?SlfrCczW9W!32PN{jb0aVPi&B23zP#dCw5MDo# zGi1|sOqMrHR+36iK9=zpcj$3Q>@zG#g=0>HwlWLq4bSAE8v9s2000937u$z*`B{j9Q%s@jF~vAC zymK}#7*Xh56VX)8i~hBVZ5~0M|A_q2^eQjE>N)Olv$3$$*#C-w#8i{m>}mP75H@wh z&&s>W$`YgjRL&XrYTitu#(pt~^H!&?TN@IMdRspmv=U8pT)03XPC%E=D(U@_sR1NJ z@!8UI;!UVyWVv-euwol;-Qkybe#(G#9n3Zm@gJAIfWA5vY(VW8+Eb&`WWV%{-TZRa z>-07sq*64Mj8M`eE+`sV0wvGc#>|shZ^ToY!?B6A>}35(Rv&=_KShz z&<_JMs^2o)bF+BGb}TYsQo$xyFUKp@g!_(|Z@w&0cxug8KR#Z~znoKm0009300RI4 zvjRj;2Wp8{;}$W%4G9+`o-n(%WW1ltOH-Syc2J3PL(OU&BfN^b(nt+@hgP)*=-xfU zCHaD@;My&X)c3LA-X2q-6q;iO-lBO;3SHP1(+fg~rtR=M zMuP8aT2~uNk#<#^`IHoin>uHN0(#oapodml)r^Y+0R zEZB`5(?l7ImrZ#(mscZOThgFY#DD+*0{}eX`N|g#UI2$RdAi;q7Q42P_E6KX5rbtw zWcOa-xXpGCkqT%(iK!#E=bZ(w1EpH69(+PC6{tXgCP81mBXhxId*8tx67n;x?H9H* z8SHeXS#v*)v{OQ*wYuk(^kB2)M3HC8`q5XLR}qrsiW6w#HXr;HDHoZ6HADpKz-Qb) zuW|U>HqSpRQJ4S#0|H1{)*yL@lTz3f!ee@_pDeZcM}_qw^l;6??)yOO4wGIbc3;ws zYod~d!J%WH)Ek!8?{~}Ki>xh64$l3?g4Pg1LI4;HtiQeDrJRK$r1e;e4~JI)8FWju z>i2k|DeNN)M#B}sZARxXep1C;U>~mdr0ffrRf*{U00bnxFYp}pExnxyXYsP(<(g~q zs)Z|YjB*LmyT4R!3tOd$-YlNUT6yKXN0sv=kR|?NnPPze00uxong~sg{{R39BhY&b zJJx*jqUi{RhJYR@N=^Skl23c&2|1+&C&_R6*UaKb!^O&E@AZvrP)rlQ+FDyAnW*S- z2;kFGTJ3LF?RuG(02AejsgqL9JuxOtHD@syhr5q??~S%gISON7jDwhP2ko#A`uP7V z>Z7N_(Qiwi#q|{_ILhkZ&?)N>5kUusmvY7_mdo-;YW>a~=Me&?had%pN7o%7<&!`F zE#n1eL{m_@61fQ$#dT7joNHd|$j{2anH=o{Ah+}ogF@w2$h@Q5I7fKqet~Sk!(d)W zmM8y}%Q(ZLkpDX2UA$i%#=BNA7(GK};1-Q;!`}u$HyORikd(2Lt(BTYE77>JB(O@b z3(zcpd%YLF1&kfSo+ej;rz0Nyub3ip-XYk}M)Jl|q}VfbgN=N$2Z2EkE7#?ECR0hb zA?qC6(g{Yq8toQn-yg4rW7j6Y0&yA6?T0dX6F@xK@wg~p%Bhw}$|d2*W9DcqT?b`q zao;oN+jTqsGlFxL_G)02_oWS~B3+Db7dNQtse>y=$R6VpJ1q36v2@*POCP60El*Le zY653Lvp&=+=Bt&0ORH}!26}K?mPXLQn#2O=0l9xq4|R`niQy@2z*WNiEJWZsd2K_Lp!XG6e zZLCqdO_SfBjuXHWcj-E ztAR|^R*W8f9&oX&;bm0v-iu%Fu?8u+&DR&3pbPzq#D0L}*_ofUhSGUY_u6m}stL=1 zGX#mF;Arnzpj>Vmv+D}Up*r~kEGiqp2nv8JOWHcwqPWHp#1O!!TUC=z5kh;!>BJm3)YDAY!t1(z%7#@O@FKMWGvYwt8{hJ) z98*!(U|l7}kqTU)3Rq5og11?QLplF-C|RzQb4gb&-$!BDlJ=*d z&FB2o)~sH)JVqU7x8LdbgQIG}aod~{jp|Mqr9^e_^)}e~aY8brJQnK@=%c*q_m!Gh zjjPZmPhi|rCfe49Vf^+Kl&Trrzmva5z`$AkOF*(=2?2Rk zHfi=qpp20wwu&u#Q|D!BYYgx{Yp&T27QhF8nT8{HZ*qM9T#(;Xhv@N~W>PZ2Na`nyN;*60_a`-`+3u?)dn9>HIH{F&5u#8Isb-vfy1kbs=QqO%teUBO^SMpaaff;Dm88|2*Kl%H4)@*P}3CHCDFaK zJ-!Dj(;!ZrI9eHnY}pM6`W}vI|M?4ZS^q@ui||S3Z;G_aN07XL!{yU!DR66DjWIC; zY|6~I2!an8_kST6NZYx^8^s!SchCwS!IQ4MtiHOu3I~@1vj$n++pY&iXL0oee|0IH ztX280mSvjek6p5)fqqd+6%Ag65h-|5AuaM_L1rMLjVOP%e8$jXYSw zr?7bz@sTqOG1D|xR`}i3wq5kCGhxUvUkOjUQj>h!?Hr0)jhni_ycuOO&_u6* zY$x?GkW+p1V7X*YzLs;*uMi3$7K#mp>TEy&00EEzo)9l0zW@LO008nwe}n)XHJ&o; zm#jQl000930K1T!3m5rR09TI1OnP|??^JId!ovAYKFyhl$?Wq=!0U182Ic_zZL}&1!BuQbbIfJ>+V;4Jq=#rGt1fPhX=v&$3rZV=u^b zJQQu4H%mwj6vc@)f1^F4nYV@01w&V^v<7F-lZKygLUP-@9)eO%`mkr^>v@%}M${!S zLxB!)I>QzjKEO#n#d^?BxAyGi-(l~RQ;_a3a9z*nvUS)nZR{Y>!6TYrei;G)!y!nT zD$Xk82LMe#vcD_`5Ce=MW<|$pzzaD^0R`_c4_msX6B0Zh!3zxuNMWKI8m!jy_B~bE zsEXExY7#5so=q0pfINU&fDQB=003QUL7EWD@E~N$VgCRC1!Fr{H?4MAM;e%0o)orVVvo^VI4-;mxnV8?YZAd&His9zy+dIM z^Y?{`GIob!6}~lQ*+ZlCPLiy=Ee#V9v?wu+rjG@oS}O7<-jWbOwRVDRH~yHcNx23j zT6m(^RoNJl6^^Q+5g7_*vFAV`xzWeG$jmD;fyS@-dA}}m?r!P(h@++kr=<~0P;)GD zgOyD$!uslKG)OB;ebL}e`3;Ku@Fs!_gp7JmHgvC047xwEgk4}a6Lq_X6l!Np0vS$* zOJn6lukSj|lKv~8_n0RNEkic4-T<64ww)Y-&8Ir#`e< zHsx#_6x8Trd8fZ?&6nL*mTfu_2fgp%d!rp$9S#|m+l zXuXlqegbFU%auh{$z#3d$;x{gd=Uv2k`L%@2*^`R+3K6Yh^OULJZ7ip;swZ#s7NM9 zlq&(fn2V6Pj)epVW%}4z{CgQ}xvGn}$Ol%COB!6@iOE%(B#1Ix=|YGh+t1(xgd^w;##(?W1Wf{KJ zIaf_;E%c?6ePBaTQO-5&=7e^@xBP15)vl|bu1N~|{WpT=A_i18_@34ztEbYh$?Nb> zXN$PoK0oqzj--khtU%9$B^3sU`eQ}V58Tu!af0IBaZJFY~r5vhin<%Vi z-4s1Z519H*62NF+EEi4=kQ@>2_%CvIN{e9&BA7WQFya^$JC+0P(r7Zv5z>KKL`7)> z24AV^Swdda_E6*TpWe%$$l#)&5w0%mA`3|ex=uA>KMofbkq$Y!M0e7p2nyBJayLSgEX9uhX{zP#Yq)n9+6OhBzP*iJM zR<6DRv67Q4WaiBihAI#+sgZb^-~!PWYgmN zg*?Lu5Y&rH7z*8NK!^p4gNtY_Ut<@R6O;1)N6J#O0Zq_f3||h201fz4CHyi#QEcbk zv&D-SUIcA%E~MAEr!!K}a-=;%h;>G$lDephY~)J1GEMptRH6x01)Z^OuDn(#&O-xF zzNuf+6Uq1NXCG!zY{55QN+A4OU;D|+KVchChH{tbk1b<+fyb(2?DiYj?&pERNj(aP z7G&QUEk39%@jh|EVExI}Xtt(U3mZ09<6ew##^ObW(@rNcPX@^PJ=X{3n{;aXtl?iw z1Mn?=9m)}i8a~46U}fM$%p?SHK{r4N><8LNXI(!b0Hn6$)xmE_J9>gq>W93e!?u(^ z=^^7=-Pf`Gld|4a#TR_>NoLHc6RC7hJu}bHJJPE1%M=|8yWWX{7wN@;ZMy${!-S)<&ZfWtr{B3-clcOx!K`23bs!vp;2?BwT z!~mm*aykovKN~=$5vH@Ogu<#n&WSOaXt{3<0i-*O_1?C zVoqS`;!4ulsChCId?{kx_pqBE!vaPt*Eh3!KA0^M$r~Kk4F2KUmXCAEESO*v15RPAu+czdux?Ibo(yfEP+>?OPXB zC4~Y&wJLyS-pC&m?cU+G470cSe<*Z2Iwb&m_iALcaaiezP8?{a_@?;v!-_0Lm^?6Q zG>pF^p(8Sfp?w>N~SXHCgy72P15$PrPqpkKqh~?8RyO>WsfBO`;ZwtU6Q@+ z_o|uRu*OaVNdBd@O;|5-Gp%g9O>n@C;?Rd+2IsSs9%do!2U+3dQp}qJcOE6WNK@IO zdAz>y;$HcpUXb@q z2Ojwl4+sQ*$!BGoaqOffhS7*tWX+mHN0$JC3^N2wP{j2Wh)RN3N{ACzTaCpOQ>v>z zUuP8~gaNf*-_#||2ER%nTEg!Q!4`PlrJtigPZc)VNgDUo;SfB_DyHcs#s8|EnGgkJ zkOqz8#4hjdvzC}4&vzX8gwLSFkJoQm3+iJWf5la!=D&F#gfpXI(C7VRbiJzuS~Qmm z!haFaml`L!Z5JkwLy(BXC5Md&SRDg9-z(PQ0DPRnXT?qZU}5uY(PPo!Y90b{=_t%H z|A03!a|sZx2AL_SZ1o46OgthnLTf6y#?RYyl?n6>OZ^T*KmL{DBa-JyfD~r7KLdK6 z0)P1U?E@p=jD6@dGOLy**a8Q_CPl`m%Zl3YX)MDZ;F@hsPl^nzHZHWk>rg7YiWKN1 zX#e2P{LZ{L;nfJIht`ibVxpJX16+jHz7FRs+~le12xbJ734hd@xB=w^jcN1s?W8@( z&u=(QmZMySfg87bNNs4Q2P5+Ns38}^@UsiE-HCy+J+9Un4c`ww*|@6dYuY3TAr;J- zrc-my?&LWK0Ha_!zZZ2N3wx#l!)cMq=ZQh&%7jwi2Wa{+(a#|HDET)tb_ta)e0k1# zDSBYhUS%Uryl1+I_xC}_hkU#>>K$!C*UuOlr|xTJ1K2S+$q*_fuc(kIPe4sdeE4Q1 z8^cT0hXT#$j_zhlBUCYz&FbNI$c6jQjaGW!fjyr;+3r0K)_q|5FOw%c9y>_SBS#_V zi-KE*NvR8hamVv^nqs%_@d2UE9%8ptzZ&7x_M*2SZc6IfyAdKDIxcMCT|{b5E!7qX zVOurqc<>}|Kp9XEcV|j402yBlo$X- z%kP=3=N>EAvh1%pe2f>On}IKhpZF1afzW^@J9dO$e|9O&UgeDAn@}+FDv5odzpk!E1y!u`=$%q*rt}HtJh%ql_y7;4h+S*Cv*<6 zWrRFHzsb)AfN1UANc+w*J5GM7jSKlzaGa@Dx)RQU2_!X^6Pz`J;BJm+wTI%QLt^?=CYTuR_%tP z3@KId4#)M}GuJWyyU)g|kahpk!ma87Z#$$2-oJsCZ|k-=%k?eOD#ekozX{k}!l;n>|Nrhn7Lmoi&m!&E_DItZz+ zLDLH9Jfd!i&v;gP$@KLfCq!Gpvt&crNQyRF>xSe+xnC!~=h(gwC=tW@uX9JW2vgCr zEAtf(l14gVCcV*Cb$E)lyi=Sit@_XKut%RXu%cTvD~|qbX~x#>=N4glUL6ZN($z)RWCY zEA)su>tXB&iwRs%^^|R`-zOsr1})W|;#(aI15KucYEf>k-4lFg{$yh7vgAOH)XPD+ z%dH^Y_24v0C(|ZAS{^#MbNk4Ma5=SJrZlvATX1>77DhW?+U@G2DCf31k~VVw%}t4l zoM!K}U&pdvSCu?2kYYE^(?)1MSIA6|8dA|XIajHf%>|~`es@9Vq}nR8t^Ev50gPrG zSmI{gjN+i>syMpEW6k_;p7CBeFS6p@TTK)}6I%H2<<>>vCn(MoOGog0O~Ym>u<;_G zeNdcS*y0cL7u!BxsiJR1O!lzQg`y!)qLzvKcg+m&3!6G7$XDjBS)i}H$&NmK-!ilZ z`7De4u^WHXO?}1ibl>hQxhc}iqj(C1JBbg{O~g9p;YCYblp^sa3rrteg8coYO^W&B zg(ri<9X$%?PRE3*m;Ia3g5|Ev$ZYIMrpwVdu%k$fyB(|MjhNN>>&KK9Txx$227H?n z|EwHhU#ap%cVoceawW_L{iOAy#1PYp0<1mK_6&=RUlPwC=H^*RmwGY=yL~MJ6y7V{ z4jAT*s3X3zq*Kucvy&(DlT{0V(ayH&B6X{&OyL=kRfKl0X#S9dh-25bC}i*Ye|E(J zvugJCNo=>oRBw_nn9xvY(kFl4ZmHSCzSzhR9+VE6VRp)1mneSn&k9ZJ67#~md-U}k zkXFN0KuI{*b76=%ks0!0pz#o&l`d2V%EIC6nZtn=7;f$NjMp-n;hE+TEF@ok<<_%2yiFmfy z#0t!+^JZ!#Y=A#PL>Ps%wL3hi}WD9$jxYsdGf$?$l05t0T?~>+5maPnIRv5ul zLmc^ll!b`)+t;Wb$WD;JB4i*m4Y2tNZw?jLB=FeS@{i2`&gIoY_8UUjX14TYn{r$c|fd>9nQ3Kf@YF{QrM9E~jP;&6O&o!SeQqx8661tDu0Do_=it zU@?qg{|>S`8sc)ZnUOJJ9tYa1J97s{F@(~G71t6$vlgyaIYp+zIZgCYn+qT={%yHl zM#kHcGu37h{z;U?|BC=s7(f{D2J7o;E-8WSeb~^wb)>r_dRGjX5@+Y$Un0fZCY{R! z+_s3Wm<=h6c&9-q67;NDD8EMn&aYYkz-Vk(cwU#$Tf(vr+pqm3m+FfWEid%J)AZC! z+d~3rWkt~8w$EHh9O=R}l^dzgQO(0Au6v;@c*yC{h&IP7&wTbB zBjw)gLZ4(?dGM%5e9G<>&g~)RJX4a#b{DMI{__-drx4OQrln5I=Txm*N#vXe%Q*_K80i3%iXqj~zkz&r@pE|Pb+8EFR;v>OB4bT9QqqlH_S zVC3!Cncfg@F!V*C-Dc0CL(Uq*l_0RrX4Ka!1W<#-Ox;&!%1B!4O6gZ8|1f48(hWt5 z4kYss1s#=Z6;W_1yy2K}i!_iz?Tv&q#v@!>)(ZYm24i63PGELbO+oF zk1pUmrlBMUAxr;R;Q#^#tqtd>E0m56yeGaP)`DenkuRP977jw5mZ^Pg-8q~rH`;=w zF}O7Igjzx7J_5v0PJO&Rlm7MyR?DdMeX9lWo~cfwuP~2-VdiGWB5M?5q-V_uG5s&N zb#>_DnQOmhByOcK1LnAJ(uW}b_$mX=kCxW-0|<_C4V1<5pwY8%If({V2(n7Xj>Aa| zFe=N&O0|3BvHT=Bmh1dFqI?9@HOLe=4sn!}U6xIlgSY_#UE{uW62ee<1w2VU1 z@x4!h7J9O#^`^;RaWBP&#IwgRqd>Yc1csJISn=FkBRmA^T$V2Uo8+g_RVFk`Xyqtd zJ}T4?0kC1!@R*9}$o7O~%Wb980k%^v0}m`;27zL5GzDhsk8i`VhM-kY<@mYmSiy!J zdS6uXWzn@UmZKn8TYHk_3;qjCTV8Ntv-*MjZ@h?1H9L46pWiSLiz%Au*|V(9#7;V0t zMK6vPDk_hJdcLc~;$h6yny4>j@pE`aV5CJ%E$Kygh>{n{*guhyt#>GGixFwz@sOo=fdbQqQXn63u+C)9VBLMvFYh<(QY zW2Ed@|Jl{5Swx_Ru_JGgQQS}bj>N^w=6~J$d%vn)_5ol*8C-g%ASvQl*89mJO?ZI7 zpIc12(OdJ;QcP7jPN|W`0>124NJs>4zy{pD7S1id8v9&49NfnJ4S9H7(uP8^0d<~M z+1xVQK~d0@m?2^Y#y}%iLS+Phk_}Ds>$N`N{TtU%!0H#Zxv&cA?{^ACJ6QPkGE16f zW-DPTWxcH7j?%ZeR!;GhDxsk8tqJL>&uYzFvWg3-I?Z5E+Kg-SV9Sz+eD}wfRp+6S zzWLKTe@JKGPNaskOesRW-HB#Pv!f7F;l7sNoTJxn4RfS7(#>)8s4UY6SqMtPBA6DC z8mRM*{c*Vm>Xho84SMS9mbwZ;pw*F8nbHH7=$_uxSadB;fnSTH98}F*4(xl??tV%n zQRSTN>fCW8Nt`*fA%@#2u9s=`<#92?9?E#9MhzSK!Xow!Fzgb3x!44Q+=!G+dx;wu zF63E9o+cSFKh@GfLbx*9J|l`-7dYg&+@QcU3ut_~(GaK${u=6W5=yF{>ze$wE8m;yx8 zCl-v2`86*ci70#yw*;R#*Ym|FtGjF=B$zm!4O)Qux`Klw?!(lfGGllk8*&k6VTq$2 zLMT*TTaBqPoQ>l$J<(}Z!{mCpzN&Y|#UIR&)fTEDj&6SU7Fs$zDq7WquAtlznZ{!j zDR1OLLwos(cerS~;^N99pA_ULD)jC6D=MU@eX6*jOY7(w4I>v*L}$%^K7Ux*7Yr+@Q-Iq%@&5?u?@Unx7B;} zw=(^A*&*2HW`gfMy{L;x6&z9^GqkNNTHZ+Z6tn>{>56F%<5iegzu}o=ZbQ|16KN$g zN#Y21Ft9)G(Ycz&Z;~uhr?@xa2~nb;6PT*CF?)oc@nEBG zXccTp(P(xnPA@lWJu7u>uiyeZ=wO1@C&T)87YlhrGfASe_dd76yZrwVe_u|1otkGW zEBw-p>qt?p<`GxHTsq!_RH3!~wP{lPVmL?}Qg1{HV~gDfgd7jxcJIM0XNlOE6WslO zD7*{SB?rL7s?ojTSWkP6d0vutMeY2cpEf|r!woCq`oM6^MbS<*xWPVC!n0I%jiP)jbJaK>eqJ7{s&C`mM zMC{6b3(lK@eH)s-fD1J8Y5W1sj@4S!r+pW9$FzFWO3YPhFt(g$Kx4?Mq$PL2bSX{J zE`wx8_Fk*ur1V`p0HS`y6IviFWnN*bPQ$QxG3g2#iW-A3qOgE53_eQvMR5V48Vg%~ zS_2gWUO7A60B9UXeHt(ri%JppoqY8({zDcqV0<)uBui8xQ~>LK&Z{rHmejDcjL)x%Odh*sEvA zna$>WA0Gl&RZhfj>NFNeYIqR_aX9ir7GVM3J~FdhMI5hL>Jp&(oaCGF>G{V; z&o@MI`1#>Hw{-J%7V0%WdBnGSFJi$kSQwZR)G0K4Q|`{H8nVK$PCcre`bOx0fauZm zIs;FFj82?s?tp0i-zWO$-vhIOtAH9bWVoY2ai(x+=cx5fROxnfm@l4~71^If0EuC9 zxVV4PucXIL-olk#%vpPMKzRqH0Bh})tL9`nVv*3^Dds!s&Bo0Y8D&NHa=ZbKCwZqd zQNR`#KsHp1+5z&8Ct!aokrKcdC)9ZHvDw(c1NDv_e0QG&_IZ~6Q{M|Mk60Z2h(l7$ z0EV;q^S#5CwwPjQyZkw->pM8c%upcf{w{;~1g@;_+iI9Y=Zi)gQ}%C+-#jSAkW2~- zD_50P`2B^kR8eivV>|m3Hnoj02WJ|sL8M(4Vk9SI7U9rQgURZ^c|G}6#$mE895}v< zym5auZFEW(!$TQ756}>4?H)}QebpP0CuSYw7C~f7 zXuR>E%uOBzuBUGfbW(%MDgaRaLshei-pM}a6a#)y{Oh76+Yb0Eqq@<>m;3?KR#KJv z)&_MJm5yZQgtSYs+i?v(G&^FGNO_TZbkuk`L>9jTR2?|dP0pV?l|p+o&7M~kU*D#J z88b~Q9{9EEs=(zuLG!9`dn~f0@iL2`^BU6{m!$&@lFdpP?9YGLPxI}%IbP%%Bkb znz)cFJiWXj;g7o8%f7U71z9(Sotg*hI3;8;K;%bQ@nC1clYw|kulwPkNv3r_ zc49gIuIneO)@EqWqWCAu7Zr}Q(k6j_ozN%M&{$7FfF%tiDm-ed*hJ0HCcn=BEGTtmOZP=F{9E4bqf%@=O2TV~*9Ux}X7+JT^8QTCyw5PHt_9 z3=3?>Z#hwEUeez;B{s*t^N=Pj^>5yei6}Y%dll#Ui(nVKH5;hqsntVj)@KL0#oAg% zDO&u?P+x1J#f4z&gqT;s6bxyEJZ;`q`W+~zlSR2jiK`Hr@G|1cZ5&UOuWRC@v(KyB zKIKvzNnOi1bu|;-G-nXllE-q+>b@L*;=9NrxaQL3qy;H}ViKX*nYOJGipaBq3 zXRO#FDq;CWFX&B+Kq*VyJwQd=`r4!G0r~i+>w9{wMuB#kwPki3jFF1h#cI}0o%YZy z*wCJ-&T!Utrmas;#N;M8;+&54|JWJNrRg9;FD}XXeKwf>&#VHAU?t^EMjlu_O7@)T z@;|?K4xLt^?TzVJuY0MRvcMDuVS_=VC4%1jevG93!f6#X13_Dp#wBf*dO?=w5s?u) zzhjh+c-T*jHg6sknY!n<7hMkO{y~;fW1j^C=yZz{ivP5iT+(NLJ;aqEwE!19)ve^> znTC;{^;b$%bw3EoepRP;+)i^1)Hq1SCvxM+$UULeV@l=p-{*70f57yMGdM{-X7%_c z%B_X0uyy1_T9fT(I8wL{>+jS%lrN&Cd=_kP5m+K5qIu0A<|aOCdaJgUh<{v|i>#WJ zFBNA$Bi{scJ`jr89!hK%WpY)Ra|;QJQ79rTZ`<|DT-+K&rKPG_OeUUbI zvMUwHNTWVEtW25ZJZnQ3Dk#c_5b1%`9#=Wv$RdAONuH-2E|*W5=vvr_N4iZGoGCAd zH$`PAPp~lia=2IX2zynWzPk$+&PZO zyA5Z)M$1dO-(bb#%NOLk{tbVlb>@h^@Wxu0yBIa3f&9O3!xFWk&dap;=IP3@Dc|?a z9!Q;@tn!YLFnxD^7?3?Mym4ki-S*Kq*jU z4Tgn;jac!7qCG1Sn^YU)Z|g(fhH_^Wl(P+DDwfD+8xbM5o=@E=4JZ@0S76*03~sNdW$L`|y_Osne{gPkSKS=)+=+ z#A%5jWH4I-eRmOATfl_(baatD9;~yWMFHQ42zHwWacbLgy3T){tg{$?*`8bVfhfXxJ-4Tp4WfoEpQ#J8ZBQH0_R zq!8B)`J+05wAG&~DM>pc&y|exAJA&jSqRFS{#tv9Je$bu9BqBRR;z(T6E#zS?)P;F zdPx$g?eK*WPbm^6=7LAXT2pYk&*&(1juWXOO>YNZS51#^@%L9$2G8Z4$v$;6ab}pP z4$XfnBgX#le7@beA;QEfzOwtmhx!ga?|6AV4q zB>{GOf;09H=XS_7rhk0cQL%9KPfxp5w86EVItnSDX)rs49@JG(Z$~7!$3+?6^^7n% z$L*nTYGrt!bQ{vS^p$A2ETlzD8qyOh0B@8d-JKCZI6#UFe%H+*2F(DsW}1NRzEh%m zf^AyZmp}u?c{7AXiTDP>>Cy$E&sIgq8I#gY0C^wW%FC-b#LdeAMx+bMXW)*Q(!Mhu zfP~y`9<=^CNTZVH^J}o}*Sa~`vIk@@srFVQi%!o}npDrf)GsT@;Z3Hz=h_kV+-0Xj77DE{}Q$;(T-s zroDI_z(JXR;@Htm;K2Iu((2jH@1~=Q+~^z+a$OibFsc7p;);G8Is~lP{yZ+wyBA9l z>}6!&Z(}MpiD6o)XkC>Wsavdgbbw_4YOF^t1L?tu8fJF=kV4sqP#A*CBSZ(jtlJ%6 z4oxTUoWO)kqmv~<1b)=-c8>2N>XclWi;Yr_hQtb{h1iomk}4m4Z82l%?qzMkCo0nW zi&fK=#Y#whvq!C}axlhSjTSjAS^ofR9hp@9hCmsCG5wMf&Ka zK4HM${mxVx_~2SVocGZ#ONuw6Rc}VQ!Vo`V%WfNc+WN7Z}n3`mpnL7gDU(d zrxJey30dhIz4`NZ9_&1wtc+aO%7gxe4zmbUOV-$T<6E~@|7y#L5>_R28zZ2tW1D4Y zH0D|Ui{iFTnKhfs@2>;qK%gZF*h*9{_1_6{xQvhs$?AH;Gi$7LmO&o{@Y%35{L;Hm zN+M1c=R!@Y#Hk@09AqmDh3aDM9FEZ}f{!VsP;0MyXM?$Jw)|}Z<<|RRRyjFhmjLdc z+-)|0YhR8NFwYy{M}|ZXDss~#TaG#Lkxy+%tyJe_{?fNIzAl1u?~>PKdDY276gz!a z?lraB%ZDbwHxeKsfe->v{kb2L__E2Wh&3ekfo#m1E{gG_Dq69?!Hy4teR{_evx3vN zmxXkCyIr|up=4wY1_&XT!al>)S-VJW#dI-h7N~>4lN{zH>wAP(7pGhc+k#Oj6?wfR zfrtETrOb|ItyfF-u__2j1AbIk?I*8LaitrSnqQ5JU- zjO;p4kwB*X5SD^TRw?b`Si5n4BV6j ziCd*FX6hN_=ArSgDYC~;1IZ3qYc?%soIbj5)d~_GDOddLtJgDRVz^)r^@PY?Cx*`o zJ0eD-L(&~;@c#4^=LQ56;JO6D1n1Q!3qwL)U?ro_9Q*UB8T~{0JGe6@8<;bx?$b>5 z93eS2Wa0_BC3(!~0OfDnQkVx%lcd*iT<*b>s8F)NP}GX?^v?{}UtBdbr5VtjU>%Qa z$dV~82hPcZb!A?g#1pMD;erMR2dmQt@h}!DPE@XT6htCF+<@eRfaED0F%YcA$kul^wbPJdPe%RVu)@M_{lom7xA zk4{qS=RaCy9y1`Vs7lG2*{f5&xrrbL49rfsQB(3Xk%=Jf4#y%%2*rTUpxd4S2- zf3(UhSJ5B1d|UiasHAaN*|&NIQy>64DL6kiv%UL*>3nqu2KbA@ZsS9{KshHa#KS*z z!!FY5oa25o9b`~pFx|Z{pAb4w49S&+ePV>r3iiZA&dCu%x72#9_17I|ob%!AeBjgF zuhx3~LGW|ir4)a_9{3fBeJJ7wtRv+^&#YOz#4<7)zO3=)l4dKBmEJle|NCP9x=9jxo>I;wlHX|<0K7w6yYWiqMG>UJ| zq?ev$I5CYAN{R7NZkz#-x|hC$$``@c^6lmZ>_A1b6g1_(7@~a43XSt_oT8Y|c6&OX zcX7aTN|ps<9lS>2O7X$vPEI=d1Xt&i?IpqO0@L*d@ghxFf`T^y(_bz=ieZN$ic1zd z?^_kb857=PBU%f1;oN+c6to{EPO2H*s*tAv+Jf6S1FnV@o-ofepJ24Jt?zw*wIcms zq6rX{I4|rYUht5ZWOaf|jVbUS(OOkdiHMqHL_P%YNEb2%ddSI9{3{un;7i`MQp}lU^rtDHD^?lx&n5MN- zcYG8uQQm^eVJq-^ml!KZ892&O?Yd_(Zr3HYgc;qvQL7A>yj~Qr9jiii^o)3A)+cQ* zMuMZEniI0tPH>(K$zdBxkC+cz7CY>)#Qpzb@FWrGl|mEbx8m2^Jqlokxik-+)pB(x z43aAj+b^yL<(y973~!-gC=6D)mI+ z%ofmvJaBm5gq0UD-ck`JHoeFVNU{bUVft$+1&ii99SiWy4Ct=dSlz&c$@VzA(t@jb zAPSE}>~Z5kz!nbL#d4C>LJ$GN^^r2TJ+jE$5GY)_|1r#ZVb0|`m~4}93P-SoceS13 znmRlN$tmd$uNB-(o}}DofDGG);6P#bqbS3LeYjVC)yM^?%3r`L3c5a&*%}4p5Owf~ z1${aml|`e!QbHu{vrrYACT~=}cBV-2|Ef*uebSYKu9ehoB8Gki5uHwa(Y#YOFS3j} z9=ejkis|9mTsvMZ-C~D-ZXU?O?I*B9q2+ru2b$b_I)^uS}@mB(y;|BPJU!>&hs$$8^WDC*`B5&9+kvwA%}*#Qhyo$`@i?8M~Ap- z!R(8N-OhlrjFuqxu3fPa(_bjtiQa$;vDcxlh-bS&kx;XCHi?m?Si(I(I_G0b!mDyl zbLAeEZx*6A3^3q5S&F&G#eS_f)rHI3J5b&8_%R)Iv|mZXdO*T2>@~~^1%Ll?Bw`$w zR`6#2DDh{&!e+$d?=Zg3$nU~&)^!7eTG@3QL{RP^j+vr6T+b59y1U%Vi?sPDL<(NN zU-qPD6WoC@AOu6iq3kzU>`bN~1U{;Z#(tyoZ(%*a*K@$n$b7;AG)gdyf5(BoLO%Og z(!=_$Ij72guRs7!#9r7u^O;UzwtN2>1`?QRsSM!L?$wrvt9%9e$ZtzTM*C51L-N22 zw#vN&ufmZd4lJQpa#WxVPCpCF2*_f$p7Hd92-i4hp(!W2icv@ zZ4YPTzL8LUw`>7<*y09o0z@8Oo+I4>F*B}nES}v@A;=t6Hl@?%ukruw1vhi)Fvaqa zo++)H6M9JNkg(cIiO$-{tspq$f?>2sX_%CQW{B8wL%pFj7|VTBm4$KI9W6I-pOvb- zYlujYK|idNb=mSWAHrUsr?86tgT-@wLr%&iei|zgb=V5|E3fA{M}D>i0t153AG4N( zm06m8%3?!41<}v^R5xuKwgX1c&NaKFg)%5&u2l?xu;I^wY{FBXD1L8hX5OhdExM*C zMSGLKRb2W~9Dg(BB^tsTZMw!Hw>n+K9uI&pAP?-FtjtqLyPp@jL{FwNlRq+t!P%*i zFsno~Bu(T~%|MmIX+1-ZJs?Xs-=2enrCA@<+}X}$+{3;rrQNR1BuREu=YCwKPO$Wx zv*_+D(2rKYXt2x+#1ucCz-ZgnHD+J(K$HtYoFXNWWUqelQfLqajU~@l!3ZGYKwCC7 z6}U^_p41zo3WOor;jYB>vA-C{4)HnniRzC|N4W4uQsvEj|iMMZ=(n<;4U?$ZC4*g?iUzZE=G z8gKsZL#y7Y=p1scG5C-ZY?}K!nLoPm{B-Kg?o2uQkw*uV>Z_WLJ|$~?9y=IME>)I? zkiDe&9fKM}!bXCM#>(!Fkvgya&%vVDau##eig(cNIpN(4wJhvN}c)qkAQR zyobvmL-rDuqrt)@ruNmR@qm$I@2ANa)hy5bnQC~?ZQ?qK<0ZJ5e3hlegCR@@M`H}Z zDTbIen?3{$R=Af-4?U{fy1GQi&^i8s4kBMsOB3>qtZ@=UBA;lXD_t!tw>sHXB;jBl zYbL`md-OX64L!liGtGo06=_(;IAIWjY)M_1!YJ5&in=3JLDufjaL%=dOg#lnvj4rb zCflu_ur8)LDth>}tuFUhc#Q=N0Om1MStmO64y~rASbsAgY(?BX4>T(({LoiFQNugT z6FOYU1c05BMjyBM17RC?VF>iT)+eHf>vW!S(p=>hgD;p z6U|!*o#4C-8!PBIy)wf}BtG5f)Z2eW#zW1>%#yo?ui6rqw5gQ$xZ|x#A^d@V$PDvm zFZqX#I{1`=(ZeOVY4k-XNq@apEU?YZa-SXF#HN!*K<53`5|Hj3u1*@|0!yqdHx6=N z`q1U2nc4b;e-*<<&4R$=5hFhC^;Ka`&n;F21^uL%Ya(pkFc`n>Zwj5)S0lpKY)b$$ zG&}xo(LG{Vwj0;>wAFQiGr$hA*8l)dZ`P0Y--KC)T10brt*$M(b(8}mupg0e2L=LW z?09uE+&6fgIdr6?30?01$d4rc)^W-ggyn4W!CN}M_V6L+tPfnL*FuVHUzs6KG|NVD~=DO;YAi@fyu$w^Fqs+z~h&txnqoPZ?*3Yu#x}W zLbCSxZeXw~8hu{69T0ce9iGLN0ay8jhZ~5+T;=bC&3oS8c0wC-BZ~ zhrWo6Hl!Lu$Cg56Q?}M-_Qli4G%61&xj2`^NL<#P8awT6it;nfNTAZ+j3(Hbj96O+ zKwfvJcice&XkA?GQ&pnMpN_k*sF6p^f}RNC9cODrh?j6x(Q55}-L@Z+4Nq#-K_6%} z^uGE5>TMa(d}X*EbLW%GR8gi`iO74At&3BYZLLvkWVy&ZUuH?XCDtd`PU$UvQs}aq z2#j&b;V%l@|Ff@j-6PlC@R3)=TWsiiEWd`9laESCMFYxme#b@<&<6~Lr+(O~{FqB3 z$I)H)>|2>iag&V%EU+_G@qL7p+Cql?)e$aJiPhEBZG;uj)SSjO5ss;b(TO&=yLGBv z(0@Zlkkb%OV%K}SYWUjF#UPNHDdK-n@JT8;PzB!Bf=dEz=5JMZZw7Z4|8?A>e*yYw z3-xm4I40rnz8uHBlo??=8)T7lX0$1aY)D1vB&kne%7rxKdB*{~I%d6|zL^Ln=>%ka zba9osq9WJLpZrA+IYoYt@1A*7*Kq7Te&VL?VQ!zMC^B5s89CJ*=bm=N^HU#1g_W#BqSwRwkYuG{V>hK9LhvqBRY(rHB)nn-XcJ#r# zMR72mi*}UEVX|zlf6EL#A+ zGdNPQ1XjtadY(WSVK+8LD)&V=3ntdmInsLWs|vh@!D_2H#C1!MVEPp3BC!tIdP^#b za=z;OmYGNqUw0EuV63Na0et~#Jm}K_apU{Ms$M70zv$mdn|z$!v@d(8j-tlNVoTi1RP0KWEUkpHJ1y zOCMN8Saytw`Es4|>>Nsf@s#&yjsGB6Hlg4Ptz3%xA~Fj_rOIEY`p$>L@YX>V6O$DU zhoHX=@-_{k;YNbd1rq1A)F#f4yFPWvg)H~L|PqqW% z4uP7h&<h6hAk5-P4_KU=KSi1bXVoEPh66--QUrV0 zpCIk{(iiRD6z)2_*ALXj$42+;*9l0sHTA1AeLGO}PC-qQ-V+ju&ZMl)41K@JS}VwU zo@yr0^n~c?{cTl1OHmqICiE22Y^6Ts^G8tLt^F!n+Jy;Ksu?x#ZSpAmX>tG`BL*CU zWcGl{a4c(t(Y0%6Re|>hoR%0+uOl`K=l)3our@fb)sbh=_pj7bTMArA3MDuOWU zC-sV{p}@HybzgAhTot1J=tn|07#3~5MQTK(WH$!MKc^KvU0wveBW30QcOH#fYZ5-! zjBJ-BR=dHlhw+JrDP)A+CQ4OMbt<3$lJ)lee$wbG=!W6<14gG-wF5b7Fzcg(k|c1g z^W>7z5Vv`;N|J)1PY1n}U{(bTRzXWVgbwzZptGlAKc-ucxa5|1VRt{b_SDC%$Dk<@*>EVgQPUI;JI0N>KyVa3M z%^_o{$Cl2m#qJrOudiKte6k574IA~Q%f=$7sS<=-nabZlYYSYR#5}x*@0%Q!Zw%}0 zW9D@=#QuCluV=ac@s6>2fUsi=Eb>5hB6oaFmbm;o`xtJ+*PZi2h|BVbm5-z;dfQ8gZ5j|2mAfAOB(~=j!mIYNMrPE#MKdoENj=;to**51` zVNouA;K_m9;+Y9FC#+hs`v-#J331o~n%iWI)fu2sD86_^N1jr;)wsT?9_EOqPl=G0ry79mEL9x6#h2_&~A`YMPsU2er7b zR2F7k{KKTn#*bDdD~2Yve&c4GWosi^6_QDIyOK6l$b9yZp+N)seS7e6eGn5k;j}2} zV|w84t!Uy7|G4OK$N?^m8whl(X%E6iJ#dHi?H+QZ);0p6*;Afey<>PKQP-`#cWm3X zZQEwYwv&!`k`6nz?R3lzI<{@wNhclS%k#d^cdm1t|MjEhShcF|HEWGEEVjN4mgHVv zG&Vq-i{#H0eCGb^l{sSi-ecm~Es$=kYHLPRNu_AV)PGQLLS4I4d@eRR+B%d! zFU5eehS3cju?S!Jwx}{bo&Pyxe1j-B*{}@4dVPX8H)uYtTq4ooTiN1OqC}Kj?;4mo*uQ9c2wJ zo2_;oRwEji)?p23nRKHd&m-1s;6h`INKbBMx96GTx(L_En9bXm7k@-PM;jjfK4*tt zcUEqY!V`v@C#Hb1F1zE_#5_a9{BFhR|G4sv2Sd8FU*xAb%kyZ7w~mm9UDxBq$5nlX z@6HX<00JMm1#A^o;6WZDa`=V&s8t&!xv?B6iMs99ry=(5(yzr;Eyp!j{ij>(rA-KP9>G;74nas4k<3VHB zde6QuxTO;UYptZH!BMV+Qr9$arY^jQ>fY@Z5)V7x-VLmX)oZc5k)Ja>&e(1ZATx$tDyM zXY-jE?{<>>VvpNXgqgQfh)Bz#5e@er<}+ADrLjXYokwEpguF4cWq=KeE2n~o7H(#- zOEX|JZO9JggyGB5&H%?4QQe{ka!>%4zxHrU7>+PuM*~w>0kuZtRpz0eiHL`Fp{~$f zX!{d05sunu8;L}eicMkrT49wR-C&=}2qB6%C#ld{9P{<1(#ZWmKGlP+c&^Ri5c0bI z7UQHONUs>BLsL59s{cGHb?=w3Nm-+apv#MUT9IEa z`_#v2eFu1)K_hYrwgB4FS|K&8k%Mu9`fr^-C3n zFg_~2b5#YYVt+;EmgyS8a$@d=aOLooV0IGkZ)}xQ?bBbSH>lOsjcyM;JDC{LjM5xI z)3M!)-NB!rk$6Y`?`(eG|79&U(J#fsJZdK5uw*Bp1uHuQBEf;brWv8;cyWWeo`)G$#3+zn;1Im18Z8#ZBRe=k(*0I{V_J z2(HBz(VKX!XsvYtY`Y(}$&SZT=@jnzDiY;RhDv_BoMURP05oa;YST^Z>J^)5HP9`e z;m{d)U74t8XX;Z1#QSUfAfH7yqScAb_0^{liFAiq{|WKos89Fd(1#c^ctliHRj<74 z_0Jhc_ge?wT^&6S&@J!5v(H32RD54#(b=uN!=46h*?xM{l%Lu%0s>1PK){Pq^|JqS zxtKhWJR`Nh_IP@#@!J&nGEF&KDtw$5HMD`Znl?~(sreko=Q&xs@}eR&Q1!7hWEKFf z1=0KGFG239mizdGOU9GIq3nb)XVtkYAS-uO4RKL9k2&aqukc@GnX9SDZyMHtf8@T( z2^fko;72y(AQ^4>Zo0cbc28Aq>#%;VB%WQw&X_lOD#4#ycZLP%ib5~FK z*S!&iF%|}@Em=^HuAcUY<~4_!2qRGGhr01g;Y%#6mU3KFG>Ba*9%E{^IW(4dB}Fl! zPOD-3k}#W(`U(#LNueMP6#q8Ciax!Jp@Y_~;{?Y{1AcIZ+mnx^d%_e=e;^KZe|Lti#|VZs())Ga$JU0}1Rd34&ej_nLOUi6h9kd8@@Ohi#^} zyazU=o_`K=@5)%%#8*oT{*fym+hfCmGB$Nnq+!kYZa!`t#0MO&fgadv*=vLM9due1 zdxJ{9{Fk*iHn&o*KGXB4s2iPZ?jTV}zl4*<&+5FK;|3w+88$*lv35!B3b&neM5Pa8 zH$T}&FYC?lSyJ=C&9uqZjFtG1%Ze~juc%#Z{h|CaO9)ka69^Ql6fFo|3(#D#yHDTQ z?yCr3^XfCXn|CZokkgHU-{0?+n^@*OgMe4&7^zMwiCvh`fDZq7HjdqDzq@EL?Ogxm zRcr)L`#?ENK%+Di6sNCKgnVO|VZNDqSBY3Z#l|Preh!tb-YQ_|nhe%Z1SXQnvE4%{ zrJ?if%ti8+=wBk+R7iVvaz|Wu?t>aOU)wA$mWL=+Z&@SgSUct?10hLEizoeT3x61v zS$dKyALsS#JftG6>kio~|NAB8{vWco#R3f9B(6S5G8!}ueG)2n z=RnGM?>60pJSw-(1l~*B+NhGBBk&BdNyUu0T9t84C=H}Z)n*YU!k{~SiSVC6jZnoc zkh&`1pT-{KS{WVdC+lhypDf2jmj;CngEv6lkyLo9t0R@ws)34KCM$+5iB?nFT{lEn z#ixOxfdaPJtvq9M(`=HT#!s_Ivb0Fc*JV!DkSpVh@$`P=mAfPQ010-oVop;?_G)7w ze1P>lU$qCwehBR&Bb_gE)JJg=X}V5Vig&`duL(N#&08Yb8Tx}T8>W4FEUW`=b9VJ9 zvMNnA-4||UUJMpthDU}IZ|JqRB5f;q$Auw|ZA9Qm-py^QU2M|8u?`1}TW)yzSRLuo zC_O;+`~sG(zr5|wL&*COcn7;j$jvk_J#1dasAEm*u$r}^Ata;8Hu9PJVz(KQz%`Vv zqPANcOU8i_V)_pQxvXF6JH~jItaX@+NL{!8%(8;}Hu>*JSu_6rGl}q325A8Nqf|`{ z<6VC$3teM0b%g@5(c4*Ut-_uOzf2zkrJU2v~E5dY54mVYUREQ}z2KoemooXciL z)U7twa*{o6h@Ja)AqWQd8`Ux0#t>C5=4l)8@qx(|Qx7I<3jdN(^m38u5mInSCSAt@ zrEqagQD#9*qeJm_|F_2ZH$=wygImXx6V<4Tqq;0J3ywts1ZMX(3!?a%V1Xu>65>pg zJzsqI*RO~U?EA|54}zkOdYx~DF-7 z;fN;Qp&7Sz1Fc=s5Aq<}*4{k4NLb11e8 zXkXkTT{K;U%)SukU>XVSGQq4XQdpnC{kBC$4NnV-)^<^h$w$ns7`Wc>Ur~IeJ5h{O zaD+F{h^K^F%^t$$?J$Eh6MK#K>b5K$AH4YwZc@td1nR{yq5eB>YUe&1JEaVyZ!Z}f zYT63Yv+2~iBursAp{8Iq`euW|zxnyl#sA2+U5A0EZ*W`FbJ+foX7#a)Q$?n{+jeMo z|L99oX6AVVR5o>x=?&$yMaqFff>-daZ3u*Co( zwo_QDe>oLnn&|G6h7g%hguAJTe*AyYEG7}%=y%`&KD$)d4)r1K6Zs^}KK>mW-h@ixnKXrvq1W{4g;g1h*GNp& z#VQ-zCsPm$xsLT;Z>kqry;V-(Cp<18l&Po6CyHB?z3R~_&et{`(i78qtrB2kyOUB$3G98 zZj0Y`*&>sdTFt-*qi|2J1#zt(hqa@`9GJFSxoCbYL!GSo?eH{hzs8Tfk|^Q%TI!<| zkKmKzfi+T6Dom}!mxVu+sXRJ8dIPe2bKEYKK0~Neqes$VlQlYafeBSrq-u_xW1oNR z8f5W4E4BTK&ycmC%ZpxBvTQ2vct_+fZ0q{|9?si(w&WLzYKkP(vX09}_$`vH%VlpD zeep?Ny-ob!!@h6mYn|EhU{NH_uV7YzB$XAj<$r0Kqy=pg3jyJHpp(lx#2JA7V0oK` z1U{!P4SC~oUjxpqE`%eIt{Ecj7`++em7+9ysS>)O_0?>t`;TJB@zG@3kc(38L?1n= zV`bKd$NgQa;d~Zlb)PA>t!4g1isWD<3lJ8=#8J?Fz&0kq7Y@O5EPyGMv2iPEt#JaB}1%gLGf61`1$eK3G z0TijCZ7YKCyU_7RJzH%)q&4r%_dD_$tBiZToE~SfgsdnQR;61*UuP^BVZcEv3UrHU zl~^LG&i@2ZBT)Hpp^)J0R%RG)k?3m_&GS#@a;zlSNp;Y?-~S2o`lX##q14l%`vOkE z%Ks^<#BIRoe3%e}@c0TPM`;7u=~yY*`c7$|x~|!B^8y%}`Owk8qRVB^iZ_4H!urhY z&GFqdw%4Gai|M>b92rGwzVr{nfFCO3ED`5s&1J?)xWKf%KxWAC!|$|*qJD2xIa!7H zMQ;hkia!_68~iZ&gE3X?t6x@~-l~DgdE(TH1}`JpB@z?-PN(BAavrdTs6QYydsSK-LxH``r~ddgpf@DnX9-LlU5QchmmeIXwL)*6&+{uuA$vv;=&(>^Hw5w`6j)HOm`D;m$=Rgs{dGQ86V?<_E98#A=*eCrra>|NLAHbhs=|Y zi)c=<62xLcZ*+jumuL@ocEXE<_QN%H(Hx#8g0kE6i~DACML* z7>|N2wT^+q?@{;Dv{HBf47^V9kY1*qY{7(hQki2(g7SaZABOa^qY(0Cr~|jF&UA*S zj$J@Ik$r?wpk)H9${elgDzQe?l>B8jM50=m-o@ehH;;)$A?#OXy-C^Hd_YQ?K1Yf|Hll8!2p9ma+1@64I`b{i}jeQf)=9H#|AN_(Y>!gD>vwc(~2pm^)1 z?H?`ZmC8X~k8Q*x+0G|+3w-q!Y7$|`BTL2UmF_=o@4A|5KO+V3gpH6BTr(g5W=luX#UAG^dbwbKm`oI?DO2gT zY8dfp9BvFKr$)nY(MJfuyPa{*M!I%Y$mckf{-Uf;s_B7}8F)JjMgru>RQ-;`AR4)z z2fv&2Gk#oR4Ar)r({R!>$oX>fUZyfZR~fxU)7s5V5;H~NBF$0^j#_QE+mI$kNTj#v z=TDCwPrYCCz_u%`#Es&j@D z$y-zTEjr2geE@ptcT8*=Xu4w{8*8i#y02aA7%%vn$f z$F+6zu;MVK_xJo6ZkHr(8F=WjVt9+t`~?QnrWc#2p)`fJpLiwHYJSZjziqY|W0e~I z7#FZOtBDIPGr#ACJ{-}reKrvDLyzB&ch$~F0fnxQlz^akOXq6%h6CaN78QLi81e~0!qfO@`HhnM^$9onh>#V z2(!zy0vPS2OLXuew>Aa&ihKU4M9W_5m$e%at5tJkFG>W~j)PoQo9S4nlT>6OM@Wxe zKE!+V6fO!`o}9sor`n});+vy(l<&RBEP`EhO$o%97tfpcp4vDCPdW$7o1r_7dx$hY zLj`UOl_(EGkw)H3m@KYrShIeDZR$)Pip9Xb*~x*O==*KNt#P9ID6Dl1P23l~^4R#E zbaF$CP@JqZoRH38Hokq67W?K0&IYnDy__C(lC+!?^~5b|u&jfHi4#n1rkO)~`~?0c z(^O1loAa;yRC4;%L=0}?Z@Voa%E45DL{$7|)&7BCm) zoW~bbubH(xAHqx&k>Kmn(}-$9XP4$$kAKc#9Pecge2u!J7ttW++io$cE0s-mSb2nD zZf*#mXHQ}M{ANVfUwAHl5Ei0Tl*PEoDsw~ZODg~qpY@P$FstA8%d5~g zz>qRSuxQZE|E8f;ZE#GODp5{CcY>aI9+XkPRhKk6M6-Iv8M=7L+Zv;$O;`VWt| z{nx1ieR^6GUuk1WRG=0b*6t;h5;)t4}(or+6%O@+)3cxLXOC<0M-?k`nW~ z59m)*Sod25VpK@vA6l-f+N32fqMNXHdYhHy!TXBOvZuLvo+qBLQrxG(W1fXO+zhwO zSZPG0+xd+;vGbKYPABk3o7AF={#ZGGo+YC+A02gEIB#!IQ^9?&&C=n7Y(p+Jtz6(M z22+2VW#R9{vr*=i2%ie+V9!(X8D2&zVCLI_6yRCNw!P6!P9OXXe`Gspp3__g?x+gj z)@z4C#Xq%{h{vJ10$sccq6FyQzERnQAchp^axC%m+%o7AS8@}NJvyIUj<6X+@-gg^ zK}QRgBOSo&#hRZu43Rmya-^c~OJ*zaJ9Y>>U<|)oyoNa}*(ZCAkhF2IAo_xQ#noAB z2kLp%mKQiwkkb+EcSMW9MG3b|p#n*!%Rm0v-V1|!;i|1ht$p=BK0kpcikv)u679xo zxFv9f40rsN>~Pz#`4yD6sS0(TxN}5J8kR(3Z?zfOB$(tirCm_A8Z!^B183i*+|^G) z3Ux5_ED6&r7(_u=2_yx^I11vP%Wb*Qd9utduC0fvt!~Afcr>`bazV)RcFFtP2S<2mugnZp>3Du+F2HV1s!|G<5?0muCS#hC%6zKEcYzN)Yt@O z#11CR#%q(?)oe^QP9G_#t*yus(0+Yhg}>59gip(;3E=X^rX*4UpA#D4zleD>@jP10RXUe(OjGu326WTb3>5I zi!eZq=i-4yaZuTX>bezH-4wcYEqu;9Oe7{1ETKGd2F&|G% zq{Unn3&-EeIOO5DEJ36>iC4(H${rosO9?4t8G8d;1(1ee1;rl1R#fA`r>*Q-ho$5Z zS=UP4J8yYhlVgj(h+HwfDXqNB7chT&`f7XDZVTc0CnB<$fw>p^V=!_N$Z+@=Z{qt3Tzaq|ir#4rr~W@ZUg$2NE=KWJFv=a{YJ8 z0m`CQs?Y(7!9Qcx?v#nv`4rkG`R@Eaa$5{AN(&+`p^F>FBP@c{=8j*7jJg{kd|1vr zQspDsS?OaD>VHV`4W!tdzYll{1F9NWP(pusAw42Df4TBMR3E{#D1oBkrS#Xf^ja3V zrt!f(d8TEPoAoE$DYsQ^E9DSl%U+|gqsxHZ$|#86OV}zl@qUH%SXTw1%;Dw-)5)d0 zwzlH_6Rc!nw{uQI+B=hnNa_|DejFm^=K6yZz&mtUdf$wzkG!5T1H2QN(kd_)GG$ zcv@k+Wm>y^vg)$3uF5lkDCt-d>6t;nUA-E{wuQ}e#j#SI6hb?d=; zy_zf$%8wKqxHx>n30o1nV4WVILW(8JWwX^Z++nXWa6+M(3+BK|qoW4Dz?^}c^>g9) zgcvB2E$d;}og5ufr+;)*b0Bf6(WSs{@E`Ij9TZJgNhHxc>NjlHU_`F282BMXHcT_w zYVq{lk-$x&J)z?(z+n}bOX5IA|CJPgVN2SxtmVp*Yv<%QQmr~8zX5)XN@TRQHP+57 z@)b~k2vOEoK#j_k2sw2@Bk?%|4`6lz(J98aH!VP*xSek=}geM%XPSVlv@l@(u$h{k!?VshZ7p-D+TR zv06nO3$p5WgGT$Qw1?2wr`KX*9a{r0?eD;+A#bb(2wbZq)=(kku}H5Utt0bE?MMAj zR-V=(#Q)63R2pdx{XIC*axb8se#q=l$ANYX z>k?L<|G~KR8;y&dJvL)Eyy!GJZ^Xd}kI}u>A7JtD_v|Go%E z?smRY(cOA z+(arA#)(FRFrL!p9QhgpU@!VLxKv+*TRl?yKT#au00i5243Bug2@^6=4{%0xwPKi$ zSttZbFVd>SQmOzIjIC$(u*Vph1q3((AVGl@ik}u$#x>N4(hA@Nz?gpZhHp0RwzAOj z6L3T7X>t^C@N@+8i0P_=()%a_t*;GG&JTS_g`oTIWEGD8p!iP^#&$ZZYK7} z*F?xr*jG}$9RTtsq%l3qS4PPh#zhanqMIKNl2{Y8Iz87XrK(PpdWsEHXFQwrc5^xS z3KWBE7tJJ<^#B7~QYZy}&4sTBwzUsUh2slo{63ibOM|yoDHwcuxQH=+g=j0Hm%5%> zMaBY3B(cc$DePd|e~BN_j6=r0hih8^S-Mi2ecp*@GJRdWbae-3M>?sX9)G1XrpUJE zkj9{ezmawLr5-d#Dp|e(-WpU;)ra;lY}ZaaXxK$ff))_4DTvii<&T!Cv1+maI@LG1 z73;gw5*TWA9{!B8$|UQ$u6gZ$HrwEGv&!;~M0&;Vjz3I`Sx`j7!g-g9o9snr&h}Lj zwvuuMj58y&x~ksgk;PX}H&Iy}E8JVmHcWUoSNl$425tUyv>ajK+A4w%7W#EeXe*X<d_T6mhaZ zg21+ZfOB;O_RxcGaVS2TJqIr&9^x#eB+P7%f>-nrTGTsli!$oz_=@xX)G#2AwK!al z%}Aksh2+zB-nK75Sm?sPo8Vm?w$oj7)XbIkA}jhiHKuWK;hwsd?*}}`K9ebmwAnFI znOP?dQuqGjW2)up!HqDI5VB64SR}=HHcH<5dmbei`KUm_zdS`ClMI$&`g4@@Z#t>n zj$_pFQR#)xe0K=*c@v=sEgI@trD(#2k{8=&#ti9Ra$yb3g;=&3Aln$T_+&B@Tl_^7 zDzRlG!w;v>#VERSGhBp4?et&U8)AVJY*4dM>L4PiD^|*fSdM>nT+jeTxyPx-6an=5 z4+(wRL|zGU9fNHwTf(bz&0YylrT1yon`vQD6D+gC+|M0GG zXK5Kc#Qc+JR)?b9EE7&NClFH^1+sYN%OS=Iu_-QYcRa0A=jIoX&Hn4>0FNB+Xe4^J~_eceS3s#%Qx}(+Zb&$k zy#df{Wg-aQ3;qAl(U2hL12s-Cq)`=ws=yNE`=oJ!{HQ^Q)Ge@lB?hS|wA0N-to8`tKlN!B$r zwQaJ3!gy2CsfPqb)Z-EH^__bV&80<1K>eQ=H@F{roim&+E|z=HZWD?aIZgtaZ9%}a zA$hYU68J&6>0L`dwhh?D=E*X-ZD$w*q7xEaDIhv5?6{1-@Aht23JvLm88Ksxu`vYy z(ks6yg?VhmHS|!Yz!oN5Lw$pyjZ4~9x9TT~lc;s#%A7+(Zf6YtgyabVQ=_R}r+Ziu zwWCv;j2tuS?Xs9$FsW;^gIGZ4a$(dCNXbkv?p6C?tv}UXeoNM_?iPQO3#n~r80SYx5ckLfu9R%Oi8*wZ7 zSj*GSak4{5TUfIQ%&Pzx@ZYCyNMsk^Ks3x^unu_wCo@UPoN(N6Y8~v^6wC4eqa~PZj0>EL=d{A_ap{!N-Nil1r+l55;lFB_h7aUk+6 z^BC?#@+EE1=AWc`+79ZrdDWLq*S${Cfug0GtDJ zSs5DsgZ*EZe(A;%8^T2+1^}p(n0!-Bs~Ev4WE@G3ft8PX8J8*t76*VJ1`;n=A!dQ# zAmjxWDbscg*d2TkF@;%U4iWtQ*L2z`>v)8{42?tR1h2H7AT#ae8nvb34NXbzh}j$g zfyOHz5w74I0{#+*UuuJl)@sq?V#Aq4VSc|35Wt!XU;*&-wo)tT5~~n)sF5QCq@d^4 z>EthjbvSK5H^$%^2_K*U>8}KzMi>L=KrJejKZB0|Xu2W*<){>aY5-8jqn7V|l}?46 zq{@i7FCy9kC+iJ_9w&UNX2K%+RWA6BXeOKNKQOShFTMj1|F>uWwA*NoGPrHxP+H@u zdy`qIoIMrP;3yL)n7`&_%u~`|eAHI1`CbWn{-ZSo9RRQ>pV69u_>FP4UGseDYb$T@ zGW?+H;kpC)kA-A)xGGZz2sU2yTn_7v`7oIsE>iX8@XDcYuY@V3{#5pkZ6lsAgIxX_ zE|pMK;jP_W``bZ(7b% z&#yCo7W!IRzcHs)F-4@|jpc~+_x&Dh?MqS(ldVT-xBsP__4@fM&H)K@FdM2lN#uWI zc7E|qObVe%9a4*nm7ufsufui6spEjO_X>Fr0}H^x)LJb4wA+3QYODY(4Euxrby$1vryhcd&vEBZW5 z^Kkf3CUU&X{(YHhtj;uTMGDiR;^1Z*k~SN2VdaiDiLCT9guClP$e1VEJGcC#__JQ6 zekP&@6!3u@ehPS<>+%RaRP&qt=e+2zk&H>ThVqj#WN0r*iB` zw@BI3meQyE(>+}WmVY8u`sMYE=WpD#6$PTq-oz`)*A`kUFTSB} z0guoPK=B&#g>1;dZY~Ul?TTBo5XIrW^iDW2-NUWLM#7n9=&5;sQX3B{Zl*)Z-tN9G zZJCqwJW|otY%u5RUu8d?xHAQhkUa3fP~) zWRl0?+-*E>R&ej%xxp;mjE#W|TRopC-5lSS9ibnEMuVwh7Yre|lgoQa-TPLw>IGt@ z0r*Pf0^|3qTQ1|l^G`JyR%A<*p-i$lA0!&!L{hsb=ljHnWZMuUB;Ayf%&JB3Xr$== zrQlf~7V3CKrCFp=%$z}pbon9j73Fl>-gQCB)@nxnBlgTwe?(__Ec}$G-)yV*mhCDcH_! z|KIS9m}eiR9%U%UrUcs;Mnte-aSd7h%&@GT9Om{B0i?i}_#?}*93mJu+SB*6L2qs9 zVq>Vshh#r#kg7_XfKqw>@kXKwx&Pc8iN(dpNoUeuzi}yw{?njzr%lz}z_E*WhBu}% zDv2VKy}ZcMC>ExOFgp)*n#@QSWga=vsBc@F_o|mE$1AaUN!jwE^)Xw+$%zfz%ki>0 za)zV z(74!IvjCp>yXb@~D;@l6R%)b0CPY86we9BEE*+B$JIiwOokASLe?=JOL(4gf4)(+t z5MC~&q!3@d25INLDn=4L*|hysv@@CBdF2mwu!ITHMwj0BWqYKF>Wd9%i0v70Qa!~ZajpI){)7R>IK0?npm`# zgd3OD0ehvr8j@Mx0RvRe|MIgHXD6QPJOHOs>8r9CEYm-Fkw8MQ2snsEI|;%hQ=JOv zzJkPfRl48gfg9yIU_TrrKYSs}-F3zrL*}hn>2#(>@kA)w#(ptD20@SoD3hb~VpSPs z(ejlD1Y|lm`WQK%nN$^&$p<1d3lQVC6w?#LgI(%A@^Rh1{H8Gu)m*ZHXs$jiof*{p zkwi1lgUviObPg;sA1$PF`EoCd3fVv3w{fOA6-hz+ zZtpAlYtyl#Vbvi&_pKvB=TY!ds^YnWglQkDCv&XEHs(v4`lq{m$ybqF9O9sn=6TfPmXBIU){!@L#5*XI5t z((gK6@E|RJ*nVpnA0NZCwJ!t~X=u3C>%>>O0%pTGJ~!;nT|>pz-{wA(lmGyW*D|6q z-1?#kl=M2%FLR3S&|649+q76abTrrck#@k|;t_SwFAgQ|G`((owQrt7^aX?G;;9dJ zHef!QJz+J79W4;;T%p;Xtn#RbLt#3bLh))?I$C@pKmCfjZ+N0@!FV+tV90-DE-+8( zhn7XwLd3ItqpR)FDP`&C)s;3W?YVV*8_-4@c2_WdI`tHA&!Z?(st?V;GI~N|$Q1%U zlqdHDsDKtgfVy8nmB3vh0N4TsiIdoltU)Jy3D`f|DMf8mmi(d-R;oY-+=?$Xt-jQZ z{=d}xLLkDN@KA$AabN{_`8NJxYl37226js?qjvNlUfYyx9{?Z?#R54JnH3C{55ezI z+m$AUgSCOc*91`eKy=CH&{gJ*jxmwwz_kiN`Ua$p2u?7u;-wu?nk9xO%yM5;>A_h* zIma>&Envkohmg|o$sw;V;IoB+UOZ%dc-=?B;$nwUHs=T+je%1&cpTFqQG@KNS%{_B zLocUm7a@g{?vavckx!ptPy}ZG_Vz)m6Szzk-}MLk#Drk2v|Ct+G%ZInDpk2cMctJV zQz+mhtmh~;$J040iP9X)(FZM8q!3h0Uz1)Q7#j9PY>cv=7MA)v1cs$L^SE544o_x# zV+ne%Zw!^t;d(%@*rA%QB*^aLK>Rv%sr#l}hhU5i=W`@h6VBquCafLlKi&xeDY}#m z(*toX`A|rWD4uF7Ybc7$HvULjI6_Tm-!0%3op^c{|BvO1GatUB{`Fs}{}(j@;9$7` zVA2GY(HR={G6eY8PZ9utgai;`$66T#CI%1`v6Ere%9gh$gFMQ0r&efuVlhrEBzHz% zWC7O$NF0cO2xd zOIiN41@A^@vUTXE);nIqD_&pRC`9%a(%%;=<=dEhh&RQ+0EEBal<)YSYTD|my}k_q zTdE`zvDwjdD9J7obI=5|TJwQ6P|wQoj6E=x2k}GRU-t`zv3IMC;Bh5x{1(kid#BBT zpx?W9RsyGdU{R;GxUTb6`OR157k~c`VgFC@V5Pnc0Obd$R^S>ewsUkZ*Z+_xy}pKo z%}zE55de@!0B{AN!c>mf0^k!SLD1g-ngF2Om$d){ur+|+-gl!hs5v~I1HIE)tl$kwy@hv{{-WPy? zXa+t}BnyrXLwT`id!*4Cr2TByeCO@`FCj&Fh;&66#pXHy81&b~f&=D?A^blz0|02z zhKM0{D2-ERAQb!%gwIU5I+bPsAb3{MEJu_Q z?gWJt|9p%ZEn_?p%zEgiG#>!eL$6dMMSWPWRj1(M*DVn)28e?SM5rIv^w1z8>Pjym zE;zw|;Wk_5P9|}fql=zS;13}MV$>yY_Xx2H$NP{YJgysKNW#JZIRSj7TkhY}4kW4d zBLsHiKisgCprh$W@J3kjzv+p4_Gv}#cvdyS!2--DlRTECk2PZPw!g-mB1(^ZJs(B} z03lMh{iNVI1rhRkd?YJxQ<1{F-X~##=@Oj4Sn($v;p+(iDt@WK@Lx5UjzItbmM92- zwFw{hD+?U?mjeWI04<5x$gMtnnY?D~K~FTmDZ&`KJibTb5EjkhN>M4CYIQuas3dlazC(jxH=Ko~&8PPyEpb6{(02IAx zHF0`(H0vqWP$~j)9`<)>HQwx|5NwJI;g^3at{aW%6GBHwx~u2TmlpfsiI5Je#Hctd9>766m!H$6O(L6pKPlf?9)^TMF)nM1UDB)Vo&+mgkQPwWbPyF=69i z#=;~61wy8)1_@~1sOpv)Q@O-au#+rOnE8`er%tkzao=U~>)i79Sk?~R^KSRd7z4f* z@&NES(M++C91&1UOLGz}2oU(+bsUfkQ^r0G%n>Q;wV?CuP;uW>*F}Tnm`CeqLGz-d z0VY#$G3YFqhF!1o87k852M+ySF;-iFNNDaIk!@T2b!aFRcw;la=#>{9o67GGi&WUV zl&&`T?`8DuF~+!yoN)Cs!0cKr5MYFX^!8g_Ww1f0Mu?^YqJ8nO!guwk@XprQI2}1H zP7FIUxYDxr~3$vwj_ZI%ZRxQjxTEkootDn-Rq??a9*TSf9C zz5$wFBylt``Vi=SfD@=iHC2fhjd3A*{Z+2RW4#k6>~H@4BofNz9=1Q`!w88@3l6lF zE`n)_pE@WEzsL6K;LC-)S}GkuZfbgQorg^sf`8BKMQf^5a4SFJzO(__+g!SxP=Y!W7`?GKJ2klnje|9p= z%BI~X=mA?Il}r|pIoYgKB(xZoYfvkHKWlngscW&#@l1o6;L1T?@~T#Eh|A$Hl91l3 zfBR6lDfMWQtl)JwdPe(bPy(Ll3YM>Zi@FHLpr1P z`7mKu;|U2t#uf3EvJ4A!iHCNq{)cR)gmL^gz018$ZKV^&6utxOHrN;|>Af@w`S*{0 z6{e(AGvaX>TEf^&ZDNuUQ#TdG(97NvkR%~jw9ZQUB$r_C_5BC4eEV-Py59bAfuCl&4giM8utj^J5wp(J8+g@jifv2}CM9Zwf z(M@U$&)PVmpTo1aJOP~RMpY8Bb8}Cj{rq#aCR4OA_G;^KREA_GULM`<`d}#To&+*! z6nS(<&OtX6oSy##(t?lC-tq8!@5E0dymo zi03t5p|~1~%*tGYsOQ1iSs+dk0$N>1wk+57Pdw7O!PQ|qcGMngkm(^UxF%8P#B&P3 z6)B6_9qBhaX?r9mvHvq#o84R+DXZWRyRfj9cJfXjLG9->+OMVYk>K9uaT`C2x&< zU}Ir(yn)w)y#4nd$dMqwr}6Ly`|qcST_1!McQ*^g73|W>=1hA4G{F~T%mZ`P?8V5s z|NAQZFJhsox2^KKOdztN?rC{lAD76e0048awrv39^7whEZ{9bNYT`2h-XXso2V|ld&eXEz0hXe5Ixzh9Ag`YvC{v@)V&Pj!G@Rx$=HEID0`LWqH-h+gR>C`= zvWo!(b9f3Q*Qm%{&P>waCW z1yG7LV<4_uQi>Ko0n76;l|zIWDAYIs0H_N7c>utC&PY>{H=S0W%J40x|HvdxMF2RU zQ))GV)mX{=8R*>H3gG`AUvB{v*SBmBpTXVT-QAtRo!}B&gG(SdVQ_cXV8PvjB)Ge~ zhX6r>TSCG&`Q7*4efRyVzNx8UYU)rky>{b_|uL-rPIL=)gQga&(>-s}Hn z<|6&!=fT$u$0RK2-qZDvY4I9oxeu^D(WP#_Ma7u>EJVd~Y^%8Y`VnZgLG5MV+kL-* znVj$Ie+mEbZ-V9ERX1ZOc&;(L4BNJAc+=&V`SJmMGEbs16hASN4?PN*dK#9YA(HsA zSJ|pCDmQOM{YJCRSJ9rF*a+qW^9YBUe#3rJsVLQ9OUZj{d29l?3zI=yTGrOgs%@57)jc_TJEM=I&nA>u< zSPVvFJ@+_q0aSXwmH7quI6ki?6Na!wwIMU}HGh!m= zSg`kU@3SqiA-E3HPpmb~LikJhJl7GXcJUd*L5#w>A8X!!Izf_1se`GiybSC*x=vb^ z!0{nQHT9~Yli270j}%we8|Vspmot&g@cV>y1;1Rw^d!ZtO6@u}0AYCI4sRtLutz)g z0}!4ZLcZS3CJj{vElHf_-%Qu+a-BynrlXD}BcDjPI&h3FpO*T-W4$Xx95~=;90!wM za)A4E60e1Z5v_%BXgDvSOOn`91x9Q-YX3cjna$xx(R*PUWWKaqm8?Lg$`(q+ zVk*sxi0eT_6@pC=Cv0|=f3AzW(aWPd5zg`rl5*Q#qqYtvih?{-aSA*^o^6|6O`~mJ zTCGtzgzm_LK*)Ti_{QDo&6g@R=9*&iPibJ*%C$H|YZQ&Du6JS7pDgEvPPo!M60(rT z!Ka0b=3(-h$C|bAMebj~FA20BrLWkLkY8Tp2YW`0e}1bbGlNAI_#Z8SI7!ZLPc$!Ay&Y&LJBG_*LDHM&yOFjEIA_c7rA|Tu z#rc&*!b8Fl6^gH_{L$@e5W}QHNa*1yv-AcgqNiu5KMZbe?`_?s<-V!Ko@i#fo>;|9 zmNs}H_E#z?VWb<*n;hOwb;3IFDuF%ddo`&k$Y5m;K6@pB5Y}P#nRDUt93mQqqx@5L zjLEc+XxJm;It%l7_mSJnX!ef7;=Nm1&Ur&s4UEaXKsUUD~%Fm@%Ir_u{px_o8Dw*g(1(s)8|E6q8&X|r~4M+pkXfH;<0UzA_ zBaXzU$gQ_LKo*-*!NlB5%S8`>*SG_!$~-IxX^RI?DW)1q$3$Nz=ulYLaxFi-NXEP- zXe1UfD*pMJ8koSEl7&0a+oPWJ>HpOMzl)f+<$e3?nb3~>j*;#mD5|spa4BNkf=GwcFP!7J4&UaGR5k z+y{J!M487P;!A}u0)Ved6!w|0dpW6eB5p!(L;wgGo?qSxOcTH9T6u|uJ8Dn`6G{Yf zMewD5Ai;(J*u)jLjw6fWDbcc#IR&-6T(uTuv|~Rm?<}HSX$QfGo}yH6i&RM-Tqr)k z18(H3KvV@}Gi%WOwR%{*z-C)s=)hD_Y0K+gMJVHgXrYFv8vk3(P+S76-PyBY_kiO* zwfL$js(CxV3a`6$mzUVtL(DtrbgtcD6&~m+FG3W+ixzABJtvfd^5@cwK;SS}E1gMY z=)uNc^I;$)5jl3pJTiEs6yk@;II(sFwJ4I8A`8xGIsk!SKHygTAZ~;{ z41)ozz+23~MbsJ)7G2!#vGB=|CSlOPeH?L!hbA?7hZDK`Onfb0AOJxK{7aP;!l~8D zJN#PLCw{U3Y4p3Squ|2i?CPZjpm%ZWpdFGH2{2!)q)#uSir7&w=|#8fav93qG1-Fw z#8@thAkkg`_!!!p_|3w#Z}!P)9)(Lu80|PK6|vCB5N*|!DT=l~n@%QkMMr88Or*iF z2Zf0d3X{`+!o-rkthD!Xiz#h}BxOU)q*g!;5*A}5`2{4vFv1;!r;=cerz16B#xs82 zlD`DrhlIfa3NT@?&wB@4#jOuNXM547Xr+kxYolm+!{Cg*$}r6qyM%N&t?A`=-BSr7 zf%44Wnit&q2G>TpIICw-(XB9s;1t&ZEm`l8D!GrzaggquTd#}wHcLotLVQXUU_MeI zP;J!;<_6q&`>sVTuKD9|7$c*)6Pl-3g~1nrO zMiHYyj!v54#=nG9{efxppMbLUN@+iBS*zD9}>w{)aqdU8DYbvshaIs1EaWZNSK$P;CrtmoIUM6 zSa1CO50t1ErqtlUP}wvLz4!8yVT|iv?Zthc^O6dKxYZ!Hy?iB@9mOra5cy`#KUlh2 z{&J6=Y2HPeW)w;kPn;4oMJ}hE#)(1LnibRqmD^9XDOGGFXb~RF3vMV{km6N?vd)~X zvz^318+FTu9cKx{BBBbO+h5wbC4Gd;JJKw>-Tn1eecQ~UNJRL^j}m$ts=iHfcpQwz z2{#*po=tCZ$Cy0b!hX#Xe!AAlOk%-Tw!l~nX@gsz=oyN%U-z6B3?9r+N5G`n zIS7)^s(9EOeIYO7Uxt+Ufe$;Jq@_P0cYF7O@byVS!=P{O%^Mbyr!?IMNsOM6_p<&~ z`ES@lNvnz9naHSKMqeX;*(s99lgR#VeWm?iUVwXTVD842+wZ90LMYVuDBsFG6--e5 z$x49zijw~|WkxI7=UbgOmfiJ=tI9liGL)Rl{e+d{PUQIqJl={OVOuMr0^T!wD)25~ z#9&QQY+FQ}2EX6YHwMJcpA1yk?qrJ<2Y>tRP5e6eZcRh}vu93smv7sWs(VnZ(NC+; zl5a-YiJ}onu*p_UYV;)?x{djXCx_Tt{shDJ+0ul#M({m2ww6HS!;DK$I~CXCrjdr@ zZxoDO*@mJf!|e1$`I$s{87tP7V@WFmH0M@Nna(%28=+aHgv6x%VzgAD`0-%$v`+&I z8^u>R4k-C(3K)I~E2L*SI_HoD*lpVyvGUTX{6t++dq*Uz(uxv)7(W5~yiXXzuhL@y z^yuYJ`}vepC*GksR7~$sn|FWnRibIXb@1~gZux0K_Zx9o77s~v?hZM!26ttd)cRm} zQ;*SJjJ$@vkKJ;m$VQ8ThxopD*k}LT8xcl|>f8I@{)kKr>sbTT7>GN6m+F->RF} zF4kU=ij{CPR^3ZF@er$HD-0E(7LOTpUaeO#@=jcEQYb;P^c^UR=}*bKQEUmKFoT1rDrkFlmjP+v zr!Eb(>AQ$>P)$EARp7*Ct@Mwk|J!GPh4JbVfHf&ZlA^bP1ht-It*xZ7r8TiKJ65*ApRxuFur5&ieq`*;th6B! zUA{B!>^dQpAbd%=dnVAN)=~eAAH+9~iNU?sT&*jyDq;NaQ^<_A{&Zl_`12L$+(qtk zC(o`6MLjhQDDMA=8+iYIWg$n&XyB$w;nB)F zrAT(aRoy=}oT9gXn=>-tq~`P9(vuo<{?)L1ixHbWy<=-0zyPF^DajTEWzzTd#tV6)&w$9pGr&` z^LQ(VLCqDZ_G@@}v4eA%JSX)W>CjX$R?*6EwUuU#xyM7kF=Je068lp;egBW-v`6^X ztP%1~4DT{L{kVe+cYnX%tjK%C2+CmDHx}Iip|P<70?C=;xRJeWcln)iPL+QUv<%sk zx)sX%gp=v2#U+*HXQM?GwZKjA_uGxIr~)u0BE?(8yo%EgVHlLZvM_jl`81kkJ6aLt z4%gDjp{!3Q^1#J)eo3BA76u{uX4{rSCbHXRy|<29-aprf;09|3KG124v9mM5jmSZ> zR1gfPz+=+#UkS7$tEQS zPMuajQ6*jo&34X)suTz`&Q8LS3dH}Ocnm;$Gh{zyDiE1r^q;+&a7!BotdMeJ)=m%e z8gwwv=b*vRfM2-kY#M`ZD*Qusd>maKsHWr=PKpvU#(8muBU_Q8R%B@PddM~h zD6O0Y_wkSOaQH3Amh&LA0i2*F z@oq^y#Y=qqBJ@j{`pa`--@^>YftTF2S&THtGim?p{sk1IDnYBxT}3b!K0Oo#Tqp`> z{}%?EugTK%`j}2SL~!lCg`-96r;D(okqa0~mu__(JWHHMqlf zfRSMO@81j|;=72hx+vX{k>MHQIaG-uEA+v=dx9@SyEX$JD8%)D3ei>q7Y^^fb5_)4 zE|Ge2gj+RU9Zf#^UoyKW5^-k;BU$1_O~JV3si4UUqv7jeT+mvXCuOKnkWqXd=;T>{ zc-bZu>fICrA)87k80gkakR(go*W;7W2jdx|(xz^)&)cx_yfdyN%exud#I&+OBFVzh zT%3HQM6IJIdd|tl8rrw^8cWL_Y98^pePx>3W``X<4OHx+RaL5aEikwc9*T|XTUKiF)wEhiUN2ZMz4un>+iw!Y)@r&x6-F{wto zJ(@4er75PJ*k5!WE2;r8d8sUnx6LR*IVY-cqk{-Wkc~Vxf_$~C)qGB%ZxNsG+jmvL z;_rbW1Yb@l_65=~$1a*%%SLVn>;xf|y?UCp7$8NjW6dE>30WdHnxYqb#@#PBnTi)V zw(;UF*q9AMQ~>M^)B{kVrm8yqJ5BpnzG)y6oz}`uh`3fzzoNj}i!Z}6r>3Hlj7Jj; zMkCTlhVcCgmfYYD4`+)Ww@Ju3*ky-vsTlGyfEYS_FU*q|S=smD90ieS`VRjn)VC^x zmiXOwFQ#gLL~WbX*FoNG5cMM6H8TRK_z>t}LZsDkB0GqWI7<`egNRLf8B95$t6#_W zafJ(BbquWFOKgf)(kD@lHB%Z3MbFxX&=izAc+OnA@ybLu0Y(XS$ZU|zH>0r zD{@-FQJqr$EM+}ub-rAYLeNVKVSv^fOSS<@Rw+TXyYvvt1&?G)>K?6$-bWVcWBMRc zcp+obYNmG(fLId>hddMxr+>r2`ZqAJBb>qkum)z{yn?FJAJKfI+)=Re<&U}d`;cEs zSq%0s7pTfsZShrkspARavBq%?c;3l#hVg?DUP&5oOn={%szu&;9g^?gqu1ri8phSY z6|r)^EmI<~-rC#(eYvkihUi?p{`I}PZ|F!KHpLHn}GMca-l zom@ubNEm)TxrlDw?^D<<6rNhmbR|JNf}>P*Np_m1)N@biqP{uHf%xUT!*}Kz`g;YM zGd*1-tcWK}4;V>VV_2b6wwz=$6D&OJy~D+ob%Of2F}>0f7shzdzR8g&h7@6UGZpa? z-3-f3+jH`_&u-pd;02&$xdh`F8>hLQ5bq?z@mva;xVHHl{csjxyqW zy?$Zy{=H2?&3dH+!XzIz;{}vVsv#9sddFPh{bjJnTAfkBmCFn--#+ticIZ-)Rw_E+ z3;g!fzhn^auwGzhh<6`FPb@%kSDLp=_@R7s_T6GWVduz*c^L>KfSbo~*+Wg%q3<3e<3>-ulq2?VOGigM zN_^&S4?ius^;X>IzaZg#8-!6U@ATX9RXQB6jkZ=z>Cp0t?_((f3jflP2B zVG?_~MGnfPB5kTyPY!B?e}LnlBFDMMp7A3B++x}Q{=jdP0gT~ASgd5p(W7wN88Hcm z%q_@g4N2`q-LRe?rj<&;BX+JYGNrB^v0o{kc|#@vd}s;`QilRs^Iw4e(^&xv;JFH6 zim1lfGH|dcIN#4~!jibnzJ=yG<3O6~5V1Lqj@zX+0Lpi#~M=Q)TBaC;U_Mb_w(e5r;aDO<9TT zzR^MwyT=!D(D@bw0*E0HU&uP#@MXzBjv4V|i8brwS!PwinS-3*mr1sYa;ok-7w z-vU+1t?-+vcGX37)$8v(3j{j$M(68%zRH0N9CJ<({BSmKRO*%)@=aKFTo?sU3;0Bu zP4|DTKW?5*#(W^rtw?3-YS@Ff!2}H_MiPUzD`1V-7NYu3=#Si}anGm+BSEfYilgot zFvFtarG2;fhTBC|s9k|{ZWEN0MY->*QPHxV_`Q{g@t0dV!onz@V9I8# zYSq^pauB;`3_qHu?=lN{oE?Y-N>R9Ht!%pXj>FJ+WJ>O)O`*$$a>?u_?};PVv(+>alU;^D4u4Qv%OPbsjHv&KB|bluqkM!}vA4`E(NB*169Nmi8pZ9IxCf=Ddj)Vd!tLmp>te zYgH*-iRjbgxqLW}Q4|%38T_a#*nXD6L~Vg}F9-94mC5-13Y7?lNXc}%Q0PQ=0KT6BHR8icR!lOWU zz*+744V&782YA~O-`kyj&5E8+N2NaP0&9b+ zV*+@tWb)$~j6Eq>9N0y48;4T6{CKluHpxGAxEpx0EqWU|hu(=1Z0hSPff(U%+SHQE zKa&<*xBy|}W@X8cjmT^%a+!*^NIirzl-TZb_EyU^N0lGwb8`d=f!@u*Yt@X+fB$#@H_`jylRx+_IiDYypKbctS#+Q`TEP%HT?Li zEz|u^#NC5`@;3W7g{?;@jW6gVy|3Xio+ z03dHBvi|8ANZzL%qrzBaLKo0-xy|!n&W_!eEgieWANQ(xN2-cGZ4nQTW8=Q9_=RFG zG;ANP?1)NZFZpuNYPZH|O=Pyt`>-7#6v&inYMjzij zhSe}!2vhdXJ}2GxqU~LL6D(V^HPm|QzbX$X3Vy4lbRh^}eLG+uLlheBkpJ#lecGvH zv4$&K(pwE?&C8U5+bn}qp3#ck_2sRSVrIwXd)gV*$!`%i!sK&e9_iPZ+j=9IICU~; z%TXQx-xat$rjO)kJ&`5-WTzhWr-GSbUUf2Q#>Mxh%xC(?|?Z+Y08S{umK`Y0C#w^uRdi1an$+k@WWSOH7@C0Us8q8Z99Z(^%fq@{s z#{xJQ14aBx+BXqRF7aT1hZg{_R<{s)8q*LXmNTeuGnrdh&kqx{e!wdP9fG4 z2T^7xohL<{Two%?4d%vYEBhGBGmik&6&m!(6V1R@YO1bX280ZXF@vG5nhEdZIaXO0qv4MV&^SlL@}iltDi7y~HdpHP(8(*`i}; zr3~5=5eL?@J~JB#iXDCHx@lZsM+qcYhBwzW#Ae2rnDP47rf^DQ9eBV>e`ZA)I>jPk z#g4`;S(TA;a45b0`~}fKE`RCaa*qT>qGCmvB!OZT`;k81cd2riqsb|`@FT-wyJ4$- zKTao?z93f~UxhMrDXM3bNEL2ZyYe=sEHOUh;tFe{^y9(9`<>%?R0!t{5@pp7rSBz= zH>Q@D$P*f+MTpN-Og@K;otajVYC8c{rA<0F20wn?egvUn3;HyQ8jp2O8aDRdN31&< z6)uN#!~LY^LUSHUF0pipl^m_3&ll%ntY9rxGGpsyTyHW}_2n^ULucT`JOUlo`U5fUgy8=W3ba03RoYpo5_Xo z*9RP*n&d^YY84{fyjjGR zbt0fM(Cwep|C3yjb9SA;QZ~^($k3jFgy}jnDO`iZ*MF73zS|Hk=Oh1?+fRC-+{1h* zDA$1{jEjTP zGm1`w@H4lg#3BH_mxSH=FY_ntH}b^Ks!pYqyTTonxFU2lSOLwSPT>iW^j>^TEe(Z- zi9TQRh)YfN=1Zdyk~sC}NrH6vVQCJ4n6~-*IS(mS$IYm>Lo$1AhhJB`xilVaBl5d? zgvb(|8;cTjiP4jPvXgMdofHA}W_I?4+pn`O#|KzQiTxC+c*}N4pBw?G`X|^ZD zAEc^D0M48=aE0+v6;Sr!&FrDSQ0G9L*nUkPLvx?Zv#nGbHHxVTmp4__JCs=fXj31u zD#Crsl!Tn18XywJTaBhWE-0gd7&UIZb2CPqA8e}6{Wg4zz2A@j&aQ=5Fv$|Izw7Yu z?@75B9Z^`S#Y#`6J6F+2+Z?(X>)7$@bDPK2l6X(ucYqveC6uE^O@O(RwWl3rA9xJY zK&5^y!ogcAl_6*sm$oXAaw*kz2W>&$xz)S_`$!k4TDW^>^Lv;a1kdbooen%IKXZTH@7Pi?3MF% z0k2b0@|85K`ghh4-C^!&!%8!+W-I{EA=&WNQJa7ady;e;U5EV zVWPW4)CP87*f6*c+YIRbSbh9-{zv%xL^PJ#@rnrCmZT_<4CHU-Ur#`X=2R4(ZinVv z0Pu}K74Mg}fsD$p4@#3#=IpyaW5Gp}!5~O)vPNuW_LvabnrG}P`upf}<}+4X-Xud3 zYFa(zcJZ#uGnIo*I*d+3e;Y++ypA0+w_&kz^ukU%&Z}O!Ayn+fuLw||Cygn;;`l} zI2_+cKJR{4AMTvjc_qI)iH<}YXKv*H0L;)}4)akeCnMs&wT{vMt91a5FKHTURG*zZ zWhGzhX_z0?Jf8%E~NJFJ*O`oj3}TdeL5Dq z%l}?3nRh&Rh(u>nTjr(u7S%GJY!6NNO-tdjN=L@#^#Rqhm`B)^>W+?E-BD>-*ASIU zaKU>g=29bW_+zitws`t=GSb11W!kIoQ(uBVLGIwq)zkvMzmwyoCKv7qSm$4w`Ut;I z+Vd=GWUL^Jl0q0RZq2$k$*SOFnmYCq_eE!PU+@c zIIE(cU&Bo!nXnRrQ^rfYIT^K;zkE;seO_>d85gA|4sXkujX->!gdkJxQK+y&6j!pD zNKe9gPr{av14DIst%TJYHMLmky!Jcyi|U%)tdd)mz52&hPVRl1J>Dh#Q?sgA-6|_HGssO})@RF;U@V zd^dGYqMB_?#Dz1s{5miC`@!UkRkKVR^~CQvcYG9n*n39?U_1Plet+jq)GHg$*)Ie! z+ewJ2GL$gaoQt`+WDnF{9Ep39lg@n9F1|~1;2M#ffi=RaL|sj3ckxh(cJr$zvP$sphpPKGMUzI@t3 zPc;{uUZqo#{#Of%Bz6e&YtE3g!<6%P^u7ax1Im!R=-UUB z{{Zl^heLiumQMi*K8Y0WC_{_vUUjx`S?{txwF5RZ-BW@$0T%2b1UbkvLcFU>2jw+$ zgg^T11ok;cOx8#*?zi|X_#Z&bK~G(!I7ygZU{?sTBCr>XjKy}pl zKc3{oek!5VT+!wszYFct*@K!k2sO>=KVv*B>}L%aN}{1O$it_Yl8nE<7{;#{!ax(Z zBPH_|FZ+W?Lq2%$+gKsn350a_AQ&5?5cmXvt$=24y#Qzm3HXB%-u}<%VAuu1%D6VI zO*BSosNzz`Z<)MOp7g;w>hC0G-{>&L*~zIk zoLVl5@DfZeR3aiIPx8Qgs%i2b^fXwM~^M@zeUnpYaBuoTw%9xtUg za462aWyMZ3m*X9_cLoCAn)*3>w4B^5RH^+ox@%Z@$Hc9o33BSixcty=u`Ib5z40sB zw8~yOu%7PPtW5k7j~L82%zr&lGx#v=WzC@T)n_#|(!;diW65PWQdTo>gJv(8<3|1&83Yd0NM2OsfbfzVNt4b#A_pa9`Y*@qNRBN0p z7;QC{^a}0MSAJCRHB7&3yNaZ!9inTcO{Xi|+$}_SL(4@-qjqt~ZcaC4!*%SL!M-IcMuCIt;04ea;n{yzHo&IDe z-{)>hFv}-g7hg^$RfT#JpXA>9AP{7Ry=gz7K{~y&W^716H+S~kn>piv?km~P*iiFs zAf!>sRDG}?o97P~K@N3f&%-mVk_)xe`_O_u9JKzKP@>5{4q1G+r{N|U3-r=FXSQ)A zop`Ph?^I3-7&-N$(_^2lOJ{vlC=M_mo2c&VPOsH_DEOyWy*l5Z@Kq87>RfHV`amh< zB;{jq(Gbt;>5Ok-othi2wfRyv)M&;FJ4Rf?rAE5`DbhOpwj<{JTbds|jp7UV zN|xMN!3=GPzulg>=a`Xd&xHp>F4|8vyo7OLj-4{Ak4FcvrAwsTLJ=V+6+f+1iXCj%fAGM^o^_CiMUn*Q(&yGurBQ zGWfZbkDAoV&CxDXJmFGzB0bJ4-{8efkD+a}ap^OK+361Ak>@xIvwiW%AUsc_E;viH zgS@{MV`ahr0%L1mI6OL@C}{7 z50O&2q`q>+RWJb1js`&^;DYt;A{Az;ElrgUknmNvM>xj1x$;EeDgu?z(4LTQ-7HeY zeFhN&8a;{-+!88M(zjgo4xZM~8$-+-t)BWcJ;&u4qf;vhV~#QPNfHcUTDFt-Mp#SZ zs}be0Q{s{EqEh;Ms1Mj3k=Cjf4=$LF%5?T*l%JWUEs;f=^V@ey0VSib0bvk~pg!)j9C(omthPH>c#3tA1w2Lm0oR48{Brtv*TB#>dV@3vxlo#0674M7OLsglxr zG$bS|;A5<)fM#EtIrJ1NSTr;yAP>Sbk0su!>Dh}n-})K-W0))+)^c?oS4f_-*s8Jg zXk6)SBwb)MJc%eRRU3|?;(%KxB=Tr&*a!wy2nJI3OSyfNhy2d(+w~9~M+vMbxFPNB zv>J>Tz&gC2Ykp#POe0|{!Qs7UkNE#Tjdx4K(uc(aRV7`XgRj1Q$Z0`N8rAsqWxz7 z1L-r)D!&T=B*;mTm>i-_G695XDCzWGjM;_c!A0SvUhldI>*c$W%ajW>!6RQ=s(GxC zX@&uAwim18LkmkOc3Hle!9*qfwlGDFUMAx;7n&Tz&{)G1_2gG1K_AZ}POWHX8Aruk zU=voxk-erxgUNyr`%_|-=!ycG2*2w&5NEGw=Viw51R@@()e|~zDK=G@I`Nlp!N?X| z>Y9qk`uApY$>n=BXH^Hb3voCp#Jix!_$^FRuO5UyEGwkVQX_tF!8%W&>FQNan3SGR zqC|k)axg~1o!H1kFp0wfcrlD`gkN67;V0XiG|3Bm1=VickL*u9!i|W-FGIB-(0_0u zeDY`gGOv|mP#BCiQ0?*O#mpjsBApuQc%MN9J*xldcu@RtBC2;Q!Z&);{g_^}sZQZg z0=;B75cQRlZ{K%xP;$)zGKs^sxRr2tW6@97(M$kZ@Ew`iG3?8-Nut_Hb8!qnARLuiRJ+6fAV_Op9S<+LLP z!(=S~eJp0H{`DZt|CNqWa^jBTOS3>U5XC@ReD{M^8j4hS&&&Al#=+}F{_jZ)#&_Zv zVo*iU6C8VSv`fAY6^K<226pBJNva8spnsN*qn*y(u-{X9b!=gB^nT~=e9bu_C&7Nc z;Fv}24RS4&Be%cV_Bwma*LX%bb-~RZn7F-4%h}RfVSYu+nA*PZ7U~}~Y#lM9Q{Ggy z5Lfb$+Nf0rP=q)Bpigj=j#kGn>Si0d_DFK>=O=l1x6n<83j!afBrG!5C;`F(ff}_p zHC8elpuqj+eBgbKHFe!&2+KX)7-f06C2KA&4*>0l6$qY^y}J@Ak{d?RIIFmL@M}o* zP;S|Qam^xcx0MX7dEn*fv7$%ruplyxXjOWBETVZm(ed=Io+-G405Lcz#ZKqzpC-z? z#^_Ai^N;5OTGknO&p13ZmldCcrfbxC5Px%%N7m5m9GNY)VoO$H89=BIeAf{m({McG zywo0ZcID||?`jvb9)LrX@&fDMtn$%~P7+v*^Q7`@PR-1{hQ_G`UtxaCWf;EWW=AtT z7Z&qAHhN#0iz^?&`z1StAlz4w$rbkdcua>)XuZ*wYg`O6gdbu0UQzlrQDH?C@IGU% z7ilxg=Mm>^$pY3S?F&WGbIFF|J|#hhBcS|PxG^@Av+#5_l6-SPnh5yIKc74n%Kr#t zan#*yb`l?3mE6^wz`P9ovX)n24(`H|)*nwJtV0$0be!_Sh;S#@$7K{?E11(jCfw@q zr0!E9#?*+~a0wgKFK!q4sZ^J`UI^(A;-u&D2l>jIS?-j0`S^Mp=Y|oYy5Pv4$nnF& zrq8e`-mKoaG~%H~j4^U&$qghsTIf*(=k_uN81Bj&EW_Ui9{JJ6w>4(%GZ!i|uY}Ci zy^-~7uf5+)5Wa*)B6=>kHadimsYKmM- zP=VeZz@9C`u82uyL6;C(lIE%O;n1{VCO6Z8%tlS2$EC z`MM{-Y^`T1`e(+yczP>|(Zc&W`pp_otJYAM$LVXS3>82U*(wCFs{O5!)h_C-Dz`PA$x%4 zT*1lYBn|nR2#Ev~1skMiuZ;2DYdG^|+WjaPbmtqfSf!aXN$1im9Cpv{XI%)lyb`{! zkX$)-@?nVx3EuN+uL=&3QR-YEz+MRMz9-XYH&J+5o^}rk-{pP5`MCkgCvOQZ=>=j^4Rl zV!EY5c*2ev(r`e*9e~xP9r#HWC^sf9!C?a4c=Rb!vKHI(P>)u$;}PSR1IJRsu3f_=Lhmugn{UETT#@kA2wz8XvWvXt0t_Ud&tuvia`zJqECG{7+ z&%7b_1d>{zT%Y%BO-h0~_=KvhisgT%Rz%9ke~T&!K{hiYqM-L5SD|(u>$9x>xrLP1 zTS#6!LP>uwm&d*k)Qs8>Te%G5_3Y@M8$>0;;cq)wv|_=zPa9!K7hvi0nJza`?0FKd zf7Y*wC8Xyaq4X_zS}--$>z6ZHc9!`j(jeNBz&1TH)6DgNu1r2<-MmH3M*Zg#`Epyf z9pZt(M=}mP^ij#>?B?#L1>q66J;y0MU|mGcB0NphlHsGJryD~Bv~lf}wesoWJ zh&iJfI`ptWpD+ZZgQOVZ@IeoWzOIAGu- zYR#h%fLF^Uf47UP&s4#E@VflbIS>>0`Re=|vTOnfV@sF|S|0~V14K0qnE0I=8Vvw> zat_#a8ISIM?qu|ziqQeop2`2D_o389$XKjSH^`E|P~Q@!%nS7Ep|{zR23jkjftSDo zp(=uNU!&1db+B6JbZ0@}vrO!DEWD>ILI<7Nz+gd=B5s`gX4F=N#kwW<1DvExH7$;i zjz=oH09N)CIv++|q~mJ(vLY2-BT`a2h)g_N29lQ|qHAm=bq)ZNJWRD!!#t+53@BZ#8R z4MhiV0D!uT4wADq+$sHSFuYuAEsw5#zFCOA4n1y`s&b{~X8zG|zGC89MM5*R4=CwK zm!jsgVn7+5D-~Xowj?o4XI*N6#MWL3v4qdWd}p>iZ8eN-PT0*p$@TTu zbPGs_f)dgVQtCJEXTR_9+xvZvkADVc=3v&k=epNAuXC++Uc0IGCLdjj!Xe42)FAfk z?BMLgiB0;F*`<8^10{>o8|>(mN3v!Fv%d#x;x1(lL4;-V;>F7)lAab{Kt?7sh@O;0 zLeyQT=zO#CnYbIt?^wLY#JZ77bVq%1GQD?dNCC1Fa|8z^xqb-yf?zQ-w6Q*s>`z5R zQ6^^u$=Df}HvjqgPay^6|HVdsnic{6gYd(#Om&Y7-XqJb^`|kuv)SL6Wp{fp%|k5( zY^kl7TzJ-jmaS;)LoR=v}Sjq|<{Bn>@C@o*v%^p)(@8Dg(2jXuPB2tb~1V zv$eU8JEaL)can(7(x$-9J+EP^uX$Qo3p(fS8(zmA@HO#OKwnau6jyqO0N)^Z#&eIO z&;HubIcQ&W?ycCT`mWSBSxJ$fd|CTg=%f@8$v-Cvb?33kCeino2xDur!nr*6ztn~< zSJkzLJm@rV+#33YdS&;Fx+(@M_dE2)n89|PU?AI%Ux-`td-t=~oT7gB8^SVL63idA zOFK#VJj_!ey`Khey87i<#vik`L#b ze<^r2;6EZkg!mXyAT)rWV0JlX{AT6s7R;G!5+=>5B981w#M&)9RguG-DA{Eq6Wa2> zwJ`vH){fLj=MMump0mV5_w%e|rUMF{pyf*lER- zcIi*Ny7sl7T|ujgk8wNSiat>cTX#?#A2BhbBJ;2Qy1iKQNc{RntD`@n--f!4GfD?d+v6e6gHK{XA|5YSAvmi*hqv&2G~awCDKjK_R*{EGwq<&t zB(i>RI7mn8rG&ru$>&bLVOfPka@Nr`&dar?o1{2Oji_4^hc#x=0-cxsv!(RN@bW<> ze=7b@s!#pv_W5h94FI?b3$f-QypIag?X?h5NbJZ|-qAHNs;_3q`^^#- zK0SXUhTc7@1o}zK{dBBR&(#wvua7my_+FZE?pYl|ydj3As~z|BE4PCE9mr7AbgfYO zWQn`Y6Kjj_jdp%6?_O@4bz0F3N3!;wr8W1?ilm+RD_6^T-;M~)HCw;D*#b{1aD`XG#J$5=iijS(|a-$guctC>2JlC`--ng2|{R%JU%;Y zRU-Ykq54z7x=%Q=ZMnY6om1s&jzTAaO``2bdO=@-9an(8E4WPX+8Xqet8n;)w}LNq zRZV?F2Wy!SN2+6ZzBPAB`!FY#6!krFoA^g6VexfyJ#|gEvk@APDw4jl zDCOCWoHxI3Zl1{=%f{@+!j1UIeG#5y{aYA@Pi8Q0^DKrrfJGa$MsCQ04fRA|8QvoRC{Fx~_-jial$WfM z^_`YTM|zNssQ%3s{;wl{rm+6sLK$d}!afP0XJ|S_Rxy5js^WxL;z}Wm!pqUP9q|Dn zq$C4a2w8J^RzjcL-RHcU2t0@;04Hk_*LKqVRxpM?$3@f4qaNq}5Z4+TP7&XZr0 zK~_rBpd5yK*o@*?;z4`byCmKsH{tD^$yJ?j)J@-lcOZNdJZZ;m3`b}7Uh9%sBftlp z{}#j3L=MXA7%7qIVk+OoCH=<6Ksr&4bi(DIl;>Zh4>vyzTnY9k)v(c{50`^D0H84r z1p~$pc6H#B5ePN@>ow%dSx@)@$`9Wo3_pBeRKxC7ljceAO`=(??HC@5d$!! zn#7}ZVoklEmvtcGDfEX{`C^ZIkOn_P8eH{H81)~68yVn#%muKh^N^1y+`u|sS>ec- z2OtaokF7YG001!sB;epLm~ZJO{(3VC*y=xzK!q_6sy-@puDtQQ8ljqfQfy zn4~u2V>NGTQb*$Ur^v4=awdG`!T0bAGDnnTsuhHvt5gjRXT?+fR2{F#}3#5KX_w~ zQlMuZBM3N-DFnb}NGG?EPW}tQ^_li41_|wc%_c5D&lO8YpGV3JqX44d@jgIs3AZjB z!4i)3qbqRD4e~*NVY6)=9%cA_b!J+taS>Drk^mau&9pEWmKm54EGto$|0trni`fJ# zRn5)b+*;rX6P3v`b#bb19YNfs|b3!ya4)r1uj2O#m5)41E4Nkr6-LFUSUhB<6_x@M4=gn z4RG|9x*nf5FK9owxx=MO6=Y+WEl_Hap0om^lR`1K~Zr`-JuvD?qI%NTTIh3w~ltD|>=7h&VL`mQuP<|DA zO#pl)1bJ#)CAjSlQ#ynLL(1bu#tvq~TvN!)h7!kzHwAhMfG9{{Z%-x>EQ%KBT?ot_ zkc(63iX{4N)dlt%6U@f{dO$~(fgYveK8qr_L5%$lp7SU?;2}E`aPNa$iYQ7lIZN9} z-u6G3^1njLjZ$>>G=ZkVBkI0!EP|=WL`fy9I@H1MK*$a@6fn9nDE5Im0&H*2oF5}A z-mYkS$UZSDn+E)1^E+Y_tf%*mqOfKDYG+)oR^I=vsZYKFl|WINu2P#VXB}V;?RAgQ zL7Tv>!-;l&n!%!e(#3;~;(`apu@xJpCFlqW>B7+9>Nd)`{H}A-o9hYOh+~c{DQV5p zTemKI-@9UyTr*6ETv{ z9l&PCk%GPy&?nSiw+1LPNhK>D#%@L0mH0Ri{Hnack$A^djinqSH`1(8fpXxoEtnA) ztFuRR-6OQp!Gqfyx@%j`C-d+qv1golI9{EdB2>JB-JgWw*@`4bXlLIm;0i}A7WTDc zbH8+XrrPB7_~&PH#H>|6cKHc3_AV#R>?q1NAZ7SFxD`)Qv_?;yXEF*&#g%b9pjT?( zq>x=~T*fZZ-Zzx$URnfx?5;VeV=GQ8w;;1uj%3nU8ye zY{vV-+kQ0$-f>GCYw2N$Zz)#M8sBq!b0b4;@JX%pdDsR8!>#zV#7iWTy@V#e1q`Nh z*AQfCB+KQSk{YQ^IMwbNjPU@kLx)hlz4)X#(mkM0b=%sxU%IvMJAG1TXhy5bhWpo8 z-ej6mlf|XH^P97gN&!aauoJKK>H`};;eu}BN+F-1pX-Pcgaep?X3X*S+heK?%>dwqo)Ke$cL@bN;ozF7bnN`ZbLG zx9q5OY?_*S;~Nsl8(h1HsvJ$!FX8Q#d0Gh(XWQZxtCSqA5F_c zlIna`xXV;u?#iEfc$`SEBo?}tL%d$s*NHMrvxdhDUtxTVO~VUdP6^4Er3UTEsNY=r zuy@c8fbg|Cy#uD+%qKj-DWE@>j6Nh9$piNo_{)yPPtDxhcaeUgojuW*O)*2!b+_Dm z*7j}rW2e=yAk0lf5lTCkpMO>V=Bxh~M9|I15|KLa$!mc6`!>(7ZVLm^Z2k_MJjS{{ z9nNYmh5;+>r?rnHqN<;pI>m| zc&MkfVuw2Vx{9`Fei2r8@y+$kE z`Sw#Mhv$+k%>+Yp=cl94W}S6)8Y|Z`X87b+b{XcMoN>gSrX+8Z-f@hndvkM)WiqGC z70kh{nYo6r=@hbK>Q&^oStV}$Fwm02@DyjfjvA| z7ZkMCEZv9m{e;#k>powV+#{tc2~txc&5*$XSNW1Qw9UY)Zo>f&CZB7nG%||&YBq@k zm6*TFr%$3=K1%=>Oy#%P$C2Gp9z95WtK9}m#p9PMgCb{qXDO=Fp;8og5Y4=8ZL-eM zyPq;zd?92mb;^5%(tVfTs3X3>?1aLCsh6KD-!fd_V6Kx~K)p#H_<9XU`~kGL$gA-$EZ7Hx0imCx(#?Q{c4p#xc@F@9&z|r#-~-eObZAQE zw{7L{+qVoBm-Il+oRL?|ZA55~MVPbB5WcIL!YZIS-i%-lMJtWkbzcV8MwW-_Diy!9 z()ab}AHCRENKSqe!)q^*Ca@jxMv|^Nf38;a2BRG!YaQt%Kuj87N%aa8mXEgRJx&jO zzu0H#=xj3wt+$lC=~;xTC3(yw0t0U#*8)D$`>KBe z%MrOG0L3}0l4IvBwI3k>a3hkUh2a}dcVrO)hVai%VR)!srX>%oX@7~2LzMsk%a^Q537y{09E;8 z-y-3Vapn7=J8eo02kr;PwRmjDqxcuiObI{EJ<}+I{Mlvu)oEojzlvl$QQx=t`oYFb?(8SkX0_k>LzYH5ASXPcy!9_{p9LlBv zw~9{%{N-2&0-rt*%al8{ANVlGLzQJgl=8(uwR0T+oeU6T$!BMtz{-DQI2N}NyoaZ? z@f{1}lP83JjclcidY5e#TmbFCHhy!GPo#ohfl=}MZOXSnWvohlTm_ZV85+#8U_?85 zUCAI*rOt2Y-~{db0%pKQkI2K|4#&2F4)663`^zhZdRfs_anj{JGlf3m?9F2$Xc73w zA$lrAXIyCBx#d~d8n5-39+pimf}|f)GG}GySmAo`<;k#)VTp%U^m)1hqqmU;$mNg1 zD3h}n^`~C`7x4Noxa$G8iU#4uOF@imnh@RSxZ2z>x0o?%-O$W(bE0^{YTf7T-r|?P zkQZ*07Qo$~M?)UpM*p5du+JljUBF~|aI6Bo(PU>|cb1dGYHFzLj>{?41Mv!7?gWRC zYXZ#7Gn}kFiRwGWwHVdCgFioErY@D`p=hQgVM9!}US`w;YsrF6l z1kC$ZL@&S}qB{e>}St^%W&n`sUcR8caW9a5e-R*<8S<&4q`4%ItTXmYV%-!!2iW9I7)x0tL?7~`9luampuHduFGptQ!l@OprCSp8HOCZNQ z%#?o^VK75V!PjKyfkj5*@k{bLy%S8EOyhx_AEbLE zDQt%H=s5>6>Moi(z@GzO!%1R!OMbNTdN+=Xhf;dr*@f6H9Sy48EIKy{9;wJGvVB15@syQ7=TN$@88ixb(K*x^oxxgv!3Z@vt^Y+a4hT8-SUnx%x zG08^ioAK>@Ct6Kj6`Gj9TrXp$|3Rji&L`y4_SNH55MwWWUq#>m{}Ce1>tqgyZTZP3 zNKQh$+-{v?-FAO$YFD)?D7eugk;E<~T4ZqGktj$~F&MA`_7uJI(J?&p4s>mI^ zv`1qG`%(R1lvGnAmQ$_eRrziBJrwa_VZJXYPAa_ai2Z;Rhh_cME%{?i&>)_YUb)+bhFVc&b7?C0EAe!6wJEE`Kq?qSBZ zpn{VW8q1YyFCu5@3qD0()b@s)&6;~{aX!^YbC=!=^+c)6NyD~LmTsW~#AbS&%(~23 zNE?ztCdm zS-;tG9Y|=p7GH4i*(?R-NGsr4KZy!5vzg3gv1ITV-{OhTMZQ7<=y6#A;om;3#V}r3o#dmf90GI;h-(vqCdWTT^CQF`%M_?$q;<6GM(g5^wJ@P4_ zbq}(EpM_aMHhLX{TGAGS;FY%(l6pH&}N#(HK2a1%E6BRw)gKkNoJe620&Y+&6`U_6)96hjmN<&Pi4{b@_v?H;mb^kridb zq7lp;_giGt1SXL_ss1x5HRLOAuu}qz>EnfekyapAxh?=40Tu)B2?_xyJ<6T~?dM8E z=1Kyb3@_{~IY0MxLe_@Ky#6ZoGs?SAdV3Av#H3d|fb4g`*rA3TNLIyPIEqJotIfdS zNj&4*uJO{Q+{@hdR~BLacrz^&yKe%+jis z%Zr@D!+3KSUBzK_O`JI1VW-q~6)}9#L|t){Uhm%7)<#zB^B6eD{$MUv5G%6l4PQ>H z6}o)IEMmGdJA&x;S^Uw|i=^*7_{vYlns}U~7a)fvg3`*N=w95h~di zhv^}+ZEb<98p=`A*$M&)=GBp~dFN%E>pyK~)Q}e61#V0^G!B-?e^*~cC3GxYYf?SL!GC6m4fAypN zNwELPum6~@ULMkm+?w>nj@8`ptx~w>eP`4&SYnA0K}dJ@+o97$#)R#4b|qr4ZkJpI z6Y;YHsbT7~zPk5~UQur=M)9(TZG=yK&F{{%i)<-@8m0b+^D^9Ty!tFxCI-%w2k@-F zt-EIV1`cqeY$WiK&}ZBHm6rs}*_pZw)9FkHywrciaMf|1JjT-3y_d}C#Tzk#7tZPQ zTjJU4XF}{V_xN|8(IP0;PCXh#4o-HMSDf}oX&pJ^&Jy(LYM0~K1&6XSMz-~Nyn77z zw9_7t1ZjXx%%aCyNp9k6*2A`5W`3p###|kHW`H5UBBQCrVa~@BtcU}bi)Iyk zRc1%#yLfedA4kL>)4rF5K1rRXgY|JaD5b#L-_>?MarBMn;DOqSMNra3Y-CH{d*C6- z6RZi^LgGk)$f7TpmU_%HbMgrbPNk^Z!UQpJJNK<4R&8vUqKcyc*JxLqHf?!Y?C#eu z;=N(d%!gWr2=HxRb^S7_45O*9S*m)Ns5%})##f3hz3k0j?;PB(pDXswXNw~Kgv|Tn zl2r_5hufctm|*d|iXhxpUfwn6q)P2IkiJ(o=S-4bwWLUw|NSxbvnrt)hZ|nWrS0aP z+PpBVK!Z)5sVVZUsiyf}*(23?7wsif13rx3kKpUd7olu|*an15QHgZeDYnU<%YWfk zz-PaEYIq5lMP$S67 zaMZz8I{4N#R!GyjMqk{m`|K)^Jn#3c%bIgIwgNZi5MJEZ$1fmy0W*xlmXwlvzJnK@?9jAKb4ljHqnTq@BO9X$|3u2mA zn&B<&UsYp`>r8e5Bg$WKkCQHs9T3%GOEHQAMLz`BYwx}WeB@#Fbqs5}R#8Tta5JD3 zYVe8*Tmfv#>tAv+Z@@GUR>Zdiz&A8# zW27%7U#q71NPSXde8lJ=!E{Beyi%WkNIuK_hf$d(FcTlG^b7it>`B72VE9IQs6 zSSGoz{rx}j>if80*^I(oiDOUhuNahHLgiHDR$nuXFl^^fBXiR=r~tF-U-=d#3ILyg zGX8gX3Uo=59wzr(90D${RdaT6TR%{Lah*BQr4^=mD+iGH+qz^oS zWra5SYE>g3gytQYP_a8{#$N%Yj=WKD5Oe%9EO(G7+JTLy^+x0>fR<%JDk$DLF>rs z66vWU%AIh$3;A*1=D&7xolpMiei6jKhJ}eUQ=rR{g*!ipkhYE!vT()H$5zIxh?7O>YaL6im<`_oN~ z((9PVpItY84GrKVsj|g zR;8l|CCAmx?3;UkVYF4i`p-3;Mtbuvn1|}9%AEw@M-6=&?ftN$ZV8u#p?abfJz{7F zQP={-;_os?O^cGQiai83Qdty@WQ|fx_Lo!{QfXw-SVyc3-$%$p=|N9WOA-Nq=wewT zLY)`iIQH`i7>yiggbWD#7{LKO`+adHF94vzfj8}td{BSI3vspv>}5WsGgO{#Txuivpo{s{1@_oTXN&X)e$$>j86x&&btHxKW#_5)2estUI##h z*ic-1*}LDnEB94Gy{*qC-`DUx8KffO1Nabp;d1t}`4BF2Bh>={^FH1T8&$KZwrM}K zT&+mBU8OMrMFQ-EaD|L6RjjU2<(bMWP5?dFu8fft98H%9IAlqN+f0&f7neJveqWa8g-fGyYArkxV#n>2mTb2u&Eo9Hk#+($R{%I*05Gx4;Rj7Du&()Tu}y86RYVwYjm zS09oCh+ftiKHIl#eBCXev^QI&9&G15Mxte3;43}-odEVCm-szXJx4AB`Bps~@j~W% z%uvFcc?f<}82fZ!&xy-5j_aXOW2i|^`r8LQb;?pD3|=^zIrm!}@AwNA>q$s)f2V)j zqdwBa5xLQ9M#a@C8jlBjKG+is?0=&?#?zr0tUH<1v3pI5NqBK*{{$)-xo)zbJZ}4X zVqUoxvwz`YaUexF7oRz)Y|_O~HZ$lWMa|#|C*l$6i9DIyiXnTvlxEx3&-?Rrwtf)R zy}@S|eTT|3+@20E_>V6yTLsLNPgUz5c5*;iylj|OD@h+@7~7>#iapJZ8eL218=lJZ zgfgvD;4d&njpCraPqe``} z!{`}vH+J@137r#t+fS0!Mtzf0=QRAVW80+yXk7H2-()uzdESeb^%kk}1oD(AAo{C- z@(-b>ZY|=t@fgyxaqna;F6AHW45I_nKc{#i{HpbrD1(ASy=3{1LZ!z6!N_h$wf61( zx5fSs%RP%&qu@RHu?+rfsj}o&*Seo}lV=}BZ=|sLUNZLwX_MGyp%hl{i1;jER6MTv zuvd&g&x{}9KS|-|;h@1|khF;Fs!$XW*ZdLw^P^-y=}SCe{>k1F10m| z&{P$!ES-dt9cq&k$;aYY;!&?s^^}yd=q`Onch5p{OMi!BYnBKG7jnm<)7}NGQBfqI zUKcUKbM9HjAJI`qgU5Sj7u|k+xB0e<{toK7J*NA_As_E6r|GjdT&h^_1)<1N4RsA#G zqkzi-P`mPGC{BHN1kNG!$Z1|UkioSM0tsM~p$28XramadRpDOH2;#VW(&42Xz<4dm zhw6ip2N)`+`1d$KQMe)GiLI*Z$Zifc25jM^aYRnlp7KB}bOndHHwblESCUGW*+cfR zz4fbu&^~H+f+1b)e3F)A{mqnSfETctb$5)!1}*0wU@wpZoTwu(oEPC3#di#kf7nI% z03c#Cbjh3W9!=1I>el!e91vna21P@eT@( zs3{K-93Y$tmrf>h#uz#{#Sg#~l1($7FGDmYzc&Q1G=_c$|6qjM8=Ad%rLg`15`K$n z9iLmy6AbL}?AV2r} zHkv4~Xhv}Eeg?L841Qg7t|3WMwBDLfy3Ag9A)}nSK`uJMgOn4p;d}jOMr}GN&cA|e` zMy?UR!FCEP)wHwdexB>B4WBGVPuQ}S9?y<=&YERE6z|K@TmiP?%X-`~ccRxUv%v#( zh%%p2*zNIVwXbxn*3De2eMq$+>=tgEN{U{3^mCB9beL+ylj^!T%+!WPCys^0Gw;=g z1-m!nll6lOmC5%*mBo&OV8!rl(b>nSDYTC8=Aa8lRzo6}5ocb;Q_nZ)7d2-C?pDtT zmy@xc&+p}V8*TgK$e)MmdI~R(0hfv9MuJ2#<91+5lKnD@iOAoaw0BOi?*1&WZ~kt; ziWc4o*5>D{xwpFvml#?$ohB{KuR=?I!8@v_Tq6FU&=fl&o&Af3$iXsoek6<_ZrGOE)k9I*nz<(BiMdM}8d_ zqbr{-RHJn%DW`+;Q19YYI7uqL7?kfeOdEMm{?h%!Lz2rBF#p9v{&O28-2||Xel5$~ zNc^^==31=uGVGDm>AlIk|3XQQDcb`PW#|fxj`BJ&C=+A*!ty0cCFxr*cldyyIjFM2O77iTn~-WU4Ra-u}}DyYE&sgPh|XP1{H7}{1dPv zL8^uVH>jIp;%}vgKbsY~Zc+dT{W@(rCdl)m31zQoQpA+|SIu3D$LU~H9e{-NB2iEP zm{XTwt?ki`oR_8yL_Zzr=~l4hq2WUT5#lfI{Sc_y9d{ zbTAE^GyLf#B?t{(_c4745Ku#-vZ4t-_qEc(pUUCvtjq@-k@6D+s*eYO&x(^PFr?w3 zpaSmy%W9$ke>bfWpG{`Z0$}GT44*<4sBz#8UGl{N3K7xt? z2IO=6>wkVv(FFh=dO|}40D}SUaAf2}{bDV9#xGI(6%JtW{XyL(Q%Nmil7%Go006v2 z8u2fD`Um0z+>P7~xFkRe31iSu5IeaULRk@(5qm;cSma1q=K(^Er#TrXLq)2yBh3(? zJcU74FP(6|002X7XdjO}<-wF98eK&@fZ_oIy`D_WYk!gvZcGkj=I|kIk^O7Pab`qV zx!{klh0(ghVOwl`s{d{3}ra zfTngZ@V~kjG;EIrVI2g`kP&wPOKnr1gPN2_@Tn*STL1-Ta#6Fz4mUm={L~2+s0pJohC{+z}Bn+UMMqZK)nOq*U{{UoUGWajKfajhu zzbu7y@Pc^bQliY%DJ%C=IC`{_e%nf_owB7x|7E1yE5ag=tp|F-r=Ru%eva;9;Zja~ z^GwMUuDoG-^UaExHTOK+yV0GNl4RFV350Rw{ACEda^mp2u4C}?{>907q#ywQ9XUlV zs3aDwSr|SZ;s67`)&=Y|+q`jCj*9rs;pAVX4aFu55y{b4Xqy_Nl#_0$yt!SU7BdXzDpUv+xJVa#eiZjnv?u(U1s8oxk-t4qk8Y@;h*;1=k+YKdbM>t!Bu$EIqZZ))ES+276w$$Hqx%Z4K|}#E3%Fn2h`F?zm6i7)l-=cZ z8l7pmGRrEX&Ld_{wjC%~n37bU+dYB;RDY}l$!7$?_w-t$encT0zS_D-&xzJ5CV zICzUeK0NX?=Op^!Rr#J7H^T&jsqM%oP~6)irc&p+E%S@yIw|a(gxMzCQypx{hmO~{ zJlyg{GyPy!I%d4JJZqg=6b>z?W?brZ$rfBm-Iam6)T~yACj7Nw1@|KQ(G0Fbdey^F zlY)Mp>Q}OiB}BRKa)vB1Y7JWA*>%rw6kw`}O>OeQJ?rszcYPaWdFz^0fwE4sU4NZH zytVP?oJlz>JL?c!()PQIu+#XKs`9{Qq6zhAyrv*{2@?RqMQbZyXNztRl% zG5_%GGw@-8AhgPt(mG<$v-!L!^9$oQF7$I}^dyo3cGa1d(P-TS#Hg)>45d0V%BRi9 z@iLgy=$@t#1f6F1xR*KdcgvdlJF-K&Z7wWX=eWD;Cel{YlRQim${90E;~Qe-QoFC6 zwN$Kb-|t8i9M-5DUL4?fiI;WzE>G`*`QKvCenZ7hin?)UfVv%yM1NSx@Ym5f$tc=oA#urd zuC2K5fnhZqnJ0Qd1(N?}FOd`I|E?BBrP2K010-IrKC(7;MyR#|r04GpKgGB-Q?dA< zU3kIJv61}AI+Ex@Wp^yC;R24Hc|gIkCs^4dRKFS~WE0~HWzj-heo8kk;p9tT2 zmvj8S2ICZek8kEq0$C))s75(-`avd1fyY$E?;udnvQ6o8-i(Wgb<4Ay$Fs;5Zd|1m zeC|feY{woK(w}`bDRZxf()1Y$X^?CcaESEc;GfxUAkzolEQ`{MGTaFGmA!s~qGWG@ zvW^M2+i%||%>pYjKBHcHDK3nYlt{@mr2$`H4JpD4pRJdkKugEHUPF!yV8?DBEP;e| zI<5+Et>FAc!^#ETr7XEx2+gqGb@qzc@Rx2 zFzO8d9+y@+>Y+!e5mc{XW9ZU{iCRK~FNx2As_cY-o*JDYXaXv|Q>lj$z=IrBsdVnE zMVxM57*2jqkY@R9tz90l2P&zt;V<;`2j%!yHV(H9lq;W+;p|~2(D=Xb%uWJf zIty5!*NK#PFRXQByks5kqXm9-M5w1?{qv~Wu3i7BoXI+e`USCIR%E39?)ASe~4z}W9zWWY3J%M z+9Tmzl;a!?a?VEW#3Y~= z#&%a!3FNknrzdT`Qc}tK#C{mY#_cyQwrZeR5%;2&Y0bp!XyB`Ol3Z22V)MZx0sM0? zNn5&_#}xobPVY(W5jQ5t7uZbv{CqK~0`5xQXLgwVn9aeET5qhsOyDl$Pf+LL@vUIh zxnUi(ZEqjJe)#uC@ ztTnbEe+${1_k(0D##YD1q63VD>;pRcl_73(-TX;i;gp)I@U7F*$JNw=Y%!~y@U&>CMaj|%|(5|$9VJ76~ID2pVITfBYFe?m%jH*IL zhu7GH-Sm|u^$t20rV+9aILN6hGX(Gb`f6eePm ztC&fqKq3B*?$SR7yHG$DHzZMtac;2Ez_J%Vi47&E(G2U}-)&>-?TI+)1dSV`ZWe7( z#Fz}V16%@WdtsHzmV4hq+cOM(X)2bnps7Nkd{D7DLbCkj>5Dd42lVE%ETeQyNZakv z$^oLf{@D%y#wOkl%fo0cHo< zM#KD;4a=Wo7*U0{Lp|Tyz1UOkls^`-VONPo@@TaAu? zIf;b?RV1}yJ&XyPZIpd+bwcv(7ZP2k2YxG&jgQBOe|dLAzks9J5e~Dr+OFWvv!{li zUYd3I97XOVXCDRa(8}*_!sz8K@fy%?HHkd&ubl6bJr@8YEl04n<0r zkjD!l5C~)s2@5;?;Zzy`iWW8nTII7Z^JTWvR2D$fL)zblv|siA$9^85!1GcbnR0lu zJWG|kyhZ^Oa$=^dIfV~PLP)V%B1OfM zC3yriCKreA1IL1TtrUs*$r~fG7emODwsC$8UvkDw%~q z_U~|-Q-;a90ky%sQEEY26oNA{8F@RII%BQ8P?VFdd3xYot>GKGc07a=9DVjtG@PI( zYFl#@U4kkAm5p8i`5mBu)&Mp9L}>5DXpAS05}?+Dv=zBMSNk_PihL__d(Hp{d;i&L zA~l%3jM3%r|N2#@>8}UmlWge#xDGN707uj1JUV<%l~lCMYzLe99bM8j9pn%6eQx)M znk{;qmWg|SuE0DXQ<2Dtlqj(1%nE^BD7n*IXc0?|=3V4gk8O?mSo}jgPBY)-d#tBW z-`;X|LP5mg_3t3SOKuf3RX~zHhO9Ut#nF+bj{g&|4E7)ZPQLyXIOy|u#qcmk>=%l} zGXSg&I7JDF>$DPLT-%nijZ!}=g@Z0>ZVRPA`T$b| z%=kFm91<5R=EII6&V736js$hw6c0RquR}#iom_?gDhj?XYf1IQ0E##i2R^RWuq4cM z7VjR5C)6R~JqYR1zaZFPPj4+I@bqbit`O;1aJ9FdFr@IpULe7(ONSW%e_?rtkK!N^ z8`Z5owmA`*_}&N$%@r0!xkO&m6Ypiz@HM2IU1mMMQtNb4~9_+`MBkP&-F z5cG+jxm5rF$x^BGoK!V@+hJ4k3x46_y*8MWK$*bAqdmsv;pUm$$zp)x9x_y}en-t` z1!VON2^c@An{aEi}T)hT8aSZg8A>2Ta*aIADWy|q44E{JiTMRvPFmLjvokPt*#fL?!E9E)9x!=gQ?FB2(iA3=c^D!-lCvFnOt?d ze_>Pzs__3KfdI&Kgy=_Ydj97=L{Y3?wP^#;@~^gDv9+jE+YG-o^~#4KLkhA!k$VjY zm7GG=`e8Pn1%lGZJNTCAHKn ziuRY5PN;g&`a^9QsTrc}InoQE!IlIaN3!McUV&E1&Z9nKn=AH5V(r7O()Zaj8U$ZF zDiRrEJ{#kmZO^B;<7>GrJ|>#cWkB|!$-JwLXLo7o;XorLU&x{@dgFR%Kg}Tl_bH1t zURObRVtZ6?R|Ry*z!NV}UlwqDh}Ky%T3$UQLD_dj(fYgxF6vg?JiCja7H1VXqQ{rVC(Y5=i|v1Y)!0oe7KH^)_L~e;0$d6gcX<<-;JE%dTytx;&bQ zNP(cD2}Te4bxj~k_JDCQMDSrFF5IdCUwjk*lQRu*$gBhIn)A^52uDs~_RzG;2b9VH zmjWOW*!O#8#5)6}grm2cSb_owIjd0i^f zWIkK3tt%}xM=#@3ANfv+-+oFVdVnx8m&qhWL?{<}Uxy3!LFLxv6_lgSX_U$84%y{| zGwyO?cArQZVv5i;=Mvs{6NwMZq{xzZ3`aQL6*AKVZcSL@+Wt)YU@1eZ?s?9T>WYa0OyBK~VF${AcON#x;Sd%8Eu9rwpG*t_c^aQ$d68+6GY=2DI;5w!~+A z=w-g?{o{C+Z*CNKvBaPI5wJLk41-?0MoQ8G?b0%81MG>%N_6WMnnhw{Mz=PWtZ;m?hfgYl192gI+gBr=|-faySrPu zkw&^hQb9mKLjLRTec$i@#SF7Mz|79M?&s`%uIsLoj_AD9YWWrJq+v1Yl! zDjDJZUUCIFqdC*#VAUu#lkNR5)h#^Fik`)xbTx z8?qQA4kP`5?+>@)uc`DOsH!Vj?MohBqJp_J+p|e;DP1^$;~popBrd_!aadjP?^om} zyq4}vxtb0u2L!AdI#HHJ9@rBE-4+I&zp)e(-WAM!CTi=73ir?d`N|}hoSEMKc0=99 zbt_s4j+U8yXdAg26YxWCE zbz}<;W!VGa^6>Vy;7NU+7vd#o6jT!fZwpTM4)KtfTF?)EDpz<5)aPRPmak^X)A?66 zjT;>>)u6cFuGg&Sl0hpU62+@n;X4`k(^UVc9EdSnP@~#0j23Ws(m(`NJeCrola43Q zPH>i~z(0&vM5p%o4AsIY(2gRle0kWE;Gf5)A|5NBc z!UYAQC8}%p`^d2zw<#3vYxs6YP~pqu&QzI3OX+adSLZfCyja*#I$S^2$Wrw<@VdKC za0`hO5{NQu4kX>;9=imqvBD?{ozGR^pOhGhl2#>JgNT6={FkM}T#H#ddOQH!JF(LY zh^>*min<5%7O20+_1+{!Pn5Mbg;j4XK5L#azX3r7x|4b}f93_s^U2kxe@qXoD;6BY z{}^YdO2BM`YpUzodA-Ds@BWn9JZi)wOC$f@@YB+oEU)0)iOy)9n?ail$D4={B4h&; zhy-;el_w-is=4BdL8hczT!v?g8am z$NnFFjiZJXS0^rAVLlIfgc`y4Gk0*=3IJXJY2ADU_ym0mW@RQrA@$T{r?Enj(Il`r zqo5OT8n6%j4E3|i+u!UidX~0@MNyu(-Rn!Sk*g&=wtoSXm_RB(Di1|}p`5Vfyh|?u zsB+|C8g0XEwU+^{VL()B*HI&CcVSQ=wTUs&hJOkJ8K3l8-i(Lh#dRwYrzI5tbe3j6 z(J7t2BvoYQQ-v-+{{9Su0FwyT|BK7QI5kdmsFsj~NPebl8h}>^U}0?uQUP0ll>KD> z7J^*Sr^Z#de$mY$#?bR_4i$h)f`)3%RAd`KC<8~v z21HmVJ*KUvj8x9@<}#vH0;MU|f=ZypJ2fERrwL9OiR>FJk*Nf{c3)YRNPrEmz!Zf! ze{jQ(GjLFFt`#>M7i|4tA<0aelK(Z7>Hk-nBYD=({~%o|$mtt%m0buj?nIVpD|(4G zyE_B4Ya%>UFl7t?0K#q>SE9~v{kP}PCKUH&tGEM)=Tj+M<*tPk;ERz(rsCCH#OKnO z`o3RQV@vEGV0px(Vc8nIA%NdWpGYvR63;|5KUv-FLmZX8v`{sJ`LH=z^|nIpcMHcD zMN(9rQqY~RcYmP@b1%-phr{|YPDV=q)`F}f?}peHMstvbaJnFJ$J^&bOMc4D;12b5XPW@61_HTJf?kU>Tl1i_l(Y z6mX`$d|{i6C9Qk;CWC;P0A>88Gbd#0iN4|s5q^-jgr!}lp7IS%FHu8)-R~{E80vj7 zNN9&bh4il}oQ9$ip%bz`a}~%q8#yr_=3(}OZ8K{2l*|Yb#Vt10>h46Y8J!2#Fw302ku|cmy zn2GpjiGp6QUnxTVs98lPwW2fhx@A`0SvkK74Cwb+CdLgA`L4vM4Bj7F?_BZad9O8R zadzy%YVmW}wOrZ7pt#O`Gc6e*QTwtt^J?R{yQ%5^+ zJRIEY&>7WdQE&wkAf{?1O3g5o*|aD2hrs;`U@g7m4np+%wR@;~YT+%(`6NPU1F$J2 zXL+|anvSD!RGOoJk8Z9UP$W7g-ocJrcYdCW`eSMSK$WYatgdU{(m*2F8^QV~rR)AG zBRTEuRH@%2aq5(RUf2Z&LR*_CND;n_?s#jdKVKH>Ee>fWFDe(}0?T>6$CP*Dnfu<* zFL^ekgorw;@eGjN=uH&?v-&jlan#d*_eidzQeJJimLk={8HRG%yu*3uaLd8VowMp-mA1N?Ey01(8ktM(l$qQ54uy!? zso$;>nXcZ~JemN`5?5>dQq=(KRTT?WNaM_vcF%W*$)R1U%ZHb}YwT>;u^M1lMCI=p z;f3~p&j|H{@pKg}(j@6)9D{2p0u;d+ylKJ3tHtkwCE3b{hRS8Ek}rZ0W&zC5xLRoj zGyk$rz1;Xk44+C(rPT`%2E*bVV1UZWN%ujvmiBe{8`+ÐAi>lSJj~bR9I#YADtT z`r_MHbcKRYKxc}+k$xFq_SJ?u{e+TBK=@5@6^o&zo~VxCqEUJ@3jl-a5D>QpMiVgC zJ#9u2t5l0TYw5CzNF;p!hGvRj5ZL|?1XyV1pP55o{xSeTuks53-eQ4*w&-(u0l+Dw z>Jh^C3II|QVKKD2Rp8KahJp$}PHlt2l>u>Z3ZK_SjdnOt;&TnI>_ZZWzvOcEc8i&&VX z{Vm(B0hhn)9EGjZ{(tJBzlo&oca`AKq5|2h4!t62y(Tm2+P^9m?1<3s3PRNq*GKVL z1{!JJ^gZ-b%yR*Anm4)AEb^4 z%5W;bHeKBwHu#l`nkvhGpoe@js+hhMH4>?sSm5w6nZv=ZxgJyR-I0KtqW68c43pbe z_8@ym0>azU5AoC9062eM0t+V&>9$Uk%jo+y5DlS&i8|Qfi|Y)-aty-~`#-TvNqM97 zV%C`^Ch|P}o_5D1wu6E*CBR1XEZ!JIJR?K?@_d0O>8n5BI-GX9qQbOyymb}zOoK_x zwl$DxC6=7^Sr%it*CL6#aF>a-~QKO}cK4LwcD87FBCZ;!AA?%5>_)_pgEz z&~f5S&ZVa?PuC1h!A#{U@V3GndbaW_vCpa93mNNwVhteYw>>GngW&hR%tH3W0d24S1{iP9nK?vnY8r_@ zPP9rE_H#U&4E!+5e8c}6$`JqM`j^eYW2=Sm-_n-S-KO{i{ZhM!G1Lt7Gr;*evgk-AnA3He2qcd?tScB0)#5= zRNLc1$BipwBow0vVhjBDZ~69fY9GE;jyC&`cuWnop4c*4RN%9+lksGN+QMkqY{exA zx&Fv~O&{wq%AF&=PQW()d8=7ZjNiVBzaaT*qymRL+P%-=lF4Z_oj64PQkdUEXSw>v z#qm1TR;qDbHo5>i>83=i`W90Kd#txqCn66xhe;=-(>`%AibXqMtvbBwU`_60 z2ldvxFpchSSsY}RcWCB!3a<9jzq3_b@xE!EQ`cCxh0zxipq`Ml*v*gu)Tx+*+3|s3 za1-Np{-c?B(l&k`_9xA`%P{U$;rP1`3(#lfveLO(3R)%}cgXdhHW8xzW-_|M17oV6 zx&<$?l^$h&R+RMX$9->w97GX|77%mZ$6V?h9(?Ta{JunkqLRPk1Hw?*@!b>Cr{k)z z`s(T`f)e-fgk+WqlGtL|YH^}@?bvrB$*aG^N=_PxhlE&p8ZI3?Pm}Ni#7O3<>^({m zgvYZ;qV8ASBPprrd`t4mH-x;aF__#loCf#EWqqQmNXW;%yufaqNZC z=So4=jZ0&G$nCP@MdWT&uH+3M<;{&5anAJccT`Ij@1R2k)6U#>ncs-x+wlY$W>cN3 z6P>Wn&I*p}$mM(alX=2;mf0(+C-b+l92YWJ9EFG_l_+5rat!mJ^Ao!`&DrTH{b*#j} zD~*083RMkum}|ddbHE%jnOvHPs+5>yS$%_a^*Uf(w)Hn3o{+UewR^JM@iK+(_&n*a zc7bA#HwcGdDbpUubAs=?rgJ75M87HQsT2%i+-o+Pt1L1Po?*9H$~e9m37s`Z0Ta8h z2enupYDbttUeX$T{BhABwq?nVNc}&x#HOsnBj6ytYE$W}~A;lWw>=G98Y)4@LqJ zBbq+cX}7lvvu13_FMZm6wG|W&@1`|$UeBpk>^u3phYjDiOl1h`fDx_o1>OuC930Pi z%Ma!X7_VTY*>v6bl$;?Z_L7TF@*YWmsD{F+ojC{mEj}jV1Ay^Gg!Om@`Sq2QcO9q& zRR<4^3+#{HP20RGFNKBb4N_gU-moM`KEew+ue3DIFN0kmM3mw zbgC1y2%}%KFD|dYG>Oo89MA?Ye{*}2aV>r8lGo^K6V4zubozB3OC?f{@hACjDo({@ zln^3>b2LoP8DK=NBnrVBlDdcEybEx==c=S9tHxYWz(9^mJfiogGmBKPDpR_CCCIX1 z`yL9HNV-n`u!GWwUHv8?_y$LQ#FiQ9j%9ub{9*vSPt zvVF;PWM5iU$G|B|fuhT!1_a=`hu-i0X7G;-5gDq$+?^`0_VYe;d(k z`uidN0EiH_JXrG>^uGsxDJ}qdzSJ}l-IR~G1_09ei^~MyYMKfF@YGD3Q=^ApD5AlB zfzb;vI1B3nu2!lSprX|gog=7ImN+5<+Fqb=fKgTj!A4YR$0JtWYUL|%2(Jr5!y4R6 z)Mne^t@Vlz!)|gQ%#}J1Aungx1c)BMHStV)<%nhp8)$Xl=45JKFp|LubUSg%uLY`5FTLiMd2+(kG=pChGrFp=D$<7 zf6#pF^MLorhUIy+SdPY1+vo)i@&Gm(npfa}c&eY6p){(Ea8M=AE`mHX5Nfg{A!UY^ ze*&T-l$KhhLl%p~6dqor-uo663umS)VfUk}a9`p~)P6(MwUOG@Yi+aN?D~u`VjGde z9aJUkttXJNs0%2jaa~7(ROr5hkH)-Ok`R%1*7Pe&V=ykiMAZ9FUZtf(nMRHW;lE!? zPrCscoPt#EGD&W-_dgn^V(kSJn+x+dBWb5WH1924UYQ|P{c;Y)%8QR|hoSokL-)VP z+<*lXfV*e8zCQB~BijM)n7 z*RFZx(J6&fQA2Oh9Df4Cg4_8x>P$&EZ9Knxp=O7TM*u>bes1}q5rIuau{B`?xn*=M zCklNaCK1V2t03=JnPs-QXC5fg<)sHf?K0Tj?2rp(yEuaB%g(Fcj7l(1Cuwy7R(_d) zZ%<@AH0%zXbfH#MUJ7X7Cs9PPYx0}ltVW-kbWWmbcbW0*$eQv52_bMJS<*luGtp1& z^_XL&P8_)Mf9i*OgZ{b;SmGaA^=}6IpIMEtKFY&?-^-(w)QdDWjm0EVS|3UeDkOg} zCEQ*uwZ#!5zc-A-r_m27QI9$aY}0qOsOakoCf#U~lIQ~(B_xrVBmjUHJ}C6;CfA!N zNC~Z;R4ZwLqpDWS?12_ZjYtpl7NFB{%=o+4vB?;CvEVKMBT`tdRTv3?cbLES8nyg3 z+>BHxIga;vQ~6Bt1gQ*UnnMK$QI|n-F0c}&dba`gJODt!l*|nJCj<5mEB#kxGaTph z+}cbGr{|8op~e}Nh;iS@HUJ9tR*uW&ZJi!`);-?4$6vnBJ}cO`!-(??PFc2qD}0!O zQ~Wb$CZm(k(8s#RCEW+a$>wp_QnYbUCH!`E<(GEZ)t=Hwfx*J|KAl)EeQ|kKm(=8$ zv*uSx=`z}*|E?xb&ZCDw*XzCE;At~iMK;%JZ+f42jHz=u3LZVZ@+pH!IO@_3di5)~ zQwwoFLmy*EePp-*)(g{gYg+1)jzp(?54sWZu)Tt)YTM|V>EUs_N;~LV7biKDTZQ`V zI&sRDFC*D%aelp-lontgxqZKS2nE!c#}U_Q)m;b|J{aLorIx=Pb$X*GaUvAvP<%mf zEL72Lff3o6X=O?Uw_ZB@QhE@!R}*Q>TJXuIU)*uoYKnYr--pxrP+oKWxYJV*Ho}(J zdnO5KNg;msO@#&x3osUHs!m>UQ4CHNJl)miIOEU|OKDYJeIulWA)xO!@$F;k=BIeV zU|f@$8Cjw{G9u;WPz~3X?EZ+2569Y1zIzWZkN>zQqzMn(V{fjs2$kse@UL)i6NYVc z>ufRuoBJFhS;A>L-;dVY!+kPAeWh(lb}rdQ-wxf~1;V4Z_gC7~%p2th0t#B*gsWBO ztdY&X~C-kQh-D+tfXY;h;JL9<`~hKL10h}={)s&BNZ`p->M*mHz=*${tw)WWmw3^`Gd$5BUUR8OiJP{jwJ$^q+`2B$Do)%?z9b;~M0%U;Eki+FtM*akJ&_8f#mnoKVhS6uW;8 z<#}Q$+$o~^{NUS){=D!SFW{zM&3z-b#!*5z;@as|yZM?XYO6MdYDJ4sYUlTAn~-VZ zS>A4L%0I0-+Q?0Q{6YfOAf%14^}3_+D3UMFTD9{lmkW0n2Vd{loW0x|v%#W2`ss!o zX|3m42K;<~b$*$2L2Oit5)?c0T_*O+bZyd!{Up-30|H}aJ8E3@`=W87`Hi>0Eg*!3 ztEGOadKS_ec(-wdU{s%vkaY6`Vy?G+%2PcO=oi|sgRR@+P#cw1F8eG`VqTn~3daSO z`u$}y&G3PN&z-P-g0m#0aQG}kTdr?SvM->U;}?mXe61_kRNs#6P*qI;Ygg(LGdVIK zS?Q^uQ)V5iaLi}^Lqz*6r0ccgnJ}N1x}0kY?#g&HF4=Pk5}Qxo3=>ttxP-H%YKg9~ z`~7DL94@Ki=*yf68NM274g|r~_e}~m8jBE@=ZG)LMwrT9Z@O4iuISv694?SZ`l!Dw zy1s1+yz)i`DvQ&jSX4WNu`JY^l00W#trbvP75NnXs7$A>HZ3(mq20dcUv>wY@zioy zB1Q!)-Z>7Ju+6;d2guLvJZEm*m7>EMt+Of>lisHC(*q5YgVE{?JQ$^Qm3R>ppf}}astUl&Vu23Wc9foR^B&z zBnw4GdKSN?Ht>{DOJo$b@f_Ld`g*NCd3+f}b+I%-WMwgn0sZVrab=#H{d2Os1<}|3 zKSxEbX)pbL?#VPQ^VZ$|nGSGBmD4lUL;Brt-GW;?%r|za<{9C5=y96$#@BT((qgrb ztGt6JWrw}JQV!vY5Ldee!DA7g5qE<5X@R5#cQvNKWjLH1v!v8(=pzFAIYVG&ULSx2<0r?1fkw@wTOgYtUi-`@tm$a9iFS+$} zjwaw$SOuD1VGYX#AOFq(UQ*-pDxkBKz1+B)r%4J@*=}5mfXB3_48h+_X4OPQ3D*wl zo0w`-0dGi%n=qgD>*j%O5YKI7kq3*uP%VM-R(0eM2MP1?0(NTjvN*VkCfc4LH zcQ}lHbTJ&a%A3aHPvFdf%lQEikr$nO{}WPp6qC8$rQSU84q4HWD80F&5{)bzy$$KJ zi)X(urWQ$uz8UGS7^iAEWQon~m6~qpG}5+GHP;8IOO7G6#c77|uw z;I2;_7{B^77o-j6(^KUCt)WSgNtGZqUAdqxJUtH=aYat5kn?AH9%$0nTK!H-rwyam z2v`fyDZ^W!4}I0lPl4{s2A}dB+03a$?+oK0Hc*h;Y>-@psaHj?FOSqVpUUNC9}j;Wkh;BCt=2I9yMrj6?m81 zZ7`)FJ`lFtwOBSE_gnnbRaD(qTrb+tYtSaz)#YPh$=y^&+Tw$ni>cC^wNmju0hD%W zOM}5Ok=ndW?i3&)xk&Z&f||Uv z9&$>I&!`;VvkxM7=xcZ}3Z&4>;g)UXWX%DC5&$dtPaR9x1&y6e-)8fN%ZWazJ8@D4 zeL&ow4rhKYK0y|^)Q#oDy3SMGSchADbtG2ca}$PFo7@9$BynS?qFq&;Oc)N=sjr$F zgx!=U`Nka;n_rU8-s<10LE03HBvsOy0Hn3#ge5M+vEL9Ozqm z`))AUBs;Mj>jW<}C$#mH`pmrYB|-S8$I>(Dugk-EA_C^fCT3YY>OvLx>d@oyr?N5i z0rCJBYqa9~0^wVY;VIume4Mr*+prLtM^LrePZ1&B3ayMWm&mwJYFEs%`L9_Q3jM(q zP4<10BA&YjO?V$brTM{^^o;EZ{U=e(VUzg}p&AQjS1<8Rv>Gc+vGpRl1s=4K}d2CKNr13Wic_4Fv#_7i7O$ZZh&C&z_gJj~ zLZ0ghdokc(qmQBYfOhznVE$u3G$W?R!=*ZT85L|Rc)`#qyVn|IecL;{UbJaJA1l#v z4IyW`6FILi?!VIhX#LKXV_kPyisZ+?*9j{qgaRn1iC<5aVXJtiHbWXNxID%plj!;8lT@(C~ zJiPJ-#06I03pu9G$9?T+$4OeT!@2KIOGlU(z9#!wvkHaLsr1mk8vSb}O*(o|9RSo$ zzcE1dI{U?-d!zI2s>`DShy@2_GCfDz8}th`G#N`ch_V|7RMy_r3z6H=yxpo3yfRss z(NXFf-(Gw00Ued;;QLrC;xDCziM@O$#!3K=2x92a+^axSjp#quesQUpk%d<5rn;?< z83nnBmkFNoALv9=<}od}&{xEUN0T+LyF^IkE+MyT0$bs}B8N6ZY%-4EEtg&iN1Lh3 z_=JkUvlQ$dD3_fwQ?=Zn5jod6?VFRbs=5{UG#uSyn5wQ#!lL5vu%SGOvj5bk{d=mfc7Q|71ykaLmQwh~0J}8bd zs5Y;Y^<~iL;dmPWbgcYr+6!0~q{u%$?Sz;|q$aE<7F>NieJzj>tndDM=X=?niBd&- z0Y%wG<=Kmm^t={E#BdY99~LT^+yj$rZhtNIgwITNi|MQ-QQ1i(+GelK5lkP(qv~|T zlCKJ~JlKy4_rO9pI3uzHxujo3TcVrFO6MO@xJ;^##B+n}LsQt8(OibGhHKe>uIHE` z2=a21VaN9r>SE|jxV{w2r^WxiH09!uPI!*`IzwhXAW&qdCZXx-X=yvbIMv&Gexr96 zW#&D*af8&Yso5hO2L82FxYxe$H~LSYGH*M_#J7kp=g63GvmF8@W_D~U^bQKf%lf1) zdN|nP=I$5?iL>2*P8WW`*I`yrQ=?i_G7UO;h{buUzcO{mzs9W~XOi8(IPjZn%)eRk zYzQn16G|h)W5q73FrYJUve1@sAE#*wni|WMM6cYJSI;F2v;Kkg`lCEAqFpa=(7Wr& zE=`Ilh^K(0m4nf!8**#otHBLEiaTi@E_p6Tn}{7vyjz>wxY2it@R71oE?&{tegDjM z9To-GsENGM)~WQnKXS;1A{s}ooH{52q$S1lx>)b?gPG;@guDG->ZL6{@xbs+aN(}Q z2q;y2MH15}Hj#hbV(C8Q$-4NS?H5&9;W5rxi1p+@RU{kJyrApMWMCT>o9I@}y;qI`;#9<@CPGs(`=@apLX-(4f+1(Kss-IV$ zNBlL#=e|<6v3<#Aej8rY|8}s0APZkx1AdU8u5xDa{ksHOBOb9#!tF>kbArht#|n;- zI~w9b<=VG(%Aiv!-;ViIZS zf!@*&4%X>-CKDt~gCsvg#0lVC6%>R;`b?-1_Ap!SKfG%tY9>r2Gl+TrM?RLHbzIMt zvLoaENqFPUbtPKs$9Y`5!5ylpX&ufdTTQ$NYCqDY8w09<@4?v@WPp*C`l%Z^(~!g$ znxA{@Ww|4ap>?)ul3{q?L^)$!10Pwd)u4hj?|br#t*xrIm7_AH(jPU@f}2Shtr?IGAE?Psq1uiW^dq*Z}mQZ z&2V;jP5y>z{~TGy#Qq)D(daBvfhzkKvn%3tb_K)toTmOf?G*Hdz4L>6F*2HCm`l3a zqse#Z*zG-3tBYgq7L4s-PBi7li0AMDCX11S7h!@#p{s}jrwI?3a;srwW*Ge z=7*-GH18u@u}U+AzU@96f7Z}uw8`M{n~c7-A@kPt41ORGkPO;&&L zW`Xi|dobzhC)X$T@Q>K1Fux9GBbl52R~Mm-H4mt{c1h?*=&tIOwKn8|swQmu>VY~fUZu-9 zBTs|V z`Ddjgw8D3=#n-S)s0kx#TZ5*3OgE>BhbVEwRtP844-7sa`mu9m^?1Hf(xiBjbvC6C z&(A00s-aRKy{KiUq@c0t5+=(1&P$$RfZio@_}Dv?_IIu1btC(yksdj*fxfYDxC-tB%g^CMtuGf8i4Q9ba~j10d<#k{(-ard7yM^y*qLRyv?)vIh7ITJNyVs zg)CXD3nY63{ZA9$lap5zHwB|E#H*!eP5srM0_UTX6c-xir02`8S7jNoFYj`+qFNG@ z_~mh088^d4-nsRF|E#3hFbSeQp?&Fk%d-Xz$2T*c1s)hagU$x63q$e+o~{$o8LiX- zVj0@C72ZUoKlJ->We8071KTVp4`u##83vy?Cn7^QaUL7Gr*`Sr_c|FIRxIfk&35=P z?r_BrDou@s1QQXr^_dNLK8yPbE(1ueg2QoIvNF$0$ALfCXKW1$&UekqvgHs#CivIi zNQxd5d!6ty>~`le`3)m`2({4~c(8?}rGI&z@p@yhVz|e!vm%5s55TjU;9{*WVa|}$ zAr>h!bbc?emWRApZhDMNc?pdlp1Ox*PIz7g%srTjGdsYB83Qm@oTqI2S|D z3O^Gd0WkKa2+GZmearf6Aj>w@j{Q&F4U%@lZ2D$NFDQLx+8C8Y;&BkSxh;;8d4$y! z!Pcqgx29Xa;SgzaWan4BRjWm(HOe9(vlwg!)e0WAFT3r^#YJgfLj4e^oalCO`;KK7 z=gNsYFGQqH;Dh|qLL~axrNL|_JZ2TJxU09;i@TDk7cWxhPHd*>U$p74Z!B5UIY9+aMfoLVqi&#wc-nfQGlFD|; zaEz9f+2Z00O(Q9Bm)V-EIu%lVMo@!}28>pL_+Zwof>{&H#$Nr&Qtj^+mXi;aOPK&t zf3S1wwa_bAQhE1BF~mZRNhdVsGSkQ~sOxr%u4p$m8oWL5mq>--yiLn!yDOB>D1DDT zP>Pv~w@K;IAVe*EQuizJJWJK4OI|+QgQQa8S;uW0l&Hut!tn$slwR$kUjYnni}xGF zG`Dy+OpSI(^Af1!to}m>!=N+bS2L5^B>=U7VA)<>CfjLyZM0C8vTum~V0iAL6L&6) z`o!uDi zQSkR{l*=iGx~6drXY=62rEvMNOQ{E6C(osVy#mx_9K={lD;MvAy^k@Je0FdLgN3kk_m5NRQ!HM-An)@5heKV)nUDeM%FGMoEN>h%I}r zqEl)bf!>yM+vkSo)0kHd4kHwS6fp>ou`W0nBA<(<<6&*rp>7is?z^Aa#4z-U@B7gr z*Lu%ZkRXdUfy9|7Y04E{uX(Nde>^3~H-?k;BaiTK(DWNCe0=P}B1ReGYcBJpdNDYJ zs07zWR2p1O1zmztqG}Q$pU$bSnf42C6C76;ofn)lHm6g_<^C}zA0^r6tvWz}8cG5H z@Eep{fc75)p)9bdQ(*nuNB;Gcn5p*FrLW=buMGHhQmcPxDtQCmP{cqs0Pp0-jBpvI zj+p6*>^3K&T~$Mu*yV)!FCKUrA|%k)I9Ph`2=+OkrqAJXRN>8Amup!tJr8<=_O5PQ zz>V7&wO~C>>X{T1lqS(&wrhxW;TVDk;AFV9A@_*PtIvy4_*yoVYaH(F|BUg))#FOt zj&hhrbnsZt^Aj~2aFm4&eZVg%LL+%1=(l$0QE*26(c<^YW62f^Gr4NWlmuQE4|G6; z^zG}%X5)^~gY=Qkp}vDV4iFY|U}Cu=-4%f_cM_Ajkzd zw{*F`D@bzcf`7*`5moaOV~zGPH+8{FD@Sj!;A~+~z=^JPh^2Si=-sXtHlpcM1)cWK zD{a)=Lwvt`tajj$P)V1$9ZM!p|}vdNBeZXyUeIjS9@I(G+bO zuOCCH^!=)^#QVl)puW=Z!m*d?ATa0T=dhp3?JFHSi(zTv>rZdK%ElV=52fKR8FR_{ zisOP4etNpiLM8jmM7r7o59oiKU$c|MpIOO=qJB7ND&2pD@lgn40h0zTgtjR2VzeQu zNT}=}e?_-}xi7gW#>z>{pjTXQK?^^93wPjr>_nU5&2xKLW^ln%COv1Y6|VwlhqeB; zTdk*pWC}I{^TX?TC`@(ANM;r?{Hr7Kzed5r^1%qFj%q)udQ{+K(dd`uf?z_Qc-h{;Q{D+LF9ba*ow+RrvV4ScfN`3Q&*K zfjj^qbQ*Q$e&k(mzvH;AJp$z3)VASPH1eA?WGfL1I2@)bxlCs^Si9i5w3j!7%{jy@NZfBVQ zIn}59Lr=FL6h!9}^Q2D?A3Jg3{d}}s+Sv)Rn;kXW9U#~l{O~5TN4TQFP>YR+c_U@* zot>7S9X;b?OsLMjqi(Wr~|(85)vgH9WyhCaaInzn}@fhnbi6i7JzMH z-@<|gW%_X}Sc(yu@O7##yb5WZ{Qtno=IwQ|quL5c7s_dr;DkvihEl$)7t z@~3g*2W?06g-Ghs=g-?ZyN7D~fs}I013o32#hzv3=Zl8aIxbO1?y4%b9~y87#=ov9 z6@9JG_402agtb0+byE(!clnq%u=TsJJ3{Vs0Q#XSAiM2FJ*vboUc%6a_Lz-3 zDfsh(5gprAZvqYsJ>B}AfUb{*Cy?^tO)o;zEIs0?0()#SLU$IIj6S-&~A{=4$Wv8`ZkEx|IgCTu&JR@Z3Kirr$T@Obl?^(Lu)-}B;xQz3)dpWo#q-V4AC~=+QvG-I`!XjUW-EzNT?#>%l;9&iwyhFI2 zkf`823pdh&di@rHlH8S&20e?OH_}cMa>l!n{k$mYpORRAr?4tC@@7o*4*7BL*THkGF z>F95NtS7V=R-U5GLX)ECc3LZ`AZ#U`Y7$>OHG9r#-)qv^ex5+1?W*N)hbwQ3>MOWd zmuz{I;ZzLR7%P~Z>s>u;(7y33oznIiLivPFL{KiYkt5u|gg98s#W+t?P*$&;cmLe$ zODmWoY$kv6OUx~yqAKWxfmn`h-DN(}FS8-Y7oT1e9TGC5)XJvo7cH=BB6h529{qbM z#h3PJ=Zw2+FJ!TIyk;1sL=fl87=#m4hlO#FQm!tqn=DS|A}j?JaJuO?e}?K%(lcQ* z2@L*_&J7uIcBY0$=+=$J8hS=RE#C#aE_4~>K0j0X1xUZ=jqJe~)|t0c<9}rTEj}a{ z@)O?CC-eKfS>nXU@ptGXsqnEcNW|xU@y~?N+XHSb%IA13=Q|`aL%(GPv@#lQ|9Ed- z%%pz+&o<>@n&rJ~z^2aLS9U%|E_h!O$mkr@g_W$KiS|xaxiVpJ{`kq3`DW=y0}#1_ z5P-jDTt_ZkoG2XNFe1Ik1JcaP`wz0weBB`}x>IS7&=Lm+@A2Ah z^Ql}aj>bl46inu|Naj{l{Y&PFA98Qd)vNz5VgLBF`Vq0#Fk0^0D$cnh|L^cxiOG82 zV>E*xl$2as00>}fcIMlTFa?^z7xrV|Lf=x?6DN1gkmjl`cP{ho#;?}*;v{%YPy`zq zSi9ZPQ0FlmNgxJBgVhTcvZFOVAt#gb6F=vGX>4J&Rcnj-0w$BjFY!m#Zzk#~b0(9o*xCAF< z7EW$(v}yg~UA|KlI%vUjYP`RqK#=sQQP@1CK-l z;MhGvxb=nLn9YMeH#U8!HVMB$>Tnv5!GgtDpwZ!oPt2j^^nLrzXw8uYvTI%kH~YQp ziMc8f!!FN35sT9Ap0t5$+xG&yRvUN{{XOK1N9}Ys$oGpHSn852_C^c25J;r?np1r^ zoXMfMfZ8aj{Yz%X3uC@dQ4O4hq4=?bq6_F@$-0k6^p43fCu?X25lAym)W~Q;U<0x+ z2x(Z8vODpfjp$FKBJoRd{+}AUERPsT;VG(WGL%JYsTpFTd6D?@KW(w!GMT-Y`(h+X zPpn1IRnX${!R)hS0H1%l^fP?RLyLvV`E#}0?i}cm&QQod+xrUZ1pciz4^PfQYKdap zl{|yxd@xx`_3``0D;33;NkguT7T&TG9c8n?Sv0XXF85plpO1UozRWu=f%FwYNV{WzCbpu3?CXLu`pxQmB#f-e<(xjDli*sK>+ zN5Q`9&h3;zdvgw0kt6)1A!{Zw*DU+W)hv?6SPz2rsDdCcv;P(AU_(E;|JWMF{t@mV z*SAosKYgjy@eneA*%XY50)Uoqq&!l=XyCE}m{LF{F%{E`A%S>u+t5hCnqEpgNkboH zIuOsozMmSLdGowYIX-A=*#DZyFf1*b6 z2e%Cmfu&T}Vj=RgPS187mn|KK6y8cOUJ7{2TGCCT>E{O41htQXu$Rqbk7Fo&S~88G z9D`^Bvpm)4iBXlTz$;uDaTbbI!!LOI@PeQ-j)TO#o2JI0m7v~e&v{NmLi?Ui&$4z0 zT5*QUDqN_}OhwSirgaVa`BPL2Grp%W=|h+uJYaVC;$92Ze*d!4`M(SS>WM+TT7Jjx z7($lm`0kbLd+^qmI4BVFHnp?&?_57K2}T1NCwW%w?NSwhj9g)m8q)R&!2P_MBAVnh ztHWz(YbdIgQS}qqT;x+qTX%#Vbc==*Wz?(XU}hsFx2|!poG5|!kL!_81&+(9xQ+Td z6n0*XafVPl69Rm}f(V^dxK#~s+g(PYnbwqpN`kV3$cdo*3w2GouUbD(ID_|TJMmtq zid0FPoYW=TO-JEhKMYE44ylubAMT!q>6(uc9VTOMRGyGqf{#SGU>!-`4kD2A? zJ}oU7!HoelMvsr_-~jC+BV%@Dgtd2jyTR2c0Fo0>h9XmEOeG@P4FN`(ne3o!wa8x< z!l>1#_TzlI$1lL1Xl8r?`eU&WXM5W>108o7eh!#>O#H=~xS=eY6g2ql;;x8up$jbhC@_XZr=S;44sW<6j;B|1H=E{9=&c z1iG;16vRGG8kX&*2^sEf^Qm&vJ@y(607yy;06o*&0E{g8{-8JVAp6m<^q}B3Uu?J2 z8Axl4kVcWXkf5fyHSmFgQk$7Iw%tvr;!{pp5;g_>Uuky-+Nr!>En6R}A${;?IgTp; z@g?-q9SitWN$-aNA+Z+RpOQrf=j@82Y^v*8Xb91yv%V6eGq$%b8wV&7! z2n(ud?wai3!JXjl?(XjH?h@Py1cxxVy95mm!Ciy9ySqaO?#?%Po_BY@{cjZo z%&({^`pmuEeQx(Xt#H4?BgkO$vMWms00x(y&P}PQamL!tpF@#-GlajeW{`|9*4CgE zi4V~`y)~Z5(cF$6#+3D&`mke{ude~uQN$NXpe_&@VwS3FuN7?TyUJxZ&u`2Aw(j<5 zOi=AcPB?cUM(wn9qQQu;{U$u((-@AZHs4{egtOW5lg!q9bN-S4czQa!P+pL;4gMHJ zLLpg1GaLRxLjPNOADsFFg1W73W7Yyg91ZHEhVC!QQi?Pa=yTd25Ab)vg6ZnhGM7Vq z+RJ5LT}e`?FZ#jCWaTf%Pw|r3;Yg5;Zc>14-}AcSERc)>&iKwtJ&^1hJ`HX%UyqSv z5v>{Sgq*YGy7$j}>Ej~?%hcv#0|BU7N9%BFqHZrI8$Mp5wHIolRH5}{XSgP^<}B^B z=>R};wdPb(>gJ>KuZnB}$?qI}4+-c$NeGH3X~#@SZ%4|D=PswPY@mj18PDt`!=U6V zpNu+}#X1fAeXp6BZoJ+W(X1>3p{9~EkZ|=S8>^7x`GDMrPFP%pih>YcV{lpm+guuM z9^Z0uk6kUU$5XZh3Ua^5T-osaBv?Xullk+lx`+s(J?>IXis@uRoWUmH@iV<5L|l~6 z4HnhmM_>aSrv5KjYuf_gKCwI-3Tt>KPUp#K)^!%Qa-{%C^2qP@<1_t1dLbE}g#aW; z5raqVIeFmkR#_&W*5A7F`a@P~kz4e~Gu04JKVnB-VzUKe+OCKMW`2_RzRId+i<2+^ z+#sCxI$Ac+=hl@`dzI&ZoH&oGDUN0>51-NJlZM623*mk0xXd6ahFP63J5}iL$l!ado0OnA@<*8wFZ?} zc&Qoc+p)~LxNJczm33c6{IJ$whge(p1dSGRm{n1_F1OXzFyIsCp-P~E zkzWT@TOW?u9A(}-4-%y}J4SV8fM1+61 zj9Qna)1RD!38iJBCH7Tf=uNnxL$ueP({s}1#l#~GVd*d8M6U)8%JQCS4<4>=CE~@f zzR1VxiucSKr!vU2O%aoONqU&NZCd(^w&_;(f95qBMxf4XgvCyC`H?*tJHhIE>hSt! zaWinEdja(w|4jDOqS%=QkEA{*?2az-c0--wg8&Y$^1UeT;Km`xuWGVSW?+D0unhcz zTndZ(YH8&ToRCAg5JNW76!Yc7{8QaLocyUyq}7CebnBykH2zt|y@$q>Y2?yeLaGy~|7Nk4M!#`>#AXZLHW;tnf`{5gAOhHu z2SO|YSwt^gF-XX$9c(5Z6ZMz8t!Ws!R+mog8ln_B<_I|gLzI+USMPzJcG?RT>?wO? zj`=W+f=eHL?;Az|2tAXS0KXKYTTWqR0y%{Mf-gCSQ)0W!N*K%g5gJs^m&n+%0B|~S zm7SM!mmkj+U}J&U{0B5^yKT9WZ%SNPUFe}={q}YJyH`_AcEqR5Z3j;pL%`nBpwc1? zW-$eX;se&`pb58BvG*GbR{CCAfb!@R^9mC;?d^^LO+u+TxurmxLGOjg;`v(#C3wnR zKxGA#Nk7V06>ZENz$FK^_lo8N__}I5;?4u2@0w?lo)8s~K1Q81iY02?<#t*iskJ$; z3Q%`KsG!uH)UT&&%U4n|-fhCL%wy|eE z$~6pRN2tX85@&>STNQnV1Ae3|cl`b=8(I%Gv-K;r5^}YA#<_hNRd;q zP3EhpAFB%N^4ahB$5_}GPQFli!=`Z!_TR+ss<(bTI|fQvSdBe_yd@rhwNucEJ{S{N zPM-oOnFlN=3V|Y;p*IT<#vByc8oMFQFBrg5U1L{DWAa=C5=wWd*cbzknkj)A`~ZT2 zc#sxSetH|gn&3_(DKdnB(vTDA@MX9tQ?3iRShX&4FLC)Fo_lrwKw}}(INx5 zyqe~=dX;(sX8>b;^(t&SS!`pH|DGMo9B1p^#iT6ddZOZMI9s52S z1H}oJDZCVeZYTQ$#b)a*8~iO#4J-!1+~SPYwqka0A3GUJM2O2XKkzgCM2#n{Ec-87 zsfNX4nhMRzNK%BgghN>M7+y9EH=pMhL_`B;b?=Tm%ldmIS8DdF-1R%*3>@Vy5H}F|*QS+{+it!W2}fBBGk*Z0%j80tWTGdK5dbjEYleM!GMAZV zdaN~0A<#3*E`R!}aHr?8kY!SOWa|Y=fo>D>d0-(R(rw=Ykg%)h1fOvJ_;&0bOH;jE ztw|uoLI9WPb{kj-)XPhqYbP=>Y%$&K@TQnme@Z}?L*j8&f+c}xp~96qU-{eol9LSIdd0YX7ZvC1X9Z@3h& zNy=is_V-H1{X30b?G~z?5|}9fpgs^80}BH5q)3+mZ-a!9SIV}hl zYqvO5^qW8@Ji-dkk-PIr4>$^^j~`>N+bNrBx0B7G2?;-8JL?2fZX*P zMGcZbU9lgbZ{3mFb*EJ@1wV)y1%K0jK=jM@7^JS*+l;m{%o&3J;0336LmpY7XE19) zER>O+<*^oMtur#^zNAD{Or;%Q!K4=*Alyw|&DD{WsKl#|VfEdLbBXyfWmRL9$2{?d zWc3F&5a>I?2zT9WqTqK7#R)RI17tRcWdefh{>Si7e=8tBaEKNFA;{qWuplsi0szeA zC+Ib}3?hNcf1V4}hZ<4|hhHXT(VlQrMd_r#-F-UN<)I;VQ^&~W?S(|qyZYw1=-jg% zxxItK68<4-Gv^tsS)kSi&5h2uow?b4 z_WT&>FL-y8sY_>#NNwfgE)gmW(2#&YcKEXng6Kci|43)tf(-b}*4+O4KLyyek%0`L z|B3}+Zc%oVtqYip%@%6|FgvM$=F8A*1HevXc8v32Y2n5E6!0a`#4!{aMetp%(MI9c zGyvccdX|#gm@IwFwJSRHohLp=gFV|)p;^ELrL)|J#LJ;c>o7QAHoFuz=F0%;^qjYleLP++y$cU+4 z@|(FHPeHAq3JH{M|7}k0|I4wK3iGx8n!Zmn20)Gf2ZTYA3R)AK?s_npT|4RnY|a|z z;81I%8x_bB8UQyGgHb5(lLlgi3s{HP80WBXNT6E)Jez(p7_CcXZ{L^pPyj&Y&tWGx z8xk8Q{i>N&Hx(P0lUu*MY~U1sdxfhu^*bB0Q7?=h67hUj86Xdn_sc{wRwLS?n0-|B z3PTl9BxQT^u-~?gQOA#0=y;{(Fym$=1)3V;mT-JK$+8_34TVk%pK+NT8fW7?x?g?Gb(#Tn0!ArW;am1>S)$7?l$;2wGWaY5&C_X2FOp=M1A!u6K`|r6m;QkPszu(cI|G0ck z>UBs$oY6KT1Rpf=+YckSRfehUSR}*Xx8AOVH7xKK={V?J8Q#ABN2P$ipD`$mO4FW% z)LeZ{-KJXP6oOBn*^=rKs>kZ0Ct+^3~b?z5SpVjikgS5(eau8P*z zOU5|*NBg*2Js8Pnwy_JFN6`U60ul4LF83rkJyLUwVz_%@$ahdM zn~r{?qW9O87K~&8;-UR+AsKXCmvI~vUkZO#5Lqx}#33jC)(Sh~;3pO)tfBc7CU1)g z{ZS`Q>0C5DWO)hO4|dXN3V|Z0b!?vElX4q9IS^$jRjjQ_I&IoL4+z=XUUwZ!j=~O< zlTBm!{&M5>(Z^rSI9eO~tK%M|YA zQ4#dL-Zh$VYNf;dA8Y11>{f)D@bAhIgHij;x`V!C&z2|Lj%P9PM(vI{(1aM=Kyc`~ z6vL>6UP1|sqoB=I8!_|sV#CV0>qFxLqtPvZnku`V9&TQ*7)~m$ta2#();R6h+>Z7t-`LBWG<^c&~+N@RV zv6rUGElxe?QzwGF<{B!)B}U5c*goIqdF`U?IQ>h=tCPJmTZDth$7Oo!UlC^H&g*^H zxV<>IG7*rESJI>{1n|N__y#2qcU(sZFbgPUPOqS)m$Ta=6-+Lq7mSa!zB#2QUutWZ z=fD*elxw0RA}RBXm5tmPaDe8Zfh`(<#~X!LlytLMD#qH2@s&|X7F=#6bsj`o%;*U5Z-Ia{d54TrJ`8|2I6@5x3sZWQ{<; zw+p{V9djesMTD6d#ei%gN$&bjw6)vz8OMceiNukz5rJOBuIB92 ztfm^>;Ld25@nMzUF|G+;rCy6I)ze^^L(kpXd0Q2wU@JSI^~CB7bY7lz4?7FArr2DdY@$ zCEaT6&5V#QWMRK5ygIhR7lHJn>@9);jZ?g0YMz-4!*EV&RB0&E*ZCNR+A4C`myz>g z3uSX~Pc|#kYBfVX5%7rj;2@x1Td~29-njVcg*0y~cEFw|tkf71zQeS&QaGf-v5_w# zlpJzA_|dFb%;RPSTUpo{IqAxP6PM3k&Qs*zTFJsryLw;YH*7Q?qRdlb?VP;zn}wIJ z9df`#VdnG=&n1zKR1ipkBMTyh-J&_;py>^Pgx^2@lET@8p_;!A5Bi1ePzNA({r7i% zVbg?E!qM$2dvXc8xQaCR%#K$5J0*$%v7#UNpDqQ++nInf#ip!aSwS4YPwIx_#wJsKb6v^Ce;zm7ia$6?e~9ab?CZ`2|Rruh`Fqu&s~A#;URud~Q5I=5ez-tUKiafhVcs0HonKsWmteo%Bjv#zCxdf|@P>7z5RP)t%aRLC>p zaHfRHf%>z3n=5fp91@{e zf=xopgm`iwVUsw2hIPc+QNguoe;EXu7e1BO&yCsAt~BNU`IHQrgPQnbvXO|D=^fA9 z(MK|Pbl1*U9ithwLxuHMg=gpNwF&e)X-`<}A2!cr04;BJKQeU*m1#dNjj4i4)ZtA;eNnM8QeBC?E&6wh zFllI!;m^=FD!3&2Cg3%LJj71(SO>s2v7v_2qLT47ve0dajU@%jWezR{a*KcAuXuh2Om=>3|BN9#RVRca#bSC*hqk7$Igy5W~+zVr1a;~6+2SkkK z|Dlqg#YzXt??8E}r5pGJhe)OoGYNG;F;oP4#xXpsH!%Da@Cge5uy@rJGdcoC?g*#) zUIWHKe>Yz(Zgnz7xsT7eYBjFLd~oVWH5gK%2?rl8533 zR$a3S_i7vDn8#eG8>D3CpU1>n!InIh}of-^CfP z_Yl?Whe)6I5?Ld}yPU+JH{Xb4;{6@CJm*~5xwI^e;HnB{d>>wtC(!9ij2T`DakQKz zd4mWO>*LJAZd`|3f|id!vr5_iGZD{!(6eEr>+@G#28;@t!jA!!rZwwBpZqPEJ=eX5 z0^nDRuTN57DzDnZ;iI4sW!lG8{PG}rkKSkbL@&-U4ffdIy}9Ceda~63s2GP1RqKp1aWtFni(LrmpjC#h!POW{6FKvOdvdOy+ceV9&s(LvS*y~zc*?QGFGo1(Fnw#`Pm4(z{r;Df~O}pp!u-B;ydL^bV{g2UxitA8zbl(kxE#T_8$Q^D%X&BG6dZ&K zh_!uAGQcgXeW6y3So&?!NL9!&|KfM5&Z|_00 zR5*|5j{z_&A$YPb`4!WMd2kzAc$Miu z5pgit+tC(tf#FxQ_PbPyqrYur2No3B#2_?Z3MXLLebnBx!o0$?nxPfx`ma~@kx|&3 zz$Z?Z7RqR&yFJO25lOV^KtuCv8&ceN#zWNX5)1I`m$#a_d%jGSxqe2nny}ooOz0v+ zbw+@MD(rpMWdZo(ca*d=gMB;aP54bW2&;PT2|s{u4eEJdb()QcTb#BnTSzF!&2<+x z-U4H)@n}QEH@Jim%uj^{_;!Qf zHUa8?h(JI01Mu=(kmo^z0_e_dB16eq%k;;7Z`Q*Yr3>vGKAFLAy|E7cWh0qKo=MYG@!v3pU9hDcA-#y0Nu`_CR>e~1)7 zo)!8?;emg?N&VHOGPJ$0kAFq$Sh=TyJn0y4g}R@l?r zpGq)nOriDt0uje}2EcPG;$Dw(&u5|y1U@|Bcgdq2g_)vu7zrxG*M1Up(;w^-H>=~a z&pk#VKpj-*+^kaV0ozH*{yi+*JJXtU%_A^klioi8GQ^#fS1$ymYD87RzQ>mxcaf4e zF}8J3qt9O0_g(X*LfKN?10cr*-YJ^7@bASz(B$g>3|@nRWEF-1O#&>1hI4{~nFO=% z__o4=T&DRCw4m)sa_1%mk=?tY2clEw!zeQrjyX_p zv{uoU!Lp#J-j-q3-EP2j=qPnQ4@eddqZ}mcQd%@Q;ARi&rys16(IJGzvoB^sU}o0* zB2*=49nTSn%QkHegS*mdEO86fXVywppDmlU+Vz{!#-rAMj`x+x8WS9El_RU)SI}so zKE*Ld*|g9*Clp{}(XiK7_p-&O&(za^F!z3|3Y=8Xm07ssq5|!9FfOp14TgWW|KC^v z`s%2PqKpHPV!! zk_54ToYH>*mTX`XQf^?MRV6mx=W$0`3hk733_02zGoeZ5toLyMhI);32YqoRBhX6- zfoL7C)~O-CZJM%_t$zu-(z6{syTqMyb}l8o(Ec5vWWqjyhl4D|$jv_cVkU+gLe~l# z&PtMiAzm>xH?QOzNcG%eJ01BVcxTp9i$zkq8vTmWEm-zvc52u`S26y#Gu5w${R|Ag z0hyI!p2Up=N@VyS11q{*-3;kgGG%F+0_NWbBYUa0n?T4xB8g^hl>9%FL|}9NZ{b{W zLc`eeA7sheS;$ z`v7d0#$6nOXqyh(F@2t}*ZiKyjEPp@{qx!vE2g1EA59rHFG8burqiQHH6|voLs#M_ z_o_t$oJeC7_IKVaHcJzyO$4YEXEe{grgQ6#CW5;E!O zCWDI}$ld-na)3$!avw@((#5sq35nebWa6m$o`Nw7iPgT85`4p;DFky9H#Uq!UJX3S z63*=TUiG`iKoM+inwxbNmjEjG)|y%e2A8sG*=nOS_%845041HmjKCZAd-WZP!cRN? zBkXetEurJ-C4Q?CG}hdFsCKoxv6nNcY zCO&{Ojb5CAGPDN1>Om0kttN3IrPa|zR6wWYq5*B76?)euRkUQ;U>ki3lAAs<*XKcV z@;z3ooD`p6m03y-tj|DL{8u96D_-6JzP*%@r%2@nXHrS{q~M|y=$d?zuWP6@Sy-LA zk>w#AqEz=aITC|A=}Ac=YJ9_Cfu5LL<92ft9n(T7WN%+XLIgZTDf#{Ev)6RL(9siK ztB=&)p{z4`eX!Yg`YidEyg&!GGy99G6aV2*P$*00h=(79lOaQV5`V!)y5QX^wqW~V zdJJ|}B%m-7d>UZaZj7XrG>FJV+u&VEQ+HU*o_rEQh++X9<DbJkk1iz_d)DVAV{nAtCc4f>gUx?|mcfJQEJs0cm#R;eL;19yzi zwCY<9{2b3=mN@}d+BVoTi`y3~R)B7W##V6HR5)x?@n%Gwhw^8mCD;53zB5oMhc)vX zVfgdX2bc+N5RZHg=S<2M)vb>k)48Pub>a^*1R6xmIJKcSeN1uUsm?w8DP1y4QNb&) zUd^AIYMA&N(?)lE?@HLe_F;rXWpXDr0zZr1iq&zYZrw&TiU+sE|r3`%&1b^O!tq~dvExWvf z#xI4Ou7rDZ0>5A@Wx!xbj)&IdFCHR5vf-*Z0p{EN< z2CzhP4($ICbNNTF^Y1>6?gkx=@P-3|fhfvgMZRs_29UqyCsJN;I@pyrL;yGk{whQj zmrkd-2f;D44=4cU01f}e86NQbnkbdbP*&GV#71o@@2oxFOdt$CE*scLNlp+8K$l(6 zjhGFVnU99%y_0qZy1OWzWZ!V1!|d?DU`IU>2-s<`aTI91cm8m#X565AGIGozo-gFU^cdiFy4_zVU5}If{l#7(uIW!fs z)74KND_2kpTg#P~cApDT;H|RGTB{#SI38e!IUVUs@pMB4T_8igT#DfPN8l>s?t)|S z?zs7R3z(g7#qp1L2Wvn32y1ovQF3S_nl2(Wz{r8uMWjlyt6vk%&Uh`@$n|CfLzG^O zXhgr^e;AgoZCQhZGHWn=u$;5#{}p6GaTaAH$Vh+f7iR*-_&+W`8WdD|hydVdg7Fl< zT@Ahnl=7HG)Kt_cF#v)mw-L$lBLK<|XLezmV57$5^aJ(}N`?NTz|&{CkiFMdK{*{d zV#E8Y(!|v=`MYlW{Pn?8c?OpU+BI9>BIo3U> zX52>t(vu78xxQo;*pzmpBtkg(Qp6TWm+c`!Z${9rrK(SAMAma5qAR)&ZSR)vJ zgPO>bhR1#35sFBzMac{CIY0Ws+~+c6@>kds;#4&AJTzD2A6d-C|59uJpB^+Z4-@ai zpZ{Q_mADN03E|g);SfVgFZT=<2C+>7f^ugWAYBO(Lji3$+v?GO{`9jN5X{!vuZm`B z79HmA69iC6wZ#Urv1~Dl>Zimy7gX55vo3U7C?TG6a{f$Kb!^iMo9Sm| zIa2Ko}BGWB? zXcS1j>Hhfm#bp7l{mt*Rl9tN6ui}rauumBzLL<#jzVmWy=tK)B$UQjv!JJfK6Q9#q zo?-%lP-*C)I_&H<~|$s=(bdb&WcC%AMfrtF2~phbD&e$_<$7#@W5AzmDXiV$WE#}XW3 z7Ai7JWoar8IeL0{GZAtlqM#vMY*v4`iMYQNI!hr`g(0d4yM)ma=Ndqv`OFmS`h<>W zHd<*JJW5cy88ou~?Ep<^hqqGoaBkg48@K&A%2tpF zb4L$UltdR!4pb)Be_l|!LRi#Dc#cB24~SK0G$BNulMc>;r9D*JaiVXP=nnTlfz!uTwKtm`Izk8G zWoRqLMlKTvAQ(F$gF~vQG9e)sF)S!nXEFyMLsXI!^m4QK42#0nhz+3IjR(NJ0L<3h zZK#Vr8G9c*)mX*fy9TVtiHmn+O;pSH+MAZ2xdu;l84D4XZ@jlh<(4rTLuW_MZF}ZxZ}wFgFn5 z$jt}lq(7LLS??e53LwD%ZV}RJl|4DfXZ|waslg=pt)WlDqrNvhLy7bpmKeivjq#>k zs~~|WEQ&n09<%m?YLV_OX!S^%vg8RA_EBVX$-Sl zcV1cO$=3wU!48*oUPe7$kWg=Vbbm zR3W18?8xd>_n764ip7pTP6cm22~t8kv3~`gT1DF%Z{SV*&RkO8NwtT_jzJJH59W1X zdGr8&CA2#ve{@0EXfP5C;MuO1VvR1Gqygcb9pxwKRRnK6d7sR#(s5Cz3}DG&$CsM` zm$%8?D+|m~C&!Wln)(MO$3jpva)|R8%YBio(|MQUHsI7XdPu+V?F@3?$&@_b<3%J0 zXbMBM&imslPU4e^QKisU)2u}AUS%DWifs7X9udCaYD36dFb8`rM_hQ%sD>;)QOVYZ+>X< zbn7B?WvX7n=Af9%PUE!#XO^OFy@Q}bW~+opFHXV48L=gq(14DRE>-9+NvSK54I`aJ z1>P|ilnfCBKQL57e!*%ccZi*+&Btydx-g>FRHW(-57ypG4NKfC$U!*0)l}~t#;Xk;t`AC|h3QA(fdDy1XoM@R6(bhDSp|+ANpVBkm*T~f+>ibe!1K%WVnntdWBnrJ}>MUGRO|&N*pFM z@1w>^H%4K?jBk#HKnr+ywsU_kG`9qmh48d036j(5%5hEYiF(@6o4bF?lj+* z^k{Pf^oKEM6mU^aTa;Cc0Tz|cbj@BJ4k2g0*7W<6wp|L*Ff=#vWu=7mL3lS=b?~!c zhP|tY_3UlbaFcYH9*iQ;^~;>niO1AbrV%`{o=UE{-1l={>E_j~-bcLA3`6~Vh5Ob~ zBGLpiJTBKGX#|xy?h6vZ$is1U7W?!%dgvZQ0?V5vqdQqpg+9PWl>_tlye-OTe6OV#zn47DZ*Q%xQRhyH|sEvRz%3cJtuA*V3vm9Q_kzBoDDX&Y}$R*Rnb)h z8^qUp`d|IOJKY1mK42n!P0>buCDVHfFKdoTPjBoZs_7WOZ0VUjdT$hP} z#jzUW93mUeT|&_Q`1SN^y09APFt?Q+=3aNH+g63FEsbH1U9?TlF`XQm>5LzPFpFMP zHs)8Rg683~axubl1BPsR6zAw!!wIK@u?Fq%ooa&e=98N?c^`12v`5_SGf0&`P&D)7 z@9mU-slk6F^Z)J<6Ng4vbfl-=Xudiwtmk$rHNSbk(VKG0L zvWKy>ZKi=+RwXa+V~PmCrbc{~_`ST0i>cmYVq(9zZnb*|^JJ2_0OnIyd?rP3*ATq<_d;tpXtGf77j<5WU> za_%-j+C%aAvvSdPz3vr3#;=M}SrpiQjb;>F4c`{fB}?P4@af zsW{_^O{s*l%YJg${6+RDb2aT0Y8tJ~-En7JgpasO1s;x9H@m^qL?z@oc_cUMr>Scz zSg0mKJ4fCe%j+&|tG?dUZcpv-trzuMUk79xbwcifza#J=?s+R%IaI;9VDJTHlW^7= zweK9K3=-snF58Ak{ebfZR9ujJLMw827;(htW1Co#+%24v10d!RS);I`t}RK)_~bO6s%oH@1{q{_UOQ95I8Lx0cW9Bqm~R}{>c#}mJPpL(?1s(C@ZvD@%d;FmD~)`T_fTkrMB?5btO`yvcJqi5x3 zl!&0KyhJQmJ+YL(U!X602o5`0tDW>&a8r|6U-R(;X;8;C8CPS6cKj`n-i7pdic>1F z69OISV@6B8sEmWUx)X}w(aSDiGU`LW@53VCM)ar2iAK5dE`+$<2_k%9hAs`d*>z(U zH5gSCXhW`Ya+*NCc0urjS3)5=eX3tagslIaXIlM?>8uo%;M`HpY1Y$Ce64 z#!+;Bn?yPans7aDP{kb;@gt8!El4Zg){&0Ggbi~#J!oN2{p6kPtE9QP+JP66o7;kE zD~Ug_wWqF1Gxln_(L&QJT#T}m?b3jamJNNjg(c_9{5g6Esyo-K3kLg|d3P*M8GW+K zrVN9#WD}!O!^pP>SWJ`NFxwK+AWfvQYU3ZS65q{?jMkdD{~^b&wJU>0TO2rPht?32 zL$_1H+Fnr=BfRv@;_>XoC-6N+ak8NJz_OG)9&IRaby=^7w(pF3fVaVTi)fOA>uTfe z$iHKU@UEb;isjzz<~O7YjUAIll;gVE3;)38YExfnr9v zLB2`o)v}S*^~1~U=LCw$-PsReeH+^}*}<@;0#Avb&MuX?R4?M5)(D%tU>(FOQ|#Dv)oXt>#TqD_9bLc=#O1y{ zHFp2}(eJ>IDv3D%9b&~MeiG$t^kfoY>!@hdk7~%T?9Ooyq3a4hR^Kf26biU4839=llz|9|%1x$ z@>1)JsZSK;(9@jsySU`D?hoB5)Q~S1RinHxqkL^;yBaivmAXmFYcnA~rbGxj#~D|{ z2VDY-|FgQVE!0|I+P8hKj}>sY?oFwxElnbsv0C`ZmnD$P@hndpeSwWZe`)3X2zxYD z2LBr;%Zp-K=?1Ei{s_Pul7p1N6By~tO8U0ag-9KW`uN1`If}x#p2*aKKi)m@Z1_II zp`--`hOIuecG;*`h8QnF5Y)Q|BdyiaUAX6B|44mnhu0XH99I)q0UQdDj@4xRx*z?y zb(Vk5Nbqu5ESfDxG#{d2$T(K0_|XaW@sNO2N<(XF=vFkdouOcllMaP(0qgcUSUKoY zBwawa6UjsUT%eT=dH!xzhbW*o7Yf;AtvumLgyfRcft21(Y`VVfGr~po(3!PtjJ|gG z52xS$XssL07GY4vf(EeaQVGOj)EoQ^0xyS%{550<$paTwn844!K$;>t%&BFrv3{SJAO-%tx19l}W=meU+r{*m!byk>6?Dfd22If?7=(U@0>@;_^Z@E+9@W2{u z`>O_8pB?bWme?#XFvXRex-9wRsP|LQ!{aBlmBg+avnK#C0<&1|y(j4=7Uf`xo0^De z6>bk0PiPf%KlACSdk}r<=wS@xt8a?Ho^d8Y598^XSo z^}!xQm)|2?)1%9duG!w!H}>qm!f|1$zEYSZ%ieNIq@|448FxW8VRRvNu%EuHu~#Ak zj{|3l6i6ntv`yH*dg%`JMxl2$x#}k;ThFI}rOPKoUC7%?<}!kS?rJq%_qE2wpu>umwhK|Ij_OxI9#_66@3sKylaK`-7|O-^o@cCag(xN9C5$l9PA|W?iqe2tB|6fhdV-&ozZj&zU;76^?0O`awz7o5OxdAXPZJ&9BQt9}X-Jx9}( zn;Dazl(=x`tU=+==v*2Y_hCDK#_O0IQBlI)Xrzu11SY5U;yPNWp?4>pMhh{zo9N}= zZxBW=bPJJ>S?nu{&dB*QbW{yx!RRI1%QO7UDFY2W*JHI?W>?narw09ENXwXEQET04 z^g<9^m0#pnPS5r2Jw5k;K>c>jlq7Bb#-j_lcC{|2d4MR34S(-+c6~z3AoNQGhq^_an5Ho+) zVkhrOyfI91qLxaYzKV*XpbX>(#}aINU1-i)zGl_@@}n<*@$5bjzU?xEnqRIjy50&^ zGJUbPZMQs{-T%rN?S6)-x!t@yiEma{GS}*k5Djw?t6CJUEbnjC}=C|;$Mk4wa|qZ8euKp z_HQ=8!TlEh46V^H_hQ)qg4QpHVy!Utoi;e`m&3A%HXo*Ovs#xy`}$3_?yuli@Kmj1 zF!JB+nsZ%Xll7u?fBvL*)el^Md5A;Uf{@C}GS)whAV4VMbypc4$NscIQ^D9ZCLh{r zVhgi4sj$ctlIH#F;K?KLYjR4Bz*$WdG2qsovd99p$r;(_T&a0nZfRVTtjhdd(tV=J zLjL>LrBwIg4?RL${~pGx^Alu(L4vKinVvj74JPomH@?Y^bdOH#xI}QD&F}dMf9e#A z!Wfb+Q{^VTWtOh*+|6!kSHSjCf8lG-qo~as&o{u@DbjlRM#eSX7OK_DhyUJSPCi|O zYr<(;bAKOArIF_QgI1@9)A9|EZ|gjG^@mhtYUiuR*;Vxec+li1c%4fgF;|d!Hn<~N zL#Sf#V*kY~r;MdW~-{&SXL9J`5 zzf6z46i8YITQ=^j+Yidf(lt$j+(s{Em$%yKp48ChcIh7lNr4SpUGty$J~^SV3T4`w z^dL=R^ft_dDp^0#((D<3M+i7yGSg>xKT-8wqu8AG`A)R;u5G7D&a)*U-zjJR#XaMX zkk8l2S3f&C^%j_&B@F#t$y_}eOla*~Txc=qbiU}48iIo*#IN?Den>nbO72_@_a;Um zBotb6$OY{bqhH#r>tmW_?Sq{=wUw;}8{ta|_~FQ>90Pqa^kY!I<%dT+Uz-U%C8qj| zD5y?}eZ|^v)Juh@Z9qqpu)5iXT1mO=qnTZmCv$w*P^}<-`k1{i+Z2&gV!bW)cg+#l ze-Wrxw5ZV?wk4ulT^yIN8k@$4kNEaZ6J0}wTG?9F=00WzrZu$wNY;)N31Q{6Vip^# zOK~mGD-{r zn>~*iDNAj~zr<2AZsG6K8*J8TRa0hzjhHW)^F0 z5fGM0>bj+qSxF+qThV+qP|6UDajVwrzFUtG<8Ez4kuXN0}K{9*u~Mh!HvN z=Mik{ai^)V?mD!?U(1^T9}B@uJ43$PZMFXRF4xO)t9WmX8)i7xOqfBQ#gq0oOY+E> z;sm-B^%S5-4|jVzA+EudZ`D27R&*S#u_Y-wC)U!omZ&WE{OytBFkjykOli}W7fVH? znnZ#*=x$03L7!FZ(?_K`57LdhL#5kGtUN_msEIJnLz?v;wC zYjW6|2Z+@x#1IhV_B{1Cc=Y`PRLB`5O|BvdO76t(hq;hTzD_MGnP*P;+H@$#diAUBXejKa}`_>4X*aFx*T zE1nTlS^jaST$1yKSP?H#R=MQI^?tHUW-b?1e$NZcq|F47w$zPgH`PSaA1CBfDZirIsSKx)ornbLS z=S(_Z;tHo+aq|Oa#*bE%?pM>eOP)y3Ex!Zp6L9C!IfX)Ne=6NEMEyR7{9)gyohxuo z=~Ip@6b!0=JE*5DJ6IgeKO~umf9IXV_Is8u?tK=#{fc}QYK2`Xh-sL?#u&~`-C#?m z!*zTfu@=UQ?(dLlg#a((Az`BoCe2Qtfno;bGDH=;{qYuYS<&fow?JYKi@Y@eM3;kS zCN!+sVA+F|??gYR+Q}0azAE|L7-3FcXVGk|fbDiFR>cbGKr9}BO>PWa9OE-YL4fOx zJYcD~by?8Yz@&ELA>4iL-Dbcd>CYk7j?S-Q$1}I5UuT-7&tuo!wU1S_pX^Gu3*jse;i?r zDNOH^WD}v%tgxbnjfB(Xv!jX;kA*vP{$0_KMahz!b!72coIs=C9-jrSaMvHW&~y9S zEJ^FwRP=OIim7jVVD_tntO?;Mod{3b;u$|;s%bb6H90}M^=_DsMvw!9772`X<&gQr znl|x!JL?=wmD%cTHTU=Zr&`Af7Q_1YXy}ySSbWF3h`vC^Wvy@xEU-U@$@;PVy+kDi z3&!tnD@h(paq!jh3p!I}^vqOMnuQJaiDJUHD;g)sG_9D&>-wG?AN#2ZE@a>k<^Y5? zNXc>%Hp6FenmWOc9WA+3^^6x^$^gf;e|%z?ywN*hP;n>&Zq=)7q|j{dCaa?*ap_o* zzy@{Sjv@if$n$la1}l`Y>>(f*v|WcNdm3UmP=LSx7b$lc+dSQ~aQhwSP?C*xA%0di8TZsH_i$UiB{y^oKypzIc^F(|BMOk= zO^x?WTkCSRTVr}sy{zh3B;%LG)luI%{M90aZjZSnGuQyJnDpK07U*ODuJwYK!~%(W zwBFxDaZ9cwLFqUfuu5>Xf=6(qWt-E-P%J!P&0hOiGP9_lb5DSl{C3p27`8l2+0r#U z*;QbxzzEa#PWN@hDXw0eZfRASDW{a{NjLWen(qT`*55wXSD<}JFYUBa@oowc0$Vqa z|7v{(WTx)I=FIz5xL(9l^DeA-nCdAsCG%^}E?jL^-ktYm>-Ldtk4jGm8&-y(mUP$Y z#VFKk_S__Zf_fsXAwPM~omGLIr}VQOe$i-y`f`i*zO!bvl+DX91JRT{A73^#%6zHh zMm3{_Ch5P(7IMf@or!w+4i!`Mm`b}!I)kN<`zy*LIov-e&WVoQQSVwdvLL~0(6@z= z{-HD$>Pfcd^54%rr9k6|A#YFKF-@~=;7ZSrb?P8NduK2qt)Vhzfcw5`c0VIpAD<|A zE7JhtEHdRxxn5SI3?a_s96Yhcg|Wuy)EG0}I!Y7t?cId(hVGSl*z}j`D#R$O5-m&= zZdXf}^Pj#s(zogVwA>!>KFzEW+ZVG))`o|jR7GrcdW><2e$j zn*x^U_^C|RgaJmRtt7ZpD;=QX+7Av^c`Fvx&9hauZwm%X3EhUJsURX`7^}uv-HGoG zERGnw%l1Zb*%TN=4$b>}Un3Qc{#3>6IRZlt_;sFCxuch<#?Hi8*&f+l7)l1s#Dd-d zeHZDB&AD=kC39>vR!WLht?XB%-LI9b#}u;62do*d8LVuOe^IMoG~;ekLTr7WSJ^Ry zD`&pJ9hcJ~uRx2Xzq{cjM;)uz0L+5db=5r@3)i;Hoam($ z3bJUAb=acRr*tYmb52~l-DW=o16lijb7(Cw2VzU_Hp7|Yb(HKCvQ zDJfi<##W{=g(CCL^sGTxpw!>++4$OBy~lV~wOY=SgZZ*A^gtSm2T{xKcLsUtSJ9u+uV zTYZW`1$ClM-sTl*i@aCMYGLklKrNnPa+&H=`n(4b2sTeov`8|Vy8J0;f3jBX{W}IC z@gOZe%c6Dcgp<@8l4d(0gEkzy@zF!e3985Qi+GWtQ6Pkl!*73uM_KlOvmY(YKJ*XR)x1jwiFue&WD?+!-?MatNYN>`R z4B8Dnci$~GKB$nk=qFL?-nsKGnox8#juJ|a`T?cc-j+bC+Qm!9H%x{0ZffT|^PH1z z?^4p7Vazgc_LyZSmZ%cO#z*5g#D}UZY+}lTw7F`ljL}QMj?$YddJ6fi=DIZ)&(gyR zW@%zY-I1=|5pbb&6Z{^m93w`C4I{$M^bIW9{Y54lk;p@HL7Ynrun{X&dWBX4d;CFR~pZe;=(dwrn_7>Gbpsx})`n=$|2@Kf zEPz+|BhD}t7%ys0fK%5xN+_q>q|KRUK`!>8oXMT~M%K6$2r>mKDNFv%EF0r)AKj@s zy0{u)e5G>(an?acR_gL%Sn^mdD&BAbQF`NNKX)J+SSwj%87`2cpcbWzBk=*1a6MBYw794*zo}yMQ z`6ZL@2j`u_ZDQm=HDX=37`k5>&OP0%tWgRUZ;UraLY=WK> zZI7x|BKU0Qg0Jl2?V)t-ngLzn5pJTVz)|DMJxR>ig^bd|S3Jnbj-Tbsy0onS4XqB9 zcV*$>xHK~y-4Aj3X>0e1oR(S3K#YufYQ#5b zX2*(gA~q~gq>Vb;kid)N-hn!Dm2@xJlR+rHDu%^$R!;cSL#oF?H#MwW5OO3Y<0QPE zKYMf1hm#WveINyZt+e?HNA)omOsHPMn;oY=SHh8GNAlO6f80XC-vv^5F89Qhvd;v_ z)Iutv5)Y1MAz*@Bj@J(Z)sw$z48;-ZeFFqMEOL^3(6q~M7riL$?@mZ*U`ybw=|qTV z@ScI@McE~}Qk9cQ)ZUCV!mrUuzkr6`cMZANgo%$Um`AfGakW>tRIE>~E#6rrvGJ^6U9(w6x56H32A?5U5*ZCc zT|^tob!PmtT}Rb~n*DyqTFFIPR5${g^?{Ny1qGv(WDoV$EGQq?!+$XQ#cancnN}tC z++QISG_LXH%0|C{p9f?&n#?2Ti&ZfOCNP#_RYJMSag!6VtJ~CDZac_|kp1J_u|T90 z3T0Ds;JxZ$QEnTqWoPe0_IwcZ(Mr~*O8k2)w2esJtvDuy_&%%wG-7T15C2%UN}oL< zVK9FGVtP<2oL1?a)hfQ`)dX^L5XEV3&g8;)vm_i8`WK$mv`-Fj*`*U&UD~!@6Q?8X ztHHlCaPC@ix_+V|!BMDnB{>v=^e3f`dJfgpYp-00GT>b_9Vm8}bz$uC^dY4GB-(3I?t{OJ=pUt8w((n8>3A95EviwyS)wk=K>*h7~VGg?u*buc(}Qp2hk#Gb3tM>P{g{9)K&v6wOZAXbA|5x+)kw9+?)KHI@w4hEzea>@937J!QS@e(j}~^V zjxtnk4yIYrE7FfS{3_nqb-dfHMjeN^bZ~@DRTFOiozeSUvu>Wy1=4?FHZg3e0YxCWN-%5jEfmsx&Ijy{64)$jAguFzl3 zuzq}kws;RO8subX9?|&GD#p%z0+jFusl4z}FE^rY7tJV(l_vVRP(*mjLkH`$LKV zLHcQ#USc~i=!%Go<3ScIO$~?~-Mk(oi*CO+wZE_=Y-ftcd=;p<(TVT1C(b%o9_`qv zU$+fCgYVSh*uu*malAfeA<;}yFFNPdPYcu4Qi{WV? zbr4B9W6#8wtigY9VOBL!I8!?k@m+qse3+$z53V#l?ST!~43AOi(JQxAe4HMzZ8^)P z6Y_V4wBFa5Spjktjt4hrd)bHeQ9_jhTUb%yAI`z_%R%GFq3e85OFkiM%bUOa>2md{#8E?E< z{j+IM9k=kR)7Mao?4o=vJ!Vm*_Lmkvcli~96bdviycerMB3CzXCMOf>nHA~1nE5WI zCrFXDoShpPz!euEucXWCw-!03Z+--!YWi8)>20gWBDc>oF@*=!x$Gp%7(miP3L71` zrKxrMQZ=q7rmn09{(v7apVfm`N48bi3u5_4U-v0=pvQ5@oN3^T4w6_hXEvfBvg-un z`*JV#V;UYgvR$tOn+Y!jL&(9AaD4dGy_#KWtc<@R zl+v;LgKQcSDVDDqTN%CXxueGj~q^)?hSA z2Eg}iJRJV;+4?DHodI>4JDqQ{xZGb_IH|GWGh0%PF4NP;S+xRKSsCW2onci5#HBgu zp1>u(9ZmJyW7fGXA`$|C-2u}@1_Mm-8@TpQgX@Szn7_e%Uxgus2L%$*%0%H6ZXFCZ zaWw`Uqi+C5Nc_IuDf z@@reMKC!~2P`WUMr}v)isI%%GYt43_Qqi4<#>bk6*h){x*;9_DSU^laUL(Q=#Z7IH zx4$v*P%39B_GF#4e6ZqgUHRe(EM9FH$T4s2cp3pnSNUn1JahBveGOLXu;zocV}uju zJXWyUO-~sNe&Xy`HtJ-({stJmm#>i>5PJINhR8*qmyyLq2O!s z|5T~h)^O{Sak_=c<$yl-IN6WvLsp%lPap6kN1UMp=2;-K5s}lNsrB)7M-8H3Z1Us= z|B!x!QI@-^#+tKu>K1~vmg67kVmHcV3D&L^Oqo`swf7$P8tuSk1M@W!ZFt?V@)$(A zxOvjfH|L5wzbqnnt6+DL&HBS|f~XzjWrjD)dX~hbk@A`R;vSSZ%>5LqJ53Hw9G;5` zhYU=vv_;WdD1{je1jud!@|)GjKo0wyHD4b|J$KS0dy-GR@BZxq@s7}`X&yLWm)}4Z zpf9+&}LzJ52>^m%FL?|zWZ{56zfss`>JPTbu#D9F5@>qVHe8A)~!>4>vs{A zqrMDoRvOG9h`KaEP_{~Id-3fxz_Olh(}Yt&nR;E_F|Q>-z)t}BgeY3W5VNb06y*&T zaL0gcak0P9HEOhgM;^n=JN1;{`P!)E%fj2SQ^*1&VKc@K=_9RU(U~(uSjsA@YTuu! zAVoVvAL?#ZICB;}M8;jez!joP zM`Iq}S@rf5`3ja*(gPpg3bb=o^YQR12#>IWa%nDo3L1+!o4w(rrq`luw;Cd+p>6bMstS7HJvdbWao)<98LC4ZA*la@@5&S{GU-c}L zPWufWKB^-Mp{2`7A7V(7HycWUDssb5xpNi`F7q0kD5hX-{j9o9Ao?V>H|VZ0Y{i&m z9}4zpQ*Yu4_Hdm`U1gx{h~O#et(y0ukJ+z|y&n9vT}V2|u?I@ev;|$Q*ID1XgA|A& zA^$3ke|DgK$6I{5fp+cyH;}>8OkIB z13Bx!7`0x@iaoBCniaiLg3`p6yJo2L@_XesBLxO@RbR=^$hv!X`bNPD0|^{OO`3@H z=+1HKqGDca5vtLPl*NMvE-h6U|K<-k>afbvx%(6O+AP}lk?*&{Lzibqg$~7Ff_$@` zfov7Ks?5DkPmbJBZKYJVJC4QX<-(qR|SYeLo>I(yXbqh|t6Oze+l2CBMd|%cGM>Bru z^Z^ORa&B~6jf(WP+=^!6^{*Zk;4mBCwj?yNaX}{PPk7_h;M(pMf#KDjSa6{0hQFWhMn+6B-pN zR%}ukv`S`?2)>z!hMYe60AFm%HV5(2n zbfEjyWUQqdWkgp7yiJX;ApjT~b#TxA>_e91il>%seQGko4lTOlJ18A7PA5|+cS&`D zRh1ZyhD^G}paOl={)X0ea(p)m8?6|gEJpB$@tA~wT%s+Y5VyCgj~^c0{!tjUneCbdY((*HQm|#FqtA1c2)QZj>O;TOzYD4QAs+7bg%s+K zLeIf*C>&1ffL`rrQErx)WqK;vF%jNvA^gy z8BXXbqiWz|p!;)%Qixoi@>(hMlY|f#m4;&|x|%Gm*gE0W&u_acow6GSo?uKj=Z%z6 zE*pf5g8Bxc7N@2OWBSNcxd&6sDtHgwZ@;Ls(qzZAu z;mrP~13U1R55`;#B+^P(e7Arfz5KTUbget4!P+~=CiqQ8*QCG(#kVB1ya(aToBOBK zy58KYo6lHhlarC)_tEm7^4HZ$!nkDs7hLhD&P3%!t^=(hr@qztztGHe0rypFa7fth zBeJtDVHT$5%N=vRa0?D}yDdz!Iwd7}FP-J{^W}PtJU0eXWoN{0k66X>eI(hQ{K9PU zr){x&J&S~ToZ7ZgMCM7Z3Dix6omr7??28XPFxagiEc;;DgzpJe>3{gvg9#*OfX_m z(e6IFeBTPl0H;ubHEG1gg9qD3zDxw1;gMmOvho}t#Nd+ZsuLiI7l?)On|1~o@VN3* zoju5)Z6?IFaJ)cqOMqi=qDUF>Y*jah`CEjc_Ywa~v;`3D#(CpW;%kZxUIn*G$)`kB zy#;M>fIR99dSU#@S7811_23uR!ju^)tN#)f^Pp58dGYAadUezxAejUbLbt-$W55^n z`*&%`6``C+K1iQy;*~cO>Q16)ve5UQP?uQQE4eg7e+Jw^WI;a5WZKcidv+ zxODJ_@oi^Fj>8Ulm2`K_&i3kqSc+2frj@GO%&t#F+2W-eHq5$4Tj8!Tui%@k>rn#H zu^YZVoli9`ehX_!$U_HE_zXEJ_Xyr&B2;vaq(rcfe9&~|I8}5%OaVR9NpURvI_456 zzdzArI?V6>D@-ogT@hS(^GrDv+Bzgc0#uL-U6IRz>jr^j)iSCY)9-;#wFH3}B{Vb7 zr#oX35e_3z?v8hz0JO(o@3y9R`)l<(NI%qc&B};uh+gk0AAf_e!cjmZ)bOjy2P6yu zDB-WNP1m=Xj%xC{`PzCl=8v_bNr_eDQq2OP)2c41zAm1r`JG;%ux*V3ScL_>6*#Wk z0r8@c#A%9EQS_vXp=(5Tluag-1vIeZSwMDoJdlfsMLFINsiz{C3qJWDuiW$F5Zu2J z%MH_tEJHLKGVw-+p4~=>=-b!}wx@wRWWF`An(enME;Hp7j)c?epAP^qWAvp-x_MuO z{8QO(po<3<-cr2T1g?RDhHC2IfyPD{Y@G?9Vv$a7>vx6NkJkdWdO*~blnYkuujR01 z6Nvmh+^pRwZ;y%31Ia2C+XPEqJzcuO`$pUc>saG|YqTi=AX~`*N|)tFqxhzy<0+N5 z<6T-B3a3VkRqQOfuz!>Q!G!Ywjaiphl=WaDTZb;`ad#M}LNUW{iS+Xe&z zH)OHRE8~^l^*=ox%CDa?3r)-!C7Yox^9fiDXXGi@>q`LNOCJlkp3kQs)wp~4$@|pb+Rcb*^NOEVA z<;~n(52uGv^k=YyHbH8ZV2GMLn}2mpljVO?X6JLLRaDCqc-l6cA7AoYCQOQ$2&I9J zSWz5vTx~!4bKee}stW99G___h$4N_6q?D*tWr(m{DBV=59~Nc*xbrhRTfV*!BZ#ySim3f9T&2?h{fy3WCBR5cJQj!tVS_%&EiO4ub2 zaX|1x2>$2*SOMk2SO1S1hPtQ?&VrcpwP1|bHSV6#W05q%zBB;ML=&OzS$+ApEi}IE zi%48B4qvRj{`+O_B_IApp|7JLO992^1E|1PG@JgfO`TFL&Zel0&ySgCh?zAS+=6JA zs)Elh0D!B1BB6)2I01N_q^a(lP3uQ16)Kj~#f}scEfHYVqVp|A7TDdHoiD+Y&awHI zl4_b|v@=|()(ODKb!b6h_p|Hv>E^-tdbH;=RXhJdZM0P<^?Z&2_TZ!zq0XBLS7*Lk zFqXCq0aZMxrTcm>E17g*pMx>-=7b;^Mg+I%>P)0{ihF`6!EJG&u)j`|V|&#NC)*%7 z3Ul(o(5eYGAt2@{{{X&BsaiMFM?6JWfI7ji;p&<=uUO=US8=V-3a1?g5&V<>Y*Q#A zf|B(UOE8(}k{q-`Nn!EE0IzKNAN=EyBR|DKDyWu)k4}SyFVgvJrS$LO@R#yHy1j?N zwSSl?7!B=WJ;NW&uTm!S|7CehkC_&Y4E1H=UfUe6gliDXb>JP6{mZOviFOm5!MS8| zRZn*31<*W51`f&-rU+$)F~dn4e)i{kh$fZ>&p8p3`Z_e&u9tK~;SDBR#F8NApsJ{q z_(ow_r5c}C3>2F{pqj9WWAx9|IR2UbFbE_BM&uvRD3xP44w5>U9&hv5+XO^3v*he>HG6){;>Q-wo|1)K0fTm zuD}nD3-dGDF8>dX3-oJEg$gE(MHwa08BD{dO+L^J*|+G460~q)~G+8&#^mf<(_ap1t%sG>!?I13^nK&!5K3R=yAyt~S|es>qM zYcK0M{Yand4hq0_#QKwG`)Jm*tiKke^ML)!OWE?jH@!p8t@SjpFG7-k^!^G3GZBve zGkEwPjQszPMXsR^cqYFG7_ltWlAU6lKm9|?liA7SZE|< zQ)Ym#FEV$_k^ThXEVgG9fbtH7ZYJqhP%?mtNC6^Na`@Tjl2`#nT#GI?roX-vK$Kp( z*|4bMumB$r6FnJ44Dg5&6(iJ^{7WYQDcS3*w1F^Oz^zr~&x7gx7C~XDXar(d)uL-e zf*@vQtNa}@G;`8~?zU{K<`};f_}N+N9Sl&$`>BT~lBVzVKbR)I*?>iE#rzZmCOB_V zIvlT%d~N3Q`17@MtbXd^HPlLD1_W|veDLTeOe_5xU!uHM{_|p?9=u5f9_2AQX6*f4sig~Hp+&H#hyfJQ$Rfj zW(F;>!X89bEm#;w54A$Lqg>~jD_HS6un^r0Fk6`n#k*#Ogcnv~&NQD%Hipx&=RsnD zd^-VJQ4D<>!5@-R)azu#GEYk8Q(3?XBSv}jT!jN=53M;H{MQAC&-$+@OOkjbv*LJe zruh=&Tl^w#XRKd!u3R76TVK~raM~tMGG+}+;v_#!fdHY)=oO-c6EHs$OR$Y|^6WpV z^^xeb)2m0py&GL7=*g*w_gAV%nH*!sQ&0g-=sQjK=IY#8ct+TNzThGo16V{>&tZDv zc!Ps3{x|L8LBIltEu@#g31o9hP{KDX3GD?h5xHH_g)I*x0oLeP>EzBtjnlzXEGd@U z(VTIwWA-gBprV}m*|$kOGL)E99*1tp+hC$irx`ikovV!!7)sN}_HY)Y@jpq1%il_Y|ArUQM>(!1j{_j$MC`hJH?di+ra*XD{ z!Jelp%`)}4Zlc^QxAy%=DSH9|HO-TpsKtYN+WE{YQxf_>W*NM)d!36~USRW*l&T02U+w8TkU>&o_=J{9V!U ziU^?q7gdb~h~j9*$9i751)2Z$gq+({&_K}x?gvt2`w@~*Z51V>zR(3ZOVr0=MC|i? zHn=Mdg7DDgr-$J9pv+!QyL5t64KYZ&fDg{>qU)yjr}|iMr@2Eep?KHj`fhgYpvkWV z64}?{KyQSFiCmIuw+G`=vUR$dD^Ax0H-ppCs1Rr}u@(c*H|U>bvbzSw7XTm$(&N5= zwT~KOh}A0)rg7?LRp4Y}H1$6`Bz>6&>YI2Yf$N>@ z`@9c(g|>JPM5VKpiSUYd79i24h8^Zl4l+buur}W~9-KHU57HQ5drP5EHUY-q*Lo3^ zrFH%Z)Q$$~4ZYzr@s`i#E%apKlF6CyIby0y`yV^g8a&yB5QT=!bBUH}$m(|$gZ0W} z9M}QZ_K2?2Ia4(zwVU}sH6m@?Du|(Q#9&b>ver%ZPf>S;8;yxafB7Y72A$lCy!pZj zwsRci+Kt1|A!9f}O~Wd|6&x8Jq9%!OxvZmt8M+Fp%sXHSk4qSADwToi+wR7 ze{4j+s69#On~&ei1>q10AB3525N(3!1IP+L@^J$wcYix@BEjd^WAA1G)tJi<(kdOE z)oI9NpcP-urR$($OWhEc>uT4-gb$@k)>bt3QW?2?+`t0nk!DkU;5j`-8Dz8o(n{@c z0;~ggOgVK*7%LxwvWncd8k~x)lHiuy3RtT-mc~G+A%AP4ZnH%ZHL z)AEP|zqMpy?K7r46LnNIg1ogwu|?OjvtynCd+T;QX=wIaL6f+;k*nL6nJ(}HCqa>( z9xVCgME|3~67-kPysUfmuuix;g{f}3PvDe^2qr(3>?>6K_@55J{^=0w|4)ao)c-e?u>9(b*Vg97MKWgP*lmB~$e*w!T z1rh?jhR6rlKvXdUumK)s%Ca5*jG#i5=|LUf6P;YOcWuXKr6*;_HxI$w3t_=lq#l1~ z&Szvg1TwWdXhR0-^CmncQWnkT;yX%$nubddg>V)4h5=iNY?OI!8Q=hC)Z4-hUkxMQ zQuty#HX*UVT72bvvnY4sP?xOou##yvRFL@(9Us8=rq`&2@yi2NlwI|ldco7$uVj`u+%ph+=8ybm6kS01Xxnj#mF=}r!%80&LI=%D1W>C8T){H`Gvde8?xiE}$CGL7U= zlM5B*q5!t_^Topecv#?}i~`5)U{O)F=W`9{|6>%FOECHWh67t#01*1Wv0?I!4{_1U z=PLjJ3H&brkD$l&019qKbaJbr+`E0HJ{?_X{lckq09?LcJhhBJzy<(h1)GY@Q{s(z zsNO`|H(ljkkL)HXPVQNpFBgIHqi7a#Yte5jw@Wk%;93%4MlEF~uDvH3=#~k|^B0Xs zu)#xDMHwF#&mVkZ7ML{|&Ciz{_)!NwEIHR8*_rBnv0uF&*s~T$Lk@yMx#6KYYeRp zA@BOGDMRj&o?AwKYHIviV3*dTFy_wf9HC0`yPuRUZUgBo#)BBRM{zCMK$4QJWS(8@ zJjH{)@cJhTHiDU$q5tI(|4StP-#p^K_yCBv&`elv8`9yrC_ptTb`A*t*9rne4G;DL z05|`c1-(<975-}kBF1Ff{-pZvR_NpZytWYShXSpvs{${nP;bjH24@_R1shLL8DfHluAlw4`Yax{tUSn=vaf2U4X!(33BF78yNUr z*G0ub6=FvzN&(b5PUn&klRvxZwB@P%!E<)8oLyrVy<18f^gJ6f&FCk&d>y~c}`{`KqW2nyG#)>^_kSS zBQjFquUvH5U<9Ovj7eDE!~U((=MCs6iWN1aU>dTUH?;FxDefD8b}YjJ`R_M{y8HtF z)xga|$6cJ|>jY);8af2_12^4SYhEt@qC|ZRdd1Te>QOLJiBB+8*8ahx;|G(I97Iz` z(m3jZ1S|P+gL#Iq6l2eDu9j-SKpgfH)|f}4U9{DRgcRiXbf85j9N~Wmm343*?KMg_!6L%90Ks@{sCQ{cbX<1gUu`#*JBrEC| z_SM)EsMkC-N7AXn(%^{Imh|HBb67mPbZ_ZpletHEkP6nOe|sf<3*X{!QAlI4sOz6i z{|oe}&pDWoKX{qmc*$2PmtxbXH1Aaq=2fM^^3f$IBr;=_(? zc)5n`Ii5$YR*tCw(iGY~)rx zE^tJ+8X@TU;^lI%NnqgEa3yqq@bV;{+=MV&7{lpa?0%Mn9#T$W%-Urgc-lZO`JOr9I&o}cZFA(ZaOy$yMWv4!o@A^J$3}PJGAkpL# zF)EhvrsuLEUKq&Clg*PB!~;H))`vCdfm{?366RJ~bPUhqK(tS$veHgE8J~^Je(Lc#r|N11c1+sOxjC;Xesu{-j_u@`w-%KGk_LT?Q>22jp)-gwD z2ENk`xo~F~WUkJD!6Y+E{r)4whjS1Vt7{CUJC?iTb6}*eN-(l=&&{!B?Q?(X6P1!E zwR7N8prcfy3Shhu)4=f2lVOx$di+#3f)}D+B$(N*FnP~=Wcsm&Ou!wAGI3|zKWgKt zO8P6dVW$CI^=lk6e@7fvDL-vz(jGu$fv3U0C#1}BdziJ$#PXS?CcM_O=jv1qeKKN> zh9?V5V^}N=k4mm8ZMXXuhB(rm=#H(rvKJ|XjCXu3TlG`P1&=fT!iEi~^{DGeOZOgg zn0CObn79zGhknM>$#NDhG{`+}oCQ~_{}2Xz5q>d#{MsWu{ln>cJ-^F3bXZzGfoxcp zpuj`@ANrp4GV@HxU)f6Wu~wID*>Vs8KFBoss&UUg#iO15UHLXR#OySO1oqwupfxb< z*mBM@)8UPwYbBGX+PNuN$4M*>6)OqU@&TQk)UL-G`}7tUs=1bv=~8$Kr-^&05TWDo zMoK)T2EaL9;Ob_QjQlNsJyE@I8m^_JsPrb6)q`>fkRMdzJa+CyD*6>iE&=k(<8a3c zigrQhoOlGV0~HcRNnGe3v5Ab-mo!zK;48fnV+PDYr}9|oISYhoIK^#NS^*xb!)`LGv&MhiOJC~sFFLE`A?BxoB?@b z8}VZfQ1Ki1a3{(+eJ=ysoD6d2to(t8VfGx?b|y)#=X)UBKQSd-`2g;oGr=bbX@1@R zhqAW-j%!)6MZ3k!3>GuXVrFJ$W?9V4%*40%#Cm(}^j3^M@mV)yds566BG==i6_M;$rKD_|J z&o~$ZKik38Wx$o}E3(og>L5+aB#N87jVUwr3?QgIke!AKVmBji3wkSyKr41H1 zfwS1RV^I}oGdVk9iiIywM+8pbpRFXHjUmFnuxPd-*$Z;UXOJ`G{zdOVfdUHeS|4=e zI)L=_Bmv+Ecd8_o$o!)+5DiQS!2jZh!B_#PH;CL}^3>U3_7n>SI7$Sa~>WrM650amU#kqsnq!5t0<BY9#VhbgTXjw`d)J@28v^;Ll7DHM)>Pn}Srpici=YzI?f zMv`JgOdwEN_jb>Q4E9wlCT{7zw$bUZ(L6Zl(RSBOV2{Oi9 zklY1Y+Pfx^xoOhQdnVLKduWk-As&K%dE2-bgy#MVMmCN=Xb3;7n7Q7>8b2J}CTvxS zfL}*p_N{<+L?Sk=*4j=iY^E$gY)PFAZl@BFP|dRGv^rWBV-M-+N+h!? z{$(FhZttgXUx9{J9%*UEz%tdWIb_JeMKi0~!wp(qE^z2C!=7gvt{0Fq5AsN}#T$K_ zcl;+aJ*LmU@4W0FUfOP(H}1Z&MTdz_!jBDhCJCMC7?8bnU?EX}AT3rnn+ED{uKgF; z{ukH&k0L!Hx(#q3)FUI@`3wG#lLf{9F>?b!p`-}K3Jn_rIl{uWQ4!Sdqx!wwzrOQV z=O?vCr2pqVfVq~d%u)#`&%)X#?Sm$XC+#|6fUFXp&(Z9($?0idvOg_(woiprRP$pQ z+;@cb!_H7(X&?}wGjkIe2t{S|p@{sm;Kj0*ew$zPg+PQ@4c1~CbwkDaopzI5ncPKD zd=Hp1xf~~?Js24p5HIYN68Ys;%zhx~_?@GrT-i#{2cq6#Kc%}slYt}+4R? z*KIN%G-UdrU|MXgO(lPClfA{syRj>H&|znZ55Jv*wy}UI=;^hU1rdk1FOI3Y%VEfM z^*I9JvI1@5>Rr7iR>`6TU#ZUazWWtNw=u*V3L(>*3${}UOJKZFIM~J*@9pc~f%)>J zz-n9ts4ojM?5|dw8*2ty+i~TOb7rc?%$=9a#O*S`K^XXJN;Oc~p&Qwt-ghRHUXE!M zxiYGYIN&+#*+~H>yArCToB(bIeXYp!dbo>lt{7}a8o8MLkrn#dC@@Q)6Fx{vaWhpLig3}2HZZ=42%{&KvS%r9hLKmgN{vb}gD~`TDFwQoA(xNP z$G^{UST@gTvnOvTbHg>uTvwXvVbr|)f#==e*mwmj-QFCz&qo}v=CXk^8!V?glx@FU zuj`)rVkU|sSK%;@YMxDZ3ERGu%Q@?=B8yymBIhs}RzECA`_|ah(jLe*!D&g9bm+=b z#3A-v*fO`3yde%Y4IKxZBxq(;P7EE9+kua1ZoZ{1JWo4lq$qCa__tas@7RCRp6MB> zf1n18Y}~I4(~k{Um&eZm8p@vi#^0<>SF-XS49PkZ1+82$@&nF){(+fg%csRq(&X+X zRn&Th*1+V1RY0@*SUvvjmqhYzMZHIIi~kv(N)!5ym#*!qlLRVr_t~t==IJF-W@< zOr~zt*q=#SIKtX=f8+*Li@wW^qbwPypaz1`EzT-X?pTSkdk@Is z(sfoQNZ;-6ebavbLU#-IAP%166@}ZBAT^UhuHyl#O`!mzto;YRPixrA@DV(Fm+<4K z%2DpOhHiSQ^jXce1tIa*B;g+w-guaVo|b4gS#_+xCj`VzeP!b1eDLlEPjL&yv~DFk zc8u`@zq=sRpFe?{6Z`76JM)OZn)1GLtyt;$^Bk7)ZIKRE=^B;c=@{{e;{5PZ55<@| z!p(WHmBGaLD*34*74VG5eq^}8tKkKecPFyoO)r$`W$59E45d=-+czF+QQb66*uc{4 zBJ4qfPYFRDICCRk_-ba}b`-;)2nqNotSz1HJ+@|yXf$J5RprhdqL>gwRgt7ElF1@v53Ow<9jDNe&>d(M%EQrmz4i<~OuOxd*COMdVRmc53gRP~WDl6n|N!@xKob$x3?tgBP^j5u5@Sx8h!ql~2-X{Pu#ziK@uG(um^V+gd< zYO>lK*~Q?$F^<*F0o7UelbqXiVsupg4E}hmvQKR8nEFJ)dwh#K?xru&HW9?MwrCkK zi*Z$q#q&w%=O{A>ol$`KT;KoAF#ihdFn@JQNcS{xO*vG3F6aRilyquP6Zjg^6TYws zI^b+yW^YI+*}AEEg$Ogt}+|8t}r7oG&Ff^b32It&bf}v!Cz*O!4e1+Z%rw6 zBV*OcLywS9eCX?HLtUf~{tjuVzK_|b6=0micOJ|VuT;mizr8@RiF4{RwFVOvufsPc zjPm&~T3ca@?$s3D#-VfRmX;-vHNeQ0iAI4q)cT1{!KoxUktakIu1&+NN`f;2Ja z1~Qz~7Hs$x-O9M5i2jDH$(L&^G9Lfe{;8ASe zk5Opw;7KPu{9G%?gq2(%n;?N~a{e#I@|Q{eA#08rS#+=m*>?i~7$9;E#f&P1bA1gS zsDqk&N?IHU$_j)Yiv&n$D9O4}(Gvr_0Ki0fa?A!G0Rz&7x{-bk*? zeu0)@Y_&q{ldfOdJ~`Daew4OCK=_C>Yy)z^TdkWWenrdnJV zQcR#Y#3fU@zG49r%_`<(mAAP}?D3cQR7BhKCPA~}dr}CNa=K5(S!3J~638w7TiyrQ zt*CJV_L$Gv%vp0N1P>KYE#jF1z zDYqn01OOmQ+LGEn%n}^`@hz}?X*(u^B*-7NLVq>LyrPkY6*GSsOh^JiwL%J`i%O61 z$>SOK;iRl^EEkm5{nmb~_F>w!@^MQRmx_(|fhptwDEF)QoIEP^?{#_(x!-p*ASf=` z#>nlnJATWUw|`{(Hvio@(!WC^R3SrjQ3yRf4a)o~~p4Sc?X^k$qm&4%v# zoU4r}k?Z%drguLp$MK9QmI_uQqTor6?BA7|ijh>N#RwgS3r~0XJPJ|qhOi_DwIRf|Ezw?!8n!XG`icDyisH5OWp6x_IIPoP^JwpqQM*%*`lK3ldkF7d>2I-MU*Vb@&ym;~O+|{?# z)X_xW%G}{$#Q+R1piX{;OBPR5`-BUd%nyA%JgV<|2(i_{~yYtZ6H^{1D-gX|w3VbrnfB(Ox{l6-Ay%CwiUQx$D$EpWvA*X+IV? z+Xm#2zQ!dTx^PvoUYFha~ga)S4Mqs!XF&hlWzdaL?=b{a#9naew@3O zYo%tZmyPLsEBAG5anjk(_eP&e2wunJ3t3!|n()ST0LoN&N`CG-I&Gal`=w0v#(iB# z(%|AY|6Oc{?4%DV26dHEFMYJ;=x{gB4oBDg2 zSiq=Ls19q7->UFDNlic%ShS`LqIx#rS5Zl=&}>%ptPLYj0buyjbycUeZcDE3f!O=q z4f>|$MELsLDV4~ltSQfl;zQgazHsHbG?t}bE*dee+b@Fd?w~%5$lj#t1A6+Gz1(A} z+I$CO%CFD;tF&{{Y_~}{#2fp0g0+02A$-C-(4ZSFU;W~)E@)U=#|%{Hp{xQ3$1hyW zAM==9DfenzD~@uEE-?I+l{yta8yr7_*ZO2n7>Q@$Rh@gSM+4r$?V2^zX?`d!DYRs_ zI^y^C^E8tyS0FP)W=~iYQrq;gp};+KRK91|5129jW+)xgJSE@05&5t#H*!?U3&5}J zOVkk5GQFpq{Y@<0-Ri*`2Q? zfQ}t`urNqPcSMS@CgSxX;_NCt2`4NgB|NnLjY794muBuXF$Q&VY5CA>vXPP(Lohg= z?ce-%Y+cOTMQ5~l{k$&asaT{|7b4}V&vQx(p{hn+f@u@EhM{iY8EYAv=}aeI!WG%lk z6AlT|g)M2s*V0=fus4lwCJ0v*h0Fu0?joi~)ZeFMNR6e@!`H(?;@#5{)cHReUzV;u z>+%`jSykek?~%*|e4-r1UKsr9qPX;=PTIo_JwZCg@F63BD{-62ZZt1K6wI5V$;JCT zdNfiIDuhPVA%c4BcfIZ+V^>nNUe*&L!ZlS|<+g2hgToS^Tb#^HXoNp8y`nne0^I>}Y7w^PpJ zZELuuRtML&TuoQ7?>90sg`21%5rD0K1dbF;!J}U6J@v zwBIBUi!b=;&1w#@h1}f4)j^*dV+s9=(UE>9z54&of~iI6Bg>wU{rw|X@Z}cyzy`A~ zQ=wTJ+*8$`qG`XMD6NF#;*iWn>^d!Ki}W);u}WA`LzW#3|AfNGd)W!Ouv7q!#xD+Y z%}+}rgK2MvUB9OK0e-HC@Y|K27voqK;uX{@?BzHYoT0gTWg2%sy9dQ~!MZN505(Bf z2uKck+}Qt_9V)U*^$G{-+!N@kTLI!!KB8^K8*jk=OrXhT?*q_K)NCjwuKZDQLcwnWrKG;@TBYO<;AKu)^I zKf4~gQ(BsRNa5Ys(WIEgeU?S5dgIoVV=TZZzVoKaWjf6W;|y<^=5fWm5oYI5NK5?xi_FarPTGN22(Q7{m8`>#7p zhp>We((!0X=&H>9YxbX$K7A|Wi77s>&NBVX`OQ5S!?qACk>rjlEWa2vuTc#F4}JC3 zYp?IK+*3G}j9a;^M12UswihTfFvC^Z6gzhpmf~C-WOH=vUs+g_jL ztrT(s{7bq5DsH6QS?S>Q;<-h*3b0+Qf>?12=N?Z|Sa@S1AYrG%gIAx<0D7mZCb-EB zm1Op135?6O{Zhe@v~$!R+pvD51dW7X>%UL>x?!Ldr|-!w#MyWz`la&hWF>q2+^c0V zG189Ppx7@1p^lEq-&nebrp!0#PTa*?DeoK`-W{(rkfZq(5YT?Q;IO{j(`#@Un!>PG zvalc(So}y(JFw>sy6?*SOmsA5ASh68aJ{#7If)tGZ<*jtBu1=ISNi=iZrfIY0?qpm zZ&1|j2>)*OGvvA3l73C=G1vlR>WrbB1<@*Uq;#kL$a4+kpe)pD{W)ke|C1wMybN}0 z%sv~q>iVBe!4Sa}g;i|(-P1R(J>VSu<-kM_9{GkkimT4AiMl7sMmHMWUksn3ej#FB zLQxCv!=g}a-L+Pk)&_kDe%3o_9sxiSvc=>}$|x5@OU0S<51ih*oAvCJf%4L1OY`|h zN=+^vpx;Ox7?54yt7x8UDg1aYeDM9bKk;X!v9fAa&KQ?Pk>c7LY{R6$jBCE78v1AIImV}e_gPJ2*jS`5r4nJ+HnAH zDuiXA>uwFa3c7-}_R{rkN(4fH>X?aRv7jf5@H2j>#Fnb}^SFIAt|emd|B}{7F(2Z>yjgMVE-f_JI*7hMHE7rQybCSWZPbNDx4(MUH^fu(K^k^a1n)6qh<7V8vTuOyz+(>+%MR8ArMYyDyh)wvUiX7af6pjJ%IQ812v>d zS;^I;_zDG-#y!)RE+oSZ`&#b)%iv1d7*&1IgQ+pwOt-MqogTH5>2U1_`|ZfB76i9~ zSLw`W?l}z&!!@hM%k1H@G`-p2>`5_D(LW#pFkgG(e@WzWY4Zco&o~vHURZnTx4;%j z05C8#Gmn`7O(C8K2^w@}%BDq?K%0x3=BcO&gy++O;EY@C#|Ul-amyyplOCH<=dk-$v1lJYb1dmIKTghi&*V9!UerDA z0pe)6@^4t5B`cEa9COWOWxKgc@3immeR@i!g9Lt_A)hQaLums;n!m?9gc`cCuxtbE zK=yzH=IbE*&y3)|*Nae46bh$M07U>NZuYCNe%JKVATwgsqtygg#6$+B$a*WQHJo&! zq3!@qF1IuI;_s%T^9ubWW#cYg*^NC;UHo*|u?Ity2y_;o6NUIgCuYg3uA`)D^iNFn zC|krhF~c`1AcizB%gFur50(z2#n|I0wuh*vBR4q=5D3Ao`a%%$c@8#$7v#jmKZ{wI zfng4WX7>t?xRONNmEFviAtBKSe5aoe##8dR!sT({Y@NgZfPCG5LH^(H{mE~|fI4BwBK+`YU|nC~-)(=RI@n_%0Iai` zqyj9r;@_rHpiT;$oVCmn;_m-$1hlLz8Fk ziY(uL>l@%>TSPpv=F{_}*jjB;M{T%+V0+m1?3LY(!-QdfRa@15s5aJXDstc6d5&-$ z%JZ#V*E)ob|Ew=#AX=uHj;8u&1k;xpd)#(I<{oJ1Efrlw>e-abTTJ!rXcbwrujtd z%OiIoIoOMfQh3Ov*chdxdGGUGJShKn9dhAXw4T8wI>UHrnV84i zezsE2oR-eZPwaA3TJkN|O!I{HKBCtrH%of19={W6bZ~;raAF&9ua7CWAdj2p+{k;q z<-@4*Mz`7O+apaD3o`WgFi!Xj#g9&i_mP19tE1FhIdyp*kAGCgI8I4vD%EUex{zpZ zDAf1oe--Z>hC2lQAcyD7&L9olyJz2G4o(#gTl#RB4iF$Gf{7+D3o3RyY8Fwd;`^qa zxsN`Q8?N|3C_3fP((j=vP0ZIT*$=fB6Z-In=kqMK{%M_xbHKMisU`l|NaL~0`XkA9iXD*Y5+?|j?h8B z&XL$AUCw7@4w);{FXITtBn5P18XI;s#R92errEv6kqmE`)+meZ`%ZzSDhcUtg)12$ z6{8jde9L`LNqGfW6&t*P;dmN}cS&syWnd{@)h{N_Doj@+P}~QqFQzF`s^-}GKM-_& z-<9959J#W=u&Y^IyzWlC!>X1c41s7ia8@|qB-Xbun(*g8Hc^1aWITlsus!y!HE=Wa z9;AI2696d<7}F@Xlpt(d4jYl~go;23nzPZGK`tfNA3)+gf&u~g1|ix{hA0qUmBdF- zj*t0b@lXfEAh{3&dF18?0|7Wn7*P}XDDB^a0XK=c}cLM=X-nsY*Xq+fjfqWC( z@t+xBm3Z1^F=0O}de;OWh0ALDTk8#T>1cIwu&RaGgBd2MfOC0mt6VHPBj07C8TE$Q z)`;5CWGg96X%72QO?K%DGOe{TTo-?|x4pZC;sM(;51o@f_4K;qtx$NWOMDCiUs}Yk zGmjLrPKv#kR@vaO(d@w%M`z|(a%DztE!xaSWJTWwvE$sSOLreSF0mby56i5;XN#%% zhpSTrzn*#L6)-_1c&H;Fm@Ub<-3oUvdU|O79P18xB>7G{zbCa8_z1psP;+}?#p}x9 z*GZ;iw}v9toYb5vI(k%^inF6TSIL)cvPjFHsO{;zJrt5!^{(#YhuBcW0@1I~nr)jp z8jdDjXcy?ae2rt-gqKw{I3GLlO|0~Xf|W^z++hb)lt;GhzJ7%151e_WavvPiF+5SZ zwP^W>{*4#Oc#D!p4jobQilRVqkW)cfEH-lg1aBaGEdUgK;RpKy|BAdUWhxO`5XX7| zz;+-2MR^jS)L7_pE1MX6DWq^4IQf#Sii5~F;;^_30F;L0xqV9nKtn*u1&2=D2*J}= z$i%uD8PR5v2&*&6)d32ZP1O8v&CX`ANQt>~pQnfB5xzLZ_t<(7o-SWO7EfoC>JigN z7oVY^+v$XBU@i>WO-|(uoeUIUlpx?V-l^*-Ne_l0q9Gmnx&dwy?><;fit00gfsG?v z`1$_Z`ihx-a7J(G4PI~#N?58 zu=wT?)t69YPslGIvq6K*_T|6jJiLKmNC1HL-xdVG9)tTE0RYey0F@p9TA~mfoE`uH z1)9ze`-|n*9u@G^fa0V)7?kC2C5p6-Y@CbQ5`8ysPO6ZkC7uYLIHcp>+vsbsUfe0b zVKVcHer%t{o{Nx8zQ&uuo)Uns6VBsQ>9F0vT}9TTHjhObDCwa}GRE#+Vnfdf`!8sE zF^xdHbe?SXSguql5h-UI1z{aY_5(f_$2J&PoK}j+Ktsx85br^fGC-hux==SNkXXp9 z_2}qMe8RXPP8eY1qrD;W<@~{Nc)Fw_S&Pf>XWF@iPn#xaR2~N z2r|X@f6yHu>|gx`h|&7jpZ+NI|AgNV0Kk@I52&XE|BdQLz$byIOaQ|+Kn#TXsEM5S zkf7`l2;er@kM%}JL+HPMi8%up85H|r3_ zm3+@t(*nsB3ICtxy-jfX%rDbrwDSaY*_9;k>~4S5#6c_UfMwACIPot^_Ww@B2L~hP zGD59C?paY@Qt#DMgR1~(BOH z>1RU$29ytvK!l0kzUjjvVJu+Z4&0(@+@Xm%d%g^2|D>8}Q@`8Ifz30meoC)x{l!4O zp`v0*uhEwHo~uN62{PHVaJH?)|4p*~k7OR|c21$cY~~ct3;^h3Zvy~J24g+onLR)< za)2JkxAKE8s}UyQ7Y*iT+dr=)LS2Sy#n{ku(tl3kowANZ+$NYM0=eLA(aBb`m>}V9^boZ^6D68;vz-2_jDXj!`!^ozFqZuRSJ9_L2JgxU@*IUDw!j=vlWKxOf={r<78YG)I73`lYZ z`xvH1pkywD3L*7(C;FRIf}R|-t=%9I(lX;+(;lV$?nwaQ?z5HnkPXn7@0YX|PiY{-;X9 z29!CtPGXL(7ZR!2MrFc9W(c0$n|pLs=>$3tPmn_^d+R=(;ZeoDh})KVnB z9Aq7pgm1&*jqV?TpDM_~dVT+So1YSAt}V7mpRB0V%(%k?rcIaj_B~!#UO_XMmHxE9 z%6>Y>xCpTF4O>#n^_L9_Bbwt~@>zX^H`WhjW3J?Ne$?}$((m28)+rpA1%zRLtR93a zi!g=VX;NhkIU`qQv=ccn!o&yQ84p(8e2C1Nty(b^+3)bZECflsW%8MW1`o0zqf5L@IXg#6?LK0$`Bbc%Z1g6+ zm$&7tPIpl>WG=Yq!CDIQH(jaxv_dCBz^)DwM-<^@qfr$LQ~1(Cx0qt)kyYzv$1b( zcEzdS{-khof`#8CgJbPhLxgVs!CYN|KR@LE2{UTTWsDn!X3YRLhJ>{oYV|?~+hgk54 zc*Yn(P65;qttPY zr_2f037cMRFeXa#Gb{8{$R)#DiS}}3ahpWKkoKzeV-3t@stm3W=T&d8i>|1I)m~xo z#LujXsTy<-SF*0cYu6{~@ByaA6=L(~QB{57)9$bBhvb@7S0VYy^o02>g%X=b;kAuEJ$OPg9%Vg=^v6%>;z?EmTX4 z^TPmMVG#xl2jv+;^80c7H`EU0|5T7z|_amB{H=;I;|- zpg8H2d7ogMQ=Xz?sQc-K33>`IegGVLwiA7rS8HzkMiwG_S_|CEb_u9_t7}w!7oWkW z+qtXe*^n26;|V2(FF5DqkuWL ziY2z@eCL^9Z*t#T_*YPq?-fC(GveU0QJ75yjdYG8Ozvl?BHAJ|qc)ONjr<-K?fCA9 zp^kls4ar_9OI@cXJK{XJ>j8Pw$1&M>n^lf_3xjKd?p3|6p{yc~;OOs<5a05ir}R|_ zN-er_%;<~}q9KMmB(Wp{{G9c``tr3i_T=*%_0>=eF`(pM6%j-K$Yj#A2G(w*J2V72 zW3OEB@CusX$mBEk5OZvdJmmz0lU^AKyN3JPuuOVMsJwvDP?|wK`$m*-7#`y!fv{6o zINSHXAwz!?0m8{&tQhPVAv`T0$756J`Q5Gj-A)h+0F!bAj7mY2YFrl=@9?|uAkNC9 zEfMVMidZc^6K%|Lz>p087cK!*&I))53hhrbW+*6R#_*(%?|?FeVUPwLhP}I|BOmZ` zxr_6%!IV!^0g%}7Vn-h({H`R7sA4-Yb_J1KA1upZ$^&ga=<^`1 zW^b9pzD|AN;_jHha|b@wS2O z5{N{HwZegx)P=9Ek~&|S${drs(~(~8&LZoP2fpnZr9FB$w(*8ZAyqWAsp>)Cbx!T8 zrs0rL1rrjo3ROg9_%(C_qOFS6XjW{SUncyw*fMJX-Fn(Now~ZXQWG}G%KIaU@V?G< z2qg~lE{C08rQ915{0?E@)E0`*qovRte<`Tq^V+WzY_NxGNA;=}2sJA!-?MrPi3e<| zPWfL=`sgFbkMo`0m59AVNoNDQX$2So8KcOWgF{HGR1};w7HUjx&HiZ@H@kXdspkon zG71kvqa@!u+**=AC96Wmsrmy9n20nM^7!+H*zq&XZFNZAamr%gK2p`OORd1$8+1TCfg|qG^f%)1s8_ z&?#~VlA3-KhkFnTH-hKlZN$k_+*eBl>V7Bon_2zv%P;)WiU$8DgVy%}-%Jx%+SFq- zX>>>&ob$&B8c93La+JV5zX4ASjBEd67CH`R9<0y2Ew$*`CdhC<`QP!D(aDCJme8r; zzwXz3wz~o!CC|U_r!CT2ed9aQHY(9HNI2LL7=xn5U#8&k#iF)57uN+J``HrNfo@<< zS=9TkTsYl@dFYcSE%c!F_0A{zIvwwY=PO{*N#@LHOl>YyFn;NZgf zArpTQlZ+36YvR8{f*Cphh&6N9>@%zlp>u{#fCA=U1GtSD@*N0NgSuQSae2)UYS;&8 zX~URFYyUuomf5$A8;A-zZ5(kRW^lzc1H*{Ki(EmqK}DguEVRD4n?l_t>^Labpp~kd!-&^tl3}{r&KNY=@&9p7 z1cz*uQiv~oZM|qff+zWvcVqCPVay84_(A~T;<}&=+p{JH!4eI~f(0dEnd3t6=S3rN zFqq^07W0R=QZzWqa526KXs@zFCbC<-JJBH!jO7#kT(R*Nb}WnB3MDv-teXh{)gmjs z)^nASLhNa0k&vOB671#X#bM)2%IOFM%sGzbMRdA-Zqv5=wyrM^?4_b@=QXZ|*z0WA z%1PaWzRcO;qlofa*=k%N|Mb?NT&f>}D_-k?ngg?!HkKLQkNmw!sQcQq9CF+ids8u@%I9uvXSPF~m#d2F#U6aixyVwN82@z__}Y z3LM8LyP6e_gUusUXFYM~lyUr==bYcIki#t+qmRi3esvN%1^u@e*j{jLs)np|@B72h zvM7~%4my;zF#0_R*`BQMoTS#0h4Ff7gfLFGPPHpNMrF&W2^`qgA8dDa_>?rVQ)Hp| zveU-!f*r4QQk`03l=@_XvMVijJ>Mji$&_g{=1;Lz#@+DFQ88M5*_v_esxoQCIX}?K z5^D|6F{!stMDBDG?Vwezx8|1L`p-*Ps^@*G<0N@IPXn-0c3p|7C7Xx^;@L3}En>B5 z$OR44Jtip!@N~K6TY|G}YZ8_fG7B)$o>;NMH;lm{+!bIcWJW-wNg9|R^Pj{o&^APH zAZ`{LH%Ty}YoM4A7~G*j19MCrTn{%fYY%|?>ZF-!HIn$XgPGpDdC+wd7$`LL9Vo`x zi?5Gj5a_&23`h)_&93Cw2ILmfP%DW?3B(k)ilDO(#pK3rG=ib}W}+ViZg4|ZYc1}q zLOD6r!$Z;fTqm$_mNjzw7^%)PFt2VHoMV1?5WR&hZyes> z9mp>bOoVmnQ715N+o*x;s2v?ypHPJ1ty4DHW8YLV`AGICDFoGRIC1Vv*%@KyY3y!I z)M}nGXb$3d(wY2K?o1did#$>F7 z3>c>LE1`=I+KQm#@=vc0Fr>ZaF@ipjnlF&-R(^I!A1C?9L4x+M0f#|-@cX~b_Lso( z_eHI6YV^-rvY$9!)Bt$^iqbzD01ZG>9RNUqyAuF-f15I)pB~xJaZSa7S+Y@YPgD3J zk3osH<403p5`)2K>G37Rpb&!!eHkoa#ny&g^srWGOrUc6YTAb=6%XfgWL&7se&b2{ zu^j84oNVy+x>eM?!IA+NsQb47sOIdupLz&7FAzxta}r7dcRaHnQ@lg=UY*n3OpgpJINUl29|E6-yCqGWNW+ z13&65^6df1S)6-a)S{-zNnoQQnaPW7$UaF8Ys>-suy17QpAR8_pMqUH2jREjCER?Y z!AD7W9rI;%<+^!<@S~&7o|+P~u|4&<4j7T*^Zu1c>Cf1A6$3s}9bNzn&Qg#ZrW{N< zQJYWvbzhaypR(jrE}=*0;<8L|_o5FP6yXRq@p35xGnH{oNmrIcH`Tfl%>xZ^25zQA za~qV}F&!${0{{RHL9RUi&vP&k&{}~uRHXj){s+eXhj0Jo$|w9A}@A?2zB*)ENN5^SjX)X`cLp4Ww&V#$DcKo(4Zr#kdst= zcfaK9qHa@CJUTXzx{KCvurZ}{jobwN8bK4)f?p?{vYyl3Rfv4khFV=6V4;k`ol^_L8C(4uC3c-yx(cK_Pkb-XHKvx$o0NDsy!zN;j9w814atqtT2Y4 zOhs0SlstdSg2aq-mf_LUZf2Y@>wuFa4L>L316n&fHIAMcmJ^nD%91t6F`4u)YN$*v z!<-d3hAzw^-Q8EuzxgzyB!o(H%TooHe2G%a&ZY*I7Sdi{7jMZ4sS9%I>d zbMXxW(DV$b4zk$4=jVS3_amuIMdaiFxE=ug&UofU-xoEU9-BZ3Apo2fL*sib z={0lc(-bgJI=NTtfh7oliew0TsJabs2wta%1+7q3Kq>*w6+#JHw8N*jCCvS#h43>+ z3Oo2ulcR{KMTYG%_i~FvK5@@Xaw%)Ge1yro4d~1+q8`6(Cle{PlH>^D>&fJ&A=>cn zL3A-@#pB<2B#)ir14L)csuHRKvsTjHMCZox+C^2EDrU1O>-0Ik5J-!12ooSZ>M!p_ zBFWlV%s@E#7u0*>9y!^}Qg*zYwx0HQ*i=U2%0SEZ!hH(WtC{WJwY`H$p1iE|igtql zqtf5rGH)}e${rLOx(=>Y?xmMD;ukkfzs1U0E<_kde#DAaho+DmSM8$UfIxg~XO6RW zkCz-Y;q^aIrvW#&6YHc#b0nQAs!4x19x{td+MtdAX>8!h!r8Im|HrZcBm|4#e_c1= z@y?cEEBtGuv5o?KIqD;izhX zBznU(s%K|i>hl``;FzF{2$I9(Z;Ofc;?s+Fcm~L?24Jpxy#~^lW#^X9x3T^Xuo0-4Gw@sOYR%rns`;@6 zo%{GncS7i=Ky^!rJ4NHsDigfcL60nf9aU{+2)hXH8FpB6)U<+l%&(Z2&}-e+_J&Qk zG!Ar=+auivNC+OIx}AIv9hN|_R8*7IxcXLVXVS-PDU2JmZ#dbx?R*0p>=0PPX#6FD)pqTD zg7}awo+TB&d$wq@RDb$Yey>vvY`go6rBkKgZRZ{1qXZZEVw7^%6K4|e=XXh=*3|+U z>9?9xEOcft)r>!GlR`{@A=-YhE)iS0%p_w`CMROP%}1ep^Ccz4-%A}yE_2lVN+At& z$*gWeG~(MC0!RUlp%-gH`XhbxNXpu(uA9}Z5p^4-yQ_s_G*bvXc5xP&Vf13;>i{Rg zpp(f~j>pfU+SzcW{R^^XK}Fi>gu&Du$=LJnQ%?%sIPYIp$WRx+$Lgb@evQ)EuW6?4 zck6@A{* z&a%g}2QIM(=XOcB{@=qX9GPzplQJq?L1+;6EC* z@zzc}y!vzQI5(rKHpcdaE{6)i_p2W77X(sUB6n1_{wfYCipQdx&b*}2=TJoA8L_r#Zx!1XFx8v~NhGX1m0Q`9M!=>Z+rkh;(oX1yD5I^3{P z)2)cxExOWS5MPduDcRLI;nBc-nNO`n;TyWP!_=P~5@<9$Mu}LI*yPAuvm^C&*UaB4 zZ5k%QcyQ@27F@O2cSg&DVRO4^G1xg6I9&Vcx2tw8i_1%7$BwULij)zPL~%Uch{^KA z#G3bDoQ{vZ%-y`YAR-`d_8RLfJ`iNE()w3PR}>R5|2X#EO`!i8kY)HvFEjCS|8X%t z>o~!K0?-u(X@cUy*=dqNVChSLy%w_M{t8nt1^+e9saCC=4JuI+yUSUEiW$JvNC60# zseB-SmH&u&;4OLp*dPBNWA7Yf+1I3vp0aJ*wryKowq4cLWpvrLZQJg$ZFJdo)vez< z@60#f+_@1qVxK?GjvXgrugtYh=95o8S^Liyk{|Hy2I#1NE@Agh0RT8fAj+gU`yNda z7U&xrXcNN)h-1Xl(HDaYmGaW%-$s*1tGdEC=a#Ih{Dyw$!cl#B7QF#Pi`gyGK7B7Z zpJsjeFoY{c=4wI0QlGX6>3N!c<=nT)JE9$=-2@qViM$1yT!52WRN9cc@+4=ba$)F9 zk6cA53kYl!e{qG>apSmkV@eF|hW$@N<2QM1ai?ACYsyojrL3Gskyo#B3-2O`>fBzs%T_8*4ZKwN?Aki6h)IOEysDcLG_ zNka13hIA0%vW#i0>w*{YCD~g(Hr(0(+ru$IzOY7bVv>kidUE*1J+34IToUZLaYI`U zoz%2TzU(B_tQL2o8X_hYKDZT_P!q@*v}-Jhihi>s36j>k@cL`gMhaAWRCdlZ`AeO# z)clt`XouQ-`Xc2w=&%zwV6C65jgqX5dx$G=g>6pq3K!|yYO|2cT~k|Ni@dxKqt(?n zny)Z72-XOeYnY?P>A!u1QC)eqSR$-Zl zfdfOD;mA;$LcO?v_wyb~co;8J3rl1lQw~w^ZoDC~#UcQ`g*c8BRQV;Vys9Y0jM_`L z#I~ZZqcl88I0g#e9Jt|uhs&9U^CeWqm;m;oH89W^<18c#97QGt%9S>0)y@!C5QKF( z9ssM*hz=F#hQE)&dhoIoj)HZK53O|CiowLoA)L_H9oe`DF_x-R}ir4vzQhC2M3z*H>OJr zDz*vuvF&eG1!vk@jgxhl5?pmW{Z!r}$=wll>>JnqFTd{eAB8^nMV=&P)Xm=dJZ#vQ zrvQO#rbFQkwhc-_j*Bi%hiThR+V6yn9 zK-E~>cUiJfC_D4~zljKgbpo)zIR=sg6tVh4LtPF4T(eqWTb}Vs7wc0+*txSj7x2m( zQ~?0MTf_@3_ZXifnIQjVH$g(!X~{x&P+XW(L20nN7xLK3Z?-#6kB|7uyv&A%${a!0 z0H^lp98$9lsIk3s&I5`Ps%!@dHsX5@^d3*(Pr-FxAQkP-YCNTle;%0|CuB)5u&d5Uc^I>FG$25&%iIzD=+JFZCBWj#Oq84x7 zwO5MD%H?dhdLN+S+b|#rL}=sb+Lx)!5~B1Y)Sh19lQJec(fE~k$|wOb{cJ{I6*nxS zvJ|N<&z{0pq>7;EHvt$a569qSN=kx){QT&3t9<}!7ia5N8we?trfVO9S^UG?J$d%{ z?(Ls4e4|-zZubf4XeQ-bLfRpQYfR#NFh$aI)yOh1gWwiuZ@$YnW}rCI83B-PW#10` z<4gDpEF$NE&$&KSon|2)tu97RI=^MtLUZ?(wurx%fpy@m9+WADVx>0u!Dw+)RjhJN zlixvvFi>{ke}hK;6Q29$-wOmATe1fr8XyRO|Mpz)SVnC|R)X6zLi{~LhpcE7Py|NB zSrM*5NC0kZ%7{TJBRgC`Y5(;;DW|ZVD%q1gpMgn5&@hg*tZ88)^c5i-`^mSGx;Bnr zz6#Edd@={WHFOEc?!msK zs#%9A2Omh1oi&3oB&|^_A$g5a`ijc*4~9mBfnL+76xk>$yyd>gRqCm2W1`w=%k&4fB+P&1ZKW3Q9?q&eCK~_myUE!4rN! zJOcoLyYE$;_`d+A|5U>G|H1Hs>CH!mEEXsQ#^HSk=N%7Y1Nl)1Ab}LC;l*>Dm_GNhjjmb?RTK; zqW=w|_?L$7KMCIVg^UR56+0s42LNP#e?WkofG<^Ga{+APii)^O#=@&wR@}qAuI+RZ zBIh{G(Op-~n{Krx9yC_?Jp#9v-6ObvzLs#OHem6-_{$z8=mIMC z&K=jq$7gu%Aq*PA_li=f<6I*ZMUfGJ-F~5Z)?SJW3Z-g!Ma~n!lna7K&ufbE&%onO z2-?gN+OtDCHsbijW!V?^2>Er^UqSqVs4xvI7hwgzY*{!_SaES&QQHJ_dXgD?0BXd& zJJWsOK5$Bl=|5l^4bxTnBtisN{oXwI-|zo_0}jE0|Gf17CfW;v9rh9cSn?1fCZ(YW z#oZEus;LtM5(bZeQpOX6&jkQBM*9L!f%j0P?o|eX8N%X79Znq1s{=u5VnhJmtX|;l7@k(^aPs< zFB6n!aB{^~1QI40rGYB|Dt1MA;K-b7E#JZ(4U!!jP(<5Ma={mxFNZ(6&)tJBGJ%C4 zjs#A3kqM&egDz}1)CI1IHRXhK^(IL~^CME-l4Y?l^cZm*ZI)C8x;(xSoDtTIXq;GZ zK&gaJuWyr%v!J*!RE=BG!Cy8-82OH;QH9crhI0k~HSeS8|5H7TvNaL_4l5KaMfe{s zlR{&MmCJqR2WY1G=SBu8BIuQN-?xCFsr0`d00H1D9vb@1(hHI=EQ;1d5>gk=FGID2=qZ6+(ZSe9!1J?MKQA5 z=G+4F8BKJXi+emTEu4iQq8^gi2F_!I%SmB+E115U;j8M&8vP16Y@28APS%^l3)H5o zZok!k3`CQi$j(^#QPF@`0gq%`trN#8BVvMdIBiY59E2&Uv!|a;iN^)kFG~4`g)x_uGNR|qlR=aveK%(+qRyc5) z+1vtORD{vBM_%rsF5Z-ZBk$v9zNDtq*2*`FQ44jyS)KKZlcpQJ=9 zT@Rukr8oLAh$uM{LEU>zHAQ|o(g(h`J6X}!m&1U!O!TbpcrCG5z+#hx&*xCY!Hz_N zchVFNEd_Gx4yEN(p{yof+VV3RjQ(7f8b=*=YQt%`QME>>l9h*c6IJ#;kjqy`8a5R$ zI^1&nu+{Z~y+%+nQb(KwTit@MA-4IP39X1ofe$%T+vY;M$tJW)ir-LK8&t;MEQDCB zs1Lp&!NIVj+%~w`50koYQL+|E!eNV!t94#*;2J~itn6}CoYN+caO51bKN5)^p@ON40Fvmyjk{^m=5DIZ6aq#P)n3A3T%k|> z_eKW(78I_E{3ksAf3f!dr;6EscAf&Pf?nlY#~A=j!@=8yLzV#4pUQD}R^~y4PC~Xt z!7#8+S-(dffSzGtA)48XdI9LyuzoK38RrFm+&5|vgckscisDIAZSZ_HWC?<9A6f7%gwdP(!7U)|UMovFr^7@cqOc`1um|KP6$y$oogT3Hh zFaoR?c#rX0s-AhWp{I=_|pltoo#W%h8gyDLnSbD_q?e zZ`!KYcqd<$%~wtTEkS}|Gh#4PN;6S9+DA%xs*nAiB3vgk+Fh+9ggyhEBaxIn;_O>w zE^ZOA2X`l0J(fS7&14V4gwPX^eNT3r(w7z1+&nn`nh;`pjg6oaZR9|9fTI<4MUOp8 zM_B;RNW*#(JWIwIF@ZvAGq7VQzO95D66xFmvW|08$~ZY#RZ-VKZf#Cf_`wthM|6cu z0CjOqF@G)ssyKTPGfu8-;Y!!FaRP~2(44;OAL_};Q|m;Zrb17xl~!EfBG z-ddmncIOqxm{zf^g3P?ac126Hk&L?a(322MK?J8ogT_di_~J`}i-HclU8C z)ZRT|kYR({iL-U9KWW2SbT9EcSB#jr(zW9}Pq~IX;~Ex`>p!iUA3)hnHvemo_iwqg z|E59mf48ne_%?n3Aa-b2G*l6GePu4f5>rsQxZ}^gaW+L9TL!-q5+17;>aqH2IGm>FDtkP( z`vBNVONvIEwrjlHbe(|3xYBtcE=py6(x=mqzdzpcMJ6WcEBHoE>CNK;8#}38J{L>W zFa2Onbkw9pK?tUmDQez?eL_+OyJ{G9{GmSzvS{r$K0&Iy}C%*DPD8Amq#Y z!YrZHWN|x6oCy)-ywr!!WU8v%6tdgI>al8Oh>bCFEF5*Zm;1I z&4s}DR(KV1kZML^?u%+LrZPTw+=AkvRkd)=77R9Ii`qUNKkCRb-Cx@9CY2IV$ff#;aDk+86jVhi-gEeB^F+{TfR$B18d~$IS@Yc zsO{Amuth9P- zMHBWVIF<^4eK-p=du(&PDyWzJNM{QU#F2e9R4a2}#j+&jlR`~0VU5UPY<8C=jk(3A zXq~RsCke-H%Qd!#rj^4yi+LbEK)bom3E3`G^%SPxAH9VKB^srDlhqmH5f6JFU)+d# z!NjhvOxv1ustn&ZNM27k<57dog%qbuY20qvxhX*Hm8T0qDem>2+dT?znH#M>#EtzH zkth`m^}Tt4|?O$_?G`fjWknCCX;jrE<2F_Vn=M;AzUQjK^ z6Tk?C3?9%t)_#Sn64KSg*Lu0rtZW>xToDxl_--Uzabd~-?(#z45u%CRF<{G zMeX08Fl`e<&Y6t6MyXdmg=X3ebLD! ze`f|7q!3ik_|S(vR{0AW1)vtbL%P;ba2EB>`>Lj}f3-(Zn^DM~50C!y{VUiR5!>>yvsyj{_Fh8% zo68|r%+A<0okIwgrX3bUjWqEX0zi6kQN(nGo(;8W!XvQU0u3nR;8dPniHycTobwkBcz0w}pRy$bP&+BGqBIoKbf1 z{2^2Z;DF>0C`a%cmJM3MyYZXH5?7|BH%|z zRNX!#V~K9@Fv$8xnda^90Wr{moM{Z4QLqLOY3oJSr36(*!R=*Fh0H)5K`_gGKE;rQ zZblM^=qvepT{c92K>fVeb^>G|MV5FeRcPoX?9z>JsHRp`qs*)QW*u>YDbT!BCX(M) z8ZSr)HTqesi(ewPQj|^dksk*uR+PbGQ|v?jO_`Mh4z)WuQ1mNl739ISrp#ayrE=Uu zW6x+UqiE>Y4&DV~i#g#=gqOE=Uw+gdYn{fi+mn0j3sb(4j|MB9VrcqciLXT|?%xg2 z!jnH>vNBzl2H6f@26$p_RB|DBlQX_&D%FH`6CBM+Doa|aTQd;KXm;E_>$c?quSQqU zC^>kQK~MGk#kdv-pISiQNZ{9>jRXkL#UVWgNTg>|EC19q zrSllM{TMfU^wqSG;nU8>8K!Fcg>@Bo1`&b>Z(N>V%^I6fAjW8l|@;M)6op>Ryb+h;_-rDsUqY7lyno8Pts+i&q(F6=N2BYq6GY z3$9sS%SMG!1XdS<UAZ{ac82Q=G#s|)vrGBRSh*ve4wxc+lfZt39mnj^SO*GZ2B z$^5yL_wvcWDB7Jd+N@8aV;5vZ4TN>c^E+SP6Uy$U{U_G{Ux=_H@}96(j z{gS`^y@(|QkP!6ts4s+-$hU`DB*&ci`xiisaEi3&yg+B^l$gNzmH}Y6QQR`*(W<)@ z;Fp8MLaZXrsuApPHIaTeM@VvY#}y=H8e;{v$WUTr^ z+gtKe-P1bxGp0m}o9_*x&+Fy!IgbU78xs!ZbqmG2H92m5rjAg`^x*-{(1BDb{KBWk zgNAm2gs`JD*eu%f{m9O1yKipid)_{8nSb1KW2{t>ph5mZj$LmW=0T%^S=R34#2fIo zc$zwW?E6G?^|r0c88HF~c{$sFqcr(RFeo+P7b3mAE>eF1X#jgZr1ep` zi?%ODc^bjPjf|s7<#Y-7R%Z?8Y{F^@(9r>iCEj>-`O5? z4abX_3vrrgnueRx@QTn+UFi&-`6P$N>VlvOfbL?ng@#WV=>(D<5lmRNtHQ80M3hba z;U9)6+k)!VG1kavGlLhY8TYH$-om#rYGh-@>umbTb9e9M6(hig(<5nWmU zDxU0>)DC5Yp@Nnb+hlP!rG@M)X(I*6#bv~9;{eqvGjxgGi+pfX7NbC>SFT`cCKri- z@aJj$>agS>cQdL%`i@9@uk*)&LW!!~Y&hogQBfG<DjQdL(s`t-9z<(M@ixx z;(31SOMT3F{Y2A|(*X=Zj8@6 zq8*H|U)(K;<>^2c$jn55XuSPK>41)bvWL$9Pj>X5g#3g>HDgx>+33W_ge!o?F5aCI z%4-3i1qw~prmZZ|olXX_S#=YUp)p|w@EOgn)AmSs%h9^oZV$KbG0vm&^?SIY=yRoz z^GbtyjkaRd*{Yf=s>H(#JGBN1Bp-9Swm)Wx1tR#Nc$kie@Pba${mz4+lX%kA6$+JL z0nP6p20*`h;NqH?a@)>$vCEYZK|b>r@pP*H3;@ImZ-C9OT;s$a9r%7m8A+=Haivh% zLKk$QycgNsO3sbnB06}gLsXhmvk)!LJ2096@0`4Xb{8>>S^%1NfX{wM^b+Gk`JU!i z9QDzoz-Vd|qZ-lJe&${COH3jL=xdoqRufdl)GnGx5Cr8WxbEGv2M5WjGk_9R%T{W@ z^T>jBXs?xjqF`!on{+682lGVCuQ>%y`mvzJi)zM7g*%m)e*KhuchTi|^yjWo74OK& zI9l&pT96c0L1#`!-AnKcj!@x zd1%#wF@jHezUTTiO(Y7-dNGf3$E(ySK|E7183mAp6e!QH+lAxy3jFV!SR1|n_V!wBqbv2XKJFG2vJ-56Y%L5}1R=0V!8ZsBo+ z&)cyiFCU%~YHkWDWa9b8?K`4Eyx~<))z1r=tlg`t_VS%e=e{Cms=S8XWM~gtt9#OH&yyuUh~lXR4G zc^11AJSr`XRBkO~AP}3t^UUpHJv`!Ei3v5`peJqg4W<&}jdJ?D;l62Q<_wNnj2rXwQ4pGE0mT zhx19ILE2o)RS7SVf(1vV%rw=0G@<%VLGtSMjcqTP?N9nOx}ko<7{-6*@&GG*FObcD zU!eby(u1SS03QBX7T%XQ&_b|$WE_4#oHf5tZ{+t`jn>K7N=^x^0TbSMpHM?mY;hGx zO88Z>)`wT`H$;<}r$bN6PzSr(9|@Q$@lTyqvq)JONQ=USz^M?V}VD>+! zZi8MK)0g8kLqb%)1}GSu=q3bOWr4TMVB%28stlKje<0TaowQiKqW4+N5(dIb`ivSv zY%BMWn!JlU8$Ew|pWF3p(tXzWryI11IYKKT?e!sCHr>#>GS4yYrtDALT2I&i1$J%# zFq9Os?+x(*NIH4F%H;&rp1Of)h_R(VkgM|JKzr>t!uQWk9y_4^a`$(MUs%|(IbJE~ z6-2_wO5e3WMqxLjpj_gG_s;EmCb~?Xt);y=Ue7s-CMB04fDtPf+q(0q3S_?@UP`R5 zPbsP4zdQH6<{&y6{dLh6PB?#(R61xh(*-~9KHRrut<%qCNY^xef!?TKBHrw> zzoc%^ssf0^9X$Eni4TSt`#ZGq@lKik_UUkWf|i67dII7_wy^#yqMxf~&yH<8=dC*N z%WJzpBbgud*048*twz9k(u!#Sw~kPVu!v1{3I$hHW1m|`0S;s>0`}g%Zdp+l+SLOx zSRx$Ul{T8_nfCYAPixM%;QNjT8Y1YJAl_G}Fo@n4s>giH$&}x;x7beA-+RvO+odA^ z%ccI!LQaL+&+7(2tXwmu*Nt$u^fN=}Lhb;7G{Kfs!a(il2)<@__*VH={V9(nS!sz& zebF~~Oj)o2&fe=X96esS&IQx=VW1JtPqu(!t6VXWqUxx|B4jMc6W(k_5{WM1wIx3= z&^wV)n0z4jZr^jJnS5Hpg~%U})wRs`OLIMvT0j2o50psI!><}J@p-$i#c1wNYehC| zD~f-__wFiulpThpg!Z>2@};$mZj7i>7U^!&)q_BB_wZHf>f@F#VJH2bnT-cF^-fsU zDLTHXEI7lh%+p2*hJHWN`TfLs-`vEknDy=90lD0?t$Sov)8HbE&XZ;iV@WKvEFAJk zbLg1VMS^5A3W#2sv)%LJa|WX`-Kh-nl;Md>bY)6_Z75_F6{t@ZaqAzU+$?3h_5+cL z3xhxyP<&hnTmb?iZ8EAZafnDv;AA5FVK+^bVJ`$KhX6~D(}9>6T1tl43|t|h@7+8v zl>UeOAD;5R@Tq^pQ$7DW-V|Pv=A0pY|9#Yjrk25gu9cu!3(dx(E!MSX#_kGy{pK4Eph?B%?stss zyUDYz&^Op*1pijgA&(1xfHxxYN8)yiddxhqvlM2DboQT&7Zo)qhKv8F{BKc^;)zngi|3$oxjQx$f$>8!I7pHk>-E{#X}kx|Aq-c0F*ZX^rj?H z4uO}w;4nLQFpr;t;=nV}p$kYpLF3wVhnunm(c)LuS+P|u{cEVNgWGCf`cHP~0%rIW zxec`%Qg|aA#J?oCz-C%i5yq!sH@E*{tntR)bUU&NxR*>iPoAptm;ej)^y=9@%UMy! z7dRD7-abOQmdW%&Hy%=EL9KXX4h2JZe31BsE?SA1P!pV1nuMd)s&b)g@o;2a`p9fO zMM|xsKL{l{{A|C2aOef{Fkv%8Rde&;Ay`n?I^L8Gs|}f*Sn0Rlm#r+$QQGi8Sv3!B zz~?YYpkwoGNgcPyW?k5$PY!+gs3u)6unuPLx0Y4t3bq+S%#QgGU9dcX(uJ-B&jk6b z^V?UX_BQZ)NHAOas~g;+kDlUY3Q6j9DC6ZLuadn$nL?KsmFHrilnv*>=IWAAaHMs8UN69PBzE8vMsL2~ zc+V~go>n>_i;U>D^Ic|STo6_d>|>unf;nPn=2AYkQ8nXjFyQH(7hk`aBXtpsQA$qL zE&4a~R7WKo|Bj0ewnIStjm}Q0z=3sJZ!Pxh&Q097Q1G|TGqABx_SAoH$^PxW-#+n= z^nQWABsQ1}CY)7H2M~l!zmQC_FkNiHZY8HJFnc_LxdN{%Ihp*vd&W>*d7+e~SBu9`$@gSGf=I%97`XIN9e-@()h;dkSV+(V;1 z*}bc65Bp#8q2X)zkSaV(P1z`k)ztYN#mrX_ZWt3>W*C!O#>{&k4BWEINK$r_!(~IM z{#-e+F;W0Av9*Qrm;+KjvHD<$%QZM^0T3NnDsp_K-k{+Njvt-NfOAzWEXD|f_qO?U zp@UH$p@}=0d3=~=Ob!uL?`~w#eH0KDvZ zT&!;`1`+o+_-sAPV3|>x@KQ-tO)hX_8Ez1UCUoIP`Pf?r& zZ?vd;VR)+JFMj>eckip9>WSTXb8w81DGnv%c9ZOaGI^#AqvKOOpr7`;X(vKk)<@CSOYTF0!4B zVDi}Q7DMC_Kxk;aMf~vGg3f(YbkNB#sOyDIlxKFb#7aEWGYNu5z%^RhS`IsysFaquad82Ui^C(}E3S>M-K{)t9w|R9y z9A5eyuCU<9X=JwL7iJZeU(vWLFSMnyx6#0<-VE~wBLJCK5t;~tP(g zpYUZMbHWreUrDR^F_W{>2^)m*WP{4+`Wj%*MG_BS#?ZP!bGRtI89(t5I3u~P`pa0O zC=Rty4G)W%fx=@H-N~i=)A4jq!Qvi^F=C@53HX!)Y1q;#5Q#GJDWjf|x5hNGcB;gp zi>%d897(DLCh!#JJB4iQNDGG24Fu-lEz8!r=s5e>IF`vd*zF&BT$) zY}(5)g90d$Vl=st4o7f%IzCiX!-tLL&v&O@kDY@yG6lf_gd$a29BnJ`9s(99njdW2 zAbnb~snO%t7d}=3tW#WHxHQ)p@ED~=Y)e(L*?osNe?*c+nqf8R$qES8YA0L9AP*aO zvGwcWHyU?rg7Wzbn|yE>kx%}Q8)DJ2cVv0=JuEQk&=!XVPN{Ms46sZtU|9X^90ydp zq4NkbeEq4`kv)q0{UwOsLr1d>>8{WMXwM)#{H4=50|J5Q{+xc~1mClej{15r;|L1L zd|XYodEeZsnFfoZnhdU`o2zlHAj)61GwT3K(wg2M%Exk{;PC4!gkbBB+{G^vVmF~` zJh)H~@!+%iM^P!Cd*$z5P7naq6W+CVpV*^4uX08w-cIG?JB5Ok;2zoIDapb{>_T0+ zKUR1qX}0@7==m|-RtU>52PKx-j$?4Hu|L{(0q_|pdl~k>Lc8zZ`&YJr1?Ao|p?Kt{ z%^6r$L^uyp_scDY5R|gSLSxoUOrh2IuWBx$;&nb?RLkygG!+)Jgs`apW*$B_a$RQ! zR;sZyl=vL=8Nd_;04@cP5WBR5PxNBGTb}tfzFjfP?5w4f0@1PF(Lad%T7d|~2o3T> zrmxN|M%&k!LpVlr6cGwGZkCOKTaEt=CeAioBuN1^fi>|JvLusGj=&Pv7fCFt3FOn( z1$$Uf!Vkh|CxzAsv{k=uCCF}eh9qu{X0vv+oWD}lHKy|mY27_Ef8*BV?g)S1O;L0c zo~9(TdNcscfNlVQ0`pBn{Q(GH@4q*o>4DgMRSg0gM^~D9|5;Td^%Un$kyRo9Pe`hVUcQ8v@VZOB%nMOy%aDM+zfM(3qP`v zzno1|CqXf3%7TmARG|XJKX?iHc-phx`%O`bj?r_Gmd#3qs_*YpQNHMiIB2(uevFvP z#q|NDRsaBEXH6WHey~ep5FUdov1i25d1A~WsJ{Mqs!PVu0= z7!K(#h+k&U_m7S)q*iYHq@7tp%%vyGR5@8Tm+F5xvCu+JVo%?hFT6xGW#QM^RKY(i~Sop)Nxq`cY zM8gA*OAgLh#Pja1inV$UFakA*K{yHiL?Z!s|5n~FtZ<)Gs8_-(SMU&3jU@7@ZvHc3)ReT z1Ivf}{_#Pi9YGxIw4Xf-JAFs-7ZLZ#f^f%XQfohL1FFo~8(PIRDF?bL)9^S`o&$Y9 z6$#|UgNHBhe|eW&*K*NPhI^-Vfj)$!|&s?7v(blQ> zl!Aiixi}j9>FUBb z7Nuq<;q^+Yy_+1z@6BI?=@o7)!~{39LC@sDYEm!U_))AawvcOFOsKTStfUX3Rm5S5 z>*p&iCkCKyn^2Ckk?56UrL2c>(LN1MBmdkR6ZS0&q^j!XSG5jXeD(*L+PxN?8)+g!U}jA^xiAI)8^~LIT5)l|y#t>ora$W_(YI(4Jep?hg}`u{W8H;5b6|D` zTW|EbrLfpD^W(8zEJYJMRyZ3SRI<=O~;gFKpQY>oYD` zf^tfzRH(RTtQA?w7&dL(H1$CPGTpY4WFs2t_SWa%HZwO}U7k+ekBHC`rvgC*yq*jXViIAI$N|#Mn zx5je1r*<(Q_!<56sE#Ee7|~lFA~IdmL*8asgD?1!8aQx&t*)mA!F>l@m^gZrgiP|j zX2eSn;)~s|#eX_=B3SG;Ea9|6rD>jt;a@T@q}W^%?1np}%Z~`Ib!w|vwUpI{SPP6~ z1g+WyRn>~eBH7z!L^TDqcU;3h0qnN$s94&ZWl>-j8ZPmI)yvN0$URXC8reCyA|G!? z<l079D(M#GoI^ zbSbSQ=dK%oG@=q2C*Y@39ck|btwzPcCWQ@CpnfAJ*_{Abu=290fb*Qf8Rv{w(1^LS zbkG|MMny|*Hr~$Ex&TWPJtZEaH7&@mE1;BGnKT!LFCGmz@Ga?g%7PxfW~& zNT0`$rGKRG{N_@Q(C+S;-Q4dOh%7msf57;gibc|to&Kvg9z|olT*_T(qwu677;e>} zgZU5Dwr&8ESrDmD8^(JMS1-%g+5nOWNJ)4USwGC|@gr$rJ=R;SO^Xk7ao4K!)S`;X zbErJ^3V%>V--(~TvNZCge(tI5@m1&7wuOgCe_<+%0Hy!SU6NE(pZPUfM!ec}GwCK{ zBa5OPUOkz_o8Cs*AFBrRxtmCK=XB@;Q9Bi9@d3U!oG4=L zhlEZHHb`hpJj!7o=}3-;h>`^68jrv7zTN~AoBs5%>r(5K(|zq~qk@TFOeZFSG2>Qe z?mZUE%qdu!gE6-1CJC{7z(|+iAM{Fg)0_Aj=oCB#`k8$KBVDG4@Pi8tLBP~A1x+&> zqmR3;Y`V(THP&&cJL~9@hTrfZ~oaIk+!|aFa?(U>f|MdK#kaN=8 z7FvV~jD-woBPTIcV;)<0bxZC3`$95!I=ijE*8))K@8TJG&Q+mYw-mhY z;dd|+KD^X&qG`Sv-`JsyTV9FeJ*P0OG;}psU~rlV&9~%2s35PAW)h#q)Aw~~k3W8{ zW>Vp2?9Y#kwKlu5?`U?Ub7yD$T}j7S?RH<`ybHqIGceD!ggXOomt4kSRzP?^f;7fe zsmQLfk7?O2@m00%=KOwLiqOygYSZ+ER22QZk5wQVmzhJZX8+k5xC#OXvePFweMh)o z@8tqE6u*FJCcPmKUDtUqnr*J~_s_0&2<$?_q$&O-m-!2ARToAtetFJTYBR@zfu%t$ z5Cc(=n7u|36@RCm@>1o?+dHj9e8FPQl_r{(QHc7k*ku= zW=@!&$Zt2AJVhCKZJIMBcE9DsQ1j$8l{;~;{E9{ER7CY^cVTi2#7m&raz#y#J9pT> z_>I8;!n?2`)WkhUqx`)un33qJ%-6s$_gh+~@J+#YPnmrbKec()hy%2G^PT+SdXQw$ zSu)*e6-|i12AxlmbhCY2cdT|_NY`yV!SkjR*x8=<`0m)}dyGz3XHWSRKTiKMZcnjoq*fgGLT0jv z;RP9W>DxvGe|t$BRqVbSko}2v%wOPCs(k4S`ESQu6BM}tX#$KS0jv$`K%`Rl4r4;a z-7}_t*`@^Uz~{i(hhHVw1jlWoWHAD;%rDD5+kC7lUx)gVe+Y-+z^@Q2*{kk7Al3nc({8?Qtgg98UMlHez~R?atAkzq`t4D77(~ z5jWdSn~FqT3==R$>m+l1`9X5VIcJyO>Y#tik)XW&W|mat94GxDP+|9W@=MnFw8YV* zd)0xT?ke*LgGyKpo(deMb;7Ra2-P9N@liA(vn-H%zaAK}VAg-llBeM=?*ZJH+E1}C z4SrL1@)T7rjx-wf_dd`^nDTgIo0QEt#uU3|TRPcBn*))wks~->0@80lYttW3V~AOx zKRFi?tIYFn%_vDQxZH{2R3?n8Ck18~>~iPewAWob6FK{oGQ%aYwtXfMGM&}|wE{4kf8N-p#9h(HAxZKDAEXDd-npY7qlSw9$NBKBgJ0ngF|jckSRH&PcCGZTT_k_J~H-<3=EO z+fT4*HkwL*2?_ic1SQ*#9s&RQ6LqLqX^OzQJj#$kO{Qy50QM#=j_t4Yni@jra>x$N z3l{$FCKawP`v~8t1pS-v6KnG68B%b|?}5ogYga^Lz^qr){+@NXxQPofDL1YP%R3V? zwN{XA(M%triIl*Uh7}W4JWXI1Q4@iJ?9bf@xp{2d$Q${3sJd3xg~OAjKr)j zq-{6e%sS}iFr=BvD3lj9O^3X45WHT5^?lKK6xN6$wmK#^G(`67hgH-KXe4*7L&c-fw{%H6&VLEnAz-^IzpnJBhIkT_~R?fy)bL}~g< z&sho2{0g_=d=fIOS*FFQwApnr|1$npzth2{Uxa_2MD5{2jut!(MEb*3G+^B>hFl`M2!n<8M_~pm zNuCG`el%_9_Kg|oaL^Al*Kk!f#*ll~&=b9N;12?}Fyuf6NfFJ|OE7=wbU#Ih^${Jr zC;8TzE6vMN31(Jbw>Dob84G(1{lW0UB?f4OPN@{RwLt;gHOgbVJ+`?z8he=+>95{B z0x}<9g$S;ZfvxUWBR(Bm%i9YEdjcJT*fwY?P3y6vivt)ra_kv9eW%B=@udAb{!wa# z`e_?cGsyjo3W!c=wcC{oakbbskNRXfug?yUma)g|kDTp_qOhwr^s_&gEOlEaulCma z8M0QC$-qpI)OY9ZL;@2yU5kDkPcUiLqZ)}x%DC~VzJ)K(+4n>lZ`s%_Aq;&p z2yxg2C-co}QMte{AKYGpo!(nhoGt`U^P(tfvO7+mANLr8U-uU9N^(-sV`2Hf7^7ct z6jzG2STJ$9fUSTa>%!Tvm9oU&(-5V-rBhZXvaB-R@>AKN9Un5S9+6UgPJ4S;4?}WR zCH2#Z^T?_*)0$wjx8g6li5)aE8hE)7HL?Q1{;X9dG1@f3M!u}z8yiR5LIt>A_cWLz z#Y|YKE)!XkV<8t&{VAeHr6N=QIj#TLbB%Tw!)2H1=bP6cU*zrYDhN0lx5Q-KzcbmR zQvC^aGVS^AiLVOoUoqDG8rv*km(FbVFdR6?c; zq~4=q)F;k7D8C3_8XXL=a?9kez0*#51m7NNaPA*LgL85$b~0pzqGpuQZK1TrkxfP+ z`f{__KfF_1YHmU{2<&WPTiP5AeQ!zK`Xz44G$nEe#Z^SsZb6+&zf8?oN6Q1jE~yJ` z{~rK8K*7IhWBym{_LcInu5aLsv2ML(N!y42Xe!0^C}ds20U$(b1&NVf6A7EY^Pmsx zEpsAJdVpD*?GH{*pN#kt=1tIH@m(ZoJGJEW>R=+1&03hYM^i=EP`h2dhyx6p-@%2Y zgt(Lo!^^XDglJ$yw5C+4NqTTadC28;EH66_QpQWvPA*zg={;@dP)vq4F;FLh@sa+^ z&y;fG0S1~5ewLe~2fQNhO4!I5b3E+HR$8Bi213+kE4%d)$qS%R|Ad*H6C!(B&wcIS z__r8^R_gO_GBh@Nt)coQc_W*{He^k##1hxZi;Ry@0~zLPZg|{7em1}Vn2F4w8vtGp zJ`Kt>xIVI@vLg0Sv!REHaHUApwAmX_*ipL*V`_c}t=$qT{21UT%(3yULKH)=)y25R z8I&?9b3k9ku%*Fa`mn0# z2Fu&h(ebC4|FWXnlyAEPV~SmXNuNU+jaZn@kB-1eh@N@s9QNK7s<$(iEd4Ll0{{R6 z008-h2%M_X6zGUg1|)k&=@-b|3F#OWZA&^Fz2QW)E^0x@s>ua{0u*q6@C2CfoREMy z$FS{9(!AGVD6_1x>*(LXlO|ZguWgyg(*3W$23pXyM1T2=C$|2<%qQ!>?pKsJjakcC z3SKsO$(-SXWg>c|tl=kf6SGMOf}YJ#o$RA=gQrMUJxAeASMF7$k70Fxl^sav%974= zFFd!6@rF`m(-Y{h!CU#@^CI;Wk*5$bz*bS%r~g`fEuCNoV8F5&>wHmpOzLHy&%36A zxjZI(%jELWqyOyE|7tyb0YV8lRB3zj?~%v3ibGe#+}F(v>U&uT^Z%aVUD|&{4Nu^7 zS&;*7areT3MXBZeE}TSKh#>Q)rodHjcqbjhaK}0_ER6rcvuE3dCa)1=uxMNaNKc55 zG!)V5r7E#S|N1!blPg1wMvSYu?&dMjy|Cxq#Edn*Y7Mve0&Y1&21Vp^EQIWNV9}@&G0&{O7T;Sdlrd<-WQtCXXVt@U8dmjH-l$-ccoo*-%pN2E4rQD>Abi1@(Oo zE7t*(q}hYtI6dx!V zF~=qDh5`!fzksd*kXNh5!S&E3>~oW_A&mNT;tT<2b|ieRn!dVowk+)Sd=Wk7jyO-A zP0k}elWtr4w`Zg}?(^Abh0+p+b4`)r`$0c?1 zc6m|M-xej~*%~z`h17{XwQ}8727OD}bWbWv?Z+1Y5Xx|B;RY#Mrzb`BWTXQ7bPOxI z^*G8}%6ydfr<7NY;T_R|e}7q>)pz=}Xby~30>IP^>#Dg* zem@{@blvzPUOi9y&cogHP{B=6(tC8?3V2J`V>Wwdo4I&wC!aRi?FXi)jB8a6iU)@* zh#j?(H5igJqiXr5F{utLSf$yqvj=+OI08Q*Z{}Pb_JT@kj-vj}DzZn;ee83cWF`^d z-6Jr#N`8suXxLdEfwymdIP2N@_u@DBP-&?Rc$G_AK$gzZb zA5*M~o;%pSIb{0Mjiq)j)d8y>{R%|CSM-&0~FmH&nw6R?tW}Z1ZD_jKt6K{!{pJCH?#=7eAb-MM`WFH z9(l0V`ZqMn+KW9lakRf?ZWe(xW^-R4rjG4o0~1+d>Ajd`x=+x9aKke|*LBANk8V*IxtH2-+92u-3&(%Cn)b;24#JXCI^~n=g4fRTW7fUEJHb-RwG5@*lCvZ zJ1Ot$Qi07L95q*!{`yqnm*nv^WXpD4q7KgzgdJ!-2N%;o<1wTufF^FbT)^4&w#y;_ zV!t}Qh!ID7D+s@nayoy;%jenQhWBLhs= zN@>(#aLymF=x*;#dfc)xwzk~tqC>UN!&TlmJE?K1J6>lBA;LTG*xPNpLmPisD8PKG z(kr-vHZ{<@w{IgMZ46?#F(C2X2JF6d`Q=s;khTNH5HPlLdY@7!4Lgn&~#KO6Ry2esoGfs`FSQdA5C+0-olYmi@4a)|DBc&vW36f3%E46W`USi17n%h4!iX3)!y3iB0!mmY!oN zElL10&I9@$QCnc@5ueyv<6o84cC~cYYxGq(L~>B*qhHVPJRrCI*k4%6kv;)^FygrR zn0EksN@kP+n$8h({ksz4e;MG1hYh7SqD$F%T`c^KwBhMhll@(i^u0R2fXAt8Blt>w zv2TbCvaaFkg4PQkoLHbiD^R--=Cgr{W6%?-W70Cn@DWA-gQvtQ|+Sq1zC_^ok> zbijRaPeX^zq zc>$kK7K_~KXP|DI#~kG3j|0@vwA*XeIAmzRv^0HX6_>T~Usu~h)tWokYvuUF`E@AD zKo$V4ex$hdH#1vHDGPFno1kc0(oBFonvcs0h4a2tp(vH%9)#z5ti`g7`)xN_)IWGf zclPDHlQq$`pzmLoCfRpN($z3{a3 z;&}ie&M@F~ztMhVuFX&Sv8<8?4$@ZCeUmGBT0Y)IA@D)ak(j@~_(a-+enI{cp@c;d z3KUy2=@^>YCPN032JmJ54wh<`oCX&#?RY)K01SCJi0l%(3@o;WR>Ey-VZqeEk(s{%xI!`!?GWUzT(<}lm+H1~S3(w4PxSn4DN129b*C``Nn!2Q>w z!RyhB1-gu>s|!Q3m#22lS7$c-j<%rLyL6!3NlNG+YPUmDyZ%yDyL3vd^0}(D8}QEz zsF`)SKEo*q4ur-7aD|5M6&WoK5=CG;!$0}13qh=FvEu=wUIoQTfkYzLwF@3QBp;Fm zTa{F_2l956%8*SN&55(3eFFJ9N@!Dn9xfQD+AvnS;EiK#Xv8o_g%PAZZ9(86w!YOk zxnjfFf^!zV{?8_6Ts6p)4h$08`Xrg8+~f@Am0}lg>Z;6=0j<0>Gl9FR?z(-J@vLanC}5RloBV4&t5Bl<1sR#BaG*Wrxj z{sI~{$rN*L?<;K}0hLO=2F`-Pjwl;INJuHWd(LlTD|}k?KRr3ln*!!D6g^-SPg4b= zm`3Wr(~y2UV5@z(?0d=6N?Hf?hf#bmaJlx8lE7)E5w} zBwkpj>sz695zH`sxnUEU6~*GK0PWVoqnFJV9l<;1PEfcwVgcac0jvC6E$g+9>7!K=ds8HnwYIFy4==*|Ko{i>~3A_2u0d84wigMIy}gqrv~oS)vth?Hww^Q1Ig zLwzV@WSp^&k_blA?W~tp;iA572d8J|{>5y!YnCZtfb$&KQXj14r{KucWEF)YZqfxZ zyQ+uAkh?VYS(7y>7I161AUiD6zlxnyqRA;*Au}B$INORW`(Q{~oTDkJh;LEsRBhj> zskTbcgYbEemBRAg!KU@KA@!Eb{DZtCzy4DMX!&0%tXk;in)tv&KDduu)7uYpISza< z?#2n3E2oefIk~7Nmha<3FcP6}m5X-FO&3+_ML7rzW*t$8t|+X;JmOq%_nT{5CKe$` zd9sHfUN*8MA*W&7%pum)Hx1)W`Q}+<_~U$~7a;2O+hHV}cRE-cXK5)+{r_bWEi!d>C8ZHuiJ&wQxWzA8b}e zjKJAX`K6RtvMuz>6H_$b7+!rd$-Jzt`R(F(we=hY>$M&xSh(1Kuen705yaC|TxzfK zzsYBDK!+hN1}y%V8vcL@(;g7H7SR+?1H&BnT)E|!d&S7RDuww+T7W{4+OYIKHu3Xi zY7Gg!5O>SXiObeomc5Z(uRq&iu5FF0S5?VnK6_4`eo<)D7CH&qaTU!$Zb4r2h|&~D zLGSUo=>T9#reOguum*+vR=<^b<$js8+Sbz<52!7SWAAM_&(m4=q&EQ$Ms>T2*Q_-q z57k>#?4Jjvc{=zSeMeK7eUNxA4S8UAHF;C z=zqZ-`uvqeK@d^@XUm7W*Em)CU6j`qv-Ogi6LcW;I-kh3d=}q8Vs9i_^gRHu7j`2VD5ai6 z)|6n}V=mEnghRR>qZcR~AEpjw6#Sr30vDFU`Lk-ip=T$IAXrxQ3Ms86wFijoR#$Er z+yl=U8O=p@Kl49{xG~0OX@B}?I~GSKQe?nZ^VqEEJ#~jwZv&t`lkoQ#(smCYk}}q? zZpsnvIg-vBDP>{vad+H4ddSiG6goSoR30>Kf;w!nzttL!b=S&AsSvPiEF_E!LZ9z1 z_E$<`J9c>^Flb$#vZ&yFr{xDctM^43O{dHxPRoFgsPZ!VJ)#^?%2NoYU0LivR~d)$ zzk!OKXkP01f!n!N1kVcJ2RJr6o^voGO1LYrEvlg9tLFYmCwgf$miZOyVhx+p-3rKo z-DFjcDo`)c$QQ^}9{WTzpLXd~V@g{;qd3>1jF7k!?JGYYlEG`7MQ=1I&K*Bg%8(=|3sNR84wa&?$Y62aN*d_qTP;-QDOz=vgNH+{LPymut^?R-h%OcUoyu zSTdv+qPo&PR0B}8H6kdvmKayH#tn)Wi5cTgBicUzGjUElrv`h-2&q-0l<*qW%8#sW zvI1k)x{ifj-cJPu(^e3=rBH)D)S>v&)fCzcg~rQv&6 z8DN>mKzC}*M(x+1qsZ&!WMeC)T)t+^hr0B;^FhjKOx@69v^&jX{VoZJ{otNK@XaPq z-{*A_xSLemU&y51vDg9*=F?u^!vBaV)ga}o%Ob{~8ScG--gMt(TTa*kKK?TBq>@?* zEYqOpJC2@yGRP~)E<6@>*NClya$9PVzUbp8$@gZT1@dZgxcHlSo^9GU=1h?VbUrX4 z_hp>aopeVq#>}unZw&ITO5*~7S-nW{LH|Z3ql2Ka%H3DJi|r#39COg=W&qMDh`FI# z0{pM=P)*KL7JhWwpH-YO#;%+tBH&|`ocSW41Oc6AW!1>xzw~Me1%#j6R|ZuVJF5Ht zC$m?kSs6yo0Q{eUStLF5Vud_Ey{fy5S*C^VIW_pAsyd3@L#DZ({|`2B+WXM@F{+q_ z(5Y|(#QyS708e`n2H5;xyDGYRS@T^+(fv(Ok)|LHt26i#>%1u2GV4<5FSOJVoEBhK z&oIRc$Jd(y&?uLBs|_tgbGBF(EE&W6ksjougOV#GYnMw1iiij4l?i2YsE!h z8z&m*^F9Fvc>iANj&@1J2rv#Cv^0QxaD=7~ZpQt`$RS3*oUMoNYMe*Z(OBI0o!QVCM1C$g7D^uCoeq~dIDt^XS69P zdbrBkBK8}~&fhK~u&w#oMkwTpYSHsPPp2@YlmCiG?9fz0Fw#xapNBe*le~@#oAYu}c1ODs)!vVl(WRi^41eJ|I_8Dw7tq+uz&q3QsyWP8QYqOF2RQ!m zPIz@4$Jdqdyy3y9Xenx>MR9CFmyas8|Arn2ywhy_B-|~xi{Km0TyB;4={- zb@Xpq7@2GW@-F2$koqr=enH*N5gY$F4hE1tN0M8~ED=3qHJaT~WIx1j`xCQGOD(uR z`N7*qs_!0uk41#)g!?}?+32i=p4$=c_o@i|!g(n59Si`fW18$xsMGtQl7u0uuJJ{p z+I|bXS=cts$_w3`=F?BA6d49S@A;J%w8a%SbTI5iG2`?h+ZJ5$Nqm-+Z=ja3!ZYb$ zWRa)Jz5MnUu+lu-s`gV8SK3 z^)eh3PjM1BB|{GkU0erwlA(nQWw<<^C$_1)oTrsx=_;V}D|LoMKk+tln?DliM3`lq zWqzVwEd2*BLLz(hQ91DRs_buWCA)nzy=kbb7tqcLyyy{lr-U=SH5F$K`cyd*oAf1)HsqCNOqJ`6zrlppJ?O6dv4ir2-@Ke}!?xK*R$C z*3i^9%3Oo?HA3RZ3aGYQ4pahg?yCH;uvHr+@hA6GtCqt z#5HHsDrC_5vo`94BmIQ4U{%1peRKCPeB$Ka5I2Bbp_h5>qc1ij_-gHE%C#r(-}*Wy zuaxXr7C3Q@WkmB8hwb{dhUU$Sq4)Gprji`PZI$&3k_S*EWrL>hSSPKwVgXt3x&t%G zrx-p_d&G}w?P-isaa{CX{%Zy+HG=AQOoFy-43D-HMVJ}Bkn&yY*c%fJgCKWJ5t-7l&napU;JV`Qs zJ8^0V+fpdw5GVTCp=B#vyUA4Eo}g%x_i|myM8}&2_R(xI zbD30{&Pm_2_ow}rkg!!g&|IKma<#IKn-mpS@QT1^W~Wt|+Q{md!?cLDFA1deoRx0) zlo~AJ6)pqnhhGitiMK7rcSg2J9plGw*Y|;E^esQiy&z9&If0eiRM zlw{~}O`bFWm!8|{^f1M<_w8FKRnn~OaNN%a1@`Te`)`9f?ysYF*rj%ws0C^=wnkp$ z#Hm14R71=(-7`I=v5~+~ZUEV%)B>7r*gN!_SwV>f^f%-pVVUJ)dN?iBb^*vYAuOpi z<^fJSU^Qx!`YVl(p2Y6ELw~E=qObpQNFm?`U%eY(_6=M-@5gvKv3Aob1qEz`b(sza zJvUbp--1hlc6oVw;5Y7&y z7)3(gA6?zYSqqJC)h0^wN0vtrO+oehgtz0Txy_S_mk--(se10N(q1D?Psb=R`hvZp zG!Bsjg5sE20l{YCvQdPyl>8xD4Sjl7(%e zU(ZCQSaidglXs#eICBaWy7N-LD59;Pna5@OhV+ z*WppFF0q_ljukhuG>SuBbXUqRxb_Q{M#bs+y2rBcC8;Cm>qKI=Cl&@iYAxIE%3aq) z(){7cV`W1Z_KB-j?{WQ07#pSjK4E0Qz$=>3 z&&}>SfLj11_*EU4_6bIy8M9In74?NO(urvTg4iBowaXwf800RMQuL6W7AgVMUJdGTz_>7az(5-r= zENzDKa&Se5T_RqA9+qNxbr!1mrB_PHr}^^-{9UK7;7%kKFs;rP=uzGPy|x4BO}2pC zGEK0LzV2{=FS2l#Ha&@ecGQe@8>M-Hv zKALm$Nvv@R1JTR@U4OveG3%xx2{@9hmH*ee_!%>MA{*vKGrlLtX)8K6UgON~7wJBj zV@m^)7Bs0~458A`zIO-FfwzxTv5gJa)BnWta@<%&Ov-I=O5nuN5+gzj%&)vdgeIVu(tBq?sDWo$Y9*Y z8s;0wX$ClJ;TGVpfu6lU#jA-=$bT%_YbkQWs3f+}P<9Y3Ll7bK9=V(lRcc3? z+6zLm%);X{;55x8u$e_>E5P@HS85z0SqIG^NxI@hl$VPvxu+1BsmSAcW8RzFb3)B0 zs=iK@qnSkR?E&5VgS0w{c2G`V+U34Fzm zuu2;Ww3~p%Ol*_7$})ycTRro@sl#Rn6*2#5~f$BOx4)Q08%|Jk~44XAzN5qDyGUjAH0w@uk@ z`Efa2zBO`K{EWzG-kqQEB{vb{!Zo?s$O=}2AY9+p@E%W-K*Pt8X^U`U1e)z7$dWqRgbEcj^2 z`EB%@QsADEz)Ist_g=X5pppdTfUP*rpE{pH2-K6))xLoKZ&izzPm<-T7fby&B8}Zt zm7X07zWuW61=bS%zVGEi3jgGnq@h=Rr6XP)jr;#$sK`;|AZs*!rSqrexl95piud557SxfPZO08co&jH;W=d+1bQI%VQ4wi=$KB85Cpt)7w zb68D69bx!9u&290yxZWs0GNDxCsCc6koGJ01|;ss_aN;*B}26vs6}Sbf-is=q8^ll z{-Q6wJ~Eo+{Q-?Vakg6v!6~0b(RHNmg^5Q+ekp%Idur7_3O`s73jeaH%)?}XMQh5P zm+7k~jNoKRk!blef%}Auli+vlQr;h!k_SMB3=8sBGWXjOJIh3<5WwgrI=m!4r((eQ zDDfFTG8YpaDK22EBox{?$g-6-NFo`PFjx%j4ZD6UIHSSL_eAtXd_OV0V0x+S?TA$M z>OB_Yf~FC5TC=blG&rz2RT!twN!t&?AC{{ie67$>#_^RHH;9-5DWHGE z?sEO0Zde|lEP!n`EJiRD>P|S^wv_G~L6TXor6Uk*G(A%J4OmN26qW8(Gn4z`f*43I zXXa%VVziJVvMY4#^qv4GuruxCq@B58tk9|6WmY@#g^o5~b1oxQSL)vY#IRf4Ns(!^ z4Re)BaWD%q+wXG8bT3G(lg*h}&JgKktY6X@=xi|Z<+LiKMO9nV%Q;16nxd{YwE z9F9U54?fh2ZcwkUt7G1;nV2IFEWI;5HM}6Eb%~#2x32gC@H|&r;n><#gNVWC`^Wd- zS^_=s>qx97ivPQfZoDLaaUGNm0hyh1kHuo=Bo2oH@h5fx{})K;MbZR{QUk}K^3b( z4#d=Pq!4l$+d3CjH3CWU3n-Ax!L-cJM}b|Y$o;=-Po@Wq`U$w<;)u_YqCyMRPVl(C zr1X~%kazii_lJs_rs<6NJtM=A-^-tpOf@_4c5tfC?V=(Z&0Wa zpyr6l{TL+eloHvLLW8=i4hoAUV#1%byOI8dTf#ug!iEO)RM;OwS>~E6@+mV0P~PNa zG?UAth5#9{hH$a7@_me5Be~U~C|&fMw7R-_^<}MUu2EVIhC9FEJ_~wauhKi4KYtB#U^Q@!R znK+Kj!8C`I{{@&3Jc8AjdvP-2)X4{a|D(a!2$3|s*!!;lYg}>PkCfmuYpOaKKG z@~IkBUt91h4C5hdJ7k6_Big%v$p_WXs@1ChCuFV}g}ZWYS? zO;#SAACV8RONuZ*g@qaB{+DL@VoNOd%Q%7Qw(gw0Ruv}bHJ9sFxUFG7pNd}@pG`YP zG2Dwt(f6q34BlsYhev$DT(xVO| z03uudtR-k=hg8@Xt7ZLz%kJesiuj0SB3zr#cn zz_~*uj?y!@AkTc}tawW0Zcz9299Gk0Z`Q1aZFM!~u*Yr&*B}0g_b{qY1BSaK{%ahx zS??Tr+K?$w>|AC+3(W!myup#e-k^qDCUj`U6P{zm6H>+8O3XAoV z(XVf?7o7+!cIq4*^ z@#kBrb1QYko|BZ()dP$uN%je}3G6T<4xfJ?=dqgTYwEs+lt|n|>#_d-^vt-zWYYqv zNMA4L9q1q{wp<>b!PeP(Q#3Hn;4AyS?XKi9+Z-ww*=KpeGOrltyq`N;1 zlmw`=h8I*VY51?ECY#0c3a*jJd_}7lv#c5@{)!kqEt-aCD4WaCz}k>$s~Z8v<{tfO zvdP_PVB49v?QC#2FTC`%phbKtoPT17lHj7YzJzL!AGQ`MSEX}*;aDC_uZWShR36Mf1byn|fUGWwa8)v-Of->h1aJ$VW>lp@&oJ(lEyqp^tX@_0Aj65-93+;9R4K;r@Jqs36)Yre%T%&Z_*#g!?AKm5m z9Scl?ejl3qvxBisb$^m*pZwY?IVy;%xaL>sIuQJ*;UyV^eQ)RZY{kyK{Hf-DazM{I zjz3#+#JW(JK$~N55K8mxU2|=@Isa32G`z{%V{R_boivCBANvuS;shM$#zyWISL2r; zcZXO#e%2D#DF)<;&05DVnZIK4|5_FkA9mkU$y7e``XTDg#@v6vJG@bdBKgSHXjxG% z;sg4te=3=B;x3}PNAwathI_`e?)E=^iJP-!hnQabHdFu)ShwAhJckhBgg5q8EN0!R z$}SMc`$E}eg8ud)rWnso0AfnnO>PMSkaq0muvUh{&?*1Jjl?fh*l4({%X6pZPO2nH zJeGu>bFK`x^C+Ksq6OIca0bY;?fIb%_J2#cScSUeA(O(~J7FFCo~P~2R$C)FaN*IZ z<_f?9I_Lb;``Qu$@fQI2u3P%Pau{$J3eO2H)e>jtq5l5CMtj#L8npbV$%eR;fZT61 zNL%cfGTo0pp?L?XcGnM&E^oV>FEq-c147_srrBqvyU`ZJ#bchSD>Fo043y6&O*&H_ zX@OZ(g6Es?%DWeTo++j9)aj3zo_l@#PhpadKZokBIQY4(6Uymt6>g2_a=z4V@^(f= zcNU2(K-Cx1L$3OZuQV>Sa^@@&5)RJ_#UkqrMPjQDE2-GP_eN_eq=^uvd(-{?S1EG% zNVE@Ea;d&5QQXn>M>|F1 zIq?V;(S~P(a;JuICTG!ic;-_0tMJ)kS^pa6I|Pt5NpMK|9-hAY^9SX%X`x_r*e`tQ zivsq?`5@NR6Q&;mOcv7j+8!8cC0ai#waHGoCL00r5{gwJXbephY1<5U6YSoy)^WrB zhhv%W?26zm#K6A!ykm}gJfOvOl6sZP@3O}cj8#a>VyTrq>H3mQ#na!aH&pq$cJI8h7i7e>aOu?l1 zB#T$XSa*k?g6qPt$_u*#|7Ai;5a`JN^be2z;cy@~A1!j)QKY-V0grl_r+$|d%g<|= zVB<>989L3v!A#df3NqVy3OkinMpTz~vzaMay5Q^|oH;vW8F`cA?f;H-DGg$?`Yz?L zM=-fm6BvR~4%@v6#bs!4)q))MkrLO(D$}IXFl~^GB5@<+_N8_>C{7xxS^#}3{j`tG zKPLkEAM=Oz-`$1iE_AY6v=Lw_+x92*yBr<+hwBys)9^*HaZ|RDgZ?@uq5Ps!=mOu& zeoP|UlJ|DI%jGHDSFAx?dV_A;wULPH?a$b*Xu_n5gjLt>`c$oO-7aDAi$Y8yxpes< zoKd^HVc?;8kH37NgaFuf;bUE+y#t4;&bqsI)m%2`3RDkUq4zBGXfWP`MEe=bWspVK zkT*aK{0X?eber-nOC;p z`nBtzYS3cw-IUoM%UuF8`yv09i0KD_0^bC121LQ4iP~3AwOVJ91>(|78tU2Z%%h&+ z(s!JSy9|HXg)a6!ad>q>nl7)icJA1sD1%ygnNJ2BBWSc9Ejd@Sco zmheSUY7h@k$gs8Xpta6*6)eG=vm8U#5ta<@0ID+7-Mpq(;0gK}>QOINStXJAeDZ%| zm&^Gzd9~TG_g{Uo#{mc%(22%u3B0e1r4hLJmjGOOo#Vbw*Ey988TnmHB$^^>*N~SS z%k2?ff;5>ThZa2$$im~BLFB{O0^%cUPOH`y7;%> zCzkO53AOl@A5{m^b=e?2H?#taLJM{W2BBSNxu7%Rh`f&Y{Y78jLx$-Qw5x@d@txgD zSm8{%B?W19vhP{Q|3a{LtBou(Z_oPzsh$UPr28di?k*y(>oNPQo4T*r@45$a4n}Xq zYd2i^et4nE>A^H|X%Jv(WE4$npT#jR`uqp%Z&r^=5(+*cerr1~MRePby&o@G@aQW- z-%xev_?TD=!i?f07xRlr@TR19>OvSj($k=sHL7PcB_>Lh;CwI=_d!YtYM+_{?gNN5m?8u@LATtuD*qpn~Jw92*9V*-}-!>JOMKEK=b6tvag zb6?$xixt0+i(%qT)>o$|{Bvvrx1OSI?y-#T${b2&%1qz6OGQ%7;NttfFkG;dIKE{g zry9vr7$Q7alYKOO0xkrGerPGpUdL+G9$8CeYqS>I4$C z40E`b>-sb-hD_9Gq&Nmu1V#8vn1TH5NsY!l(4AxLTK^gHc5k_A;Jgrm`ciPNM>+p( zZhNnk$Ry%Jf>V{VxE?Mn|8|Z*Q>My(50_hc_?!n&5LW8Ww}4;tp6m)`BT<>ds@)g= zt6Ih6n+3z>t&Wq{>u)!`wb;KRhoYPXToswBHu?_8YF#ISTTF{l+-)J$%oDDk#Q^Lu zflY7>UrQ029j$Jjk6;G3tFpLGq_OmV%X;bRIg5w|q>65EM!F_C8YOxab>UJIpuAUp zvVA@Q7!hbqLG!V#LdrU&?Hyr;#;f0+dzNpr6#C$s{p6+E*RT`eF4uePY8^Kioh}$N zqQ51*vjdBRq$t>Gnw6TiLORP$4V;Qp4sy0KKX!+}xd!Jizrl@Di%lCt#jjX}P&)4j zOehu>T{|#Y9?fH8Spz1UW_pW4+X+5v9)J@%hQP$h61#ugi3oDjc?E-?7H7?Ad>+t9 z$hIRS!gv6Alb4N_`z_nkgOTy>{&qGQ#b&`e{G#v(N|wR5sKQWEE66bvp@hrI-@86Fk1;+P;avJzzxdp@8qHsa?n??Kt z`(9;z2xocx+(2m-J0c8mZpw3$>+t++gyEQ?IcymCJer$h%_>96UXeL32ZIz= zK@e-D9J`}#iGGA;K%SZ;4gxUXe1K;BufnfWNWw;UD@9{;LafkGw&S9H;8IF@uC6zT z-W3Ao_c0v~Od^s1wkovBkB%Mb=?V&)Pu#WG1KZjAHfgqwIc>y6cHN{?2>s(IKT19N z>`aIe4lr8HP}$Xee3a*;9{!-E9}AmUHr7=90p<*56Ebzy!>i)fst#&^9g+X2VFuU2 zUNVGjOcswVDMXzQ{_-#z5tnm#A^a=w9^%6_{-=JL*2w>-fp;~b-~ z?JD(E(+UFn3D}#&vmwLNr1+Un17lZ9ZmHI6!~OOR6P41&Hqf(a^KD#c#)A-gtPchF zM%-vl6{-G2lF|0ph+E^FWT-ebw`g#m4KvOodp0MBwt4rzdR~L-Zr)^~Nec$}i*3t2 z*g$3#-ZkG&uZC+6@G?j3xR)QFAuk3l3MIz&^(c^!r}~-FYCkMU0A_(f#N5r^^QEeT zDjKvDRn0;k6Y9L+1MbtFDE6T~|7xiA{`;6Gc2(?x-izu6PuHbjA19dQ6FUB zD#Qb57B^={@SAORXQoTw;$Pb3kS&9pDo7O=0JoO;THH@V0PK!jOD*tmJ}ZU!=H6+fup(%dZhp5lzq;Bm2S{_%ACU+3h;;0hJxnll^* zOSJ~pz-q$B;wV|s0am)KUdX7@s+CHm&lr{*suvu63|IP~03@Z^^oXi?Y2~(%5P}t> ztG44B*@_T7oruQF^_`6sh=f|~Bs!>*|D`Do9hKff$Sd%t_P zlZ=rg1D#W8886Ph_xr%q=he&^c7 z;*+6nN1mE0UWmBV%%scD-Uz?%YcTB_VLR<{qb-*r%H!MWX?ZZJ$PW8O@5^}>^?y_v z0m9+7U-2w;Qb2XA&O1dg@clSxq7um-U8H2#6o7)WaqZP_0bgbO6-enu6Xa61r#bNn zv93*NWy-AO*=g$%;I4GcVnC++Yi;Yb%=@fs!efTAZ=Aat$@Zpn{>eMTC?DD{>Jd1J zn=QLDqi%33ts|6d&9YtBo$I@zDxH(7B**6!ffMwZs~zGy5YLd)nblk94HO^qC zE^~;KKX<4Yq=6`W)6XD6_lPsaZ-ZXUv+znxGPj3v_DDbzL zC-Xlp79^51fiFnqpT@Xy;6yy5LzOeo_oYdwtq$O)a=v+dH&V#D_3DV5%7os^Wxmm$ z*Fkx7a3|$ohL($~EQE|pjBBS|XlL1jUd%OKPL$0FQ!?pyY>Xmh0nyle5&x5Vnc+np zyEuT`PA!rq!jPM`<9HD$@7Fq&qXGQ{5; z?tP7C?H?-2NVl4NzL5@;@IHgC2bu^MMWEwviLPEmJCF3r)+pivQ6b~o<#50rfxIhnn zmgWdrM;#=q1)Nb=WotR=Fn%cZK>$ENzrS1m-JC4dvt}l)%M?e2HlYB$nOpQ~L+3OE zog{usJ!iCZwD@?B?4eozk75#$Gv>|>5W8m-!;`o*bb4Q$X?mvV$`bUF+dG@G?B8)! zF?1Tj^`{#RB%d{ByQQfyFG0e0xLb*sdyiz=(-{o8p~jmK;>B$k>=Ne`>ZTlkpAK}} zc#mTFT}%QxnpJ-w=mH+1ebv|JYN=%s9L+%GrT%`BZq(`&PQK;SVemGR!jKBsAPhaW zU<7|QRq^bqDlf4?S<|scAb|_JG$gIvr000LhFw@Mc+Yrwsh3|wD`RvG6Ysi_c_Z7@ z^5@Je=^r<&h~F4Oze4o5(V!#n#8*Eb#+C~-ORdtC`JX+(%IxdJz7!d~wuumCyAm?!qaI`oo6q<)goHRY=?>E8GM&=e zsk@8rI}p)CjrRj`o8D%%YA;OTsaTFXaw&n ziZvtpWm4XVxmxwv^Sx;Vlbs`Ev_~o`UYJA-k=-fUv zV5tza$)~4vwnqUjK*k^66aB@?*dmCPnsxPC)RR)(F`eu_#rr*}imqE!05J=Nq8Wta zef@bs{US=;US3-GaF%c(f@KtC!UL*(gVRaxCG|fwx+^+c7f(CO&!Yr>ulLzik-}$n zS^#+5%_Qd#VF`cCvhgfp*$#syk*jI^6>&>7XKe+DHc7zc3X<{K*jeSRRGx=FVdkHyi!xwsp-hyfmJh?5Z&y3}~7 zYZsr(0<>+a+!%Wggw6{U#udyE9y{u(_xuB{pS?^b9nt0rV{))i&}do=wUPx@Stb|E z8^1I}b4}Lb<%l;t+gQ|MV|J26ewQ=~xN|LTKhkvjZ#(!2PWC~ayr0c^c zQ#?^c6p*)l-|EEt?-pT+mPn)J2+u5(Ten+Cm%TPAxTf9rd-CIFLT}NKU{LLW;br=> z0^M+G-kXC@4mJLiMqpZjzz@38f)kZq?quEWhiG~)dkZ(wI#VX(J`$x|-Bn^`fg9F=v;%>yxy!k6ot<&j8DYvf#pg0`-c+I|6~rW` zR0PBO91-$|+pWZyOa5naV}|vC%_P0nE-W-Zgz0@oLw8s+c>ZPL8ghMHn(l< zhZvs#P3~nSN@`@uW0-i+aeDzWHy(Nw_O0KS3UN&OqY*UsUG3U%Mpc*%q{@ezZPBTB zKC$8j#j%W=(1MFloQtJ4Dkdb2PITShV<<6hHQ^tOS;(OON~}Fj#KS98*7u3FtWZX3 z4p6Q0s{ia{6VfXz@PrPmppw2UEwDm$r6OEvx>cM2qd1x8^Z?m_4C{S?`C$s`X-^Z+ zo6!-70C;!N1cfrL`?(S_nVi0-;|jktg4^=8M6mP%P+=77NQ6@`Y;m@p@24sp!9-Ib zpOQBUU+NxI(jX(rvl!84+Lu%h!Oq8vTmiGrx`FVIhFsGJ-J6c{V4UzgK#7a2E}b{k zqsV3Y1?D`BJ&#AVbly1l;%%~mNCV{pYb$?diLt$cP`c_MkglF4>uuJDoO z6NHIDc$w3`7M;(ZR;yZZsUk>6J!*9@8m^&&;&k1Zs899OjaPx1@#oVmQ~t0NY7z-L zv5A$&CU!`OQ7=}JR$cq?!y2rgqpxcIv%rnQ{UGGLKIq#u=-rH8bs_E#>bTT*k1ARl zuY_ulBNy#Rm)&?iLt@jZWmm^yLO!E!1pfGRXN>k(>+9@A<|gRV7jkset*y;T63ffATuT>=;i3L8)1yqD6!+d^{GT>deNEo$lp5hd z7j$%;)P%OYIqD2FQQ>w+&0Zo=HF6gPU@N)Ocxj)Du>1ROMf=I8XWC^L^jPoguIE?V zQm64eJH0YwQQ~x%260s!X)w<=XHiFq`#=gv2GYAX<~l?Oa#);~{M8qky0|4Ruv({y z)U&#gl;_x!Vm@ii9^AZ+-?ATXW=?061P4e}#LySOVm-WeWlj&im4dJoFd@+)SdzBT zZI0KzommbN8Pz`uIXP?H*}NJ9HgQMBES^5v027Dtof6#eU2RdUDr&RxUW+-k)uR;boDe#9*KM6T$?i@k_@Rgd z@jU!N(9E)*^Qle4I#3r!cVM{(>HH&dd=KbOp~wIZSPd#YC-9nmC>n~Ne4kqTC@FZn zohM%#%)ro6ylS@$98L(aK| zWC8yyLSG83>rCWV!7{m>^`GfKyff{xye8p|h(Jpkqxj)8GG^Cjs~EJd6lezL`B^$3 z(Klf??Xb&k@RGfgga}GrC%4{j{`0Gtmr-T(bb)PBFFtYX(Ad(S1M0fnAUYC3Gw4#m zmKCKg9yiQMdQMA+f!CqWnD8C2m~BhoCsTt6Pb40^ki+kkf2%(O^GhiNuV5smg=C%` zG(6{9(#Gr3akyQDF@_zouXopdzbskb5e$N)=iSxpVWAgGYhTjj2~(|nd}cj$ z^b5}qs!5;}thT14yHnZ-9pClta)SMjev$Ia#cHJg&5p|HILESRE1Rk@kjp< zB9bz_l0kd8Ti4jwB;grjYYX*B-8g7}Cpj}XHgsFpcsadTh7hj>x(WkcC7x{SR%WFBbl7wE&xA^esQGI+==z z4{mRgutJb%E)*(<2R+}4+H54XnqhM#H2$8&s4i!m8p5Uy8u+dH=`hSG_4)xdgK-Xe zT+>JSy$;x!`i1&dOWL*P;MY&fcyptp$JbchJGXE7u##2?n#Q;x!(Y~^H698TfE~=` zsUc&(_hg_zTovMDadQ1^C;H5H8SkDVFAXzSXmK`4x|d>rSTaRF2I%ulzQY}@5*kaZ zypD1htA=C9jfaEOr`wBZX&jfNr#J%sEwEW70;6!Qw070~{E|eh#u*!e@yM~) zZC@3TTxzKVpJa|Cg20*kn3lhWrNRY`va`jNxKFY&IRGChFoAogK_4EV`_3@8c^NYu z(t?oe*Soq!>m^VA4J9U{oWOWn#0#8<&}jR+Y~bK!!F;fUHfyn@eTJ;ktiKO4Jwb704mY=BoAm z;EVoSjT{2k`)O-P~b(GcMh9!@#O&ZV|a?@NqCDq?x{-qj?REe?McHC+x50 zS_(aSQTQQG>4Cd_qa!qRGg|U6k|^~M8Af6f5LOwM8e8Fi16`rC`2}|Hozws(rN_Ei zqtA$HP(`^~NtMHb)1f4M5e&GfPu=PvS5VLCw}S?n8bKS~BPiK3gI#K`BdZCAJMVZao}LIwDYVWT_%`VK5@< zQfJM}*+GEhxak&7;%zilZg`+y0!y45Ixscjhe}q7cdMnoZT!`!kaI6=O>dU3Zgho( zR^RlGL?}Od5s|wHSYhwLE_OT$?zZ~W9?w&-DlN5caul%rVYo`X;NfCPL*_RGDS$92 z)8s7ekcfzuJ+cG&3(1-9)d7nD(w$wkw82N0R8d&^c4^F zgplsa!hJ8rAv;an`ooIyj`5C@zMxlGBdR&ss|RTVh>EUFyN6?_c#8!xX5UF**yuC+ z`X$B2CAK||y!6{Nzl4ayA+gd2o9E$L;Guu`rYYN?EJM`LFxc))C1nUrU54cuHSd4N{7lUiwPunL^b*zr_F; zCvMdnC$T+Szc%dbJUWEOqZB)MOERS*)jxeUlY}^jXedvjni^YrCbo8i_kAdqXq;!r^(|F=cLZ@N1~wI?yZI~q0NCtSita0W z%Ae}sMb`=6M>S=ZbuTSfT!qiec9T}y*O8$iC>WP$-oJk3uo!keZ#&A2$cFjh!%$b- z{C7vgVRd|yM$6h-Mp={^~XTx);VKQr#arNb)pd;4PE430I;!+Ir zY7@C8Uq#MkfSBg}+4(mBE^R`)yN1y5WxkSVk=g3@Q=ktnG{C-EC*91!%Mr5$mi#}1SrbP9hJ@iPi~d6XgvrQ z3#L<_1{a6HgVq{gIDuzzyX8k|eU=eMD?LixD3(|E;I1#*MYsFvY7 zjN-e?SwbT_=b2k5i;@XjE7?WYkFA}|zPpAQnUj!QJY|0vJj~EAU2)I}c$H+%1<-aE z{fN9=>k?1?tpde1643Fzn^@$BOvU@jAbN~r&au=F9`Fe?WZ|iG?0Jy$o&glg-*b`p zo93kY03|Qm>%zKK=XmBOiC%ILPX6`AD@SSO;aNY`X~qE1CyVL7Y_%Gos;d0L7k_W{ z?q=3$TZy}nzqjMcz;*>uR%I)yc*Sqvre%+MK{FFnLWSL!a!jdm#i1hS38R zG7`yQfCoOS-HF_a%)3Hxa>rA?C2y9*4Zs~b!g;TDxj{>aJ}0zZ5y`mp!}rP$=U^=! zUN5n*=Uf7`yrTC%D8yXB-A?Ei@Yvk7x#GR86QBZ(2eqOgM(!7fdA zYqIQpQFyqTl3P3Us2QvIqyXAW@Ci(79sbgz{!jnCtz^shX$h#>$}7M;()>rbvZ3Vg z%@7!k=|1pfPVi%OY&$N-DXjZ^E{>dw|)@*xOg-inS8cFw+Wac@X)zSN)1> z#i>9@y=Dq(1`kJr-i7epgk3TJIdZTmD*wozd;3?gZMI^$JHS)z8cGjEV+CVoCVHJ^ z@~{eB?GOQh6!4j5t}kZpt%~vd%vSv#4`LBk)mRj#Cagr~k$PuRe=SyrHCPW%<0)@v zlIqverm#xivB)!Z+010orc)lf00hoSX3VxY>?li3-AoodQ9xBW((tVHwe1V64|(Fc z2NlGve;5!d>>PBRho7=6GW!0dC6F|aT44LH_?E7!2`CR8wW(e^H{6^SJfV@9r3l~f zIHPk^pd$R`+o1w3ys?Azfeb9fl2?87_&!_}TB-rEn-p@)O$;B;og z10KoF%sPRGI%Yz#Y;?=hfczp^qgO7dks62n);JtC_~;ke>ABiI=e%%x0xpocPbXXX zviCuYPf!GSin!NrX#kA_LPyu3lo$9zrEf14dVdw$8Xh21qnl7;p1G=6K6c>&w_ZBj zTlsH=NR74IVjV)nNZ^_AQXg&Hqm*XLO9%fjS!-DT(Z(+*rPPk_tAJ&@$~e+3i`}== zJ#R(U000931{=0it%TAJsqhn^3`srNHPh;svAi>au)l9a-^!xayrY&WTpQ9Jktds0i%&Lu~QWxoODvL2TJ~hOOY4nlN`dakF zNxvTks9E$rvq3z#Hx;M$6cl<7q}gS?mBo2q@{omLp!=-gv7-fk%alXwkT{U zXGXc-B%mi$ZDt<}FinU2oZ|qTc9sw{$PcaDk0rzXyt(;~t5Mx?eBlWsRCQ8V=%c76 zM9^K+LP%isL3(H>r?~joFM|n+cu!q?i#lPnxRHX1*yuarQL9M8#xr*_yTIOfi2Wfq zY~R`%ZWo`N$6J_K+&>LpJ0MOshv5oNYDO+-mP4%qVpg9MH2JyIJ3om1!duiYSg?4~ zOzK8WsyL@2X$PD*c@84kjJmFP*wXGmRj3xsX}P40HSS1K6q==xyVpXXk*0ge*v%2@ zC8R0Ji52eE12jpRY@&awhE@<`C-)Kq>NBw+;Lj6=a-=uZ1DSJ?=% ziKbkzO#bXFqB_KYrXfMHu2HO=5uT(!$F6l99uH($j>}vo(q>MfFtDSHw+8a?Z*{89UoNfRe1dxB1!|pv(b*Cx^D9VZEnf`+8I|jTuJS zw!c-@Fv3x96oav~UPEh&wPaB0tPY3GJdq~xS_s>yE~QOBXcZwk=4IzRo;jPo&AKrw zW10j%dAhnX@#n-n9-2JC*JhqOXmiLCYyxt1 zs3gy#6}Txffc0b@{Pst*93Y-6Fmbsqa&ooqGu^k#4|hA>$S$3?-;T$$M2K&LxpEeh zNIOZ1y3*FBnm2b@aU|tq0V)abm9ggG`UEY_Y zpDSLrQPs1$3&4W>%s{slC1O;N`7;?g>&F+rviRo0kEy>E`$p`wi-RhSk_{+5F9pD` zaLlDd^J$^KCVP-JSRs(kk!je{foY7_pWiiQL!p~L^GRf2j^<6@L?JpT#svdDlqMn7 z5Zok`VW@;V32cQV16K-MU+V&E(qQT2k#NMG1a%4aDjqbk#Y0pY1y?#b;V3oa$r!T* z)RBLC^^qqJ*68LMVBd-buSsye#81NsjxGaR+&>sCg0AGVN5-NGrUjKlU7++Otg>h1EWbp*L&SpdSzB{VFNFWn_&aSavd4ytUk&4R(zkO< zgBS!u|1JZ6er>l*HnDn@K5qv&;#Xe^X<45~HWjZ=-N8)eXQ z9?c@*nlBRWO7@whzyqc20-8c~O;l16v%gq!30;Xi3|^!qNIxiD;RCuD{xJ`#`r-i; zkWxDm0oCqAGh%mkCsc{G%B6-!KI)eAAazP!dY=|rN;L94{{kJDZiqD}a=5GEIw$xP zfsrn>R5}1X%w$)-yC3jAOD#q7x*p(fUNEpJkB)FRYpKRo7j-(79>mK!1Q5Q8L%WJ0 zl?e0@47cMzgW1{n@&kX0pKeISrzI2bh0TS++YPW=QSh|Dz03eE+Ucq}l|VZ>beG|1$ktR=7@wGn)w@Ro zf%KP2_EJzg3=%Bgw;#u)pznOI9yI3ZzA2n+4TYS4eAl!fhLm26mDgmNN^TlCAu z9IiH|IJyw?e|6T|ARZJJ1__w{S_Yj`GWw2w6bv%0Bg?!Kq{K&u*wR$a68Tg7j$mTm>_<-|GLUUN;{T%$KPn>L?66e4*1&h~|LkkzWFFE<@5^BN z&`Vr4!0nDhfPRC*iy$J(0FGu6ur6v)!gqj;Q+C&!1fB`gK3q$OR~IFm)ub1LTT= z1>)S_&)cnXmaYXK#iGz5rSUiosB(Z`kK+#bjdWLs^gAFP=}-?0hREp4Y2lPRs;#B! zYHs{Zx2L``*E0yTFz!#QB*uQ#kPjb7R5)N>G)Tq6Hvk-IL6wf_AkF^@l%asuWn_YX zYVjyx(!Cyxf~!pTKxzat*6m*7{%jTo&Xp5!Pcr9Pct7ew2Rn_BBbm*>fJUm0YabNUbCvS5TzfW(CFJ=M+yNBWR_kwHnJoI!7{wGBra{Rdm! zz;Gw!x-Zv-p;qSMm=E1>4s^wX61ndNtVIhBc-LB@3|U>^k?BXxAIefR|5&}uis!5P z&Mh9uT%i057Gyc_-a;w68=>5L@W%SEuZS?~mZS#@o}+JXAp{GdufB#+20j(&J;$ET zsEAgJ%ykf`EkA9d1VwpG6%3Gam=AXZU+fm?2)M&nW|n$gC4x)?si|szDke-Mfes%o zc_5=wcaQ0nNH$n>k*^yi!pHyvA?=iH;&ZdFFO$T4-Tt<}FrV%cT@6xx_3>!zbx%k$ zR8D{ZC1|%cYXx2yz^a#g6kOoa^oH^oE7>qL`!lVq0cggmins^|^=0j=8XJ7D(uDJ_ ziU-ISp$-r-hx>kS`0&3r`*|VSLi@v?riOxy>CbxjV@;J#p3a73Y|E@SXAZVkI|n4_ zAUMbfux<=uq5{@J^J!oR>!N>plswUGO15-Ro+sh&EkrSd0rP6)e zsTjC6Ed-7%oH5~;Y*V;yCIy-ZLF3L^+UV#p&${0=`wSm$sZSoICT`!HE9zW!;Z4jL zjbSJ~idrtRykFXoacF>mp_ARlu#-FkJjHMtCHd(5?_E_TB|%<5Iz?9Hipu$D8brX_ zv#;m8UzLZce^ z)nS*UO)Ta`moQEhlapJ<3qK%|6EcD8be{MOg7j&ah@SnvJGL6aiWE3|lD|P=4+A`( z#=hWhg=uLyv4S=j5p=5OB04PaomO!k?hkHp0-gKQt5%n)%sbS+Jl6)zG%>-R0{%XX z_w9Fc`kLF7$qCiTJ+M01mb{?a)0R24LVj6&DvL<-MqLl`!c#tP?x%AC4<5wmLA{Qd zu^Rmj$S87y^#F18rcaCn?NFtY*+#yiA8LGO@DqKZQiY7GcO2x5bQ{phf@-u8qkj&h zh_3`1>Sbm5drl9G34!w1w!$=4feRNdOYf3c+$UNl77w;MsWgCNHJo4zX1}R*Zx(Z* zf9<}^p4$Q&8wtlk*%SrqIXC|fOjZN+63B072dTVMm;@We+X*BR7Twc)yB|Ejf3PBz zs6&@8)U~Ll0QaCb97^B0^ltr9F6E!*^n6fB5S=5-i_0xUM>`v>qU+iXo!4WJ-fIb31lOB!Gqyx+@y=mGcnhv~FIV3bNj# zYlCmW-*vX32c&O+Et5==kE_Zz2DQBvHjs0Y(uH@}t&S5Ck*!Kb%;Ix8GNauuQprAB zdL9SBZ0wIXLcdfe)uQ$)8H9;kQ6zMZPM~VaWgK0DyNUaDzQiS(3ybfU98Rim?YY7O zz@q_Bq!8xSx6awe@ovNKTa8V3hRzi27DjxLIEafqUwNUhOVm}9g!r)Fa{l#wJgi%Q zW|gu#q{vSd9|TcRGM;Asqsn=ijXrm!IeOq~w6GOfFA&?`rIXkO5 z$O{O0=`+#5id{hQ0EO-M zo9rFkw?!{ZR9(ijXXFh5&>JA;_@uEY9JT z$EU(&_3{SF13e?b7LytCZztV@{7xskxQ`L9Tv*Ih@#h;y!?KU7r()TuKOpHs`b^7) z^q6^6q>IU=;4|Eed7Bn(iNhxQzOafN&RW51NlNJTrWsnBvyV2}S?tA@dG%{bo(}l! zWUA9nOH>MCoC*_QoQ^@^5PB$|5MJO155?kdIhJ(x86s|e(}H!U>m$~_m9xl4_(3Ju zqYz%zdBVb0!!wM4BGs|k@)EawZvCtX(b9O>bCRpt?2$`oZn?oNOZG7lsa3!ViF_^9 zQH^J}R-}r-mG?LX;&^BtR5)C5>cB@5CIymV+Mk(zBV=T7)8o%&qy1gXqnfKG#w-Dg zJ=E5PAoaEoGSSoju0U#A{$m$dq!Jxz2azHwv8UUM(#BaW++}r#?%)|w+~S#T;cQhE zgO&B_aY=~u1h|s2&D4=rKLkRW9@7X2>dKQJe98@>S-IKJicJKHKf6Osf=yKQfZOS9`6VW*l%^r9=15q1YA z%xBIZRSt?_vSC{!1q@KJS``%pNEPQLXkp<2Ed?ocjesK*U05MRO7Fy5973Td4A*U0 zkR>9~5`)Ob*w$CkVAbsPwp6;=P~7+b4c3d1PAPN6C=^m2`D2m*Pm{ZuFC?J5R&X63 z=2Nw+m~>bbw+RO?ulhWG8~WR-j>~#vKt$tkLwCtBa1d9{!#6!0P?<_i_kgmun?rvC zaNwiP*%bPMFQf#k9vx})z#05i_+Ovf59fHS*83UQF}h>ph76~Ue)+~y zakCJHdD~OwUC1)p4skmGx{x~yi;D9k$*UQEY%#bwQPrl=Cw#H?bTaA;X! z!;=bgbzkN5+Crq}SKMEQ1f?`Om?+X=}l_Oz& zDACZ%#dSS$v#h94>rVFWm2pp^0((FIGfa!1PqGL?ln-o_`UGker4p9)fAq+=5IvR zspt9nJC2FOehwiTEL;HO&Zrr}PRQ*{OPpegqil|oC7&z11Mby_KPX~(Jm=2>B>`~l zmwRoCBKKn89>)UFLGFQMKjl!{Uvx3h7eWt7adhBEIw_7z|4(rML9atYTrig59O%xe z8>>)mC#u6)M6*RKiF;=T63{@4mIKGDHl?K-iu>nfCk;p!N;fFk=fKM=7q2NU0!P;~ zdslBD@$DQSXv$eS~zDb(zv#O3B z8u@sk)7`Asj2UzI2$nV-Z-uK|ygG6OPngo9kV!L;>BUT0N)rtI=^ z7bAaX3c!+x9~Lw;MNC-}ef`=V8KO)p*)A;+;52++&SCC+Y9?GPM}4eTew$Xb9Z;Hr zzN`3ExwRoK*Lu;l5-FwpzJAHcnqhl2@lnkyAP*L*Tn4l{cj9toXHlhM7Cn~G2Vt~_ zvty5_=q9dwpf5l-S?Yt!-pIuvI6@02il4BxMisa|Eyi9_Nh3h>26|0V2(ua+xuMst2Z~iO6Y`#$ASAV#g~-SyoA3 z*+0_N8GB`Ib%K*ktna|VxPV%1txA{JOvM7hZ{VuVMm!+V&qxC)2)p4(T9_7Prm<(= ztvP5QqJ1)i&)q67wK7|vRJlEEg*e`IMTZ|4JFhHi(*yw-KK$*pI%}hzSSX zp5=R%`LYPXN3*p@j)n=mC;L(LQYSQ_$SR*WWgivMN~K$`qQ>;8DHJu8B>3Ip;P0+M zbJ()jVVRyWj5sYySbDj21{7n7`+nN{2AKDTM$+fL!AP!Ad#D|;i4QC4qcemgmD|pM zudl)&gQd=Thrq5Jum}hx0;RYSLg@Q1j5BZ)g1;5(vLa04r?B;*S2vqDMvfo5U z>e#(O66WN)QBUYp5Ez&j8GA}0JmYI@AtmoY9t~po{D>9{c9v>$8`^>@=>8v|-o10m z`AW+XclgCOF%qyaA4d%?A^I^6rFIIeK-^wNOJYJ|(#U1wN|e~u7WS-JofHw$Z~C{} z2X#2RDEi0^;9D|9=jehR1VaoYSs7KY0XeO;@SkGd0LwW)nE_7F@RZ?6G>ABE96*1+tJjiIXcF3S}%u0A9X|X_!22btL`n8?ddghE%K6Sbr>bwxy z3<6=~8xr&Y12ewzAyq2;zMoQssfkvUSugJ=Xy0_F$BYUkc?rXszWHqUdCp)SQSxqj{@O0Bm!|!^h6LGX@>~(lJws=f7$Rij6Z3wGPHy%td}OnpJjnh; zvK%b#3;CC)iT0@FTd`e$z%PsDtr`mgMLG+uyABW?Rq} zXH5?oCZqoV+Vzyu)h{nLe}pi z!9mS*LY)V$`yG1tn~N6S64WRMU}YnqjLj3li=CA5T+np~2e1=dejmcEzG*rMBX@Xw zi!R*gtqC&y&uNUeht7bl{(w0(Oh$qs^VOwz?)ol@cZ2z2e@yJ+rkf4_S_*uc=<-7( zoJ-k=(P54@eS}W2jpv^WtU~8a-+l+C8=ge>FXV8R%(KiNH7#WkAH~V8GivJv(3pK} z7ub#eF=*6|F`WmQ@Jw`5?r!(e&m#6)=}rx@ZS_=HFX$?NaGl|4BhO{3s~Q9b`0OWz zmIzNT=>UXKdQbA6lMfd!gD}|OY`JUIrbP4n-vQo}%_{2}3HU=T?EVHiu`w_XI#?G` zw)<3cVRHR@26Axtp23tAmefv84$%2pV$#K?L|V9}nw1Ptt!xsa8WPKi+|;~@^tSDP zcofgy=0DZsJ|*LoZC**8eg)1t$Z|80fZhZBS8z;or#~@qt{y|4BBrZu6=E^?y}tQ= zwG7;Bec?4Vz-R|Ij;r`g0c^zNpcQvhn;qH_Fui~`<%($8({4hQK8}Lzh5sH4(}#D2J&8c@45h>SYBxzRc87o00k%25K^ zrT>|Z)HM;sAWy_AXpQM@>IXJ8xk^g(P1vvt0zVqBoa(XHxguM~`RAF`AI{Y-*$lm- z1s-HNYhn+EXd0HrPu~^zf{#M;sSYt~;Iu=|p5lA-PSYyLGOUZFDr@&}%|-)|(nzH0 zauN1N9pk~!Y>cAFWt;Eq^f#2|_jjwx3;7V#BwiqJg!VnSgCGE$;MNjNa*J+UgmBWM z5A-u9SW+1&!j7sO3N`=$1vqM0nfuyTqD~gq2jFRs9wsvB<{(q;uOWRoC@XQne014? z%6p7#LG>_;U@1j^j){X)HQO>6-rTrFTdS3&tSeT0jgx_Ct66cJhRJD z!8icoUYh}K%K;c(i}5m3?>?=z7IKVZuHAN1m}_auJrPjw9xb_bJT7g}8egNuZoX}pxbiX{meT;e&ajO8b@U?GFw#v=nr^#^r-5W$AA-bau zyAMW;3i2Z}R)khcroz;hT+D|M9iOV{03fhz|8qKd?t`qtGpbnceofKGj_ustG_tFp z<@S1y6R<2Ko^4`t+f>a^zj@@%ckrd*UVw8ozXdg0AGrE=o_aHD@_r>!jM=Czaz3#( zSGa)rpkFj*=`4gd%G`_%9jjQwgU27Eg4G1+RI-GkNsH<8@E$8tdd+~zLL9x4YS@Ku zI!(EHypddk&}n&x{jl5O`g1XQ2{nWpK>U+%$VN9odwx2hKre>@GO-VjtHFI84d@nR zkF*Uezv6*FL?U-M5gg53;uBQC~`%4z0 zLmrH}u10kEs`nwvE$igbFN@~+xixM~-ZywvT`JOZDO)|A(uTG8HML$nmVi-ClGYlr3>3$JC~Qm|KR1p9|QT9w{z|EeeG5u&T^gI0X%^#@56NXh%M@l3d>0Nuz~EEq`blSE;n-h zOCeZK88I+B2r`9&qIIX&8VuqmJO9WXOUM3tsbFjvYn%~E*`CipYa+YZ={0e>@gPl6 z&Q2n83u;%?GAYOPA3w?~YFC|@+_%br{*M34{{x&17%sMV^THp_s-zvk4)VJ1pV9Z0 zIV)0@?y{PJF(J*%#*61iuQzAGb_+#--y8ApTZLVK=WS&6 zwM_=%(Hg|^1+gy56B8V4iT!}!pl8IleO%33wZ(Y8#w^uao@{?wv(6!diUM&H zaki5z>?Cc;a-{bYUhn>)Q%1%L^Q*MA4H@!=XgRKsw+%}LLND{fpT7=~@87Bn3`X~2 zGi!M8kw9r+OqC>pH-*X*C1k-oB?|Pjfq*lWx`STA$FslP65{S~zpGEzo5i*wD7@Ke zErA}qMV7p%H0bDeIy8;oR7k7y9yIe>$SC)!t6p(a;)3ZdJh$CZ>D&IU3-W`P8Ku-O z`>vFz@BiUQ*?*#>W0v)8H~j|!CWYreJuuJO->yC7yNxuaicIM}^!JQoX}cT&U4-y==RC5ukmG;a&!4&5xKr&|i`> zOg_vs{=SxQuF+Qm2KSWCDruKVmkU7(xYu<3LMV%Op<6ByUcZV!RpzKf#9ftKhuXwL zB*^TVtq_4X(eQz_1d|i&@Q}iMrh2+eC5}fC+H|{B^~nYB@>l+n26_5zbs+if0{~lH z*)|-v&NhM5Uc8f0)8TT-bR?Ew z!*p9Zg08Ay9b?;{19vA-ZM}-gzkaON2)HVsF4he#I%B2rNdW)AML^eUmET7l&eE4` z)4{7Oqbb*nNPqC3xZ=#}1cxinpWZ8LLIPR~pXxVCfPd|QTZ`GV#v}e5; zVxg8Gq1;$bDzrCH((RM&l2nWG%sf+oh074<4FK#g`a*&pGZoHjzcY>{iQ9AU((7Vj zRs!K9Q{+n1CAZfp{N%wF3IVmCAP%Aqi}=pG1ikG82^;~SQ(sjm+75Vl-(!$Fc4@!t z(V9XG&d1V-442}Q3}h)CkL6DxpKA6WxLy+dS}>JCb6)4=S5ZbM*NpOVzB>y?J>32Z8DMgdHuP`@#^Qd zS%Bhk$DeX{&QtxZ{e(TZEjDA;A2!kaF=GS(a;k~VwX|fmQi`+~))q9IpDKImX?eyp z4ik)lHsUZnaF#1mELB6-`H76ri&Ld$(7#{BdUZ%JS3OkKQKTYSDP?U#f_RxmfQ^og zw_`zWhlD0w?J~)5qo2Wbxdj$Yw4uUg2D7R ze=OW|lZTb|u%}?39h$}&?Np<-gIUiIf*{^0#HR;+E(H!Ea;$|emrg?ap+)>kBnz21 zap}W}4|#|mC+9;E^DhJG`llDEYPlMs;_4QAaeop^lF^4Dro_NJT{cfxg;SXdkQ^k8 z92-sXF$PL80%>mftMUqox0`oM;c;`GTr;(z^8rb3IE{Ig$ZLc`Q^C?kn2ONiwqzpH zX$=p0yJ0)qzKSa5_6qR+;Q(OINF#**=Z8V=I>)=Ut#XF=P!-=Ke+w|m} z*L=c@^ni)kr)8b07cwC&Az{7WfG9#do*oH%bUlb*bo3ZFuo2mp`0yo$aV)>5vXT9K zh0B)xXbtOR(TK$RFe>Wbr5+q$Cq1Fl=pFF`3V>9T5Pbl*X8ztG)U^OyK%>7IJ6u3q z73x4)D8C0w2f*zuCH;tXS(KkgDGzWDjSY>!r-lngWrYu>fp(C0n?!?CFLh~yCEbZ0 zmiyUFGm5c?F zEL!3TlLg)qK3)3$eV}=X;YeeT+%~L$-Ix&$@TTHIv*;8ZOO(7(6BpH%dp-E^2LiN8 zvtK3Coqo!U_PDglcjQK3qdobBHZ#&24EWRA_Hocs4eKM0Fzi0wa-xIJ<2A9;9y>P`4xne#FRhfN(D!J3xS3ke4xF6QgU@%cJv zmv~penWh@^agnvc>;ChJ3g#l7a}Z(lv7g{8k>$pK@o`K*%{@J7fh9w1uwIZ+JRYP- zXv!gmkc)Og#j2<>*)ZTIt1W!C0p^P%?CR1%woM%uJur}#SKZdghNJK_NsVL1hb)mGx!K zNNBJm7*4D62VXe!nF-Z$`f8iIW2OjcKAXP@rN?k?`*t(E&!kY&gs9znGil*zH^;`1 zX_Ds@!y&Lzq^tX*y|mAKeK!v`daVl&kKhtS4?;By&4sp{)cOXJ(O2Fb^w;h~$zDP# z;!2CsHd=aq3mMvbWS~(Cs;DlgaZZ(1D8%TVJM<%fnQ`;Ufs+tBn>q%N$>rpXXG#oW_3@V#lap{k~App}4D?)PY)KSx^ru92a!#9LvkYHJO0YU%( z6UoW2BstR4*R&nE|HvJ#b0E@>+Ktl5Uj7;#9BQX1Ib+l*Vd+u!P;^r~O{zmj%E%+J zy;LVX@w}DtkBdjspbQ3Fh7*RR<+KvV|Ax|JVrVf?g+Phc@K`72$)#1kRe~Y8LhV`C zvS^P|=1Q^M+xsG8TE1<5@tc^vQfaFuuwSXl{Ph|_Qy5&x}c@uj!&2c~jHPJ6U9 zXsW$ya*fD*D`0KHlm3t}>6FwJNsp+yU~W}|e0-S9uoE`EHI7K4UUqclYPeB#0Qw4j zVE$yI8Ny|NC$aG8rI-~bU|=vtc#oD)QL(%XB)Cm_VZ>>+gCGbe9$jVR$xu`4a(q}W zEe!iJe{+XRrgRw|eEWd)qT_0?6x-XmhPn2G*r%7e`qKy&a2yt!YjxWY@Z+vS$divt=ce<$C!)x2~wx}Pzq1QxjYj>zbzR2yyxAS9uH)3yuK*gC=30|5S)%8S^!2UeV z*X}Yxbsg5VClUaQY8odE!|k>VkGQ`J^BE8!a8Slqz}TM0M`xY+a*N6$Y=9_(hr&cL zl4R-v1M0B_avq#acLcT&aZ!E23&*LS#oj8WlNvfrM4RUkXB zAg12qtn~kAWg#OoamT`A3{`&?{jz5!17|9P^TCd6DMZ*?j*X7i@H$L#=dqKa~0PU`!=RA!3gz8auqS zVSOt?ex9w!2kj(pZ$kaC#vUj}*$#7C(&4PZImDUN>Htl$Vxw!^pOLNtgH^e>>ptLP zPp}7pMSM%2stS#{!&Ia`noE2SVKwN!Izf#LbGyMK;hmb1u5oK1>-u~GVfc3ViHUWo zI$$o?#fY7`tmLuSD>K#DXdL@Z44gd2x}vF#f=MDrHf0wP&Hv6+H0e>MP<-YTa&18y z3{H{swJ6a}5y%NVBofIFXAW=jQ5uto+WQKhM;AGCc%(@3knd7H1 zI6dE%wW&D20OxraNJ(=;@ulr+2Nsvx&&Q%s{j+~sTOwV>ZH8M&VT?h zM8=#9z}f8sd*kZ7waZjDK*d@f!T~4q!EahRlt@t^1AuUwnb1_O56 zy(6^RTTXO2!N%;BZGoemO;9aHKjq+uRm@YvRZ(%?*<>5}+`%=6iF1~FQ9SA@Qsf^@ zqn6ET0Hbgx0|*g$6AX%?8z4<+5R4PO739>6(j*&WQ7LC*I1k+h$-T1$EZ6)V%B}GG z|G&{eQW0g<#L&L~$T(KByL!0IL0w#pJY{^KcmAL;GmHIQ=wvqPq8rnrCLS<7+F{m|Zx7YW?K8))aob9S-D8`}t-F{lJVWggl8MH~F z2{7y1KAE>l_NK!7yvAYW{f$+F7Q^#}hNv}2Ct^S3?00`E685hs# z29n(CYJLeu8)XiJPCXH#>^&H_16SZ~yu8R(Xox2x7bEH{v6ssU-M3>S1BY@%WFGzKrQh=39@8 zlh5~8i8H3j>iFJ;Whlmpdq#t-6JN;H$q59^RA|C19Mfa`02G|qUZwghG`4iphx~PG zSePnzw0FGT&B_RCGPk(rmxB=OL8DyP5^KUET()o6oBzb zCT)xtv_l`(CN1AX)v>V-iS+RRC+A2#k)7~PCIz^~kOBZ79?4lcL6tQ08Pi0lBFFdq z7gQ*>&0tYs#A_*p`)Mu*=)?e~e#X?%c4{^J;owGdOO}*5LEs)6#Pw0BiLpyORMcHx z%1f-W^fX*?h|j0+pk35V?U;QcUnWSVydMWPhm!dBDh5I!38f^LUgR3|mzkTF#8Rt^ z{CT^c8bOX@u#y$4#vg6teVcW5zgCI#N+`Ye=|NYr?ee{F!umo$R($*?p>E~Zlq_rY z%?7$N7+w-X+T{*@B;1W@D|*4+iH6vB`xyMn_}CA2*+6Du{J557f52|;-P!q&-zT!E zfTqFzxXZkh)7)L_0c(?{ZJw}FPHbUs^nB=uWh2!s3NH>*`QBLtM@3w!jpht2@072+>f0h~g-D5FmvS0DrAktc=N4K$u3L+gW~2aVdZkT(fkk z#dh8j;wJ|(hJrDQHKD(rz=D09vz;+yv)Xh-9B_874|h5-{gfbVc#~8mMHNOcoVR23 zkU7=*?T1LM>4Pi+8$_|5^H{_z#*V!rFbEo~YKHS0-l4N0a@xsWww7?yilIIya@a8$ zVxDO*k=<>WvwDvB_5U>TK!+ME>RE-!y+RZ)ji9x5mlorS+e9S56Rs&vAeqX_$n3 zRcS&H)n`OR0r2LUU5g%N1Y6UA>neVeY*Zj)>t5)5!Th*>MYyHrh(hE66nkznd^ShV zm#6zqh)xK=o~?mHLHcVd5ID{r4iOwX&;KM5U;1j*W*NC5XNEafx%IL}I$@Y{LW|ni zoM$*tcL*^IhlTji^oGN(GoCVoYBNuo+L@WLtG2&tyvAGP?a{WnI4;c0De3$3Ls=B% zg*v|9ikcgH40m(Q>)sxz!(gsZMmQ(ZO}FTz7amnZ9H=9q41@0%bw=LlqHJC8-N7^J zZYO7ofSqa-NpDBEKs8mM@k`*WlZ7WNv~Y_6dXFU2tk7ixm2YYJ~r5>Ph+l?@N1AJb;#}_9O(x5JnkdT9u_!iBO^5q;WAG*0Wm= zsz}q&7BjGlXST`d)^D!Ux>3G&9CHHAB~`S%h5A-J#byn`FjI!Ji*zSluk5xAKa&5O zvbs*%$I-PR_G4E$>jrE3DdW|u&kpWv46{A7`#;fR)2gC$X(`VS)g&y@I)F0_grf;rpiLyg`Da^^>9)} zJ{Zm1wKUnK{Y<-|@LR{a_|kiDzbMRpT4gV&8M+9qy?kN3GO6P1P?i3qC7j|P;Z{$0 zTvd5zr^oYQuM=b%;ol;f-v?yN-P-Ptu}G2En#0bt&V|hg<zoW`pIe>BX@px{9U+qo z=N*5;vA7)rHRJyJ;HaXjW)BrdUj(&M1GZ;%Z8mxJ+OmVF?8Os`1y|Ia1B8Cj0=lcP z2Vj|C$Ak~?d0aPN_LLG;IYYTmc>fN-#X6AHqcX~iA(4-%PAaxLqu}v+nI|rFYJ5*b zPZ0M9uEIWceQ@uUXszCu?kVY_&UD-%1r{NLwPiCT^xbo zY-YWA5EF8LH0l5@$lNnGP7k^?3w8BP1kBZ7%uFUw)Xc)94mT`_%+P4?P+&Q)M`ZaKpH|E z=WYLO*L+hd3w?fsA9Q+t318gNJxe+|%MMbzBJc=bL|?*sW7!0p0KcPt+kEq~Mq=bK z=plqQS!WsL3cRNkmDVb>C}|T$!GneUx}!jgs<=eWaNpUOK`e6dY9eNi-`pgiL_}a zIMG1mj(B24nwx4Pc^Ho{T|Knq* zVxz#FKo7N0M+9ZBTN%5Dr>_0`K}=gH@1`YK;-Zgw3a&4-rI%J3g=i2)naf+3Du)hd zU2fs&^?s7wZ}>aJH7#dxjMS2s<*|cb{esU^<(<&M9mf*`42puCPbLNYvEIo7aHnWQ zkbP zhm0v|da!T1DR)`l*I?dM83yYZC8H9&rH#d(DE(RpCD0ywyCaw&Nb#D?!tBXc;P=?~ zXye95zE!LC4KigQ2^ZvxrazHIFwMP>YvD#ge>P&$2=d<|{bJVkN>+rcZ_blibaKB36F&1->X z5~8=;ojn$XIe;kcer+&;`I`w1^L@>=7wG2DVLDQ=lh9s$il(xiw>Vym!97zDFe(?094d|<}V?>d8G4|5Wqz={M{T&JOT8VVC$UTJD~h{ zSqM-vC=Nv?i}u8+x-i)^UPG2#m&TvGv`2zF!)V!EvLewr>HqyBE6^w@f~dL-%}PFG zf$Q9%6Ie5N;D!GA?PyrA;Y};C8%tNxzo|=iwoEr_z;?y~LmMDBdX<$%P?kPQm(5?D z)7mJEH;3?4DHW+Lv)sRTK&!Vg35ltzt7*cFt|bh$$iNtXubQ2DB=;Bo@?$g+);27C+JQBW1(L*{pPriVbbDHPx^hkhuQtB7n=Z53f}`$c~Wtdv#4%}j{yEBSdf7te)9cu(5Z z(J^?u-AC3647h^M;|yV-^C0T)#6w;VBVG}9Rnp3&7 z{`l*s$PD=sS^vb=7;_TH2da7V4`DRdI%v1DvF*=2Stq{g{F>1qD!KBJ@y?PoMordA zrDD4Xeg<*cJX1O#VBWytmZZ){aO~_;+m}c3VI{GVG2D+MU}COpi^}~8OCN&phQtAQ zmQu+tVwirkB8wt!MY6-ZgK)cvlmY7re3bUJgkPIi$bfWapyk0K$5dK zsAtUl)LX*CqEvA_2<$6s6c61SIi>q&@j5$f^^##<`P{d_%WaCc>7LE`! zkr6C8;GgIYdxO~j2)>fulUCB4hB{p<5>z}d{6`ggs&F=yfn`9L%+ufk9?%8PyhAFX zfx`58(Tx+p|x$3=S3$IyPg6HK3Bz}*Spi2Xs(d}tTM zhQMCDIDY7f282uhVk|j>NfyadgB1Lrgg?K70x|JMz6fWw@*u!qBNYfzwO&v+My%`6 z9b-yx>gCQ~Fg}k<@Ezxo%C^o9NAsUgHQQB7bM8HwX7N*=+=4?$i+BJ57BQF$vW_4V zLx@}`_4G-r3r@(AliK>9OZkw(Nk3yXEver;j8qC-wGDG_CAX5yFKX?(Om)V!qIGjq=kH zR=GsNL+ju>A6@vDKL_2Ip1P)YP5rRw8vbgKY)AS@VH}f~eJ0-sX?Eyq@QW8Z+RMGM z)ZRyD}uF~ zc*j_k?FX61-Iyw7p!1xBGni>6*MEgbs-v+NkJSjoO$&?5gSzpA(b|pVFEU*xw4o9}9nbwbykOIjH{y5V1(Gp*eKKnmP{y57FdGZcw=tLXLOkaOJd8~W3nOq_} zr5UkMK&__t+K*5in*r2Tej~n`)>cedRwHFKyl zRNmqq-x(qGPMLFM1#Th*-O?5is4;kz-NVTthY>#3xsY;Vz`?It8A&yOL3d z>#wAlkMh>FaZOfoK6J;!!`D$xdRk(cSDPI!X|-JR|ABW3EG>3gaLl4Z{zAu%z}wWG zlR|}halaW;l{YmOFL=Qpl7!aJ+PM*t@XA{2JXhK-d(9zgJo8Z0O2B#y^D1IScz8>o z6~=k{4N+JsHb;~l2UNCsvMWS3tFF3aMSlMnrlmEm67X~%D=VQF7;k?K`p2x^@QO}BR`QqE#%Q@Ce1-)@KQ$eo+Q$eWte4~Kti&~r~4*}7| zEbdlo$^dcP+_bW;s}z-*fL1F&(}gb10`Q|GWzbU##q~O8I8U4Ch*;wyLk{Q9>2Hq; z#^2eU0vPEqkQeWGg|9LBt1bvrs)8q1OM7J7pE)w$DJ+R5GHX$$H4h3nqia7fYi9B# zgn|xVhPOX| zDhhF85x=ysnkx@gf>GL&j6Z-|SoA80ZeTL+jBKxtl1hR}-Emoo%v3Z|dqW$VV9Tkn zx%9)FFkM5{Joy|r9?W03PEvg~bk!{<1w0q!_x}n*U!;1*X2@q7)BAnHP7h#T8`fv) zaPsMFO%570=rZexx}8ZHw(?qAFel8i^SA(P>2Ev`GA?kMJLuLR{+VP_F-O!2NE7E_xrViIN1`nzKBeLe@A9F=8-^^&>se7an z3=I%D3bYothJ7x@oW3zdYI9X0xuuMO_;aW7|Oo^8vb1EuEM zmZ=4p0ZORR+Q1?jQygx&$Kl3KKbmrMZII3*tPLep%4rU}BOv0l`=V-y6Vq;8DHWWQ z^U->TH=qGW}ci^qCjX&|~4s41xGmxI`w&(uvy!VInAc8}1=Exnsw1FmwE$ zdwn7SG(`FOD)VWe5o=*WSJ#TJY z*)P&Vz`#IHu8O2KRxpVKB;4CSw=hkWfQ@7fBnjUvG6utd(EIgZ7 z7U1-2^d4IoqCyT&4~10<$=mL&$xI0Qj?lN-2}US5$xi1RNY|gE6X< zUYAc?9j?Ju*(IE>g!kg1DB|S9h+nh}<9{!l`5G4S8k&eX01RP(QH)sd>@cs8;eG zE_)$wEfiZrHooBd9Cp%epM5BRo!Dflrny#}%sr{vW`Hd%h-islMbg2t41O-u7UHNc zbNE|#ZVo+0mXQm=R`SePR;4`r93&<)8gCx+n=$GXp-KLFY0oJsGg~F=_XQQ8_e@Mz z-ACl@*j0TYli$vy;nZkXIG*5X6l}U~lpUQ9_Nzy41C=^q=q`*I z4l5B+7U#i$c~n-q4Wnl+hE1e-x*9|CYRL1B2`0bQnG3m}MN=i>nqGT~xn7rFK=p{o z1M7}mv3OjX6a+M>JkoMmGlTTGa)d6qP5ET!l>tdCRjV=b*6v&k`Q8lX2Q?5c^QFfU z9pqJ%JYj~9*3LUSHk*(6{~#TqdY+eetX?X*X6r(h6qQU5CJk$0hIR}I*3 zW}#y0K=*wr(YWWsK=iI?*#1Ili*3+4Zj^Xo3VJ!ny4Y`-8^Q;F(lFZ@65&MFCtX$k zWi%o_^0uRZ{8A4o7e^tSGgFIM%$x@$U@Oy&e2C#2p ztLcDP8=wsnq0-T(=6hFSoEuDdC}vBS==dh5N3%db3fh`3?a9cPGt_;pI@IU>O)E{9 zBAmPLgL;-QN7$;5Si{8{&R4AMe^*0=1+8p%D`x{EeMK0w3i=TjlXQvZJcniC!7|G# zo9F!yB;(nnPVa5^q7&T9(tt({QW^P5VIhNuWhZ9@#9pB}e(-iuKh~Zq_E`}$FCUBm z*RWd3$oEe~jIKRZNO$hHGi2iNf#Azp!>JnL{L`Hf-x(R3bi2Rx{;H6{DPyX-7zvxS z@OW9`R`LKwXFsq_RI&*kT7DU$rtFpy*w0liA#8<0I-ty2M0>}l0U2N+X9Y{6BPEFw zLC4&J_TFrKlw4ZQBKA78v~C{8uj(OsAAZTmfB*mp2Hx*O_Lxe-dt=GR1zl9PMx;4lkSIS`^!uxJM$f@mAYdLa@ z;4J0$c-lYZx9Ho~hY0JA-eVkRDs!w(@ryUI2Xygz)UrPI+MytiHzTk8N- zFYyYVzRx0jrl~kPwQu%H$qCnqV7umS@j2A@)>PxQPVuEmA_eeS z{tzhRk@k%Gs|DosS(N(iC*td)SK4@Lp+-}o%EW1NHytA{zmP2nUIeDXTusE_Rjz{J z*s@!kFl6v$`?qjyrcjDDIKm6)%cT)7-G-<5Uti46n+!$s_!8b652SX7g72b04cf2C zndqSWlh>8HGj@txQHne8hI2YcT`#9Z>(ZOqcbtaqoSTM)m zP4mGzP|M@AlEO{K^ej#QxdHY8h}C$!lSo8v9+Tl9y-@JDI%^&?r@ku~wOz=N@+u6)58vWI!FsR7^K z1PJ(k3HaCJc+Agm87~z#kJ~FgIhvQyH{C<1(t~-mVd<>LT0y8WGNzg5uw1i|DQqdD zI)z}-wp?$Z%jsTnvOaCyexw#QnaHtZs4(OONWJF)MecZ9i4~7?elw8kzG#CF9goZ> zT4}SetI4x2FWP(+rG|!0Z#99x^rE=m2^#F;gMBHRpGjJhtOPu7Q+8w$uG`L@ReNEy z)8vVlbjC{<3#j?Kpuhe<%IZL5=q?z444NzL8dc?t7}*Jzp4$Q>FV)>c?xeFU3w(>` zX@fRtXn7>?gsBnnbK1#g>9^=7ZfAP~g%B~G27}5zp#UhsGz4Uii>Vo(Nl|nQzpK%< z>@h+DbbI`T?@7pzrY9yF4S6+FVUab7=iF?4`kSd)HoWnAm6bW#lQeopJ~-A45M9Lm zUaqiDhK|S28Xn}nk=42fIh?8k2YR@iX{+i@SG-8DG!(b5)CLL8gdD3GJ}nH! zBF<9gtq$uImKrBT5*46gD9T{M0(N#n#b8e;36m7mz1H&HXRJ48;%d-e_iFU93JEOh zh@_90w&m}n1%FkzJJ~LZs8{0GU!j>O;_2OFh69mC=Y8zXRV9Rx8c{Fx5nfTEsrqxO zsqYeAt>k=GBN&A5rRj_9RI=Cdhr|@+QBFTcxmVjLJsp7F-0-J$6`gYsCM8>yG9b zSsN*+@Y`Ay8@Ohv>E?FdJth+l?V#Ihks$>oje=%jZV%3Q0Xm_zco#%Im8xcVVkkEd zTkYgy*EH8{bx%Mz3}Zsxy{^1ps(yvQct)9~5BY|iC#{FUCVQCrb85Wyzx2X&XVtWY zcVA|L#>;~C>wNexVc7orMZtG$xx_3~Y@fS45?3EO^Pq$$qwy%Ld0`(0aIuAnlWLq( zi=s6djarPDwM>hyM_tdj|I1eJL$DBE{n&Ia}cXu z?}$DZhJINWOVV@n(gqRZL_nUn2s+;E1G1{t&!y^MJNPl)sokXzNsU!rl;|CAlYw1A z@5d|$Ca{?@gYQq)Ih-4L2Nf%6l9>E42`w`)FPu7BN8N59ENnBh#85Zwb4R66f2Z#G z_=0tSQXDTT?$ruTCMzH?OlJk<_x zR{{MD!?4v?_18(|6J7l-Eclxv z2kkE0+$_7=OHov8v>{^7%XoSg29EDk!*s8H9JDp;s0mRee&1$+PAk9ttSeSSMs zbymyP--fh3&kFXDK4=0e*iOKp{BM_FF|C#vEHsph9md+0wsBoa);){}vI@HM%hnmK zd<{D-CMTZ{X~Zf<4KJ#H`_eGfVbH9|-LmE@YSD?Cmy;$|#wd`Vy&e{_J28=hsS|>< zh8ta$--<)`q7Glv+D*O+WHU{z4vVY;q%^#HvX7gxa`TssUYQ7_IbEDhm0iEN6ybA& zd(TWA3jfW6CI{h1`r5Tgs{2Xqtq%D)<{iicII!4hQZ8f$(%LsLzArdzOdiPF(sIyb zZ@s+JeeQv-D~Po9?uIn)tfwd{8sfD?iD7$oVkQ<-Tfnq6S6s=~hynB07))grYUw!>BRmzoW z+q06w6YWuT2W-qXn*l7z!+;s4blxNDQLRpVqFJ`!F=&S z{trZ-e|2a>zXU;juhd+XCTo*UfCBZtAI<`{7crSJv|AkfbWWy~(2`jPCf8=IG{?8* z$`up-zK+rmH=YD)#%9WYx&nK>uqVk|tW&W_vDgquga@+NE_nst~f-Mc0}jR=QACalS}-iWk0{d=ZP{&t>)|> zAc3x!ho%I^ECPK-yW+EG(G|toy%sbA_dw%98LdB~j+kxXg?B7Laltz?Np>x|<7Eg4 z(VemvGc?lfv8t~SR*@R@&*(1qD|!cXo;L9R5i!l_+wj%WTRW+Q1N6Eci1<`!TkFa6 z9rG#yX4Ol03Hn8F@!BAWFAO1XQWGG>Uazyx|E6A*5jO2LL4-E;Yl-mO|qDZ8!5 zur<>}h(USh=>@<|aQ6sNQ+2Fi2)v4_h0UGc#5P}4n69;30M)L+s1OvpuoR>YOVoyEC;2vT&MnKhQoW-Tr~=y3)7 z6xb`;9Y`cj5yKocj2o?LE!vejOGnk2Dt#V-mma(oSbiL(agqDUtED7RjV1&ILI;J! z-J5&^oQ4kE@jAwHl=@$#H1P8svv-3?xAtt*{U8FPiH4V$x+fG@bZC5rx@3563CX2L z_C+vh>E_8R?_mp=5aFe`9?DdSb2hdYC`yI4Co^=i;N%K3Flfb%OBU6#9N}|B}&Cu+L-AgUP2ju z8g|nRP$_jy1v%h|j4zxN(@Jr7z6$VxX7URBtwyGa1?Q(w!%n- zvrHSt>1luIOmgFH0?a$ERi#9K)Puf_Hz<}7%ko92sHY6oiW|&MLMNyEaE&q`r@gbg z9TtRR%tt|*TA2fQq@9X`ldNixKvoYymC$1oa{~~DT~f4R1EVB4`~n-0I!Q|c7>b=; zzxYIDc8U%%7k5;@k~_$%6JEZ!(uOBQ1JZqtD;E=v1X8uO&=nZu>(B*^N~s%2I*ySU zO-;qk$u#SAo*QX}@09kk-`Z{74$!_aa8XqW6__%%z-0iETy3_5l+jQ+6z4Z$M4$k% zgVyC5B$jC&pg-GxrZMvEcK=Osw-aO7vkztsp1#?h$AF=4-w?SB;1%xet=vPGa!t&6 z==;^C<-tN`(`9XNiGC_N4NFs~+AgN1#N`Gg-D^_<$aU)P*~rlQKP2i$fH;hFYovHg z%-KI`AbNw7C29s<8w|x>5Ic>KmJ$d}WI+%pYyC$q{GV@WT~;ih?j_Al*a{N&v}geZ zPB7Vv1u@tukVKAo*dr6F(G`{sz&+>^7asoCBrJ%yn&vu2GVv|nMHUdFy{M*oh}bmolJhV z@`Je?{d)rPnM)gVkZiI>4$ z5f7A!VqY$A9&cU_F=h#U`G940){gNi$TaeUP%|}uza?Gx2EQmCX@(N!{j!5{s?90K z23|ppb-o)#z21^6f&u~fAPupt_OwRGU%ISTA^}yaR4VO~Hqw+3mEya}q*Wyy5b90` zObn<6HcW^Q>qcumYIe?7^f%;rOcKZ$LfyO)_ZL2`@c`vC+H76S>`4XYTITm1!B!Fx z-d+E{BF&0Y4lkKDK(!pdI^`hoN-N}!UANQd=~SSZ(`KL z{2z_|$qJpm$ww##iJOGGJsZR@=`D*QqqcU8-U(LP$I^)?kl_m;w4Uka46GUkN-CKEEU#5er@DT`v7J+W*HN@EvUB7_G2?|KY7F{ zaRHlElCjN%Z@xf%LUW?1P5c=cI6!7AH`5}B>r{g)_cheRNgCS>0 zu?+tYuFLm^8egFP@eN+wWa?f(sAd^rzt~P&@hc0mJOneS1mVOQgT59FyskKI1>mym zSHYhxWMM>Wn-GQG5sK17kz}3X#x6wtXGEBKMQvVtrjBDhjbC_j_v?ckDGz_ubtG!Z z$zAG1&oP3)zynHd2FrdwO5mlph(LX|a0f2QxXn)KyKXZgi&g1o7}4~&naJg{6&zWcmn7CfS}Nl{R4HVGK=O#>>60{$+8G`z!Ji|!bvZp zu~Ymad~Z`4=5q`)1!+VlnY?U-!1j57G&s&7y!|@|lt7|i8+mbNRo{3c<0F9xhrUZrC`3)Z&_8l#8<7OI}U*=*UdNL5N<4{oV>PK4~V3W=&?jg=kj=hXuBym5%*mdr#XfnpW#JxTfX`p3# zO};WtI)Su6gOFYj1s^>{TKs?@_(I<5@Sfn#+9|B{o8P)MzICe}1V#p7scar?JxqM5 zMvH)l{`y7|K=m387JKY6MtzMD+h|=rk$2m^EWn}4D=x+FL$5mqj2D&dX|9vs2}9I` ztTVg&?%nUu1sc3dL4)H=?T?m8#{3rFE-|$kXK_lXC1kf>S9atO%G((__M@Q`!FA7n zu2sdPCdx%--`gfQ^_05@qe4LljNp#t^>~LCTA66>0lw!T7W#3C7j4t=nO4@qLO?~X zW6FpZr3$0tKDn%HvZ#x~VYS?E!o=cgQs*K*M!ZeRGd+|aeeZ^PApVB`juDOU28J%S zzWl|tl5=^<%&P`Kbg$#wSp4xn)wkniZ*uv1dhT5#oqe3K)XB-J62s#>2s9VNM(mg= zdv$~l%S$(n*`u2*)XnZOS)>azh$+(o5*jjA5U@)4?+;yRmf350gQ>*lqKd-R%}N3%yfC)D`in`CGo z8@bJsKT`Lz6!nQ6XW{1h3Ny@}OZkA&cchWo1iA5Y!w90o&%6VV{kOT(sU>X6t1}s} zbh?kqnp%Mo zzK}LGNEkhhdpcLFoWA&$lf|-(YSx)BfAq4K6PxW^JC^dPjbz=sbg4ySU{}!NQ&1x5 z($;=PiSS)Vp^4stY(P#}MiJ-Jnwc_@rqj|Y#2a&0#L04HL_$-!ufi$?oogzm_?|(|T!qItES3AiL%1U(@8f|+*H3rI* z^rw+(4qaS~SWe;wb?J`F@7*T*h6+#vQ-OsSIA1GMt-vQVQK{)d(NuBKu?7c*uxg|duDm^#ho@u)`omvt6YNn0oGEy?7H zW`CJ`F%4h{GvB3rYvE&s;<~(1IONR6mF{vUu|D6ky&35Ke)g#68w^OAI9doxqi%7h zmOZ;K2u8xEt2VwfijVd|J{W$ZVqlaN<@dH53vnZE1(6!(J1hXqAL{|^)^KXiIUo+y z-SQBYR%)-f-v0;+@Y{&3Eq91R1o9P75$95R*EB8)9<0$BtzI7xF0!y32bULY0o#Ic z*7DoT53P)k1Dk`?3nl+#cK9!Sn4$*{S1zV44XlYdjS50OajylBk3p6qppHe%>2D^} zu1-}thm_i?qeWV26;f%hvQ=m0)=eTGJWxm_r}i|)HS5gIqs;~jj^q0lz?4OeO{Bf+0z!4qRB zGxqeMY748_Z?1yuBF|k+u@s85X+jBLQjchqTCB|!Z%B)tjDzJa^=N^w3U@Vcc_ZMY zyex)e6}na0lYyL`OR>Zwsiqux&0v0 zyN3EoP_`wV@~KliuPbEJXAsG}{(QPc9P8`GW?H8S>4eCsG)<2#Tn^PH~gQDZ)BISE2JlBj&VuRcG%|zC^od^BYYP5oNAhPzztgFudZ(Z?lBOj3^A$vR;PeXW0uKpU#-$+nz+e(vUq43_%YR>9y5rA&okQq)BEMF3Xs^W541Z z2G#fAM;>q9_YBw)sBPOS(LlNdHPiGvB?$cGs*^JDih`+~p^^wpLkR^153(Fo_W&TZ zkq4TD=V4iKu^Hs654nzFT(VVZjp%7f&iO5*4w-^{lytXnoeJG>aaTq-aEuvYcBN3O zASYrrW{&c_xV>MrIYThLh>1e~vR@xw>2B#~Mi__u_p%ap*nc$F;m22m<&adOHVJ{Q zhdT7m(S|19-$4`EkTXZh;7}TVppNU$np~i)*zWS?rAX22ZVq0Y7{QF=BlG8sqOuq( z5Qy6{Kx+R+T|)_yxKq(g(kZEsZJNArj_8y1?MW63IT|+^H2FVOJOJMOYq%HepYpC* zU$i2{6Q`?#M;k1dq>Mx#+4d>sAvu<#{||O7NZl*3%X@E^0%FZHR3)U_1Ps%r;CzXl zcYku*p5c=;>YtC^Ws+~QUu&p=7FxzUt|le5%r_gQ44bOs_9K8E11$0fo$TE6k)l{# zJZbEbSy*m-pg+--+>kk4Y%p0}QNzQ#(?<6y;fTsjo!%SwVg*@v6`wjaO#su9V#VD3 z?^|8`To--Bo6{Ew*mCGIwtOd;O>LgEvW8iOblB-ds3e;g4#b@2&+Yh>uBSg?KJLpb zi!tWfrR(F#8IddKKUDusL7EqlK8P?=`ZU!R3~|A)kd}$DBPMVXMlCPhDLx+6bT%|M zAe!M!DWWhNA5H2l*jX&&5_OU-J?hZS*Mn_ItJ$^;RQU`#4=xs*r{D!~4!4h4IOUQR zZ1=DU(+t`*5zJCL7#tW|&l-8pe4k*wQy8&k_?{7%o#D9NvopQ2n+ZeK0nO4Ym^T4o zy5U+bt;{f0S^5HnW?A0*5O8&zkeLgrDL1${c-L30tlj|8yqJkU{T^607?OtPz9!TR zY4$Y$Ds&2>i$LQKOPBxvDBqW&_?q()=I_&OjFEp*^r)tzVjSGId;c3yC$^3$K)8NX z%9gb>Xu4ZBNxMm@TI{~FMdNk$mr6-D{oD0_i!rTESL6i`3ENA*>GyfTj8hE;(w&gv zUY+M#6-<_gy56!;_nP^ns{vjcZxaK}a}1KmYyS)e2V}wQIkHk7MK8uG60ctCKR3bC zo?=lBITkAcY+ew=?`C+0iT?Ybd}(4L?|(T~de%9zZc?(LGs_JPrfX!rK7*nQ$-*0K zpP=Vst0XcD4Akh(iGBm#8FNOITz148Pyc#aL~{EC0zw|J5Zj$mmkKEbuaef*+tH97 zG(p=`nBI~MHd*mY;2|)=o#d6S49~ZoiapL@725=aviwb^yOQwsWBokn1vVhxvPQim#rQF3PD5(| z7Ya6AC#zWTF}tH-kA=|vtTklL5yt2PqG(*W$mwP*Xyq*q=80%h8-z z1m6#k2pdIvUkmX6c}Vc#+pBgU@Hf^iep0W>qhn(G{zjxk;)}rBIA4c=faJR1$@dd} ze7qODVQYv=24ZWeaN#Sm7rTn**}JSVjpxRP3JfYmB}VzfB2R(adN7{eWx*aP;Fxr~ z{Cjjv9HK2wgE>deyV#@tXZzOOi4EMdTqo{&paR&i5>)@F33)~bE=`CKG;7o$qVVPf zh3!mvGXK9Hiv^C!Ogep}2sRX9bh^w0*<#2|(@M~4uQ{Z3nftNXF*2=JfStBbTwK+X z8Q?q5g|(i}7toO!b#$}Z&6hF(#k9RA<6^eRR7?l^(5w&H-a1Fh^nPJ3IqzPf+1SU( zONV|%F-HcBfZQze+47-%4VP(aSn8hI&gKGZ_d2LB%$z*qC?CL*P9FNj5~J-dT%YVW zofhJ%z_-s&dDkB{?!dEn#E!2t@#4OOIy6Ul@<;(`<6`<<(nm`s)F+vY!|PiG9)rvd zk%zc#ynIsu*V;3xnfPkOY7cXdu3)-72GJpPQ!6}Sx z6Kzhu!GM*-&6#v0Uy5puMmvUrg%}Nos%q6^ptH|t+#8v2a%}$2O9GO~+Kc9`Cjfb; zj0%>{MU8CjC^I@V@@YA=HL|p82Sn-#-dcyS1&}0ZMW6~2z1tA77E1I;+adcf8R$IX zdCZS4^_EF>#OZo}r`_teO)(v5?@!iS+DMG>iuu1p=#9~Jw33*}$dmHXSDv7JM@Z(J zsxv-04yIm6;!-RsuZbLE>@l8K1I-*Xb%xIj`5~+lsejYfyvRU!c?J6SGY8Ro;|f`4 z*LOcwaT$}II=-(TJFnLDAvXf{5p5k3_Pvswg<^?5%FmZiNY$~6*FoyGjY5;0yI!;> z0kcN{e25QxQ@3$YO|yRyFqo@CwosAABBX4BXFI2LQR%peLKTsE2zdao0>sHxxDl(W ztR=UVb<&A|b11!DSLHcsSUQ~&UvfKi~KXaBSev#e!WR%<>nfuVU0fCJ1SwBl7 zY{}n$)&PN{r%D=ZE3S7|TPofn=upOSWc0~iC0Z?!DPZx=cSPD#Ta$EFs@PlnN=zNv zrY83opg#R(P{Cg9-!7a~HgpK%wW)A&n|&^uJYoW}OLs?#+$}2iH|{fjkitiNSww*K zj4l*-=G+}>O?Ac2OnB*$AEe7Gj=naVMgra>ZT26vVOHGExW%eUj3f=!xxPd^yZ({EJSrl_zhBmkl~qbRs?F;6dn+K*mx0(kG(Vt zy&oJtWKLlb^dmbUaw>5I?Rsq?gqU0d?yAZvBh7ZH{b0#pS2UMYB3__K9hSda#HElw=`t*FC8U^=@6Z4ft z!&lrBYL@E^*paJUtye;@=K_a7kUr?Ak(UGAc{0*B8Dff4uNToQZr4#k09i;Y7uKR= z&YfFV8N7G1n0V>;51IQa1XGwHB?y8X)wS#7##F?CF#o5Y%rVbb7JB5d$YhYNq>J{b zf_KHt-bu887Xp;vqHXekeDzQ%B&!>+=W(0$&xg5|()g_ySB%9ac|9cm7Jc2@2^?5i zUl51dLiju0i{s3+ue)D)I3aq94`q7m%ns1?O;UnKqo`BNNr?qz)cgz@>v56F6*PXo z?-c8w%cz3zg{YN}RE4^(79QH7#v2m>z4>dq<)(!owO!b+J*MPjbD%JBn~5MK#wrW9snun~T_Kt>F|T0e+^r zt$3;ZKe}^5Pt6@5tbx8C8I3Q+V9-S;iRG59B2c~4A2sa7RSoPq1d{{XF8*lR zqAYf1Oh`@1%JR;3lNhCCwaVf+J{e$lKx^8Dh?Nn6xs*9whM`pfV@tCS@TtrtgVa)+c26uinYk;h zY-heN6G2-7mce0D1$dvHcBFVLy{Zqhq=ud1tfu|6_6B{K>?=R)rUlv-2Swd$Ky9V2 z?5f`ufW~=;2y;|bWNHn5>`ZkAZnN8imIQ;WF}kjwk9z-$0>LuJfI`y>x)ejj(%>`N z0;!5m+@@Toh0^19StjYg6?r+G-uxgA`0h>R;X|8`zM<=}Y1#AI$B2W+`jl;EnY_i? zI-Faf|F1D?O@B+0a9g%Ox-3LipvG?io#tQ~J^IGT50Rwwsy5uQJdlmcew&Iw)3 z-o(SYwCX6Xt;O5qOR2*H0*53;l~>Rz6gGB4Fa$13J+D!66vA+2ywKbIwK@#hu|B2f zKk@q4>}?noRWS^k{GmJqQ}&BKK^U6#m>YbK6r(*GXCzZ(%8`Kx-s@ytx#8!lHf=>) zSYv?|jqQJqHiG|EvQmha8v8tn4&CHM#2{)mz&H@;d57`k3E1XaltHrArEGJ!%JkI< z>uNmAX75md{7vt^frkiKtND?YxQk4f?8V@QGzsFPzO@8svkBP$o(7FABrj~R(PbR<8{bn5 z*4;2pU_LIzF0~r{w3Jd4nA>N^5bWVta+49?kNO++t@5Kj-9K3GZY0{zLR9%^v zdh+~4J8$B~K`Ki&+aaB+JRC40QRIjMJ{?kni;+eo&MEW= zu~u7V=a{JC48+|m1*~na0INqU`z%)>^I@a!_e={h_m{6g7hW_7o?VFT?On;wiXl7a zLu+8Ju`+l8Rr$tEytae;qn+-5D-TOz4ky7D63)0gWN=PiLrg5hlhH05vO6Ov-o$;% zC>PmTchgU8ogk_U8g?Pa(3olb_tbcC%t8R__S7AQ$=&}y0n-9d&f_OX6S>Z*s~ROJXavOj&@5}F%+Mc z#O#q?r3`sdG8?UcT7e%SiYFf23S(RkRN-19&Zr}oQjP|vT7ZKv-KN7`Iyb~GsjB#U z8srX(><-z(KOEck$b{Lx(q&Q%7lvV8W3YF*O?lk0m~=+bI|o2auu%*Ur?C~0K9ntG zD$uXuvd!xVz8=C}*^5L0P;$7awlL`7c7^cnzcWMIS(lxwmtkhI>D-iB6vHGSh)e$J zs8p?7#2D*!(zrW(IEulI-#)hS(XKMszczB zD%q(wI2FZlx8>RKPYGGQ8aki=^p>{XDj7G1bDIAAR{L%4-zcqe z&{6Vf)%P7+gQm$R>{Zm5)=m08K{I2^&p_XqvNl`AWw$V-VRSEWmN8?B+^Bj)tz_jj z#jyxI%?lF|a8(&kOlHstW~zK_UsD62FuS>FQc#@LIOT%;yxxOzC!e7%wGj^e=O<>w zSe?9LxZyIbn`S_?Ul?2YQT8L0(+C*?R}RWxY|nLXN7wSK0W}9D8sj{j(dlW45V>oL zumjx3N4*Q!>*zx`2gUW^%I)|2M$tKV5uC5W>= z`wH;nJm0`&S~Sd4s*WnjO?{T> zwXdclW5J`#BZPwTU)>1pP?H_frM}R_Q0_E_Y;6!fyPj*G8&W%DVMFeJZca@5tfuSuanAE>`K%EXy@3XA zxOMbgVG}R4n)zmqP!IgH8yTiDk5b;O;AOCUA%lLMzTv%$tg_?Zx0SiEPy zfhcZJ8LFQa^I}tvtelvr0TwB$eLfJ-5|tzYweO3V+gEr6YkvuF4(CNnZ{FeGHQE2_ zXq02_5Mc;qt4eU^?nE)pO5&7^-c0d5)ZFJ(@n;)s)(oJ*Z^I>o;opQp z<*D!?{)2=Fml?8PPM;yw*6cehXr9E3gMe$zp!plAwj_gIrrF@~tn(|A&ff_%$652% z&m8Eq?+^NvU-DzkOH-P&F2%Bgta;;IGj{~J-nu_yA=P>8Rolb++=gHsbJ$!8muVv~ z?^*&!sY$+A0o5)v^f3jYic>OcYOvenVk^T}D54mnUxi39`ZIQ0 zbe|94D~QLTUkvx)oltSv+{%XuFKF!u*)+GrJU5W{)PEUK!W22huZdNC`7;#s~L z#H|pZjU-d{@LmF4midSw07Csf20(t)NqIeD;KPl3~fXGPB8O_-h}I@}P5o%IxBo zrMGV!CHRX9Bhqf<+7N{vj2mKtMsU(sV`+_aUo1Hat9B85;5nVid?SMW??m?$9?og{ zvHMa>C+h3xcw?~jRb9i$^~RR+yYv?fLtZ)Hdt45e2ntHf_!1R&XRcVI9_U3+?y?E| z^xoYRTFwwqEAVd17Q5+SuD@%vuD51<6yO!YAdPR^-P~VmaiayF$h~l0p~KW8+G{(t z45_nT{ulW2jEO(?2?}Dk)0Xl3f*bPu=h_>y+G1iMa?}uAH+yQrcmP}?8$MjkQ-hVF z;K>E3l}l{|!KP;k#EPl)O)i(zbz`WK{D6C{ss#6$Y};XRE2{E5ZaNS=Bf=~fu3j+g ztcRzrF6mMQ7qW%pLVNMnf9W@Jr)%&YczVywD0uG5jNFq0=wH4Yqe^`o#yi;wCSwui zYEi-lK4F+-Tj{j85yM3_9LGYR!PK&_brdv~9WL(0XQe59uZId$50+2>0+;Iyz_3@C z=95~*DPhC2NLm$7?}^W=17qgSg+Q2f?*z0)+^tV9%70c_Yq3snK|-10s^*(E5LIql zLu8`F8w_32kt=8_j3)rT<21s!?uE4 z#sT%BI3$ku#sTS*TuC)_xKQGV{JoKQ2Kg~Lax!V~Tudcea{?%@Iy6Iv ziXWSN9V(M4tH`tY^mX7!9?ixXgDye`q&~MQa2Zf`P!LOmbX)J0E{MWD4j3l+u0-tM zJJEvRFx(z^dV?DTrLQgSo+Ky6kg>vb`a~mGimW980sFJy=S;#bN9|hQ^fVCm**m_p zi?l{Z6OKj(eM)eTc_wR_HMJGx-)0-V<3Wj4Do-8t+^d^q|1$uUcs9k)Dc|aQg$4K? zNK?s`SInL?G{c(0MD*vvG3Vrm*KI01kVo{MAmC!_d8#@;71^Zn(e{n>Z3r`3SNTu< zfV@-e&S~!NeI#^?ZpDpxd>PZS%e_<@;pjIQ5Fpl_PDGi5w-lf*_C$?^t@MB&C`h8F zGnRGB1isy#K9$SLP*+}!n6~C236cI_^nFWHgmuAM|8J@+?Ava=qjl+C)wM}k~QVx;`oZc*Sd4Nn%Ry_NGX`wa*nf1p~A z8Lg7}Gc%jpnCb5EF%saHTWStWf`I+*A4CRx>HiKtqaA;z;Zt!?cS&1;Q#G%^-=4dq z082GEq@Oy_3s0F%?k+S)B;W!`0b}k&cb8!MelCt-ktFvr@oFf3;K8t-LI_b?>)K|g zXBNvG*ioE;*u=@_m(ew6<&6j4PjPzW7fGxF5hif{wX)+3Jk>8h@Lgj34T5(pMHzl`q`T}dSnRs%twv(sa)~PkKGppBw z*aL5f*-W+U$y7KyZ&Ap?O<=S9A+bh(hPvW2YT$8SwR}=vGD+w7TCn9dD!4^iQd{_g z?FDTk)&&hPzfyd+(blog7pirU$wyE)1QgvuekffC)w6{yveH=tX)h}6RIePGL>}xz z=@D{2Cu5F5C4MwR1Ao1Irj5)hJ(Ho?QWUJASO;pgb5!it7Gvuep30jFkCM2-(~CJg z+TV{5HTh_>y=Ba9r!VBZet5tO;XYk~$_aRBgLQ<7fb{>`hIPtb!rLC=kE|h9`QJ8s zdGaDS)T^;1;%mG=ljOQdlZ$l#%UFT()sWtN`3BTWT*yxwvTAaZ!LmbVy-P~r+7uG2 zQ5+!@*y+BP#Nu9EQMZ?umkKf`tp0EL}v&h!ABx_NA?-RQ1cX_&$kW~0~=U7zL@x!2FYNZioCn8RfF#D-2wZ(0S0 z%O#p3TUpx$`1^cZDDnkL0#y#G5T`xk%{*{N$x=W#@iDagikf_`Ud-kv!-`J6SG?2@ z9bU@~+@HJWQc(X8K+fU6z)p04>)KcM_~Nwco4z(xYv9M*LrQNkN4Sd*>Y+#`d8{-f zX1^u|iqZwK5G#(p*2y5nWC8E1QP7D#{yNuaYD~m^R<)rwU-X`s+@=dAVpIlPkgrcc zMlPNIY_;7FAB3uQbW#K4lw7$Cw;E{8UWb^zL&gpYXG+xNa{39NukXd_>4H_IvGSYF zkl6@)BLV1G`wq7M%iCrASOcYe1qHHs0qk)MUm;gGDq;qr^oZZu&zh}uKbZZz;|x_+ zKy$uQ&^Q-WRbIdQ!0|R=4Qt5ZmqazJB^k0$RpMTmouNIJwl;>NC(yE~FgOA;>j#j1 zDY}RB1|E|AjQ|=@E6o-#0HzK>yH0BfRObR}zB$NX&}F32r0@i6iZHVWzX~c-AVa_i zLBJON5*DAg|JZWcL7rcf9Nf+&n7TRNhGxA_NQ!(3qO=J}u*n5NmWkI=FhfkLX8PVT zv!ReW+|&kUGbB#Gt>T(#FpA)#Pb>~6Z92A%<9IA0x+MG|&WKZQK|p%$_b!RRf;(n) zn$)`RER5y7rXDowOqwC(yJTf7@y++{4*p~Zi@lM=tNaxPgpWapz8JtAV05%ajyFr2 z51~aNF^_~fgpkz&`M~hMq_DFQssAHv4;i&vTe`$!<5-}=xnYSwtK&yoY+mD3`k*X; z>z)}o4-JKU!TzMMf5R96L@1yXzSxW1*gl|vE!(YcY3#{_pQyBgYV!{6RNHj{nKT=C z(P6A83OqO=&c9nT_6%7AIg)4CDBLEo=ET)VSLWDvDGlGSy+0Aqs9iBSf~|M4txtb?jc$zaB`S{NkO>nMW-q z*<3YuI0pY@B^$VX87<=VQB(m5Ec z)o!rt6K>>rBG?P&&^=9$9}u<`2q|wY8WZPr*kdJo0$M!&$) z{6Sq3L@Z5-xh}M+XhXT4oT3=pHS7vZyd38}vTgyRa?FKN#)}J1JdwC)30&Vbi)C_G z&Vza-nhov*b0m_rlJt>k$mI0?F{H4|^OZpwC<&E9-LYV|76xXFLQ_Xih1%r&pJZL> zU$rrM@Zjw%e|THag4Hk0(8Nt2%8a3R-jm%R$&AG~FiWAp&mN&j96K?Y zbjq?KpSx?C1xFu$q`PsH=nBT&W{JJ=yHG?rZ4E7vpmT;j7c~`(dlp%fb{LKkr{DWC zq6$ouHgeqT(f{hNg}M*Zho4uvOI9d7^r3dYNR*xfmJVMFdC8-rC0L4QV7<#&7`%C^ z(E_%k`_J6HykXjohfT3tA$ts8xdA9-^reR3^p?E=$G_KY&8JC3zG1P+cQ>XLNU{e6 zqZfuV(!O7NLHP*tSu*yzto7-?#$U2ZUGIA?k^$9Hzz*$vEj{o978FaoMyXSN>1Q(cv^u$6QR{vME8E({BnjvC%kSp5BQdOtHU zuA&M&ml4brtJ!0K`+n2!br8jWE0Vttu$LM*Dbl-B!er-(IEm}IU~3x$DHC1r*d9S@ z(Ip_D4Gc<}ZU8Lt(X7os;y((Hk%xVi*UT?hyrx8gJ?%BH8;Y)o zKDtFm;z60XCXz96)PNICrz@YH28`T;?R%Px48Kae&OH`xF7>xv$Jbf{O>$0>wE51j zm>bNxpk3{%-=N^d>1Lw(s&?;WS9iJB))gSoYVvRB=zswn-r1(j$46ywm8ssjKz|@u z$TWr|vuq?bdsu{e&m8O+=5!1@?j=tcb%oy(V<8+N^Q;R-p=gCYl!sB}O_DI%k;UDX zL98CR0^IetTLm+i)D_<9`8}g2Y=I^p#CRw5KpK>zQ-@Lb%=$Gy#RTxD(!8+z{27NH zzq!2#_TyeCaKM-zK*}%oAt#ZgB>;a(eg4hw58aFtosDyff=t|Y{*Dy#%_}nMM}xA2)V{`rkwC!r@T7g<~_YP4v=o9 zkTfN8I&C=avku5GcBw`Ao}+Gm-E>L)Lo1hHa((1!Cs5^;wg3Wk?}eP^MgKI?CWbYC zr2<=;^Q1Cnav#hwR*GeDA7m*L#Gg>abOLyFDS`;D2M0#_WsU2%BI2U>bs>9=hY$%v07lO(#$DW z$>E9owqMjJQ2U8x4N_fQNdz^-R!BgnY+hWa*lQ2aHX$FT2V(Zq=YUHvatc&ZQF^4M z{umPD`%lC%Z~`DTx2cbMC6Z1zq?qMdbKVPeil!mglPyq(_I z`K(5z7g zs2My8vcJAHQM8tfPF%k4V%|g6_pDL;6ORL&4IIj&m}P~J<0x;SKa!w;iV7rjizpZg zh-R1-Kw^fVK*Wb`(bfzqg+wnNX|zXVj@#i=TWqVY7gAw%#P%3QQXjsIsq!#u|gpQ5IW}0M|~dzQ$BEP53=@jFO)D>I5Pl6&ORUEvJBK`;WD0)-5YI z!Uw7M+}h#==m(5ZV_VKdEIIYo&ENHpKRW5m&V9TTdEkMPl8QOg!%YNS7a=}nPy!Hb zhd_Ow1>X<^iRb^ROO~6i-$P2zg2?*76vNcj?*VY})s@_2|4ZFqw;9RZ{O+p)RLnMs z;>zc9QD>ScJ!n%G9`i5?9O=y-?bf_z&Y2%vvZa}UDPYw(yfz_QI}t5g->4QS|!br;yg?d+L3h%+p0kc>-M?a6x7M=^86* z=tyrul3eB2>sROU4Z6&qkr0_Tt971i#}v5?rubARI2X80V=oC_x-v_G z1k^kif+Rhsd6RGj{Wv6*=F*16l^|z#PVTp0kV1o3sN}#2WpEO2PgItGs}_|I1BoS| z&aWq?RPUOP)}9UGos~fOx#eNU_9bQb0IcCta!6+Kr6U`X3D@FL`^t*3G?~Z>=0F)* z#{shL^;!JVDMK%OO(+vy?VS`lzze3Aa zK2H;+%*+Nvk}=H;$t*dqWk%C*KABZ#zrhy)dG(?r?@yfNOKeXurg?JDOyae@i>3wE zR{!j~yF^9&%SdU%43Wr(9P9oFtmZZVk?}|@b-#YMLidlMH1`m?(1t`gaku{l*W+7I zdJV2@o)`c^eK;1uk96tvj;4lK%3enBG}JN2H{!=pXJ_#4HjPppuTG3m(&T#LEX(zU z42aBXSqD#`b(o5${}_3Y^rod-AvjR{xUj+-9s@m%(G;VPR)tJ>d11u)Tk82f(uTU$ z{~)b7=D`{AeUHAEpiMxt#Z7eZMfQ5#D%X8W{7DK3_`j~F4|k&&+V_b7KK^)}KQWsR z;r*HwIJM3d>zkCPf`Li=fhGbeoE%zLU~l=K!!mjrG?+qYTTVOZFnj<@Q0o^s+1pOG}c0{ z-SoyGMzhZ) zqe!EGAv;aIqswqSbLL321>Xb$W+rP?wqBUkRuXm`6Y~12C1fT=4+~5cFh_suZ zX{KaALS>qMQ=$V#1qR;fFECqZk_<>*BwsxTcdvnq^0IXp*8%I^Us z3FX6W4o;55nGv8ip&rQ{2yfpno@NH!fe52;1CazcO)$yLCLgQQ)kHv3ECE}k@9yL;;zBi4$TO}tEtzQGz+hBn>J(_ zJvu{fP>=A#+13(>j6GDov$_ixI2pyr8Imrss>|M%r0#J`j0X&th^lTV=#}!d&*jgQ znm^%!ii53C9BIiJI`#1=4cKzG+4in6BA)a6gt(}3E0MsOl6#76R$4|Nl(OPyyTUWe zleFsK^cAmP9M?FR7uVkWO+r4NYUwy6E2kpubY^xDT?(DqV(|SPiKU_v6%sO8_uzim z*5;CkosUI&PzWTQ%$1+@oNn@l@g;qG+pCb`2PH^)&Mg={%t%`eu#ck0-szL*ikJG&uS4IzMtA&w!Tcoy@;r^}FdozFmr z@s8wz9+p^;Fd-f9))c5)4>?(PWNx-TPhCA<-n`~h^KhrU(7eLzQ%JoCie103v zE3D-_VB%bu0ek4>fu*I?J($Re`fg91TdYd?tHD3+hDsdw_v+(qFdvKby@H=(pOMWc z$OQYQ+KQcKs$*E^XnUh+{4pj?e6;89ZeZy)h~B4!xS4FP41RYaztj(=mBi<#;>Emg~G57h#X^k^9vf>bIzzSeJ+aT}Yh8aDHQ#a}~ z?ttd$yyJhO*S14A=VVSZ?oD}rk4giTgjE;ErOZSF=ubVMVLWb1*0JdslCTo{6pk(C zSV;XsgKvvFiuBu0DPyS@i_*&u_YVq!;snNO@Qf&a7r2(uJzCtCsu58UN8o>C(FtFR z{weHoe5ehRqqB4!0ii(pu9Dp@Cq@42w`n&&=LE=DN3`8?$*{uRb8=pH;J1SPN%_dS z`#eq_gvU1e{Lk8ur^HDMS}VO5s{i>l{93V?qFX-rI zZ+T~=x`m(D==#i6XWQzdF3g_G@nKb+)vs@BY0xrZOPD8wGknZ(oTM4#@U2iT>5n#W zoMhR%8lhWNnOmxZBOQ$-BO_XZ1cB-x#3*Z61@j*w#|1Rtb&4pd*90pOqa8Sb<);~b ze)v!1g<~EmlJ9!InIk(Jq&K@+xMAfH6MH~4ptAG2R)A9Rgc9jhH&g(unk+ey%kHs+ ze)y-a-|e54heXGi=K1{>TNG&TDk2XL%@2)uRG6P4e*(|f%@uKhUi3L~YiftmyOTenxO3#Au0OBqOFYBL zptA^X_sVcn5|@*;7~AIiAc7(&ddpHj7?lJQsII{liLpq83-|M?uJ1j(y~!aR)gqt< zc|pK4$wSy?5Mm&isP^`}BbP3LNxhWfZ!YII#;qN_j*l{}IldX)_}3@GxJExPp*=R> z;!&^=DbRKPZ>tambDklc$U|M94n^azDfYwzNpJ88B8Gl*ZeI^hebky%8hCHbjN)zAlY`-?MD)OYRhEle1NAd$TJ9a*%vJV zII@JA_xVSs1Ms)NNTo#{xd8?Xtx_}Dxjk33bW++x_=diq7T7DxmCehyzU<~WZYQtQ zSCH^!G-7-&@lr|=TGc>8Dk)Hrlj20~_oj5;^XEI5h4Bk_p)-Y2LN>cwGkU4DK%zcs zatWlVIJgpS?_>RdPu9=*Wify*>unT-39*laVYd#--*BO`>lj-FDQ&u~+}Cmz?s#kI zQ(AtzS|PePBLGC0zyw6QBYl*SDGdHXxZtAAqG&zOpgqN9`9wK_C3Px8#icLpxq-yE zK-EerR;ZnnfW^d?>-`3FEX>!nmK-<}(l)c*wu@q1dz>^5&fm~0$z4JsFkJD=BM_4% z51V#JWL}!ez=fu(o&Qj{4XMp4Jb0TveWR^r&^Tzej9*kLCJI5&a!Ly|2!!NO;m7P0 zUSqMKEu?Pl*+w0pJEKVE2+@^!h_=t{2LEfhD;e^7&R`erT1c|;mpVCZWAd^?0h2F5TXa;5g*K9e7Gy;6H!t|AP_PqXy1?x!T269fxj zUe^?EWBzG~OdpYAZEAf#=tV3&OI`HHnxCD_Z?C`SsCTgDb9g+2YS-!2vZLD(pMI+X zkouWZcS^i*$eVxa5u9OhPZftGBG4g6gTx zS)9B}0}BO}*b@#SA1{;u!RtYq)&N!34XoOYusuQm!jFlTO}`=%5=C{-Aw6X#kv#J& zjpB-opjyoTQ#8Dtws(N;CUx}(!k`y|13P#y*%N9jt(<9QJ|~n>mxZ~q7f0qKNS&NAiJh&DAC?XVj| zhhu!HkG-Ae_)xKWC%WpNFcx-lh-Ce3cBfChj#HdV_U8H}p9Gkm){@XZfBOZWC<3j5 z_Y}5WTW1JOy_ei=y=e7K7k8_|*PMU+Pcwb4qUI&d0M7;3yxW%gC;pfR4V2zbcUBZn z6{sPB=eH+6-BYFs)MRvkP~|Ed(xW4rgB)rJDVwZkk+&vlk|oImxM(0?LSkuk$FL^iV~^=$r}2Yiy_!Vcv8+T=OTBr_1!qmY_Q3H z(43k$g9I><%OlLl|81=WsYFl}sc6~Zna$Y69ZufZ%lxDQ6;rHtr7{Zg^GiH8@|v;3%QFY=^$7g{&S={TBs^qCc z;V6hRZM}e6j6X6lpE=&`vc|w^W!dqm#&uXFqdn)X#x|B(b9wa5cgT$sQb@hW$+(v8 z5;Gy;WC2`$L)VTp9{d*;B!Qq*+SQbbo{C0vMac*73x*hjI5-RoYMh5(Snh+?u`Yox zXb-!O+Z_hcx#gpow|iTZloX#aFnq}AN$HK3mii`6&p#wvMQ%L;6%h&YZ3y++jfJIm z*}Lku3hlq^VWm@rzTAIOumFheQ*OdBaBA?woXf*fs~wX1~1-1(5aBp!H(-aD#;Pwl>quW zpf_zJrY|@}TW6Zx5sD33TbJNs@@)zI;F?Yy%pF?XbBfn$yT4iUqLW4&u>X+$ELcIS zV@4vHswMRV2K8>q1a&M=T-KLIq*rhtOCb=0gwucAz}$^D={{na68^5gp5-hWQRhL0 zRHdvL-ORt#qLJelG>(qXJKHbR7Z(`b08gzag!Dgy0W^PUiAYBwK@ zyr9NWYh;(tYd<#?c*QG)7%2oC;G?p(TcmOEb$+hEgyt6_3E?CRq3EQ5z{UmfXYylP ztp&%5^ZaJ%Y_|^9R0Zar)KeNN^4L45Qd9-oL&VRE%zOs+`!k5&kh&UD-WJC!sM9y| zzL}}}w0@JP1K=Ag@{Y>qU=caoU;^A?y1(+4k8;=I8Ld%<{^x@0> z8QY~+&Q+6`!oE?(GyLO(ePy25(BJxK9^3byaZL5m&{$}~Dzzc<_z)wH{j}>h{C)t< z+R(fLhcEXt#*-NZeyB|pZ3wXFb_I$RK0@T}?(ngR>Il7a z0H?dImFRg=SM!_+7_TyZ`<2H@lBs6NUrV(g(W)p&u)_0;CEMVzf`Ipu4DH#gZ z825ClLUimw>rUa7zf&L}DvYB3U9`q| zUMX3y#K?U9eHkt2q8rjfVX~GQw@wW}x?lL-Pwo5jA@^0XFkSx;Ej|U^2RQth+u+CQ zS&|o`hw#cpb4r!6p3|m{`p~qFl~pSf*ktFuu0;NA#H)mH9c+JrFZAXis1_>d;(*JHce2&?lF_0l_+b7i)^@g%ZbhuJ-F^253RC<`y% zdqB74K1D4jbj*Kll2mMS#`U+Q0rk38ynfpT1?O2ZxyBkJ2Gf zg|+R&EGP)&>34$NCW$n4ZJI0p*mS?GPVI--4?J(K6SXrioke$F>olS(->fowfCzE< z(s&oMsJ7!zmT_#<T{`sl1It;gZv@PQ^r|=4Af8NoLL%(Es90Z-sBglSFi}Jz<^zOtoVx89in@XV@t5KH(zG57QnK~uc zmqq=uaD|(gldi`iMx7s;M(T{UP`X)d1@rSKGS-9@S~PpxXo@oe!^Qzj%4EEXXDD}i zY8$xV2sIUiPKvY4GXlTBRoG7gCbR(=92qpefNeOom#m~a7;fb(Fi7cfF3U@-EOOlz z)^?#7?yP_~8{yW+J{)z9)Gmt%;i9_!N9?z+>qe=0HV6hpthHRk%>5h1&9OLJ-yN9h zO3plsgWyv+cbEwqySJbNd9<;h-h}HgB!Wd6cf1}*_{`qRp^hB-Wj_|aybI(8j^k`C z-kn~jbt)_#u+W#{Iop7tAOCDOXazV3-<8^(l zEI~N7*g{aZd2~12$Vr_P919Zo*&*9uitudadxK0@p_hDAveooh7kLVL5CjaZK(&`Q zFRf_zEy93)`#z4olKa}x&|TWDQlulBV5xYK4W?B+d6AR)d{a}VlQ5`n(*j??DZF{m z@$qs>upw*D-38M}V-yF$igNgAk(7y4WQ;X4?fo}RUmtnCEiU8dBDTS4vj!;ZW#Y7H zApq(iH#9>+w=0n8;iesibtcv%si=mxjTJv^QmsztYp4tul(p{~{jnt`(YJ?#QbfCM zGPuXC}d_}LAgO9|*o?8^*5Wf=H7d^)%uIj+_sV{W|jF?kuLIIq=Y*VUc<0km=gecbeYXGtA8Yu zh1O7Wr&x8g51GUDXQIl)M(mTb6+D)%MUBF>O~QyP;VR_MdL7zY<2I?@>mp)+AND7V za+^TC3xu8zV%4+}5v~aAbQ6&xD!tLj%@|G^nCRLQ1%Xp70g^Y@{7HDlDD31%NEeq=rLp4Mzl_CCSva%&xHa90f+5{gK5Ak4}uE55h z?NYfa-f_!my_ERH<~XH4e8OS;rZEBak|bmg>Afb^ z-$j%K&u(@nuE6UfMxH7ByrxriWj=s_)?j6^rttZpl+-EEe%H6h4LG^cDOB|mUP#P$ z*&w!rOSLtvEz;~QQVy_Q<5t7RJD>C3)0-r9+GIac+ztc}nJ;>G3`rtwrcysFdGP4) zT0-9n=*id=0A6Q3{)Y}FvfNJi%qAgemT*B_o3P&XlpaG1;0&`&@#nv0Z{e%YaDoEA zugieVF)M5zCg{xE?n1@}$qk%Zfo^;9cFVMmb<4lwtrmwnDGXXog~5NWWnv9efdo)l z!uZCW$Mmh^ZMTq=q{d0oMCN*8U24th6^)Uzyi(5Z2YUT2Ko()ONMg0 zJxBeCs5pklWby?T=-bdY$Su0ZR2!Sr(-g&ZFECH?-)Emu-9-3zgOYlZPzV(~jP%*T zRjH9w=&Wsg{f=>6!OjI|Muc4r)yH6;7KF5C^=soQIG32ZyP*DLQ5j4MRkz|#ArdNa za?3D5AIEGsS2Codcuxcw%5!Wo*5}D2W88G<5$*9$VGQ4kw1E#A4GN%d3hxdU)&!1N z6m1`IQf`jQ(Nf6iRMqRk$ti| zx3?Mj8d=(w7zNr@Qg)O>5OL56sP2Dpp6R-#y>(VgY!Tk}+!)P;CX4H6+2 zZ2=XXXdPzBd1`p5oCx5b5Vbl5SBvFW1k87WI$QU^5?t5RMRk-wDw(wTG`ok&+etK{ zVE*9yU#~6$fsg^25z=qtkN0PKTT-6T`b}B z=ckcQ8(9uOJoF4kMDgo3k_@&w9q~(W64gd6%m`!t6x_$=wE)`r@Lx^o!{77XYd|SK z9cfc>ynp&o*ZvrN?!+PbVN73_n)miz$#!Rt;|W-dO#_#njZ^h`By$FP*@Vl)w+>EI zJ$gOXkpxCXYe3pmPg;Z`U?B9*YAn(@P8}zH!!IpNE>*u3{h!Rh-RoDMJ?^<2*9&4; zRqqkRh~2j4fd<8ZF?r~M5Xo$Dv-qA+#a^VTPNQ3i(eUUYoe;eZI`Zi|5fgYXZ^DI1 z#Aq9$jM1pCf0lHeF|Gu1=RdlEnRIWp^r@nGwVUwvLx;5^bashs6xF!2j4Kz;WD0@3 zkFM06t;X=%23{Vb+VA8jXXp*qSy!JhvYU=v zsR5HZ{&OD54Byq0wusRcQ{h-m|JYhV3p9G%<=KZ)%;n4>f9-knc(<2>qtB}CdAuhn z7amBkJyi+P`Z9oVE; zP~szV2L2~;lyOQDNjWe800RIF?nijhqZw@bF37BojI?j&jY@G5&SmXUzVu>@z(Q?0<` z$(sOD;>upyjGz<^HOCZ*?hgJ>FMn?-Wh(F41TtqX^fwM*x8AB~hvkhk(qFUU8C4hik^$ zhVbyXsDkm5$6h))6g^{xc0VH;S5-U44s)ARX~;(7ZRH^irQpp}IMyE!7>s)Km$E$1BB?$93WBIkq3*9;m`6oiC3(AHPPjz&_M?7T|=f`r9j?B4ZPw; zRp4pUe03Bp$K)?^4$1X(b9QdgY->|})#?sqd%K#ox49|RA%!)oHS*OWPqQB6#d{aL zHw)&_++WkwW~sOaHZaQba11^__AN=Cdn>mfOD;6xdIPLJ=N%rotm`k<(r>Wo=LM&}owq zlXtM5sB_TvKhjJ4h?o9iX8oWbF3dt$sJk|eZILOS?JcxFMlEJ%7bWS<%pbKllMd+J|F2z&UU70Nupj+2^R z!{GdSA)-n0_m@#PI0}IUKSQF{w>KkUD@S)4$%7wch~?zl`byYTAIIj~6)t2ppPF|#UZZ8&qIIXugBbzkpVw~BpHA=U zdfygCXoZSCe5Wa8?|$*!Jo4AIPy{{M=Rp&EG-xPKkDUpqNZ**yrkuGJzyRlDxlLd; z*i9h=Z6QZouRdE%pgtvQvdW5+ioDMp(E&*_zqxDQs;RHq(ka_O$ig=^N5m!>l>9p! zT4H-nA#P~nr1MP!?z7K;!vFFAZPiY9$Zl<;C%PTTdUn?g$My1@k=8#GUVz)7P_oq_ixlw+3?u>W$g%>&pW-~i zKRQqD1Fs?h8dg|BSrGeLCv9HupovR{FW_rU5O=qHP}G1|RY~*J`Ofa2;NLEq_yj#49V5woE_<_n}+m-6_d6AbgiM# z?+iKK$cp3Jt~vsihpC5F?xEcAH8`f!y{ON2I+va5o@H>hPcIEtR6T{_M)+N9IPeoH zo3^kwjiVv1`t&$G5T?1EX1j=*fZLOrW>=k!n$S+y)YNEy{lRq!$KCBX;${BvUO>kq zf#^7wBFq7Z^Jm>GlOiT=vQy#yJAFQTISOWN#>wX!20>|ie4`qrQmsJ>JdKfRQz&KZ z^6knH&PB10ZP~gbw}q5#@E@#mNVL5*IBW0ozH0#vU%gdm6l^4)5X44<5ST6GEPB8u zD~3Jxy9ew$0RvkBAhj{mqR+Yjx908U(!@`@W(Ya;L6dX_P05Yc32s_#f}5zmuqGZJ z3raT>BiI=P-av{xalSsTYA!S+c)-8x6(V(;H6KOPUVxQ;z4}@)$n_DJeJ&1Z z>Gn~f0LFurRk6SKdDB%&LnDoqY?WTfO>Er&0HT>RBv@%D)JPujrh|?+9E`mngWV-V z-`0)bTfcUd-Bg?qvZ(;=8H;<$xhN$=*vgMm9m)GN-ag~ z@OjVNejBcJL{jrv!nvNTR_P5RWB>xjmdu)wX)vy>`MKl6N=%H7>WmqkYtCp%PSZ z)r>MZfiW1+#@3c74&iCjn0_FX;I$S-Z}tB)ot+mz&86dQX|zPDeEM#vYr&cVY128B zAICIe5w(OvcvS=cFJJ_l0Jk2ClJFdZb1iP|VYQ!mkPDpT?r|TyxUd>fJxeHUOftB5jQyECVrCPbhGtDqmB_k7s6E^C$1h24c!|mu^z`>c-*KV$d*brJ>6z9r zP41~S6y&%}x{pFF%~13a%cXo}vqT2NztT5gG244gM^{_@XanMs!;+otz0jaAwQCDE zJv_0r<&TUM4#?WD3<~526j9x67t;|i=d|HWzECW$EGxD-T9@af% z3?YbQMig;tvX(v;KXzozT{o7={J~8YjOkww3XXS(^a8B830)zz0D?c~+9V&>`GK~k z5f9r^4aaz)s2IZ-{R3P800RII_|b!Y%)!iM(^y8FGo#-|596j(sMNvts}gehy^lr| z&A$WLI|!wlU41C}HwTxc(VY%S#;B#V%TN-!CBUv7^1!>S{H0E#)nUIQ_~s&UAB8VW z>ahS@D_zKFHz4|wzgi1)DKpvTsSR4vHXLE|UA}FC{J>T{0z!`L;uksysj%BaLc26u zUBk7Kw14D(SlXSX9Bt)kQvQQZ{vwOCZU$%UDkGdAfE$(-oP-E>=_b%>rSZY`)p`;uwdlgzyDuic z+Y{nKO?5}bpBr>xgvXJWAJNn7Rxw8;atH@sIEG`96r0}XpYe;gD#z+9CngNMI#ijW zC$~wGR7Z-ka?QLoyVF**`QW&_vVvVGM{H zZaW*^+|^tJ6s-T0q}_Ncl9L`?$cpGJvN1_gf&9EPP%g)Pe;e4#N|NoYWwPu&s+iap zH@B*NsuXn%ZADV!HrC%v@46;?{iXCAlyoL&YIP_)kX5$p5Zg+YMCy4S>}eEI(|Fys z41R+^LvTHS?{X->x|Bl=8Xig)q=Y-0Y+Q*ZJ|nbe+=0LPmE{;{ub|~X6LETVhBRm2 zGM74dLo6vG^VN`gZv9bDfSEPddtia&BRN<2@Ks~I%Z2##z}LMhN4sq>NzWm| zIFGf~W};0~FEjX=z2DPMBVDi8+l7fzhTLnMQ-9NS{1c)y;};kE)m)+5^n_}d4s2)h z1!}hooX$dd%Rwi=@xbK<$4*_&ic-%RE*DU0nnL87?j%uwCtz4W*NBtMf~$&3DdM2eI8O=Em`{vB+JlW^D47NFqnbUn>gHs>H--#>|arbMV9wEZ-FF~lWI z`i5To{`UI$X_ySVSr+20a795l&m=Ko`SqLT%D|owB8hNQwiQZP+K<9>maI|HRQ-oH zIKCLdpZ6MD?fwWa1}q}zQ1>$NP|vn3hR6snk0mbA42oDa?81SlHuVsftZMcps1OQ~ zo`*h)dz>=Kn$1&OI_$MCkC)PQl(4915j-8d#rK>%}+cM_>{#~b!7$VnY9$V@x5P($@ zSv_S`Y4B$teM~pA;l=*mT8%gl%S3*Tv`kS0lEyZ~ujLQ(m>|Q{VlpnxzzFgE`0Px{ z57G?D0^Sk|N)>2s!Ag&V$ z78MYdPg1iL$7z9gPrYfm*>7@Kt23XJ1`n3feapxP;`8uQPD!1cE1?1Ss(C&^gMH1~ zkguwU9gYzl)z;YF07#COyXAI!C4FgX}@EZ2lhUse; zR7MdV63wK~s5Z1bznH-cVjhWcQ8*6Sw!({Wtf%MZX&*KO(Y^5Vh-6f&8X8cYB8W)N zGI8+P!1V5Q{Ef=$B~T|ZRshp(xbXjnVQfs`1LZLWE3O|z=l#h>=nm#omW76=6E%#o z5YJ0uPdb*fQff1?LVdh~%!sG!_HI76`=_EASEE@i5*V#u1>uuWV+WS441rbD zulN)uHNIWe+A6tXqxNxI(?;NM)w(-%Z9soKTB6Je2CcZs>OhJC5Ywa@HBG3S;R{i;T-c{1FGb}(wZK^3_B~zJ@Nc!%|gB3Nw`d; zA)2AVBs)1P5RJBF`6}8Y3D@$rxFVe)?=Y@uS*d0X3&|KA4ChYS3I+fG9;Q0bH_;wc z25p_`YYFN2b%BMo#X3cECR2R#v3tCIhKPjyYkX!Fz}P}LRaDds2Mtv;?u+W&N@gWG z%_P6Gy$PwO#pX?!2Dj9=U}T4QOsWd^0ZplfB0o(w#AyE$UjC0WDKA23IJ8Ceq?EPX zy^7gf;It@+PS`xjCJhy+Qs)9Qe?tAtY~gxfQE=Bko>{$ZwpI1cx3aGZSf!8@W*m=}k8; zvvUCY#&tdvP9vYGd|53oTBs(hW9W2X1-c`%$zLq2D@&;%Id=Gt<(>1{sJgGsOObaW zgM!+nde`8AZR2jJ_2ZR0r2VQ2jy^ANOR3zWl2Sue8@(!=P*VoQ7|VLO7om(%+U!{x z<543prFvhXl0oFev z2k}y)#ROOI000=B4H-f>^Fg7OX#-2+whf}03X8tCQ08SE$M~0pyuzq0diwf8_}gkx z2ba}A|N7Z`U6*KWZ?Qnr0Ju%&mi=P~rn`Z72m%};Ma;*J0VY@lLk)>$5vjcG>Gvl! zTk(5pFqbqNIhL$HqSo|K>7fe%<(}K30u%EQ%dq>wm3XPynZEKuOm&s+k4;Yr_kQp0 zky;o{%sPu9u_R>4{LsT8qdfgnJ_fdTmTM%a*z)_K ze=G~=1MtJdp;U|YkB9BK?PRDg42$jz*>7Tl40^(;vn{idbXuABp15_9*WGoRTWdv> zN`p5j@yPKax*;&QomLD!;>5%Jq&OJ%6WUyzyO~|Io@uARe&~CX8cRuucbAYIv6Gz& zu^A^57``qcYRf`X_oA}$89|^#_*zdr(~OxBB7|T(n&2s5&22g9M6o`ZiVY<200093 z01V%fYVeu2S5+cEqRv15ZNIfG=5yGb8VJUAf&y~23x=kktY(|iKdTp(IsDk@ljRgN zHssY}s9b64Eayb}v89jZ&&yoV%3CG26#Ri8?#B$Vb|cbV5no6m!-JOV6yOHfywhD| zR^AmdeJUXv5@WCt#Zu+hA$jlIOA!;T-KYQCynuVpv)TL$ zoD-91l&Fz;<<`|Bd39q=LD0s{yeqcNiQ*3?KjuNLf!T6MPsjzx=zOxROjTk9G$!PqVRrwF5V02ZL-M6TVbXDW)0KWu920cVWzH>kz}H` zG1|~8-}J7ytO7PQGa`<{8N$7$7EwuN^9Y>yiudgi%@SjMxDQQnU14QLO6$rCbdYX8 z$~%F;*Soix*S@3T(oMv#Dsv6Rq%|}TP5KvAJb&H`8bAO50{{R60W;cEf8U_cjsm0W z#F2Al1z-bJd#Z?~;eS+kUpxOH<#tkP^|l2(IPQZiGq9-tRFsm`{FE(otE=HWn823& zQTs^RbJBzyzS&o7v+@G7h(41k2GP{HfH)rYB)nES)h%~P*@w&Dm;wN_1Q(-pM>^(K z4}2K|-lWo1{ss(l5i?XC19)Ns=95m}<~{ig9RT?>)Qr0K9}3SD&sK#R4L}WiEX&<@`T->zocrPToSXDK8yyGUSVJv?QVzY$GcEoSQU3`cMu84r z&uxx}p5x@#oXghQ?mO3PQZ7AEH0YQx{*Cr@9dUEI<0rvt2zK}9ql_TyaKUa6kzKJ7 z<}fddSO%VY5rb_I%y1FW7P%YPnv4Fcg68;Q1$-}qs<|}`x#D-_w`NNWA1vZfgS>dU z&%I42=(!5Y19=VVQkUktty*MaO~N3iS#d4;i$*HMJt%*J9h7PE7^N?!gFe1Kbr_zb z2RQLHPsr0)jiHQ%{Cyqbl@eq3TVjwN){i+tpVQmikN~?u6R6c9A>M@m;q?3ysNG~f zt?OmZt9%RpNAgv_zv$%`&ZXh^V0(}l&kXPJRN7}7$X6UCGT7SqsXh;d%L%BTlly#2 zZV1qv_jBO?<7~1&O_|f`eB+`g8ah>wJxAyO z3h%8lwlQRSk3etRDiz^K9T)SS3aUH`nDxkeOT^@`ORz6zdFg;u&+%CN$d5o>uERU0 zbpjkQG49d4aXx$k@XA(}-n3+=gjLLr@ho>h2kDDHAWf_dT<{zGQyj`b^+j$%5gfCR z+r7P z$nd`B)t*4M*zHVpO)b1vbx&R0UP{Lt`4{W~wYC5NiGVC#tZ4&q$sj*USB z)g@w1PWF_b`{H@b8xg*oSt}X->S1mgQ3+vyMer4+Q#eh zNU=OcjDXS+Dew#dedN2P7W#%J1R|6R&7*;m+^100>I-GZIjY{QW@rV7>3Nj2@KP2O z4xd(F5+in=`2TgbN=Lx`$Hpg-tAd%EeHmyMN7ZB5>1iQT5>`cLF5H2kM_=+^QcG9X|w;tq%Tv7w?M-_=Sx#$SBA|@d$d;1sj7e01B^h?=E z3{@6PnB{NvyS`7~2#$Nx$*=y1Z;B415XLB8Q>n*EL2v7M`m z$LrijE7sYD+9S&PrCMStnjsvkJ1_o~;DQd$eZ`wD1pw~(sUUA3c#1b2kTZYp4 ztNkeZX}k5^2{LI$7Abu)OoTU)H#&J^4-y{3Q}Rm){hbe*r4j2RJ1f79@2&AZ%+ZGX zN(x7q83}DAlD5*XvB+8DT9zmidixFW)_RYG!O8D=)5nJKvkYDluQItj0m<%=f~MXc zq~ZTO8F?4tmS!_4w~Jw9sQ}u%>^p87Gyrlq_rS(yrqb$RE&pU{-~gXvH$OYE`xISQ z6#6x=2)SI~lrV)$T7Le-PhRWxAYxx{8I{)#K$ez{+*M6#iJ8M9z2uIb#Xs_KyJ~to z+ajeOijjx`+YymvB`b>S75wsvf;DjMMt&>=&yVh4FQ5I>%qwG`@C38SGT3&8@E$4> z?9_KY^+5zOcV;t>HFY0s06xT?ZzKDu>fS3Sv;H{Dbq=r+D1=?372&^IvjO+ww&(8y z8-D2)mVaP6g1kbhr^5ZIW6td0qa}je~L776@R^e;yP;@42j%j=Ec)-=B*ID z5=AB?f&L>ho-lD@0|?~s5}4)5@ftJ$f(A9P@}F<6F)K0w00(rKVYhR>bP^g7UHjG` z%CQar00RI30{{UYH+m7#@4O1QCL(>1QiNcdq}shz8HTm1FY)%5jUB`{+dpj8%AzE0 zV*x0EiNEyE;%+w!dAXxQRI&@Ar@v*bYRgxQk*RqI_}V_i!WLqPed1;ouml;A`+&k8 zrwik+WTRB%XIQ%8;q;f=5fMH-Atm1Xo!_{8(s}^3TTyI@^cScF`POK};VC@|yi#ndYvp-ZjAi z+sLLrgDL?k?Ob+#VX1}6={D?WBqL3YJgvqpxfzKQO+b?-p2Tx5Td7dvsb{>Cdkcp# z8(hu<9Mrsj+j_cA*cB_jb@(WV|A^NSg#`gvR3=Qh5nAIbO(ARTX`_jWg)34R_TlNO z6V==mef<&a5XrKGd4o=ISikv<8dT?;c78h6l(l2veagJtng8A2T_So~v!uUzY|K(5 zRf-(h45JkH7fy;X%ZX2?b(41Cse|PFq7ihjQ#X6L+@&3)?-kp!L-a?82btI0K+moy zxy%O+;|fSdzn2&Gcwxyq?Z`p)1>bM6)da9ePT|z9&K;?4RVrsb`a^z!eJ!vzT9}Pa z)Lmg4P^OX)>^@^%#C;26BMkDJw!2a%!E?Mpw3Dg)!HG^2jj_K;xYMIH%)IGzzB>2# z)Q#qZiR8~k`X9yXbK$6WR7Ip zF*ihveg^p#>dRosWrs?TG>*vbBBl{y#2mJ9-ih{7pb0`#jl@#@d&9AQ1T!Zb-~$w$ z!%V;MCmIOA89D~wi-xm|{thuB5c?dK>OI*h`>e}rrDCai8a1euYm!`?SufXJTRb_6 zcjq=l%Jt8KbUc{F8)}tP8Y2V@RP%o5ZD2GNn8@5kcyDNI4ck20Irc2#uixhh>+J*I`MiTM@Qhk6S>wb+*Iskde-Yi^ZL}Q!zpA4{iDP>>H`m#K>Ggb0r9S5UPi{zn*(%P zS*Xf5j3o^dk5D9e>cqX0@(^0uRdkW~iTqFI+woYt3aie$yN&h3D_7M72boa;m5#)% z0dq<7oP)km?uXHLbp$SI05fcA7PN7p$3yKh1ebdFFCXT{PitrAgmLY$(Xi5C@1p62 z{gmI@CFx;DXGcsiDeH5`Vb)w5#8oZwyN@1HHvk1`yI9iTrA(y+< z#~UeE#||X^%X&cnN#*8zXEJJ}VyXYS>TTkNV=3RcR&i?J+_6<(7Z8$Q^?QZSNd!=s z00093Pu@lUS~}%Reo)+icL5)qB@uDsH!}nVN!7OzQVhbK``S|$rgz|BFbw8L{!sn( z%Gm%cx}|W(Mfy|D+{!qmYgrJR(Qc!o{H_fgNrCiAAD1EkxBN2}t;|5qf+vJ>Qazr6 z=L4bL$HuumgIDiT;)fGRd|^pIGEk&-KUc0O$jX%k8$(jIjE$@c;&z0fz#XJ<+@as+ zk4VVf%{u}h9}C|v+27wMcNA@u2g&mcCkB>lyWsehz#^8}M<5D&rG_emxkGgNrkO=C z)%w0DtyUqBYNTR7FGvQbjD}0^Uf+ynDz@VjQFgM%dfn|HNX$UrqzQaS=bjR`0`x|l z+c%VUWw6_-PLGf9!|#%kPriPijO@Ms(ui0Nutb}8M)CKHaH+*g``7IGQ4IP6Z<;T6 zF6IK}geK1-BgA~pnpYWi>rXoOG@yNByJqR%)Ag*_dT;8QHO6NhsQrbK$|y8~XlkW& zDT8KmIPpaspJ<9W-AkG)?$WQJ^w5ufCT}%~Jcjbs)pR-1C5H!8OOxj=bt#T8XGT=1 z&n5f@p?Hb`GMq;+D|bdbV(Puq(4-YyggFN#cH>^pOoG{~L0$@GyHbftV-IH4MbD#o zmkgq@N65=33P5dDC%p0izJEZOE{s&DoQn?SwoQC96GM_W_RfG#1yTW%3p-==tc0m>SomV zJ_yp>fB*mk005|u;FBVECSJFrb?$X9a>;o(*j0`f0fy6KHiy(^MBgM0lNovQnj?Q(@{VpIVD6ImR?f zJ??^~QPk6Qgc-F+12{g~MMBvLj+nGcW@iap?hdaVO^NYYgdb-2=YLfta9j8gV=tLq zgebL-1Lr@^Zus<1QoDU_iIqxqjMqJ@x3DV)>Q~-ZfbFS(2R;5n%IM{OTr~u)dfGS|&&ve)g&YqsFFUSGQFl2 zV9c0bNy8+YQ9N+DT7vL$nO63{<8TW+1pvziRU2dc#FeqfB)pVDdGd+XJu`ix|LJ&4 zS47Z}Z1b|ABT4opy|AgngIHVkh zp7yv&YgH+{>2wL5aW8W zM1i5mgVV0IC%w_zO($80S38iV_RmAHM0;GcGSbA6bc`(svKt~f6akW%K5vekx0%nPG zDJ)~T&kKHkxA!wC3F)olT5#zyLU~%6vLy+`$>uSyUnbPFPN4h?#DO=+zHGp@XK4$P zVHtxz!Iba7e&(4_#eX`Cq?1x<#aKG_JWC%-cPAF$i^2_G*Mx9Ggu)BN=_AUX00_2> z0?<+q+c(9p;S?iVmpu?b+^aww_qOm&@CZL$B7@^WFh7P;jUiJua@pn$-PphY018EU zs+mRkY91;djUuO~m4krLqq7`v&ZkWHpPDRiD6VymqR(3R61G@gfBED9seh_f*(DO_ z^HA=2-O>vEuTdHWJ%9$Bp|+X3_K)OjR=cTMfy&d39|09d-H6~eGn~t@$=p2NxO~#` zj$X|dtfZa-4$FxG`#uW>TPS1HkBlu^oz3x99J|H_uHk0LRu>4o0ZM7I0v_keEJy5s zWN^Z2+?+_^m$V1alV!V@446@AI01ObJ|I1sTBCPtd+TtJ3tfz7QL7ACAjru#vEsl_ zkxcsnq=rXV(~l;boO5WtiUK$C4x>tCXvk$Q5!Y%7%GL;~v*K(BM^Vy&Tv!Afx@Q>H3v#KdGEuaj<=D#cB!;75w z9zPNSdBaOjU^ua`%Z!>cOHb>3&%~b=#K1?46e)@J_z?u5QkPJR9D}$ex zy-&m605o9iH~HAH$>)SXe1E1Dq{7&u|L*lpvDFUc)`Mx6=RX%w3>eXhkh)iJ4}3X> z@<0^q+j-ujaoZUclr%FL*S2TfX1#@l6S_U8i;+TnHRHD|Q=if)Sp9hb_NBr?z6$S1 zk!^5XmQz|m$4+a<5>{lc`P}N8}Xho`z#9{p8}R03z&0 zv<|sapR~-`2+&N;ZUWW4bY?`d(9kJh>sS@GgJ*V4IW3V$Iq-Lolt;}K+F|v7-Nws* z_U^aLf_!Yz=H?v1-{}*>+(rHJc8x z{-0S#U0z5YrR#T{^$oTMHR-;^h)eP&4$&&@KgsXc+`?>U)~LYzMBLhZ?4JBxU~$hL zEXFXD7iVq+5uLH3Nc>8GCX%39#0Co!3m%M>-KZUEP-VzQ`BOZ>9_jpk+^#+!k^!{6 z7`DBTt~MqeVB>ct8=Z38c*3Y4CT6)2xXaR%2tQI_V^>ZT>Rmnk&Y3Q z5BeXqtHWEH*Bu7bF_(?-HK%Oc48Q;Y0{{R60FRR9vglEN;Q0@{T2?xM$!KL(v5XG| zaXvjajw+GCRoCxyGNbAoE1;g{4WQrxTR!ybU9&DQoN1XL)aMTxzUyHcz5?Md zk73Is&kOQQUqOcz#e#yQ1n294l%eJ@@!aF{bWbs3!<2QR zWayKJ-`8m3V1f&cu|fM9!epEhMfV%O`j3Hx!L{A2HC8!&O6t80|GiCDSC8TlRXalBme&nwXZQM$=^th z$vz9@@8H9ZATjr{3|Jhu>HKah9Hy1xy;OWA$yy(0(?mrj#IC$m zc$aT*d-DDXP8lx)hHmo*_Y!T>b^*r*GmFJ(#|Q7;oV18s6N}tqj|FyI%e*_Y7fHzi zhSL=*C4c|`4x=j;mP6{(k{Nnp*%xRLPjl$~N=sekEVl9BRPafn`LJTr!&uBAGnJza zU3up-q&Qy+q2)a9z7cDR{&|x+l(D{h#XfXCL=VR755w~4pV+&)55a1*0I4)^`^*b8 z^4h+e$A?oHQeDHf>V+`K%)uV&l*=1js)#@t&He_&bpa|=bt0N{$9+ref%^3uGo8Pf zw&mzIiQq8B)Dk1NC-3=0&FnpM6f7UbvGg|12z+>O5-cpEZ`Nz*C5o0~Srzofnc~CV zXNrMP5iQAP@dUSA5Y%|v;AuEIh|=SiAWsBnUa+NUGF21o+inbY)&_7P7unIEF*W$# z$7x&AhOuwmc<#!gJm41c#FAWAUqBZXu&4syvmHp_;`(3#GEC581`l(t*oSM|OjpIu z3qs?1^Y_+-*viu$f;}0lJ_Ijr0m3suq+wtvwwY zJ=Q36eJ<};!4OQ5x?1SbaB5Md|Bp{*^m!`WgrTo`z-r*4WMR#XcMVLX{g*=f;9wNX8j{&M{RxW0gW9-}aK6@GMNNF}p4 z(vq1NC|JV&De#DWb%4{<2;;Gv}Z?gx7qwBeV z{n6scnArUAOv3<#^s4SFQ=?f*C)syM$S-b{%}JUxy>rkbez&T5h11B(S`AO5COeE& z@1o#g-G$PJR@JE)1TSaMUAcqvmfSllmbWGw@MH7wVfEXSyJlHHu)6j%{ zu^bl)ziXbKJC-E`Zd70aNKfS1hj@Q;Hv~e}Bjbete!64?6*KRrpl!(G(+!PCH_YNr z!*Cft|L0W)&~L%M4G)!g$KM1CYZzL4l*zIV_}-bL;e?}8kQw^pBH(jC000=nxE0~; z^?FM9RqOl~5wj1KYY_SR9JU_W96K}j_5C0^Cd(n5shwcVku+gXKIF5!k~MM^_0aJq zFg^%6L{I4QA!w*~NW@DV?R;xbVAYW~+(m#hz4wB*i8LM|NB~P-5@>?lpHk4GpC11$U1? z4d4PYH&QmQd&(_T6H@EbA~EtKfL44e{J(MWvRl5H>z)uPZC&Hgz9r(Ozn@w0%EK(uz0rZi1{*^P*?nq zDgu^oX{_P34j*CV)$gjdHM4vX;$#dU-TnBEd5DcsR@oKjHnr!W$}wrR8?5~9kL65C zL0M!iRPJJP`NhDZs$l$Sy#vO+P0~K;+QrQ`I$E+V@~@rpLfb=X+qXLS;ihq3KIQsa zGE#1uPKJopyV+e7edV=a{issDLhM;@1Al$bINg27;L`^Z1?on%Fk}!vka_&f37$t0 zV1^?P@(Z*KOQVY{WCL%g9`-+yhfEMT4A1z0zQIk9h_eh4B#n%z7V`s{Vqq;NcS`c5 z$cm0^d^CH((kqmz_#55faUdGPIniCNA33zo?pH~-no5%fNhkyF~Pg_9?gPK64J^ma;dX+QV>79P2rp+6gZ0p-aqe3k&zKRy0HizY%D4& z$gr2P)5UXI8F0lF5?o_`Jo{N&KZkkCFW&eR2Kl@DCNFucF0`$|4-xD>;ILh%+6FC? zA@^~>`YZcHaRXT5`M;!kjDue1=9C&}x?%bB3hC;DcMQ%s?x{(BS^K#TuXum}00RI4 zi81t_$G9=a(Oi_zt8y@WQa6sp4VbV>K0+QBO~nQQCz>-1UN0B$_T$dXnap^iaLcm$ zndSgJ`SUZXvFVud(Lg3J4dOKIAd?XoA;9Rm0G5Z7-Adz(%lHp~YkXXn*qY-QDSz)D zHQ$S~DIuGBzywblt~+a{5-Ii9mmgIQ2*!R<7tnq@CdO%p? z!GYIbK=LUH-rY+X30VaK{vZ6Hd~3jj17A&XD@(1#A0w_uvMEW8SrY$~5z|n|fEJGS zz99p3{8;c*0woArg(@+)pMr?Q$g`wk(Ye;~QlD}DP)1);Jmp;K_r+>+eM2M8$`1mq z0$grlTha_I@F8!z=e3^#Acglvv#D+A0kh;D-jWmsyiQoe=?Xh{Z~7$7?{R294)B*k z#{WO&dnVI_*WlOL$}{sa)p%SFKo|=#&?X0GhPRXQy`6L3uDFXvMw9Qqpr@W0)i}Fm zT|g+4Coa`n3AhXsK`imIXsE2NcV|rhdAT|G*Z#xynCSwQ9JcskkIfGvv}N?a{+IZ z5}T@*glr#;r_u&Ku2`*X{EUDiC`@p-!iUlotd5iLf*PM|>2L+l%cz5_4?=o$+=>vK zesiRC1EB_cbc(MK^j}z?pBvu>MCTHA=eQ824`=n?jRAs#oX^MGp2ednvYSR}ZUlfV zc7*$GQ!+n?(Fr4oxB4rhOPZz~fDp(KAET=+B09%bp~O-V{fY0KbimY(Ew8cSL~*Z~ zmI86_PSUN{bfoq6V{gJ99KX!=o|s-nNj3k9(KT1fym2J#3k-&Ah=O!D*w!p_BQOEk z%C_cnbpgFmBA_#%XvK07J9UNCn&kzHy$_q~5J>tgF9$NNy=YD`Ed>V;ud$4L*mRN^ zWg*jfJ|>&^5N$ZWsQhpg!=EI4@KF~)BV2~WLGHmaPp6pm7;vr#ohl#OiK5~>fazDetCq1n7bV2ONZfQN z|7l<#YWY}bWwvnEooHJM$o52Vw{^2?q9aNEAzUz=UK$gF#Ry2g_mz4CBN`z?zlP2PBF)`E_ z=yk&LCD;0|4Oe5^6aUz=_c%|_mhG@=?;#$A zw2+V-6~B{o7WiSEM{3rXfuCM`qf!)Z^&a{SWh$pck(=%=NxJCvXa6ZkSa?&qD*N+- zppRId`!lH|=QItXzoZFC7>`v8A%FrZXok|-WSbC;zLfd+ibKY>zW zfmrQWQ8IveQs=y7^7C@<;WpsV%4jOE1N}FNzLeUny0`+)E$f3Bs`+`V)0PdB?WE@SOOR-RDPu00093 z00RIDef@)Onq(m~Obu`etx&nfx3m(9wNyLSI4C9OJ+g9+Oyv9FwT1&^v{vIay0}@4 zO__sSa`ori=zh?l%rUUBdzPGCe zilHR{>cz!4KLqZ4ptHu3NNzT-iIyZH;HDa-j($MRK;VvF5hHU zF7HC`lx}LRt(D_2eFZJxc4YjX^KN$VZ9bF;mre@&TPp5>;NN7C8o9$wyB$Z;+;S7a z5$xtt%=Zi-yK1DQW?{7lJmKN7;b#+`VNi^ksyCxX+ZzGKS3ST000RI3ko<9g1>yHs zn|#t5mv(=2?CCm`$E?z~Q$(AU1TL_aT6olqp6UkSwWbrF#Sfb;BWY!tgH`Nw5it*3 z%QtU!UG|H9-Bo=X6!i8hPhe8IU2ke3U?a1N!_acd7rNI{y!=zsN+u7#KId=cHD z-wWnSlh$x4t}3{1dHGam6OW@$iBEXz>>IukisHr3>^QYHB-1*o@>lnoFg?4B!#4N_ zrls!x?w{TvK={kmlhyo(#4*SNmrygNZ`2tzY|^wE`E%4IQRDu4KIr?o>d;kCg z06Xj2b^%y42wWXX-QH_%3MJ@pXj6GpTcR%KQZwcAS;@-uo9lS@(B^X>6MQ32`R{^( z-3F{b|K}`CiY93amB~zCe>D=v6{Ugo;}Yt-VrO z{b--fK}aFTT4*h7fV58PTylFNZhwFh5yb&0qEx6z_eS2H=>UPZLk<65@SHJ6{~=p2 zy-J%xEMaCjaaQAKzb4ct$z;%^aGy@eaHYH$Mw7ZW}4;lhybV{m^B_i2(~LyBZ}&64?262SIJ8r zOBtA`_7Lx_IXoUV(P>;@1nEVC>6WnQs&iBFSlPDF6EL*3T$zs%LOp zJBD-`rCBG7e?%s>B3rx=)(m12$LIh60{~C$Kn|xnA3bNH@sao>MaqMMxFlsUj9vGJi*a3jfKF`xDWP=_<^AKmec&VuD-#*NA9 z5ILJRMR49KUhPlmh1ie~+>;$ys{J|$=1yx-H>p}pE2tKd@GS4tRJQ_X;Ma8P3xE%? zKxT#j%~(05ng2$y9e_nqVQK^2Zb^-w#q83jlfHVbeig{T+T7NWSwaG*PI;p|+e9Z7 z%K%RaA?P4Ws=55HnP<1000933JcE=0mQ(DU=fbN&UqbA;XB%! z>D!J4C43HFBJp!;U7pVq2^z1Ty>*-Dh(ZF6%9QM87l1}PCpeKL^wbFOH(^`NBDLk` z1-O=;N*~LQbnU}pCb79WGG*bCR1_{BmoattVKyTD)+R5npwcZ_;CD^=_@R0VY#@24M2_Ao@n@_@~thH8+` zD}dV5Th8h2W8rDq*ODxaXgsE98du7Qf43tU(f^q#s*P`b~&bLXX7E9MlU9BNr1Cv#+vsG#f}bqv{VY&0AO)g!jGb% zGQGA~(0{z7!QF-Ps=1uVgI!oF)1-+UbD05{Fj6; z12QKNQm&9AQl!c^bBfs#SJV~^u%{|i6Luo#Qs-OU{DfDDILtk7^U}l_w5LzTr<0-X zIj%P?g5XQS{D&Xzf4GfLO)O$Vf3tRP6PN=)0~5+{(v@z=0zf?S!3UG$RscHxLhX@! zLUI7wpKd{b*R$X1^29_2(UQ#s%T#w-_>IcCKX%BgJze@dTnXw>A$eNZ8m^+}YJ$4M6X?wBsm4 z1F)#I_gkcFilxj&F#NUt`VlKB^UG12E#OK@r2fwALA*WXjpl?n(iJ&NQQ7Ko+G0vaSlAp)5>g>zFEbRG)CvDZ9qv0u&yCxZ9cAzJ z789+wPhGfn6Z1ZZm~DmE75LZsqF~Y4d*Uzx(f6pZ10Cgl*_t?x2B(`qw1|~^q0V2q za-stN&P-cfgy&3Z^K+?xdhwPoK9CbY|7t0{| z`evMKH(N+7XP=?wv#9!gqvgkG0Xl9&m%vb7o6WP+V<*k z7-P98u~w;&&dIVjlfb1VnQrn%rgi#=VnZewP>LhQLlQ`COxfs`LJukH97wtKdjJ3f z0gG4E01-%y8VIrLBI-ffLYcirn%h{X+4nuFDU76{{B27WfVZB( zYi>*^Wd`>+2$V=dy)YdI50ArI41`p$Tg8=;T_*pUf$DRWw~q=A+rCsW9ulEdbtvH5 zYV9fCi5y`8k&ZIKtd&`@vur>_giwH?aS<=HR)d?!5lTy zne34T|A9c7Cwiq^)l06*812h3@N6WNb*lvQ;7j}1coL82g;kJL003kSxBw|PNitv& zUyf7R57`&iY)pUx3DF{~7kv`{VO3P-y)T;6r)1=?zl=%P`OfWW{m^o9D1OFN%ag1j`>73;rV5_fH2;2iQS60Kv|xld@LR?oZ5 zdR0nIr4FGSPvc%osKfTz#c)Xg00RI|fB*~TockUp3ktOV0lx~M;l$RRjRNH!x@?dq zC}h!vt@K(*t$&LM<{7jj?UuG4P^S$NX1cv>i)S>Q|4t+}=Khtd0`T4El|hM0&)53E zx3-s2c*VMQ!hgyL2+>+e-aam9nv&D`%eCl0082_B#%dcJOWVa2>--x27S_OGGHI%o z7}E=ZqcF2J$QIX6)ZzGxQ7=ZOn@~zvmFuVEVgLXG002rw+yxhb6K?H@Lv@NrQ4&Y7 z1kbj3?KD21P5I?XI`mF0$>0=$nD*if0vCZ+F;d6>5#r48-Z65k(V+>ly&ZH1-2C(x zqo@o>S>$jW9Cdpf4(mp<@UV4w8$lP#`S=D+5Hdpk!ZO7Q#s`Lp!jwXloPaKK5_BQ;=1Y7p+=YNtYwRny!gswzw=GTz-`iv+4q8oh( ze*pklVCxLtkQ#t)0si)9)1 zessaE<501am!U9en8)N=WGSzY0nA^$lpK@(6Xaj2O9U?lVb=TLEURJQ~GwKENQE$>! zT17iuCLg@&lmx#{GS-i7rmP0vhSQ&e$-vf#s=j-?Az_h@g%~ne{5+=Xji_k1Rm?Mj!w^^VbFUrV(Ki+Nj&9 zk9$4T_iXZYb5e_EBr~WHE`TH7Oe;1_e3TnsRYYPo3Z2agP+LOAdkb_@IM;>G z|;2xb)_c3)96N?HKDAw$E+|CENa+kHw25n}QF zBiD+85FllKu@EA-pl2ot|Ha^a5{?$JXO$E#F^iT`8j%q)aU}R@XrUsnEEBf(+AKox zf?*jI$+scItV4>7P<)V;VXygOlL$uC>#ElHdfmX_D;5mx?l!_Nw2rRRY@B$61NS;q zI!~GHTgtA z{gAfHmF&e(J}QtzD((tXTWZJe5ubQc4|grE{R8io%3Z`?%}%!z20&kZ_F3TnHKeK} z4lNOPhnv+NIF8~+rkT#H1qRc!3|87B%)#?($p^%tfO0Te6`_mf!!w^ML2rgvT>?J! z=SPp!Q}7kt9mlB0C}HwJ$c`IH_zc2ZPbOv_YQ|S5AJn5|BsX8xt`f5dTnw`R z(q;6P;S0Mrg$A|Rj$QYYbq&3dihg`>2~!i!sPWEbVD zcM8l`E(^4B)Y!l}sP8}o>aACcB4M5*{XzJlZJosj?Q*$mGZu(T|+|EgtU1unsEB= zp+@ZO*yw}6c}=rA3LK|0;C!SK2*DaUMX@x&zVN#26kvM;Iluq_yuI3IP)&OQiHb`< zN2E5FdyeD~apwfcOa`i-a=Y4Z2uv6g4>jN_0v1oWfG%%O8%2RL!feOfAXBxLx?X8l zI?T~y8yi^n0LCIPiqYi=m*&;+Zrs$s0$Y>n>6eTF71Y*Tt&?4`fOiHdf^`=Wn0EiE zZogCJ!5mK8pKW;Uk)8&OX2`UO&$+M+0I^REdYc}^t!t$UoW8zWE-;)+t%il>HsS)x z3N7YTHc|c%0}+I{grYAwvAX?{d8V`LFA}Mp!7()Re-bU|w>EV1PDZ|M!TKy_`<2w| zPvY)UX^tyeg}1f_P-KXb4sNxY`gq?eev4>d(a&64wGSPz>JJOmRJ~nKWb^<3nAV=o zdqzYH%v%iPsGI-=s^8W5*^pKhTeqyD%t=50{}|hYXVUbz$ zuja|oRVPJNccF*v+yqrCdp(GQmmoL;bHlRW+%Ck_jJRE*>`e#Cjv zSX^(SiOfqJ7E|xuxHnZv|IG;=aK6Qx6|=PbCIsZN1%cKh*&=1GejCCPs8|BKH09Y5 zq-U+AiO0LFKD6VDXReq`SPnkj1Hz8k*g`G5CBFGu*bsKSRa?LFZj~Y4TwO}MDA{JP z&N5lTSXI%qyO1k_WGs2x^p|+nv!2VmJckG`&JI5^Yhmm{uXz2-Jk?ugb(q~>%2%D- zwRA(}Ez1EM3%XE+@*rEugT>RP6B5CKG5#<9#p#l(XPa;h&v>zY)IAsp00F+s@kB>7 z<1ED8{=Lp;-X=7EDK&hALEksyDzD*Dlt!0KDpAC*s%;y4Qi{ zQF~?(Yc?SE*ZL*+s~tY_p^0ybS&NmZFZYi*c|YhxkI))?Nb?W%A)Y0h^Gk|Wmz*dH12T(VM_qNqWoohGhhG!0{|3!j=tCy zbg|#Ae&!S|+C{iJRIZQ>mFCR+>bEzKP>m&om#OPaKH-$wY2|k@ph@Z$rJ(=-P8_Vx z45r@IFygSvYvz4n4A*lWBox?}05r(LmTUQ0uu0ME{>+I4p)qGUcd}>{X8kb{+bguL zP8AT)s?Qd~?adr_FG>_u&1fq!kQz_qc?)RnE|IaN<#iN8#J#b%#Gfz!vLROGl;azh z44?;??=qmI6-N%>dP2gpKqe>b|DV^ zUbGNGk|Ec9;?^0%T>tUEDzTd<9_VHuD|n}Eup%#i(3DDCe~bVwf+cAM zt{?Lfm8O9D65>t39e1cH_(z>a#?Lq27Q7t%0C( zx{pFK)i?WZc2z>w3!)*lctyIQh&O~8c7%E3M5o)J9a)!LP$2;ET$HMfmq=*5>1T8` z=fyAF#in{&1%XYDJgROC8-0#(F$XSgK?D`GV;r_C7PIf_0D>zx+#NEFobFwh2yjWL z!Hz=&;F`hrrUBAQRPqz%zGhpioE|j#iTHaDr-FyeBh2^SzK>4p8lAb8FJSua!5$z6 zaWF(p@ekYrIEFk!<|ByFdnOLEgJMO%=MX`$ne`$bDVGTT79k)9k)k`G1NL3}!7!sc zbUCeM_-=FsjbhBO3_jof%%i4hy!T~rz_u33e&R%`O*&d@2yMJ~3g=y3HV3`8fS@Tf zF&9SP@KpTza3`D%xi2Fp)01S%F544Y-#AN<$}MPupaJVv65U_{l-=vC&!sN#EZR

    fY-3xF&Kd)m*7|N0^_%_y&=HF10oQPw&g1sAz}fB-LjNJ&m8ZSG8i8{+wN z;P=Db21jr%baK2e_kIE+=x&ez`V9q{ET^6~09RMDlb7%LvprVx{aXx?C`r0;9o82{ ziv4bEuKkI9Y%@dNU-tR)W7^$}NguTixm~0?pY&3=%iNuYEsWVn%5%0>vpLKQv#HU~^nBCpy1SHTV6ZAK>Spd_1SRjaq6y(WB&^DFs70M?kEG z>s~wyD=gy3%JEy|V(cq6*ItEX=Pvml&&7V+k*pMXmVWqrEdfYEW9GsCRCE@Z(3!YD zQNjI#vQj4=KaT+iLj((&H(GQvfe<`&wYod3#o|}mwaWBz6+r((DDfZI8$LxFWeUs$ zV@~fgqPR&fP)ik;!eA_reYDfHvt4WLW3-+LYk7o9eqbJqB_<6_3!f<%W*sm9gmj!z zP#*V%YCt&L94;8}se!o0a~|Kd>3_~6``rf^n%aV-n^on5C&9e;?MOF%z=Lnxj;7S( zsOQkpZ6J59j-`BGAZxy?uCCU}gP3)1f`vqQqwD|x0{{sB;^95N`IE$$S_JXkJ8sKP z=KcW+ToN49l%{v{z6T`Fe*rKzvMV8>OM<(tS8DR%l=^Pu!2&u#Xs8#x2p*x-<9`K3Y^a$R=R9-IqO9z zrE{~(if}X>WoAinm#3!Pdk7~q<0h2c+ab4OMQt4@{gP-sio-!WJ@fpN{qlE*Nw(?4 zlz;#L0{{RLa2frlvI}4dCJk>f)DPGd0qUQ!A|>GYxI=dSPHf83hK`{ZUwC{LF;SL>Ql z_c#|iEm#Ntxl1~Ui;In?0g)RM;e3DzCt&dPdFggSr`o;=`5^8m2cX(E7RL#skSCzr zoZ&_>GRYXE^2w-3#Zrb(@BphcwcET=sXJJEY1QWw7z-^%sye5jH2+o_Y&M=H>0Wi#0+-(D|7pbiEE2djR- z&FkI)NB@y!Uw1nQ*s)aFi!&IbB3X9PYr88^Q}5#OxCWf@Rojjs*stgiP#IaVQd*y`j^06Q+9>|`tL12#sBnCqIkX$~Pk@zEO8-I6E zEFAILgtCv)nL(dYLzhCv@g|G;WbDu^xHb}9myH?{Yyt`n87;Hw{@_?enRZ_j0)wM0 z$v)}b8xBZARGit(Nx}Z=&DjCrQBh`d{(OGdm4VLl2hvG_goj zQDc8>Ybh+})>TQ_dpG|3&eWK0Gb}6o+Enp}UoCq5KVOB$ETL;7`$XS-zqFd3c$v^Z z3%%*w2FTiRK}a68O2vya8DH+2?1h>OeOp+rEI6VqjnF=UTSG|?>l=lWw$h998Ks%| zH2c6Hp=#a{jL1)Ei^fF5DQD4|h>g6zXd6AW%jk>u zzTAdt<~8iMt5)+9NJ#;cn;dxihxbx(e-hJ_TFZP5yU9W2p#4)@#HE%g&=_!zL*Yw^ z`%NruGt=Hsr`w$lg59DWl#vliWsy08K2~a=i*$Q&#s?p% zI16uz2(OiPJ8?R2i(L#FLDX@JQZmOMjIh_AHV!X+(B@@m$4a(~g*4_b*Kp&T?@Mji zlRK<#wvO2s@Hu3i0kXg8{o2daej|K-DFATco+@C?Qr~WTetly;1~^qPu9M$Rbn$k- zDpS@gNoPk{u&f-U(QB)D3h5hVn0JBFh@^l1FB?(&x@uwA5%2VzvaMmQaW2Pwk7_U{ zgLKkX|!7qL^vn+LQ&Hf#`CsFU9A%}s~@E3G8bN7#$6togqSV?twGtS?u>%$Qp2tQ zCy${FXxS-*C(s|VK_()c2#2BQMe@P!%hU1}<7ME%Ib8!piaMBL&2N#Z=({t2?b|e| z;=v#dN<`uZ3L17uN=6&mepWC2NwBjIW=?j#d#?jJFh}&*=BJ4Vt#hkkQafSGRH>A{ zPr7jSUPcJT0`CcK%>UhUy*IC!VhvOJlPB`G?6C#sh~iqZJ9U<0p_Dt@h3MNO%j7|> z&NE;3eatgyP#8<7S=2xnDO3qW^uEk#;%KZqwGNbgv)8%qrB++RWgs15)Q?zKF)KR# z_s9bF6NEI{3zA;fZzsoKfh2pUTPM3((!dJ}(-{o~?R`#GVF{;)H@A%zE?66`&Rioo zePA?}W$3Ps+6o`l3}K@^kc5>9)(~veMV@N`lL4p`-Wuxqj}OdP&uNXvQ873AcTwTW z^PnSco7;zA^iHyN28}2BHoMf(SCYFE`A#te)RO7XSw^UmMxhXZT3N0A>&r0>Llxyyu{&SFY1Eg8}z4#Iwcp1sTzW#>| z`b})S>pNmSJCYqbTGVCECjJ?E7cy>Pw16WvQNBbiTVmogMep?Ha>%y_6NHtYdjqc< zHU#szfw>ye%HAprU^%h=UL}|hkn5t}o!)@tzaPLKxn;fm;v{Wlo-Zo@37(dUN6eBR zf(bcV{-lkC>Ebq4!)8aKfq#(fimAMqFU+8qrrL*XAGl?XwLV``0EWs_BP(TZK*mQ( zOY6S;bIzYf?m|fqrdY_-(jM_G1e^&N{zmP8dr>aKgz^V;oW$(*2|K5mgyB3THf(Hd z#wi;PF8XcKU8JwT-e|UWdJEo?V^4bcFeGHNv4YT^?5i0I31i*PAOzBs04O~Z_^{QM z`~PkPTO|H0?<8B!O!HCdNerO9)gw-=#vp%DU)n*#*heTu>J@op; z#AUtvz-h+tp*C$+#ic#@oMgoT*VY766;1x)V8O>Ilo{gu5#-wR3eI~IRvmf{s&?nT z88kR?g&KM&(Q0V)$KAZ-sCS@2?fnjnqZ~}?W7ZHn6TtVK`LT!TmBPt|FDW9%q~hy( z+}!9-W$qj66Pku&*GMTtsyK^I7|?yo?)%5S%PWw`-Q}xM!DksrVM$KTDLrJ zQUC;UCMb-HUnOQ3)jC6MeMUhfHr2mc@E_|Tt-~Ij8h&s2CY5`jqq6glrNcqingnwo zmDpE^=N=ARO32ZgtG!)KOV~sSo#ZS(Q*~tf*aF(P{jzN4Sha~>falC`pvV&`zok)L z_9+5S*?DgblttS#2&r`1#eHueP!785=bs$?uSJc5&B3^%S%8;rRHTG z{M)|7v}L#gr;)2IL84qpA&(4+x2E{$RN~lW&Cv(XUXJ_MD_wxZa!z-J4d~|sc6`D6 zv{n(e?E^|QBp(%(0nAyJTfikOaiprXLdnMr&6x)GcGxep;OsTxaFf{EOmWNlxB1CS z#V~I~g>_przg!5iVV|ImI0vkPI0zzBqVR00yarKzmAP;`&n64EOcWKLghmGH+yTpZ z+JsYN4GL{HVWja$-si*YO5RK7Wd^iwjwKOMJ996oguKe;w^rF-9^?^O1(Iejv!>xQ^ zpEOFE4hQT6Gs=9s~ zz%cdPq0n8gzjhVmm=K`kx+R3w+?Okmy*Hc2W$46UbU_C>4_a2Aa~8hVvH2PIk{1$y z6qBb_SZ;EFIAC%__!lzLu4b1WB&k&1`(zBrslpi=+O&qN)NDTMBLv--HcPUNjh5z) z-bb}Sv)uFA>*+ik9gRvwe`;=gB-^nKzGK%JpE2x_2ykw8t*c{z>Bu4)VtI(hR5Ejq zxzVZ^7wv4&6*3G?h^}7`mEP~UPgjA!San4EHC))qKn=DY)rJ|#U30b* z07NP2XLX9JU4asF*wTGokx*bKm;TvilKANt>L6%C?o}!~Cp}Sx^{*8&-0W zeaSfNnr~H*4nx?tUcu1?4v^YM59>*bM6N0Up6Nm}unl0z`i%T^mk*pns`^=|i1F;% zQLg84>oT3FjrTEpSqv*5F>-x4x?huD%irRN)Z2+Ve^hrNp_Uk5hP0Q3XRB5Zy9WLN zb+?3ssbEu5%TJ{rL2n>{o{pDwc%`a+y%k_$6tMf#pLnDz(`0y>ploqO5Rk%2uuB3Q zvp(s^8fIT?#o8e)sIffXZSoG{q{(haZLMibjUjpTj6?7bO@p|G8_fq<0GL4C>Nzi~ zi`_OiyrN&^0f5qmH+%Oc4VXy57`XQ;wakHQ7lBCQD?pODc|?cL{eroiC*X2x<90gJ zWTd=k;@%u^M(ef%Hen3rxpf7k;()F7;WkuUU#BzrqZH7_|8n9sNNKc#Tnk4J;5S#sWQ_h?3&_UVHvxFTS#&rU2HEDw!;P!`*bZU= z7&8Ow;L*Xz5Xf=#!=J&3Em^<}A@?Cp z;vjTZH<#IT_X37h$DFAcrjjy~1Bbi7NYZM<7M(4%YDEcb%!8FKug_iA(fXO$SItn13eo8jG~p8LpkFTvmz(Et zE90yEd7@yoVV=GZs6xrNg1#wRbj3Mh63}J`BoORSWiY^m_`f?zpc^R>so#s+;JbPa z?^so*75G-=;lVukJj$Kco;uCb@4C*%M}O0-mzHB%y6oY{jWvY51z26Xwl=&L?(Qzd zi@UqKLveSv;!bgQcXucSin}`$hvIHUi~Xy6?{ofp&;9QA@vJ8^$qZ}F@g^gAlQ~9W zz+^sS0+_;i_e*BRNb|-h+q8dAtjsZJege0ff)l{Gt9T@A9d@k0?NvigLE6N}dL!u~ zJ`Y|UBOQn!G+y4->A~DT$D~g(2FLGma8x5(cJH+3^T1$`cpPo^Z?yHa9CXvW;J86u zvj8vc%ldc|bm(Yclkf!N(LfoIgfv65_jE(nz3T@1J>n5| zJ_FwX03b7{vDwMI|5-%Zd_u2#KqbTSp&6Qj#V*C#N@byCRr`9C13uKH*Fx zJyYnGzU^|GeG0>g?)^ZF+7+3^iC1x}5PT-p$R+rc!b3Ty3Ef|PRhl(~!-q1|Xd02` z91>Nf1X|iUfyTY)EE-s53`u%Qy0IFoOQh`AG00J%M-=O^k z9k`w)*lTkfDrLuw9K?8g2tXhodf_ir9s<|^eTjkPh*v;aC<+uTL*2A`U>D#727W}I zaGN6l(b-NR-c8LMJkuN*RL=`vFiedMr10D^LxK6y*_RaC5HmMpHjT@(xdd=vV2*BCRss_x9{282Z6!y;)e3QS}D64>ts8xcN+o zh{9DNRH4o+LX`RI(Cy}WIGKANY|J#y1Q_A^!k`k5!AV9jUywss=00*4QT*^=4n#?G z_l*eMUn-V=rv(gy`Yxzo;Y?gaNhRzjX5(6&PiMOqHfKyzreYYzg|6; zqio-rslQH=s+bb7Z%lxsRMyRT4G0oJYg%^8kt(%%-L6Ae@ zA8Ve)GXLUzSZy9UgR0weefn2dy!#Ra_V%Tq?nm3dI*O8g0W}u4CURHVW zM!Pa42as(Ra`vB_CyB!ZKMJ~R;wRDM!rf#JNx{63elj-fGUh~6pcKOQFDmZR@o)XQ z**kwIbK-#e?y^1dqFGr4R>m=Vo%=J3KMFkJzVX3e}EY5kjGdn5hsOZ!Wy7p~jrbf_`q z?`~Ap-i}f7?3EYOIiH5_a8$h@nN`(=KlEKHyJ@0;wavz@WoPN(ez}q44z{!8yPiwV z(;I?jSypHXuprk+)WMG4$cEfWX_w`v77BLV+P`dW%W(%UovlA3NVEdHOA_Cr5Ii&a?PgId&o-TK`n? zDBWaH8h*UDM@Eo6;EX6a0(DVWu*tHh{TQgRW>UTpwIJ~GeC?#iwLWXi^=b2rxlksO zgLg%->aaE(mTK7@_3QoG0{lS)dTohT$dqv8xpi}F3|@Dj4QVr0ase{4hD(lgj-vSQ zGLFKxpskM32b63=mXLI<&aVvr~?!z|lTW4UaqKtp<-D z3oCBTr-fRt8$8|ax#;oh=%et%qWN6E*6ZOtNk%XC3`W)?f?!`?GtMiWHokR?M67r8 z`wlj9r!|PBB$MQIDsnmw)ml9ADiw$kgdYLGy>9&)E4PWHI?I23bFtX>DLAF7NX9Us ztr1QWJw!S%*WvV-8)X;wkV1SFu`q??lPFP7u&TsxMfye;hJ)Ntd5KoNYfUT~AqUVN z)!I`e;sgrR@kj&O$M395m|D)l=XR_)EQx1)`Nu~yaTh}1`BQ(pt1gM=2+Sqi#w54& znR<&ftEeV_a+ch)!^7zdTUV=a{}tPCFp)RJ??7wKO@) z);tcY&DpzL-V;hSYCaf{Mi#khi+Ja zS-Coh=XYeK9ArC^S_1!LdYyQ-VuTs?-VCJ*K6A|C;ekouyZIYOEvDNdderW*lA<2} z3=Femz~ahKeyuEMKjtDA%O3@4zTxx3UD7Nb%u7T)58C_Q zzi|-{9AY{(o8$1)47!A7RNzb~25XapeUN`^hT$7iGkB&v@`@gZNxdrzJ5<)1(=J^) z3`%JiK+ETn=13z_t*D029%?OQuq%T>be2q7FA`9^KXz+|cX&@H)Dnx(~5*@5F%+>NZ zX-}5ikxNd{lB?xD_YHeqv5ce$Hewscpy|#1@Y>fquzD-VVxTDrHYciPln*!FXcdQn zqh694CeU!&H7d(?_C;BGKK5%LxrBS?<6aFso)Z#^p&vziG<$<8r3y0EQFb=7^)NWC zs4MvA)2#bfAE~dO`nU0czgpLy?%SA>`o@)NViLRR&6*x|KNkPN)wQw%U`QSes2e=1=aoGDDi4y;ZxfJlrIog8W zuxMEaa&&@Ts{kl@g3RE&IbXi|xC|n~SO_8C19eg3r`ONj!2;NY#DSi;NRRqruP_5h z7alJ4mtPi;Eu*Au6?IW&iDshDsGvWjdpoH$7kwFovt70p%EzqJw%}f)Q4kI%Yc=}4 zt_&s2!AW?}+DMfELu9OHZWBK+ zn-Q$HuJ(New(V7EFRvt^V4fcJSkTh zc!B#&n;iH-R}W=&e=$(9FB&{(bv{+K+(f^EkcN@q@tbGw@4eFt;(K@V=TvD;`UqYp zuU5Jy!!+ilazEcERoDLSEklNKIW6hwp_`|I8|c#HJLTfYkl9zehayBM5npS^dc_U5 zGUir4^sVf+)g^kn=`Lj`CbOGh*ARN_*ib90h;P`wg!yJH4vBqk>ySl)1?>;=U`LT` zr%K@At3DCfYw-X^IR511t#zTpOb+cZ7l2P=oct>PnWD1_x_mAV@;c$Ruqf(gXes)F z|0l_a%yFSagy2TIj|4+;Ryh;IRMz zU>TT8Jz3cO4>5(X@A)SNVrz)eJwhT6C}jZvq~5-D0CDC#n|Gi%44WB#3ANZFYXLJb zgbjcYfS6BR9o)zPRx}zr5$Z0Vc1sh;$n9~;@fXjOK z`+Iq9lwhsb2k6nrNK(fTLK|*OB0csIBob8rI@HB14;VtN+kgfIApbX3ZoyB?1wy<9 zpa%U2%%wp{{FiJ%kfQ{Mnj_Rhr|`umD*+&|ssTiZ^#A~&5a1eoWk3@EfK)OJW&=^u zkpcM6fGyw&0Qe(-j_EX?|3Nl@hw~fuFY{AMQc1#`6NT`zHMN|$e$R1JfocSK1UZ%9 zI39872SFIV(#j9C06y506_SV6*e|UIXFuXLuy;a@{r2JH6t2&`dV<(GPT8ww2Z!Cg zgc-fwVh)8EA>t~%(1yEbve>}wQ#T^F^Ty+-N>>G zqc681=pD2w@T_B$rU$l^Pxg{igGzrZ)Yxp>mf5+2K9a{kRz$H)ulUCQ;gj) zMnaE#9_yZZ+P?E^>(GTd*y#*W&oA6(iCJ39FH7O|0OXf zrNA1Onj?i(dA(}oS8=^xZ^=n>wU*nj&nhC9M$`KMmOph52devz|E~ML<{p2lzq~!@ z<-rX){fBOixvUC-D%ycI=pua_skE6a^IhQVSQMT`}JzPXc4h>tsVy55~ae9 z(ndk}uFcR0_j516SY8itthMZ(zalp+f7DSO8rR-R$ov~`;D&6`e8A_&w^)8HBtYxz zyHIQ&d!Q{s=a0HzQGA5!+DGo{F#I;uP~eg|FWemXsm4QEsUDb+^|(0!n0ZCe0aW}s%VMuQ`GO`#0-u@(QEojoUH^ap$L?@dI^BJ^yOE}j4-E? zCh`+Orw%bF%;w?yD7YsFpUe7y4#OnWpC1m}x-RU;HHpg`wX1&nNL7K(;;uOfesV3M zx@5l~OK#hdJ%7W`Zb{O~=?)oLHf(^jIA!tn0&rQ1&YCd{*U32387oVzU2c7(XH?-J59Zs_Hv)?RQPkO8 z^R?%P6MI|KX)fxQn;ldts8XAuJA8O62jhB5KJ)PA(7yI6Qms9x+H zS$v?Q7I{_8jAPsJ_ihUAc1ZJKUcJ z;wGu07$aH_?Ir$pt8)wJZYPYr{pRkza`xr(he_m5RY)C|&YT1SmxhWW7&X^5=D(EI zChkA5EV{)UD?Cfn{a|#qd4Xt0V^=%|`KDx`Bp4l(G-pot!Key-z`m_D?=0b1BD1-$CkfT~I><8p@A8kVy_nw|1X#Gp5a6el~ zRsz0`koywU&w~2Z7U5jx>IVP6J5Aso9lI}iMs z?@t6L4c8Imdxzi?005sN!EO%tlL-_oSF-5=gbD&+A_T4YMy0@pZCH?}g9Z>zO)L+q z2B@OJe+472e=mHi!(lH^8tvFOPJPx^*MxW7&D3_=pdImv_>K1@Sf)q3tXAP!2Q*t70VY68cnd@y7qep3d6!aF;Ne z)O9AA@`RK!8S;Y$N@?TkPS?a!GH=L`^j<`m zzs{J@_>Xw%PL5Na*Gg1*K~%Qr`64YAep3Ifafn!F(4L07&HFl<3kQr2TUc`k7KxLM zjosGK!e7QLAZad2^-%Gfa8B>*G#ir+d%W`0F5`9I#ysS^NasCX=Nm}J2ETQ7$3pM= zYO0@`*XyFYJ+dLyp%NOT@2*V5r z6=kKB&4f8?`JEE51Y8W6^imBmf)-gXyMD#YJiK~9@q~NUzN3r8CndLK--k=@libyc zFNJP)_%x*044X@4M^xh;SbNfvb`&P>BWu3AjF+cOqN3O6lJYyvWEJ7$H#Z$XpJcHg zaY51$TOEeDV-^kGE(pOr>RSg{i9!+MYVKO_WuM0-F;5rdG5{@;-LPn^I3BOJ?Q~q)RD26>6;Z=duF7)s;adsseLxfxLVr z_T8)dqrOeoJX{v&iZ9krd4;2*ffcs{;M2_eVA?~g0|_2fJ><(09%eGtceJDF=l!eZ zT!$hz#%uVNEvL`54v>U?9eVp~an9kjp}UevH~2cxc+z|T+x|0}L9I7C@jjKCp&!xn z3o#MQP#}+ud^iydvJaIfy+}Q%*8l(@69m!3T=ze6Lx`ig8J_%;_@4m%or9d*@OKFy z=AUbA;Arr$uIQdW8nhi8DsQ?>Ad`ClfSC~vUno&Tlzfm#UV<%a1Xx*%%>;n_$Z-^O zL-NWLAcO*q%J%z31y2ZVVK3PzV0|Q!&Hj{0Xb1qXoz*Tp0Dyz&9iSNWbZ7s5y8n2f z{!jn;px`D1LZCdL_y7R-JsSWWYh<#1+ zbSi3Y1Tge&9d@mM0R1`{$$o(pDkB(kN^}6^xVMxK)cO??LdhceX}TjoNcT-$ z!E)R;29iFRNeF;M+6n**0{vp6a3;@Dj8H&JOS4=l07CKq$jiV1^!{Qz+2hFsYXyIL3pw}RTHmxSb`S5%W!c-f-cFzs72 zy@1b{Ng@5`qFOv=7=nbQue$ZfM6n+QEYt#dG@8 za;9Xf;8Q>1m=a2oe7ojjItWD%W0$&@dj!fQ()>n1!?bZI zk)T7OoXtg!_*P)?t_|b6|K_x${7d#XL0DbDVlZCGRo)V5T_S#i7s~woFq5wv(JvM~ z`SOB!_E=U@PC+i#0Coa6`uKp4tSYIg8ioUfF9AIL4E**~bFy)*tlWe*fvcZ6cDir7 z-wEOAl?6ZeFfG#;-huD+6X}`)aux==pt@9!;$++|;GbmqDd_9`@R#}I=Nzl_mGixD zr#!sBN*IJ{i`z3(RLvSEC1s^GSnhOxIY5x#%{2OsO(JIe!S#Hsn=!z@#B=KNyxmH) zUp{=<29RSCGi*Bh<|u7j2)@36S%wMC7HcMU!JFxI$Uyc|8K+AiRf^vPtf2i!1Fhf} zB^U%MLqgxEyWuE?FIbhNJoJ?%jd~L-i+a{Eed7WJX^MNJUG^g5yi$gE5E`$bG3|%o z$0QR(_GfbKy++0+L4wsuW{)x$S@a@W-qeC-C%&Rq7T&%SS{rE!xE&9AG#R6`%eAAH zyAWqD$By5t@CuEH(#h2U9RpB5I`OrrZ|&Y3!hc?i9={gTTLhx%XE0Y%+w(1XEh9_t z%CEliwbZab8Xz~3sFNSs{ESKgdgyyj;xU~Iv{zI)6dOz&^>3(Mat@_dEjmKI+{Rn2 zbq){06kSwNplyT3Nw65g)>NJ)TKXMKH9sd)ih0mt`bB7z2J+vSaSgRqU z?kpa8r922yy=?$2g&x#lR5;I*5&*~>4gmN0QyS8Wdq{~Mm3SkaS@>XcRio*2&_)pk z_gc!l2@T0&O57XEw7@j8E+Hm9;jx!i-hUgWWtWm_G5HvJ+W>J;^EvZ!UvAUhV|L6X z(kKfXII+49fu8e&L^M4`G*-BHdvjS*Je|_iTMUj%9^st(ZMJQH347D!<^Aj#ppqH1 zyBj6tue9FlTI1kHTHd~OUv{a)!2C75blZ>K046t-R~%`x_G*AQ+K(9{V=4;PICbunNRi_<*@GACLY!vm zrB^MT57MJ#N*jO$SLomSXL!_Q7RgX$c*F1W=>Rq5F+`%LbDaCEc%8xfhJ}bLBwhqu zE6{^9VANJln4VTf?W;DdRc(_L0VGBs{7^vn$^8d@e;#x9 z#r$|R`$=$Pturm62SCnaP#Y2Cc7gR|`k6{7{A_mcvbzi4TQ84KWVl*L%Tx&j-dYGJ z^i-eTZw!tZ*M~M10f@H&0Kh#6lW4L3(xztd0D!wc;sObn184#`0(^!3q`-X;Pyo(C zfRj)VFc_eD#=oW!kY@sH&)GbJ<+t|;TfV%2tMj1|S^CxnDmjtEwiYskn<{D;6Z)%C zf8$g-3E-^=oEE>;corY3Htx1b8IlAQjKS^9cj2NmyCmhS-!Az$JdJc54;3YjROmK- zG>%UxnrOiMa-P&zbHGBGPow%*6^h%l3s-Jm0eH3F3fs%UF~c`k^6UW_7i4e@(|h}c zlv@~>fOvWzRF4c9%eXM8olr(7XnPsCesP#xeqY$D{R$N>xh1OrK4{a+>jw@5lY zd?f!8Q0gz~|J*VM2@cx1@Ayv$k+(xe8zN5MPE5zM{tJKa&gh4zY#wyocT|H2Op5{N z)Dia7_71Lgc!NmgUDE(;7(qlIcbeej?>=xlWawV=@)lr_+DeGzF18=_4I~H*!xI&; z&zxw@Zc7SFZmuIv2t>@-3zHOR+);4WueY8ypzNdLb^ux=J(XKg>g!3bkhc2mi%l+b z?pCK9v0;5N*P2xB_t&X>BZ)Rh8k@Mc7SHl5L%30g&n}HMt3Gy|&#QL$w85>8+sF5f zI3!8Iz+ZfGJ;-eU0N@RT!o>eXq3o~04Vm~ang0#Uzautre^7uu;Bu?O_Z_M1e`c*E z^aD4Kx__n6<4dO6arzP5kaXbsvnRK*;M7KK<*Bq3;W44ytth>92>9I0#cunot*hCK zC1#V&xl!03QB{P0-gS@10e{uKyXi9dL0)Gppm@0^Kgm~Hn_y;E-t zpRNX%c#Oz1b62M!!KhBlz`|)40_N9kifz!E>8Nm~tYys~a{d=P2Z+6cQ~hn4A)?d7 zXO}E!_^-AAY6OVdS5lcCZy%1)(eyH6ypEBlF6j(^D#FRC4~LcH4~O_sYDEnaxJ^uf z`;wu`56cW}1;9b4ZciBAIejs8zdVMbYjWLDi6m~rj1ZeN#K&<%7#Mg0eMH}HW%=aFB0jyo5fr^=K%%{XnGba6+i6t^PWkW;2NdSzy z+Vp{V*uKc?2_M7I!M7H5VMaF#pIF{0)&S5><{L~bp45qlK@QXd-bby4S*D8JLX5v) z)E6$mxVe~oam3#OO7by6c_O<^FH?|?5j}hUg0$L;uxc^14?tdbmOQuLG~0(QxnMzW zbtrprO7BBmt|uxG=j8)^b@-DKCayrA0n?X`tvFs1`2-!8xN(c1WrlA5+CJ00m+xB)X41PfkG0&SGe2LBAR> zU^8U@ZdUOdFHgyFErVfU=VwvIk>M9(n&!ImoR-}M#n4>Uz7c;Mv~69x(&I0g8A0Q; z!z!$*)OQ2P9Jargp(YV>n!8?gYN;@2(zn$IvJC{9kF>~W90i!)fOVu^Fy)l=h)qng zYc&?GI!?0P%g(1ONctid^2KWhrQJ2~629VDg#t8sPR5dHA0AbpBst51J-2q@K9iy{ zJ3Kv9yG(CL!jftKf;K}7ZDn9;U8kg&s>ZeD#{KT1M;CK^Og_g z{1%5jcN7+&oo&dcLvi^sv6&U^b*h%XhVS3J4mj2;noRn&|H!m43M~f<4>2^?OnT(d zk0?yowof!uZ5)=+Ux0=s9H93Sr@dM(MFn`b?(9RIA8)n=%4x9Lco%b*6KQb_S3n@2 zzxWDS^nM%B-ZR6tkf5J$nA3faR@%!E>A{sHjI$UBsDnsg?Ogd0F1n-7)#KEi>~P8H z2^h*PRV|h3MJ>*dm4_SojEO|CERbe`yVX~=XxXL_CQ=>b6Rh1(B@C96#QQKfl`Frh zv`$>(NGI>Z6h^(r`z}FF(({^S66W~L0~6Vpp8#xohR35-!ttwn8HPc{`8pVNZ!|^M zr9{((h-&1-;!E^<zhBs(n`m^;2MW z!nvv+<^EZ=1%sshr|W`xu1Kf<`Gw^=ShRXaGDvl+Nyze?(sIzz#WUpCg{a8JT1L=h z-(;#9?rj|2&d9blWTm31rWFnim{24yP^8f);k2M%Od2RcYmg6M0}+6%sJ~R0V$n8B z47zQ$tcnD)xl&Z2!M?F&wdE{PGit)1My?32V{i4yoNhZXF?qzQ6eOqV#xWU~5A31H)A+C&p20BY zGIkP&^hCrJWgh1hVT=5R7|)BgeIcG}Dd?WBcSPgeq19og@nf@|NgKr>Q<#J`p?V?- z1wjJf8D{@vT|)i6lDDMq&WnYuONz|~PulpT*P`AS_Pru;H9&R@>qRnE1HF)nGOh=I z=vo-NIrwu2n`W>+D;u~iJCeV)KVG1OHKE90HwE^B*>0Xl2K+g)P3y&HO-+9+(<)SQ?CEfCukrHR9MSf@ln9=Bud{@{ z7sU$ALib5h7^RygxcO%Az?c+i#plfm`jF_L2(5+j+O3P(OhT56or2mksJa-z%+A~W zlD-yYx*eG8Z|J}%qU{xX`^t4qlHx_`eJ=eW2ApPMV>-YZXGSB$U1WLAF_z5kan z5;RPL14-RC3%E~z-uK;<^lJ1blzd}`@`2q+E;m&g?3^0ib**`aO@UwL+n63Ob!)ei z_~lTQL3L4#{Aj9Wd@TMY)z3tb=JTKLoO{U%`15_{L_%QP0whEfyO?E!{!0;s=tp_& zLlq~bj!lbxs2LRW!;m-pY{#H8Xv`I~yBN*EQDefzegNi-$c32e#%dty%ESGP_z!Gq)|Y{mtP^ozoNB~F94kIE}p&2d%!HD?lrY@;x@&UPdcEo1hbhYAvK57L6?JROQa3^gvh_p`-OR3q zm-BOPM#+i5C&NX7SBdtGp5PW6t9x+PIHuvl6=BehNTFWXNG9b5zJoaWJn-?yo7{c& zkn92<8n+8cqO;v8luW}uV4}037^ZMOj|`u7^e!0%H-FAXF2Q;Hp#)Ib%9p#d3Zh;_ z`CP2@W~+scTv2JueX4FDeNy3y`5_Y^bJQjz+zX;)I>MPcN0Wb1vcEame=eB@k`;v! z{1Fo@hrSdl1Cjg(!_|e!Otf^RD!J$w0+(p$2kHD4>IQqg8#}M$Akm+d0Dy18IelFq0ExFMY6!74|=fBBPy|MlIj^t|jrN zI`%7fir_XwAPPol8bgWB;K{bfEN7A=R8a~AqyOy7qnk6LFy6bgrnidi!H>6q{kFT; z*%wO$Qk)yWRDuE@m4%c>&^A$hB?Q3;|1e>i5vd6 z!KOBmxl7`k)5-D(bea2=&FhJyRetq{#WYi8hr35bO@s4FKltRL>D9$t*zi6$r=!bl zUOi>6)_MnPd70Vup}e0rXKM~xa+Z!S1WZUu5`0Qg4!fm+nOPp8-*EVVvqqOKra7^A z%cz95w>oBOTnXuRP2>CG^T~idWGbs+NS3abmfX;X%!Hq*s4pht?7(TmX;rYbSJE>s z4Y~Q$wz=WOeg?&RP|nz(mO3r^yFh;qSk}3}h;)YoF0Ij6tAN>EjSlY`4i}fNLewkd z60DeYdfjZ1fv9N2i(4AZgpKei;K%Vt&(40&;dF73aSpHbbQQ$+1PgP$!em&fYQk=3 z;gq&I7}@^gpGJ1Ei`)7hR%F)wZ*Ch0xp4I}gW$uNW#HjCbe;|)@Jz=zBo3^|cqu!# zrkIlgldZzoA8)~QTCZQol|NgFF1Z7{p@LW)%U|OZgVcSzFS#kTin4>Cf{;1&*aD7@P$DIxQtipwaE zbDKu#`9QB{(jEZ{pwy;0aazZ7BWYgy0=^)|lR*WO{)do5Bw08^+-S5_ZPRtH>IL|m zS5!GmM{1^oCMVjf<1kZU)&re(EsY}Kocy&nOK)NdhqsO~HII)u-q|rCpJt?yg~ZiE zUE!(VRCWklI3gT&JEOt1$L=?iobj-RiX^8tdyG(q{1yiu4=7{KCM*PK`LMR_*NkkB z6#X~#b3i+C)Vax}Lv>ITueD1N{NN>j$(0M0#|1YdPWWiGLjSpm`e|mavXm5#7#yJ& z&H<+LS4D+}m01`M>iGJ0i9tWYm9AN69Q7y{EkOWY@AMxl88Cj~T$5_u|DPn`UP@!5 z{H5}|+gM*g5uj}>BN)*mQ0X@;r-5gKuW3L4*b1OEXaRuV1S)tvkDm`E1aO`NKuO1B zuA^K*ezNSQ5XpY@(v|hB?2Y-URI~-}nLUDKKHXnlPaC7oG*b8l1gzYAj z=En1!EzHIRP@G{zOvBRZnsh{Ymo?xq*?Q6Nej(z}w~EDZ`ZdhhCW3X|x502KP)N}m zuE2K3#v`1mTre0Vtm+5ll-8qDdIK}P!jMn46l*C{oG;r!3}HkaM?i{U`%Vpj$Er;0 z61%|4kHq4Wf>svYgkuy%^dMjS8kw3uuv)H&#coD(a9o7fUqS1}`L z`pQYODw`QCWkxu>m4e{NLE71W`9bD=v+ND>ra+8%?dY--VHu!`fa?f>*@CHI_cQ=t zpgsMax%$x#@$hGONmatKLn7eFix@&wd@4n-#>l5y)M%YJ%Gj0j$C&5oZtQP`&9zgP zuGPl+x_mv6pA5*W&Or8_9)fewn{tgQGoK+BX!IL!sLi2=8Eu)oXxR`f87ZeE(IpzM z^GrFtGx4ipAjC$RJ)zf#yOO5_7oyDK&SL-rIWn^-~|tz+Ey!5ztO z^o%&+oa{ozo8*~*1qlOmF_8**=f}G@=VY`D(9#j$9hhqq{po*@o_|J-UI1eLUs2YY z?SHa30f2P?L@``Gq!KBKWe)%|z!Ol9Q0{0ZANQdAYxK7$((l6`B>J?>LCyM~s4M%( z!^C9m;T?hM>W8DsWU?_dL1VhH<_^uHKc2>Ulr0mnw&B18F$i~ODOuMq4p{ZBzZH!UWNpKjXB zXfiKVScF+bRW-cGUJ>*x3faA;Vs47cB$Rs}->~zVqzlrv%RQZ>`MFbw54ci>Y3ruN zGg~bnUG;#UO?uQPcWLiYE|@xdzI*j9lV!pV#V@z}oa08Q=G@L5QFmi!6G`Su)(A~6 z#5^b*yu?7^Uh5${cIyV;8~*ZKE>^cD5}CaM|9CF-ozS^hV|hOabOOozqtX!y-lgOHY|d+lc;lgRq3+@Iv_httnWR1yl{awqACXL0dx}3lj?UCD&_XCIa6VbQ zQDTlPzSPcIw7t&Hm+yok0?>AMt>dGmtDNeC##H+K12RJ;vsFG!SqsXyI6B^?VydmT%C?{BQClR7w@(`89@z6lB!$K3^^7#m5D%z_sDcDmw` z$OT>sVpmYYnYQ8Qf3vH<=@s~&MX&$rkJRb--|7+&$p9YqCx@z zVNoMu&s19lwgini{oX+)3eg?a75Snkn5((a5f+u*=G4u zH7e09zHa(=NlIC$bg{#QkvoBSAowWb)Ej$-LKOQ7^B0)Sn5YT#J5=I6W=-OtIhngu z>j&1&BQb0!;}G4SLgh?CN3fTH7zy=oAKQPT`n`9U4~y+g_YkCAatQYjY8SPIAs}G- zkhq#`>&a*LKut4rYA3sWMdg82k86EWduP5~hEfoe5Wm^bp?wn>dUg9qa%^^VO(OJb z#|GxzyQUhyBq()H?McODd{q2z z3qDD=_H5wOGr3U0aqxzbK3Q=Lqc`}ORis~oEk#^2cr_eOF@!%YLOAsq=~0NZH$UcN zRq0K%djXfLZG#XlHg>Bh+yUMVf!xpK^E{9YWO!f5pN$?k+92yJ#B6u$J%K0UiOA2p) zD7?jAd%7H7F1n~YxoG4hu^X$jVR`8}T3sn_XTh~QL`8r7%7nM3cKv+h*YpMt-}5OL zPqH^R0#D46{MO1QVJF!wF7(H6{lv*-4q>EQE?Hpa>sz}nes{XoT9YbS0wZYuW8=3W zD}og$g}Y3f;0VSQp8c+`fS?73sxm2R5(qN7He&V3cw{N;8!KKDr_n43iiYKI<=*mVi03tMh0nGRK+UG>%lY~{7=pDfM?2R zyxJn|&zn8gd^EY0HQ4kWkSF8{758y-;6}}`;&^WNW)ALd1YRlvbkv2A=5mp}lxdWP zgoKJ3FFgTe&ejt3k*E9F-qGqo|GE#hr;+^iVSYH$00^%tR^Xw~wo+rK-5h-?AqtF=D4SL7p zclBU<+(4c_OwX+p;d_$7d^UJeP$Q`T)>!=-Wz$H>PR&SsJZL(bvoo*Y(a*c;D)v-# zsBa;+AX<>kiEAb?Lbi!_5?0MgvOk0fn^gs0ypeMn;TZOcXaxGk4y7`_(P@v63Qy^4 zLFPRavLe9kLeaN6KD}3_g(*YwozE1Ugn)6)C#`W9CuFI+@h&p7^nI|F4b6*(DADJI z9&;+FRF|lPl$2eIjp5*#6A^9l;$L>7o?EEYS+$%(sG9YJ{Pty;QgDZsYf{qfq2$MG z3WI?$d7(N*Jt>R6nB0Gz&Faq#r+q0fyRIV znl-g9NzII4jT^F{5C3%G+wB(y*rHs=>G0cPa+IMRxe#E%n~n^%Z5J z0A2?uh3PRHqSjtx2B+b*O3mlw3NTIw&m^)Je;t|>P4>7MCj~_&g@l)&JZN=7D!?_*MAYC z|B&zhk<^raAw*bERAy!iG*h5r$7m*D@}01Z2CJtKz^@&7DqxA?KRnIZF7J^2^4sCk zVwe>EI1K_tmz$Y;nl84H9Xy&Ox7SZ$fY&NV*eX(o_y-@9kJrbK4#^)k8;Jr+Lqb0c z-a_Uj)O~}8`=&#SU%f^3;pb%{e#x0^7HtW1{5n2vx5xft=!4V`xXvs09(G|7Z!i_GSOmOu zAz_~r8Yp}-xft&pH(4*{#nMVMg}`;JCbK!2ue5doDEhCAXBWOn?g(30!j1b&8#0LL zex7`C_zrSV$ig4zWJ*MsrFp;&4??yh#EaVN;u}!}A>6LF$}*-c83mXrCpAwO_zA65 z^bi8`;1czjw*1p^jBiKv@F~G)v_B?uxl z?dwPw#-6G9sm0HCx{RfqO0{(b1d(3wMBz+diF_fQzy3Z^s{RoZjOzbNogiS)ew~MZ zXk=;ptNZ+KxClA^ah?Df^GT=$K=!x*=`y3ni$YoWw$L`Wm1C?GI!V6%%1H`j2J}8T z5I~#3Yr7^+B$Uzh!8tml4tDm`B~N>>(vuhN%{}YJbl$z3e@%c0?Lkc`Ce<9-Q6Y;E zcH5uWg65wo*YG&a_2wrDm3Ws>FG%lh=qDhEPBeaR|55WP(uaTyh8@$Ih+if40RPPo zz3qywS&KJ7*+`0Y)qMUFwj>|!cv89C6b^j`#poOz05tyfe9*h$XKmmf4`j5(;tua(Z?4n z)R=FGhFfilVMe@7U34NiA-2HV;Da;5oD>pAsG^cPf|jxfxzQPS;LP$PM8a9g-KL2l z&V&jcZP&Ke%C5J()EuAhPe0$z`A%B>Y@>4`is8BA7AuMy($gT84}$%2vRq{{OvY+~ zq%ECvPh9O2L6I7!A`GGAK-r=un__+Cshx`_9yd(hk^UHNN8nOKjXdGjqpTcW;yxG zb<#G_7~+x8w?{97*Ykd=FM8neZJ&(H=7+vQ$fF*JXjf))LrjH0B%7nM>SqvEno61z zB(VscSGRwy8WyghDy}xx%htuT5C{p{T1w@W*?#k#s6EpBwvUlbth36qQ_APL)8Ffl zX!zCe5Odwxr2ERB>xw~{hna8*^Zi^>qTh8Rm@+ukADP5`Hg`f*K{+q2)PWsQ1>_XPt|JY5eD2U&n}@uhC48TJ7JbQPodvv5}_1Xri+5Su(~ zc=^M=(oFMyORzBy@^qGILlMQ!9(T@ijEKkw#;!76qUTEW4XKEI`NmHuu6Yr!+GZCM zylAAYh30LcWiEQ~Qw1Ov^Z#-7j!}|D-L_yv+IFSwO53(=yVAC8+qPZl%t}^P+P1Aq zz5Ha_~-97rxi9L3lGfu3vcEp;o&s=k<3g!l%d*=t@_5SN;=YOhJ`1d>5kU3Xh zLy%tt`6vdKOZniFfYnZqa3j@#EdT%l>K`n4oU;P1Xc^2!gwJ<}T0gZPfToyfxW*$a zoa?R94g8%D`@YF}pHJSKLZcUF*`DTii(g&>_VP~h#Qq7y(F1Yc1DGind31L7H3@RT zrq=RV$H9;_T@OM*ZoFome`zriUA)~(ET^CnX=qL|VyiqhILQ#XyVVVs*&9anSOfP{ zt;ji^W!3)|Znsl*e}G{**Bl2bSbIXzbmc5HG|^hO zvXU$mhpHx3@c^ov|Mqa8U6|E3y80>VGv?_xB~wG^4bmkzXz%L;l) zKFEROC!sbzaet4@$f^LhQ<&rW)1K9pL9|C~NX$uqM?^9kWK0Uk*FI}A?k)bPa~sI* zJ(rZrr=lV#^K2NC*AySP)HEHRGE`yLP5#;^LwTm8p~e-gzd*tITvbyCYTd|b(jhmd zhCy@o!{Ibg1+8U4$qMcpD-@~;e}#(Iaj`g26Y_P8%ZoVh;0MxSR`WBW>hK`EQBpEB8ctXo6LRtl9DhdvbdlwB#jiZ~2F#7F{(k^32oeA=lYgzO|9ylW z1t1~$w|?bGhWrO9<1Wf|Y2AQorD&Yhmrv7Z@|JJBC@k#P^ix_}0|-==#=-XYoC2sa zwIC6t!7J-UgiL{z+Rvv&yJZ(02wo|z(9Sqhz9c-j6spvT-?oH-SW#h~1B*oOIKP28(29aSxLEDpM)nOE(h)kqbilYCJQcjPc>gItX(R{y|#@c6`}C`5*27 zS1JP*H~(+j|26f`BPbTY6=t_LvEfsK2SaC6ky)xAvmKgbH<^~Vw+~Oo!{Q`Hql;Nl zd}> z&x|6!U!-8srgeG?>La)6+&Y$QqcjD7N6|~iDj-Utw=2w}WKjkd^FwK2UDhoL7O0va zhd7M=j3sE_io<}T0e#eg39TO%uN(8kIa}p$F9T&ZSelA2bG+p(5jTqKuikxRO#=!1 zV`%kYcwWw{oURjKx!TmPyQS&|+Gw@mi+uZRc?|szV%HonHwNxMfwX_eF8_ZF-B*2d zsPB50LTtVYzQmveurdjA^|5@v`<{74bKls+f>tGA2Up?#=Cbg1ERYtx7`&5-!!Vsz z9Mxo<{+kT|IrWt=z+}VFlVpW0N(w(BUy--9xP44X-K5#y;H=NnGd^0?+h#XrBK`>; zVJ{jA%Q~SgoeF+;38IP?K%FJs4osos5!ERIpU}+6r^JfDT^Y(+I&g_n!XSld;?kOzQ^!PGTo_|9*Ru;np2kA~fPNJ}=z zRcfGYRlE6HN`MZnEK=%Fh9vVZC7jBSzP6Uby!C+Y3=}#>6LS@O25sWibS&m3kcM`q8%r4{j?B4myxrhTuPI_S?t-Whq2obaT*A!OU2Q{{p7k{~v)V`sn`&OeI3+i5TGi z?Kj{P1q38mORGfIK`#R`cCwf7{cAryg1m?QP8*nA3GA?QQ*&33l)rPq+YrXAaNUG; zV=g7E3t2@?-jMbwH7VQAgm#(b1~~T3>-rn|U+5AX-#jBl=PdILjprpF#*|cO@7oaE zi!1LIH%f;aCu4r}Bm{c~c@bV1qgYDbMKez3ada*S90MRvmjO2a(_Mty-yS?#KDaUHf;QKhrokk?Ly+wI?B@ZRokZDIN2Uy)!DK*T_?sWR zID*2X5{wdzfX9)~(Paog3cZ!WUZbCvYyhwr9Y zk7fdc3>tP}i+#Vh4_KlNE|3!}W#ROi3#h`<2vl)S6rRF*^{`kxY{9XO>Q0JuZCuj8 zZ%&D_Ba<9Fm$3!}QTth?7dA%Ypc8#+JcGJSpO9Y#(GTHX)O+3XG$L&}Huv!mAGcJQ zOeB^#G39F_1ac&E7xKj8=Jtn95YdD1LZsNFJ5%)o7v2(t`V+`aXq0^Tp-l6npkzx_DCD={l-%)B`+RT9+#VdJlui*4-=({1 z;vhzSGL^SyzTm8tU~WpacYfsme>iLSkZ$S^07^q&uXa<0e)`Aat{$v(oI@?leh0)@ zkGarQcN!l|6*M45DM*&In*YSTYW!rN`M%N*v|yU}Lvp-V_@NRpGU@m#QMR7}yqVlcL{q|}ntFB4gqE+N?Uiri=^_tBC9td`b%EH$r~L;2bI@pI z*WjReXY`|hr$MSK$G!MO)zJ8)PL-auH#a_?rU)G2a<$ahio1VR>M9%z zZ(}@dTcasS19NLboi5{V9;b;31e!+(46L-18##jK-;_Ggp0&Q+ayw9YaGH9nr)COEx+gHc#`aLmKDH%}BOqNp~(JH&6S1P|*y(XQ&K+ zUkgqmivt#w2pB6Qcj46aE{}1vZSt|07L;Fae!fVW$5E1wjS=4FMplbgus~1Xq9-4i7Ri&zPj2QH43C!T&rw;?$U{UiFm8 zV$8$l6LPX2_ud$S;j*^$M}b`XJzSMJ$y&kvTNH)lk{gS7ZCoMJ7!e))`rByG?;BOs zLhoa*Oe?eF)<`4fi9S_?T-@<4aE)sO^ttE7IaEsCnt2kg`lHlW9gry zu)_W__N3fWnvoopqFIE(@9}r?IG5EZP`K5Y;d^*OKTP&14arWDl0 z4!SkZ$ym_^i`V%G)zf#X@;y9!1<8R}yKbuFC0soBIa^SEbKX_kZCaahb(PWO$xoDC z31o-Su+8)#eaS>+M9D7azl60Ux_n!*j^o!A4Y3EW=2_Mi?wM{q2oHY2Nxbc0-@GLz=p-ep?^PAZES@=v!!N&f&q+Nd3o3I+}fVkZh*0B+e!0 z80%J)P8uFB-W4{Nn6y3on#_Qcy7D=)bFTR{El1wyi^^6wjI?A-t5NzGw_jEvMKb zx(kwWgc18I#iZB8cSNmXRLG}XXNT1qKCUVFF^{36x4B2=LtKSXZbO*AuF5RRl_6P;iDW8Ud=LNtX8tIJ;(tBbaDm7 zI9-YDSS@JZMN7z(vlJ~JDu#IIEC4Mx7S~Vn9E6^ZB!fs}6VslVm0sUJ;d|Buk<}R@ z#@(&n&?K|bmlM%Q{kn!AQoZhxf7`~VKu~Wi(rG8xlziK7UyPNu;xDCdurHn6^PEU& z4K9Frv*x~tmhvJ>$1vbh%-FwZDK}-ey2Lk$5FYKv(jd~E*`M1*WxU~!tq|5JkbKIk znLiIWXq{)f+W<&?CbZS(AQQje(@1cqC-f50o)%klmuX>h+mXz` z_sJ43MxslQF%s_QhGi_(ugZP0|D7JJ+^Rl7QYyO(8bZ$WXylllny#(QluD!SLw~6n zMNh5zV)yi2i^ug7OzvC-v&ZQBo#%>IDDf>Ry?Dx9^q$(uXcSt0yah4x#JuF(v$A*m zA(n{xjBvQw=a;sS76el8#QMlmJMVMfrTAz+#l{NGj1!L~v>f4qy8`1OoI`EdmIp^M z@(QeMIdgH*502&0-r^J;Wu7F}t47Dzso@EW7!R*4dWxjL+Kx%641>V}y&k%I=z~9d zip=rNbRbSxp__#dVbD97WyN}T5mFrYVvnmK*eF&{gOIJrmS$oVrMgb3-nDuw%)}O? z!n$pAQ=IB{eN%e|l`w`?<zb5cl!k@mAIJ}f8sY!ThZ5O|#J8wA@>p0cR z$54sEbrif(s|t>GN5fO%M9gG=n}^)aM=`o?6xvlf<^Adu76#1nnto~WF=iwABhMlb zw#e`0Z-FFRp1tiLv=Ey`hP-MwQwnC`k;rwi%$S}x$74~?)a4~VEcn4?I(bYB=Sr6P zXG$n>mCB^selTJnFgPI$jL)s%c=}2uAe&07pT_TL1^gzU+F9<~Ly3*;cPnteOc{_Q z@>cHk%lJ?CMFj7G<^30Z@ySd9u5i|{41V$&-1E4o@8paZL(}T(%IR6z$A|yZA54J7DB^=3%bj3)oAGq?&zaM#|O;+i-CYv7{Md!`d_pX@rDgHe@M1 zXsp%Ip5Jd3y~^A6}e3z<~WI1dSEMQ_aZ~0-*$A%S9z~D;S zw?J(bXu&)D?Ynl_at%a)0jozv(ln<&5CQn@$KIL}w+D<2qGZ5nBfG_C89Fs`c;B>pN{gN4y{c^iY8DnbV3#X^eAM zDu#JrZV^j(Mb zN_A8U>@KYlgJotF0tySX?0&;{HrW^hZ&)fN^dVS1P+g4dGbu$SQ&Oc;eN7G=^%WzB zR?lPn_rh-|QnX`AF1_y56nQdjL%3Qb9LLOPrVrIrW{rB1AEn40ddjQU=22H$?`pMz zgBHwjjk11&2w;V`CagTuBG`HkFiKMViEV_mY_7)<-N;yN*v1}iVzwC|-KJhV7nNn0eQKY}lNC@!jjHTRBAQEiT)VStBWpB8&;eE6?c~?q zX#t*K2nl~`>%NMrGh6F3HM-;X!#9`^-Ig8;X6Jp5=^gW0YX4ek)H(cl%vs}R@Rnc? z5J05~ANXa3iNf~$jB_k$IK~;-Yq(D^i#Ju>fSxYpfQ%XJY`rqLn=9 z^Mw${hsQ|-f|li>O7_y?5VIviO+hi2 zkZKa+8odv^DpSoiAc0Wm+V^)y(-yx=czokgB+eWRRy>`Qx+XpQW!OFEw5y8%DZ5vlzdVWqbGMUsN0Bk(sb0Pvcx^Z_78 z^9R~e&O6i5H2emtgJ@TspABvIRc8}; zCpwyl!a+Rw*UwEUq;&m2MYTR*1B{0$*|YMtdrBcxR?wwzgJ+FE_B#C6^0GHfdC$!6 z&P~ZSkyLE~n8RZ4fm4Ohq-TX%Q6h>u!>jRYFEr_U)#7-c=LV!`+agTjMo;S(G|8Yy zE1kmHT`DTYM$u1a)V!cBG+8SLi;pY90dH_ULl(R!z8O47ngXD4HL>8`VMAW7?y-T@lrru~7tNjkmXBFU3)RW>P@_ zKG%UTk!m4Kr2AlYGxe*ClaP*RU2zLyhB?0O@UlM1~ z&O%t@`$UcN)Rt8rz@oc$3;<=~SM7*F-s2M%Y5de`_$*tPX=ipXRj{5-5-m$^DhyDED#W??Ne@~;*8Z^AVQ>5x~@b6J4g-DS7fu;TA8RUn#FBbpvGdnSynEF(2gKby( zVKe^*67xhAatnISCpi9cV_~GYme1H#-s_r-=QE)-gCSp)e31U$mH5glUp_HnHlMcW zK^%Fl!=z(056c3zM-e~dd|SuJdA9yTArT9L6sjSFwJSJ(olSsj$JDx=)On%a;V1hE zy=IyzA`MjN4s!QRbGHD*lgzm9z>A1_hJNK%J82W%)aaw!sg_=b?tm~Pp{E zT*}(w;Z76mm*fLnOC;(s@8jW~H(9Lc+Edvt(M{8lQhIin@t9-RU-!j7>d>d0demWZ zBZhA6u$6T3$n59>^6y4_iOwou5p!iLaSkWv5k`OdaFi&oE9N$B+}8y=>gAh#+u_~67MGhPdl7y?0w1G zAj;!p!?i0B$|mXt(iTu5G>I9a4^+S-^QxU!xr-yTUrQz%Yr*t<<}H+ne$kw`&gF0K zlY9>9IK6r>%y%fciDCR&55x<5P<>O44^au7uiO!IguDDu39D|K#{_D<8F(2SVd4{! zmHmB-#N|Ub0dj_VEQ$tvOs0PpfK7GW4;YOl^}}W1&r;SjY!Yb&Pz#`w8?wS~$+P)e zQwv}uJ2(o@ymS}Vp)qjVn^6}mSooLTY>Z9J7;Se>08i4uh03yi7ZHRz39ByZ9RV{%JnAn85sMNKIo2?vlGQcu&*~e(2azylXO&7`n0n#!A8u_X}6) zzR}2%Pjb?a&U*!`mThbCZ^B!FwK8#6L0DI`S5&CV-11IH`sbA{?LI_kO$!?Z_4LAE zveEz@_o5+T%GfRzO<2!7B^uM2@NTGP9CmJ)5d_7F=jAK_cZx+^0Y5BB=H-;0*#Ytt zmL%T(9hrO1ASnfhF$Nk0^#C(H4G^#(G$MGv1IV!9$|b|vC{wgfq+IOU&0gztXSLji z-|i~N%K+c7@UKVr5|>}s3zy%SnQSQ#E!Vo8w5x+;rbmaS@7S8fg>;ZoCj zwom7qc*#XacHBpHQW=j+G%9%+iYNvtUi(N^IZ4{xDNryz|aLA8~%V@#tI4tE? z!lB6kbDS*RW-zA~qKor;idk%yk&Wh)BrGX-*JiR?oZcPXRaqh(F+#gAtkrBZ1lLfe z2R@xjFkPv}olrPBk#Gl?$@;SisuL08&tab#3m9A)V$rbs2`t-C1by3eB+L*6WI~55@rEre66GK7;x(8d<!$;f!rcXH*9r4?+Y2xhpHIA#&N$`z%QkU7R-G5thp$gEudBTr zuRU#K$+6cf{Sl>{35Zj{krnI~z8Twmu(KpbC{Ksd$$b>1@ePUsp<~_bKo|qlhxd8V zDqK6KQ5}WL3u8V69svFO>~!|FTeE>ZeiE0{z--9^D) zkND%mSNOx`wja3rHR)7TP343GA1g`r&okJV(HiS{5jUiQNyF*}?@G{YvSoFA>f_dw znRnJFZxZb5h8pScIS?ac?~4+UH^=uX#}%N_mWG~W%DZ1}cW7z<7~r2?q+xv0@G-gB zzM{}t3qb*N-yBh6%kP95Y0P3S7AM+ChEL$avn_R#=v?L~N5Q6gs!I;};F=5y+nahY@M-&9yr^hD;%jMp_WFxU z8!hN7XQ&%4$QB=w1Vx+dx}kGIlOoz^~+dZI=nk=Jb? zcue|lSz8J1$+qiWy9)k9losEixi-40phjdBZeImQl{6#wvNc52{{2p7w4P-D>ca@X z2h0jsszwT5chp90T3_B#;>bTkA`us(8erNUs3(%WaarqxFc-g_7KZ6hG*o4Xd4Kti zhr6A9|0pMkaRMoyl*{s9lsH%MU~*!1)388eCimv8M@$Tg3Bx32q$jcN;qb0R*!sf^&&OcLHA+QPLTyyQ(B(deP^-TOnY#nN zQd3s;bL_*j?ZS|DziYF^nzP$2uS+=DRS6>N&Gd=&Q93;E$Ec}_L3ZWprf$W2R?y0a zz*)*vtxUQc4rlFaj@A=#5y!L=qxeDnnoQM0lGPyYPrpE=6SN!<*I+-@o7m6s-a+;7 zby3_;m7Cmc#Qxo+d=W<%KB6ZV+ojDLdyL;&jv{S?F34GfK<`GY=O?TqV&ajQGjTuV zl*jqN4b!lgQh^zjawKfzr(9V?ep%eB)@t-QP9D3lGM9(GxXfi4%#Bc@m=FA{rzC=W z*=81D2=a9d=Opo>2V(tW)NbcgOab5G=_w3gdpkUTorvLafPo7Wo7J*oae-2iVcZw` zk95W?5BhN1PI@|6m=J8+z9Lxgmg5sb8=BY1S|>BdjaO9H#|V}(xpakjT}Y_Xe=zgC zGj?Bp{aaekifnkS+9+%6u$BBL>@MqyZ-2gH;4;%`RP`1Hy){5iE>16~WG~I1kK6){ zih}U^Au4q$qA+(MrhPRClJ4^Wt^2ghMIm}DN2)&wR;9G|FI5=xMaKvV@!oA!aAhZM z+{mbm1+?DQ4g&VP%O%A4^h7tghsjO{YX1;!ggzO3z53&h-ANZx3_yG`T#>YK4f!l>Y-QnEf!jly%52$%lly|MV;)$r^X){bR`M|bhfg<^X}tJ1?gaH; zItaXU4?tGTyt0H#Ydv(va&8s>c+zf57KQGv3QFbfHs{fdoVa13?G_C9v>Q*nAtk(L z5u7O_`B2sApQWPxwUqRR!l$pz%d8qIxU)JL)F}s56d9IJA+;@+;~pjnvlQs@Y{>nT zz>uCk|FvcnS~?yx)!`Jk00b8{)071Np0_x_lc;C|d^NlYk6wYy&64;nVG&p~zwiG9 z`%3wOU%{y59as!_#O5*uij(^4E6yA)$6Yqk8O8Oj^AvN?eTr#_7hp zX>-`(pWp6^QWbvM8GsM(sQ>V5n>xe_E*u_Em@;p2(UddVk^;&) zMI1$x+kQ!z(_kZ70xd)trI?;#5hF%o3VniRbq>Q*Q2_}8i?4`sEbZO3?690c~k&czrEjyy5U zA?Y7j6grDk0j04Tj=M)dCNxCCch>CT)SxK8Se<(%tt+-7NLP4Ai}JJ`JR`)H=K@iY zBmDUhuWu&;H{JmsI8py$0@a$qs;Xo1tr-JHwEmC5RH1BP*srrdZ^Q*73oy{jwAFcI zx_ZGao}!I*2~(@@J{B?@W#KB}g-vCT`l!)+H;6>?s32U;LtxjP$tBam(q`F6dzS)$@sVJ_mlc*)|LlPx}2cl!Yasqqg*&K3)V zKTf|%T(vMEk67&=w^t8S>XsaH1zxGhh|rEV8=jCDRef&!n15tN&@jhjH^=`#BU8={ zDDXBbvcC?dq_lv%EcMz@x^j7@Gc3c2F_Z%1`-OEbTOut{5#86NoM!Um&jjo1sX@}P z?>os+wh!%#rXZa!y?3n1gZQg-qpD)BP5WqA`1X~-t9*g9%32UUOCsL%zO93aflpFk zWd|qr&5z&uxVMa!q6)#$G2AfY8?sW55|;SVhcF(r5=~D5ldkz9%ch6>eY{mPvR4{6 z{X+ZMSxET2u;H!i)eSA}oY7ytltYnleR;IZ9~~eKSx!iFgF4BC5n!Ah5Q6v+SxN^M zgM+Y#>o|J74RA!nO=j3ikbnJVUVVH5kG2;bw}t#a1N8v8BVp!=WRU8kf@Blv`t({Y ziH=C2G%Nzoc#yARxb8Esn$&-j)roZ*(h-A~jVD~hw>&_TjxAvqj)^QXGcr-GP>v${ zjm6FR{aIbaWY!7UFcPeX<|zmebX#H{la^>1d4r~gF~H1cay^N-o$uXBzQnBem28}E z1YgK#HrGKuS_k$A2e0MK_g)WAljz;NzU@=d)u=G7^7SctbsX0jlWPxES=eql?pwJE zzjzcx!IKA#8uEL{4K3UBG4`56Dn!vMVzl*mQC0>Q*bMP0Hwb5M#tc$#xo4$`mfTLE zy_;eD#auQfE{e+a8e?5sqK-i;YCwvshd|^J{WjF>ifk#Xh@}KiP!v>2mlUS3QPCpP zR50ch$t)XPoFj)Y_U*i0Nx`wo!GwHye&guk1MZPRQma4FSr@^qS>SldI&TkSCaNf0 zP&r;)s$dh4LnqDXUONeisW>UM`jZ(YGM3l&T@LJ4YQg=^DwjhW^tC#EqFtKhkpnB& z!pa-%shid}Pd0#IFQAW+oBjBt^o=aPqh3*8WY8n^C`hVMTlx4V{P75DoMyzsRR1Yut8X0GeE~z z(7mY5Epd4=VAKS&A8W-RM?5$&*ipJ?3f$74=PIDTcGVBGt@51HH+5d+4?wBS;*{i1 zC#LO0o^STU(OY-;xGSXXe5#o8ZifH0Q6*cn{{-iqSS4xbNz*#bk~6!7>%~-2q*kLB zak&Ts14wYSZuQzHJogw-<69|u%vJQs5KvJXIZ@Yf%RG6mF(gIX7iOPY#gMa{GpViB ztuH*eCLy?(+B^e|lmH5NIdy0Tu3a@ymhR>>2aYFoQpfG=C2Zy>#VhkTAp#;B^Y-K< z&jRUJe;#0oi4!XHwAQ;^FHCth<%*wJP_Qy7%ZHULbQ0xcy3YZ2tE)`Cd##Gre|*Y) zLY%R8UEdwdFnzUoQTW&qn@cbppafy2PEtB`6Z@hqCN~_!Mw~Orne4TgXVb8J0Z-?g zGhD3R*QFaKIH%8kI>-7UDpfnZe|f$>ycWa!Z4he7waJ|*3#8V7#t;xH$|qp0GRf0q z9VLf*Uo55>IQ+fOkgK~4o3yS`-}Kv=8Y?g)yB_=x-FMCmJbAmIRchu36mYjB9%6n& zpFu?5xyuDou(O&o_d5=}2(ouPGoOVYgvPfHmu^qWJykd`caEXZ zc==}r$ncT4mpGH~!6)0{6a=#_#bW#e0v|-H$A}_8n2@rc}I$O zhNS(P;47QTKz{R^naXO%29YZNiW+L2qtFRY-k@1IeO+6_-B9&G*P=cSe{0uj=WxRB zi5`lm9`g}wCLeEOA;HW`VysOgLkhQT6F(NmdWfSztGGCxgsOz3FPanVrT8CF=#l`k z7m2<|60S=yo;Z<`auz2nC!cm;hovU>#Z5JQqtZdIhr%mN z3|N78C#!vjvDi64$(8en57N%K254TeL>L4UK=e!j9#g$_El#p zkAj6^EbX1YFUds?)%!pe-*z=ZqWY{x+`3n}08<>`&8St&$kD zQ|1$AuIUs`fiR}1lmH_kC@eki#1k}%hvarMc)rDE$)Z38rWPq)1`Dd86e;l`Dh}ysUwk{ zMXiam5oRF8B^1veP6e0wn^0ICix0*c4?gH-a0?#JRKS0n_1Q{~&83HvX92g1L51zW!W$m%xbXzl6XjMWEC= zcU7k@r($@Yv2>pMwmFkgqEi>{g>pJ8Z|IJ8yafQ~RLC2F8I$AOk#*I}$yKLj*|ok} zNwFu{Wnc9ywsDij-0EYa_^JS&$CP8Aq#VK?29|c4+Vx?|LV)yC)8?0jlZy&&SvclTfT(5GjoK&yniz1ypJ&)ykAGv2` zic?>HnM9VXSWjMI^X*^9ffQvF6xhw+IY`lh3zj$>--BE831|__-sBK}Ghh*Y5*2B% z5KcfXJ~*sIxY~~}R9;&O0;lxo;}0Qh5v1dA%bpiy)O;Rv5WFDFuTdf)MR}?VBgw*K zcK_6iH;Qx%Z$6;atK6gami)R?VZMIHp^?=c3Io~Z$`eZn(Yj!2mx-#Cm+c+CmYuo1 z(pCi02*VI&epYTrF+ri{lox#w0lUc}5(Jizjry53?qwBX3IiMmHlx@U9yD)V*`Mp? zs6AlwcDF^)pV?8P5Rg!?%ds2A>{JADAojdks)!G~IV;)bjp!BS91l&$tZITBwu`Ij zw4#89Rdg1J20hrAiUM*kj3l0^X)bQ%`|D{YBv!*P8M>a?f^Kyps3Z{IyEO8>Ozip@ zbpcX&<}V%&-tPqDlo6IiTNMwC+pTwMG<94^ILt#N3CjbphK)WHkMY_1mdhaI-82LB z7H>lGYNh-ch2z z$wMj5KyT@CII{)UjLUNof-!~YWC`67#FXS+D2Af(J&JnP(O?p9zsr9yuiFK4OKtwa zyiWTB01y?3XbKrNke&=6e|k9kABo6Ely8IWW?v)uv0F}k1m7`F?RRfLQAB?+?m)9A z(|)H20DxoBbF9x)W?Jo^3%bEpfEu|4TyH9%JAXZ(;3Zp_tU5mLf=P)v=21#A=m+lH>xe_7@ow5(=9c z{5^{pK$ef6{3wO_oKMNHx3cbq59c`3$vf!$`#Qg7s*Z-MhM>s`;)P!kB+iyOBHH3A z1D7(U3|st`-{4R&F)C8?B7t4)6qA)ph1EvC%h#)uHiRd8@+D`%$L|k@#>wBhuWn*~ z(x3zyVM|Cjy5a45x)5esvfaN8xVfs@i;os*daty(DsUKZ<>!5I1yhjAJY^-9G^Y(% z73!I1o9Ke2p8Ue0drYqhlG!KLip7$w?lhicMvYGdW;J+HSquhPjpce>BbHv!cSRu- zLp$K4cPa?awb7*}JYjz)6M{D>rXl#tikL6lyHM(g!Zoi=(IAde=|Us_pz{sbY=-#F z5K|EU7x{{0^%R$?7Xy6S>q5~`dE2*L&+Dz92@=Cls|1QWdA=OYiQA$pKQso<#k`mG zx$9?DdjBUyjFGhz0i$BoY1Cp}<@Z;oo9rq=o9ynemZw&!buB4835w{X(I!Szh~k4F zWqM{I2gE(>ADWNJEUxGUZG4H{J{`t?a$K{xY~t5>SGWBI{6aV@wxqBrSH-a&Q!DD* za~MyhKegyx!uo}!68!znKjq<~F};znp(N#j<^GS#+x-m{a$@6h2m+ZAy5O>O!ZM<) zE>nGn?=rfyB-Qr`?Dz|GFZgE3p2VwtMuU28DJilq($+Gh`IAb%<7NfpIQ^qY3c$VN7PxMYCS6P=AS=z}Z`dl@ zQ^^{q95p>}008vNivU0xk&*!h0ZZBoPeFo6UzY$SB%~LWm<+(ly1c^8yT1z4 zc9NTRPbMzYPRCLzM{)lHS>V4ws|EKCgL%&Ik*m>;q=44uK_}ZAz!nSSjv4`5ifZgmcQX8 z*v9uiej9o8ud0yE2vk#(ytS?sxs#NvEMe@{jZVr|lsC*W7$(#9WVD)4RwPh%U+lw822-n(cq6Y}!h^<@QX=eHyU@R!`eh-xAu>459by;oyOtL*&@nAQC$sYg!oP9+h`v0Og!#;hj&40+p0)Y7!Ud;Qy0f_$;f&E%x zCvvd=BHM!kn24UgF8$|e!~BH$X?wO(ZyKr~3HIonxYWRSTWw`A0aDL_FXdkV}z{C5P*{v2!EN znN<`I#7jZf7qOj==D%AKZd(NUhyKX}(s!bsNPkJ=l!D7Fm+QX=xJvcgz*Fwnb@oSC zbfVv4t8f);#J#5zH+Xt0*}k;jyZxCNnN&QS^#_~$T6E=K=2rjP+~;k81*baBzbyff zGpHT~67Bm&jcT|$E&pS7&*-jXO`PbfE$?stnYDkP2XgB%`p+T!uMR~~xZ(UTtdXCk z-3nOttsHbqRT2O|uzy4lb2ymfbV1BejPwn?xy*$)6i(zPsiLm0>1(CYC>72QdmelZ ze-cuGqc|)9%r0Eba~$9glWE6JMgzyrx^yTvT8yiriS7xM&J$kA(-UzxbYZy3?&G{V zOnafJLfNW1EAGGy=;mD1bcdD!4JydT5*BFe+~G zuD4k)1ZGQ{M%H$2LL9f!FKzev&`1fRl#(=TcaUodwiK>;2jOO= z-DtD?JwyLAY5b+liIcjx8FehhiI;>1ud4Qv5@A+J=e%_pJ1*4V5~JiN@Z0d`awPJy zu=!kqN+tm|lkCT%^hI2BP?xnyrUYWWamA$jom-VFPG`IUHhNvOt{q-c!8N=U<&neP z0dvDxlP*hPxWNj$Gl~38hA>}TYoI@*>{qOCzhd=YRTIzqZTS$y&tHxQg`)&5G$kYi zpkya#Ds0=5&VlxO=KugrfFIrfOo$a=zQGg*gvLKZv=%M!&sTa!iEFQ1+Wk^8VN0V( z><9uH!dZqdi6zjlmc#~|;)OPieeL@4>f@L>7NNNahlAjj_xXm{n=LxmOH|V^E+0ksCf8zK*8ir-&K-=!H4>-*an*=A?1S&)RIhVj+cW~+rG}g zFU37Z6+qn6WC4Grv^HL-VhlkELn7@dUU;M#(R?q23$sz-qUt@B`{@7Rxn};GP%#yv z($Mu&^r07|7)usYewLo5T$#|pTmqrf#1D?wem9h}n91rK)@foL^!Dq+p9^Nzh5ipL z`~S0f0yzM%@7e`(DKoG8jrvH^2bk$CLnqG={uv!t}eSq>0e=Z9PMD z0PbEszugO%qka9WQ-~xTt@yOK#vo|oB0{;L*_sqLtX)t8sP)-N@kF^Jy_Nh5m9C?a zSCGK??=ke}Us3=8)rlmvG}pqszUKMGqhk4(a3V2&s+{MURcTq{a8$8`zm#*3!!z7V zU|VTA53H>rNY;0&>C@$TY4f}s^Oy1-7(z}uBkjv1>t?*D*BoP&km(k(CSVvRRx72f zDZBQ;&e0mcA3p?eCE)H@(1}aSpc-uD)%{2?JbGCe%PUk5d!4Qcm3N;cw=8J1gt5Za zR=coEHc3O)gWjebxW#@`WdD&Obx{?1M_+3Yp@2}GtOPMV?4XllX=W4=aXr-lGI%LidhQ<6muxXzm4A0$2hUu^vYbZk+# zEecm`+qP}n+0l+|+qP}n=1#I>+qP|ECokta_xyjm@154FRn=Ov+QOK%X76*1Ir{jF z4nkZ93!UW9PJLu3fyHSVEA_;k?h>k;0U-abRJ4)JGj`q^6ZlZBBhjr-M}b!$m#?M| zBb9@X33c!R+6xi7lUAm{Xt6H~5KU-$SqL2*Pb@*YT_EAU&Xl~+b)rsab$A@iD2rlA zN~M53@N`3#-GjtXgh&Yg@@ zb_P~-+Y2I{DTO<@q$)lNLOVRse5j4VtqUPAX4D?#9Y`I64v#d=1<1lmvd5iF-Hc$Hwcn8!}iO5;Jx)BYnVL5FkyjyMr z+a2HR*eC-`a}C+eH>t`oy}W04CzU4o)Hx2~O2%_F_~m%clNt!I|9bMPN8`Sc&zHds z<0Pwf&j;7h8kf}v#x8=nf(T`hZ6xSI8o;!M7=tXagN*tR_`(`49TgD|H7Xx_TTnk# ze?hzee!;!v=sFR^Qo@SXHH0Te_S8Hgd!UfzQpt2k6u=Av7Rw__Uh$7lN-IEM-}say zFH{qBWHOHh-O=?kkEA<~m)Po}9g_vbtcN&WglIej$p$k10=T}r9VL8H_h&r(ky&Y@ z{r~5s9%eUVfpZ&l%L0Jjf6Ahm1L%UH*H*!Haay__q=cZY@wG#j^`xi)03Sh|;t9qo zq{3a0P&{Px3}M5qg6oR^fH^hJN;&{w-it7$o@9wJ!FSG-S_K3b9sM|&N>`X*X*Osz zQUY>~9b_(nw+Nta;k7BMpG#2xeuqk!coDB?f|w%I`O7`InYK|fON+oKf({1rJq$9=^U3BF-o7Vv>PoL7vs{}A)fP=&r9DySiA?;cg@ z2)J+RPn^Dk>(rc;5RCg#<5WYCU8eG#0uafBcg#VJisp( zUB$c99C+bT7X(lA7k2=z!w&~41{wI zOCSIk;Vhu>T7*zRp9YNoTo%ye&y~vl|Jd5kx&L1;W^{i5IT3CCfA&Lg?EX(X*b?3m zB>rV@D7$&RrS0CqJ8A(D?$aN>S`cvtg5l-#v zBWOE*tcvyrC9=>DY>1ZXnFs=V1YK48XMrc>DtTr)Y>+8LHV! z7G3SVF(-`SFE-z7Dx+@EpBUCJI3Z&aUNl;K9$;La8#8fiq4>+PJKyaz{x^cceu-8NB@@;-Y2lx}jzf30viqfv%-05&GAXLsAc? zMO@3Rx<>Tc#1PBQX944+c-Fp42x1e>hBny36FsY3Kmx{~P`?GeE|QA>u#eU}C8V3d zP9#n~E2G+GO9h0Cl#swkIW+1yp11Mv-o2yGlB2447eV=iX>v4c;2Xl|F-CIjHK6Qz zdio4D?sY+Vs-ui^8y#e`S;u-IvT=lL(_srQ|DACuS_A;31^7>ifgbDstv`WokU}5A z0RUStNWEP)+0#wH$^Yp~JhlJs+;Y%U0wowi0(siHdueu*a5 zIxUf3vg?YGM9hBS|{LwEmbU76V~Tpy(&I$T3XPPcR!3y@U8Ig9m%hc*AQTie?}K~Uvuv6$finBf=$yl{&CtvfAQ z>WKIlv62uRr+-q-l}g+*uJSMW^363*Sx_eNNNi~cFR6pcwlNl0d&-8J z2>Dk%`SVk~&d>P7>U!iGE-#M+OAx?xvLKda<9*xK$POWeif(H<-mbEsFQ9r+b|+oT z_N3&eL-f+}1TBh`WZ!M8eTnL`Bp$Nr=zQuHqMdvR!o;fr$wrlOpmoJU$H2IYQm}%Y zqxTM=i#(rtKw4Izf`-U)1OYCgrtwEA!*_Tbg=Kxc%(Va=K#DE!l)m2sW6k`6ucqnQXi{y*TX6pc&};9px-jdAb?Zd`%4o8_{a`3YBVG6 zOS<4JHuZOM1L))gnz#Rny&nG{2q?Qy?#Si;cxC?!a{l*Htf-eR%u~yB)R^f`;D=muzYGM1%-z$4Sc4B5*T zM4q+uCLUVN$Xg|%7K4?GG|uRhIIvR0nv2}8Kxr~)7|>`_gcoL02kA?Khd{0#wwLhA z%LM)(EOIXv1k35Y1ZI9~`V;vsqp?LK{?xPP=5{}sdVds@gE-?M;Cy?xpy91CrWRiR z?0c1GlpaNgKfk?G>SO0LP1D@SY!;3c7|3mmetBHj!4;4Jd{c;O`A~AX!z5}k?q}OZ zYTLz5)nSuWz4r^S>Vpb7Z~s<p>-NP2Lv#>7wN@6o zRjAyXV5c766wYaaZ{b=I=r$JaFsdQYZ0BBP_#z4#BPX=YB<~x7A&lI{-hta5cdnuR zZc1GvHP@ODJk59)H%2~t4B?H^nGap~u=;`#wXI~>fzTf%)X=->f#9hz__*}#U1fsc zm7dH-!E*0Nx`F5;p!%Q-Q`!1-#x#vgzLcQY9(&wYu&6_pcN%O<4pdY#gnTgTm=qvlb?-gUML9Kx^Tx;9>ul^ zUlRLopCo$JjE4oBP~LHq-_7{!CdS?DQRm`*K1(`yf3NzIeEn)1Rd2+nqNWxf8Ho0n zoZgCBR=l)GA6jTb26S~H@hN3xsv7GrNQKdF3Uw~NNGYbj6`-U4VA+mFOR!Hn00pX|26!q8@r`{GtEd%&(2277}mkH>`}Or zvgH&vrCNLc{X_&EjXvW!Lxs^;lY775KTDJuabA=lTF(iT_Xg=F=ONOC zy{6hK!XO+ml*~w7?yNiC1(P+wN>_ET>rwEp_@VhkNV%ZbV5EXTcz%qb6t28z-6{g_Rdf!a0IgrzUChA8{z&rpmMhESL;F6gTrH>h$ zKpOS5kohDi=Jm-FQhGy3VTbmF_=u3{zOkp$PT>r}mYm`eY&!o`)U}m~vhQ!_Qy>Bn zjK_F+#LG5LCCO-iG->(oTGi}ZFEn8{J*@XrV#%B(0fc3x#%km ztIC+?8DN9q_07_^LSuW4Ky6?eARN(D5T;r5Q=hk~$V>nUK5MEUy6Os)J5&8X#QML< z>XID4KL8Xxnt9>O1wk4$NoEx$H@FK9?J!8 zY`^efU{T|+;B&_0%CkFycy_E%RiUg2X}&VSMAw?W85=r)z941ToM~>Ufr8hVJ8x74 zh0zbYJEnAU+D9%eD?O<{6o zlo#B--_6N7^Wgz!$KToPI(bvJpyfz)=~3fz2jfQ-kTs-^*)?0IQkyPe8@4zu2|@I_ zuzRx`S2$B;83E?eoO(-n{pl860a>fzZPvkUcg4S(E#TgxIh(ljB3Avj|J z&{DJ6%2xT+`%s`Ji0S9MT$oj6Y+)s+BuFqV?u^Y*m;8?Q5&!`Rg*SEVj>hsUtU)+h zsQZ79|3Was4P*|1p8C@nFA{|H^F+K+OI7a%fGM0aRm1W2g0Cy$Z;0{oIXI%IXX*PD3zdYQGnL@^FwQ!6D$nt zfqv2yNs)VN?9HiM^2Lf;GTno%=AlAkpqCha+I?EEk~@rAoON$(F3$CR=OyNyEN_$g z7UYp0%b^bgh>R0eXu6e9n^~6?WQHc#ZSf$ME3lZ?GHM58FkFOBv-1QIAf?ilk!9l7r z?S@Z?rjQk;S(MJof(45ns-e%l*0*i2e?Z&74LTfaPRN^vd!)LfuyOMApN4=x>#l=swj8i0H+ie-m4avfS+hDQ0k9OY5y;q zF4_OMbrq!}&J3xrjEe%p{wp{pl#b;b?A{A3*({nu-Vm$~w=S4)cxMado`|Ute#<3z zP++M#nc$alz=u;aW-S;mg-jKA11!~ZD)MJ98AW*(;eMt!(ZG35R0M^SzMn(KGg?Kh zfq1GkBfEt^O6vCj0c(6iKZCA?G*=VHrU<)#bx`4*oyT`phfZie_MO!~5>TFO_FGuG9l`|;ZkB&(`260?xpkW@S^)j~L4*sxM7TN+v+2*O*zg=~5# z08vUVNGu+==jLdM9j`6Dg2!kqP{86m6PGr-!snlI13z0wX-HFTfy-8KLk~`Sanhk@ ziF3)IeL)YI!p;H#fzNxafFQSt+?@gi{Pc{&PtW|{PKPD?LX&`UE4qPzv;N$>cPt0z z4FE80!BUpf%mfM%Y%d6!=;U<*<==?)YK^*w-R|uoUM@nb#7X^ecPP;`RHGoE_SzmD zAVSmMB~-`hY)Hy$4Kisfq7V213k}#L9TYw7gV{sn<;+BG(W%U&%i3|h0E`mM$pP*$(f>_C=l^!@15a!GIQV{$6>jBc{lw2F zHsHU8dSJ=MbXOn;c7M^~A29eY-~~=Mb@S#o7wzQ;4jLyRXuS<(ZiG&G0{atHK&gA4 zya-j73eR5zAAeZ5ef4mRF-h&ZwdKvsUbbY)#0o7ePUNOmA^g5jwtt&5DR!dlPv2C) zxGAg>{cj5#nFQ;z3~e)M=`94@oCWM~Y{f11S8h720hf=&r%|4o4Kj~AI{XFj5sNG@ zBk*`$2X@oBbj_e$?8Eu(fQ{BKF@%!Mbovb`zhriqxI?H{31@cZYz;t9FTHhR_bP#0 zo;Y7dtI0?U#lFC`ZQ=C@nU?lgvc{~UoY1fYyiGxi_ZBQ9#_;XPiVaj{15e`Tqz+T% z2vY{sIW&1Ox&vT@V1%nN*CG_+&*_!t-SihF@d5Wsijwyrfb>bPJKw%ZdNE}WvqPG9 z48M%HXOU7zdu6 zi`ob?K!$47qG!eFd(cWO)Ld!IP37^A@WsU9 z8Mu}dB%wbi4*mvP#0O7Fjf4@E&rKk-{Jg!Z+pN10Rp=K1Z6NW0QLN1{5l{3xGS`H~ zKtTlB7`hiNOXa+)afC|+>M7L(#`y?T3ivgn4_C-9Q%8ZqyhegfY1`yAG6jKbpE!BN z^~WL9iNZdS8VID%Gp*vXJZ0@@SK~Enw>?B*WY^^b%TNI94?27xuxWlX*#70sistIa zc_(g80~}>-w-K$7+a_4RJe;Yfo`qB5Q)UHUE4y122x(?hc%)-}bGpNn?w(}>G;eAL zuP#Bl(~tPqoyEL>Ps~$nFiP8DmD+McV_~od4uo$+Al(6WxeO<{+Y*#TDba;73T*K2rcoWOO>mOWR4_DT5!{#- zgY>L9m|A=-)9v1+KCL{i2n=MmqmC1a06a1+VjWffn#WYDoOvD-!In=XA^o&Omu04% zwkq*QASusPm;bVY6A%hGw878%CuyPF+5ad{{s7|7Q+wmj_dj~Dz|8^%#Q;`}$Psi3 z;XzTrN;I+xa|wd8D9AZ`R2$Ice}2!ne0Q!#N*{IsRSiWqL-7h5%?afB%imOlAIu1b zz?X7CIQ61gj=Hc#hAJ5q?(ZoRSD4+T_{KfEE*wQV3$*nlj?|4-ZEsS9ri()MSjcM=pn!(6IX}?x&hBA?;%$5!oeE}-5*I}S{N6=h)xoI z$5OD!Z%rvAb8BhncUHdx9XDbi_7~eK>+H=_*^>>TK4feKx2fT+n zRV?mFgk!Q=c$#K-08c~m%rZq^L=*Y}?KhA{R}*QkXn&?H6Y*D{OfxXlW%5N8wqvuz zr!XI%TI3$e6u-g&JP2R@#$+a|@5AyBVB%-k|F8J@YV`li0iL)28wmdM4vUC1`(Iz+ zt=8%R0Lt~-|Lo<|p2MAk&9Ra-#&XmBL~fZ8d=#Yd8;!;Z9cTpL^uRrs*sC_E@=bq!YZ1!g@IV zNZaBH)+D4?WoL=yfumlQe`#r?T;Ad+H*xP3FICHthLI&obr|2JXRMiS(v_=sK{_tn zDnnH%((>;8O0n#^&w^TJ#Ne$?nW3@nt$A_*pADVymxt8V1UUBr0D$Em`%L~H#`&Lk z&VP{dzf2)S&-oK@`!C!C0MJ;G{u@J^I{@T_00`GOJOV`#=$|&AAMJUiJ+H$rg;@Y*^IRDg-l>Me znaoJ=qly&0hAsvXg>ve1io++cULWn9Q1*S{$7*yS0ZTyXIdPc@Vt+ZVz&GtmBstkXEzaI~UXM`q*rh(_l?1JIqP z-kutk0s#(u+mo&BpZ#Bb|!X|4b<+2}Tg8?Y9P3JS) z8C12P3s-iP72CQz1x;RLOtFke*3(8R^10Gq*ZL~_*c3J_v@FnW!+kb}LK4uGx{G+$ z>!IMkCLIVvs=o@1^hHALLKj9DluY+ip`$NFR}|JHc9)0!a%{EF2u>QccqsJsqY;sn z@J8HCFJ$dZnu5HhyXp%(m7IP}_8IQT+MpMODVwD>Yj;#0gfLA^LCFA1q-*JcvK`jv zLldU20qQ=H+It{P-hY7=CA&|H{yFb_4QctJ8;sqp zaa~x1v?DP+r;RKNK9ZmWt{ZD!JCgFRSSAYZ9d1Q+66q(oQ-Kw9(FV(st)@?0xPp$e zEO4f28z3{g#|nS2;A=JY7nRAm4hB`|PP}GCUr#y$DDvdn2UHVQb2b_}Jmxni;HT|y zLu1fn;?|-I5puZQpJ}@{doMz)(~2##50sunt9`5$fq0olg1@MwC#-yrGl+!`vRurU z>Ik2DqwJd2WB#trXnb*C29di>GrixlKtvXjgHmsS5w;Oj4KfG%ZW1U+yZqq^qRYAJ zRu&iU0N;=+VwHL{KT6+?x<;tWZ5`)Wu{mz!J^z>0c+axKxV^GoyD)VUf3w(yz%+(q zph4p%^9pn*3=Hv6$UFVnGj~3QCR2_u<@yQEiX`t?0A& zoIKEdG(<$Eo&B9V2c;}!)j?yMA9`+@D$|HbevzRy^t@*TMd6OzNXACryMd6T34tB} zHT~&chQ}fz!@l#I1s4TN8;K|!xOA-7`){T#BB-8`zHnuvKH_!+w9&k6Lp;n(p??Fl zz`?;2_Sx^}jnJ?D$R>^2Zbn=^!(@1@_BtQe7ZGcG>+Tka-6i4!vtK!9mif6sytU;y z;D$sW`X>A!!LM#BNuyswfJ11;bW|5CN4kY`QEE7Cj5`W%VV|MoY>6e3RyTwF*3xnL z)~98pT&bJ!*Lye7<;PJ`pXsIL9z%WKZo8zQ?g;z+0}5f@V!FmL-QUq-f8;t7k)R=D zXOK}QXPI*&I^`xfyaC8F_*}0>7%heWAn>HezwVvn<%w=wC{!T{7|r#Da*7FU=D7YU zu};1?OJm0Qj_6bzM%P#SJJc=>$q%|(_w+TnJ}P#-vN}^k@ysi>>PTU9(?dB2E9u_D zs`AfP_Q$sL7>pGl4cI14IY4>Ul(?x7Ol$ab3l6e1?&phB>ixFHu3wlg^?JaCC!1{P zxsUZgO+5A@qVy_ZU0+9-1E#x)kA0XEgO}C)`wuA4DTZg*q1K3*CJDIXNHaaW)t2)g zIhb7w3vthl&e$m#x;DlXx!jH!fm`YRy1o>V1~#cTP1xI6%hl{Lmw?(!rcfH!gZl9c z*a;fZd0`&oEK-M;w~cYkg)5`%5IIvi>ECy3a zGEHi^7N)IaU}uH+sU(IE{Cmt>4p%H>8$Q!g@^vG=1-D=!PosJCt{(Cp#`|s z6wg~3XPahRO2zfSUXk+3n8Z?K7xLjxP7=Iojf48Bxy0H}#TChP*+_mznkDCyo$wTO z`UAbY7UQ|V_FdJY#O}8@3G8+)ABZ1Rq$ecNx%;D6+-8$f^1s}|)I5Xb#fcS#YI_eCW4^aHs18Mf~)nQl6nbrYIyfNo@%`;V@R8N%Y- zl!$ zV?jZS)2)#GR&ezG1u8tDzuzs1&z|17{r>JFld0h8@^=vq<|Jj)r0NzAc&FSrk#J9=)=+ zTOKu*a3z&(k&hUO5{y>LbJx_VsGK#EvCje-m%~l*xVL%zdJEiYh`g{`HkdTkIPzgJ zBgFs9gK9I|VA+T$v%a-C0sEgN^BT*g6~pqrnQiNo+=9vYZb36^4z;uuB_`UfJmbj~ z)zBV!gZCi#x9B5AMavKui1<~4UCa1mDpvrmu!`joEVGfThAX-pGs?MsfCh1EisN`dy19j5&QA0H_)i?O6KG0b6r2KgU#CF$RCJbZnA*yDr~lKTG1- z<4aCESFJszwoFMQdV@~=l6RWDo~eL?03)X0QA#q>#tQa*y+NQG&`unLT*s{?*XU51P9c3cR=s$C)~abBLkO zdlm6(oicfC!jlT&XZDt_@|*)Kbj>Db3sN8f<)nBZPrBbtU%*>e(r(>Z{8G!Ms9=iI z+p?rhB%!^tAA(ib6UjT!ub%P&(cvivv?O|Q z=VJBU|IWHq%Q)=D8WyqFCO(`a%g~K0|2mY5f*kiqKAAEa<%0fZ+WCB}M|SoHLx!8* zG^jVNrZ$pb&)}N=02ps+@0HkwPB=#LL@?c3s4gvkd#5S3OHQ{?`-`(b72SPZeoExQ z(MthqIxL~427LIwhYR8C`tF-KZ>JjC#^T}kGX*JxEdX_+*`@)ELJ)9UYIWbnO^Z7BK8eok8Tl!$p}4UW z5OQlI5$2wSTwf!~c?Vxz*gS3WE)Y_Vk9!tqp{#R8+_Vl7tosz8gG~A^bFGK`;p#4C z>ryp;i8c>*se;A+uy|bf65ld32g5SX zi1526k2GhQR|mh~y(z4-OIaS|SC!Im&NjG#Et=EYpi95m$(c&SqRE4fZ><6gyb$09 zztzqFai!hKr|VM4^&j$4Z#LsvmBlk~76~DMLB>PZ$m#i(?mF~A8Lxr)R4f&3Hy=lv zaXPelU%H(*x#YVOS1N+Drg>uR{K`Xoa89dg=y*Q4#`^BFTc6uCfryP`vfZSlo-y2? zZC$h1e%*uWkvsXRxJ!0QIz6lTLQ0+T6e#POWbJJ2hAr4Vc_yEC9x#ejWl?kLlr>SX z76%dPy5GVqm)#p*YwPwQUmQ3y5 z9$lRfQKFnANoUi_CVyH?|ks00!y23`AVf2c<7-@h<}HWcE!2CNG`9FD<%c$W-u zc-^!v4nPx~5?wM;YdbM7T^ClHuU|^Z7Pw8Cfve$@3kF7Oh2%Ua+$@iaDHW1QB)`3f zfQKW{kl;MW%PGGw+l&`-oyF9{)N`5H9NVKtHWl}06Q<>358j^taCF)gxeW){qcD7m zoxpYjw6)amELwuzrbxEN&L%kRV0$h+Y+Pe4FTtx?F0F`%N{y&G)W|3c_|{Mmj zhSLp;)8LH?eJGL*;tvm}(;pzM{%lR@(44mjoP15n-AE}q-4d^E(dz_l;AId(!V02P z=D@=|Qt$=>(fMQuwP8eoKs~=*j{fS>#G)_FozNQmfYD;T2C`PpCX1XlC4e#+*X_aX ztJP0!@P}s$0F16fdNQC*PcF%^H=gQb>Zdk+jEbma`kzz?9kL>`)M&m!_OFhB1zU;r zF1BjY#5J%WSU3rzUmYmnDr$$YEJkEOF)|u7gx%33g)!P0)bt{`j(4j4_Sw3gt}u8> zSckrct$UI?<_}@YiSKL2$o@y=@%^r`8t7!9@QG(J5MP@Xru@e>ghKQQ?XI+aD7{FR z9n;dt#t%L*u6B=h?pyg!sQ-W;;h~GSj<{j3C&q1dMXj6f_`1oRuMmQ*D%xEuEFEiD zHxY;>bt8D6HR5Jz9Xw*kMuRursZqVm9?Hwo&;Q%XU{RJi?sw}^o^PkY=D#HO8w$Ok z-My~Q`*yvcZZ3Db9I6$Ov3na>g7;Ae19xiJj10>f{hT30Mk@y7UxLEMIseo|l*uG+ z&}tWCs_vx`$L=R2GAM^%d~f5jzb!EWhSdV1Mb#Px~Xk926e> zlv6Bdc*in9XRFLyq2Ei5NEHr`i=M<1c#vbgN51uI7d5L{K#}ll|c*w1Xo+V`>cXD+J2%cxs1MpR4PYK zo}!@)XpBqpU|@o#C;7}OFI-@h&0MvYr3W)Cwrdi?z0Sv)mu5Fq{?wGbYORn=p zsV?e{rJ>-NQ*`-;c}Y=?ZNq4Q$KX#x)QZo_Hz!?n)_bm*u&|$jY#ik)$c;*2Hp1F3 zq3$Q|6ngE`g+59*(A=mHeP=fyW-z`%Nxbjw0tP%fqJ2&U;lxJ@P07PqFd;ykq2;Gt*__V&<`Ikv zcK@kL+io&xW87VcJx_JE)ERsH<@AuRa(xMg(}dG103zgha^F$^@xbF=TacTDt#koK zE25@P(hrTzqk?nLLK4>qVFq0iSrtt)Q6p0##4&U=AJ<@vp2|R_Bj0}*-uLTw0d`>Y zery$xj$=d9+GuRg2&z)tq=#_%6en>tTXS{7gdDp7vAV)8G$+LgUzJxIE-f7hjD@fp$-?6kWSU#{J zMj^A)l_>@eer`B+IVkY#;$EW$(Td@T6dyz+-L51iDFoi-H6JOUj{%wGT;yzu@GU%T z&r2RM{!pLw=DM=T*yPuf&$lEhQNI9Mv0evIn(dy2<*d{x!Rd4m>=g229{yGaEMe;= z`#IV3{k%b)hN^6sCD>VUna+klKQ5Ehz~1=rG?>S+zlD3S7w@D-6fq4FEz||+x;Y}2-CS~5$y9 zmkfBsZivXAin}`oYA$Nr=fu~-rbLnJ4-taX%fB5ob~_+#Q%pP$phmH6jRnSAwRij%3Tctf3g)7@&D@-;E@a z^srV{Bf(>(67p%jFx#NIf$HZ8RcwE{lZ-A6FPe)<7RSdk$vA6tXvlFgr39dvnGakZ z)av1Zgy^U{h{)>CVN{ietNeYtf7n1FV>fgl5J($uDHRT@EbuA_M@9Qa8%U{PFDpke z`4~a)+Tt->&L&C^8>Mlh>-8kZ%9@+Wm5@V!;Au zYs*y=gA@@5e+f$g`B+Nd9oAOJ9>*(0-u!~RDqfRZ6Hq0UP=%Mt|L!Y*nXzJ?+n0aw zd;qT&^QV(G{phEk0Q_C|gJ3sa7|9=#bH|WQ6?n|j^LNa?AF|yFb)V}i@2H7CY7c(h zL>so_y&WB!*p4}o^zAE@OSOB=m|>6`{#$TOBRRRc=MBG>yo~haoDWQw&$B9`%?6@Z z{Uj8||D(+I<_s5B&-JbXRa`X{>@#l!SGdBYfjPTDO*AJnZ0 zJrl52AS>Kg`9UZy(VsS-VFfP0KgmI`zHlTBPv(rm?!=e07ilmP;kTn|Mamb00Iy41 zIgtLCN;HFLVePNuWm3Kmz4XTR-OC3(cKBz=wt2C3N18`oHiHVnOB|HOlM`Cg6AE>7 zJ@>x5C}>!eA^s)&j;gaxti#^@$|fxTJXblK@h8i2&mJc}Sja*|R1MNj)%2IjAVQNd zcP4x*pTLl`onuuW8=49TV1fBPc8Xj#rTbk!a@vw&=wEoj$xyu>Fz=qh+%-chJwtH~uw5)2g>+ z1-fpRM2o~mz4D3&Bu|n@;v9|CmTkcG?SFq$uN-r06DKnuF=Ph{Oj6rH(DR775A2P; z2e=qBZxQXmGh!YI+B4i1zld%D0zn8 zz}Mg@wwWll;Fq)CL9Kj{BLHLyCmgo=1`$#8ikPQU{T1;1ReyyT zP9}G46x0aK7*{z~Ulntvp{e|j`gn2kCIlh^DE%;}`PoOyaB4uwS?@R#YD-*ZF*Zw| zk&+oR@z|~xvgo5_r)T$@M?Tc91V^qcOA&CgPu8%6~dzxOB_cviG*sTqlX8j?;8}T+$%L}!^a;HpXX3K-63YO|h?oX%i_+P2k ziOy-~DbV;R|N47;c48f2ZYsfGEEfbD_-pclZRY0Pp_(-1QL%GU8xQpJfRXTyjwSy= z+#SX4?Wzak85j3)tNr5M_eOWRZ>wmXUAu7MOQ$rltzWQ|mz+qPOE1HiPTjfKiyVgv zqqLU4aHVjv$^r>SRcgT@{nK2?=1QiPHZTTTB@Br;Y z77DThjO!eF;^ut_*Nly8<|SgSm>VNt*(iM-DfSXVsbCp6tp+wIQnb~xl^*+=O1{^& z+neoefg#vw4s6QJ)j~I{Ris%wto#@UjX9THGt3;+QRlO4(1UI_NDb*982D6Q5oqcY zS)72!^_HoH)qH37o|P$28PprXcZG1nsWmxJnN>AnwNHm{pGd`jTaKFNHh8)e{<~OE z%Ee!;6)DT84u-(0^Vt;-te*Eh?1mUc-f&jq8Xs1a1^(zdVo{(M2XM_;t$jLfbt*au zC3%jvF&NCFYzU&R%<0{t5uE70i=p5pBgwBakh!Po%jz7;Tk4x!M5t7BAyi5zcO+>FN`?r2+_CQoV?Nvv{ z5$e&iu)Rm)f*bC9Sg6WMkij70ghOUCm#G$_J!Y$SULf|K)8ml&1RI$3XY1Q=gYliG zy45ayqB3E4XC=Wv)xw@%RMhpHNU$0*O`}9^eMyaEkdr>PL^X5|tPDP>#>!lX6=Vrt zRS+S?cYQZ5b|BD z0oQ0nZf8_QpqosdiGF-G0tZjWJS4(QCF7NMB%Ct!bw?DDzUU#_JjcdFjJ8DsDO!mi z@diFy?WebxLH_I%W;dFHB5$m{v#ZRX`g*FbDRhl z;YjK1Jd(JkVl{Dh%`4^G%__ z&BtMd)v4r&Ge0hkK9(1`ONL=x;K;VKX)WM4@@%%YXDm;>n&Vqo$%(AVSW{4iY}jlpHv;75D&{yO+mI%%4` z%Z~0Fwh$&NgS!FB$KR(^m;frbio>jhM0>p~q%PA6lQhYNIhSY32BUe{h^V9(_`**C z8^Y_}lvS{ReSs7`#Tg{C2MGStRu42a2H=>>@tiu%qc0>Q!vJ=zxO0JgF`Tg1yCmAs zc6#$DnH$B9rM5QQWE2Zjle-B;nyrbkfP`3fmB#Fa!0V=KX)~=GG{S6X4xWJY@|WQm zPL;hdM;HQXbv_pBCkStD+ATcw>_SctU(1R3h6cohY|UQ$j6xO5 z`OAnET&^gARRmF~Sp;K6en$saTPx^Ow>jB`Qf-f;Ogq%C1JzW1ITas-&M5lE$Ke!P zr{Axj2eZi5$#f9{4l1d=Q;byBHdr*<4sQ)~E7Z)aZbnm?2x|d15hp61M zdbfF}tHF*1+=j<$oRazay;EphF_H7F&KQxaierc)%M$`5scX9V_j+Rz2J?BO{kFKT zSxDT-C+I;p1z^C$QzYVJu}aWV?-J3B1H>PVaG&XpGFE9Tim_-^W{+7!up zX>O1GjTz4BYXW=Ncce^Us-^E-^+j4tRlaJ_i|vedka`hg-QV0lC^KjOyc+>y`JQoC zzIXse*uaoafc=7P`AdM8Bd~35uXt_(MXtmmcf(elELyF<#cJiEsQSHAl=A53GY+a1w};LIn5N`F<)Q&n(%&Aswf zvpIqmf;eL~1j>~Y%TcVN;W)9Q-y|14JOlDQi3l$F7qPFW2)PciZ-%Mj)8Da%f4yM0 zQ*jlk^;YFq$^K0lO3_Pf8$e?<;B8h%%(p4zR_}4>N@96%;rhEtkoB^_e?Wz)~ zTHE)VPxB7+u<<`qpaP5+h)<@bRHNdtS6~BeHy#>jI8(E~rsc>H7}hBgmRB_SMz=xJ zC9HXLdZ%A_?#SS!C)KdlN$J{xKDIDq-yxkK=9xM zx8Mm7Bshd%!6mr61$TGXpaFt};0}R*CpqW7bN};?3Q6xmrPexcXgHD!bQ1d z#oDWs)b~Ht2i0n)W{!E748P08AS&T(_e9Ifvjh%d`rqxiu;z-LPl))dpEO>IQJh&T zUQQ-xqU&-7y}y(HX8S$o?RA|U7fzYs^;K-*(KHb^ZbuP62Aq#x=@)ONYo7_y zQ%1s9V%0hkB}0sF@I_1>XHAW9P3RWhHiWak!uCB|?U5;TtP!-@9$i9bRK;{6LsT-j zQTv+lc-4BEfr-~Ta0`1I@NMeJP2A8~kU{*O=K@T9ab;c_s@o#cTu~@wj~W#=!#;^F zC1CS<6y=B5ak=$j;ndq6FZMG1r_)TkWFXlHq1An?<<2yk33(8aDMc{cz@8PIz1`a@W?hzBlSi(84O2|9_10qk7W z*_RxKqrl#5R}z6M{%=87HG+COHnq}rXx*O;Q&A+3de=Ev}$GHr$HHS zpGCq1gK5|Cg@l=b?l;C0EFZqa`J1o_l@CO+qQSix@clN1y?zb{c+~98#$6)34Ig5r z-7@IU%qT8&Bnde^;^&nrd}ev~4lg~g*cx->!Bk9h5BY5q5`Vd6?~)8pV6NJ7tl$8) zt(Y0f8Us8F%*01U#FyD}N&-2toqu8MrIySROgTsr zi2i*s27mmX19$CT&12wN@$CM{w_cICuj7_C3oW&wtZ+?)8ga^yAHaBN{ zCZc1EnI1GIdI&A$Cw5C27X^FuVlSdnw{Rn5@7 z3W>btrG@gHtkp4CKw5$RX*1N*xrlAc`sEbWv2Bx>;|OKeE;spCro`A#D*eLd$S6&? zZTz*G=e$yQZ+P(qUioCX>gQxj1R?Q;aRdUYnwu*HGEuZAIeZeBXe(yhOnWRCV-A=r zB5MdpodSs!N3JkN&t5e$1H-z-u!DlPIAEA5LXVGZ%5uSbaz%7bkXsK>_sF9b+THRo z$l(Ip@%2d{1Ka1+86};BRYSIOjGj&TVtc}%mPrLRk%~rYp8TkbR?DFGdJiyl%sAav z>dZB<$Z}t&s<@=M2AK`o;p|kGm2%QzI}mO5>$4sssa&`<$$C43%mM6lb@D&Dj=JOcACTy$x{L8LGBN?<154Pu8HqYcAmFy8!&|Tw=ntQW| zy?< z%I+Kr#`+G=vp38zRW{$wleTnizb_BX{i*w!DZ6?#TsLkYn%dp+?pzgP)}<3m7sslA zAX<+Ef6T-vp_!@w;rhyhh7#j>)EA^4rC&OV8MT%!RsARUl;qz|H7o{NY!M^C!ODv> zoO1LD;^Yey_68<*g=6L+s+0o;9W7f={$Ff$*!sf=)~9@q?soUgKSJ2bZJ zGQSB;<-D`uaPYyafJu;6C~;kRID`F(jms;nOEm6Gje3*o)D9;Oe{1nFl?V1C zJ18s+_zKtXLrUpR``P$+>$Lt6XXGX&nphfSyj+yZK9$6S3zZGv*>7KUBGBjkzd=(F zw!bB>Kl=oW+bw(c(ar4cW0D#-7aL27+|s1_GGuQca*OKJ-%zhzihDL0KvC2JFc0ak z6B_+Jg=W9P1X;daRN@7pl*9ml@g(vq)xKc_u=3Egisj?M_DDZ#$|tBJ>1JLZ{A*qH zkpAh(cm{vZ6hRdaL_2+7uG2`A1=&A9hK;-xg3-kimK`%T)pCeNHD~6qaM} z7M0;`v-T}{yXcs?AETY)Hoks>QF#w0F9yZy9xo2Eg~O*)qhn$DGvbP zYzB}WgKoF|!2|No03hGrQ2&@6@6fS|Tm{?#KkpT*XSz0QGS+uAFH5Z^X19wcTRM~S zmde#8D*P;frj8>#gn|!OOn!uVUVC_ahvCLXLap$F%>jEXF+P`t_$%UjVafUhk^-#5 zi(`Cxo62Yk;-NVaKE}FV!lFoEuKo|j@`23UIrfY}R|bsQZVHYriLeWK_?=4xuQ{O} z@)&YDClC#&_xKGILi@koRt1MP?^@S?X*h)qtzEzZ@6?o)B3zPAZr5tU44k-mQ zmq`zGk@dtZo{{o7CI8o3adU8lbd+W{zAnk6GU9kLGE7Zhv@f}Xvv#1)R5=3)JtWfP zwQ$RKWURS;&M`Wy*R2J6rF18*Xkrx28Bkl?9SsL5e_sg^?~iizL;Q zY@_NNMd?Lyxun_p)%G}VOJt`8%G~~NPS|tUXc$aE0QhsD?2Sa~LBan=?3VTvDi!g0 z5`oJ2;^~QS#m&ik0coF7f1|qJcrpaK@{NM#97P4b9z)>xIjshyKujl|Tl*zxRT-e{hba-%!zVm^MX7bPc1k zm#*B^D?a!ibxo+JFqp3P9DS80LNz8{_cbnvG|K_(Hb{~#%Q_BXf$qH-PFGTopQWLD z$)0kfc)GRrGC#U9(bx$AmTIDzRx;WE(qM~?9}?i&O4dR;a>2K@{SZkGdX7Rsq^7VG zO;`uG+{os6T}6a!GmKTf)+IlqW!kjdUVt_EqSKqvX}?9P$A2L+ee z;ANnn5w5D$!EFStqx@-xmCjJxo=mO(8*(hHiFU^M2dJ;oQIFmN7c!TyS(55riGUS$ zBKg*0_M1+h21nIh{KOoo1+OX6#hEo2{2Zll0gTmdOqtL^MeGt2pY=?td}8AG=5z|L zF%%SSN_!B82u3w*uwrLWlyZ4sGU^dJN4jWu6bXBeTon1UAtO@sRfK7UYXfs(R~;Ng z8{w9@++k);okt{?j%S_`IADy%+)q-U@8E8E`|2NL2(z{qZhr*93JoXysQ@ ztC7PQ5*)Aj1*JP5I+}r7*#&`p!Okc82b)%lD+B(E{u~IbK0SWr2Oey&K>ogqTStU7 zR@Q63H*#6DAEXJ(B&d4^=ChH0!tzwq9E%@>_CE|;_t5#VVNj2PwOGl{NL*a$Ia}8B zWZWrUOHbYCujA?F7NwZ99WQX`2UwD$v^6b`RY>@Nh*MeZ%_tl`{RHGN-^Bu+jG4sZ zvp)g6I&X6$?rMmx=(8KF><*}05Rh0J(kaj4~qBzY2{0yzL@Ty-|0f0xe3j}Ejmx9XQ-C&P( z&RpL}_kpMiA%3<)jE-yS5Ju2+_w{5kfR65(M!G=3M>XAbp|7z7O)Heg_KhZHA&+Xh z>>X~sA#Og_TZ>;rI?~r*v!1zQdlb79>1}sbY2&bSV*O|NqD#nlr4IJ{3JlpGosl78j@FaK`Ct1<@vd>`nAuI@UXDaN ziFqc#K(xM+pbwf;Ok_v6RO}{lQoD!Bz#)zD>F@V&V-+bf4=o;+v+Sa)hdmOSEfH-aGQhk zJ!2x}g*4zg4VsU+&%sJ~GSbjK7APk0X1pe@o5$>yDSfia>;$1hnc=graRW;;KF>;V)EzE90_v-qCzGSaUAe(r>3;M*v;&nB)C`i20s-~X;Fb=65l0X#rY6-FiWoxwYgzSFQi=ZML;{k=Q4!v7evCu?_eBda3=-f zSig>h1M>m8WmXTg0L3PBzAJ}<`9F#z#Xo@p%Q!RC>sE;oCRJr;V zRF}_Q981RgzUPML4; zW8UJ~h`w+{eY2V>`>3MV{;g{E)?*Mf*q6DywywM-Tya%`%nvMCJ)T0;>mJ{#QdIb& zbmkH?>*sYzOp-nbn)qyaH1MJz*!zU+Ju3 zjqJ>8UnfcLUZg~Q7?N*YuS<%OFx5P{E0rTqC-fB{*TMMtSmztk?)0d7Bs=rtZpVHG5WSfn#uc z{vA?|W`3`xy7RJOQ6nLJzQ$B8?Uq(_Q0KUn?zz4=?dpMer<9^8iS|2|&(={UC!PG+ zP=b*`3HCpFu_Ba&e|Zk`XEK%n0QW6mVfrqf1ul zj_=zR*(RIfP9H#lvk2WygJMV+ilNB=`f_WEV9_Z689FF}NMc~s08n=<51OPnioH(f zGq5FzxpZJoHosd! zBKFHPY~h)~b=vqC;V`0n!t|4<-6w9JM==4s$!vDz>*f8Xhh;qM&FY6WO{{59XeIjC zYs+g?bzS`!>A6>Yml&OR<&=VJQ!o`&6nVUa^(+N`F3tH(@@KnGmTX8x7$EAZ_ZDw4 z!QHj)I}6En#yMV-$@(Jd_Ai76p738vY(nGV>8pS=Etebb7JpSmo%oIqWEo&0OO0WU zDkTiowWH@#-hBJSH#~HTHF5W$ucQ|N$ zQcm6I3^412#-lTqNWF*q2kYa1hsOAy$+)rMa`A>_W)Nz;)S5!^KVDM+z5nJ)5N(P4 zOZnerq}Qf*D?+|=kceRb@2PO>=vBhL4v&`KvB74Vi3tS&hHS_U$siXT`1iITWLTi$ z_ghlEvcYNXJX1wM#GmahcY!h1o%{mO&)=D|T{jl-d_EF# z5m&0S@Z2uPL;Hn(2H)y%KQ%x_7h7EUG%%J(#mLF?#(IZ=J7unP7S7JGN0p#pef#?Z zQL%N1gFIqD$M<^<&tG1ziqp98?Q2#VbQt9ERZ-&)bkAQdwtSALJnRfKp}J3~8+J(y z7c10Bx1sAiLfXztZQJoBu%KVBu0l;EchUcnwcpiymSR*_mQx}7a^pGbw>8gTw4URi zSF{c1ne=iz<__*%^1`e+;Lk=2%a?r?@25YhF*Pn-!ItNhDzVy5WP zv7b22Jm=V%-8%aHGPV8bog(o14VUhrAjnN4vs6#J{=Tlgt$sG}$cFCPa(nt>Y7BH6 zqMz!qg{+=5w`nuM-ece29!{J%W_K|9EX`E5FQHq6Ps##mbyMj|=s95k>nFe9ttxV+ zM#4?ci;;GGci_G#?Hfp}%I^7zF=+gunhe)C#v-sl{j$pL6#OfOK`V#ESSs0Dc_8Oe zE&`dd$Rz_YU~a%y$_>+W;x5594{K8<7egJX7#i0`;Iz}aiWwiaeLG(A8i}5@IPmUQ zr?dSCf+SPJue%rvQZheFX%GDU%F955R~h;fx<}jSBz&$ZOZ;hqY@G|bGhiokOl8-! zqQKyfk%l5?)#yvj6dy$0*qy4_FT-@_IWSNNRBu*63)LU{KfL%xGjzByPCTwhZ%)H* zX1g@=UM|uW{K&{~KJ?2DeVQ3MNB+b^ znR12w6VJ=-Ilexu3I_ZAl6V0zp z?>*X(e>ehAdy0Dqx5{vS<}YV#%lkORQM#G#uN1*QK4{Mo7TW+%9f_M_IE&pzQZPXk zBk{JCqlAgrTcK3~FLr;lDZH|{OQnr=qxzk{E4rep!aZU!56%ae$+3xS)}TAOS)rLC zZUKxFIS)G8p3X9d{$K_@1_G3Xgcqt|*07Bn{H*Qa0k{`A3Ex_VJptY4{mwDv6yyG2 z4xe+Ar%%Y$Ps%3KT^g|}=d!g>;+XS8$ffd)Rs`#40b(i)#jjB*X# zo8bI-p&15JF45|Mt8ZR=M)$wqB#UE2kKB`~o*ObAeA1iN3|wP5-+uRm+^XvQNC<(( zej-2_v!bDI#Y*l}X+}I#ol~y?_Pw!ru9HD)XmWu z!08o^_U5geJC_y$LVqUlk`?iWBvh#eWq~r04*yFUL&XD2_8)>rQ31f;5;S(VIh5AW zE<#XK-D{{2feivPF-3lUmqr<>F+{gyTV`=nOE2(Bpw%MefIlef0qv0FG%uWSDN(bX z2)%3rUQ&1|KkM~j!vfqmFP?_Yx$eqiu$C+cxz0GV1lNN@MPkP-7{*|>E26CNMEqgH zED(TfOG5Jt~{y?X7K2q3-V4u88n!rbj!0lgojO>hT^FzaisZsfk(qSt}FIy}%i=K^m zUg_Pl+D00UHWsPq920<{uex!$a4i8D(qjw3d z!4(_Oy@q{>H01t&kof-?EBZHqH0<%=#Q*iZ{t@;6T?QrDSna7{^YWPhPT)42bjJ;_ zS>OLj)~SA!e(LuY z1)-NFg@OVIH%$_(Mg}*)h^?nr5?|Y%Vrsb8G<|w%=Z_~_;+u;pJ-Vg_dGqRpU%QF8A|jQq}`z>BbW|t zcAwAXKMuEKBcv}=9m~84sOLZWnCh{3Q21)*tGfH%{l{_+kV!^Sr^{huWy0Kf1$b)0 zzSj^d=Z(FuZ=O(c!a*M=39KpCk+-#lLo*WC+ z?UF2EdhWP!X}u!v>sP_HPU2TcT<`l;6}LS)wCX$fn_r1x=aR2oZ;W`qn*FxDJ~kBO z(Iric6($gYaeBn+KIPFFJVet3xbC!BphJ3*yRD1twuGmPGiDdb}QVA z(!u$Tj_k%vT*`fjY|X~D5!FFxO%E_Kpw7-FTE}1%S$hdV)ZI6NJk8P2eC)G0))}=G zQZ1SJHAL2U)I_fQzam+&l5j4dYd2tCiA-$!-?FFUH`78i>fkU|cm6YaPX;!f?q7Ze z^J*5aY(OGAdi?>2tsTBbCm{3bBDM;3kkK2i9F%>bu__LAisldp;5oRgv8E6@v8@8; z?9grwHAp>gZ%bO?M_u$ObRisk3C9!+5}|l8*H=V3Fu?FlYAb;~xz}lqtxfea^WD6a zHAC$E+f^x6gQ6NCYw-m!y!~mhkV1o1Lxa+y%T)#6J>&Fl1dZ_W>3TkQZUZ}M+*4AO zt*p*xal3nSraorJC0z2awtkGmx*}m|j3J4yPjC~r5FD^WUX`b2T-T&na_`}0Kjr`6 z43GyRO~PZoK4p2bl`TcV&My7%7pnjg>(iGyQaSA0&1 zrg6ZzkV^|n`yzpZ38pHo(^e-D^-MY0jzB-8&zX&|OCyq8g;V>#8taPrR72S$`S z_6NZZ9*2^9Ophmd;PS%U&5$Uz4bEV-4jYeUc8(C$t>~()b~`k)P`0DiTvw>E6$K5a z^;eDTSQuFEsMYq3v?nzQM{N20lX37{Tk9x7-&RqymCvF&r67Ywj8CwY7||aX;;ePe zbPVr~6b2b8o;|XcuVu`AD2jtidmlW#q|HUl5LVa)_l&RJXUG*<=`dL&qBZRD)0cJu z|9+@20^xx&iCO*??+Nnnc==Ek8sAEzB#kox5F^!~Yy%Mo!k|w>Kp>>7-&}+kcB1VM zHdxGi_Zn%E$-jjD&N{k|!5>3B$R7YVQ&O;+^xkxU^tNv^=0A1bn66r%T9q8Fp!6US z^qcPR0C}8Jz4K`;k^zTx(Um^99Rc}o!;m8cbRP8O3%c)Lj@UOpN~(2zel|B8X|S~V z0|;}tycFgsc2#OyP3N!>5nxZrZq_p#>U8q9c-0hxrneKj`q^{N6z*B&`qr|Kd2VS+@pcuSMfTQ>&n zBz+H&`g7q>zzWW~4Vp+kt)v#U zW2>pqK>;s6_U&#N0tSyX6H zlp-11si=_1AM}L}!rDWSYw1_!oU|eL$StBQ$x=B5OE-Q5c<_l0O+o4cf{2NsBh{kL z@dn~AaqQB3-y4fBfvgjwYmo=FB(KBphlG&x%M41$&P{{fSOgMo$k z%KqPVw@rDR{Z4?O6aKr&Z!k2?S%d)qJJz2RLs|TQLN6@EIafeZmjVDRf~sJZ4Yieg zDj5spw@rdNrDY7N3#Lwy)GC9P0?FU2X+5G|5-h4k*RsOeZI(K3gWKbxyKXkP%v(iS zt@H4M$yRu9tTpATEnr0-1^TXKHM|M>A!{t;HlK(I+$&B531($_OkAI_C0KRLiC#Lu z@-)+m(`GP>BqC*9!l8Hy%TqCQxX!~;9$V+{2caHVj=Nks6G8UbzQ&~-xgFALN_^L9 zv>EouukK^X-tRKm)NCZ9^&l<4b9wfaS_(O9D zwnQ4qf2mG>F#1_%`8udL4uy?;QP)nQ|3PJ#NO>7DfasMLY+~V$-|cUOv^KRGCaH)Y z;(n$lQpex$6}|nB=b=o4@=X+6+_3==Lst&~0t>_Kb9DT<|iso+C= zk=MrxM-6Hun{ubK5c)(5IkqYyFhu@Gy5pkN8L^Y%{P!^57C(tT|0|c^Qx*Y+U=eA` zpDj;rEN8sRikhk4jPkWBgliJGXgZeBJx=z%*dDRfX8kNcx~pj}Ftv&hYuPP;@G)w* zyda)uQ}FuCNo1&kT-|rNEFZiyBV(p~wvJI&41P{E@v||Y#KF-#lzP3J`6E4N$JvFG z1l$i#)f>*OQuNzbi+d&2W#Sg`7gDn-FcYywfeQwnK2KM4_7acix5P5j4F}95TTJt@ zhOMTy*>T&Fb+g@{j0ODZ!q)2MD8(SH#HDA4HhhZ@9VU1p^1;|NCUd$NdBU$3{rRqu z!-$JG`yBGe#R@3La+_kAiQV2>*0GXOZjCSXcPdQ9vRVC_ zEW2NdB7GTm>z0t3Z0~B=!8*V*&dYKZ$Z9n|(cvlMBKtlVvvBguWDoa7$*CHy&H*@ce7c2QfHPbi>uX>+d}~{&Jb;3H3$8RuptGml|9Kk>a^z znvz^an|)#)6$DRPB%VlAZ&+rqH{a8}PUp?H@Mvs+nr|^Zw`ybCLs=o`G3XKP_A_N` z*5zRVaa_$+*9ndZxVv7Yt;BIp+^y47`=>CMZUK@$m}%3`3s&2oj1M{Th57IkQog^9 z>Y?kvdc*hPAgd>H)XqsbwWZ20cSvg(%w>xQlt2x6u$@FEjq<;@QK4FvU?iMLv0tzM z|1dTPj!wDiPp#r2+~eG+Q_6Mpn(Fvl%S6J^e#mo>u!T3YM5zE^ddaeI zgVbl|^LW|hVAKs9;)&_|1QHRZG+#VD`R!HPPgmlNct5I#^*Lb)vu!KZ$L2)#>W$2h zl{oA2z8&X!mwog!Cu+!cnZ134xsXf6=lJVgc_;#r&}mi~{MC=4K{1K!q`?k8u>^Pj zp@-||-$VJbq(29D#|=uhb+|sM_$Ynvs8|bt$7cVaC|#PSpDZHw?!B|12w|_Mokvwp zYd-@iXhZjk05ixwRq#-QLUK2lao^KfT!O83LN38}v-M;L_UM&(IOd7qsmgZb8^oEd zV{|s7R9NyZI9=@h!8XLgnFxd@qj3t&J1_o;n_)E)3#S_}`@_6TM)bD%~hB|ZzuCZ5gelmBA#`4fRDoy*a z)A|=O~ ziy;_G);+9dfy6L3Y?#kPwdpkj(#v1?3WKy@UF0G&I7M*k&u5mj9HNaIEuJ&K3{678 zOPDeubVm#(pxHnT7%TvlSGSku*4-&>GTWqxjBDpnm>3T>>S^epEKfaZ^glgRjN z*<12oGjSqt&bsE)8tdQfsGeJGeaDtu3c(?s9E;*U`$|%S`y=r#*N1>|J=l@cn6%`M zwMy8BA}Hlc9%8(4v6(s>Mr(MI=Abg6kGaO~;tjtUXmCMID~bd(+FCQDaO>`R&2W5y zWMWBA4w6@j$f8|XqJd`eLtel-C7rVwx6#CKewZAi-RVR|uJ`|r`85xG48_?HD3b-{ zpOrSQPAIZKOU?>mG1;8}OiVWA-|rS8Y5TjtE1nCg6P-q(L?E@a6bAq#U1WyTz|7fB z-9T0WE;3(`(e5c8;JN?hzN|DuSn}A}tXru#T!|=*ne9|q?;A{h#oIR&di1V*h7yV^ zfdRprR;xViKiN~&_4_tpJd_aaKU-j1%0yJk_nfMb91+ z#i5r13mou?#U3+>ybHG%OHtWnckNKPb-uRr}p7NlNFh>DOa-B zyuv$?KP+RV>QmOfkS7tSXfy_T>(P^Q>fn?k*iA8z{MdgZ>mVb&plrhZDckjulTzKS zw%NMKad=UYCCw-+@+FLmz}qA9B$^SVpBjS{#94cMIbA9kjFHsoN}mqM5FDF`I0+sR z>?xZbuxPM9Ix-mLrKj|Tb$%C&A07#G5#EJ4?S2wMy+-Vj<5rkf;My`RY}h%M&o~|S z@2kJsMP~-fTfM786Mz!42};a=vQ41W`h6jJSt^INW&yAM(h&fvboSH$@Rzq?&<61K zvBRHsR2SJQuxZnJqxt0YcT_WtNcks|oCl) zq)?F|17G}z6)?VSw>3I3U?u^$a<7YAmTrmRSQ~+EZ^IhpJq@Rc(2Bu6n_o(LVYO+` zamnE{Li6i$qse5V?SFikE#6b_{&{Z|*=;7>QS-g7Hsqq7V8#V7|ERSU5h1p<*qf1- zryA_H9WTGI#Y_K<4nO9EQ6mWbu31EsQYajho{ z^zq9yA@y+YNGo0xpAMIb=DZ1NaoFA;?N8T|#B)@tA;q|Ld5U@!&YyDEL}2GYB|}d! zw0&5^cjBg5)MjEz>TjSdLyPbt05NY*A$GbnnP2tWv`G`*@#jOK>=Y38Pk^E zoG~srS5WF`9Oz~A^urIDq+xuOtUKx@sr9#db~k*Nc^Kb}*sa0qyoDLiHkg*)vEg2# zF+rgky*C6l#iu9;PoWSTLLvBX%Lh8Te=YL<9y7%HUl70%{uTUn5ARD(Oq4T!H=`Ff zd6U%HoOD0peQuBR(AcU(@Pg zuuoIAw4+YNQ@k2@dp5jPc>AhVX$#|ecmjmt4Z1pyD3Stm++2DEGSU4B=V{_rue-UF z1=01~^8`Zil3(X|A#sx{vTMcHWq1w7)r^Z$D@rxON7u&~IC*_C9TNF;8lddN6a1P- z4Rb3z>?>>Yxwsjtm)%|lOmIfd(T4Bh_ATmRMd67;n}JX9&D17ax`-Oe5LCf4mPlij z{lAxt{Q%9kk2fYeOXB|`HFR=e+oNOrQw4kZs8)MM$m8&P{<{~6edXW9MK%+nhzDYS z7$ly@eq0?mWU&q)ks+1-l>!PGw!EO>_D%&pHiv_MXtQ=s&VkVjp`{1JQ@d|JQ9pfA zs7?5??_Yf3!`W(K6LiP^W2|v+m*keY{R3}A*@>{}h&x3LGKJA6wa1i8X44yw@RjK- zxG#PjSKS&nQ8C|g=v|{3j+v4_f^gM+fg;kq57B+gEo5h05O-%XWt2hG#Bskq5kv+a zZhn4*5LXl~sZEiq4Go@rmOV#>j&B9xC<@{LPj^V{8jcw3NB15WUpLoP*rmJ^?A(#C zUCoI08wor+ch~?*#O+E157TwDwu#AX+Gi|T0Y3{P9*QJYkSJklJA!n-vy3CY6uxBn zNI`>8jwdSN9Ns{ub=Si!`<+Frnka2o#czY&S;EtIeloM7o6ZjzOH~#_+uwO$XoI3F zwsAOhDt>(y^VwDxWmELlGi{2uC7e<|RZUu59!jrrKT^pA67Yt9NPvxc2e)|nrjEWv zZX~btIP%TrwkmEF2N? zv=QnXybhhUhNLWF$>C20XWFe$iKO-8eL?QZ)0UuUAK3mXGKF7rS{bCJ-qx`K-$t6* z*7+_i*A9cKAg8<{J;;e(dvB5%D@ zZgxEMBLn@E$mB)&k4-`+MBKVR>_XeEC>uY;1YmG2rEMs7JiH5}coQgKfU@JcA5BG7F7e&Jrt*X;RL zi}4~SG1Z~xRzg=8C4z?cK>o2wDHE9;P8f_|V&l)@dEP+WtX5-@hetv&QaJ)Srjz`= z^oBLh9fe8ws~tDb4~bM&>57}`et|4T%jZQVBiJvpno{_JqC`C>>Lv7rq_3S8dD+FUW?F%aNiX<(=ubY5 zlx|)Z^g5M3eCKIL$+TzQx>?R(xR5MBUhtr0W`K0%=Zo_tIO_TklO#1F`FrFCmb=u0 z=kix1H+OWXkC-2`sK zN9w~>dw&rfK?Cw&GBj&-H)A>icmx1|bx@}8KWXt$68+Ig0g&Kta)A#1P8tyCFVgQw z`?!-P@7sU3F-$wR(9YXT_AEGFVu%JWav3~ZHg!Tflx z+90kTZ)*-cow9)QCP~8vtDAAfKR`K3-D@w*($ z+3TaOMhfu&_+o!#Mkt79piB{#e-icoKXyZ*LR5r|A2j|eJx2Z+MrC}>h}=PefG6pz z&zc3}+AN`EtPZ7xn&+?G2RYg9>K6N(Dze3u5+0K)(8T3FsB#?VTUn0bf2UG``@%+S z*Q(gr^^(v0}=%Z(7bl`k~%GBe(+PiuTCWsxdY`h<3LU zp&vf{Y6pJA(!Q-B?h9+MD_U?ITby2`On$1LqB7Y9?31K_-vGyO`CIgDtGwMEQMP~&I%nzQT1CH(WbS&H(>!ZjR3T$7vm z@(`XXK)XdYc<|BjQ}4agh2~_tSL_=f!?gwz`%&|fQBAFKO}>4*TveX z*Abe&Kyn{bgb>mT`J`IS^rr2?Nio$|)xpwlxf5_o1W>kUaRBL0O5G8SVsIH*FR_>0 zcKG7yziHmRr%>{RsqXtR4t_HbMOSHbm`Xye!co#lX-2XV6T>kQ) z{?&9bP7kIzi9e=egMrPJ;dG8ayY@#*dz;WDuNFDw%}~W-E7M-apYsfX7!V=Fw)$M0 zi=|lk-TPeh+jS+MMmG1Gp|t>t)T9h;SIMINZ2ZU2r+{srpD&VUy}bcS`JD;$wy}X| z0&s6177O|)UdILYz8LMV``1Qo3sSK>18ykD#SL#mw|+RmHqDUl7Z*$=9HeQ_CE^j_I^GJaqf@JYv(_|$$B;Khw0l3g#|_E`RrqkIhoVOl3y-ebeL zFe^3e@OSaW+w%Q#%Bp}T!dGgL+i z;ih{$sPBaYl<}c^jWT6__8P%?P%}-S*1rukPAjePe|Q{h@0()sr-m>mflBXB+~8~v z0K^*B&B^}Y5<>p>{?SxKjh7Ldg^-#G0COn$6Rdc|`3qKF+^Id6BT9<6E*CGm0W263 zgh6@==zGA2kJrD{-Hkm2y(w32-|S-wqmfpquYH4;QR>9o5Uw(;fy?_WK+H^D)R!M| zzAeO2<~miM*7iX{>7`zea`gPt;PqAAu!J-srb5Kpl3OJ>N!1|Zg_AxRX|}6+%lVI3 z>ERH_Y}C%r{ehZHPsJuUI*(7X-QK;+jW^ck*QG)nliraY^7+&4bO!adK+$s^=Df>n zqFQ>c@A_tJxxKiS?eG?j9oiwX<3&maifUUeL;RG_yjsRd>^IXzjLTOSrFh}1`CntZ z{$ejY*evxSz=@mW|4QAOF)~yvax_%}IJH+RiX4qCFyOT?9?&_N;m{Lk+P)OaWYJqr z0f^e(dJGr&GuIb9N;ae()cA-xs_gBzaGZL)c=3E-Q(pP`aFmdgX?FJ8V2*F`{FB*t zP2HE3Wo@-N8rHQ=yMb>Sk7E$#A6^KE!PPV%a=aErz^i+C_Wq9B?6vPZ)ENZjKq;!R zN0GOzpLGtUpYtw=Wo($Dw)koUDWgbyO+IbmopKJC1}I;M-KFooI{zb!B@(@7X) zUqg);;7$P>*;JP4CO>}ZL8(Q-W!25YiHuwx_T$gNRc04GAHZzNf3Rw?oF`Mj+V)P< zewHN~_oM-e9^P1bP>T+XxBzpD6lPlnIz_c$J zZCP4>f~5KdN?_D;ELG}ld7f?;{%ZP^v_kc8KYtqM$=Tp~H@IS~5=NWl?^Ir+-S3JV z3t<-3IU74CbI6>rYq>AWlG%fkXY8A<8Hf39C4HZm{qdk?6)*+GP2@k|<`0a2Aq4=Y zJ^w#N)V~eTj>p5f}vFQ)FF zDSXv?%`V6o{V=qe9&`q)lNLIbKyy6t&L{ojFTrwa`}_em=1h0^0SL0Mh|4T9WYf=84AbwL20N`i;0tBE9P{5xPgdEgE>!5OyzpW6o!+l^L zP0zJ}LWU!=xS9#4%4jFz3Np^zVnxw`psY-D6=RZV9=f$(7=1xn<0Wf7r=wy~CJ`Fp z=SZQlHCqYUwfG@s9J)>u*T&FMX1Yz{w=ae3=EXrz}5U}1pV3DZu=qAl*(25Ny-t>_K1e)-D?1mh`Md<~os;xfJ@0ckWJ z*kS#&iVkmPcNeZ0+?#?r$dR#35x&YAdElK$2(OEQSMi{6tEZd#I(Hup4@1vGzfW9p z%$ujvdHyf>T0eW=cxKYfSN?JpbyVx z!jUiie$qrY+Cd+YHEe~fbiyj?Y}TPrk-tQw(uN5|(7-o=E8a+Z0#WW$U)VdTAE%C< zlih5%mId&7QiGM$Iq6`+3kmi6dOC!(=ts6-VzZ6CWh#cqL!pdY-;kaM{zwR3U23r* zEzLItGJ|F=9F2j819&D(P4exEj+Lp3vf?3II~*p2oY)U zk*sGn+FDZIseh!haDApQ4iHOyrn3;-gdaEK?07bgX1Bd@NQ^qxuG>M8nm0hSHCH(K z>z$+f^`Y8m-4?A{uFCTNVeBiw;@FmTXK;6ScXxM(;O-JExO;FXXmGdSPO#ukaCd?P zcMZ;)Wbbp|x##ZtzQ@PcFx}HLtEy|&U#o2C&%1xyZ=oLPciS3Eys;V4fA{|xR+RIxhtLrxt-#tX$4@l12d=-cE%X+*--q#QyS z8o}?|XxM0~dqJOG1lfnK+69Mmt(}pqi`3(^bz#stU=Zm8MY7*dWIM$S8A3X;3BB93 zy>M02RWVp`xV7!2LE&c22XiFZ1cCXSXr|)-2=!9GfqWiMmEC{Mzu!lAhcTt!e^IpQ zB_B6oV-CB4agH>d#EDU~;!n*1kU3F*zgIvvAR#{SD#^C z!D!FN>LpSr2PGtpVXvv2X++31w^+s$NZ>lBQPjEB zlSs9TT2ap;=;c+Q7gAo^8?6th@Rf5PoFsy)lg}hgrY^9$KZ`9UHX(ouc(0%cupaS1@OZS zc|&|SkMbKV0P_~?`d1D%UKm7<2-$)OJ*bo6d_2524K1@X~ZPK+buyl%DUGXr8MDjPdD&07oyr$6! z6HBu>>28XdD8b98QqF3ajsSO>@OEm?`-%65qOefZFrs+g85!{VFbwt06;@-$Xee2J zU0{GrW%)Vjo1u-@nDk@wTQi}A%R`~<*`}Y`gq3|VYSJfCYfI}XRNx~o6C55@eE+ZR z0s?(!2Pcf(8bG&yG#)?PE!4r5hMEI}SIsJSf0^4eff;qmJJS6Sf9PYYb0(Q5a*!-$ zi{@(D{(G!8)ry2c=u@%t-*O6)WqhOAUXXtUhwj+9*w?!=cKw$d0a!Bp;lcEqrncxd zOR4uSKDxNlYeFQ&bTl6zrZo`1uDMSpOsiK)Yw~s12dL0ys zz4VF}HMKECqm6q3+tuiS#f~s4+aB`UIP?U^ZPj(}gnd_TV&rrTnpIA~ zear4uechR&76*11yo^6C+aV#E5=ZpvVn1BcK5)L;Q>S7x_$%~J+IM?tEPXP&L8B&L zR}dSyP5Io#kou8ih@h0j>QDjQTzlIJX|#Df@8To=e6-?gb1HIsaWi*oE5 z^g(w!MVCSDs3Qcdh`lW<0t{X|zsJg^0oH{-ys-O4Q+;|ULo>rBlY89sFp;H_vsY!KY*GbrH{!w>_VS0;4gbbz)2CifspGy)K+ z+9|&%I-}2i#_a`BixK^Pg?Vh$Z zQq=XDCYPwJ>a>Ei)|DiC1&kj#m8*;o?l)paSb*vyuK|e=~s^RPQ?r! z6#>pFqi_Q%3sOOK`~j^`lOdr$KwU3}duGbBo_WHs;m4-Aoq%&K`JRqYA#(T7}} z(o-ELuHHB2ea05KXW7pLZ8mOJ!793FcQqssnL38AV*)LuS7X_b$if{;% zem2vbJZw_f!knw|n8?H>Eq`4HlsWM89Rtc^oB~1SgfTGJ@IQikm@##qo7o(TpIf4< z>M4>PjfGK!??yyh{6KbYVz0@ZZ#RH*ZcxT*RR+<60<^7(4aC;#{sMpau>_gsSw4>S z%)k^U;iHs9dLy<%mUAkuxHAJqjgF?&*m&`)6}%AD4=1H^pGaAVg$OMTczyVRY2iyylH95))l~OzOzqwL97sc^tSv z&TuISFfwoW%I{g|&ka0PrI)BgKY@+0O->n$iprBRo4k&gP9Q4*0y_?3uI!sQZNXw+ z!=B$oo9c$4v`MWQWFiYhw>2^NYJ3G~KaZ28pRs*yc%-bUH_`n78imK)LPs5lWyvmh z>sAEFkh4x}Uj-Do+_uFfk>Lt-!9;ePu|fn*_Yb|ABojme$uLT$HYJ{5w-mK{uHNN2 zD%%D)#0{`%q%vn#>Lw~TafZ<5_9V1z5_m~DdJ5I#*vu7P#6a_1~ib8R1(Y?42xpl{;r9vxHC)X|~o64sf4p&DIUp+y5t^5zZu4aD= zf)x9hJB`SAVK5EVE!bf_MFPOzhuAF#0JeFGNq-hDGVG>6X5;~vI%4{ZzK_tjopdQ6m_fdyT_8bf9yj$GdHJF18Q!kD+1Xc2w>Lo_D_2g32hKthblKXj z5a&8b52c)dQ%tbSe{?peD z3Bl?Q!?n`T|9>qi0Bj0wCHqkT?n)d%zH#Z&cwt~kM2^V~fLd;-3-X6%)d}IKLcB?t z2ms(pNPpEL3V?E;8wDw!IsveP@MY$xDjB$10KmR48sPWYEM5Wh$-sz#G*QYdbS*9w z^&Bo`44HIjQk-U52snlIy^ISEo4i{&2Cpee0g=?*o1rX7Y;h_U?G0~H*uLD;Gn*Gm zM>!uj{1}2n4`GrV1uU6h>6|=4U%Gw>23Q?7Z;5``MG~QcO(KJ$B|w}X+-0PlzsqUc z9jE32p{JsRHAk=lTke!+m>UhY1wy!logA{`suCzEpIg7IqbnjrL&@U6-xh@z!?VJt z2KP2{nq-zW`Myo|{k>T@BZ?E2Hw&uG;+-&xu_=Fbcu7|51iH(_Lf^|*t=cMXj-m3c zxa_j&?$*1e?oD#ZnuBD-nADr&*2T#Uk=xDH=>}LfE>rK+r}KG4K#n!F{~n9^zWXxf z0(bAp&W9lwRla6*;ef_ty`p1f1UIUWd%W!WrplFcm15vk_K(7qR%uiztdLf#TItZB z{6qCIGZqBmcJK9AtmnAoQMu}8V>=};AQF6Ket6Kr#v|_#0g&w7N8yyD#6fL2Is zid+o-@8AS^1ktXI)VoDoYM?TiZ$!Ho=wpOaH4LQN4?` zC74s&avadlSz!mZ8RS3)oC9+$PX3-p>;F01BM^}p`bah4YX%(K$DypCFVDIrb%@5%{+vJaWOA?~K>~7>5s)vSL znH~6vj@fj^OAMoXetfm<0#9WoS~8n9qtMGp8=Laf(h1lJ0F9AYG}AIX5G-Zk_s?AV zZ=nakbp4C;zZd{I+Io7yG*_P{l=;w}j@Nn^^pwL$l@0|-<%4Sg~2CzJTs zZK1$F|6x`xUV!?KfNuYY)Ga`yFK=dq9aa4-)k(WXqr3X;3xJVvEU+4n6_L(gn8eX{ zP=#X9ruk=CgDqojusblV*l&iDD503BA!gQX23p_#;#zW_HEG)N7ez3Ef7`v8h<@({ zOxhjXd+Cvo69ZrgQe2HA!ue28)-h`gGt^0h1WiOKhK^d9D}6LBnVO^!Ls zAS?wQbzrwwB&p(A1qa>+fq=266~Cmzg*Yx|<4FLJ^=Mt@0iTppJ<#s{OsKmaj?9>v z{))_I?thfKl>aq)XHQvSW+`RWQ#bg>Au+keS>TJX`Znabd6H*?=Jct<>kax~ENF&d#LMAY8((8BYX{=?0~7O8Fi* ze~sb|z6!@^(XjIA(RL>PoXhH5d@+jl(D0_7xGh3dB=^NZWL-f=toz~; zrBhZ5_h+^df&6u@o#$YjH2!B;_5&LR=6S+qZ0|TBCT?cXM(nJ4aQZ}#)_g_iUHFSd zsMp>4tCP6tn#T#&gbr1bg=;GxTfb!q>Rp;V;>DTZ<*KxHW({rL(+t@1J>c_7e+{r9 zuyB0~<}JVZK5w5dH}$#1zW2b=#M{{i$e;CK77*qr{iO<4ra-s>P+?eA>_lY3Jk}R? zvoAc{+XRciy}s2$EM>y_UiR(nf%U>|zZ+5NhxL})>t(*KT^Cx~89||Uvq#fSL`8O- znOgk|7QwAykJ7PBh2&m49t$-%)`6n#^?bEUjqkz{G1-Q>+UT2tMBG6iYB~%N?GbsX z&@zIzt$u7Ww$R&I6REI=Y*K$9Lr~GVvQp5w;^W7qYM_^N;{quNelSFH9Ta@?4@gu0 zGOPG}fw6Q(mn8p^cF^YQkx2}HzrxPAIZlJ+Ot$-+W)HvsnYI9?PgdZa$09H{;{g0$ zTk12_p~uR+yIW1r<-0b@M>Mt@O<=}G(vi$vp^`jqzCS4Vs&1gYg*NBYepNbf zryOBWV%X_IU4v@N^6Bx`Vx#Ef>Tot>VS0o6LKyXpjvx&_sXQtHQP15^8_C=}dCY)NA7htv4}QdM=TLq54w( ztrsU_qAGccGjDEO9)95%zU6a_g~2a({9pv-toQXNiCJ0oYtbDXDQ+qsA+!tU;kt|n zAtT9Is7z*q6b_FoUBpc@LYAkxvhQ6}#6vv&7jlUQWwU_B_t?wjz%L+^5CF{eVEAwA zn}4ZG&cC!j=p{5_-XFmL;lp2O0^Uii<_jQ?00{9)?5dsa zuJy{#D7eh~=EUAV1reUCYe~hGH+NpkIN<6%sfTyyZfy6*Y-FH-k5@WI@fAH?Xw4L~ zSNJZ9(vJja&amQ~bwg*hMsYF(H=RX}t{8FD1{0}Xw|iHO=NCzW^3tJa2$5F`V&n$l zt>of3YFuksimduk4h5X{#~MO8#Qicm_b*hR?RdS&1lc(C6LCs^AaT!3xfI?vK^E&1 z3!%&4Uxd$3hkk9B9qsq(0{{RAARgHMH?#OJG69t5V2+*uyg$_AbpK7ffahu&fPglj z_FG`&s8>w9yM2u+9jJlp3kj%4%7ixwxGA5{njr)nB)%H>sN-IaSXcW41 zuM~l7^vzxR?c8AB-s~T5V-+poV7A1~FE)S4!P)gG8Nifi^eU{<^M1A}4kH(5e-pMK z{tDAjA%2hbT3?7|JB;up=u_=|cj7=XXn>HSnI3z2BD%$2fB#Ua{U!>G`3=l#ye}OP zU6?LC+#B#Wp`a^3I+(N>LP1&tsOKI}G(l@wHqKK@fk+Alt)mGTUX*f?!+2|U{3&R$ zH`E;aH!vRKvd;O;a$ef6o8$uTp_#>~l#FJZF4gOyn%HjLl4yVhAa7B-_!9t zeig+rK$Wh1c|G#tUfDoG3%E54N*QN7xYd8q9&)=`j9wk6SB=jWecX7dD?%W0w*wN9 zpK-hrN?|=IV_JXdw;NZ(N%CK@iFt6?#q*ltm?fB1iZXe`UGaxtBeCF!vQ??KA-EJt z5pTIL2NyG>z<}avkDL3-SG2^!0lwHK>cMi=w1-s~G>`Tap}l_PLZ8q92qbTla1AId zOUl!u)nK@x#Hoa-mYlbvM~gTD*h3@^!$8b$@LPoGSpvSc^iiF)K&7eurC)rfpM_N1RC0Ac~4D zJ@z8zx+8&TDgLuk#IIq#M$SJ9f)?KibG%Q%8$6y+#Cq2J_58k!*`fvd1Q`c6BjP;S zAOsc8Pnoj6oU2Vvje5&^D^@^e1tN<32qvY`5AF%?@nvRJ;Ijnk9fPL&?QwB+g$zo0 zrvhD02(I62++GVD7!e0qBE%IX%kluJ{E8J*7;b;;$O?IzGT>S7$l!}+93+hJ3Xax_ zm`*|4Ngl4RFAG=z@n;(bo*x2x0o9AHA-VQ(b?CY|h=?`xa6PAVo5*IJP+FHS)S+V7 z!*;nC-B|(n#@%iq+-S7t9|EQLcEZcza6BEPy(d}nW%E~lx&!UxzAC0~H;CAL@bRin zL&}GK+)_vL4P2}Z)=T#g(?oU3|IDR^a_JLjy~u?SKtGkz+hf*4@33bggFI*=Uuw>{ zOUI66MH^s$C&l;B8xPBZ!gXTWKbW|uRqIi|qmD5qSH)qoP0_S>BqtX-pAhV$ZU1E0 zUN37JZu3>Ivvt_qp8PSS;dwmiMIA?q{_Jvq5bSgGtLU84k4-7<(9Txx)e|sbn$}Y& zU_)y;Sy4@l;xyr)U36HX4UShn1nPCz&|>~vsmZMc!hy|Ag@-$HoO$JDMG$Ur1MW|h zr4lyG5B7_4s*Gd=v~x9OMWu(6V?szZ=Br#Ig2b6*3Mqh6cAyv%8$YL5(uP~)gMq2= zxVOi_cXKxB>{6GrOUCiG4+zz~P@&u7j*no(+8PqK3*J%$!YH{t_oxWoMjc8cD=f)! zGb0Yp)s6u5&R0dSHmG%Pi!7Hp!E#ph41ZS? z)XN=`5*P4Z4X>QUk{N)4{@UOV4fHaG4rV{rT#-7BL> zJ=hxs8d*7ld*1u)FY7{@x2s!tTpm);qd%IUU1xG;bs< zoa`lz2bqcGwujB27#C-?$o`JE+C27aiDoS7BpMhU1`#B>Gvq6}c@y^vJN<1?b^%}! zm>WL!kH~ic@?!ptg7E?1`7*y>z$f#7BnKQ27QpT0!08W1szWEs$R+ao6u6@)tVaCc z!EOS7%CAisU_$ywuZX^B=}U$kC&B1=%cOB^(-80QilC?-AshexSWnNG*3S&_DuwNh z+sRecEON8RsEaJ|{cULlcnLo@d#qt%D*_5pXs%@yx5@6X~Kz< zpcfV$vdCI)r>~>-&cNrV(2Y6P7~2n6WvgMs512m3g5>*2G&8^glw0^0()|r|+;70b z)pvT0*x1R9PJwCyB>$rEUq%l=?E&}=xb;1NCfo&&0+ey3Qflxq;`h6>jv{PQ0nlxt z7#p9O;EZ%Y=YT&v0dTY*rM94=WNCrX>!qBf>LD+3VybvaIMA~PI=4@;t zM%d~N6OEGf!=EE81&)!#i$tfi z4AS<#^ZW|6xSh+iZlgG__!+qwDUkT)c0oH|q$H>_k8*~VNsuhYr3j5lCv&MA9wP^65$jyIeurN7Qq--SR~c~t2fQv9Xc zwK+@?ol%r#=s0y5z43HEUW*JWNS`7VqdNB2at5dN!#Y%MBf*_N`Ykad==p!06-c@7fAK!lZSY2T4DILh&&?T{v zi-!%%^vz5}ePVQtlH}KOo(XAlUPrEOx-YyRV2EYK-v4Sg7f4Qw3*`JZG+4CHQS;1| zCL(4n!mpnNLt_>Cf|R*Y*=~#=OX&nf*XpQ!%jd)T(^e;#$6M*Nauw2f^1whfC~HDG ztNE59xCD;9f}&yZobn7ObJFS@niu^$>Vjm#U`-I&We*%@bn>DHgK;NEJuXZtwc*qD zZ+9cKXl?|qN8Mij8 z)Yvtsrv}P>_0L$~Rsxdo)~wV)%i8^4`-NLivsb2OEUume5?eX8xjes^a^rm$jK~@B z+FKKUnTt~)*C8(zZOzX?bYEoF2!&g2ld>M+sfpg0Os^;6Gz;pU6`u?K%=SIj$wP0A}g!H1E9piJP2xQVSZO)cN>Xfd{5H56E2lm0shL5Y|qD zjh>RU$XUpF!?8)OjQ$-7!K1}#aB>B8^LozgNmn(z-VZoJn=!I=o0FZU0Tw}=3wY`< zc6T`(lXT~zB4L8|q)E{kO=98L!KPJ7fbauTp5rxxSf5m)=5v5 zVe`HhE!Nz+>aSFg9OxaJQLkL(3;30RR9iAl@ka697V;q5L8IzkmT8fG0kT@cW$0dw_DV zuVwcio{90`tmtnHmCk<0Z>BpAiWIuryUV+T(1&D=K8!}b*L3_jFmfjbfE8t|<-@y! zz~h>qV%H_@-OTtt{X*t0B0 zwS?^;qy}3N%}k*BonQY41pg-nHk2Hp{U?*uttns#oRZj#jNhun2*K) zsTs$m{8kQG@7w9}xx~UxNXb4QlQy3{wioeNlc|$vg^x}PhC~@l_gcOa`urH*#;1zT zn0={5tCm!7w-j`gTdBTaKI%FQVKc_L_%mJZ_;E@9vMe%fQs+N=$MCr@uS*=z>??F8ISI;2Kaj5hXpBsmG1L;gEf4v(G7FlE=p$Grw!4xiS;6|uu=i7id8JPl8(%?yV&*eYImRAN--#BQT}^K+l_D7eZe<~p z6iu`{>L)$^CyE%0@mp1qmc2V#Y2YvZNX_2w={V3A!vcPKcNfGhymnD}qhAxm?SqGN zh|Gvc{rX2AKfdYBh>JshRJk1Jjc?Oyg#a4UcqV<6Mf%}3!t})_3Rcq+CVx$V7n0d9 z$fo~Db^CDBO1u30%k|@=AwJA0uMg2cR`c8Lmxr5dv-2;6>r;dK{;hpk&Fjl zFcGu5=J&pBNV-I{B*k+D1DDF3jV1c>2OXEnc})dsDe=?i1kuLg!N?$p1GD`DT@6VM!_`5vx%0xL=^uCu@64{+r)HkHeW-=vY}#yscR#vjGz6slJ;lCl$Jze+6#@Y2(tEymD2BwHmK>&;_yiX;V>I21-vmR)2vb}B>w#{4U_Txx0ev(GS{a- zqp;bdUqr2vXEyfVt<7kX(93Z0l|*FwJ)#h!t2%y!h3t@kpY&Y=;4FK3SIfV?WwU^k z<~Lw&Ud%rN3heN2?D(TBJbLB+RxRhzAXNzw0)9k9f$xSc{h2CVBGlr~HM)5sRxxDX zt-wqgh~kUlPmY`<5K!J~&4Kx1C^>Va!`xAIB)}Lb*1!_3)iPtik8iwKmP)DdIP-wS zHqf_-oea5%$0?T4*YJSKXLW+pz;OVH3Kr$$zvL05&%PBU7l?y9v*#t2F;5^BH2(~= z`yfaP8h$Kj_?7=S{J(JU-;Y3tzlr#-lVIc@_yYid)gr0P06}ZK&|NEP0(IV1^b<(??DdK?qQG|L4TZTyBW=TXwV|)g^px~m0@M$YtIIK z7GM%IqJM?#{>pdw`|JJ@g+zXT3z&Zanj7feKeC;+Icdu#pIID=wlo$0xqacjaMNYy z)weR8Y{9)n7wc(v8=K@AQ9E$UYe?b#8lgw>Hr3mg)?xb6=ECl!n~53u8w^+WA$`Zk z5s%Y~@%FZXvBUNKs)A`_emQWCqqJhY*cv}$P@ik0wnmbqT5`?7At5?}oq1LuxdPw^ zs$JH;TCP*@FTdM+Fi992v;ffL1pEZ%<|F)Xz{(BvXXL=MKPxMM=T8tF;35F#BPg%A4$) zG>GSUk+u|)0d^EjSR!6iCn0gJ){Z3%J{lSYMSJVDMK;j^TrCUiR%8Gp5KzZD4sU4H zAtPt=A-jf7J_F4KWV=Ccvulw#&P*S>uQ znU9$Gx-=CIfC5jbggpmA?5JpFKFFV{_ZPXb?=@Y~-H4@A1?%wJCuKBjzs z3<3;N0io?#t|)rEW7DH2{ern@$ytbSc zC8teMw3o6~cN;}HLAmKrlHz6NOj=2|qJ?kF6fBHCmcUfBZVPUnXn1=bGM$#qT697X2K2~MblLT&Kh)0R*!gnY) znJyz}m!-2miOZ*^m~LyT{XfHlNW zgXYE_V$c8~l9@BR{E~()9j@VnuWu);bC1v&zA9K<@x~8lP-Emcm?BX4v z&1;3t_Waxv90rex`PXPu`z3HU2U}06I*HBAQFW|29?XioTUuQdN(n!t_jN|Lw`y&> zjm*8z7n$T$iA6nU_}v1Yz`i=kCjo}kPincAlw4WG91QkPeQv=1vzSgRf%-?6(IwJ7 za}*Y89(cCCOx8MAaiWr_Et-5~pDHOLh8du;D;;`cC<(6J^>aO9Z$CQ$ha8^gspfkuQ%86|Bpa1z}wJ zr#-vjJW~nlp-m0`sb#6Xh~A6sc>vtGWp9gZ=*ov=q_fHrIpUpdr9=$G-8$GU;hbQk znVXjuqR1pBBFYEXE04M-Y z0?RE)%AmYOHRdEk~;tMYY0H!kJ}Ton%u>d z;yZPIl``k4LsPu6>+T=Drf>W7wa(!^D-s>YdpDm3b$D}qTT56JA%%R6Q!7>&xJL$# zZ$xrw)<}uQ2hJ$&kfvfUHBFofQzW~YB^g`_nX(dEIO&xQdtOz(Oap3iScQX?zgS&_ zwYupGWT(`xwE)u;K`PA&5XNANLwCy#u6WE7Cc{|M8PYoAj-a}7gC5kD1~Eb%Eo!8c z+gX#+G;KTRVObh-C;DW3Gc>Sbk?Y~UAAL>=qv~X&qt^NM+d73@$?CP&5nsL>w%}R$ zpdU-E#)9#Z85Iuk@K67wQ7~|iFj|sEME~-B6tA%hp?R88>sUXcYprx~u_>^!D$qom?i5fmq?c+EiI@59y-ml-s={RmQI5hh_rl`j~sPC>jn+(Q;6?L7ySo>mqOqDE@?;nhuOCf6LS+IxQQJxPcOJQ91uY5f>>hvk1Y8MQ~&+= z#|i*;0-#F)0Qx)tDhjBTC&bZ+wd6A_#w`p_b3h9wLOgQ@+n{7{t5=Z>L{C7ZH`gId zY1|dxy`<#pcI_%0W)oOPI?^}Kfx@4iV03V_?gdfj=Y5kFu`#rZ%u=Zg zG`Afbz^b)-i#(|*THVQj9Cot(uiN!?XjsZ1LP6E@b(Q~&#J+#Q&cCg3A^GF~h(M|> zxLnxZHF5w#5n=f?vhM~ei2!(Z4lq~y!Dl!s`pTojDqAp{4>A?RzDXaB){S=jvT&!< z&+a4j0?S2eh79&FodAU=$xzKdLk)#&aj^-D(J0?xt)UpXn+=%|5ZHa_GerO8CP-)I z&##c9$2(PFH7)7j-UfHE$JvqSwR&s;gZPd{g&F3T1l&!+uYTny>mp^7>noX&z*^e{ z0D})(LcYbc4rpl#*aVR{_Rl1u{3a)e2y_IiVfjPage@o$5@eGp!}OJ#C;Ub3&+rmM z>y=&!!|z~nO~}(mn)p-Qu*g&>oLgfO(fgvC%oOBK5ItB{waPy%xw$aAA53gx&d;tO zhCCg^Htkzs1CO{Vhlan^HN%BGSHKoWKg2iglgnz{NCga-Gi#jKMWYVtCe|Lc0-4xt zm#2PwMYSjX)e+<`=j-aymuQVk4WF#Z2o+XD>J;vu%?Ig3BB*_t&U}(`bp#;$8Kj(--hBWDWsH}&BWt?9=M##HXs5kf5jlhX&Ls5x^vG98i! zLi#&s)TU&y{Q$UXs>%N~aA zbet$7B5J}vuMBe$kG^lUjqttkM{2`H1bJ5k69t0Ko{i|C-~fJ~jkkI_ckX~( zs3Oc!Cux-kJG>7Z8yo4zN#6z5J37?ZN!o<2O&!e4=D22*x;$-zGEcB~@m4CETeey| z59KG;!GiHzmKj7S7S4k+z`QiB$lU&jV1`dyPCSn$nV*+-#&@cHN4gzIwfTg| z$9VR+N*7Yrno*fNRrnIcmf>f=hfgWR}5{5dE6Y~cA?26dC zwcB3Oka=nhD-iBcvO6s9xcvFp=fibtC=5>k>v`sNQ!oT8`%)XA7KEA=qPcAfzm1{X zx8L&v95o*Yfe4RC=kK!V-{%m854ZlzIym79(7ps8{6)Z00ASy!0}!tjRC~oyorwU5 zZ)t$f2gEe^^fdY^MwZpHxLp{AGs+fAG*+2w9Bqb8j{|Sb&f)1;+~7Sh%r-};K&rW) z@vCOBF=pe{Lp4858Oc2NRKH?*nJgjoNWlR@S=rNPCZ_MO38Ib zFr6yRBK_tPY+Az92gwM7ZeQ7C;O0=CYY<*dYa9~89YuF1BRYmML7C>>TpUoOS_oXu>|o499AfMhyoIoxmieK^houRW-&UzM*SSu#+F1 zZPwa*SbjcLpypTzTa?4z?ChM3l82plBKd`YuOQv$7q7lNx5DK(DK9uq?6w^0hp^2) z)|{k!%8K_+l3--2t|=kr4|6}@b;TM(-t z=DNm&^;I|DL15SaGX4f_(`wq%_>VXh3!F>jEniA98{;AfJ`bnj*OM?ygo z`5(XkGF^V3?)m$o`lMFxmACr^L^q_kF_>*iVNM&=Y5OSzG8Tu99TgY)57w+EA{m39 zZe8Bc*QUCuR-&1dC^*6vKX6ovehwx(6T1^yN>~#(2=~&E8-OX{FR@tpBvLMk$iBnT z?`()uU;&>v=%>42D*CFh#I1~8;&F@17u^4>VQV|?LT4o{~+oAQrLWmkTg$VZ~QN!b41X<=KyFwzMKj5c&x$I5>uM0gI%Dl z!CyS65)Hf!v}#siFMSIkWffs+v~@?O)G9XzTh>Rd8JSC^g81@fg~?bibX}QLakkr= z@$-j4Scoe>wlX^L70C%b)Ks|004RN-=iK=Do6LwaQZF*?YI3T$#Q~i5%P#vy)*j4? ztSN@d+Oa%glBGprxtod5m#M@Z?i&n{CV>SJ7xPcV{pH{Ri@+HFTQ0#i!1V#(h&0{- z;E-KxUjX=>rE>qG;iOep&N301PqGzGv4o7%1DhkL2_ms8sDp0ZSVl8GEDr=L&Ux006vSH^(kC;P-3jkh39`ns9Rb)6d%%PZ@ZR zGY2F^+9Y3Y;uWQ@NKsD(;|zeDvr@ETGJcAnoe;{~Ux7hbP}ctLoR2JfUJ4&s4b)xH zU5mJq2rk`_c^Dg}beo4S3#KF9A0 z5fe}_H;BVrM-9Kg?V0VlNzCNvK9~VN-tTq4t;6duVFd`#TT{#l`bR?I>@LzZs<*6O z1L-piVM!KR_-MJ=X~WTT?^x+66|Q!YJs_SjV&W`<9UQFB~91=P9i! zT3$OIlJsu04}qFXjRNO~H<6Q9IZ6c7XK|m>*r|wQ@XfYi2-P?(rxtN*}cl(n<&#ELJFEPAsfH|%_vR5QQmf~vHJt82Lc+Aq2Xw{xAj zgW^t7=10|q`^=kyQ%oe{s`~7G?8_FnF!U#EjUMZ6!EyLLxQJyyHC+kD`tGqee`3+- zg9J>~&sB%ltVYw zVvbOv)AJ-oejLGR(DVe#iRO+X{JRV2e`(QeX}ZVoM`_ubO|1n305h=wQgv6?0Hf8*0rR3D zd?gX`COss^qn<>h)y3AspEnZ=G0ubFsDh;sMzAYmT?yXc|`WAZyKcCQc@2megM`(M@Z+0`7;P8+}8ByRnQVWNsUO z-2=Vc8DI`S7#^h_uHMj@)JeJW2RkbHekktV=b6m>kw&uo;$iiOH(9b-fnJKkv;)L zNrKvTkbm>6eJ!tov}_WGc66@;@Z~`f`3Ve#rLyyW{Mkm$OcE)YqIR|$Qd8|pn!)#> z1*GgMfVnd#|A^Ipd0zenX5i|-=QLa%07(Xo1-2A9z>K5xB&x4s@P`Ooi3E=l(gP_N zGzO@f4_u^txS>v+fN~&GyMXav7D+4TB>>2zkFwXFX$)l=4?>JeX>b}qp^6{@4D-%` z%j_8gMP6y`AnQp>GfY6MI)ow{=8&EUcz|=50(Ww5bOBE!yu#^$=LkqM0qTIcvkd<` zQ2o(E{{mz@aS?#Vg^e*_lyIl{GluOd_$;)HY6p$UnlU&*N#{|}LjxR5*+G?1apL+A z(xWi zWv zN`|5`*Rs?7fDHtp1EXl>>|Y^;-%*8sLI-dFH&v`cYpgKecXKC=7a(R<2QW6&c{zq^TX zwR50g;-#X+d(U;r@9(EAl_*N0RNsAC9v3Rjs7vo z;DrDj^j2~YmvbEyqwWZGCrI&{#5^!d*%O+)wb96`BJF71CvuY*XYOWv(rHB@W@+u~ zmoM^Z7&gS()W>pxGE}!N=E;+m@O>mq-Oa4T@zYtrD1vL36)BpoHFMOnU7+scplWey@pyPKHgf!b0GX#Xs;|Nnurn074laBtyLMfHJnECgx-c z-xRHFsi~~{hJQ6(nRIZi-n$C_rnZ=m?qR#NJ9})S@@sZU#!^I4E;%=r(}yqcQ2+pB zLJHR6{|D;*%@9(5d^8v>6E=lHeQBS(F*I_s<4A=^CvhEg!=8ujCmm3s0H`J(csG>R z3qtrf4h87kSmI|ywgH3>B9X(q`Q?Rt(}e~WXoxaF0Alr-r~v?UqFFcrZ6rcvCHZbT z_r2A}5l94>nG47Uv5o#GWnIgHfAILyiK74v!La0MZ-y7v06IvCol-?SArW0Y05BzV z?M`)i=Q47p!K~TEi!lJ`I@L^#JG+^C zaujp0u)C0c-~S6nkxy?f-R|YfEHIl~K6nv1-`mr;6Jql( zw=1RnWbBgJ_$pgvr4()n_@VY3j<8t2FiH12h!|4#^}J2|@I>5RjB!Pf*MI)-if`^U zh0EhR0e9c7dbLMu+r_pWyzV^x=)~cW#g_P8!%a6aB3C%^`+AE=Z{4MUvL+98y(G^F zgi>1Oy;x@?cHJ$W2Ak>TA4kbMj~0^_ogcrc%*Kd4MGNeZTqw>RHSO7=KOJ(}ENIzK zT%v4xt4N8h(^-Oi8~T*`=;{XxlKF50TplzeN&Mp$i^{y%M1i}gd6%2^lR>+fWZVEp z#R)OVR2*cMbG1?P(qvBXTZPGhG6f0p(X7QlNM;Iw6-m6BW>a6sW*{718N%MCvJ0Vm zoeyu8?5542Rapww^;?TVe0bsy-zI9p$!b4O#m1#;E}3%)kJuG9SQ0x{p>7eZ>;3rP z5WN$Onz+5f9zFhn_e1GHEuw_>3$9kj@|iOQQs($`&URh8%?teCQTKLiv*J|T zJx2{Zl?A~RK~EQT>iBmLhWY1HFvCo`Oa`grM-@M~xJFAhmUzL}pAEOsUzlR>PEc(T z!adqwzfMjbK_kDzey79r{r7OW%P#~p26EI9m;T#&cc(*RpGo(7riI#mt@qFgqEcfx z`UNrV(LZ1*!&9jo$XAh#$+-IF%tp#ObHTS{R@JTM_bXqQ*imMn6p0Nc??5AmL>dZ9kGa$=AA_=~pcJvsR&Y7I{b zQi^{NjM0!Ni!yT330HA@)GhehTmC@UyR&J!{RYe#f z=bKl%E)rGBw|t9p-ZSj($K4J5W|AJPg%-KwkfON1-S!4;rc&^oEYbb_C5GLW#*OS? ze^!+KkHyDIDU>NAnn9Ksbbj5EBY6b01$H%E(sLy*Uc4-Lo`}0fiLnXCX97%h$28J< ziVUpU{P)u0Tsq6eyXE)#6$X#LOG)GixD1&ok}Awa50nxa3$ENmSwMb1{95J25A>hvM)dWJRX0}G1kP$Yt0?SXZD)~_h~Yg> zdp%LR_R&V`NKlUuuOpPy7!krspF;AAB5aQ2lr@=5hyZd-N#THG0QSHY7UTBB?XY`D z8ep~1?rG7dYL8@2IgmRrHyX>cxq;?4*1DNOPrslO-%N_|em4AgTPb?EiDPM{^b~AR z6xg8uQeLm2|7jYM|J{y1bZ&%PGJyUI066+Bn^3&xIJ>jpsG%K_EuV`}lnZ_EKA;dx zaQTjc9|-^on)Zb#fXtfX`EAIzHUL<3wID?Tgrm#X#a%e|06>kScRUL2h4WbjlxuGR z0LTZCxc@~a;p{N{uDze?`o}T+-=K8u{63*Q$C&A*_0!q1;6`~dASjhFQX?3YzV05n z>(Tw-?b<8^fSHz}n*eY@BV}sN#(`G@uAwP9^OXj)=*0JP+#s^DCkL8Qo1H$z901T@ zckZlt0}0S}>?cN3;wXC2$tSL7)pvq3kXcv2`g-MZjuHPTmmvOPFg29p+VGNznmopj z8CN^!tfS2}jbZg97wkF8<`La2X>n$m`*j5*3@0Yk{xoBl&ps)MmHJ5M-0&ADz>)Y6 z<0m&&y1B&ui}HJmE`EL^9!0JIdt|2N6occs1KIp!Wq!~g{a9d(mVRa}wjWZ%mDR~h z0{M*XIOi=%vKJR6voQ<$F-6_J-gjR%h9@R?;TWQaa8Lc@q)?}X@vxXu=$ypqV|5w2 zCm&!jK{SSg1FSVI5{i4h;Xey9VfBP>d$@7kvlq^;bY6XqZor9a3tg(b%Bl1~x1?b{XVl^29F$EtV_-7B=r_cV21VbN}<0*~fHp)f0jzJ52V=vXA0bc_9~7fM1T9b~A^MI&ZG#FJM+uOKo4dDp&5Xr@u@6Wv-aW zbX#Io?-2(yW!WsWItQYJZt z^Ruj3ZF#HXQI!{2&W;~Ak|93C#6c2AZ4_U3*VH7KmD!gV)EYsdc~`FBeDr@1nlJ$V zz~7!0382L`!8UnW0emiOG`{o^1vy9$!}I1aV+x7ST2Mb0KB|sn#woJA82ORzZYA`O z32D2G8mbkck#en@FM=2?i$0Y8^ljeF2)`pgSa)8wj XhGXG&bCze+ATK{kImk%Q zPrVKz`>||2;XQ*4!^%si)|?{VpOBYI<<+0{v_GBYI38)EB+npJ7#Ut(f73u`7!%+k z7b6q_Wty+eSkM%gZD)%z;af1>dqpBqUG6BNyQ@uXSzRKOJi*vfqCr8`dA746E@X8J_&9LX{S7W zyLDnSmwX~oH46U#B=%NFK3dIR213{QWm{1IU=#K^`d_4;OeG51pQu)PfW4?nU?3S| z1xe~#9W^C-QP3w-Q4;g%5RHgTo+ald-Womf33qKjbZnsE0VM~f`oSYer+dfFBEcH- zI1u0xO&R$4=R?G8QzY#{l*u_q;hz!6}LYlj0BaR8Inc zp6P-|3tR?(#6ha@D!D?*SO9dAWwaU)dKw6Q=PxqpS~P;&|JOLl%VIzRzI51vY%9Il zLVn*{SH~Lj{UL=!>zE>zsBRda#s0qAtVC2BIs;e~L}?O|q{yG#Ji^t@;LC!7F2Al} z{LX}=-EVe*FM`wj(7Fc~zhBphS^3986R>LpR&v?!zZoL^pLz6A1MmIb{6-4i9SJ@8 zXkLtNXhLtek1wwRgBiNCl^_Q6-3w__dEOMB-FR;|GLq~u$w|r$f2F|fa!hX2_Js;Z z+)*rH7%LP1qY~BTs&gq}sCrx{@PmSC19#LtB}H^bCqbhcPow4H^yzxsFDn!PkC{am z?8&^PJCQ@%^l58hZNMk|S4^7B{jsfIy**d%_#q+x)%@GcS<%eoQ2UNwfxez{E7J|{0nag z3%w(Mwe}{p(=#%u1bgL79CE*E%)JPw!G$2bRd3I^L89_jzr9(V?GwvVFAj-|G#0ao z;$J2=6^)hx9e*Cz7>^NUC3DYJb(c7CC?JQqrB*YEF@ zRxTr9t5D)BFd~y=CB<#<2!pdsHx}SR1z5PW91AET+{Z3p*>L|>K}BAZc`aI>MwS- zzRA)t>yfbA=r@P51%u1Q? z=5@$mE50qEF*ltKiY~c7g3WWL(bbWl2HKQP-gbyG!k3ngK8&anQp<8@c7Ms4V!P*UjE1<9Hh6c1%MsN@ihpoWHJ9lwMfNOk|XSRA$_{S zHOT_I1GjdF?*VQJ7$5ds(Wam+4`D6HKJ7wkBKQj3r2JQjAlB8WgX-CAp9*r;;@k>i0A z(1*9A$mqA!-`!Xg_B9C6CxXK$8?(1iiT_K#!w4rE&AMteY4l1zT(YyNs`}OWQ{Z+% zL#8$7?GC*0i8e7Lb#8>U8w^kI#c8G{gs1QR<>}6nW4di))w>r`?w-4In0v_$=#a=y z%%s|BS`^@tT_DdELGnp?{vsm4pipr3KDdwn&0>eD{~|N+k_mVW3pGOlH^Nn{B?ZP& z#?_D;gQFqblRw}Q)i;_FsV$7{g=%c}wJZhzN@6@XE^@ROB9R;bdve$&9RwLcLcU-q zPZUw=ivd8us6K0NXh4t#VGj`E{_@v0q!8K-n$BR5X{xL}7K~ zJO7XZ+_HNyB$1YrFKApG%Vfi$bhpe@ZrPZuF_j&}vq`6RK9`r5_Glbp`WjYgE+XBK zk|fDjHMdhWM^~5;;73$Ya6Ei|S$cOjP zzQdjYNH^}ug4z9gz)#?dTsE2Ve-C*6F6a+kNKaQ0ba}`R$C8HX27_|{T13@BAZCDO#X$W5c`!Cw;1%j+k6wiB#e-HSWIa%m0VuT z`ifTHQM5nuFsiU&2=+BvMzG{H4at)?!s5HO4<@x|Z@p;`cRAo!uyvF8c9P^bJV|p( zIyO%SPab>glGH)@EUwn%KBLW#)@Lw=Qaqz>=+kmHDlD6R;#@*$4PAjOp7*n!P_hej z{pN@Jl2fPp9QXEK?~g#G)H;fJb9z?$!y=TfI6q}^*5H$sD(_xo>!77 z!w4*C+@c9hL$MyrIFsl=U(W?e`ed+o8&(CP#Tr6N;q@y^-uKS4zjH>MN!49zIzQy{ zX?Ome?fz*t8x8?$#_xY;wQeC`0rnCYkfpmS1nDvEL07y4;EnghEpf>MiHuPn%%TWt zIyD#Z$c;-H+j+5Wltp~edU@hwSOFaNe#Px&dx|&fa1-)Y?$xKUw>Y#~S}pUV<6Bw_ zQ10lsr|bz*3KHJff=w9`8I3x1sOU%LgvIVBOeyKb{Kmzn_9&M#S3*5mR&AuWeWku$ zEJBlFYt=2rBoX5t3Q}!Q`k9VP^+{MKO4^?8Z6QUELq_uR_k}1DJ_`WN$p20(98Y>t5^oyP=>-yW@A;Mdc(ID2@oB=LP6S=z^m(%Rqnp zivsFRQL|!EVaA>@JyJ=6ada%J8Hnf=dl`UZAYnA=Dp+K^4Dmqcdnm$0Z54>Uvi5Cq zC67UZ0e~|VLWGIb&Gy0Q?kp7BpHc7tj0{8<3ZfhR4`%%1Gy1Co_ctu5<=;OTaif|6 zO1(vCQv_l27AVQwabw)xa*0HO3`I)-trRn_zY+j&5uDPX{RZ8tA&Zj{3`_$b<#7b< zBEK6CCHnIKz?uU=_(Ss9aQ;pW{@0uO zr>-8{SlgqFyuJhS%k42m%8~fOiUiBQ0G2eF|{dfTx&p*=*(iNs3@*kE}m3dt_iGr~Pp^ z4B)&{c|&MZWcRW`{g&6G7wqbi&o0PWV^ICAKjka16ANwbB*N61j@7fj-y)j+l$cKP z^PmLfW@Xc7P9uS7aR)1~wu6m@L~iRMq~vBd2+c4{jBG zAh+Rod4l3#XP=)!`@BDR@px8|iT>8FwYbWbkRkrw?Q)g=e4Mfs1txaBvBxIY($~iFo1Xj*CS2IkBY4b#2!a)!gX7PoHjnkK zH6RQ#0iw6jy;bu$66Q4~+qLsT?)xb#q+wen{nCvNxmlLLSt5TfxaYQhv_{wmOB2NS zg*Hzd92yk9ATn0_8JBJcmr+jaEVW?iA%)j-b0PEs#0h)sG3TrO?wpW!!R*xJx&Zu> z6K0lJj=OE~s|6~BZ?Dr6d1iXlwg8^d>4dJDcUT6xETO~7 z&sbcX`4sr2c~q@5K>Cx=WO51v|Ii^NtTV`9f-rjgqWVfUQJ7HAAz`P}mrjEbofldM zzh$;~%fN1A{LxJdMg=KC;>KZx$k42#Po5mFlH$iPqtJ;e>09W|-n^ntLayaIQ`@vv zBhPu6s>pF-QfnKvdr3;o?sHYU9-emicPT2*%)~@}rXF_m_{hO;P1raQWYC(O!`{@F z5w3u0J*&dF5sqKGn{p2TfOENgKKE;}@$&jZ`R_DNm^i>!92Uq%At|uDcl}vFz^|Nm zTkUJe1O!+BlfvIaUU=lm9RpL^3Xr=bmYcvKcRU&^5mLc1%{1`dJ>5yYz$GUejwlKu z^CQyG*AZRczok9RSm2`hrpWI-&&SR_R%V6L_}F)*b@|wK&%u{>9QPc-q&wX5KrYT? z^ZB-0!O|&^*Y`4hpwhB~#%l#W-Eap|jO<5-+AA$Pe5L0n*sf4PZF1;*3>n~(#CDt5 z0onluQG@wMLW-U@czaUd_sl2TlCUT4+26CA!3@d4#LydeAv^~MW+r z?)dFfDWPd(Wf?E8fn-ft=9f{~mBS-r3k<&CF*?~_|D$Ns?;m`z;5jHgTtXZ{iM%df z^wsqq@(m2;cqx}H=J=mv_4m^@(1oP%srr2TOl5GZ{bCIy5jpHF+d}s00y-BKh3WQ> zmDL&!Pv-mAl)7^*v9a`~DPk_G834d@sVnh#d?D3IlQ0fKh3=0Q&%_o|<|j=oVuqnb zvQj`{_%gT!={}eMr79?y%6(0Jk&*<%W@SH_b+sj77IXCWHt=2LaVQsPumF?xl|gNL zeF~-8rd>s=EI>hBox}W%ttIt%olZjr{>)kCYF%VdEzD!n5*_b~WIIWaU@23m8 zT;^L9n?BW(sg~zez9BT!Xl*1q8z*i3O9H;~vCS|Heka8nu_JBO;&|NKcHg|+Mo*$S z`SZ_@ITB9fPl9ECEnC+%X@|b7&zBW47r{%w*uV|n8o>6+wus7dYSg6vo)MOe82QCN zB!6clI(~lD>Skx_E%&2g)>_20LC#SOmqfT1MUl2JgP6Zjj27{0`+6Gm@AkXui^6S9 zXvKk}J}qxONXZR;`9&2@?%ciPetIFt+y081Qi&*3SBBJ;9pMEl| zPSA%k_uMX$7T+}+a8ptXyex@H+?P=xe6;RF@;R|OpUAIJ`K0i`zH+-sxR{I^bJMXuls1DiBIF~j~|a}R_FqK6=@pkd@)xN z*f+n)(+P+?3&2jP6KGBoCpd{@Ryx%`M{DCJm)5P(+Lr4#nk-OIt#sHpc%1dKo$8(E z#O?mkaia{05Xn!g&rAz>P5PfZIp($~(yJoi94F}98&vO~70Euoc|gq&Ro#VdmG(x( zS;PCG^z+(MoxA3ilSC``Vri*2B(IdvuM+9E4cMA$Y=2gUw`%T`+GnMD^H;v6^ z^a$Lj5=@i^l6t{Gh_qb3EYAO;nPTr+UaUUim3y<;Q!vj#CVmPqFaYHX*#weu?m-k} z!q}Q@J}Ld&~R^m7}KAUTFposmHQDDG;d6UMfW{L5fGkM9@;|GP!M`cv z-xXX)I!MvUnF(85&sO^y8JM0r$s8UY*1~1x(cO9qHmz?pop>@Fcy<er7!`FYj<|L$X>h&)~gRVXkf^&U{#sh+j2Epz8 z|J857D47yl?*73>`MU`2FPtp|#tfOTZ9%re!#r2OgT=nUbcO(sXuhr_U;4Q%3Yrd` z*9Fj~!Qm*}3#*6A8URFS(onbzpli19`YzyID2OEhlCScQn&$Og|F&I6AJS1;1CYFk zyrUf?>wJ$VTK78K2MK2t@#Iq9K>-pqcxo^H^$ZSJB@DQ+e7(oo{By$V|0xg06s$cF ztX=bOM9FVk^FQdhPWOmhZ+?Ca@~F=U)P;6jtOoCW9?E8;Feyta%8>BAM4#%XA?d>=3jxonk<{}dj7 zujz7&z10b2DHk^~!l8vkFTTDO|>VY%P_L`!#zd_!M6n zFX<^?)fJC&kcsUKl{3Te=ot%f^sBd_crmZXyEzZ$8r<&R5JFw(JoAMzRna-cZ`Yz#urk_R*_~` zp;*9n^|s+xxu9wKr2D#R4as{OlquvFDJq#g91@{Z>e}NKS1#M@zaE%1jeP$>)Aqo- zui;#t({weupe^(3a;YEgmkls?5c1%Tt;eGm;=}QuXsXOhmji!UXqf7itb~e-+nhhy zjB&R@syobe|7?zjR_=EiCzz+NRv#@~7S7lO)#YuDc=QR2R7GO$;bvfI1+xbqjS{9R zwoTSE#eCuuG~cxYJ&|Loho!_T_b%0iKH^i{GKy6)SfLwgylM9+9cy{IvXmZ0ExBdj zb~5FZYyP^eG*ps3{ql%b4Kd0Cv%pOW9r(8WwD$d?ig|hh=Q{hg26?d#wpQxlIGPC% z-5@=~Omuq5PthReaPx zD7U0Vx15x6duSDiS*0276>zh=e|hdAi~K^) zsaJoo`E4l=8J40~VW5_m-uv=*M)n*J)6EMfb{VSS#qVN!2!}iaT;_7MU@vN(ow7@M zWEMzazI^|6fe80Vr5qjAl5Ollw)Pl&plNmTKOldAPK z{rm5Ot_sSkF}J!sI!GD|@CjNaszd~a#F~9c*$Ns(mN2?oB+B-Fs$Ohiw)Eu0X^WO0 z+&cXF(uyfLpeY=OX!$nm%j* zT+gJ&o#~2Y$;MFbm4Iv)`ucJ2O;5{sst-3JJ&XglIs4us#oloxO8T38Iv(7L`fw;B z`Tg^ccoGTnFItIa>P|gD>-cTZ8$sEMU5uWL=;&% z$8;YYO>_3kbY|q@HtF}4C?THIhsKHIy|)>Udr`j{|J11K3S(+Ba1R6H{($Hc zosIO;=gU$tVcH6=zNmEh4`K{+8;0)f9>iTq8r14+5Z|vB%&YPiGDF3sEF?$>bs}Lb zuHK08+x)ExN<-)V`$l4(1Ik$07di%1zmSM*DYQySzpyqeUwy;aGfMlmLY9uYcf!fk zcFjfOq)ACsUPu4}nqI-+lYEo-zaf9kW5D`1G5sHgthnZ-UT_D!4+a=AAY=GH)))lb zdJlmi6zMm;jsEq^wBLHoo*Yg%whPMz3j|a=aR8KY)cbc7!n_*&@W*PwK)AB|?gdSQS{0(N|-ubYGihAt%O%-y+E z0HZvMltB^?&ZV`~>;%h=p^y)}*B?f9C;wY!u(OtOT%>RCmsG~avdA@k7ym|Ie>AAI zMmZt31k+NMcut80`>z1sD!Gl1%9}1R7#IUK)fuXTk@A$R>^xQ4@EAE{*j<|jVd+7= zC$DY&t-|Ot$hN*^@q`2K1INr~gI>{C-M#v$Dl*e{cMJNs%&}ps?CS_YBqF0VMsn!I zmaU|fqgrxZH-zyL&F3)?B|;$Upii`XzM-s`UBs3lvXH%`lboYB^y)b*-sVPBnm=kF z+LVuJ%^$x3`|iCkpA8tK;yz?H{#@R#&wC`Q2)71CmAnVPTE?@av=|hhL~MI_i>yAL zJk2dk73|sB={@}F9u{98;6XxGAt1oKq0G&_ z7x6I$Vm8B1rXbm)6i#Qp(@=GqSq;mOqGmI3ST_rV!zwu|vhzEIZ5#xRH5?>r;x6)9 zeCls&X~aW5w$dQvF_R%y9(P$D>!XJk>C}3@NcHbiiN0%7-`g|#E)Zl+1-X3F-zI|p z%QR+$DKrfLE+Dd(TVl7PK?W}?xo>smG z>V+;z`M<)1AP6No_Uh%7wC$_VOI@Oo`$F93o&KuPoGafjr_5{n0!1W0Jw`>jJAHZL zc4|#*CsOQV+T7PDil@)*6Q6u{lj$jk_TEmnJ#0YwkkI>i1UcigXO|MDw6&(( z&Jni6UM6}}fE1QdIMWU}05Dgq2^jt7vn5t~Aa$ykmDX1D)==f1r>FS<=JQ@vFa+Y} z(GA)g02gTO1XFiXDb%1M27WoQKwChtr65?IzkvONZ~w5VgFGbo2lU^2+&0j_Q3$}E z-;v!!6O<_Q9&liJr5e4vPpcbZK$c=R!Z%43D<9;UkXDa+w#uAhy^8LGyjc!uhTDuo ziW1Z9<|)!Vb$e&+Q|dh#bbA3zZdAp0G~%Tfd8GiFE>64lw?lh0-1dO~bf- zLnv%@BKl`((!e^)hvMr36r`{BR;_t~uLZ-FQ zF_HdVOmW&_e91-)luwv6-*lsS+YhXhA|bY3kZ3U2Ckji5rw1S)$lXMOE>+~emJ5d{ z-*mrmT{!F$;DEy8>H+eu`#KnQWBpfY{3n(_!*0NYDlFmX8}hclabXXE?~{!w0#HYpCn89l0VN*5g=e-cjnSdAB5>b}Z%&!FT(Q_UB2Y0By1YgzM>cSyZk zgNW^<9^Ul zSFO6e-x5F4wuRm;+rqVKcOaSDdCl)kD;i3BW5glnpmg&_Qp)ky^0B5*n9~gSZULI@ zv8{cyV%6CLaJ=b67cQAB^RX$~)|xj}Ob{!6LUFiW%bA!ZrI&yqOWU3AUo1Kz(x>j9 zheY_C;QHY(ksx19*ylP+)?;~Z+K{TfRA*^jmmrWE*4l9FJod1kewtn#w`fzX8XSs+ z%jeVjaA47M3lDwY`A~)N%mkB#ahgh!(|vc;0Z=+&-z?+f?WTrhBhI{vS2T7)d^0w0 zI^&~%CHxR(swXt2)D&X1;J~fD{Yjz5i!e2m0ps@FlendC=Ce?_=pX@AmMyG^RJ{{6 z>u|+UsA_9NmsyH1P6{gzIYS%4ICq^O`|D?Qrtla_+joVzE}@*gzTI)B)pyzK;U|yB znjZ%;yhSn~%*R6kCLY?S=jKJLwqCIhs4J;n_N)2h0UN8}%q1!+H>knKUT>Y_q0u(d zPBwkSOQDO!d%iP|ZzljaI*C%V=TyQlSwxp5{!7;Smr2?9CF0~CmIqcz2Olh5<{2^^ zHg#;@eXeM#G|s$9blm>K4;JD5d6LB4+2^6rN31~Rgwe~VJYT*csT~JBw&;;Nv$>=j zM?q2FpFMQ3!k%(=N2UgkF@nPSrd+-Y&;K&ax$B{T4S-=XFu<2?9|PokkWKblaa^^n znFMnK86wZ0U<)wslz-Xev@*qaC&J62JezXvq72nG_I$x{3r_fg-9HeGwC$UA_S2F` z7h<_zzj#>EqH0;T^4Kc8%K}=zH`lIR_Pj{YZqq20cM-oq_v*%J+?c#K555jdbRo7Z z+UVvN35S(3NP>Yxfk*_kp&cXb+_-%1z$Cd5y=s`}qf}Wcb1g*!P8Ov^k-0F#ar&cG z-3S!G)5~RTn${;?OE58bC2wJ5H=qR6d)|!SH~k?$E0lbyw1`8*gGP`-xvs+fc9T{% zo<8!jjD^5i{J~EL<&d@dz4&YoE|O{gkBBV{)?)Th2ot+}@p%Z^GUzM>nX3kpfA6nS z`ZvphZ|85_wHO!xT_FIc;4c12uK_y>qI>Nq&vMEx zt=b;f3QIDxeT@_;wN3+an{wRY445k=X+?PBcCN_))G6K37I&cbO*JjJX5McOdjr+H z&vN(ozXk?Qeq2UNXf6G8nahX)&$pM|s zQrOlY9Eckz2OopP4>gd>zR&ib7N@@sO)&mw4*-AYw0_^mnoS>atinm~3M@D|>t20C z%Zb*@WB}5hsPwJy`c7?MPHL?ASF1kM=WN*ax4VJLD00!O2t-M24 z(L%M2v=*&wx#r1`iZ`j%I%C19ET?MED-64?c$X$#Qt>$y-k(?q#-DmSnvlW3Shn2> zWs_aUPIH1|DioP6Z>em5>}qn$*%egKRsTV-TfX-(Yo__aqW&9`s({piR8i57x!3ct z9ki5z`TSdPonb5U6VGCqDm2?*MXSUu>PgVf(vzwg_oz#mr&|4&6EBUfLKXOg%lD}E z)7nYeAB&$zboGmW@=H$mh<%GN);D5woIori^(-Npmu!C4Kx8Pucv7cBK`tRb;(Y=W z@)lbBh60c7^aEm13mfhCyq$a`+-ytRk~AETl?F}E^|eMD`t5Wq#w#3BrZn~mNDMs~ zB!wSGO&vXHJmLCsVSIaZJ?3YL;g0T(zV-lPRnAVf(ZbMH{2h1h6_(bkCN_%dkOTeE zP7y&mKolm`-SCdf}n)5x8chxDk@fq=k ziL%2uL7#G<$p8~qKFDf>a{2zF|ITXv6x{OX#|mkNnp^e&Z>~EK#4^3i3r$%HAgvIW zF^H>^*!0o#{Vc%W>uUYH=Hm)6vgKnp+xr3%%rK`b_rBJo8pafXQJt^6@84m#DK0nL zpNB*}%}q^H@M5QD-o9xn{O}w*_UzKNfl*w>XnVdt?CnKTR zDh!1_aaVpM&_olAjkylDwQr+E(R!(!jKVb3(D-}wiWP9BHVZMLA=r{;Q6XG;JBLwT z;u!e^w=!yPV-cbfhVg6;-@Y@b?oX)IDp#C$F7X_L$(C=?i|srv5|w*heL9L z&BGGXbQ^&W72w1vh}HT`50MZ;rwyRqI_!b)Xo5~50APF(4*(dd*8r-2i+|9&U{DQ^ zGWkK)$`3&m0$L)M9X9yCaX30cKf-M3)+-U`M=mv4!q7ng$1ttL8fw?#_Q4OI$1A5s z0DvHh&~Q|xQ~{E1$kuvkm#sS~F9$wG4*)qAbd5UhzCUD5k$M+L#_Aci(jcO*!?h6q z25lW0%uB!v!>4M5XSA11USP5HrMSWdB;Z%$&#-KQc#qm~c`povbZ3;$Q%;RHqqokw z239R?sgjV+;|~ewU!IDb&r>@7K%f*~L?gR8+`hgPz(mQ&)Nimh?pVWbeGz;Z?5cM= z?D*T+KH33UsHGg)H?+Y5Od8)uHB5x%KGolC(iEhKjh|&NslPkn3w}IH9lQ%WQD$H1 z+leA?Z5}n!F7i`X=iBOR^sGN`A|p$+9gt0 z4?rV;nzRXuS9|7u8a=Z@SJsHlWuPjDyWfO2JNC2jp`k79n%_+p)9lJUI$FLdqbsRS zQ6RmnxKF;lb=mKn_i(OihlAlo-j4(#e)kSUvhbscpAmrV4;d#&myfQn}3$$8*+eI=^%iJXJ80t#h=NSVRc(XBDBc#mn)V=-oP zV+pmW`B&z)DkLhK9imcnnfh=avsloEv3cI1P$AH-9#fB23(YY;Co@*w5J~ZSV^3Xa zGv>|pE%LnX%P4C&T9P8OyYa7uz`FO9$Hc0{F6sn)t%14^RkK!!t!7k^n>C^iqByLF zvOD6f@jnl4>(MYwwoF0B4jY@&3FUEckS@^xqXE5jIFYHCz9^Q97Oo$f1?s77y_9x> zR=apz@<4x}l5_t=<9C}9c31ZpzQO0@VTD-W>RtdOQZ7ICw^{1{lC|LO;w$|Z9UL$` zoRGP%H#Vdnhe`mzNGabf_~`R?LkO2_0xP#1#`0XaqalIvz=JT_nvO>+yF6HJ3`}S( zVLRdzTd|lC7Oqn^TUiNy3{UngSxxADwO;}4oPxwR1r0Jb)p}q%16fJWM>VZWj`*$A zowUr!id6H>KQ>&6`=)CRuY|vRtI*PRp1a7FLBTTGZkJOn*qJPZ+?a1!9@7fvzJ2uM z_Tlq|5Xdq40^-w1GY+{HTr;@EfpvoRzEU1O`4Xg7gJW4@&*34TkVq7=RlD6aoK1 z^OkU3U>rb;c7~?lNS&Ih`lrE32~R|YNHNtHn5w_LwLRsr`q~uL-}8bHw%v_J@F?Tv zJE3;##nYmleE=NVJ5J5LeeoWPr8=A-)rx^$l1VOfZuyuTd7^t=p9f-we_wEG*ziLM zekP!=4$1xD(V6W}NKO$Iy z06?tgTAZ*j=)H1=en$g9U0(-<(;OkK%7+^7SCg5d6}{n(8Xw|Wk6=Y=?6ZMrPgy*! zzUx9QNUWK&7;CF8Dz2h}nvZKAfHH#L#sUk00mz4`>jEUs`_|WQ6S4y0o&j;!{1vw| zhJ#U|?$j^^=mZXdE(6BGz&I3v&fZH7y?$(LHXA!nO1Qp?KxSkH8w;Dv5l1_&@DdN5 zd{ZZ2*TwdPE^3*!_jWb*A?~{_l>(X|T{;!)fZpaKOQGK5Z3c2bho|LFj?I{&GAN{n zlt!fX1r(C=Lz5m}4!785M^Uny($7O~FZCNb z+$~=RV^-POquFz7ks&aBCK&yEeL9V)594C|dPB!w52qYzmg|4Yyn&9>n#kc=WkctglRnJ#BS) zD^vUMqSGdtW_&d6T=VIt`E6vhE)Gj~&<6_hl76+M<*<%YCnF8t=eIi1c)s*h!CCRL z554X1W`{^9*m?1!E z@}Fq}*~2aD?=mPRqQ)8q+BNwhGj#9%K&%JRi z%{!e$MfdUmthYLDUaNVQ{i&{7xNnA{8I_9AXt-WuS=9x8e)dI@YOKRK?SpH7D%M22 z+vxIxpOR%oZ9&9IE<-g$(^*CiQA)4BcZeO%6Ba&Kn+q47pNf5GdvfDml@P%LDLBob zAS3`3B|=kP!VGh)*=kxpvKe3dRhAH&?P?yS7M~D)_M?FkA=+a(%S89A zx=QiP*vJ=(tTaI?!~>yhuSOW>)4d%x^Nk%SCugk9ms!ED+Nz;C(cRTF9k>6!;IdZR zxHMAi8GLxmmImmbeUq!jYoXre>&Vu?Ls{slFfvMm2;9Ksd)aYBJ1??ny#Pg>;S-@3 z3w0^HcXGuU)+ehq^7~1U`O7IRR`Olqm-hBY2kM0T!_QkXR&$V4?P0%qJ^k%Opm;fv zC(M2o#wt!8U~7RqNPh9o->UQfG2|!%@7_ZJ&`$tk`xKBV?)5aaf^nWPWx6TO-k{KD z!mWO2FDqikf?l~0MaX%HS}d#uUnb15lqU1c7A1xvA`se@k=rdKCXmScv$;5t!=1!2$vA?%dy{3HFG~}7)_5T4NH~;~rK=Mm){t@8+D~n(zX-ELL_AkQ# z;_*U$u0?8UA8^&|C+r1i`6)#bQ0rqz2UZ&y^F~ScclhV-aWK&6RtG~2m69@m3UAMb zMJT^DC#M((6n^W_>`%ejsGZ<)kIP_z5Zs33bYSo|C|r<^uO}#!X#Rz*uknK0KiFu% zR^6}s^6=nA5vvrX+t?w^u&EGpth4~_mQcDSzzK9O8#d%DNIFr-FX(0~QF@dj0SGNc z_1h!p!xVL5jdai@ejorgO%eIK7EoqD{yYE(Y#G2q$SlzB05q|2`h)0dL3Hl_gzn!) zA7cnG67BrDAV#%Qv30w_wAVzWA9{ZszwWba-G2qIoUm9T&_qYwb(jO#o)>#h5HefPyL(6SKov7y!jC5H+D0 z5|&AIY~c(Z-{PSnECj2Bs#F@}7wiVZL_raOFPB}4_-_&MuO@=;l}PxqMmgrFgep!~ zdJSfeTW-;v8Q_+ZU3fn0e)jw*h1MU@2D+^9q5?l+q+rXs@_J3}iG4@ww5 zwjE@W-mbMs(+sEaiOtOF3~16j=&YhCmpak!;o%}TJPXDBe>i&!sJOx{U9gJ6-Q6L$ zySuvt4ess)3GVK}9fG^NySo!0xC96UCoq+JyWhNfU-wMUtX1pO;)g@+^Vd1wwr}rU zR-R7)Wik@8WrC`{z-b7>es)C~fq?$~f)Yw5NGNbII!%t4yax;I$lA%e7zZw0NW@=4 zB`g3xVFUSCImfT@e(uBFLyk)D&KMqbwUB4`HsY_l_FKPF{5m;*>><>}6xjFof<%G6c-5^Gwg2U31g)Q=L32B$x*!LE)uYteh z{^{C61cU7}D6D~|p&GwEQ5an+nl4GXb!sMZM{u3W)SivpwS&iIrT-Wgd?uN`gias%Q;&lhK5L&A z7Q*iOcwnEjnoeYw$3xkG(TJM0bT04B@Dvxt0GCANudeJ$7DKkg#Rb z0RTihGw}Td?t-dP@G)6yqDe}z1Y9<{WS_yIKaqF|9 zYAl!UwlS8jP=y63Aw)?WUR|pIspZpZpQwBq6F>gO#$u1gQOg^bHrU*wEdrE(Vn@%Fn&at&$3O8jGpT?mswPbL=mXE zpE1RQDcYiMmSxrmSxf;C(ExBX6`0%jUx!})V)Z`(=zksgcmFOS3Lai@TnF2kfzXK`qe3f#n4<0R2^9uin}eD&%$>00Dro|FTZ^_hf!d01A;i z0Fp4DP!|Be9}n&UuYyGW^P}*=Hr`)?X5+S@UL zbC&cM_RXe|6`qq(tO1KFzkp8_5$6wYxS{p1BH0szXZP?7v2IfAauX<1(td5ZhXj)RZ(@ z0v^9c()+fK5UT!H!;wcX&S+zx^H#rK!B-e2-GFT90*dS0 zrOg!>rFwvQAw_0khtd40y(G7y=Phzq08tMXu~6*?nhr*cJkWP2!&PYtI|O8bPflqp zYzu~(eN4WNDVseQ+Nj>3B0|oZB1IBW{u`9#y^;z(?9|t=&-ZhP<=O*C7gTrLD_mJ#9Q4 ziO}vl-R2RUhTVZ*Re0Am5iYkPeK3)q(U?XKnN|6#uBc1iV%s;hi8_h1zJJIW?v&Bb zl}pl8W&07P56>@P@x0*P80FY*8q1skeUtsz=T}@eCSXzV5c)g52Xl=7YXGvT1D#t2 zPi!}CU~B21SITFB28Q3p?Z=V|v}ip+&A&Znhv4I01xt};QZ2Ch{{)bbec(_f5wOD! z*=MUKnY_hfubbkKJ$^$a6}z6g`SF;n#>MPVWcHT*BVJbV*T*Dn?kfb!@o7Z}VQk!$ zBHJ^KPi))RFnT;C^LUo)XVuoyq}6dTF|+5|W%QvxOsy)sUH?W^a7A;w{$ULF{(XY} z&w3#6B5($50pI<{0|u@Dlm&p9D}P=79YANQ>$Lwad^!^4s+m&^C|L889MRM1Q^HO< z9IZ<_u}#sk#Rv*9rAoRIgwVzEl+}tgu2JLLJ~=*tH+u&plE6qw?J7nzaHPL0$M1Kt z#J!^CSz8hE(%J}p*PBz-kzEsqJ}9N4{l*+>4O+QR1`FQx2ziDvhwOmi%A2JO!&S8n zwSWBa%EFT)%#*?j(>wrrj#JdIk>!*T#ekJDrBP+zXQ^xdu{004-v z;O~S^G;^5h-!bmLPQbxHkzUgl6jsSj=dqWj48qTD(k;)Uc+0>$@<97KDv*=wBv))@ z*gcr=apnXtXDwjq=NIbOG73o;sKs>t2{CaP&vvMvUD5a# zeAzGQi7_N#(vqRhPq^Qm>V8>Ehn+u8w#|W-J(6FognqueYDHQ4I~CI$sL$q&biPL- zexKSGj*=eK?;kDPnh-Kr6^)ITR&x>e%{ zYu=!Sz4=+p9R}qgLx&1*oRF*5gkz3Tjbp#LLPgX4u;(iztI&6xF)Y|S{H47H-?5GG1*f^NV{SR56y|tu4<^r( zy2oyPyBAa3`^(ums%pH-;tojPJFgt^l$ZA2a&uxYi>T;Z<-wJ@3}z9i(m}GImqn9^ zz>%8W^1?fmGLSdgBe-co-kqcdg@1@!J%xi=koZjWNhS=XL|fRc^A{6E zNciI93Y+Re6*Qn1-;2J?h~(Ay%na+{%RaEjiKnFpw|8fM0`gLdf+ZQl?V-HBC*h7x zOFe5P?rR^S5-FCUe8P0up9q-@{wr-0DA)r!Bm&B9%HAmTbFZo@6y@=$apt< zCeiOdF2z>1kg-(!ON(=lqMw4inVeJm?B5Qv_WPWBcR%t1f8`7>naK4%D)rP%hu+B% zTMs_W@0HAley!Np+)`nxSq(d)|L!nIFdB16lJ1v4h)W*1yJRb_<6w~309876Id$yA z+{Q5rM!Qnc+^K)D8~CY6##_3VR$i~_pt~U*6m&qfE}sL z^7aC)kHjsCP=$L#;xsld&&zRWY*Ns1!Q*L|%8auxIBAH-<29rrxgY@#Y2L_3VbY=^ z&_&yR-+z$ChijKp(?=)MFlGtMUhiT~p@b5`24KfzEyW@hLoyBjfTz-r(oeGME*{%d z=2huGj5TN(?@yF<5rzUcc^iDwk_`>>O|1`AMK87ODC)w_>WZD1TA6+BkK`WFG1V-5 z*6~TKZ)k1uL>WCF;31{~bKA)90r?%#5&;X51}bDqNbGr-$=3n z9>E$iFLMOAKQcIK+&2%f`&DBw$pBY`homq{Y7q|7vw#~}!?-LUiA1~@ zJRbu9Jh^iNphzJ#FiT=)h`3q-2t+u!2K7>bSsb}|cBrO+FAzd%-;50hLfdmWsQgDD zV%06f^7wpd#XT#Xw&=Prf;MWYa32Rhlk15c(cmouJ~&*88y`%_ig7d&e}J=vIxs*^ z35e>ACobLNTsLtQV+>F7$1Mh1sC|Vkgzmy`oLJ`Ar)EzMe+XZp&lgSqAt=n0l-XmyA}3t z=Mhi{Nj{Jr&cdeNzgmZ!_-ZC0tVPU7|JoD#0pJSU)^ADo~=Hwr5 ze_a6xI35513mr;u$NYt~o(woLc~h4i=*cclv__*J8Zgp4aa6h?4wNnn<30tqNdg9; zb=ZAv*oB}sF#(?_VY82?3QiPL#a;p+Q{W`Zw81lOfP}LFBLKM4u{m(D0Xt6s05}O2 zstlOBjQHORi8VTn`(VKv51i zXpM`Or%kSCMTJekT*t}`fNu$5;)!*IuzQ$Gjcc7P&jt@81}rxq2LTv1Y-lJTk<&ji zUdd<2f|D-axzxBuz@$fV(m`)1RpS#_w<_qD4>3R307$3c_(+^+=JL`1%mjem#PEg> zPjdoDeiGgiMm6m44YbzZ`n$atJ95KL0J9offTdz9rjq^ad;|bM5t!D*Okyh_m%Dz7 zI|1o7JQC=*{1#;g(zs7Q-i+#tlUOeP{RZaV1fg}^#t3avO{pjoKd&drYJFbfC$wQNPmXag0w!7$l`>th!B zT&Zu}%f9 z0hJ+69NI>lT){8>DjY^xJ;BEWE>@bN@+PFCX~#=(VukW!=VdQ^4sqmUQJ{V%d!35B zVnD8o0JVE%hb0;<%Wx!S#NLd&V>!UGS`{RD6#ol! z@eShiSMYk*jtf!btD%7PyDqVxN^VgdY*U;}F$s1+QG@4F&KS}UvI1qEX_Umeg3sSp zTAF#V&VDVO_ZCCnWZt)gImw>WPBi~k?8S`nUGmr04bmj;)^VHd= zCWw}!-W&w?9JcyRb0+`=ChU9>=2cvyu%qSXhc&>7306ldU!`vnO3x%jPR!&t|eaF=Y94t2$$)i&d@|XZci(*4F zfYZ?E#fSWb@p1>UC;M=0$!F6Q@LY1(>N41jY8IsfoLVJ|iM?i@qSSl{6UTtBp`G?q zx=A@Y7PwGt(3Mp?=VCQriuisuONbc1D7FE>b(JP2fp$a0)X}~K;UEpeB3D2t005Z- z1{^RC@lfI4)!koo`QLen;94s10{DeO3J#DEMp_+_ghCpjR>3oy%UzbsVpH zGDw#3OUCgo)55sT;qK;nc^ol%x`12NfTjaE!_~}Nu*#*&(-3ytOjIAS-$n3}Dgu(X z*8;GBQy?06gbADgz#t3XwP>C?@8jQ?J^(V`Ta?ot0K&zpS21nd1;A8+?wg$>{4tXT4}g4OcscrA`A|>K+XA%s)`i!SQwMd9Z+WU;(H8Cjx?t zegDzX`AQnvPB}#o7=UT76L;osCg264{t<}t4c2JDl**25B=@q164vc}J}dW`CKZN~xB$*w0U{fPC9p%vyigW900372Ep{m!B?5&gcU`UShHG&P#%ZbI7Rq;D?LQ$0NHV##N1BS(|XUAQzLu5;Sz zP6g8|Zqct221(IYGVxw=eAhtl_0b_wV(#<(KyH$2+#&}Z?#NDVFkADvPz(Y^+nw_^ z@w%O3_RE7sn2Gn5u*3J5%Uz|_=e|{9neql9BO(&$#h0Zb>ka{P%*C{el^H$s>cXLg z?akOzaA9f45tEJ-D@e@8A#7*f@70yfx7je7Dm7!scu-7g@tA+*Q+Ns^w@?f;=X*L# z>smeOt-w6HGMn>k=sE}AAXQfbIUCDv>v_BdP4M`=k#ZARZv5zwM2x5ubh=`Y;LBa0 z@61d@>&r_EW5P=&`grE$Q+!Ca8r(ESVu3Ox2Fxz%;geQb(O;qC^@lKBVK2ohQ|z zEugK|^H-e_=NTifq$Cn^{sWWoU_T)88>`)>`SN?onAFh;D~8gCx)3o>H;@?d2gN(_ zy&z*QsR=Z|otC$O)#5q-TRk-QHh0;b@*7)U{Z5|`z*HSgEb*7U|3sgS^pIAxF(EH1 zSQo*F=3f3I!1bTBp|t-}7nvfZ{zDakionk<7-RX*b7e)egr!aZMED{=t2U_W@ldDG zU3m>58Vl+0^#TNvnh!NXz6_q05~Kn_>L!HY#Ez;%58-PuqZAaxtS;hN%*=2Qk*tb9t-Cx{{gj#x+xeu`9y(L7&3+sslI4>tmV_6pHpbvPUtI)2(b8 zP?9FIzn9h;0bmb1oPy`8q*vClU@h3WoNRvS7dT2EjN5`} zU|9gt;qj=E+)c1w`-q-d`gWWgvmGiZW`>6c93PFR zI}TR@0NrZ=s7>>(W=J@GNdXTL6-;@W-1Y~?Dc(M@(d}P><1`9wKc^u4;46j@VRKXF3 z{dAyv%-rW)klX2!3n>z!8ITeot|qYc7>EXI*+>N|CgnG&+fxA7Ey4$YQoY2ofbrn~ zVkvB*3l@(C@5GtbNO?mX&RKYkZA@GM;(n)&_Cc2cNM{)PVa0tggYwqu0O@;sXPkWi zAeh(%q7uz~fc|$-2j@$Q{@Ez)Yh&pd`hQ3cBw(3;IGppcgNH#qtgznJWdW2BFF zl=JIeg%fbVP4*{K8wkYTX#ng;Ne{pFgIHZuA2tlUc=IEGVGD`ch9eXVA$`lNrc3V9 zQoJbD@sDo|9s63<^&`K&1qH`0Yw-5(rshe_BF3@dI6;MGqJ5vZ?Nl}oRw6L4xhg=x93xr?J)-imhplg49re=12c;%^;&rvjORnU?Oee*lQ-X|D& z4uTj2jPP+UAk0WnSGt6RA5_!1y}4|^@UP;ZauPhqBq${F;t^~{H*b(v{<#NjKh(V8 z4It~C{#Y4q=$OFB(M9U8>CE6NN1n2LfDijpHOd&<7M_5s@uy#ME3i8st?OIPl%G#z z4|CCQ_x)Z5ui%o{fpHDEKDi-h=D1H=xtfj{?*sa`nTH7W@8z1^#L=b*4u@j`Lut?z zM)|{EdBV3cwba|q8*!ohQ()|1UA-_eiC#Y?;hEb(C8hJHja%-&5G?erhp5~vM|IaA zn^S|Pv67g1>|pYL#~~gg3%cI@rX^fr!I333MEyfc z0ra?6nfM2AxwYNMgTEc7L)QSr6M4+egH^U6u*yh;mdSYfGv99GxB=q`r$UXKW0$2F;Y0OM8vNfH3R^)8H7S zzJdiw$4Y7mF&w;tqi6AF4$VBM|2vHhZ3Wisf0rR>007v}io=Xo?!6LetN%{n6`m zY(N6D3s_P>)XMbL2XK8Xv`9pO4ZLI@fcQ*A%yWUPHlNhSr_s*?{df%n`6`zCb>)gItE+ia$_-p3S9R4Kw7F3 zmmc%x&u?P9@PUQ!fFsZM>4&2Ton@I){rBoFC4)g=DW<5HNkvZHcT zBECG2({q(NS929G(Z`NHvWa)FKmL)b-*8s<)cIC_p zOZ>XTfZLxS5FSU`t4_;R=iGFzgbZsin%ZR+^KqFr5$A+=jwXUgXyWKQX=vBWsBRjm zHhp7xAC!;0aa1)vKH?A_ywcut?HNd~H4HWl>jfTM9P^QNzGL!x60RjHUF9xiCqrUj zxgCZ3ll0oxIjxUaUDT|vNMb9SGI?t3P_jvxN+w%si5xkXHH^^V-oX{3ik(t3Yz+!6 zP_!tbg{Kgof5cyLANj!Yx+pJctyl~Hm_jbPhKeu`L1wTIWH6%9Y($>;z?hTpxldZ# zHPF^aCJN2^6_kU#IHPlrkv1lGCqy#^U(o;>3wAV{PZbLR(bg|i<(v^w#i|$R#6nF9 zj>4ON?@MOjgEV4}!SClE$qq@-$qypmX{01Q*SR}5d>-6&%05?K6<%vQ4>JjS?7|;T zOkT`jlbYqpZhZlHzZr`rn_0R{sQS&fzG`(;KrY67QOUM1@hV=`7IR6yPFd-%oP z0RFzl)GMjACLs)!w~eO9K*D;b7&cMV+R3~t`GZsd096QW4rZ;38~zM*{cO(*3h`p7 zs76Pq67(Lr5&XM9uI3W zV^X3~J1DG4bO>0#g(CSCg${|cNh_K(+8g@ul)&yh8LCQrIF|#KacomPir|aj?y>d9)EV;r5#WZvy*0%u4=}sG zxRw3`gVxItXK?PEW+7I?+sN*nkee44&-XExI$r&v<3SJV+jS{#j@;K_-P!s-)m_DM z?K}Reo(mP#Ou39=gfqI23TA!_=(kth)UBkHqNKEGv*%aaHEj!@dg>i`=rSLe-zlO} z{1%N1&E%m~u6Kxupp2pyJ}YZDF=8h%*(&n&o)l^>_p4KY^c5wRyVp8FH!d&P;+n$t z_9TLk{ql(f2Xn>l6(hvIQv3}=4zq{dR_;g>*?`$nS< z$0gHGsYgK60=G+QAlp~d0~nUzp>>(H9l%o>GX9;!`1+9YkP}f{mF$by-hzRu3b$%x zojNmZnna04KUHf<;TY@P!7GVL5u^P|b=A4AYk+^W^gfz#!_dZR8vq#)(@ zZ$nU6h8e|3_m{0-rg05_f(zomg&p-XnBUu%C4&2ZPlYXfD&(tsaGnEb92e}jAQ6HuhqTCq)2&=FPJ1NRq}~kSrP_De9BcWv{|(IUAzpBjK2k;*7Bqg`$3<9vYO9K zb#+%dlc)343S^jN>s?~SEj2>Ps*m=`!|qCx0*WCRL|&MsF#_I|58 zEs?u`4-rK_UOiPp3|)N@AI!k@;0vxgVVhMH&)8AFz0;m!K*T_(o%HQe7+-exu-aMq{99|G3#2(t{S=|9q%4TMJ&l2XB#Qb6?i+p9pItSw z1V*x{cpy_Z4KqUIQ`Zss(LCr3;A7s%EL>r*I_DEyq0ge5GY!Y;w$v5UA(}w5eq-pR zii)^g3@3=ba~>rRn<*TF&k(bfpwL6)(-BUfcF{RdRm4A~y1|Q+CqT3TE?>#cZ^wUS z+|pxtq6}N6jR_wfRZm+v)k3TQGD1P?mR7E+$NehBHsLMRH~E&M?A2n=A6qcjo~k%a zObbXrAdFbp?ht8YSi~o1d8QK8vck+W%MO~k*W)g3YqHun`O!v}MPy*ys2J#mcSugU z&y{>Y^1#abWyFEmeld1QpRn?Z@uf0FEs5^&Bm@>T%~>_Y&FmODC&OYMVjy3M)BTA( ziO*dS@QN3aX#Qr_neEW;+v*KB+NXSEtz35~of_hZGMyvx2R)BnPRr&%&-5F;pK|gz zaU3D91@e~pS!-{uPZr29JHXUMn#!xzv|i(&OZibtK(-#iA{^bMo6P|$fWR>Bj(uDu z_Ijrr`1Et$d=SuF&qb!SPQbbP1I}M!)d!R8$FgtPy+CI3G!}!(VTkLObA-JIa-8}g zO~mK0Z(>F;L(_~eK#qzPK1Y!)@cboKCS|+ysJQ%X)Q^i%x|D;$G|j1JkXG6=GPGQ3 z_2C)%))yw80whRtmqi!A3CCgmFLaWUtBk)}R$sqWEJB{COQURsbn+IO5HrZvtthY{ zL6~MxD1ef(3T^ziJ!ah&&OahV{l2m{+~;6^06HTRpXlP)bR8(J+(iG@L*{_!usip( zMF#%a1t>#yc0jzA;a}Tn>D!89dNWvZ9uK|@((9D3gvVEevS2Ha_l*k$P^s==Uu{5Bta@$iu0HrJI1D0VW(hSVe?{nK8qRTB z?_WEwn(A6uw}hJfD+KSm421_}L0>CLF9jB-v`WzF>98)D)`F6wzy;A}Pdb}iMHaf^ z!>Y?r*LQO$#IA+0+l$+Ln~CrKWtRlsD4E3Pa+m5RbwADdw{4BuAqg96G@BERMNr=}CuGWfnzBH*z7EKv^2Y+`;@7KEW7a2Od+AaOn-QBk>#hha(*RgDRNsf3+i zx3e>?KZTYm8c6n8;34Ol==6ls|fHn29gXbilf?AAvLW%f#bp6aB z5u$MDj@J6sr`o>i#`9;uce50$Vcu74Sgm16R)~>DkMI61V zhDnDUukNK=o0J`4MX6O-Uyt2k4mBvrw|!HR4Dj#eL8sBn10590oW_L~lL{zm#2+Dk zx>jKUY9Pi72#5P@dqNTGm(+lzKW49(VqD{qJmh!%%asWgK=_>;i$4W-ZaIWCUwC$v zWlO#vPTo*dtOS@xbP}i0vg*GwO{wfxLx=6=cgLRo8WutI zOywzsQYs@fAU33+eHYODAtiLP?x>$^0AGq`IP*W~Y_2Yw4!0131<@M#y+2c*3 zE7tPv)9W=qciM6U-{8k@TbDIow5}=o+jNe@rpENQ7Bf8J6hWhMygV#01_2 z0q6R3(%E8c=5BiO=b~_ARQW5NE%^5BlAD<9nLju;Fdy@Y;Q1{ha@?$ zj74-EGWfxAEBf|HNovhD@l6|DQfsv5d+@@f&PS3G60l;cn^5tp|H;yowB_2w2)luD zX@b30eEYDQx7==${o;vOGUV_N2M=_rfp8Z_nrTW?mKX{4+4-BK7jwAwJld;{EQlN! z@j9EZ4fFLoe#?$i<=D}?1zW3={Tjv>cdPlFODmNZ@_aTf@%DgsUsG`tyYI(zc)4(R zJ3u9*YqCIvvW+LDMIXS=iP6|3#zwrPdh44IcJ zW#;*;T&l0`1^5Yra&%BLvk8=&GL%$I4)^C(N`e+Lt7M5I{^b z^d*SokYb*`aA1fUW^lh8>_TJoml;AZYc42cfkku~RPWOXpobV$hvw*otP^S}C88c9 zcTSutf)c)c7(rq;2ueZ4NwGRTLLcG!PS=U9KgnW6B9rFIl55+K9uA95P4pE=^B=Qq&&(WZxEAT|wsD#kv3A~>t`gS1Ll;6#bBL2)R^T8f1M|l#*vh35nObt`o6K<$!!3z)G5a@@U z#|ySE&ghI`>rahA-12eO1qX_iaU2gn*+PE2Z8QZ;tANwlEWw#KI=6<2Nvd$Y6!prD+ zz!cN(Y=yw21B@$Z3NKefzvolfXqEfUh_Ly=;|K0cTDpc+W+()?Zv-LK6{aC}I3qHg2Qwxj zGxMmwJ(FxG?_Rgt*Q$M^(3D;<74F>olJS(%Evn{5Z?j%#u+Gt(kDgJs8}y|D@l5D9 zJt!05wNZP?)hMQ-B)N1NkUDS%Sfq6zKyThx zy`LnnwGoRPEC`eyCkR!oF4){a;#59SJ2z+p97V8JKuA2?XFW3e^ZA2^$c&2)79J>O zn|5X8=QTqEr^tExxojX_v2t!P$7KaLPQwV$0u6=F(tJoEcuJ9b;#nZD(L=eAE+lzf zTy(4=W$7_~WyTS+%NP)AQPg4*NQ{g@^{~$UHC(bcfLZm~?(yqTM9&=Cgd%GEFr2p^ZKG#y>O@oD`!v3{wLqL2^9w;<=4w z)K)41&)YUe>$4_0LuOl==X7pzWbbD{PH`1=LI0cyg71X*IgdLS8E5)6h8y(^NsdQM z2RpuII02okT)@dGb_RTh2#2(Z(hr+`^S0e?F9{3%bjt4Zk7q8^)Ud~cV^ecrR>S@W z5PsPXMaCkA=74f-u%18-KOEf9^E%EkxV_5d!jYx8VY{M5`^EpvA zpBd7Ah;HEjB(mO_-`S4a?JNo+S&(5U5EdL^IB9TL%fNL%aCL2V_1 zs8*n{TxS)5K>sD*DcOh@$?hWf8oK&EtDBy3DY=fuXc^ZH4+yZ5jXg_^YtVB1iX$~1gVP5z4TnZ4(szHrQvUAYI3y$}rDDaVYyjJ-b>lpz&PxK_U5PMM`-*i~D7<;UvjMyyj( z?0JjP4L>m_?CMC1iaaFX5#)3mnf*Hwj|q-RIH^(bz9OdZDI@P3^_x*_o)e)&w`t8x zPx8mtrSotUd$=zs9^BsNZ0spch!!JxIl-4ht0bw^9lstxHB8v5ui_M`5VfYP-t3cE zx)D1ITeO=KS9-4@51gEf`~mAIUp%)JY?`R}mPBZaOi}5-vUDcUf8M3aJe~*2sN#4k zL0g3h;iNE-9ag|pIbg_%WZP+5JF%2xQsD_#I;fhzYEYje;w+<<+` z=)@awiPH@GKs5&o-af|%V=c!`> z&1`8BIsriYDTkO@;0+U952fpGYE2tml*%mzL_k*E>dS%BBA;@CJz);2fEPggxcBR1 z-LrCx^hIzCGEV$Mm?6^wUT*lEU{U(u*q%%2Wipop`~87w{X`40ecN@USF(d^FlEs_ zu#3D_AC{MqhJ`)AfAiU+#z|4(P7&_4O~Z%;O;NC2z`Z`cyBjC)aQq_;GfJ(VBS`G7 z5ihjX9S`uKTW$!H2o48 z)$%c41V=PH7H91{8M&#nYZQAfsfNLxTV<0DO?=374Tqp|(PrjHw!IO&X?f4MVOrw( zBe9Wqgz!D}m12BMD*Xm;IF)Otwep0Pn+F0_q(zu~?R?vv*ld_*`L`+uN?VtDkZCdL zio*kS2sAn^yEmNfM-A-I=34XR$fMXc?ca4B0mz)!PT?Aw#L>;FYd?r+cX2lCY0Z4da4U~j9VVe0SnDECW?3K4>G8R_86v6Y#{M#`H z($z&se@>wvez}}trbAbbHf)oT zQbN!SNn-Mc@=`C-^Q%M)Z}0gV<!!WV$fW)q2d)s$8oZ{ZpjQ5ODD-g0kbU|L5M>wv5ci8F!ebh zzwm7sQV*<)EjsY^`gdH%*McdhU$(d>i)?4r)|FyI4T?Rtsv+f-aG}L5wfKU`z0T! zB12{yLSk^8cQ0h_$fSKS@5Q-U^9tectZl&Xdvm(XSK#DOBaipY{rJ-&Q%Y8dW&NAR z2gL=3L)Gg2{$9B)pC!bK=zN96Leb*>ZcM2U&Lf}hpd#gMp6i7B@LyZNMaX%0uaD8Mmk*w?V4_LXu?!oEh#Y#hEAk=-n$whw}IvVdMF z2Styqyp>)~r&A`quij{V%tetye>U^xRPxDo63e+q2>+3G24{dJsD;(N*gig=nI@n# z#B2cd^EFSi*n+UG+6U(R;fAti$NJmHs?f{9zTuGjh&t)bNZ=6mKy=?z{&fMjg=^!8 z?CpII{ZQ$n{^8l3S|W7nx)1U(xDc<@ot|f_z4odtL*bdEEf*P`6)$x7(M%#G>#8)3 zHfB;gxw==E==#s}%R^P@SszzU#TV|}(S#s{l2g2HPS7;XNp;s1%5!Q)CXYSESyZQx zulWo*ptdd@uR}^R)WguRfmj%EhO**g7fIg}WuOIC+oYV{M|t1YccG0H?t$J}VdB@P z$AyC;tdCzYh-*b3$AGtkFbX_SkWT}B8g5$|oO!A23lHR081s!xX~3xiVLo`#xE#n& zp1IT`O|5As`O4!}zsTzxuq1u3MDung@=jPZg+ng6U64Ne4pzUf{a*k=K)t`nU#Fd)Vl=T!I}{ zPrW$K@aWvT^|1-g@@@GCf97luu#(8$4oq>>pPgCq2Vc9zrd5h<(8?i0mluxy*>R4 zhf@$VkTQ5+N8cU(yq`TEQq`0ExI!vx!-c~zqu4+~3XPlD@eOrAZ>5LuCS(eA1lRIM zMz5pHAgm|4{)F6upo+8hYGteSTti$dMnJf`@(QJXgWBn_wr(T3dggRY!F2x2^#i*S zIA~NCma5odMoo7`7WZm?x{y6f@JN`3s62%Bt$}D0lhoTGk35xSQ_zV1@8kEbYVITK=^AlZ!EVvkFVy@L zb@BdnIF@iIdcL-BzDQ;@l3n7h%h0P!?V=f?7-Pchd=Qzmr;!43H9$LhsCWwIg%9{3 z%*|e~@X&yQIMvjb)yHQ%jET(fe7>F#L19Aje(~djuEC;rP^q^n#c&1E%9DnoOXK}F zBYlC+ZgRS_s!{4wr+3|dlno1@JSRQwrE9=zyccFZt($?3spXG1_Jh(s&wF?d%V zS^}$z4`qm|b?Zj_W99m{CA0YPLL)l*Hu+PIO%s>Kr}*Fdd{p1d1caQziT`oITntv& zjI__eIIDN5f7N0Pg03~7iNSlc_ARs}_JAE6+xO26)!FKg{Lk-$tMotp)_jEU#{emZ z<1O1%9+nM#QA0m>RZ2EWvI}afX{J`tG4Z+~nkfG=SBG}azDfOgc6HsiMD0s%ev^pVs_A^ZF5>5gOp5$c)= z=`BJEpoumYCX-`1?3b)-i9%FTt0=rKW-|I=!#|b3OAM5~>N#2b-f-t)Xu8*HI1~_Q*3BIGjZR)J*-FA`LD2 zcIVbjthOq`T+e!;&Skc?cZMld>~Mg);>KJoqlSwdc?XMe>Ko-6Kmo_co;S_n#o5{; zt{_o5WOj5FGYjJ_}c10l;x{!e)!JRu$IzzzRSNqUgvhojd@x!3aG_Y6v zW!{g!C7q2JOqe?<^ft`ds9#)PNK}cw?Tv?53{TW&3xx$9BdO%68arLm2}F+Ww9ug= zpb>g*(91*D9Bi5KH@U;$IzCJ19$C}9hXLa;b&V`xN0%|UGy%T8MJFhNSf0G z$Cwg3UR)#PC|VLsT1%teqGg6&_%S|ouL38E0#KY|*>K+-H7zlVgvs$KJr0Bd_q7Vg zc4a6@?8&6))PH0?k+$6X9U(s>iD=YSJ}T~<@j;$~#r;@3=__{hU-Vwaf)!9xRCG-( zoL+zp8`pPA(TY&$zCa`&4h)ar5X}ND?m{MsVCarAD;~EczcZ;3B^y8#?-$wmFLC6} z?wLFt>eHeyg!;kX;B!JixNN}^eA2k!>O{4UAp`C6`CMo14(9xke+7%*DDAbuT7t1H z{|y{s%rU*AgiL7Y@kD!b&Ca|%DZ5f!=;ycGyYK{c*3_*4j=X0L5DHQ<%whab{31d5 zOQ^Q)Uj_#XNE5@NkU~^8Fe0~I%b2R`U6Q36jNT4M@VTiKE=^Kf>xCDThKM++X)(2H zrQxC%ED?v5LJa$eC~3BP7^!M?(7;5mujeg(CUZH^?b5Aw=^POVE;$eWiAMxfmRoNc4)R zd_NOcGAIk8c#$d3P}cY_;yB5vcOku5>oLoXB5U?H~=u=c#1QN(su6mK}8l&YW z!S@(oEq=}KgIMq*hzB~|`&d(B3fH`pnoMWL@bOAZt7@+Ij-B&yEEhzhfW8@=m!+dd zf-tgi-H{M8X7}KB3)6>tNHeQgcR7TorN7AP8ae#OO=JZWX%c63+#5*q1Zqe4zDZ^L$t z3_|!JTPn4(DM1=kGsF#A-=S2A&z+hHE4h%;VSKwq2nerI_Ht=`ni7k|a)d0b_I#+)zj z5wx&^#ZZzRFrTT@L?Vz)ozQFU6UK!p7WWDy6s&%UhXF+Ixz5KgO6E4Q#mfGsx6NH- zouLS-^cENrPc&0C1KppUErk6AbR6@tshY`hR1^GZ1F1P(-QwU8P~q4hrV30L`2dTJ zGP;7W(tOsv=3C6)SxNW@dVXiOEhPO(!N>rBiv{mYcIm?}mUR!-I#KpQ?7&hOcFSXs z^zGyBM@xL5+rya)Ymk~q6pn|JSHmtdZyDe{O6`c85=O4f zn&|Es?(@kPHF_ZCY6RBHA_piQ_mrLv&ZeCNBQLfkTyclDw+`ASO__?t?W*|y4TnuY zs+s-$BYimQTGWGhY2zV!Bguf-U;ZIbXY}M?TEqbf#;t_Hsd9#PH$rh!USER!WpBvl~tFIyaA&wORrZ0ApM8Y43q|AziY3MSXaP~6#gycxP6tf zw9a5go{AUAjYRz zgm^mF1WDror^CHlX2MYd=^#=lQUKtJSib$&|GGxk+rfQ6>E0q>5+pq$2u+~fW_IiPSK@t+uF#bV&;rdjM z)_tYd)sc*Zb5v;RP0$|(YKc%7cG&}pAhlNg1#n}Z5`;k>Y=@!=n3#idbaPn5iDm7X z1v^CIoX3a0!3;Vu`uAZJ=RyyTU2p?uEyOkjm~RP0CPYF^pqOF=LWI$5cl)HS<&3R$Y^F_Q>kfMJCo%Wp(1j6+QXZ zQ~})QP)BXV_1WoY(}0Y_s`X7P2y!fxt~^3q{jatf0R(U6D{IJe(ww`D6rz(j1-0Lr z0yG>0Ta5U!s5g^6;cUV$9Z*{qY7p%ktR`^m>-EL>3hikOL?#p9KMdbYHatk$BAYG! z+`@z}t}zd{UyoJZ4=#K2(ghUDeb=5*IhTp1Z(?)+swhJJZIsh!lhgicFFHMfST@Ck zx2?l&C}oI>c_h}{I=G%2hOEA9M`%cqh3Af`=Lft4cqOz1F?3x|$_vcl-;M6GKxdKv zb2I@^_KIa7ZZ$$J8-DWcnrb{mYMs>*?wUF%PAnJ3DgQhfTmHphKGdRHr0h$I=bpFF z6K2%f1pk@m$~m*=Z5@=p^mYOF0 zwZCiWdUjp`-@RIS+wk`N3mhjK>EUP~#SOWS08$QT3y%88ZzC&}Q+(3>|L`KNW-@fF zx3Ez)>IEg>b|cr&KGt6uTo(%F=|rB_xZTrs9@q!3o@(S@<1OD$K-mN4vs6T5oqDK# zZ|+`);AtC#{|c|K_V|~3w6(rf%13R();Z8(n=>_4d}K+Lhj?}202lG@H=%JM5NM0N zGQRliMNL9F>_0F}TS29G2-HL3%^4Ch;<$0*4!Oc|^Uq4D*u#+4O(eq5mTMO7Rz$p$ z)jR8o`jxbCADudtH=59ebkD~mty&SfBN0EDwcCu(c9Z#vl-1DJrlTh&ZObRg%aU$* z;Ob|^t>w93jUVnp<9XZ?Il-vNw+>V|E7Us`^h}V@ZktYxbR{{~VKKz<;+XT2gX><5 zYyM|_?E5Pen30|Dz+$Hn$Mw`0cEYAbez}h1C+gg(%1ifY3oS>sr16oEli~5jnK7M< zx?DN}XKDGETMO+`5bc-{nXxk-+G;xSWNya8<<-1MU#rC9-tVJ-Fn7)X3GPL#FLNtW z@BiGD1}j^5!fi-l?MOryUewtP<@K=?QvL6w@U+HT&u%1W(jQGzcf|tnp%INoVw8t! z@wAG$?#@?av{)G-?SiI-7mV*BQ?4^#A3oGsT%WmC9AD~x%7$CmwShB3#IfoOXfqkA z5sxO-WsH6mqxD>1v5<;EPLn8e9%4TM!03~pPX`xJb7>s6g%lPuTV##QppYu(tpXJjAt+m-5{%1!>_U3et zSQJHjcm+X&>6ueC>>}Fw7@lfKtWy51zpJhxxVk%bZ(GL)7fHoZTWP>9aG$aho3`n% z9Kku}detk-o=&8>q^%FmvFLIZS3Z%CISU@&lac%GkSSEQkK>h+fr+Z4mY@ZUV@}NB? z>q^o}XO6Msz>K@FJc(~pfd?N+`w$+xv0kVjK5642G`_;<<%FhPdb+PU$Ilrd4G<%&M2WF)^i04KCz7^-vxat#LH4U$ux2xz zFObkqZH@4s&qpWHbBaJ(iaV$N!Y^%s8TXF04xx&Q>SMJutV!(Di3i~1*;L%j1LpW9 zs2bTrybJ88M^pd{ez@8l$;AvxFC|tH5I3}rEN`FbO&2}#W`asb@|hp?P$|gFm@j$9 z5kOk+NERGrY?by$$lK@pg9a)Ep{3(JjwG)otIN+*COg4dC?sSUiR^&Tb?4vOV z*R2a{fp*yEyxPgSVX;2E3514z$yJMhdLM;S+5f)qUk*9tbCgoVpuGlDXvpY?xJGN0 z@KMw+a%KC4kA&QZUs7WWb+y&EGlISV8F<5_Bcm93kcST?=vb$yt-GO6z5K>4TAG8)?8X? zuly96cLrZNgg#{&MDcd2J51Rht$wCKegoY&dsx>h>yor*E8&y)VJ46sr=d`WH-O84 zA1K&_xmSPrZLiHiC6*63BuP2kPO(Z_hvg{e$`ZkTao%^lvN>0rX^|w`Wn<7&rqDdF zO^sjCp7(jQ_*-76I<;SRoqFyt$WqIA%@5nXIUB@%j?fKBm%&|%S(v)#Oe|XUjeb69 zzAJ;PB5grf8lkO21oHdq@hN`R0}CYv*wBqD0Ok9bl9{9#j0)Y2Ei_#nQQwrC?B9H$ zmE$HEOsE&NQL5NY+7TvZ9MHy&iC#sxqtEi$yw7DKCq!5>(hR6L(nQRdgNu+Nh`WI7 zsg$1G7HCTPPnXE$4I*v;GSYY8Ke_3(!5O!_BU)qOsaA`_QrHl_q1>1ympdmU&VUx9 zY4e!kg}!OM;~v&|7yZuGixspgj@#jQx%pO0I&U0MYtazjKDt1a_xrQEt4ZKz<0)TO zbylh)_UEY&P@z4uVxl@<)*YmR4?e__e4EXE!Q;hbbhO+vPk}ZyA~Lh5NkA*OhI8`q zxW3pQmSkQ9uRBBv*sTS@CBi0Ewco5#}j z27=ad7bavKvY7>~(6+UwChvpT zoMoAcCwl#P>i-zHys@U}VotAa=&{YXE?Zo&`O?rf>Jp+^yu4g_@S)LEUdj+KLh3xH z*2g*&LAT+h__M|QRFq~DGUfRR?*~Kqpm6_-*%C-(F{=S$iQRM~lgNFQZjv{`#^R=i zL$ANk>cMSGeC5oCcWK@*%Kk!^8PmVbBD$2bf0fy~pRKqXjM>6a8shu(Nf6C#yh#V+ z9+jxGz-9TT&mpHC>356yN|}3>ji8AxLxC)grOU%QPwdLU2#t*zIa*9s^z zZ-^WFCG%*Xk+Y@atFE$EBV=q(V8GhX{rfZ@Hlq!&vIGk}hM{DvdqNwIPaA$1i$T)| z1S|r1VE_OF0J}#RKDzHe68Wo!heP8h;yn`z{wBgDtrmKJzge>vopGgc1 z&1}v=9GiS96U6u60oYL!l9a`ZX@&XJ?qk|=@oovGY)sgiI zC_M7rl1+j@3vsmeaubaL08QW>e~+z{f)C+5%g#3Edw5N#^SV|$(<39yr|T!- z@=ZwmE4G%h?JCP*ri0Sc*`zVNPNh$05go4i+#o=6a3NO2zKj}qv4ca?Q1umiomg*A z7va3NJw&_DD7Kebd5*`FsY?ZV*L3J&v^m-R`Ua*{1^xsJZw-q_wa#V7!$E3d%y;sK zaq*J#c9-ON)_u=QL4(QjpEYDA2G~OOD-&-;qwQO86k7ut)nxc=VV(XeN6{q`Gg_v8 zrk5Gx8`NHnWPESqBgd=kN&Cqn^@u>D~rl>anc}6mPb|WwgMM29t z=$?`ffuB@(Wz~662h$)+Eu$s?>Qow@vsgDS+OB7LXvqE2&oQb@Li5b*7fp`9 zCh9;9fMaFijS%mP68s$n29z~#U~goornZNVp9Z%G*iPm}Of_wN+X`r9Qy!1eE4Jbb zj9hn#;TR8L@s=tkT!Pme5OR|Lez&U$B_Hq#*krP~Y;Y)$%8-}+A~)-91olvyp(%P* zj*x$XeTpY>AY=+;+e&(cC5-!GXz4b5etXS0q59AE;$3r^Q%;RSFm4z()pFG&u9Qf& zwhwHPUXKm`@xRD&gfYW`hcjdI{=o>d)Y0483zWLA_&Q>r*UH<9L|zn$@25#i*fc%o zZS%almDj$w$W&T<5!Qj9Mk5}PhKl#`T}TW=K3ES$E-T=dMGBacGDd>tq>Ag0IvOZZ zg@NwqO7t#VnB4c!X+R`=Rw`hJ_ArvJR_zSWM9^RC6|iL~r-KJ(#DDvQH1)!%6CxT2 z-4T$lc<}a%PYPToXWX7LJ$}t#Eha~zX~WHd6f=7$QU84wnOy!lxtHMJv0l!KA1Lcc zgLu{7 zZUYeK448ia;C`H45GYf|;JDIUm$SrhRybQZ4cfm=migerR+pcTTU}S}b79TF16P{L zgJXL;k<75P5eetqfONJDtzdVyPt8rYP*e|`6T`O=y26M{VXODbrUgZZeR6K>tjfsa zD@8X;dbzhW&nEpc^9cEO(|0o^f!)vS2BLvqx<(qcA9&vSxXk+CKGv7f0w7{KB%Nc+ z<{y8iI?P_a{M3pMcxTQAC#7jM!T|cNQ3+3tr_71&Y7u{Vc6y1_N1xH!2t4+20RM{e zO(T*JYZz|{df_$z4^k+tS>7U>%jxAOPTUR*HV*sgFZX1ceh4Uy^_Sfi=g9-c7s`Q( zgsmvEqhp>~jqj?HZjTRs3r3B?G-@Zs6V>9{4z$XD#Vy2G%^y-qN0cmWwZFg8px1fP z7ReRzlK%#Lo;&s;8K2Kg03qc2=yU1msE)Ef?m`xMkLd~6N>pPSb)DSvO9d^ykDFMd z#B98}tvs>J2F|(r^Rk3?27L?j1Lq4)T~}5$Ejp1EP8L2NaQlH+Ba|+^gOD|3M*#!d zgu_oiJ*VV*)3V>ayKuIQH!rX^SNPh=q)mB7W5np#8grgV@vn@>y}n!_c(Ys7@qJZMD@l(pP z=8ae7gCRQ`pZfGdj^4x00>t2L3h!{XTIY?LUG+9IDS^P#1TN6VTI&k`0Z9wpft$(B zHd~`u-<6}~j{8FdQRM+?z0#|fz=S)F^fR3A>2<>RCtS00#S)7_Ozjwvw~1@C+FKIG zh`;>%WaXQRW7FXcko9d0$%6>u(#Ne!lNUrAk%Uk%+%$R5@LG_i)d@@B3=I%Tzggm2 zl+H077oL{uHi&*py3owS3W8(TM~N{z)n8E+m!--oCGwQo%1BA_!&ILp@mQXLIFx^a zGiyZ#6{^#&E&33t;Ej8zzD+}VRj1tDqY{RCEL($OI}MrNJAITegWN8^$4g-)RBx_) za#NEn6xIJs*5cKA8)N{L-jDhT7D5SJ)anB&&@m-4N8IC(dw&DS!R$N*@zYt3ijr2eN2z8YiSvzlu5Lse|QMrqi!q3gIhHzDEi&iB#{x zsz%C4y!6GzW>a--5cCt;-xd%7G|I4d#Y}pGTdP|04Ow-Oazyo!x7d?&3K4V<>Q2+$ zP9&fMDMo-NIXO8RWkcb;OB#t0g=9}Px^Yq5x&A35N?=WJ3efr}-9vLO`|51SbhMiLrmgYTO}Z!Qu!10k1?d71vw5ZoGSxY<+h?l4kTVHTE+YP{qCu{2%cdh@ zWI(IL2Sroe514TkpB*A?ar*`1oZhaDzn_O)MrJavjK; z3S;@2!1LOPJN-A9(ICX>EaRn5rS|ukn=2$pO z6UYwzSIo#}O^`Xj-ubZA5a$TC1O&r+rR79}%{> zAlIX&&l(``Ez_=-k*7UZUAM@6oxzS>m?t`I+BlLvYl-f2;N7$szi_D?241$DFA30R z105b#Y<6-2JXG4~?P3*_|13R5275W(pP|0|J~Uh_gJZQ2+4ydY&g}cuA0XeBo60Fy z00H+6x~7O;6mDZ;s(yy${_VUXyhWD8ggG=bEE|2~dlpW`-kH?oVjqt)Lc5-cT_G~Cguxy7Iw4h9lLOV&)ci)7fm(zf74vF>1m#I)79r$qC zu8ZK1WjFu0QW;8@SEJWtpS45sVlw-VBk|i8nNbB(|DQRVKHf*%FWm8&pHaf9pV=L{ z(Xrtwx=*^0>$WDpk8AVo8;L-XPBNfi-#0u8D9?+d9=lOjofD1TqeUVDx{$UJbFoUr zb3h)nY@MC22^9zvq+{`Y5=Q@M+pc*?(n8;r65J18hB1sC*J7DP32R1wlf_4iXVSf(yv!!+HEhg?^y3oiQxnPi+qiwJR`|I--c(uu#Gj zXuLLM`Zsgy2eaW5e`0#={zEJPd!J9nBS zi^$>IL$(@vHO{63$_h{;0Y0vo!lTglt>k$O?z7=7IRtll4Q(~`Bi7m6-Mm|17BnNA zo0IefR5W%3q(_lF zsn>-`NARw&J%=9VY@AKgUQ*j(RbZ}5I9#LDRL;y}%1@PMpZjg^$e!+{i$>(r79aqG zUYdZu9W2IOjt~-|R|llz^L$5f2d@g|(nlnNLVaHR30Vj&QPl~E{&DE%IMoYp6C8yp zz!}%4Ha^*IQG4=(Wsz{hhH-GM)A(5u~_e|!dvZxHuWxP^SD=Y z44iIz8*2MxBJ=TQRGp3W@^c)H+J%Z@Zdk4<(OzaD+r)^|*ruirmf|IyJMV(0bdiNX zrwa@T4amzu2=>bN?3;ocr&LDeYIZur`1k6G@J#lZqMX#8z{P$a)qdFac;NV6>vmHT zrWUIsml+Mon(g5-o04q`sgfn2yg{JkBOIn>cM`o#zn&Wh3i|q#epvRCN z(7+M&9rY>ic(Szs`rv+T`=xE$r$Kt~%vTUY7(7QL*;&jnY2Hz^+1z7#1}RZ}Ogd+A$0COG9W^+DN%3ix3lX-N{cgiN5` z>i^Hf)TCYF_rNAhx}DtB>eK@W@j;?4Dfpb|)u|8ag7-Q;6&t@WvxQGShY10gGmHQJ z^rKlGjbtWmtbRZe0|mi{Nx9-mBR4+TiCfe9Am#p3^T4FHJ5c^+JWXJb!*cMrk+<#N z`8nqjgGcpAx;Ls69^g@ zI>;Y?ng$U)LrLxXMJ>L1f_}aHlniqN+?!aE;Ep%7e--JAqiV2WTeLCGL{`R9T}$2+ zHzG9oj9lZGKuyCrGPzsBupk?@xlxkM^a~NQE;&@~--@drWBPf`ZwEaq=TGD2%(LCc z9VNE%Kvx$lw*sdeeIB(9v;O|Xgn$4@eqpaN?4pB?8 z51=e})JW9`KWX%rrQwYB=yY{Hf_*TT9}Tx?RUa$7IeUHDZ0}Qnz^EBlJcT0%nHe^)2^;eGx&?jXPlSnwDaGJRX%j~R#H-z;OgtJ^sSyrxA^I$#^bO4@hmI5 zj3(F2aQ{2~h5JbH6iV0v5r58B$#O#(jG3}FBZUm};Rl`W< zr;z2szaQU!l&r=*o_3s}m&XP&o5tr-E6|XGK)7vUx$Yo<71Q^Ho{Kr{iO>$+{O6$V zmBN)Aek7dUcChlG5z&u1jaSCQjZ5sDOb90(t^pvwEY}wYq z-Sr|9cJ533;oZ69jdPN5w<+N2-4LWev+J&9GxI^_Hcl~9Do8CYZqKpxcY&bm7yLE% zC{hO9ndlt0$)yEh>!ipDGBk0!H-vCYuIi{VpBg6Wenwi`Ewr0qdGaF_2mRrX+4q1} zB4AX3gm~SLYrR(|;!T-lDWwl1up5!arQZU7B}+h~w=nOl@dg_t{t+@$;?rJu?#PlX zTtl}e4ThSzQaW>-P!1;~P`GmiHU@*O`+PyTUpl%lXtk~ho&rjRQ3#yCzn08wz*zw* zmGQB1A#S+`{Q_9;w9$7|iQxh-ruFN(L#&1rM)MNC%oGDJVPBbtq`_-}x9`c7We0I{C4^tosUmDVh! zJAbSTv++RWUc z@$G}|E19@FHgVjPVbziF5MIiBzX_j*k)m$Vbtc^NGlpx44&`GJfY*?C?LB%{sR?~S zdvy2ggG`%np*iHOsUKgDdK-GCYtRftMdSAo4ufVn#}Mj5)B7#@e6Y1GaE`(Yujnwu zE>9sz(cam)-32hp2Gi6(eA8|rpFQ{BJ&V@{ zhw37-Zk@x?R~qj?3M{A81=(T1U>6_+clHgLEGLnXPN_Yo(95Xi4AT5!jgzDCz#YyS zpLE8Lj7B*Ie{~qq5F}o}6I5EwO|S^$%}i1z0*`FcmJy$-+Cz3C}KpJVyq3&&{LIfx8{P z_i>z52p=1Bt_SG%Lp~+tz>vDebLoCCRvHDxw%YnFTM_mN8!hqaxenlN@sorx$u2MV z4=#D7o&m8ukA^zn597jC0&TXkT?I~va__~Oo2{?zPa(YTxz?k0(8$q;i3=_6Aq(ID z5sd&D@n-ph-Lif6bDl_GrK*X2*Q;N{;S!kat;Pz8v7 z9t=#Q=P?OViS=C}Hg0#0uZzMLkexH`6LJ0d-2FtW*o|}mh+FK2(Sd*;6`(*0Q75ba z^zE6~n?>8AA?&0I=vNUFyLYupY~l=I$FA{DM{aRlX9w2GvOdCO zzE<)Q12g4(KxixB&lP6Qyxk2!HIwaKo^cQ;A?bOYT#J4xD{$ys7~=<7QgT2x;@Z5; z=#m1A4RFmlMm6>usbY;0vkalIe-4j4!0!xZ`$(2#65^-X^O6kTb}q9N3{?jfHE zn)Ff?Z;ZU5wBpD658)u|AmF7skTREP55%e*1&SgC=JhE&^X;yH?ppS4>DuP@;Coxf zWfi1EWEyMQJ4kWqFN7RUA+E!7${^AC`HFZQ2q>63Q`Dc2U}*lyvxV*AWdB*>aUPRl zY{sJq(w`A2IC`1LsQ877RV{(Q!g6)E3sG;Ta%XItiDg5+E91XdVgoYOkK7sDZI)Ux(-s9QF!p%d;Y(bJ$fk&Kp?$E9#??Cpkb$ zo4@U#7>}dlWTWYUwW+Rh`F1%+F!95nZoStj^)$%-;ocSiuA%G#Ac^TJXTj5T7oP8KQsq+rd453yYU%%tgWfI_6pR- z`D+_%=+51J*In1v;(wgw!^hqoR$h`` zyx%ZWRx~gg=~ITkDSMBL^)AaeE7l1z1zRq!ghf^QOI3s`z(;}ZXNDkJXu-rD{Z^^6 zVknNqF1EMiW*FnR_Z6g&&&Hf8LKo<(l(8OBtVRw_2;&%&HxL?b3JDh~IJy~K7B~aF zU1`$Ntm_fUGmtoMX4J({dDj-7+>&g@8Ah!acdx)XxDyv}R0Gv(ZnxhZ#VaNbBM;alOn0QkCX55+yj>-4a*B!*#~CMSR$$Fu zp9YUI{T=rnKV&E&yPqzLCjP)61WmTo)C11|#<|77+d@bx;!}h3^gr#WYZ>pgtnd!< z%g^YeAHq2w?Ss*QOx7c@`W~;0k8I;&OQ)I~8<>R=wMHeD23ES8DZ?&r+2s4>?cng2 zmaJG9BgC(mfiB>dRM$twUQ$OUtMITRSAn?=qjt~B((1CbH_pUJ#ttkZhX3*|Ka4*E zw9hQJxhVK@xbC5N2J|z{1og>BEuA>;~xnO!Vvb+p0E0>qg0R>NrpE zsxGa!d?WDl7@Ge+EysVI4g>h;+sI7keBy*)VNn8F<;~2JdRJPOCD9P ze9rROCE8ro07QTEd0c*0b0dLwkz<4zk!tIkA}SM(RlX@h(=m%)@F@mqH*xFjH1CNEiU_<`Js1vhic-BFr}|oan>or1qPZ zD})ca&(DRh34$(TlKpWMqB`7Ql9Y35GDNyP{gsLi#^KFe3q>79W%gIrLo~k?c3=iW z^p$S@UscJ$`%8!9HOD%o9p<>PRx0_ma>)Y~8K_o71DVYi!<;Q6e;r?fo@bZN9LyD9 zkpDU&I0i+RASYUDK%?_=TW)V3DD$~_6|&g$v*mshv`uG_of$x z0EcDNk#N36NY_GLisi-oYXV5E86UUu%9=&&wC<%RJs20OTv=?W5$zr?C4*ZJIi)ro z+P*J5LDcZQKPV>QM?PeR)g7TV17$xJU4*B9z90Yq|HI-k8TW7Ff&*=ML{eDl*K*kQ zJ5DD!XM&zq`<|MsNr6LUH!AskyEKj&h{fJ_+JGU{O8f6Npk);d*?@b&>Odj(9A9YU znj(j8P6YPUUD(H9|H-OICS2nC=uuDVP&FF!BA zzQenbOpn<~Dx*{%tYLA`dP-Q#CJx;fyoeTEewLL0OFgSS9kecpQbYe}9D>g;uu-M= z55iG#jiZ!M8vTRG`ro#g^wPC>TyH-{`z=5x3NWDrxtrKXZ(Il1;y-K!d5d;%{n_rQ z=x)(TRV3$+cKZDot+YKJYRBwpe*r>DUSA%CCvek+J*1{$CKe$xR`le=MCGS_85siz zog!Q!d_-I;rLY$$CZ5L8=92wYR1D;zDga7^9v*IMWqOd@0F`mzihVTF+%Q5z9W^BrKt)+hS=@ zgm+upf1UATz}pcK;5KriRj1|16dEiy$sRX+4sxulFhM3`DM6{K>=?A#Tjt0oCQ5=F zE7M;oai^r6!FgbqpdrqBw7eFd0x$DrdflITb+E}yyLNG)a3}hMFOq-~fdcCK^^Gf= zDkC(yr+=cEIDIs^6->moUY6J;2Mc*-xK;-zAWaX8ofcJOqoaUjZSrbmC%;!47ZIPZ zb?A%(5NqrlJPl@X|3(jqLbsFn@AOH`Z~~j$FFZk|XZo@t)sZKfL4Y=~n9@Sx1aPjd zt~<5Y#uMqM8WSl(QH)y*(V<9wHm1Ahuhx9i&fMHkVH#(GpBL1`H|b-ipp>Lv>p3!G zF)dyFoanp;y(LlO-*${fEh8)2U4~k201aK=$`)QxOgEIbIO<+ZW5q0ZX8zF)@D0J2 z6f+b?W?+mW$xxrq@_H??R$#-*7Cbr`@Gy9aU?o@MagqaW;Wfyxv=11iQPh81Nd6U6 zS2G{V2x+$mLs_xa99>`a9HMn}f=wt@qNI0hf9zsTLuhdB9@G6f50)_MO%wElChJ+% zB*Y_5nSEtM1C7(Ab>3kJx+Zzi_8nIEB_tTW{^G+Vj~3#jSICW`5?5X9YVjx*$FcTM zIf;R@<1JNA11X+1eE>p0y}!UFtV(r{&s8E)#Rm{45M_ja8zinJBDO)(rT%2I`kaag$nyH$Fb zDZX1aCY^&HY<``aOMenzQaY&gRp1~*k>-43gYSm(g7yU=vPY*e=--{WPv9b`>iRx% zGq;EbuQ8db>cW2^!ySDX6G|MG7g`t&zmRxzkGQGT`au&$LdI+V=+Q$Kc%Jj6ynvEA z;|5!ze>n-V`mu1_Y=a|QCF^U^j4kF1Fd<8<&bE-6Dv%Ol>5RM?dZKXce)G13s%R7FAlq&_BvX|O4 zMMF&Ijq@>G$-8+W|JfQM)htxf03aK8Uscr&$~=0tO})q5!TOA`A=%lCm9DKe zl=i$$Zpeot{^+V&!l)QaE8L`p!xMD4KvUe%_Nw+M!_2wJ@MC-tLu+)P(UkpzSG z@M-PMA{E%{*QV{Uyw%qqYOP0Qr@DTTONbMb`J!$nuf2FLzBYoS;&8as{uCMAtw2|{ zBPwFd9C)=KKKMT2JmIL*_XmtG8;A zBOS7SLwUtw4Cdc$iemWb(`eR6v6Yd#+h}m;kowpR+rXz<(t!%n93oFQ0YkJGMo0!Z z?t-2%8S=q>ev?v&57pLcY#p;YDtS)xAs*O+XS*U$Pnal)STLdy))*3uI2Nv6@nl<1 zW15VP-ggI(O@9?|G@sSW2?}lDu1H*puq-H^@1eLlja?mj*)H2igr3dlz6XVcwzOV@ z-?Hl%QB*8Lu+iYi{mB2JU%HVk3c7+TQuaHElkX=jywo@ktDiM8W*ozMpI0zV+eFjJM#PDr%c2K7_G9Gw9*P@t-PlKv1< zxp|N)UoUw@LXPd&Nw)Wj?^?L6`(Z0CKE)<}!nE{_e^}vf^VUm=}=O89^RkGQq#)}I8 zOs8fMHP>+~K#%ny4kh)avL9VkfL`2&t!h;dG?LknQm%~oOah*Ee|NC6cOtVTea5(1 zOK-YEEe+(}X4CT-D5-rm#VC0V>>%Kdp`FABDT9OkftU2}J?$yR?tn9gv?30}&O?(H zC3hdj55InQa=UL(?rtp@^efovwSJH{g z7TD%OO3wL2D_4w=?eP7S6U#qy|AEF#|2NF$2^bj`LQ&c*)anfBXG$&v^fyma9n>(F zSA22BGo7_Wle!gO;V?r~3OMJ-aYlkHdL@&wyS z!L7KlkYseamYyAg>i3<3wLA3mda8`b^Mr>oUeZwb`U$9{g*M@gGFrTC%)E!-J{a~u zeH#;Xx>XDEH)6F-4LXnr3fN~)cm}zUxOVUEGrWtI!LuYAuknbLkh~Qm-S_N3MT72{ zSmx1NQwK7dQ2Bq2P-={>(<$ z5w~YDa6$6Jk1Sarn0Qt<6I9r6J?!6^M4rGwEOCDj&SI)u8>jeV=bWk6d&Z9A5>4iR z_&{q;6?)X$rOLKhFzwub#c988fESqwADm8A;sMcpSOtR59qujS>;i-+rL5g$Oww&h zws0m8M zCd{t{{bq~Vf1D(bA%Fk@_jxVB^XlhjKh;@7M1!Nbny`8m-Yl z{;tvZV348acOR?qIqSvuLTb2oW?`{mcQbwym7fqSee7U9E*U96Nu?&i8B)D2%Z^`7 zHIWTSLu!$u%X|55rk}B9aKT`oy^lmaW3X4(y%{(wf6{zy|DzjTK-M z*=CgVT&2K6I!t)S**oZmqBaCOC%_wrgWXhyJQrzzTPw`KWqh|Fw#3l7O4>_qGNIJkpUQxBmR`S3bUE5z`%07DQ^4N zG#WBg9}DmLnLo@kw1wQyU%*(L55aELwLHg|rDLnl{aH zA|*87HG)6%o2v$o`v@9cfdqTpuVysOcG!(|bu3=eB%ejNQDbW&upJi398#I}b_mo{ zQ@J0ANd`623rXW?YbQ#6X+SZwQcX7*)9Ld?>QU{s4$q+MiRH@M=QmuHw-!TdI8i%p zw){1|Zh62?j+YDL6eG1{$^TT%!!Npl9zjw$VLGyn#d%AFoY_HPxLcd7au82F_aM(0fNfRn4OVz=p@rJIwB%J1K0wil&*B=5{m@Jj0+KisLrmaB2>$>l%|0~?91RJ9QfnZJGNsJ_2!;Sluog}7p zc2)YHd@0;UvNr`+du_}Bm6stRQE3WQvdS-Ox`qHS*Kt;=m zLz%0~n0zt{{5XDnHF?5IvN&JEC8_He_A{O*07pA{P0@z25neC2<-yMM9C?Jz_|2ud zov9=CO>O!5)0_4==bTQ8;is4a-l6|czTbV9f(@gkh&9YDII90PYPq*8>Km>mATVwk ziS}{zyIFF|G%c=PJ7(ct?nvW6V2^-;({|)qo`sJT=?edy^7v^}RhEcJCEXtn?Oaqp7jgP%RRMr>(00RKS2jsU&5Nf|8e)+MX z7o9h9{D->2S*>ALIDvG-bDe9y|MZ+FEJNylnp*p_wf$50H0`|u=cPH2az3nhp~~Py zGb)N`i4~MT1-e_>!&aDW=v;_KI5*&(No`mQkq2QB^<;brPe_I~sh-BZ&}s^07;$Os zp=@Ziq8qoTzWj0^m%bPGGf!!sfY0qV}b_W zG8W*+Q`yi;1#FlSOfOf)f?>hFyj_UJqm2O*m{}OQ`RHO-fz988rRISBn!?jiL!sj@%;sk7sTGCelybOl+moj@`Y;zPKvyF1nc%gm!{VpzUe%`+9B48Y}F^R_>L^RtERC;y!S7pZ;4&w085( zK%Q`8frLB~0e-}@2%;e94dj7AEPwAeq3jn6RzajCAVwx|yaA9cwTz8?FM2n(^Nnx^iiLANKC$+er zd2OXsF{}6xq-S4koqb*3H}h@IizX#h-e?BG;(nZ zu|kkt%uJ?~osmu|kESaOvr%Y^ovA~8KjdZ0M zWK}0GWtr6N8Lj0^y80wF*P5{3b4Fij5~gekSNNd(i68Slj?^~qFo2=q%q-qhgrwF+ zOJC~y2w!Qh@fZJ?$~`cpw&7(L%R_K5uNRyCO;0}8#>UMOR}_*@%Id5NN zHBLI3RQEsRJXka-(~6?yu|LM@ozHaBDj^_%L{*nr#JpfFtTchO=Wq;b_M1qFDA)Fq zMhk*1mG|2e*T7)_{*-5o?Y9kZ2#r@y0D~I`tD9xsIEKC#@z}fcr$ygbuu+d9rZ{+L0xaL z>JooAS$Hcav%&~(mbfBxJr_Wgku(@luy`8ZyY-Gm2D=DYj72+WowbGlJ>i|Q`B1VH z)C^Q8sI`K7k3|eu*P4@WDCFDDCV#4httBk~Se#CY@DiC-yr~C0?$I#=R^?9Zsm>jo zNx_F%!5>G8=IQmAmxo1AGT7A=IqsU&VYCnwHvvai&B8${g~M|Bypwn$G9 z@n8E6$CuV!(gLt z0sSc1E5nT0AzPx|=3VsZoZt>p z6GGWuy3a zyCElPfB4#(eb>I+zPCfTZ0b?95K>=Vv8Da{lul;wGS%kBVgf~!3ZdcLqVSqJxcW5V zycq2P!?}1QssnC#$}fi3dUp%}=c0WV#q+SrS`9p^eBuZ@NG5aS{TYlY#-)KSDr0V` zp`i62tHZp=lIFLHC03xLrOn`I)Ed0}QK_t#&7l67s$?w@l2$zTH_IFS&3e0Z+2|>d zH|)U&v_|c29V4n@`^=+LX3{TSqqq0Pc$xrwU$p=>PAfpMz|>&T>NqnMtmAh(S9&$#z^o*L)HaRv) z<)30<7ebmRKf*E7zR4y@sfpcFo~*?O2QR(+M@J`II?k*M8P~pco{PW%p#7tiTQPGg zo@Tb9&{4nkFWDP7@`=bWQ}Af5D{V`ne1snju+^3O4r` zB!W<-f4IRFD6GB#aHwET9Ek$A^-S)4Ihj?Gs0cBj zf8}@aQR{plv}Xk^_k$>XWPg^{iA$0K`PHYYiT?Qh?Zjf%Xv?5MXA={vaXs$^)g7!;?;8=lFsaULzLgA09Dg(&`XE zwKC97ON56#RyDP8k8H_$IUXH~i zRSn9--3Kf3kW^VWo%6TOgx6pDv5h)#VY%{mdC07T8W4i0!^@tsefk15_9|SN@6miq zw~fN$9C#xjvx8R3JW+LK=&OKhNcrO#&d_)1HOXhIMMto3EOKc+=| zMXNCfQZzWsz+w`w{*P`MX7$oh2j-0WBleLn$l>_PRwSir4y3w=pVyLs$V#(V;fn3t zobNsDTSR=*>5}d5bq{P;GUG(pX!?qpR2L_ML-Wc@UjGJZT$L$<_VwR5EP$mukB$bRqCwXS@1+2rm`=w>f&{n=pvI(xGql$ZDO3T%RJX1X3iEY+({MPf$9 zumdj42mYD^@#+}`8u}Bo4p-ISd+FZLOcDa&!WqF8(EACMD|Kq}BJ^x z8@WQsJln=~}4%;|sWDsb1r7NiLc$7QPqO8vCdbUNJl)1V4Pt-z!1yi6lJE2mh&6^v;r? zTQ>tPhf^WRdcd$_cWw_+F&eX6I0Pci4rDZ@LRXFcjAoF>K0E6FCj?_0f?(KnU6Wr% zeORb~$8;m4D^~^#;6l*OD_;6j;h58=+GIg#*ofzfK~nafXh{G}2sc1i=YSi9F>lvb z+oV6Dfh7^p#NvS8;MgyK=@$|O62?!W$2^G=<|C|g9iUWw*ufX+J}0zpt!<0tPq4SE zv{nOoJKr($;dH7^8%BTCzww5v*c`_=7!36*W~6utp!)=*!*$5#(0{i2pqjp!8J{p1 zBBxM#a*&qbOBAM8WydsV?~EHaMV@s68XiK%$;;6y#Fp0X*|B%h1^UtpQoo&YurzD4m6pLGsU<_#oB?W(squ|?}`k`Cm)0E3scokqdu8`<;$4ZKAfZlGCIrx$`3878Zr9t*h{3x1FtX^Gw4CnpsF zhohBfoWz_2$?do}>YXF7^d`M#xJ=2G=| zZ3;#NBN`RBmu`vWkyZ#gQ}3jxglb4~Ma}%!W;-V*b>=(^roGckYl!zzXST1yNMz$6 z;_Vz#N!RQkDZ8_bn>}VySWqx)``pZTV%L_Cr6d3HMYayc8whwpL_)Io277o&LeDCj z!_X20I-M{_YfUu&82dplI{2+phrTLJA2`nLr4H;n_CxkKeSfleIcM;AFOt97I5dl| zkrH=B;Cp^-@>Gq%x(WcEPtHHeM0w8h8dmpth-JNgU46)ZnomAiA#_9(;UaV0#mNzp ziXK+9+oQ6M@H{ZY^3KKMWzm2OzI4#Voy9x2_n4J=fm{-(;kT$NBGOE3lgy7{H!um6 z3gPk9%e)`6)KsBbqb=GQbDv9>`PTuO65c;gSg^y2TTTp@#IO&TcVb7S`5Kee?BwNj zJd7Vv1+N@oc~Yov8hDR8b}bHUXybsi;d|+0dB*NhtYn1mUc=u=#lw|-Q zx|R~y%5nnL*xmQ0qDULXz*{wJa!xKC_gtrcRyCV}*NyHG9i< zeul}6MX~fO4)*qvA&8O;mDNB2r>J)Sv7364e@!N$AYRRZzNjtm}%C&s(e@w45c#CVUCI$XqgR}$82ct*o z0v=q3`MZ_%-WhW|RLm!4u}Ss9f7OA!ILP}^4n~Fp9x*G<)j0$5sjd>XN!296d~3oE zWQK9@P@PRL%=VWoW4b854cTC;|qj@EwmXTN1P@M3s0FNE9VI1kDb#z zbYILVY8OhSyCH4Sqo|s}Jcdd(eRxCJ60Hh(yM-tW_l)wu7YwNI3_NhjRzrQbbQIV zIsPMs6pIR;f&*%yxTqPX0#wpnFCpJ-%zpNpR}c^FQ7v^7Dh7kc+Y21%@Vs~g!Zzk8 z0$ZY%?$eQmVnBH5rep)@la?tazatLo1a2vzz=RoI!o8F~FIDy4(>4yrLmDFt8erp1e`;SnrY(pg8MVyqXNZU6|yW8UpWvjGu-OdOB5bAih&>uqTDPz_lUQek55kPPOR_+a#-Q7u%q-ZicW}lp8Y5Dx+#(LH=kd5` z;Ra3lw&4<0FRuJBM6=0`DPFtt>w?AecH%o$Fg7QJtPnCoJ)n|Spk+V5j|2HGe-*ge z&9O?f|1OtSuxU?EANsz;Pg%b8uV}&Vb+p5pC|{3L&_7)y`acE2ZG5~1o}>3$0P`jB zfD+Zgloh(DM*!dvh_-86d)hYk-NFB>3`II7x4=Q3=f!SUD}3M4;xE)OUo}-KoSxyW z>H_5yOBXQbp&qxhM3X<=VR#00RgNLXE zRcdjiAry1NCSqgsak7R;ri6hll*4f13+NQvYQ;C}F=zk`>wf-l96@gOP6eSrzK#P# zj!h^lKQenM@L{Y&lps+3y;U-eHuGV2o5{+g%_1nAyd!W@_Hpcy7=;kpNPF=?Oh)gN z+((+(f$Vh-$?pi_>R~z#QBp|yR9O}T7AAOI`yom?mo-qMF~xc%ITG`TaQ1U%45CDV z3lqDZ;JAN?+t>p|lwkHS{SO2j8ap~)MP=Zf0^^a&9oco_iP3Y-{i#LDT_J`>E}aY{ z_3nqf1*|v5$CNb3ySxB@&i{Y(v0*DF|8w82vJ)iMs0cKxmlRo9h<>8H?r@!)J*aUbkhHu$6eWwL&KrH>->`T={o0JwQ zfV@u$UZIccHkSP7Zx-ITy2F8_8i_&(P^8B=^$mU&2J^CP!_CyoW-E|U7YK#B9;7b?t|$er$;TLR=qiQK0=!w zwndEP$4NrqL!kydN*-6OG(AGT(ZINm_Sj@myWVqa|8vU4Q@ z`S)72%uvycEyDkSo=BJ!{^}W=f*{$hxw9aq8eoax`>Wi<5Y3?_zc+*p_xfZMRq*0k z4TOyGD>MHYRv6y|En0f(Dn<*9KbZss5HT%p_$`DC=;duh`vmLL82JH)4`jWVBhy;< zu0f%#;s>!2>%<&yis_bs+?%v34s3`>M(q3sT$H;3tOuB5@{4&lhnQsWQGI)vjXh>C?_3Z?Zke#XfP zulw@l)*UB`eY4%anhIa6Oi z04L*O%^k)dEJZCs5RekvkjO_D$>mnjAvps)ua6px(^oQ#ew*ik&c5 zV(_~801K#kf4xsu3e@LxW8KP6mU5GNu!y)sgA=AlzUFROunP!I# z<4GT6{pYF>o$*Yt9N(3(uD11{BKxOr^_dP|~>EET*0bQajlRfB%!kL3j6(crMAx236| z*nS@6#zs;8ov>o@nt06mzKnlJ$#i>3)4Xb+E$&S0LuECtWuoC0}w4I~$zWZk?xq`sU_S^Ak8k*8uHeqG<*jN(k zXK7t%-h{J(bH)@1J}*sY1ic81{szcQ`X7Eq!*(~;>ua z%5cV7XK(;P1@w|(lwF9Jqm}>r{G1$NlP|=FF^ZL@dEu5El5sCunK~S3(=}dhaHJtd z-&dtYdicMBqmE(C4n1(-P(%lgU_Zuzj;tRN4-Skkg%SyGklGlMH(lQ*?EuyhbJxsWv9J z`eT}1DBSR}F@*F9(Rv7^TUfkkVLP2Kddxb}%Hq0LJQD5~6UPij{l3JzTbQ(l@S}n! zyPnT9HyT*5mJ&M$ZPR@ohJRaX(NJghy)VBukL5gTxBWHT#>K$cSo1928pi06iaZ8ui|yCH z`z<_HtA^Cn z!(G)bypRPfCz@0J+rdQ&5E1pGI5WIox4%L`vXdXAzX5vh*@R##kdS8QU6eE*I2w06<>U=y??y3R+lAPR5kM zLQbowCPI#JgllhE?O6R&4+n7NtfX!l)Gjk!e)6lu`X0-vM@9Ly%B11)@#Z{;iUNU^ zIe0fI=u}Aq8q`pYa`8#FUE#`JWebxtGq(a?c575l=3rBXM$bGvx^rmpZaHu9v^Tkr zf;v`q%(VSU9y5rf6<@GF97~AX5xN@(<+~1+?i@P=ZPUyzd1t{uy|bm$9Mu|@Wu9P_ zNla@<@>Xo~#!x>^aZSh_ENDWN`Kv=kVUcK2=*MGPv(W)Su(mZ(6L3>;%$-lGa6~jz zlmUxrUAAUBe_|?Lz`fNhWTxnlPQ{a%!6y$y54f(-OP?RhQ;*BFjH>?Nlsu=`K1fL) zswl~U>;|~Hv_64ckN^M!004VpBa)*X4r#g}67k8tjxqdDHR`NtSDb;)md3QIzJIv7 zms~M#ku=1dlUG8Yx|VX*pQ;s&gVT~p(pTCOgGwTZooqv z!aI(DBwHkEri};4Gt(S?uPXreVXI=@-zRh;_~`dA%xdOx4x)~UC(M1Bs-Dwnuqt@LUeP%y#>&f&rluTU z`)Sifis=$T>OnDam{NMY`ES4JfpPumk%?q4wn2}G;mA>VRx6# zB(m`Jx-8n1(noaF8|Niy%dBhu$d0Nykgm$0toXZE`vYNUnim;FD(njUW1z}YIi=Fd zv(*>4PB7O4SE_U~m9EyvP5f+Sn~hRAHutaTrfzbszOWmYl;{_h#VrDIM?tqxPS+oK ze-nbGcZm73+WyDmoWL!mquB~yyY>ZZrx4YyzmSWtr-W^@0=9gJ-m+?)Ne{0}U}5wJ z0K)X@`S@D=^z}EjBe_KYJ5wl^P7fYLz7srU5fh=tf8Vx~XcV3|T)H33NVMO#V+e0@ zr&uy&Q&K|OIfEiOj3$)P3C4>(0EM_{9WztD*)E+D@67O&T+s@lG{EVx4PeWV5<|3Z_%1Nk=WSR6Q1LZ(B7&46xC1D6fDcLOHKJSaX}qH zGMzY>0f~V*&~&pyjp76Je#|U#)CSoe2E#AYNnbs2qvLi{?UQW|fYDu8+wk$r7;hJD z;FT;IV_>t(2jOcp-Xu|1sW(Ft%l6lSs5GolmD^Q~H{36xK$2oLbI6@`l6Lcdubm8E zGsJK02L>B}vny}|*joGJJ)(V8M1m76ndnkr{m)C*6D1+(Fc4lG{V1Y+mu;o*2@4N6@~5-1OgXv z5s?WhBzpNh{FPLW6-@+ARl+1UNa`{*i61Qs-43?fVX++e!ia1Z8Z~7Cz5ps7vDZem z@1zeKuBa+~1k;MF)kw&swi>yMzFHW!6Lw*WmInHj+I@ zK3IMCUv9-&iBGCBGMdQH>vGbYnG$^gi}v`zxU6U@po!HI?dXeAl=GLz+$hQq+7)M7 z7>qNlV^2|{H7w&4n4~<0Y8~B`d$xgq7z!~?R{LX)ktK&QbTEWFwG(^AQ*c zL;FgE{X2)%st+R`3BYNP*0iBr|a)c_hmS%X(UIr#Pw#R}rvWyeE zF<=FNtz7h1E+iF+Lzzrz!d6%HfvjN|E(QfUOKhe(v3xaEE-pEa3gjur!LrW-VZVn4 zJ!1EX8s|JF<5TTy6a0TaR9r{mz%RHtd^&)_>z@D@kXnTdlD5y|2mnKl0ZZWK4KyXz zMk(z^l5pmxVGJfa?8wzKb29WdMwmM>KBr*;@o};71J+#R0y~>>C)tJRB9@=D8h(13 zUbut*!L&-WAeo@?GZM9MkbfkBd1)!at_=`+q8h>a)mb5 zlx#ngUhADg=8fy^Y+O{dh4iC&4rlCX@6K~V!h+lbrMRQ1^o1nrbjxg7102QKY&Bci z_W0~V!8UuBP1!%!6|2*haeKu+&=T#_@ZMg)bM?)#_p6~C^3H|1=VL|Cf^ul^QP^k| zgb}k$lM}#Txz)p93-+ZT|esb7J;^hbDKY=VSyeg0f%$0E6evlwHF< zruusLiL1<*g5l$*!HT@)uPKFi)J%Pan{%5;HlB=G#m++_Bs38c2ke*rBt!>+>Q-fr z)jdpJTd%__D5-?#AT(~*NMzz1!Hl-dI(%dBBQ|G>OtEP{R)-yBh8@7hNf{ki@$%tZ zh;}-(^r&5Wi_$rJ-ZcOq7RxKk!N7?aSCg_$Z)zrHh$PD=|y`(8{hCA$D+c> zZ^H+XLnvm1ZyDVLnV-5^=#v|)%pKDo!kiYcpKqwQg3km|F&y+3Pq5t;8DZ2kit#U! z?1cSp*acYnsG|i{1jmo3;a71ps@Y3eD|X!c*M}FDi6;NTbnaQSZyi2VM=k_DeU}TXErVuK#M440JXgl_pP%E5Fe;iRUu{KX*a=-zDn*|D$;02shq0Iiv zQExkdVATseHJ(cJ$i^6JnOgVC(&BK3bBS3+aHxHHbH@(OQTmN{{NfWW zTHd?QUErE+SLk!|PfkRSMqo7j zVhq``_GcZ|BKjl_vc|sbw(UjnN6h_648|K=<0#05S~iFWnTZx;H87}sUjwPA=2Lu_ zea4<*xHjj{!lP~~I=x1d@}HgYIS=j+L0ydY+X^!ti+2~GPs@CJ1A*~jnO%FJ&4#1q z#e2R8Hl)e-97KA!%a_gXR4~lW&5HPKbk6Fu7`I{e z^vGf|Rl%l!-5o#il4`b26*kcflz12zP{7!l+bav%Xz{4N-&?&K$cu89fGvJi&#j%3 z>1~4gQkn~bn>zsPYrz!F6y3={PhZaL?i5AeVlTk;IKD7}t_5Q?JHO}%3#W{gSWEmt zYr(a~{xtY`kI+w>PrQ7qK#Unr#Ra zv`PNV-fj`2t+|zE_soSm- zTnw%et%V2A&Bmzt;MDx?5_hNCpojhw}BC0Ha-2DR>=lAAUFu5r~X`= zYxTzg8v>eE$g6fyCdlqyk0#v}sj_Y@Ft75fM z1z{N2iE!3jR7()urC}D@jjL^AUZaLb}CAA=vx(37p-DkzxNPaC3M{lxNu<9IpAePYEoy=oF41= z_(=O&AK=SKcNj}vKOB|7I3HaA?!wm4i_@) z003m)!a6W0u}*4T0li$8Bo4Ig3h#;wfgn(3R#yw8Gz?sh^Wug+^PaHF{>85|i&?Wk zzny;e=gQ+MTXf*sd)8a#;sTimNl$mkuK`yFgygwHk-8!DUrTEah7~y|jxBKj*;C?t z@JLZm?{abL76wfR7O`@KPXj5?(MwP)6hn@4_olTx!$A5jU}X-C)dAG6xy0GofGJ|o z77ShiJiFv2IshNc)pe9;&8H(;z%)WIfI54a}#r&po8#v+vw~|iS5U?@OafH{?8K1DL8B4 z_Rm{)T0-?YDW(c?`Icm(1b+qd(6jGw`h_G#SseC8m^76FA2|&@WZK{87dyB25j}x6 z3V_hJ+XbOZSy6Hj-ecMwUf{yQ@+p889l@4Us4OZ`$4v`b6Wtg(CA~BN4>SEIhy*d zi78w>GD`>uVEaeBS;;>CDNaInQqyRCE)$UE#Pso-E2nERA|&pVBSW+kOW9)*w?I$Q z1!tkbh#XET#FnyKxu6Zj!7bUjUc*I-mb!`R{y(9NrL{hGxf|ITn-T}RKd%;~LrQl| ze?x)KI#2Utxt^GFGzMNJ1pPB-&ap~gx#{9)+J!WKj|jKhF^x6X-zS11}LDo`2P z|Id+6!=oN^1;JEda4&k-^H;q$0q*q#&N!CGPh-ZY=u%oYmHg5f{J6={4*xPXNgpc% z)}Hm#_IVXLK(I48T`ZGZ0(&L^>zK?QiWy)8>Z~XPHlE3z|bo!)q&$f zvk#Xb#>H-OYOLD4ItR-#B-?IDGyJ*$*aHsyC8>c^Yin*>U{7rL1j%yT0lZb4l2>}~ z7rx4$@w>8yV8Z5}I2~|0*?7mS|D=YgFarmsLk!lO9tk$>rM31J`@*TLX6f-kX*=d5 z{bLotX=khbcXikcuGWFbtY%yGu^OP{zcG2dOSTQA%Ae|6KfkA>D;6s6vPT{M-|w$Q ziemH^q3_KX1oqmO6y47ejSfRA424|hHgYuP#>wNa5fWz1R`<~i1Dbxh`2DxtORC=^ z{$*C6@&|uHOiPlLu|t>M)bSid3lFRTX=q50&|ma^A|jv$ZJW>DX+cZ%W=hS15)eJj zTVxyB&gUA2ccG%iPP{XC5+6z*#^9p$2MH!SZymOaBE^qsUpqq)xi_AzrvsoExfky} zWaahlG$Y`X$d($d5?^@r$b1!wM4Hkp=dH}5?E%+RZGq5p%SS0imUzNaVhmLxSN=+C z^vbim2a2!q#0fe9cCdJ|pn>l~j5w#N6njlym2&EMk@>Qf(H?4~rbQuLMo_wC_66D+ zrGOcFW)^MHPM3ex+dGQQ$z1ETNNj;%bNh)tH@3f=u~Bui>Bb$`pL#{V-G(ixRH$R(0G(b4T>sG~(!9zX&07O8$zmnk5u0%NVR}NbAPy z{R8{P{4aFvDO^Qvg@V}WF7$*v{2l4n>u@Yt!L$qp08_ZA?>eSAWNBz3#`!fOP)J)k zJlIi>04q4pcKTQP?(CkvtPoAg?)xy*%yA~S`8#vKepYoSoXCm(Ki3`e`SZ|5ucFg; zg~DMdoE{tf1wM}%t}=KN>JYbH({qw@u{NzcwYzg9C`X^I-l-_|e#97!$SSwo(T)g0 z*Bem-VPF7uf}m2<4Z9RBrIC)(6A!`0dZ+hg0#*qMCN5|!R8jYVO|Tf16;r&}$ak^P zLf^k*O0BRS5_y2ao`jggjoG%X!6`sohw{zr7DVmM!PW6wZLDZ+9)75F-*syv)U=bSn^<-}e~%WrFBo6TfrinSZt(K$;A)-Gzam(VYw4pN%6xZgP$IRMKjXa!nak zIqv(tzg&@6_V!(qgNe3{8COH|bi^5~D96U>U|4sUkP|(HG>|I|10XuihE`<89m3bw zbb`S-<0=_*$B5mLMus`?`1#ZGNI8HIql%F=v>%iqK%%0cl>R`=9o%$|!*qv-~vLB}W&{$mNk+EurJjd3CF_Rm6 z>R(DJBEoqhAwW|!+W~K~vkr5odgyqU(8#H0BZ7>F2frw*%7@FyI8XDeS(4>jNYaq? z%;{g9S@fta{n6!Vm3houril;Q`$0he?(DWpVi&@AhMUK&y;Nxh7&k%CeYD<`e$B@w zSIC>3OSDwsE}fOb`zMMoguAB#n9o;H@oE%@-@Ydwb-rd}@gL?`{DdbVi@Fb&QTPh5 zpc*x)KPr~$d6Cph@O%IO0{{R;F&j^@n5i@zw?I2`aTxQ6dtT5>acq=smhwnsA24;j z5y~O*&V^!FPcD5tr*DycddAmW+5HyK_9_jDqZG$7?06f5-ENIizD zicaZ)&sc=N&k3)*{WutV%`aLw;ewEhQ`7TYC0|a(%@9L20QHtfz1GMLs5Ri%oAu|i zxEPD-PEX0j$b+W9$hQ%Yh$pP0^b%&0BRYdx`_SNLfIv@9DpKh=rL6y`sj3rdpeePq z)6S)+rX)m)5)j2Lj6IxINMOgM3?@DqQ6{zV1F9sV4b~yR7<%}`iQhfhYKKP#5tzwD zrA7|#nTO|vv|?lE@HysJ)!Hb#e7d-7RY5Sj9rD?=9o{!)x%Sv4r^<1TSs?8#9v%Nw z)sG~ji;-yen_}*AfDIQ{{-mu&{3gA2Kxrk52T3>04}QSq5OAnUe#^+PrB{=SPNlj% z#}DM#K?^+B>W|QHsG{%3{dFVGDPg`WI59&e_YPj10D<*>G#--tFl)0{EslX497E*X>iZ0Is)ZifgAmL5O8oACLXX4v5kdjM?WZN>q~=t!dCAsli##lWtdMo8fb*?0I>CgS zG|F$VSm7jLQBM?11hqn*zz%1r{{Lkc>oQP-81_u+g?(N>ua$No0)O_**zUt`+kSC# z!2C$P2>f___g<&j4!oeKm>>pH&$?Ea(Zzmf68MyzqGSJ4HnBC_brsV#Ij_caz9V@9 z_vz4kC-AbgXV%6uAxx&5Ms=O=p%t2;Zqo_%E89@%#G3qc?Prk%?X$x=wW=sqHZEm= z4Np2ps9y+6qS4>JE5APq=`g0ud`$Jv#ndT;r1#mItd1GFCch|6lb1tT&Gk8;EOy6K zik!>s8@J4B!yzpMD#;R(M(;$aAF}9*8lB} z{eRNVJu9k|*-blNd^1y?0PE`X%H@FZcYD5_BRhx5s@aOoS{|z%?#h&n)*D<*tdvXqVoO~Y-({Yy< zyP0^#(Jv&0c`z1(otr{(*?Y}Xs#)coT_*}EZXGg^pNNLIH=oeVNb1Apq}VTurGl(h z0Bb~$OL~#A)9W9tPh433sV>0LGyjk)Zmqgwb*Zq@r+Ol~P5OhmZuOxwbOke!M05;V z_CLMB$`a)ogg~S~0009300RI#u5RcxzLvcY2Pg$M|7!-8!DNs2^AuIU6q`me&}=5s z*DNvgVBt4Hw!Y5K)8>%{F^&aReQL=vvmRib1Y6P?7MUzg-`6p=qg5^1NB!IRdepui zt!6%c9|if4Alz63CEA!4xu1mVl;vTD~WjOD!Vy9eZ4W24zQ zrBjd9-@1t{zirZU1de}95z1quFQA-ywq|+ywVv#JMkUZd=g6#e??(OJ@L$8&cBz{U ztZy^3O6Xf50pxt!a;}i7U62Ax=SAjBhP_(pq{HB@-x&=U4FNH&a;_bOIW*1b-(7L*`W~s2sx$#I*loHqip;ndrHds4CxkVwmjlV@~xxs0Dhp- z!87&nfiqp?%R0yN#RVAYzoUh;Z9w6$sdroCb1*#fX3QpX+A47&{paqwhrFrWt%?Sj z>>}-V?r(Ak<6V15$6U$(4w~!`g^(>zjB3-|!N76&SJiv~oYZXcF8MGg&J%8f6_QOv z9fve7b-|ksYF)RR=FG;vc0&1TBd*B22?pVxwA`dKoSW_`v@l)P*L=39NgtbkXMJe! zte=8X?P!a``!H@++VMOh^wP<{oLS!0=jTu9CV} zC^`~rXQ%Xyoz{J3eoVeEGnxfCeVs_lr(~De{3~uMOvZYA!$fF&M?E0GLQuyl69#J- zpqWf{M2VB7lwUrpnWuR{)!yi3V2Uzxqc!^o4SQP%&J8g%Ddq;!ryN)gba(`#{VT4c zng}wtU&{~d&qx_u@`=pPn)GH%#Jyc@ndM0xjX zvMros;91Ry%?TqMe;mTLH`R1k8RMkGJsN6)E8cI12RIMFE*v=xtLbOY4)vD#c66}t z>x8F9;2Ly0YQneNG_~BwHWI0hn<_btmV4 zk6bpa68%8(g$`wmw)CmlNp5S@j|;Hrk}x8IuQY;8pJ`m-@VnlFiK5G$54BmDU8kCp zHY30Xk!`s)WV|WZaJi1%UqY z4T^+Kn$j}5Q{q5@X>#-8=v-5`?x!DZ3k7J0beu$m{$5`3KiXK-XA52uYiQ2Al}#L# zfG%{N2!nPLg2STGP|SW)DCP?>Zt+^K1|9}!DJ#+0RrMNn|io+xC za}R${MUR5jZW_Vo+hMV}yr}rG8jKf<|L)HNTiS`hYiW*rAA##<`SR7ia9&E5asTl- z5>yYLV)~Cb@l0A;qnqc4re@-h3&*{=6Z}bjXDu3#Y7cQNII^*ml}#838$(AD>alT5 z^yL&6Tq5!;I*bz=)Tn5Su&Ny39e718A3k}Gs38d`@taLlPon&jK*9=1=eE0Z*Ce%@ zND1tQDbCO-FtCiKcJHiI072H?U-tFB6a~WJwkMm;y}Z5vHhJa5;P?2=Fw7g7+KZ)q z%U*GwNj0P5jsQ~OTppqnKXv#DminVEj_EA}M=yICVP7paA47|_r%FF5=3f(`&S@4q z&ZZo@kg~;l$V%8vjp^5T`o8C^Qr$8LhTzD#CCHNogm&?>kPRi+>7>&=Q?Feq1J_Ic@2Vcwl7*+F! zeOgn1G5hs9Li-86w!9Z9*i_OYB}|%oy2sB^PYvzYve&kgnTMHnuyz!CGEU1v{l(*__P zb!Bo4YuUu?pk)C1gdH2cw~7wK8#uBE%#IBt2Z0q*=DVpEO@xW6MySak<=U~-C2Z7$ z?Bj=T0kq#~80X1Os#q^I`y(&>fy4xzqx~ed-`y2rZJ@Q$VnYun=(D|E|G=RnD;n+) z0G6zKcK4({u8fO*H)C6EejMgHyl?)K;3EFR1u~ zbHv1xS@HpYnWGp7SIOk5`OfM-@zVRb6-ERy9)s=beqvImwHFuE%QD>=f`4m|*_JN}h=HELZP0*d)RZF{-xH!&dqzZQMCI0+qdk@CQ{ zx=#saAnUGu%R?UIs)ytg+!+u@*LP;Op7A>MzjgU6&IhgyCTv~>@&z>ghSS)UutTxP z4gSqxc@p-x@D@#93xDE>V~dP~%hM!I{z^w`>sQF7@{N?O@4(KatQ|*Ft8lib*33VxS_f% zzW;U@a4UJfvj54={oLaEVMLYY6fSWwv;y0EC)t*Gd@RzisgK#^4Mod1Pbf;kB__b) z0!6Vn(laI{CO5gmgaf-;q{zS-n?{-SzJSl^s?|{Q?m{zZIoZq4>R$4nx;!${$7R}Gt(5ZWA%c{6?+wxw7HK&K*P|ogYbvvX7E&;gJrw=L zLu~&)_)7*`^aw5ea>K5tl08QW+3}9eSI!ezuqa`R2k5uQVzqgrI*TRan?Z~m7pz4| zPV>N!AFouoIs?{XU6Uj%3GDW2lRJ&2|{aK-CLGt?2L@T$` zNZ{DLOH05SO&!I@iC67+v zh+gJmg08*=wPCC%Z_%ffylTmhyUS}+D}#F@ZR`@kIIs{w@@df+E+EWp@n&G$Kc8M% zn1N7)OO4jI*Ke5PS{mF<#Od*>jx}c&QB_f#Kzvjy$k%7MW$*< z7GH7he)&M(G0BPia^cV1KZE;bV%r9`g*e@pI4!dTD1ZO}1-Dz@O@U3F5$5l7;V;dI zEVGO|Hj?$}*ot+17DZ|#;Qp>%93a>AFDe25GqF@|ivaLHo6#-uZYvPJV8J&4&X~kA zw&#)aG$~d&6wfM$u>v8=lRbVRXxZs{DyG0 zYwdf2y{bKyT2IuJsiJ~d!BUkx&G>QeApF_MkXlI^5xgmc|0YlTd;uW6Mu%g+0@6G4 zo_eUw`wxp9lGkF$ZuB)`Z1bnyb1endB$_m4nh}(q9TI~2ybN!hkTjSUcv4e>8bjL`_G~mYFHJ%%`_mV7r5v!qCu8qWxVnvu(>`JFCbZf`^tvZd@U<92Qw3Yvv<3^y2nmg^8yqCNLExJ;Z z`tv9Ul>`1@JF>F6(tEQ4Sgvq;Ppq0XX%nmw2hws#roWoJ`}7MS&5pr>R1l-(!JB3u zjuvN%>U~~p=>VH*D(Kle4@M!@^NyV+foV>{0Tv`lWA zWP?vC)M6Gh)bYx3-w3J*-QRN}JiSZWhAVW5kXq$z_@(EaT=iyjr$QRP9l#*_U1B&(CW*p~FyJ^NQXf$MQd{#+*--V`dW-WiE= zm7R(J$wJi{HszHKG}Jp92UBr^@ucm;JkcK4b z4VE63`=7heCd=`JPvk2-Svo^m3q=0ZK~QaTs^NulrvB&Mo_1Z^xU9HC7H1@Xv?fq^ zW@r1(J}lwX^0>iU7YY4B7ex7%7deJkMDSC$USzJ)?Tx4iOOx2%=^5Y^08Udj}paI&9ZvQ z%x_;>wg{rWbpkzzz8_iA3a5G$iRj;`|9Fj!RiCdYkiTN5vK-5~4HIyFDq>AXMzL@g zebuWN?Q>l?A~a9luYDgtcbgC?Iw|R5g63+Yk{=36ZjNd295c-?T91PIgxm9Aa`mt1 zcd5rOoS}4e{5kONXiw#Na$DVQKo=WS%NW~5RQ9d;tHa$kNOI0-)+4Tj| z&aT4Su$tNRd|!p#Gj<|4`a-McOo}R6Ue$~~%4120B!O~7*s7adhk#4#=z1|gtM*Jdd$AV=W1Hzg;nIB0Vo!IxL$bv|NbFn{EW5QO8{9f@>kZLq*=)_;0P&}ct9Xt5Yh28qGIg%`TV zf^v$epwD1Oxh+oCGy#-_-%+x2uO8G>%A-z(xp+t&D65S#-bIK{Z@Z(H_bEuEeDHs6 zQjF*TCxe!;0D)L>7!Vt+zN!stT_H}hV8?{Fl`6#Ij&0Sg^cHDCD2vh9ow3g!_H9`yqNQXsxLOTR9`;s!0yPvw(Tb5)5-^eV{& zZ&HQrp2%(q;GRLrRF(&aenS}l64zx2YW`86?R29w>u@9OdcjZ@qW(<-abA^O;%$21e%guUab=l-97qsBQj5c-Vm3t^S z06g}8ylA?m3&>fcL4StB0Xw*T?n+t;T8JSybuC{vgOzAa?>yk{)*2;|gW7d1tU5>6 z1%V(vhJuAv=Eo8=E|(kw%}8#ByjVSP%Y}T=W?Vg|$2YOVrrx-Iv_8zo#$-<6-;FN> z;v}&6Y6VxuT-Imw+vzb!m*Vw_zhEBI^2r}nr~Rql_8JkK3RPpCvt?FL zxr}GC^cw4+a_G!c`eQoz*upD78dYm>-ITmVVCP_&++2bNaX0#!uVGcwmO*?<=5mrudCl zqBtD~u$4#wD%n``!9LdTQ6*{d6WyNSH>M2D4PhZO8nNdVR#Fno7-qRIe)W3lM!?ky zivwEhg@1C_o@GEeB>z^kfOZlOW$On#jD`x{r8o^r%3fz*7t7^W}iNs%2+y%k0a!lCF? zK{T{d$=o3pmEpx6$m^UGzPF2yf~5Z656tMAP23=jcd&5Y4ObC7-GN^32vjkW-gJaM zZrQ}#l+&lRgU$>O_tfu}PrfZBKiHE6X-Yp^}UU6+1~298&}7hFL7nIeEMiLRT#_L%bbWTM(dI;i$g zy`YK7_!#SIY~9({Y-(dT;&FB#XYS#91|&5}M{HpdS4YZ){m8b{LG|&iS$gR&%YnMux<8UNK{QCmJ8whuhp`OG?K`CZ3G{Vo6QfO3`{N^>0lsBNRsSWPtAg3RQaea z8v{z2S$xrXKZ5uqT3iwy_o0ooDe6gK^LwT|XnKHeR=<8gY4p|72HA-H)JF=s{4|{^;G1x}O>4m7mK*|W914G}>)-wB6ucKN^e%3_ zs{%*FYjcF9i0W-f-G3V8)7`rao4(ahOETldsC=@ z^#(|*G@{zrEiuT)%o?#I>hf2WqtB;)sZH@Fv#`n-1NK&qd;S~(;8$iqR6OlSKo0_^ znyMANzsx?oi~o1_-hGjz6Wsh7u=Bfd)0s4xo+xThwUKyHh<}_hR{-j*PSFa7t_3%A zbj+C6xAPMtVpe1$+a(+(hjRb`2yPmLo);Up(vsHORH8UXkjf3!uXdUfob6~(8qL~U ziF5a$FtlfqZo44;d)qN5|!RF8~V%b|!l zZbo?=7txRJo6V;dUcL%P;t|5vYl>+3ZR;c^LV7#f3R?P}Md$ncoEQQlfOz>Ug9<4& zlid4}D}dYRNZm9{i!Dd@FKEwqo2j^85fj5KPA32HDS9P@jpYxJ9~3v_=N-!!_)~o< zjVTSN+N2{jaD$}T9g}}_gT^_8Nl8!_m6wi>iVEmQBsuatRWHTt0VX*$ikcZSg3k17 z#GurbdRAsKUKTS3G&-zA7=FsCZ+ukZD(j}oudF7p7l-;;*oe;F@~_DxoEU$kl~Jc> zgfF@TNJwJ3G#_&1Or0bbKfT55phb1EqR5Zu1Gk}B`PpBw2`|ZBc(SJmNC&VXNW>$apb z$K%{@L*1Xk7_|JPuFV0wAn{RFb_f#)`kFGFYoXBt|r z_2zC7cHa`DCA@p%F_dy8y99o3f@Ykk94O`;-)Um2$9~18i9{O)-yD5}AeuFKpDiB$ zrL#$k&2%gn;I>gh$ee_@cSUo3;RNE{6k3?|^toLPA`VV9?ncr=z% zVx~KN1+GJRtq>j!M?99C?W~h&Dpm=qI^h2<}V4o zT#-j7tKRyi*f4dJ%6N)lm6a{zsP+^bhZtQF#ZM*g0kTp5Og)SM#4nr5z7tNu$Wl;0JrhFE08qVDL(Ad(Ur~S4Ugqo10j;*&b;?qVt+!s7W zgsM~>se5yfIz4UiOZoS*v0NdQhc)s8J?2#B*yYHWGt`Xa%5*KCGH&g2X0&LdbG#6? z6{~)u3rC?&ww)d-RI*zVermVQ2p^367c2(`7l-?pMlmalDry(*U_gSmUI89aaPUp# zDF2=%uyyeaPR|zo<>KpIa#7fGCH}L&8z1l_I`TFJH3XQo3LWJ0NFV?C?cKjlve=$5 z>qLL5%XugS=1xdE!frUzj9yRRNTIhF41pGZg(9t335z_6M>hFATbhQf=|+FiPj}<{ zB;R(?D8i!&Xn&^GN26^-CJEE`g7+r$lr!TV)i8Xg71n+uhBSuvh9tbpeCOg8Xkfp` z4kSYMIe%~JswR5q0zFF68Zhz%Nh#yh2RXP7h>$G~DHTV*=cL|pVf>J&R^?^hMCWZK9TZjsU8`GBKt_qJlgQa4ygDaYXGkT%&5CfgEl@y?Dher`P12z^f=>lyIc>7ePJebGFg+$p9;S@ySvf;}c&SYUGZP zLb|Fvs39A0k|iE|;Yjkv;s?iERQ*_c0V|TpA^nF7X5v*(SD%bBgD%X#=uZv*Zg>v| za^&;MJb}t1MTwVkkOGxY5HK&)sKoFPA1bs>T-6b76b?Q}CUL^_9XyoNk|4I_YYH%&qka(dRK_PJUE_k*^@5)SAAL zO6#%)zu;VQ=5a@YC#sRyiEk|2E#;^+kl(P8J4A5 zdn9hGavDyK_F>KY+qR#0a73=suf$~US(mB?Fw@4+e9AdrF9ZgTy^H2W#kSJPX}KG^ z5TH_f=f4&HL@o>Uj5W6%Vy_H0MxH(3iqq7YTc_Mu6soJf*jyXun=y(5{a?<gpGxh6b@;0T}% z!+Kt$pBveei5Pdj%MBKRl8f%@j|=Fb*P{ax!R6WOWUW?kd=Fk7ArTo@F; zOgEyUkIM@O>l8G(Yb0@7lLQs3W!Sil8}ML>rQ7(SASy>X94ch=K@=V88TRfUuUJKP zOy5IZ8i78`<`tbopvaj+`2~l7eZh`-&{viBWATImO|gBHyo;Nj$RgTq`rK$X8?V0t6jaxz75ed zv;!edGI5(ykm)CEhBV>$u)yn&-PkGLdacKTi0@)k(MC}leWw%ok|Vb^=#ks)o$Tq- zqOZZN*}ACfg3)~f^az5N_u$PLE8W=svZ601Ow0{Xx{zGjr>*rau|>W^!?ML^WjTb< z=A$F^n;5{vTPf<(@z{_*@%lh|9<&&6x2e(Q9iX_HbyF@yN>nGvB!>td z6*bpS)8Nx+*Rm!VV$1Y2l@#d6yi^n?cx&+3D3W&TuIM>J>Av9cjDiwgCO#$1NPiro z%ArDWw%)}0MG2TT-FsM0?%ijZcGR(VFGA?1sXsy;VO(zc*=TsYXL9(9Ppi?tt64e( zoMEwWs4e=nQFz`c-qmBPTkyH+mUoWSW;zuXW#;2pLCc^jVAkTFq`KU)9I@{CDTS}s zaJdGO-|l~%nA+_-w=e}`I;_?@fTil?Uo7z1UMgpv%x@(`Y*N~|^EZvR{;Bm3wQeSX zlyIsadiZ@=M+b%`-i0shL#lzxiUZQx`|SGmc7|yv6mfHG5l;WZI@{*dBxwD>sQexn zwat}n#S`YRG+yOI?(V`VnScF92C2sP^tD0ChK`~tKy)AwLA?*Y9^ zAN72088u}=wvuQiJ_-*`NQ-eft}>}*yKGEKM6bS9SrL!@@yIasHTNEt`YPZR^5rv$ zK{>Y!=D&3ewCM#-v^*_$9HYX`D-ybTl_zj)5L?$-nRYiw>fUwmA}Y0D_PSA9{@v7B zW)^a4E}Bi9Vp3BL-(BGu7?8s5FDMWuk*cxNZk5oDss_|^%_BobaMnA0W&?2UkIY2j zojoT0!x)N-fP#>Um7w{=CJKc4FUH~@1^SjcledG7A6sPbODV_Q$t>t`(wySBv3Q>( zQ!t#x1xgwIANm+{$5u@t5#w2}BZJ$)t7l6<8%QTM99j*)iM!2*=CB83&ziS`8}s?- zRo`Zuq2+5ll+!QchnB5IU~F8ub?m7uTtn()CJhQO8b=25Y$0xjP{DWF-?`S+<51_m zHCqq~%Z1KjVlDEKXHMrLD;?$v?R)!<;j0{3r6!QiLm7z5Fw<7Nu>~7cdC~;P_E+;( zwcY;9>PMP4B_$y1>bgNoGo=Ur%emtTHt8~){q5S_Ey)$ZG9Bdum$0v({HWT9!)^q| zMWWvlS)p*59Y{*M0dk`5`u&&e0HX%Io$y4%Rk#x)19!g>laHv0u_mboqZf{FzviUj zo4Ok(v}q${Mr?>D5j!VX0=83hX-d+Ch~4y;NDL;dbFJQLtP!#xfsL4C{K4<=a9w`? zE?JgX0+JyMo4#Vv0!cUa)_s-ObAX;yWpUIW!X)&r3S+#J{l?qfLT=GLc8`|pd8w%1 z$oZAzm~N@K_sq2(Ind&6k?AWV7hjP-zSZZ=k1jZ*`(v7txF-L0fr7NDCNJA+iw|k?4LHGWuHyUj+ zzD%w495(eUf>@{Bjd-PgQ{L~i zC>^Et=n4{9XQCqHqCq6k;Kj6XiLYYx3I2ksGO0EwN|gb&t+RYc)P zvoR`1u#zn;i|JPic)e*%KJRr-cGBK`6#ynn9m#QQ)CA=fM;1tBeVVH@`@AHr3)D_-jUAJi&CJ`!cN~Yq0y;L210w-zMi$E8F zj7F4r?Z}FpB1YZD3c-;!IO@F8An97XQ7=E***grbh!I@DH%-<7Wc%%>=yds0F!lP~ zJVyJ(AD&ifypF4!*)ZkGdLXD_z?MGiLEs(tn;D8$<2;sykj1B^C_eB1MrO5NpgDrr zsx`+lp`06?MMqr#y)7au?wxnX;6}up3c27ZqWU3P=AKZKalZKL#zdV`Uq9VST+3nd zQ|VY~3bSD@B99M%Pa=B;$wxdB_LD1L=PQb+)T;hp6Z!40g}yq2HQ7*g%@iKO_yfP6 zXdNTZ`qzS`uY((kOied+7p{>AhEa+W6XzxZii(5#FB)>HS`|=ClQWbL01Y7vyVSMI z!|Io-y32HkJJv5kY^w%hFAC8HGw8jBU=Y4h67oKQV?5OJA3KHWm96fx%Y1O)HVk^t zeR+PS%kU1HRKh_TIAjCH1Gg2ZBn|u-jQtT%87m#|8x~2$7aLmGsz*q|H7d3KcAqdE zDzpt8Jb&b~O)v1ZiwMqwGWE)7eW?g;V}F3so2xUn#RY(WG6)xZ_|i$}q>tcSYAs^e zPlwJcg(1}W7lsnpF%U*R0#9fQ#gTPib+kuFVLt(B-fsgdJkn)Hitg0wt#4X4d}&5{ z!7GDG9U;P#xkra3K6fd;9CdL0GYm&=1%TdbdV}bJKd=fA`vVgRs5rL>R5H(DG|Hug zoqe+JXuyn@jPRq&v(tiM2m!W&UP@j}V_KRr!3+#;~@>#hX*BT7Qp! zC;cV>(O$KJ1kY#uP?R5VSb%@;rK+uU`xe|#B9?3Cq6<_(Gv0iW9if5crr{;Nk|4tA zuou!dwyY7vqq_ylnw#beFW7OO;i(J?Hr5hH>#DMr5XN|yN);lLsbj_m+^fS*x>N4? z?~2u_m{h)CmSa&bw%GQSd%4Xq6J_#U=EYJbf4rU&L6ndKm`|(h$!u^KLNghiBNd^< zl9HUd@cE>)?!8=tb3^~*o1_lYanD3Qu-MhXS*ni+7Ez|=_Bpv$2S(=Ba)n%CA<=)SqnJW)LnD2 zpyrbOE!B5|m@NUl#x7K$Hry8WjZ%WU0>yG>j0srvON2ToEEVZFYYMTkAuovo(}e61 zw`ixzB?Q@tH3n$%f31wOjj`uxS4|51*OSO#)LHIoIogz7bX~A>n=UpZzXo*+b%F5& z)%D_V)O_RNp5(+UMS+IxRCpcv7yst_I@W7(@odE^J)TdFX1Jo7sEP2j5F{z!(y6^8 zEx00~eYTyS_;X3A@kqGf!YMp&5F7^@>gI-w)t7`^GQ6ruXBS^^ipsz1mvZ8K;A9*l28p%G?-*@(Y53mu zY&%PQ+(FXmcfF`o6zP;`a&a3lx*~VoGeGI>Z!U=u_avmx4BiY!bPKeH4S*GTs*y1` zc%BULl`1$BWwF72O@N zIXF>&%luld!EUxT3G&)JTnsUBc>1sVo9t%2h0=bna#akl zSl9kN$li#qtgq3ll}dC5F7`Uzj#)BkJw^G7znCOa%i#4QaU5piqixT zu;K*>qRa6|2OXn3xashf?T;9ZfC*%v%!F5<_4_1TF*oTqUabFa%^$5aHC7nBBaSC7 zWR;=oRiu`#f()2wFD#G|W8LNUA;1KyK=%^Csq`J2)G?=NoQ!YCjl$kKzd9}p#AGz& zX@4)rQt0a%ehH63t)j9$v9dx5VqlJeq>;Pgmps6gbtWU_W`$qboUdBA{QC}YOf%P- z{nhdIu@Si!u%mRM9>^DF>UC>7onK4i2)=Qn`%%pz5m)^{M(2ShFRD-T`IDkKANQ)^ z_Ag*JhhPAQZbCbZ(pP_E;4sA@o{{Sy000Z81|ay8k$bI_F{$xvz2)hs>p#Z(u)8uJ zE&foYgXd_tJT$E0Z}Ut=TC)~@y~=}&{5G+f=NpG-X^)CFX0!C$x;ZRU^u8z7ONj+uFn&kig^qm7G zvCU>ly|xFB782;Hhz5DGTyP<6u)j^+e1|(4T?0?<96lyN*@k0ZgL$)>1eO2N&-Z{L zxM=^@YyoKC$aL1)df?>k(>PZQo*V2{#jo1Nen7}lE)7gGRIIK$ctUSrA-Svj<>rGA zI&5`?Q`euca>D+V{Jk6iYB&VkBy_+KIGnx~|< z9#LGaMjRaa`))~gA`oz$j3|>(uVB?lS2d~Nugc8ig+^EH8Eqo$>7{`WtX5_8%QgK% z-?KHwQj33%u^7B0*v`!PZ#?)QEisR?*={7YZdnjrzEMC=fm^_`fh^wf+Ue73E~@Ro)-%QnGVbMtDCbJ);?w`&;^lH2-GpwL?P@t0f= z$JuBreaxwB?oPLWIhjbFayeU@8NqnAw6+p%DWRy@*U>uN)9{|$=%8}b%zg=RK=(wA7fUFW3JgH*$*GW!)0Q74`+)M>< z0K*O*dW7g76nL&G*N6)uY%rQzfVN0=84YYpFd*YA64><>ZN?3k=hx*VfIjuz0jZJ` zRLVPl@|dLdD1>MoM|YXf8R-;prqfj5W8q@!d|j&XOC98$fzMff@JT63LS(a1R9^XUHcjl7Tg6B{xHU6jwS6S5&o)Iy_3S&hd7H9MGnozqxS*Kt5EQ8Oo)L_a}`o zjhITjyegyZk=)@wcBiWM%w=pv+L+_Dk)P<#4Wfv}Eb)`)Bx`p-tWapppw$i0Hz6oa z=+e(8wmM)Z)-r7;swoUzo3V-70WJRe=&?}b>|-GQq-!joG@)1fc|nmBoCXF$Bz|Ka zc#k|;yl3+2%(C38dV^;CdaRBY=6zIf`S^Z_ye0oHrmehBQ6-e2>r+l!l!rr^Ay~+laMm+d%_*_e7-mHttP=BB+4faVU-)cK?Spjo&o`MCCQ&mR?&?x&mDW zx2TV#+y$uN(Z-^5WA@M$e}8S|%&B?XI#&YJa4x!KD*_>=orH+HwwqxSuD=NI8QV5? zsY=}83kvWD(n~h5ulm58K|wxIJibK*b=xYT=_SYO!RB^yZTO}66eBNpIPP_UD$Ffv zY5}G?-n4c~VnM0)+Xw5y^(gV!;S3^zs$fMjSGYQuv>z~tr$;aZAEpT9 zJ3;9<(ST)i`1aIOVlVox2qdwG+^Iow@)x>DfflH9u&TmYwvQ=9y>N@-6=()4mA4`1ETvzk^%|924!YD4aQSQ~>VVX;UQXSXbWS&`Qgrg$ijCNu? zoig!Jf`<~XN$!ak#o8C*U`do|>l@kWzTDyx=w#_R`VElBir`AiPM@af@Aj>goqK~5UY2G}MXqwM zytJc3`0_N&i0u|pBe>bp3>AOGYlyJbuh&mWXH*b%hF+2_jTT^ebg?Bth?6jHF3LHX|tK@X|7~+tNMxds3DX`T^@%g}U zDsy4r7t_|A0so8F?PWcMGwg<>(6cZSDTadEd?SNCl`ltyxObc$ia~CI`WZ9v%sOA~ zQ{h_+jY&H_61--j-*D;9?$9+mD3HInkw%u)m4RWFNj`LygRAa-!4{gfBIkg@CS(CK zMvw`>QfDruaW1c)>C%SrR^qz9@hMVAuM0~t#1P#}reEV~nrL_FE1`B*ew_pIQdZZ7 z=DLcfpvm(fqTb$a&pGy~80+l51YUB1A$>^PA{1<0jXq|7Y@1lLEoMqTY*C4> zrFpyBlsM|NUn)Bg_iJX_a{_uG#wX3wRUfL+j<=3qHSfoINN+N}m+t`=Z}yL*Bn$jy ziKv#=a;EOi3=`XtmCcP*3J|KJASbdcMgaA2M>^dO)z_8 zY8Wd}=YUD|NX~t`^O4aQWw6P4#@l%PMQDKP_;~npQBv605Pq`b50A&Wq2X3SLF>J}5bi4y>&_nF7&l$v@pJsDTVCEwlt=4L&uhRhT~`Ja zi5|+k9bcJ#OA}i_31&nXwElOE;S@tMPH9eHqU54E_OMff-Bpq4zT%0cTaAG;cbxNS zRe7@>fK!X>v1iq1Uk^^6$|I*dpDme_K~Q1jyPe;(;(<0nZdg_;Y1bXahGapYb5w+6 z!yFQI2z+w{173?nKS<`?=0;lpZ)iAIWvi+*D-nt^QkUO)XE@i#GculR9m}>3aU!79 z{JpU|_E;&Joj1VJ{gfcrn|u1}g;BhbOuVE;zbTn3(0 zs{i%_lxVTbprKjB4dD$f$su&HW!-I%k`9iu-OX7q%rU;xLtx%2_5T1;WrIsSt>zBw zME#;QTEJfcCu}+@2k>)~&TNPKOXfC~rBN^fopT7gKfw(Ru>wucX^^?_0A@DU3P+w_ z5Y*Ut`t47s4if1-i7sBMxgB2-X84{{WbDzaxEYIjxJNPO6`2Xy;mxgFIfmCcv4|?T zr@foCCrZe~ELXhSqsjYd?ls`kbf&r5>40mUH9u3wI8}Je>n>OFkS3GU*@L4ufdxoi zJdbbVn$NA7Qy@9cFM(w3KBtgpNPnR-dr1y{p9ipbxNg@*v%9WFlbG_Lvrx>g@(9$< z!2YdWt)PY+da4EOHDrq--70XloLzX2UxDW3A@L$5A7U=%kn%{W2I-C`oQ3~QO1vr3 zjI8cR+L`&?JtM|U{}f%oZRQwg>=vzkM@pAbtYO!aCq4L0;u$_BX0FYz*QeE{BE$mQ zyTgA~>D_+c8X5S}ov-@+POQ>JAL4qAX#X9d9p*-9jJWAH1sc$F?!(8i9NvA@v^I|q zLG{k~I+hJ;pp^~}*?h6@1be;VUW1~`)-*wgath_b!5ln*OauVPQ2-zz?NW(KfXGD5 zrMih5CTjj|)JbuJ(+7V&kQEa(DPMiIItoL!i+*KMIJ)Mbxic-iR%f4ZwT0H7-(EL+ zFjVTt6~dLDov#CwYY+M0+`q8dAC6~o+b+b|G)()-2etbKFwR)Qj(&MFp-XKvMT zu_twI`5qss$BiIwM-(6#U?9uF09FORW&i*K0XV?70g2^`CW`y#8HWp;Yo=go;G<=k zS_xR7Flw-!aq6Q_kN%v8LVYGFQMBOtHf|*E8_*}}5Q0FzENJe0&B^H{Ayz-ngLU#X(SE-MB`&xA)+fLwI zirmM#M~^+LAD0aC7ym`8Y~=Xl%!E>ElH~d`vlIbRZVZe2(`s$KzZk~hh{7Fu`>;;{ z$TEVnWI+RZ-k#ufEuhux1)K2MP9v4y&qK;6R=M4rKA0(tsSNM`ly%)m4V1wV?xy4Q z3SH(aY=W2`I>Y0&AEAxq1D4)0U5f_))rL~Mp=8GBstD3M2RYq9O<|QorMz|JGi-bk1%+1d7^0wIq^ypRG_UGVlA<`KfXA z5JKc5tFKZ;eJQ3YuC!P@rI)!k{C0_SOxK+{pE_@a+zaq9k9k>eStR|p-`H36mu@(^ z=k)hSLoD@wStgiRJ9$nukffNTc01F&|5Mn?pcfl5_O6cTxUmAWG<^oE)K?zeaU~wSvF>f{W||A#19(4G>MudIpQi z!aI)*$~T|lkAxpLMl`ENv)(x3bT$Aiig$MlOl!|Dt4W^M|8m0EuNS6S^$L0GEPSW% z=C3wu+))ps#r)k%)<^AtevFD|U~_%zF{-hkbq0Ke&^7C^VX;T8fs#z zx!p2SnZzaz2`~#WPMB?3b}+`5r`~hAyq0+iV?Y1{$`}e%54*fpuk@=5>s0muS8N0} zhyaVbpY^6|B~0(9>FxJ1mKhFf9_sHjRd;&>oJwU+&=Cmv3CSs&>{S`qn8-4KiMudb zSYdSQbO{%s`z%0;ID1Ur>itP>VOHz(&!o5uP)xKs{GF}OcWT*@7VXo)@VK^MXy*JW zUCGxu72O;1EMm-_1U+9+1(lMG7F7T+>FubSQV(>ld2x9XMyh&W?6;Su*|Ye|;f=zAg))O*}%85W3GNV~_G!`p_28A?mSq5KQZ* zftxdd>UBv)$dsIh9I_qa{6C*or?);O7Hl;l3c21+-cE&U(-zBCT8>U8pg^uu)@(w7ae^?bj2=z7_=A~0-t5{l zNVlO=ztW54AeFVTXWdDQ117vWvy4|jt4 zp~lh;MbD9S>A}GvDtR2{;#QB;S@*~hH;qC0qT4f6EN*|aK6F2ivlS6~j5>FQXnmj4 zwsi%X_!|S?CY}?nP|qfkf`a5b0F|9g2mAVyBj2Hs`^%8h1!k0Y^23xGgd?v-^W#UK z7Xc{$`-KM=iebpg5Y6z+S|)|h*zs_$nq4`Uw6SCnn0dNw7n3IYD4-;)(CHy4f zoL$u21akZpXQ*|^vIPN)EN%v9n#88vr0=wL0o9albhlP~=TJX}wsNg>YwuV{zo+$@ zSFaJtQF?B>Su~~dBgb!l$7iSm?>)OABZB3lA;wuTDCyAWp)6U*N)6{++@b;qmUdfH1yqPY@#6MFulU zO*CG|Q}^GA`FTj0iQ-Ldn27rJ6lUe&5^^~B12383Qeq1cizRHaFW*AH@R1omZ<*tG z%&1!$ZpYdkD~W6fBo%-%V2TIz%54u_Ng@Q+qrKA`L@-m03!S&)y=cKrabcrG0fBph z7NE+t>C2bF!X$=DdNE8a1WifR*g_GiKq6|r9pkerXQ*#C__GK;^&A#8LB82_f$GT| zS=Nqn&vr4!C7WLu!ZCA#_B{u0122DNgQ+-5XR^ zoOK|Ty=K9$W@K$vm$S#L=V22Mwn%>@L1kqjbM^ zq0pz{NZK(1K^1|DQE)&200RMVP`u-?%e|$}p#__TML-F1CfFRg= zaRY@;-nPJkoI$gA1*JC40Q^Egbblit$r7!cH^?{M@5`CpsmhsH&Ag1|BpiLW2j@rE z{59mbP8=5ThU=*YgH~*<+h;D{C(PFfITxAeKwgSpOigu@a3ZyV1;6L;xe}#Z+EbpI z{Mu$C58$BlA$d!KsL^t6ZcMDIxdajhJH;VCb$Lsh4H#YUC_ztg@a7-@ZcNf2Um zXHl-geX~8k+mV~9sYJtueP(9MVEIR-*4?yjktAxN$SCEFxT%L2|H{$vu!}Z)H>gAe zD#@qY>xv30%U-*r;&PYyJbHfZa`GV9e=(-qW-E6RAQp_bcciEtb064WN0n7-P zIztTu7nD!;V79TZ5;>Cz`s{3o_SYa~0T2ChEgL3QEkiGjjm(*mlrZY=JB<6@4BCFT zvnIr9Ug#Ljwj#f#Zi;zW$=0L&-3CIo7}79amrSkAT#mdTjnAQ7+Y`;Gvay|Tz&9@gh#o0_IWYM3 zJ+L#56yG+&$z_%JjTizihBq?(tKn+o}&f_n#`Ls?iCrBUR9m_fdrxr!re;--HcR#b-qDKMSGI4ZsY0kb^IZ6MjdbtBE}Q|V?5V9CS)c0Q zLIsL}Ey00{3&AYMCJ~{HX@H=yfT$XFA1wNJCbbsF_0w$A(p;0Z`IPC@i?D2u3!P!% zqH1#&`DCrRJ(3ZZhfB*mk0nXXSfhFTCiorhz^YBUv<^S3m0Vkf|6Uxs5dD2=f{-->P~wFUx5jhNo9){}gP9*k-W`=Wm6GcO7^^cH!W zO=8Ad7fNG9oWKl(aX91aG)8?dV4@7bKUeq_ehmJ|`=!*X%{a;fLdmSTSN@ z%pS^v78f3a1Hm>jQ*4>lmp5H`&lp0N8k&rPXPI*rM&*9w=aY71g`Fb%9)WAlzY&QxkQS?Vp`<`VXX{mupI& zZe7hLy31@KfEYncY3v>54H+f$o-X-t410!FHcZKHb3;Y`~MVxre_}Bsfd>F6DJuaSBj=I$&%=#^B0CB3IZ^XyT_}ysdC9?~ih?v`Z60u`qd&7Y)6mETXT3eQ)pT?^ve@)H6D1>ccma zj|;6Uz4TO+Vn>G6-V<)w$rPdlUfv|WN?9!@5$rqttxJb1a_<$RcaS&SGuQI)88IXS z2GXtM7BFAF#a@YuuR_`np=1e3P@_qcdz)(la+XoRXT)){wG;)L-7zadU@QETb${)x zik_jcr_wJtin5foKFbrVzV02c=FN9fc~|qcDH3;OsP>#e^?=%wXJOTIII}+KU)?MX<()5?#V%*JC=uR798EeN)H4@;>WSwo3Ne748c8+bNvVL z%0K(K-z-Hv?h1?r;k1Ja_T3auyE+V)l2%chbnp=UmeKvY(zEin*8@*>63;glv<( zTTR4tU#vFcu;p8Mqm0^mQa=5?Q>2T0S6q@p3FPEbxm&`C~z#ohy$E@Acx$z)D_^3kK7cw$|3kLSO+UVz_m5s5Jre4URt8n44JwGg z$5qYbZ{(;za10h=Ab8BS@YD$~I@W4nBBEHx-b`LRMeuQ`%e)0rTwBF*y4Wv0J8ja}yUJggDP1sJMxe+)r&2L-&NooMCkb00sz+KTtf4s$guutC<;ht~9 zp190o@dG0NTPb;uo>VKw7gcNH-sN{&>?p&?f;>3v-16k5$wAG_e&KX+3!oXdVCk=q zT3@?h&?v-S%!7QEDWWb8KKR})gddY(`*#qw|NhX`+;aJe=pj$Bg!-RLbc{gcPZPp@ z(^s8^6`$KR<)HW@mybvT<&pb#&Ch4UH6D%*b1lzNq{Bb*I%@WYA66j#mNaAxK*b5; z4{M}0FbJg<2tei#OKpM0mox+E!Z;}$7ui}-CBv|Vl&XrT--?&I=iPQ5ya(BrKWyM3 zB0M`Kllvr1HcEwYz=FuB3)1TwJvxwrDrYqygb-3Is@!9io0aIp<>c|-llPz|L#LJ05Y}yXzolUf6B_9tXKPyFq=K} z7iGfIyQ^?6kC!PmAM0a0x(iEE@zW0GBdaH#aDC zm_2CdGduP8;GH@i6TPh+Lx);%M;V>K*Ts3e4v+$bl&7hUY!Ry9Ym6dGgySY$2K_h5 zOFM*_e=`jgd`J=-Si0G6%G;8+0`j8g*`@>50D6DP-QekMa%#d&K?E+u`2+qxXhyRURqpue@xV?+y5Pv-hB`yd9kzxEPR;O_AA z5CS#y!|L0HQWppHl*>DsQmRv_@XczORlcefyUk9jmNo2adS;D55H@Q%6FXn)AfhF$ z6}%dK?0qde!liEr;t^!je@ihXko0tDy9Y~AS~GD>=%uSWY=I%%{@??4%d<9AVsDFa z1|(3e4(h)$%G$KBg);4^-#XtvhcuG272{WGqu*@p;@*vjY1$qy)U&H9mV>G0WJC=Y0VlVX z2kZajVA|e6qjy-CzF|r?$`7}*$CD=0l3ip{0iQ#m)iIti4zeM02^q5HKC$=(W+?XX z5`mt2JPOb+-Z+C_5og^WR^x9P30cbR{4^Ejz~nnoQMq(< zXBwzr6zyk<%jKq{id*ppy)?bu0paO1IIM!FtDU^GHHl`_mtai-PHNRubP}$PZB{s$ z?%Tc@0IyPdh**bkIS74>Dv2RWK6os_5|OiN|MrDQM@O@Et!@f}cA6{~w!K#G+)a>` zz4E#yWdp7aa1ETGaH-xy?6kC00pgJfS}}2)y6c8}~eGq9sM7Ho9}f3u325+&M>0e#toHk71e_ zd#y%)RN_MExsKC*3J%u(NrB|ac|@pw6jz&dOYVfZ*Uyh+Sq#=v3wahzpXuRcYjn7| z_z8{=0xX>rS#Fo+l57N0WQ&d0p@4x9jCPZK%(_cqoj8sL=!`8TRkGvDm#f>EZB3x2 zBHNOVB@v${T}QPxPo=%dt4(Bv^fj@F`{i@*-)gXnnnd&!&1-7RO`=hP)G25zD8PUt zaWU!lHCz?f!R|d<>j_6-J=9L7?q#*8&<`gEGaRSNX|2UfO6Mrfb+b^J!EoTrw2?q& zJ>$oH`1PwU4z{6bIB-p1B*xpo%_VqP-XYhlZH15kBT?;f=3iu<82K$#>omHkTJ@T#_up0P3& zi=!bQGSCzp%5?{AMIS+~GOECJJkwbC4SrzAK5wMC#srq`l_Q9XL73RuRyt|&mFhEn ztI@RfT_K#zi7WwoB_M#swk!KAL&=Q@j;uLo^$Ue46c=zohbT#Vv|9xKCxF7<6&072 zNJQ~cUPh7G=Gd{OddOvEt6-&DOs<8b0 zOB42>T7Yt5VdJdMrIisiOfNMj~g%|U$vTb${(0=f6|O<9&lm*H}`43zAI;xKVV6HX9&igy`ZuphuAw0J|Q zHYeRZf3uxr-A%li?>4kaiQ5%tA<75t&hX{nQns*p{OsUfIqu(1 z^j|$XSOU`yvf`gL!s1l;#^7x&wA>@dIB=a~9u|f>NWAL8_K!#VI(fbSuRZoxxw(;4 z9AlKg6?b+W*K@sJc@@g|1UjxOfoqU~U@!(vomON?kY(B)P#0U@QT@2j*>hg+Z@0FH zWz^gIr{pLEHu}KH$q!S5*l~07g_tk|3*Zhr$nYA8t&b|PW_(B?IS zUfh28L5X7noE0YddGY3o->(F)%}4Ct>k4d+YlX56Xwjn=i<)l?KMKq?nLT%X3`3kV zc{68v$WE}cVVzbC273{p542Aphm29QHp)U~YsLi}p~#a11Msdc2BYJ`iF%&Q8z>)@ z_p;zS5W4w?SrQZ*kfD`VO1SORlMd|w@g{J_}5On1`bOi@H`7yTLsg5jGh z*b3&~Y=@*k=+UQSS5l4U7=87IrB8rlQRbl}lhu>v>W~~uKV_PHz1hZ;!Y@Gg#{rPq zNPGaE(C;6$TLPp-T=AM+cP)nB49;P_DD^J)!ZkEq78_2V6$=RL>m6znx5UW5h0a91Hl$j+oxoa=iIM zrt}exwPvYfHW+oqnFLMN^WJG3AoD0Vo<{FoJdD(^!~g4dK4bJo##8U?oXLi%hiNVn z3x=eH_5#rJvX?2`ycP%8Il(v@RxrW>#d~JKn?auS=2C!ns)iR==GqPw*`unTS@pOa zl49joch&85_aWBxZ1@zOjTNJQ2!S*kUTNo=PBNSv{y-2l3E*lvftGS;PP0$#vqV}! zKqUd~zjvcv20w6f5vlCk@y~S#Kwu99-V9XYs^ev+FvK$Kl01Egekg_uGvHUFN z{VysraS_`;ou(Zg=$Z1V6ntObXam-AXvJ?Q>4SaY`)aTBR^^RgBFDVVuyM9>i^n?S zp)~8LEGyYlf_42$zQI`0#B+|;8egO?+NWC~7j1xEwGAL=HpDLJyR2*Gl%6p7 zm)o^~SRJ|B_`@?#W-$2W*wH_+8{^WQQ+0$Q6ONrmbneV{_-llQL-9U)Fk9i#OFQT* zpgm9{IUBAzsoSuzo2i4r=BHjHco2-MC<(Et+=(4c?&Z+QXJXHLqc>*HT7&frQP1GS zZnkYu=CX}F&I$*T1OuPiC$a&CB0-%~u7%5<~G=3Lk2Hr zrQ{qex_LJ%D4a8=8T`kl*DM1w4~jD`RAIej>NQ-zZ>)2yT3LSvrCOafT)+~aEcCNIs-hyhqTQh zolv=9sf0ZF0HK`?HK(W~6WI2ZBEbT7>6E5MISPyWKRT8n-FMH!R5HA*FGE*18=7~5 ztP|%NMu>0%y@W1>{H2x;jmfa5f~#wHfJ?@Z^9K{=iqQ!P1>o?PZ3z&Ovfd2vQ27i5 zNgR$oF(03mon5lvEv<_=HBAl|{rYu8Ir1G)cC?Tf^w)zz7eNq9NUJ36#7*ctW|O=M zA zc4V3#Na@xJ(_eDmHsGXTVuI^t9P{19a*$O&sU}3YN`;A0p*`OV#w`}Z4XVdGbO!4t zNMPg}VVP&Xm1d7PNb7qe<;0b7rvB#qaSk@blX~I`5bJO>DigqI-c%*M8jb`{5e!B! z>qD=Xz~HFOj1Ay$>@%~eMBZ)=S#}inO^=O*=__QZ)wnXDM?k3Gl6PQS9{Q^XwoToo80fzRf#Tn>b9{4G3d)&B88vZg=(!8C! zu@ltDd>cmRCuD${!wHyL0_IV^yZf(D7T{(#f*Qg|j{RnbfE7FAjjh8pC}%TMBd`){ zomScn4U$p3&aF^Av*=2Q`LZEce(w5{e~ISA@}Aw)ax{3R{{Mkq00HV})|Jj#r9hqR z$=WXXt*3*m@hJ}#s-a-YgWSe}j%}d!MIKc4-t2VZIZ(}(Je^1)orT1BB-W)p0C4=Y z!myjq6D!QDq;_A@Vda!o44x(Br2q^WdW=V@?V?NRp7uw^g!nY>=GDKwbV)?=MX zIXu$mh2J}rjuzbaesWRQ- z3=lnMh!?G;3J4sUOJ6|(*R6Y{XFhC($^Kqh>ss=mQw_zzi!KX>(Ow;!hZ7LR$neO( z+VoDqcS6#3uy<)|bk_N3g2kcq>RTn~0iZn7Nm9mspCJ>T`m}wk9P96g?_2pFho0@; z>b|g8##H`hrsJrzNY-vPfQkTjc`X(Y(73M0D6!;VqZTT8C@|0uOiLLPmzuVqk$$+o zhE;Djc+G!Zo(is>Eh{F};ER6a2gQGniPxOf*x3>Vx!U8E!EtxYXBc&>R?@ z^Kg#LiJEP)lciXG^*q$J%s`*mI5X7Vjq}DXxNE*Jdj!TvhI8Hl{p96#P{>+U!G~kO zDexs%+4DU>Ey~qm8D5Edz(HMY^7N)zK&tqL|8x1u`Sv7V1MV{UMssg8?NJ9|78AtwJo)*`dj^#_6p4;c}o`H2;8dbHDZ zAUxatLasPDUZAqFze8C0FxkcbIaP>MVG%V(y~acUu8=X^cGzHqf^rG!)|r9RC0*B0 z^+a<|7d8-v@lZ!15g_4)fD$Wx2jJWxq^>uY?v7qlL4%NDNS0dWG>%=wy_-s+%dF2B z%H1Q*zo&3^AHs{>13VC2tMN2iCm`Og+>SsAGUv#lPrI&8{eKY-?#a6H^9x11+sn8` z!g}2FH-Q_b#(w;-LoGmS4qEvTvl}9ZPYf_D%C;+ApW?eA0`^7MgEiJUs#>2=tiXNz z8SKvDqiye080DUQ)w?aRqvpEpierxh?X-RvT4nr9D%|Y{-5WxRYhBjho52ij3Qnh- z*!r!t*SaG!*fPfCA}{1ufFEpT-8MrZmVvjXD9~}Z^L;doK$rOvMS^937Gz4|)bT(6 zyw$;z=%^^aZzs7c#z)>vwNu2DVJ1$uWPh8oJoYJ8tGR~1U1}u_koW)q0{~}#nWBYI zqfS5GpoXW94CtA18T|F$mKt1s1G*^h(4OBAi1xdmX(^}G_JuvsWz>Gwho3l|KD}Qa zNC)tPJQf<4B^JW$>A>8kSbl>BA6$U% z7kZXXG<(22gwCSrTJe&=AQFt1Q%$DfEVQ%0OWb5Mc^Ot*#~SfU|H9Tj5?DSG+pQMj_8X#PqK3#^_@oHgumPx(+28I$cHdskYFtv*Nb13Ot_K^WbYr-E@-APdUs5F7ky#{~r8x-?p5ee!KFA=p<~qX=494cihd9IxtN zo#b6opS^Ee7xahk8#{?Kv8kfN-($%+NnRCIx2Z|x5an+!IYpwXePFOz8T8uMH^aNO z4f~l8U-wC0XXEuCQQ>_;Dz4R66?%GYoh+k6b--PeE1TevYS9J6OBh~kFvFbU!G)!J znJOn_1^7-wa6Cu(L@Px{fiFp8Y#HOZ&`buuvk$yU8jM55f(tN>F$=uoVBQS~+9f!_ zl5sghNy<*-3X-ksJdrLR^q7Wc$Lb@w2@_C^(re=G9E)a@20Ojbjo$NKCv_OVQ*@sIG)AM=u znvOe^Aot(eew%XNln6k|G_-T2h|wd|nIkDdu?GjGm|t0^?J1Jsmhk0#m|Bi*oEh z>LUc&T2H8qKXhvK??Rs6*Xs`nS}2Sg-Zc7UKJ<<138;oGHpZi24q!(1_y8}!T@=NC zKZZASAnnC&nH7~84uETwBN^uyVR6@ah9N_Qv&xRryK4ghZ_$vQvo>;_~P zD_<}1%gZz{jMZ>z&7RAJ03~LGUF1{--i60>s+deBGF2L0h?6tSNl$iO#8KAcZE8oX zo7$ORY^+d$I%wO6^?*h$ST=N5sjhd`=t6S!PInoJ8L~HmeR$1f)3jMbx$02HMn3c$ z*igELG!{^JzkZ5%xT66M z;2xxu=lyuxX^EDU-2(MD_2rpL#&BlR$0w1uIM5QuSx+g4vMPw7lD+|DoreN^dSlDU zDe~z6zCc00f^KTcsX>PYX|R)z7u7_}z>}9mW|`|RI#pf4<)M`3-_Lz~@)5>|Z9^90A`=grg@%p(M* zQDYKH34khmp>z7F;ruaOgS9O3kivKRB!K=jV>nK-!z~Q~E5+rh#WGBC<-pVAS>M@0 z6W_1n%3j+hvT3nU7BpHDncQHXZZ9Pq#ADiSw4gR(RUFn~Hor8>A#NMycK{ zcyyfXRI~z&{}iHy6ovhL94@s#|95azs>wFYJbKjPq}E$LLPt}8yJXwJiDjgD!itPF-bjq`*km7!Wj?zKiq0UOMs zz!-~QxoS{G)&>^Ut+@Amt`g~sEv7I_Q)!T0+9I~Zyni$i&G$6T4j^IjK zDMs-9uuWoYDx0rMtZ0z53kg%6+)UCIi}gSA;LsW=z$;{-_0_diL?sI~E&rh7T}Y$p zPRsaKkKPmHMFL;&qr$iE@hcbcHv;g6z#V%(6>iI~OU5CW2q;eq3$lYQS?Vw5E@mQI zhTO3~-)J50k>g$gKmh~*00RNH%&}C~Y5N^3$cUxIYgKy@v&8%{#KlL`pxEF=eVu&a zvy$UdVv_Ykidu9}m0&CC|DR$bcC$tCCm~ojm>NDs{wDT|(F|G>>9yk3DZ&1enTM8C z0U@En=<%7Vc7irp+tW~HrIP&;hwbNzuI>uMECB2CG^9unFG+M8Yf6g*3uel=a&qV6zskfr2t#T*T03%0j>=)wI zcWXy3k9?|~7e5ZxIo%JL^XEV)KEabe>FxRxO=7ecCgcTUOyHFXQ&khF2!yo*rRSKJ z(W-20m}^q__X;ROx+rIKjWOMHZZd2sa4Voap z?&nS4E$>S&bwxi_r=^`d`Z11j$4Sl?UOzxeV{YXRIXZBDp5_zS^q*rznGgzlBQ(Sk z2M>4zD^X`YhQBn@t+T9{pve{A1&D0aFr@vEM&q1%{Stat?zQ zQ@6r0bD!4h^Sg(s(|CisAO&H$rb;LDIDt5soZCpvKO^UfhC8g*SFN0{sC$zBE6Un| zE;J$HY{f1iSJVngkD(54^?^YRPEpSo^ceWBy@Z*;aQ1+5aoo=gR{Ufd&!|4Frc(LH zL3c+MhOxxT+nzS`+27mz#lPSTZ-&r{TeYuBBRO1zLG|?cw{fFQv3UuBFwTes7RD6D z_MNh~Pd>)oi3@~E&?WlY0v1I;cmM=zyylh8ueC?AW1f=o8RPmw5s ziOj~=8ZF44PQz@BTd%vK=~dC3feT#cQVEh8CrbXtmygF;h~ssQD(gO75la1@f>!>F zFZbTh=b_1oLM7yG9Q4UBLQ=VCO)*bcdy?KNj0@?$%WrruM30HxWCY@2h&`cTK2F_11X8ynBzcX5JJf7|1O)0$_1n06xDl$ip0NFf zZ_u0D$N*4|BSEhVcy-D;3!-bXIq2z1Z9bn;CZh1m&emGVq8>5}19y)ZD}$1n)hoo3 zbPH$pg@55U97adO=TOOPcKDpEnAYby_uD>t_c1ra-~@#+YR4XC16jIp?8Ps3VV&8s zzceJ_UKGJIl^7at1Qjux8WG=vl!O-V*aIsCyF8It^Su4C%SF!C1hXa`s6qi&(AgjW zXYfn_00RI3R*pHzbjQ2-(iFAE6RPOQ(f-N9IvOM9q8cznFCZqY0>#BjgH`If?i&MF zGe4R3#00}ZDX?Jg?)tx37vz7Kx)ik1&PDv1BqPu5C#`7 zlFC>+&6@zXE7H8-w|YfQq;4R}gysPUlO3CI#N~fDP(rL>IQpr$ZXwCkI>zhj`7v3_ zgfr7k-vZ^edO-2-Oa+9$Bk83Q%#Mvy~!`QB#z^X^1awyOfRrE(G@kLol*iKr_iCvM>I(g4p9^9c>ZaKQndt z_#L9%B}(3~M}wBSO-yRp4AbSHhHe`03t)XrCLO!7!QR6kul+nM76K@AR$o^(ZK8-> zp`%ehbVS=r#S-T00093 z08$7}F*X5HaC%mZOd>MXIxzyV7{1g1El*q9%OI-C6Y({&_f-u|Tc8WaZD*jI_UN(VrA-O! zhv)EUeBQuTz`6TyQ&;|C$%UwBSop+4M21e?RRr;u?~UQ&-^c+)`d#t70<(5!v|S%- z9SW%~h-`vq@fhoWRp9-1+1sSkL@w{sxK*m}y z46C8j5=k+QEuuckO>a=aBs^g;wm0`*SUd3CI1o1II~}c@$1CaK#otQ;da8E`D;Mbb zMA57S)`fllfU+JHlBm~`{z`<3zieOGy;oReXAzt5_I^(IHfEuZ){LH>GDF;tCEB5X#;Y-TyJvR%zuxyquLDIz_e}E$yF(Al z)cxJ(cPB16DNr0_?B>j#mMWKvTPoZj^QVSYBD=kbU*wrUZ0vWdR`h*U?wDpu!s>B& zWfe@(3plW{xll*T( zumX#km2pshHLGPb-rlA{ahbH-nhNefxD$87+p+5w6BrPv^5AIS#1vDN$HN#DY%c|F zhv4v~#zBlCTzilRW(ctgg@6EYbqdomA?}n>cMx1~Nu$|MIiD8rb1Gq`*}G1Xzrl35 zG?Rx7V82iZ5^sXiuJ*$bm~X%U00RI3Gm_gf!}~FPp5>(rxj3nI9W(8l=gJYC@W5ny z77}Z;9tQaCVc3MyA+vCn$esN0Ryi8vh0JFe;V^S#d5{0fU6qseB5Iy^uiD?WqW#WN z*)xL7sn!XxqRxpd1-CZt6X$Ij$- z>Bc4IYX)NxrrnT##CnKZ5g-o99(OhLFRHMnam2)nybMdX3qW)wX3Wk|iN&Wm8)rcP zaJ7G{x#C>@PdPfh51tLh3an{23&pO#F&t|-$pKjA4BTZvSw9Cvom+ao#Z_P_DUapv zv>hIo`LM^hT}*|f=D}Y2yel(rKq%uQ!6V|vr^*W-NtsY*)hIV;^~&mKp0Pwm`@gq2 zYG!VCVS#65%1t=D$ZrbGv>GKP9hiB|>3!a9xw*-#vplSxkJ7Pzm+J6SfKyKN)i{K= zud2Shw|>5H8@BQO1;fP`0Cuo84Lphh`q>}pp3kPc)bB~Op0RmSp*=(twlQlgJ8rGm z(({(0yrD*~v2Cv#O*X{m)bbJ$h&L@Txf@W4i-=|T6AWEX z8~dLHWm%RHC-n2{C1EB+-_m8@*09Lr2mhcBH{03|gTi=+7Hm;Y88WZ0dfcqdG9Udt z4jId3aQ})ezPdy_Rae*E)ZXu>|%%)rtU&)R^FvA|QATRqq7H(pWi~F*# z3W1dbEf7%Cx{7fX_hTZx>E{A zw1=p=^uweDHCIQY0009300RKym^utgVAhz8d+Rkk17+{@Wst8!BbEr@FYQEc1SLr1 zuL`JT7dzC8nfVJTJ0#+%(E!II;AP7d;?W3rJ&RQaoIKv@ThC!)8Dc=s+ZxvC&&aPG zy7A8v^o>$VF(?{YR-gcx+}4!Lbqp*?rJBujh<#cb-o8r5a8zdV_gt#c5iLtvjX`IiKs@2}o9QNc*6H18T{?)Bk%$yB&dUS*1n5mTDOpMj# z9qDMawx{sYlHDco1unCXw=rDh`I6=;^T4`8P?i=W(=bT$sL}MDHW*o?<5|??ZLiYw zuD_xpfYOzRx8gfyW`Goia`8u(ls9%WvUKz5CLBNxe^<})8vKGVdB;w>fFWQ01}1g8 z%jQV)#OAoMb5rl8F?SFa1W95}J=p^}Qx&%)nLL$>y`Kke+2n&n{S<`Nytk^aw*7{5 z-B=$=y`!t7Q^6&tT=G{W>1b0b*3>m>st|eJ!RaL$>_325QJtZ_SD#c5!I18degs;yE2&HW z2F&OFbikhV>@a>hj`lYmycc+K%Gm_Odd!({yGXYsajatsJhU!)4{QVh+9d_Cw8HIr zDauF=7wFX*XsW-LB|T4I__}1=rRn22eL1XZN6}sPZl$R6f>wmw1__;{$10PdXmL6= zdA@}(w}1cu0{{VCB3|K-sjp)^0`i$l)aA4IEhybw9_1FG=D@1(^q&20@FyGTmn~#a zD3_VK9?2cHX3{=Lp;w-z_G5I{l?_Pr$bZWcot0-W*cRfG}tjfg6<6c0a%iOjw8#~uT z1zV9S8aOy>Nx%SCb)Oo2N0J$avG=bZG;&5p=DWL8)}+>hF>L?WK-i=p3vE32-|bPe zTUq$2Wz$1^?FfpCK2|r>MK>hP&Ft)AivHAGw8~N49_M|w9wz-4kY&p>z-a(K~wo-3v)fmt~~W^YrB4$ZE*15I0v^SKA2 zg5B(hx3R05ZS(?p)^`b3H>nU^vJ&7VZ@(U80vC6cXRXSRcCpTpgs-YLLI23VJ;rWg86Mj~7XBSS?l|iPf8Z}|-f0KhzNs;# z4|01HTA`j*#9-iI%*bxZuu^!MLAHg6C{PH{OqB{4qRhsH&bxrDMpO*RFWt!XJw&p@=26l=G zXHn`?r|0ZyQi;uEBn%TDN&q6O4c=Y3`Cmt#B}Upubf_! z1mF8WJm`2MdZw_Jq)7h(Qg-n8#BTCsnoNE}BhtNi0~;`^ogc2*y7~*;TT2Y#XdPVFV6!^5~sl=suEu9}*7+nST%hLs0n_&+3ULT~eIR?#0Gx zgdw-^{KeSu9({25sWjL1Q+_jYGH$qB-S<4RUhYIl8Xs{0QpA}ktqX@uK;?MojTd|Q zP%g3iD)ii@#Kov@AV+~WJvT(jJ-BkiM*$q=t~1)@(#=pD6>8){_zCxdJSGoi@;I9u z?}<@$pu>h8(d(8g)v$%7!VU$O-0U%SdnyU#<=mUM5s z;z9F5JPT#r`Q!!D8#EJ4z#NN2&yJZR{rBV1{{L+!lACO6p!B^qtO(~7V=VB`GI$pA zKP>psd0a&l&R_&YhRI@ZKmY_9RzoE)ye=a)#{c{BMmpnI7Xzx2jlzN(XHp&oH%Xk4iGZ|xV3SuIIp$nkgh|4GZ2`B2Y)Hs!9>;eEENggaC zj2xhyi|wum_iBQ_-S)D!7(6Zom>Rx^$H^YLta;-ijB6iOF{%9uI4Ym^%fr>BP>=My zPBD*i?xg?!C2}5(aBB z+RW`@-k+>Y3P`yQ?VZ305f-Lgl=DOoR}jHP3(i&!y6=HrMcaGjX#P->SjNWp;<6 zzm`R%;D?FR7}`-{JEH_VACCYlBO9R*H@>9B=AcnZ@yt3;a(?0NIwAGJlEv#y4S2r@ zI;p?1b-(reXe_O|fyVN+&%~KcEUOD~Y2m+^XA4E*gO!eNj>Vl=5H*n35%XOLLku=A ze$*|n1t*qVc-AhmU)y5<0mPZc+koqmPvB=+fXE?MX4TzC7+Q4cVk+I8$~A^vMJ>m$ z-#pwnlE(I$8(qQPQQ%8#Sb56C9hw z1Jug(#-{jMP%xQU1S?se|L#Bl00RMe3w>PGAMXYAPDP7YwcVZv|4BK?^xO*hRY;&A zWfxl3y2CiUM1xTi>R?LGlsgH$$yqYNbXllSr3(mBB%yJ}b2!9E&$3mDFW&2eWu(EL z*4-(PBUmY(w5RZPBXq2=Ge4MZ5mJT>D=r;jHNv!ye-PtnTWZD6@q!$zyADtY&ichI zBeViVUKh~kwxk^(#mWR4NKl^Crd0j?6Z-@ksS91m^OyJz;6mtY;QJa+SvZ{s5qNhq z-K@|A!|%QdgLKOi9rL2m=E`&V^9(#lBh;^-vUl7t5b1VvPW4O1JUBwtt~8i@T7*Gl z{(%Fh<>zuF1Mho_Xbr(%)$#%3pW!~OKh@x7v@e2_^hqSI#hY%)x0@Rdg8trN0M*BT zfcqu43M)Xo_aWTnm>6uDa>Z};sPh`85V{;5ps^A#L5#l^VAH^EnLDx8l%#+2tYMTc z`JvVqulEj{4=BzK+}az(_=3A$NjVQP8l8d{xFfh~kAq8+!jrjHCDpk=CX|C3w`w8e zatbupzxyBNf2%_2H>N84z9*$6c&(AvIc7Z!d0IKxfwk0G%25WY#gc2B!~xEXefI0* z1WTE;QWkb>>Wsm0-5u>7n?i+|W1UHl))Bm5nN!4xrMzT&+OLr;*RSrhG~R}^!Q5EZ z4;ur^j!CHN?k{%6OILY-_xIqp?}N;ZdXy(&Y?w)#eE!5Y_8O&sjTYqAL8{w95{+8d z5FcRb&=(SCP&6Y6(tC3osZCkn=b8mZu4cO7oG*B9y(Q86U~R$=f;JOOehchq9BncZ za>OR;Se&SfF*lKy)7Sho(CbbN?DzTil+zSsy7E<);s(~CsbFfAg z2mF}Hb}+ayp{3y~)5F|(e0DFY>*0B4bl07N#rU6^#3Lnyx(!f6~ilpnPOuJvuV&K1<-8xaUf@@_mN{8^(4ct z{neu{65o5vemxE8{x4fXEqP274z$1s zw9;ob8l@kRz#fkU8&)Q6BVYgk0|0%^|FV|N06J68(k|o&iCifHljz>?gUp zU*GmV8LOFpEv|N9v?LTxNF9hNbMoYrd_AWdFw#q4cA5!Nf0=wxABut)D>E&33RNNiOJHSA#T1^|y-#EFrQ9Rl_|Bw%ErW8F$>t{S zc9qphnJmG3S_+55~RM}9xTG937ZtHKRu212aAtFdJxAB$u zBsCAf07>I(@vXf*mIC~=i`UVU!kZ!0#NN zeKRIPfC9B!z1NQ+_y_i(y+JA{BkirSV>JZ$kA?3I~brJJF}WrXX(c~wpQcnb#3GznlmQVQkT3pQh~s0x z`S9;H?U&1^?@6wktXal_IarI7Nm@%hLP$q5TwMI#TOOYvHNO7Cbig3Ir8wE<{&lqN zm?ade_+WcqV(?1(j)AU$F084E>8g^;cr$KYr4%3H@e(GA@q0gZ0j0Rd1W_+~wrG+j z0))X~a>>xr$x?r33h}vNFp@fR!g(r6r&sR4zt)WG)hf;kBH@={YY=^z_SnPj5(nYg zUQGCyn9p(OuAyl9$Uh{@k4^N~$!q}xT1saBIGqD)|7U?kn{xGfAy_W10>DSzckB3F zC>@9_C6L`VU?j#C<8yE>ns43W<~}1m7fTN4;%+-UcYKv| zJYROX*%plgpp{`Az;PLC57~H&&W#kQG9N7p-9U&iqJ%9Q1&=89DzY%bVq;I}xfx?h zOSmMBaOaEOY^W5u_|2s;8=wk=QuHR3zX!Sd(-9pKe(aOj1M-x0top^@oUUxo{jHPn zWaAW*o5FI-eLlAC+9Y>zzkl#Kvi{1mem6Tox3H+(M>tsRwgvdNI^dC<`YhlO2!I(n z6Y0ru^-eii7WTPd<2)3G`fWg=_!IDnI@lXz-XcCkg^3@ee(Qv3to3?B9S2b*TN&$% z@sk#c{R3f^o?On)@inqFee=HMW6CWJ^n>B%KRJPieBVH>6ZO?0vAVIuXLql`s+1E4 zuv!}n5#1pkXaE2M00093TtxXNk5((#O|Bcv)jpno!6+1{`Kdo}Xe-#yqN>;_FX6yD zEI{KjSV1Xsy_D?@2GS@>$F&pxITucLB@|pwA~0{^dKH`66Q~`({eMH`zPD<*66B11 z$$KU!fhI{ZBSQGrib~(8(1MZD%1D0ps)lAV6V0Pfiz(h^o;jD7Kzh-4?9Wxab`N#H zN^Yvwf=Po8@IN)|(@D>#XGOcG#ei2D4}~U;c1TSFdGfS!+n+qsYx`K3C)qxONFq3$ zafi+XUhI$r#i3>&6h13}yw|$>Z+p2g)rf1-FQIL9Dn!j1*Kr@a4$XO;t6rN%WZ#ff z4bC=IGs*I8T)V8i9OlA_^nXku6a1e`7`=jnGkPz_*)(B=zlL+mjqe{%TTj&r*sPdC zYJ=a!`FISqMWswr?fJ}x8eL?~T+D6yq61+`y&JqtBsM0@jOqv%J-H%ZF^|>+`Ln4W zq;Hl0i&KgH%nO{jk#n0N=)n@rC$W`tt)Co}3+2l(D|fuonDV^!TF_u^_8(h)Q#BEi z3qPFJW}{}lEki+1>Zad&?a0(uMId4^J9#$zjtqoiR*y|fgEQZR-5rW<5B^MU&LCm< z6*+>AFzwG>Fcd+oZW(%s3!#CGYtH;yjgsI26R&d-zZ*J>@akbo^(orH&yNR2DRRAX7 zH2c}9_~f&xqq?uFm;`N$**PjW$uY9@+9z@}M-2zsnL=fZ@NX?ePcs6ag1Zmrfxt^qp(ARF-T$LN8=9_xC>XI~3GRL4Q)OH_BE%!CZ?Mobs7TFZAjF70qNH zMU+bA@2LEh2z7ASuw};%+J2A9$XS+H!T1UPIz#8d<>y&M3$djFd>D++U@-Ae-Y0-~ z=1RCCvvNyO-aSuQ<;&MTXedQ5_kz_$_FSa6&ov7@uz;XcQkr!N4^$};eb_v`0+=@` z`6KkU_t$%;RIpS#FD*sQ`-)jN((SJsxvj(|&zCjQEj#oZ3Ah^qCD$b153pQ!-L6=> zzxJLUPg=q88JG9~00RI33?3hfTMlRh45G*3#uj`+9M!E_g^Orm0`a( zV{K8~^RYQe{JoE6QzUXZc5+#sVbxKqvXqdU)bK*f`SFbyQ|0Py$#Em<(Z^y8z|F8l zbKpJJGrRGfE&GPJ#cYu`seYB2^JR}Nxs{xg%!Y*IGa_r_RW=oIIzW zaG(GHA3h2s?a3m$-8sRE2M-+b7R`7*yW&Q-{Fi5 z_M4#~s9S)&r!TnB*+|Vl9WnMd*nR<@y|`)Br{774o~NPCuqVybIWuR)Dh0`ndUOZr!NpQt_$`MH!^*sx z0r1m=LPS&e8>U6~%*$GiX; zr11QREwh}^wQC(Fk!4KoFBi8k+TQb3yUl{^ZaupknR$15aIMLI06Bm{~bV4k$UARfe{%%S{=;A_`PXDRbpk5~?wRaOz(FSk7{+9!UeTp`On zdB!WVAKy`LlW+m&J0zpSWYaSlf;m^R6n>Q{{aYBKARNW1y;uTO@NrCV{B6+=Y51 z$6fZLTOpkxI!_}GUS^WiEpy(L2z3kSv=J<+>f@R*5-82oW22dNd{x&N3ZO7i@%*El|aLrTmrEaATZJlB$xglC9evEUIm*J4Equddm_6=NPJLm)N0 zm^iNR4ZH-*rlRkC5%Q4O-Me+ds}m2mwbONf5A4K0;x;ldJ{#sjI@56Q=-mPNk5wmC z$C9!PU1N>1kmd8-IuTp(Yl-LkO%BcRjSZE>yYh@aWkx%ck_nF9f0MVJS1N)A78kd` zk_3qg9FNS2rw#o}7n8x;R?qCwf{Ud9x;ejUoC>WJ001U2J_g=RQ!?1wMWS%oKZA78 z6zLXSfahH^F!L<4R;$1N6|PL^S$!jS_>pEB5KJLcfWhOi@ngkGw)-K63J)NTrb=+Y zBpm=MQN=;#Y^I;%z1&Bf=9Fn4l7*Cp?&Ykiv4@3{t&#ha+msg^QAOD!HLuQhLpp5%mF{K?LFC7O=qyv)M165Cw{Mb4Ad#Md;HT-v%BYub%^aHK!#bWaZ z_*O%P|I(Ix$Px@5A_3k^LVu<@fG?~w&aLtGv_<1p^5-Z=Yi9L9GB%L4L&lvs#6CdO zp6~z>F{?Rl4nj#;j~CVA62r+{dYv-aV{*VBtQXo%vW| zlJS`$s?$0HT8{2qS*aQ*Rf-FByuYKa)>3vV{xVk~%~I|dGIF{6sqVT!b~%I@i#^}~ z00h>4i4(rNH(1tUd9h{4KBaR{oDCAyvLqE;>r<46^ziUz&GQXS{V0A1C0H2x#%?nD z!>#6gM&5D_3~fg4T>A zk0}8f7wWwxG^cbILc`>w>HV_`)E*Yk6}bSGmsFi7KT@-&mAcwsCIZD$xp*e|5~^~Y zQO06WOzsFNi?NbNopZmv#?pZEnr{OxdG!ZMrlDosR1^92&_R{}00RLVb*JC#cnXX{ zm1l4DGubogTWa!in94gZ%7(F-47wi>pD<2 zU@D1%02ev=Ykfkr3rZNNQc^j8v%L&HNe)qNcO38Dcjw%SagLkjzfynDHd}@AlTM|MeM#|3f9lWPZdcX-VpLp$zohrU5nPEgK zdxveAalH64nQE#h>bnUz}H8xxn5Yy~2&79QADB zG&Sye)_-;H(tCpDxe`gFgb>Y%l)~CVO28g}U!7WyIkrGj2q4ex<>Ce7z?4D+k9_1- zTitVk1%)wYx0j0Pj*0^TD-J(h^ zsBVAL1FYWw00RI31*i?l-LNby9XeKh>h-QI?2am}X(-k;KECN;foPXRrL`2!6ZhqX zT1s(}KCTRK-Mbvsg$5Q8{T5vNfS)}mW~Qf=Wpl{Vn%rTYz+nS*rgM_|zf|O0>D^?}B{aI&0tn00RJG{Ib(HKng&mP406~d>EW20WB0a4Izn_t#e0z5uLV# zAu+H(Rcm@%V}=nm6}s>|OBHm5`fZ{qgDTQ`&g20Lnc$9(gez7#lp9`UNk*BCz_D{I z8pKb`j54JzoV&aLS-x5_#Zs`9DwAY3gh0%8D9`q zhGz%LrVe3x*EvYF%_^gtqXjgn`pIBSb*#$vle`9_5_ROwHOv420{{Z1G4p3YmlD2T8Xn{0-EpfbWq*)T?ANJm@U06+3UHgZ{Z^B(Bc<$#Gy(kJBK|KU%n85_%Ol&E&({C|R;BN6h7MkNxmJe8z8Vi( zS$RiZn(l>mKuOnM_xg2^qW1yg-^MK@-I|3U7aXRUMeUBRm;>x_=0GuMj03hFdH^-X z(U04gNLjO)*oNJJT#e;=(EpL^{u~b`_b$2NETyO(lq*NM^5qs&{!p7Iek%`4@LTIz9?Ic$nj=ikzFHu@Ri)+SkN^NV(Y3!# zUg?6zqVIm-vQx7|Iqb-@U?fwM@MnncW^7g5xdK|PdyZhr#sXc7(;NXP8NfBCTFW1# z2I}n~Bj51p>J@DBGOH0q z#7n%)Ok4)V**pUhyj{#@@cCYA(}fVm$2*spi!Ap6|GYS9#ZN#?>2eK%DriE|F|02T zHmv+HGZ$rb+51^_%8`-uFu91^K!T0T!E5HW0LGX1p+6Yuw2P4;5qgy`Y5;nVPrHpkv z(xdPU?R}|&=T~SY_^LTYo z2Rb$1*w#$d#Q{$RC9I?}R}-Y_E-J1Q>k23II|aKK000931(mZc7i*W@_(gpGNPic; zVS%TH2ZY3$Vex@i-%^@ld>^Ve;A|L6K5m;-udK_G~=NJ2I;LE1U zd1z&|ga8z4JW{F#p~BH7HG*H;Xmx;M>@dKmbL4NZRk`^1&f|yaOWGFb*D4a5i(r)- z7?X;4ZCoE=a?y^w=8pVC+MvLO)C_%4o- zrmef>^$9v>(=K<`%2fDa(^Oe>K+G=C;^U)>i1-mcVHG_@$NU9m`xBVL=Ytl5|0q@i z*Up330xHAwOtg6b|4M{KNICS@(51fuoRL|Lfl*>(2}$%MvcGb1i@rXQ7Ww&sI`j1o z4LzJ#L*>f^1t8GSpVfU{U_B7bNA0EZEcTvkC;NB5LAv+nfig-~t?@r<0009300{Z$ zC^nw`!WGQEBr4>bz~*hwXq&s9zVg_)aJeEtsKD)NLE9=&^{dRZog|-aWZfL%RL)>( z*AaOA#zN_v5kIZ^bJ(BUj3uxDI}C0~*)TF!2uwyA-vP`+`PSQZ13ElIE?+NUmq29z zMZEkU;2^-J!=1p4 zX)2xQ?5yXg!$i6^bO}v%h|#_}014S!w-$<$Q&_KxL+ilEX5n{o23{R{iarNj15wdca68LGALxndaf&s{{;_zJKz8S0{{bdHDXUQoIXBIMMG}eD|1Fu!pYM8 zcB|?5AiIv}L(|^~R4Wqi_)*73DvqyOB*jVnb(VQ>HbU~$9P)826sLQ-cahTf>Fw`1 zzqIdKi{F9?qOKG2)av^1{fH-wY2w1?FAsv}r5p~%%NshR%T2P~=K9ZDp||^Aj*(58 zrh7*n%;tQM!U)1X&XjOEf7|hUV2!0ew!qJNXRT^REIpS_ec#`6M{gMRZ6trtf9VBh zXs@c&H~;_x000uocm^rS;h@OwDdK9&gfsUQVMOB?_>W+sO&zA_T}5|GX_0k1tJErx zANDWr)$l-7-cSB(J36dGHl{wVtZF(J=pCAdo&;@)TdO3^pD<2L#K1fpW?{JsWx)n9Bpj=qMb^B&680Bat_ybIJlwhhf?#z}t{nE&i;_ z`L0{g&nk6%-?>fYV!T6M_^6-Tk{ijOmq}9-*w-xrY@@E#C|rPDbx2^nT*bA5X(Be} zQhCFeeZ4KYfZ>ZeEQi~y&?j6xk)a-npPYj58z&?<000932~GbbIKGi?1anPVL7=O( z)id2(@NI;2sINX-yd4HQ%!)-@`vsC%WxlGqXqM?pv}+jYAFR-B#(Du(d!ZmVH_9rM zHe>@uly$;8TYVZGR5nroHMRp!CJ%2%Ns=yjx*ypeeH+NYrISoq-P79t)j5Y)h%LN} zu)==isx|VbegGFj5_nGa=vcT9NMU%SqBB^l#D+@Ey!3?}Th!r;NYA*YVKUKvC+F0; z5Cp`7*Q-L@LmokuRXawZ9mdx|F@7g*zf)&P0Z#z zM5`sV1~mDBk!(a#Lr}k~U5|{f+D!}-Y`Rz}cMY+;@thtX_&Y`u?;rHwF+E5ZLMCXP z)HN>oPilay#*2w2pQ8!37sC=<`d3h;{vjj|Y-WLGFVFqYTCD5kR9o69 zKxl|eQ#+-~r~nM3>>0nhxlC_}T+)$zgPFRAi-HY1PoB&Rcq1q$^cDb&FBqzWu6wT+ z6eK9A}E8LV?a5+!MBT#w+I2||lrQfV!F-cWxOUWWy!!r zduhrRZ{;fG_5UXCbMXl8W_EH}idQ4C#2-5xa|;B)-(30Ud^Xe%dc=!NJ|lJNvAU9GgFE_delfRi4^al~J z(i$Wh<-h;{0|71S$4L#`x;_b~dz^hHEiUjJF*)@x>RjP`Mxx{HT9mXK+6aLl`oRs` zgTG*vjl>O_A9MpMA8!5#i!y2j841rQ{+TT~?U78MK(C0zuZcXb|D}v@f4kVbg=3(r z1w^-COLThsIe5)bVT?7$r5*4{iy`@4b1Tm4SYNk(vgY$LB6pFY>?up}`HW zt-`P3SFfCcPV8vdDBb3MCWebkB>oR!lH-CojvVT|6oZgvb*o)uHQyG1_!=9A;DTi!0PKXw({+lPRLR??zLS=2ltG4z z8?dxnTTn0pgWG2?*$vdgS~i%ybEYh}6l{>QK;cIJxLTbKLf%0M`ip;8ZV=EAeBue=YdI9R?1f=dI+b1K;txzp7RmeVl_5f%7oAmle!S zI&5HP-1j1TXD<_+r2pzMhBsHS<1FGTESkF25qd&92RrC6E9^f$!bPKVJiCne?ZUha zbaIr*iT?DH@VY;!oVkmbXty#-Q8MMIH>~hfB1+^RdN}8(qUWyk${dK!k~oLBecr+x z=KAnEFgoE~{LsaB`t)1kqnAr22S6+(N!f61AQ#(6JJ8azSFfTg!< z3)0_%3z&BnL=3Xnu)TJ8D22V4!<2KeCaA%d2jc%JecK5GrYCKaJk3>7f#uTrzh(hUAm4Z60i=T-E}2){2s z0=AfQq-Si_U)0p+uIE{yyDfrnikh*`ZeHi}D>+U>SOA|?R=rYk;`x95po@r2it7^xz zX9wA-7`+)`zW_IEHo`4RoFh{*6p43#+f4%l?Nun=Kn=0AT0o^bk{v9h?+^vxLi6h$nDIv@Q#U!JO5GBER=g3~jztkJjg-Ct9zOhW}^`#>@7_FBvp4CZ;JSi`44>z2ws@$a=1+b5p_*b~fXa1_1ICD8 z+)E`meliA?D8P5uRfwMJ5!97`cUJjIa2^LYoX8`}_(_sQCytIXj(1lzG&f(qrGFM6 zS*fr6?o*?wgehKk4?NERIj6X`{(Yre*H8)0^7nME7){sH37<=n5C8#%)>jfgQ6l!{ zIM7`cCPd!X0q-XW*ux_jeH5=$u+axhA^bH{>qNPFEdfjjeV?b4+O29oJf)%mhv1XS ztaNw7??DUhXlIBR~EmJWgzF5El{-|6{cbcbWU&c2BuM$wO4ejX$E|fY1 zjJH%br+7fI0qP5U$M0hO6JEk<)wVBVHyME+K~S&4peCB+Oa&{T64_j8P@7 zN>=~?0{{Vtd5|Ax%TDW^i+vz0s2M)?(zTBXSnI{J>Ou?PuLeiKEeRf-*Ia}{(ml2@ z!8~}XdT!OK0tyG+f@Bp@Xr!Npyh4)IQu`@*;pe~vF4#52C;NR`++J3>7O8#YsRE;- z07ihJKQNRUk*F^yuswB|j&5XbS646)TCf$Qr zZ9Qh+XxEHM-4SM^W7^%5e^!7us+wV70Q@~gB3_34az=P;18|^Ym|@0>Js#`tsLcOv zG#%!d=Q-FtWS^S=K1y4{sQb9FOFI!__N&?TgImC2UR$ ziqce4^d6?uW>i7#77bnrjPqFh*|X`At2%=F8A^>HV6ePy-mS0>K~*CWhfg zZagmL|A;tJ^&ek`HEjUD>s!SYSq!!#U8tUTXb)iB?~&r?QiyCA?ZP8!TW4>MS0S~& z;kC$Dn9zVL9giE0#a%TXmiVgWWXKNZ!EFfIxBZ1400093EWz?@Ow`fGLhTAEGP@0$ zPwe@W&kYQW@y*k)Y}@x#EN-XiQKsrt{x%o1<7cjsn5qYDgqZlCultS~*VuS#Fy zlGsMTnlDsdZ3Gq0>4lyT>*LKPo4ADraaEP7jlnvuGAtKad_@`kDiHF0=o}$QyD`>V z)Bpej006Zbs#d;9J|*d#iR<-4JX0KDf9N`dWNB4jL6D{8RQ~)ej zd`Q?+H7>LQorR;)90k>wrp7T93D;Fg|hV-%qj@|K0_2i9Og=Xel; z>F>Bg4~BRN(1f8tkxR9x@UVaV>5EWD(=Z!7DG38zsqk2eY5-1$qlYP%+tr`GFthDS z-!vtsbOt45J`A7GY<4cuwgBN_+T#kU%3GJ!a|6L^kHm*RQcf%~${0{ZGcvGvD@5Ct z(Z~n7=9;4-9)cxcZ7O-7sKG)Fxf_OP9Nko%Dk{EF+zg6+WA9GeCEC-)78)+mNPS%U zbCCGFM0x2j)p)6$kJ$JwMYFhnm|Yl)R7G2k?w%Bmc4nbVa2066>hBMn3sVekA^T3N zR)U}r6=pK(P~d_&d(w}YR&f4VlNr$o2=m-!uYDn6S&xVWO6)KLKg@h2WbN=xVcDva z_p9{4W8;3*e)I#A7B27>$(`qxR%SA3u-${wJUv8SJb5zC*7t)g&I7qupDqbni}{f!UFT0bAbq7z=;?iZtOA-jW&E%M8w9uYBh=lb#NjZ_QjcB&7*aLSaf3! z!sTn#`;O=1G18tW&`tCAP_}&w^3+Gk+bs$6U^Iij^9N}Q5T{Ru0HFF?84z^Q5TSu! zeTkgZ`Pmw)*OcYBUt*pj3)TzT?LCMuOp7t0KAGW9By_#_nz<;Tz1UY~G%9bun;u6Z zb@Xx+^*AsOn@oBYV9GDZh4hgoEztcuH-TbisA#A!1 zCjp{>f?Ym%?8w-+=~80w^6?hXC*Y)M@k8^gr%t*SdGrm@us(ybr^ zqV`Qdxom%*qUvX}9WN*|qJ?}Ap1o^=zFEcRrnH-{3GV3^W1w`#Px42BPiEmH1$w9j zuWRcs(!0_!mV)^WqaiR9P53{(L3Lu;qpCXp5pK1^~nI_wHiozYXY$V7!Z$b zC35OE>)mds+!j8y{6)7hzTNTq?yI-yOFGi21K@GaAVkhUtEiicY6^Ui;2xtk`0MTa z?5jc}J0Q_nxESYfQwBaa0r?Pk52}X@oRt1uN@|M;2@aQ)@)_8_{)R8*KW&@hGD|m> zj+vS}xExPys`^8CK8ofId`o%J^4$4;HegqQdThOnqx0zT@!{h{Tbm z>M$A5#~Wgepy9;=&EtIUT7@W!K;q>|HS5GF5`;c=l6X<}GSZ#(w}^wz8FD{RF^D~1 z&?pp5mmkLl?;_oap-wV(oOa-%ii0_0gAl@!N_lAfQV9r*5N9qg&r^&Mr_EU*@9a`Y zK8(AZ`|s=;>`GrF{TFvbd>`X&hX1|%o~iuh^tB%#4|ko)Mz!{3?OTB`6hm%03{qH5 z6Pc?7?33~#;*!G>uS4#Iq%w^)C)~h~_h$DS@tr6PVtC$VeJkPcB?^mr0FhIgy4mJy zA4P~Nok=Q}J<^82W_l%;QNgILSWRRS*6NoRh5_S|D$>JjM`dBTRSAnn5rI0smAFMv zLnPVtoQ*umzfQ2#J%J6eUcArtb%KYS0?LnTfsJXjf->eDe6#w@fSl&7Hq#54HK93_ z-uA1W8Szu$fKXi5#@EBwm9MEdO`K--sDH9QVAM2p{?GfXRT5bhR=POd9rii4kYohL zslG&<#wFqqAb4VHFw`qrR$XrqK4lW_w4J0hmB^jl5FR2LPrVE|_s%a;ZxZ(+5lp5H zetQtz0Q@vz%@Sa7>?2-ww)xAOMZ?=e1@O~xxNaUw;(y?GM4M%V+2UZ;Q3h;dV=mE#tGDyl76iC}wmA(1E@OV}JTuZ6nea zOlvI6JBHi9=CS_D`~yMLvTK#~=DkZw34A$!3xo{1clwoiuEsC5SS@#Ppnm!r6+JT0 zpje#NY+TwQ=aY#b z1Q2QFr%(U@n|CWlSO5U0E%?Ktsyu@L`Z4FY1EnRS*Q3lAvaH&;0C?w^=U#hZD)}{O zrH7A%b)8~C-?R$F9ol#S_KGatD6&Qu5Ytv?dv>6{Mhzmt_j`2kb|=GIY#JfvzdYZ$ z{9lML32&VX<`#)WFu~#4vQeY$B;gVcVn$%Y`5c_TxZveh07OXuKS=Sk-DT{0v^InF z(G=;{JgM9`X9;k(<~Mc7dxFU7hubhLAOFmdwEQ6q0@D!q<)HcBd zlG~8DVdxnGe>bH$vQCj8xULW9`1xB1KvQmWeKYCqFo*msRbOzN=uXp^t^-X7-9;!8 z#+Bx}?K}GK^d+nI7?PsY4qk)|4Jeb;t!lfsG&=AdOwHoig$K4nfhs9zsjfr zTR=8wGEuJc;e?=6G7}d7r;$HEKzJepdE0trzpjf>-F6e~+mdv$$oPD{iEvi6Mh32L zrbxO+R|5W3r!ijYsQjueK{~Tcs=9{ClcdeyFe)VFn7~ZyI5`*TDA4f3A`s}>jF5I} z547m`2qB3KB4R?;F9$Zxt=GSBq)%;8D~#&WMAlIN00A}uo)|8V|5bwk00RITrc3|< zt-JsLK<@wtp`Vwh1Th__W15J)IHNFbsBGZ$^ z=J{dnr%*J*iVxtou@S=|&#cGTKUrii?keTIXdbmkvjxgZlxk>Y6N%e@;pp)w@2cCIK@hqDL$qMmi+;9f{oV&&3LoA7T^ltFhBs#kgS}K#DY$ABvRmux&QzG`vIO9PLKapg8%>n01N&f zs-ge@0{{R600I57!cZLlg>uy4K&NxK1lqw8zyRYVzz^yLTL1t903=YilW#x(00RIQ z5hox6v&0K!d0K^PiZq&Zev4(V&`>sBDv~n*fx|?w5L6@o!vh>QCt7k`=Q{TopT4k= zLTmf5Z5%*`iw@)7))CQn>DEUyK;is$8ip{yc_SUWC}Js+p09?mX$VM;`Wf#$N0559!0002j0iGC*PyYY_0{{R600bsvfB*mk z000937aL`&Wq<$*y1LyePJC1^3R{~Z$N&L_Bme*d001>;1z;E<8=Rs`!OBDcGSfM5 z&{+g_=OnQNDhTM4>FtR8u%8^1_0QCiK@QF0s-OXdg>#3!!5*){J3?;|dH2Uv<3JoA z`d0F+NjS%inj))l=(Vyw1HiDVIjAvw7{p+sMx{3f9N)4403A#6vj6}-w3}4a?Y|BH z0A!>jFN* zusS&5yE@r`eye~zwHOZ0r$rItIr~T?U4j#;n|`PP=F0dYY{P(JA<6_&*%xN|>bQPq zcTTQZa6D{*1K7__sOIb(BCG%aE~~5rBmg8$?#mx?#{)CSq# z(K;Km2l4c?9(5#yevMg@zZ{lKdu039{$Xoo4)6}ATtnZ?PS>wghjPK%1J~;}ARlp7 zu=LdyC2L+ED?Yx!~*pA@xZ`ZDo z>I5WW=rYH;q{&>WoV`>g;~0H$A$Ztr*xN4ogj&J|7}Mzb{QP& z{UJ<&2L1Am$`lEN*FrC!ehL8`qKH<@w<8X+K`-wqip^dSpWNCsX$H7{%`#cj)@N5?g9^05({N4Tfy22|Q&dpxc?9TZ@r^dQ1my zI?aE&`2^(wL;dgCY%NHkA^^l8>%US9x?O_|iFLO`H(bU$#XAwX<(e5p-_R7Ms8FTE zoW8$PgI31p(e72lC9X0qC~Yyfsv~6%YHLg*m=QyhI>B7@GJEw>UBNd4}nI=|l4YeI|2)T|aN zH@g?dnvGi*6C$7>iPwTk83_|`(o1hiz*nys*o`DKJQ{3!Y8tEFQjTnl=A-*f8> zcL~I`pPybchHnZkKc2LVT#3(MzA~AWu>pYxAFCHlLatX!NBel(`h93%@`C-cb~OfP z6h#2%*>6vEc#^KWA%-sBnCp4-C@m4g8o-bTmrk(P&^3}c%hT@y#zv#^SRk}9Pm z@J$Ix0W7($VDHff8YK`t_3AJc=d zF$|gg+8)U-nR@Sbi=DLZh?2mOOD)w+WG4PfF`otu??&E1z>@{WHWCuw`*!_q^nw(| zI3D*x{*XJ&))>h9*WxBrb8ZDyQMbW(EnfIRP2Z_q3Hbxb*=r=T)$O;+g?E%vJ9k2W zIm9OHHqV#h)vuXM7q;_0-ty``$@v5RXpeTya=aiG)DU~ZE;>F`CMjA~>H$9*^2jj3 zw^N?^6jaLrn=U~3OtUL5x?$A|dBSVJRD}{8&Y1Z01#0nA5&5v zg=Ots7!sJV?v8+)HaMT*4x1&6Vk*;#FGSSA?3^NWeULx`Qjom+gA$gW(d?C%9g@6B zL9mR8Wv6pZ5+s8-EDrkxPBu}(+jORqo-a-Y0BQnBjt>Rso}G|W;DprD(7n}zQp+Q@^LpIE zJsJZMseki|67dJbM|{-Pb^Z>le1A_Gk}pn&lp%!|ERrZ8GY^-`(mnsfeG!_EC|PK3 z;Zd$nM6M4YS9yr<_G;@)+F?^>fob9+iv>McQZ;sPT#8ghWr#`-G3Sz?`j4CwyTnz| zK20^*@h~iGTb0hpb>^2iXY&bw>#uv@xBeHBSE^**L+aboJ_@U$wYz#MzG|?WkZ~1C zboB_f4R6bgGTb|%X?!ayZfS8!e@TJRxQzq4GvmdBrwNLV%qQ4dJq+E5$4lOuK!GFC z3SMF{tE!^nn3kr$L1m)OVDl6qGF{amS%>E)U*`k$K{6)92-x^(^n&%R?rc0>{BQ3j zbwRD%p)jRpZrA-kBs1Vq0o4-xl6?4IAK~paKVI^H7tC$AhxmkLCQnz$Ykr`FSp@JU zx*$h*sPjQhkBVgPxIN_W-|dkq-M}#}{3_c~U#?LglPU^7D99w9YFb)75q#Tso?_E) zDmG?HjJSe6NLCl(Y3Ki(cXJz8FapZ&D3-COTp5~px!zI5Z9>y>wq8Qa_G>cH&P)~1CXQ{ZUGZEc^8NOd$>3PS zOc%8;VJrMaU1gF{mUA0x4E-FfWP4}R^gt|oBH(%Um>V%I$7F{cQ(S}hs04Neh3vNv zz2olE7N3HJ;Lr1@s;K^K2VO91*{t+d*A%>}%HI$UVvCIY{`aN}ALJgxWVmnRY%81DU=lI?6{Oxg{OM z0`oPWbdnf%b>zg?NuqD|#?LfDKvD_y0gU^|ADbX!iR&L+SMAXey0&AehOdW7&Dh%S zR+wHnD(>^h9uYiL<@^cU_p$sAx*`!t~dd!N;W=#uy7^|SzzG<4gJfj$d^Ov2}4aCl5mg2qv zf1V!wobiFR)_%6kU=kN&`fwXtCeskFS&@UQ(`_O8Cmrq+y$;)XW`Q4+9pdOlS2bt# z`p|bhz*tQLk&q>FXnsxG+o1YGO}=6yqjtZh0useba!vrg8n%IBi$Tfp z8`;Ifq$yCg;gqp-%&FYsc{BtC0b|s1t3E?u=(Zb{T}x{}--DKYk{I>G=ge^Zg5;c0Zsq| zb>rHn1R7(ET*8Akg4@CX+ut*#B1t{N_4{t%WR2s}X9^jwgg+mV8UTQq1&W%3^0CQm zBQiMbIfRv_QB5)rs9N-Bli_SSe+^p#HdtvUu&r40`Aze}CNr{o3P-@d1jmXfmV;pX z{DF~;`jZ4!W-#NC347t00!L}oxE~V=#kJX{>ZwMcjqHOn4mBBZW6>R)wI(!53OIyc z2HD8AYS@6t;AdD?;M9T^!Of*O*~cgpU^2Kn2qCj#sD0aiJXML2D!rB*>!BHaT1`%# z0;x_(v4*l$f_WUaLG^d(yr#5cbpsFQ;}HyK z%>E-)p|u>X_%zBLY`VIoA*xSDbspJcpnSk|g}Y$*iQ2vGzn1%2v_|CXp@AQ{dYb6(q-h5@NKD2uWu^#1PoV{0vGgMtAr?4=B6)@yQ3f*bLHOA2oVmw zwD@H)X{PlTYQPn|(&5}og>M8x(oth@#Ie85FiOsk>@xhHFILGoN!-V%v!ZFhlE+w3WYu-|^E z&z04ltd1#>#M=TBO?Uv0tbZ#OGNhBty#CSjo9t3qruwng83BiGzKcWTnKfxtlS&k@ zC!3f-%#A}zB)W8RTYY!prK4-S4THBE!R-A;9P?~F?PJfBjzr4=X28XZ0PG_e5=10^ z9oH}1?;vrd56fzSfHghe`rCLzkoIAR4LUetF$NYx)eq3zYxz0E-l}kAFviqDt?gU9}B-+h1w z*gWbTsu6P4zHjY+aDSyej-R&Ax0txiOX)pZ@f9I5gg-*ikg@UVjPf|ds$&Q=C z9IcT?{`u@`dO<|-eadGY-F7m2y<}fFEw}|z_c&_OB<$W|?BYsr4xmsCu^RLUxK&oQ z;$Dflb{%j>IjuJfK=EGqi7k{AesnH4d}=bu6SQ3sO3%FHPFppRv$!Uornzrg+p1SIR!F9Yk`SfrL7CB>gnSy_3h5xr6) z6yD*aV#3IDgYEof2>9G=tPzy&d$|TrP|0GZCDEjcVZmjafvc}YK~?DXR7PPbRy+Yh zM6Ox5hQE1Vu)EL7CYymdH__b=4OBGx7aCc?&K61kuJHw_H1Pyi}ll4IKfIxBcM=XqBuI zT52`~dN=;pZ$B{+4JGo?**|6ZK&Epg#y|HTgmB7Gfz2uahecDf3~~8)%zFb*o?0O@ zN@IWph7I0t#q2rrqI>fQ2gUft6a#P3ucF$LX@6Zh1L5ndP{b;)A0FYcc`mJb`>0~i z)>Kn7P*AJ&B$C#k`T|Hry%t%ve3_%93f(xp#Z2Ekf7aJzfn;#kbfHN+9> zZfnAdfXRm5M3^wV9DLv|M>z=-dlnLpi2MOfQoeuEq>j6cfYA?n+Ws)z`bL>7>*KBc zN3iFCg?@*5A+{xx$4lhItqBZe?Jo5Vpb&+aiH?rwWP37m3jGrOKOoP6OEzz$lPZT< z?jMk;WiRz_5gUy$F=u%Ey z;-T9(E;)WzzZHO4O?i?3eu7jc#qm!sBAUe9=V+mo^G_aUc3NYWd?k&li+$q}R1Xka zS{U~ivgClRr@{EhlWdFr-5QpVwFeGk^Uewcy-6`kIUWLC{KCOVg?7E084WD-Ve!)F zKq&#T24@nWX77=vYI~ABgACQr2$xexK6|&o+@uV{WofW}fT0@yeC60u(1_)?%UkzQ z|GLd|fVbe2P?8nv8FxftueHb5x%n3hRpSaG+J*c>)3zb%Vv%L^iBU@OlH(+DKtPFL zb-~o;+$6_kVyKPXiPPsWMHW@7n4(>3V5$Thf~6rwm`VD$+mDGH*OY3AANjZ_rndMF zL+i9|TQ5H|w9}ZB83hnQh_qHZC(>Xnj=s`&W&$M6QzzOeG()A>7bbWNmJfFIXZ4gy z(T}a?K?_pYB=-Hg;az|v1*9G8-3!WsaF zzRVmP1gk+-6Iu3_jB2nFOnnS<6iK9H%SDCYMYf*+wsQ)1%ux;q=7>WA<@Io&dqawP zGY!TyC^0JHR&xpq3_>D_>+7w(@TLJ&fh>Y{gcfr^E*hJ`e%2mDC4dKYWW(EX*4d-s z0}XaDDM>!1b{4SHX8(wxhNjmC<48kbU^@m&v$4R6hdCAWnn@CD94umLjmJ))mphWm zF2L!rD)=@d!=&jY;K&*|WoWGAZSMawK?5-&yk=^9uH3kl$a zU2oAg24jfbfN;znd2_~kW&VoZ+1C<^@;NtEAP3Io^X!C8-DC9N8zHHd zkP4jFp2o$b|K-~4c92sdaJ!mPOu+=f1&I7UB++~Tx!m;p#sSi-gb9W5ugb?;-7{Ngg*}Y(C~th+`wKm94sL|Wv+MtGc%kh?Y>*046HZV_ zSc)L5C;RrQ+>AAjsJ4N(PoHmp2fsqo99)T#PeS`eyto|Rod}o3gSgwg#i^Br%OD|x z30Bk)H7m0J>q3Z$(Cl=>albAH`x#}dImUrkBDwdKtrBMlEkYt|lg4*DAoc);h${9r z29*`j|EWk(%C2bcdWP-kKlVpDIaiN237~-%<&H>Y*f{+En1shSCfZbXSQZK&;_U4S zL$c=f_YL=|`kbh5h+G)OTUEkd$$!31^85FX`A;}9mC(i_!C~iA`Mv!HU;aL8S}e{} zQfYYv#L5oGgOfZ!p6oG^@>w|qj`1b`r1I>vo0ip4amn`Pm(W0^U3P;6pBr~n(p-#6 z4HC1*;(Hcq<4U`xC+-bGOoiWacn$mahSYJEak2pS>3G{gMK z#P1K5^>65BNWf_z+IGq6@Zug-Im;ou2~f)gz~HoJpBD{}$I*n{V6J%95VnI zCkVA3uebtUS5&3DlQgWirdl0`!ZYmSizD-kWx?6CY%$vzzcr5688o`md zc0SGpG`imc=lQkbyK&V{!rfQ z>5C$O(Q1{$=S_x0y=i%Cf2YIs;2V-az}rvZYHIl3b*~dLail@&y%AE^HqYsGnkowD z*yVfhGTt5?vZQXYp&H6M+IymZX#-ICbz#6~^<9CY25 z0KI^D0*q&ewI8GvCFowhx(v1h;R6rq$E87UL0w;vKKJujX z##_?O>n1&xkZ}KZ(}vjr7ync&agM7 zj#8>yd|qdnP)6*g9Pu$|CFbn{NTIj6(j@6*?{xq3BItenu{vywnf3$+TCmNo$B7`z zg<6$u7)}9c$l7HoF;RRT9fhC-w~?q3KcVj*S~Fly>V{Y#bml)EZ5=C|;_L*E)K~Q4 zLLGl2Hd3|r^c%W9nT|~Ze2X(Sq}q&G3fJH}G--=wyIDY|OLl<0o^B$U3!Qo$ zbXruOmcoYFDh3QkMG?RvHdf`Ms#=iSSo>WGaL$m(z-(WHQ>+;B4+5^&UlPS$_xGX( z{@^A0>JPsL{P)P`zKY~s3=|$lIH$~@^O&ZdGZT_^G*7Hm+Z-kce7!#bjXJs< zc5?K|1tc?R+nxBfv|-+9dSL(Xmj+^dCO@ZS!*6Q-e2p>~(=}o|iZ{|-{MUNa&>PN z#o2|0dRoZrg~KW9CM{`p2}H9HP5B*cBNM+m0HQMat702jO0bQ@9QaWkURLQ|_hNCv z%Z0O?`KIOMP>XQDA5IK*ZwP2*o_+ zklg_K`vq?V`!5Zd^W{%0xn6^w`ubo2#YgBx5 zB~@9zE6crEUyq6`prYv>uHh4inkjesxcd@DZ=38^6%SgOnU2PS2||WKR+@*<|GNtp zq60G$7Th%CA97@nAc!CoDWJFUaqDPQtt_*Kvo1j+x0I;BG*r3#Wd{1W1i!s@sNV2RYSc7o*2%Sa zI7`as8Dz*p5p396MH~q`^`+d7m`W-v&&ttR0E8-A)hJeU#GPDeDb{j-up=NOV4KtW zByyV?Q1M?$dUG~@*Fd|$+Q1rFgNif$j`FQW0iv;33yOwIoTbv&!Dw=sHAT|12aZ=U z2K0M7sBPF3sCtoX5;=)1cL1}sxrrt{&Fj-%OeFyJ5ZB>Ho|%gVM!?LAPP3qYRphn! zBgu`AI%vBf@ct=;lEfIr>X=?~ z+CF+tW7O{83PR-5T>`dI=Zg5?4+fqx+qq1>7`@X>wI zg~v}2=_m#62D3Mz8PiUzfRsXIB>-MlrC8Aa0zIsWZbfpp3+H7-LOXBqOVeQ2A)OvE zd8EK;EKH+Ce}WjIu1%*&5RVp^J8nh36Wj#4dAh-|(9T<7aE%HW5n6b^;s}-6KV--s zGTbV)`NE|_$XX#|J}|4j8x!Wd(IZD$J}a4Pe|*YiF*GE~N^ zT~;9fsm$q8zIq&&Dwow`Bo@W^f1{zpk9l#M~B6 zC>0gI9FwzstJS~Fg9!@CKk(>+{}#dHmD8ULWde{<%sqUXlsJM7{j|JsJ6g#C#tE?- za%k2vGl>?e2FY$2ubpn&!rs~ML0gA`X*V!;DX<|@-X-tm-v)?_bg#3_sG!yUerzM4 zNn-g0Vn^Bu?eOVa$iGMR5Vza$oexj@)Rx)r?b7+yjiSlD5TLXJ0eXj2LSmtNHjTcw zq20aSi)B8k#!Za(9_$1j$(f0E*9+#~C%e0N;Bb6r9qTQQJ82#XW$+6YwEmHL48taMIo zAjZe+vWi^_Xxbl&U)1=(z~=MHfy)ilN5i>v7-ooVmqYQvHatrm&w+OExD`Wu6$l#}NdOl4md-7n}gX^eD)JGTSA z^aWe1Jo6@v)%w?G8*zDUdv;{Bk{{t^2Q0J1HqD$fP2g81MWrOr!&e!-p=Apz)1a(7 zF?6w`mj))E7uQ0*A^52Iz7hoBf+Xw-wfaWaxJMNd7*mf_W~a5P5@dllV>M*|T6$9? z%G=X%wIYg~VaZejOjh*6|voij=giFc`z?R%!RuBQ>VdzgQ!Wc$IrBf#tw$EsD=9oXpPFL_u&u zAq4MQ0)G>kj*jBA2c9&p?T!uOq!yxG8~;Dtmw(w-=;WiVbLISaUmsXqvejjSfjo#H zA3}z5x^GT1TVdics}f-7)+>X`>6hkc>x_Yps5CM0ct(&&Z4sbdZPZVyN06K|wyJ?H zO)`kS)Sl$G2Zn(irI<_DeUqzJ3LCeEaGIs9&HeX$g9J=kvsYA9iWAC5Pr&Fl0c%F( zm!0knc*ffdjzq^2#xScJPchoPV9-bbIwU78r?PO%uWkad8`N^k)0+oYIDfGKJeYHG3 zzcJk|jbC#-4N&Gl^kjY9S!^7xaGD{CSF7Fk|w3=yM zIjFE}!HWX0$krlB{`+<7!S^4N-;ARug|J%dRGA%qRFr#xX3}Pvze2J5{uxd?I_FL_ zw6;SlBAmQ629fu=Z(uLF36}7~p+Zg^fonRJi99!p{SPZ#+2J7BaC8$6bkEQRpaqzz zm((|-!CQ=XXh;v-ss`LT;9oc&NnPG#7i@Lrt`S;&FlWP>ukzpwvoY9zONJ6M!3yg9 z$0#lrX|yCEfz~NAySbGy(Th5;3#$D1(f{Hg54{EA=152p792OM@TjB2a6v z9E%BU29I+UN`%V)-ywI`SWyVu0>~McDckW|*Oj?|;p-F;KNBM`+2bZu%N8XJeFqbr zQ)!nQ(6b`BVJ=J)x(7;>WLTI~38jSXW0G@ZU9Q8ydX3T{Bl%*)I}C^(8ndT~_a@j{ z5Li+f70)+NyWyJ=2Ym#RDT$3!0E}ve8w{AAF}h0nfy;L=pXTQ0DjP*=a_c(~G<*=n zVG{mM)KMptpB5qeTrA$@VKFgd*Yya^jQgo;L#LiS7q7!c%7Wk!HM>N~U=n)}wV;(| zp}nHWM(!<%*!(X4>ajZy)Frx0)RQ2Y&eI{hhDW5uoW*pCb{40FM8k#fMoVg&n{VrE zpl7CXL^6E%o=@$(slh7REQR4tijkrriscM>eh_z`!wM4EKn9dbmOm`Y0Fo0Eg4y3jF5-MX;^ z-WUB_fxJ^vWK$GMtryG(-ERI1lL#7+-Z6m)nRjJ z22njPq+>i*%1HzF^w9$$Y&CdtxdNUH^zu21aUd7{dIu#6Af7M>ImTiF(33y0Iv})0 z*Xjpo%x>$m|4O86>r$HQZ^iRc~fT>z1A)eANhf z`c4&Y7d4XSUr8PHf<=8;ymK@w`n($^ReV+VsT5{^GCac*08o2R%w=&@O}&ilfUMB; z&rwc8E*Y+Jqb*}>TsZHEDPEzK4z?((fIGwtb{5c9lGzr4Ai@oJjVd<1XW_OEJrdRf z{ZeXFbu_REsXx=@>0Nxl=1RCw=75$;(TnKDM_B6FDU97$XOULVthEt9+U5l79Oq|#HbNeqU)ProeJFim_@v5cH z#1}q!E*8D+Wqyp`i(tH@y2+KbmZJP6w>_E!M%AbEWofV#D}de(r(&4CYJTy>Mr$(B zl)K1BWBHes_W*F94X@@0nEO!B2E?ff25@-+e868)dEcKld^|<3Ozb=aIcE!d5p{J-RM zRh19C=0^oSI)?cAr>d~Eqmf3XGA5J;i8QS^yt!n*v5+-(3+}M|JJZ3#Pt(JAOR8C8 zX}uP2=|sW9`t_o=<|1k3=U zah4&zZQoeL?0>E?w}_u9r17{;uv&eVQ|@KORpIxW4tHAx*_FDH*uUF9BL>B++D-%q z+>oZeC2E=3XerkTG-Foi%9^s?Fzzmz>a~P_`G5*UE%Da^ts{H2S$y6&zD~g5ul}AN z88Qt+KC04480fI$sEvM)e>yVzQ7;no7s<`PP6`q;l97NM2i%miAo+ zCe6pw>l>GtaBTtrF!Ej6)zaMnrxX zDOxOs86N4?sEkkM^5ZH%Bw4d+5fFWW9*|I&x~v=(Eol z73WGQg9YT0$4E~y3?FLlb5`F&r=fMhemH0{-78;5ni{AGDhP_;sp4S2N_(S?6pp(6 zAfFKeL8~=WW=FF9=_z|}S0bt0I>YpIt$-)7=WBK2AD9HySO`N-+R@x&hZBVV$8@B&L6_SuK?-B*`uiJn9 zt^NqXFbWb%EifnC4_};l74#4ha-jReJ3!^1^IvP?FC^Oh(e06i4e*hZ%`e2a(+$M{`$lI8_su3HqsU z0y;LkCDW8Uvni76#2jH^UWr-E+b?NKPAN!W+sfR0q?Z=b1X!M^amrAcG|Fw|>3b*T z89k>wBQ9@p%3?=3mm+oQXT;pZpmGBYelE)5Nx?=n0Znvvg>eu%wGn2p*a1|o$|$#IH*JTi*DGsP8o>DZxBbp>|_m{L+hBf zEkC?mirC9zvx03Z1*D2Kpv7}>Z!t<(-#B`!&oOigIQs|vXS>{+7X{n=iHCqVfuLSp zz&Z%!0qRNw^_CJHLxmpI6B1tmL%J&gyxc^iMd4_A^k6RP zj;br3TkgM9A$lj6({A&5(g~w)8H#%d9F|bUa3CVF;RJ-q<*1oQfnt_yu?=IBXj_~_ zE=8K(659srY-71SJZcn35?JX-1U$fbI-X-F+UHNVB+&3#t7D_5MJRPraBzDoc9uz0 z3(=nOrPl+7hLBT76ET1m7V5S-R`$@J!aI!*Z2{t%+fIef(dMA~OmdJzYZ8FQQSJ%+!=C0Uj`Dy- zzBYZ6endOUtS8>lee}3|!J}6roIJx)IkE?;Df2BXR9yW9R2)sWHVpR+?(Po3-6fC=?gaPXE(vZy2A4o^cXxM!3=*6G0fIXr zxRapCH~0NK=e+0t*Q!O&bOWpQwX14N*S^ZR!#oxg)>{O^xA9x?lW0q#gK~~sY4X4R z;@rP#z%!V*|4o^c6TCMVe>0NHWijLW`uhhK!3=?}jQ&ukpBSSq51Yu*TDftuc4)`a zEsrC_dr>8fUv5q~`M>&!ju_x7{asAkQSh&{&OuW`e=x(bpS~u^RJRj7mnYrPcKn5Y zBZFU*zVi0H$-Y`doKZJURp;$lpT>Q-W?GcY8^lcdF&ehF0#*VhKUu^@@~BTA8llyUcBBhOy_| zyM>oXBPUaOKL^?daB2ohFP)KM>=6q->tN7Ep%njUzaq};-qq06JI3NZfO8-kv08tr zJzvE!9ea>@ZDrR*QThD|OAPD*Qr{RAm%DdkWc^^idqE8gvhikcoe?wrdtjvZjJ%;< zA-`oRr(WHQ(*7+bDs0*MnP*L~sR2R~8ykvHVX*au|CRP@GG(Kd+l5DhPs_Rih-OE` z5>fe1J-sn{wSqSDEXxTz*^|W$1xal8bc?k?rI<9R0e$WI(F60Xf+EQzMuc1c=VQ~e12 zOve*FGp^2|8fvWeTKe50LhBYnln9=8d_#3vTQ)rbG8@Vg)@v>EyR&0#^#;QhOow^u zzMj52@B3<(&1DT{UVJL4BPXv-#i5`-D4El5nck_G~Z$1&pNj|iupTdpMzms58f*!|?+ zt$c>p*O~Z+?#gf3+A+Vc4VOL*4vC%uw=T`=;j50kmMYqFWe}iFXp8<*{OFz0hV2wE zW6>TPnK=1C_Q|}-QclN-hrTeLnU?I^Fu10tXfuf}Xq)lrJ@vIPx!HSKB-Khb5g*wS z?DWMbKfPeLdsiG={M4FnP`yw_%ukH!XYD3vL9~BxbV_}h4<3;;7buB`Y+=>Y`R^~~ z-+obd=Ux;3_HDbW?yh+lHpQK{ija3)v2I!M4DzRKiI2S)7zAa2W;)4J-&IPx{jbYA8e!s}s2hT9afL ztzqSpXpBd1P~-8sOwhNBt;DO^yd0RbOxHijUpLGL^JI)A2nv6c$>uUFPyJHCGxDZ2 z7y!V5l6iEhL-3+IJXM}R7BUNF!N?1yrL3= zoxNbGmm^w1^KF0TY5>hlgkKXhuJ&lwl?S4R$rN={W9&X`9eOPE`GzAL{ezJv|05-^sUmH$+Qb)f!D%H zOJl3F=U=22ML@o@ms5@`=hqA!dEN&jc&c z4rYFniaDx`A!NlSBuZx3qt7c^Cq~qfR-!sPNBmVupGR?L=f+;BZ|I*7+vJt|xzhbI zQpIc~VTRT#ACG|1A67pNt71%p@&K3+mfK171vmz; z6G&;nK09W^V(2o8N&q$sa9BL<71{p$?WNG0yE&_!rt$JmsHuLj*s&0zhx_eis#UI2 z_dCh>DdlGTk_4*Y>pBAmQ(w#BLqSfDD6GAD$1)y77b&m2NB(HMN%XXEN?Us#%90Ef z0=^Hv+CLaHL^1iV?x}Q0I*_8^TY*=ZFa%9x`ON3vE@ImR0$abNVxhZSk6R#fKSJ@d zX|x@^8=@~>JQq|SaQU5}oLaQ6>i7zoe80Zwb@K<%41CX?aA6stxt)&wR1w38u`@A< zl(yh&{ABnjsE1?1`M;RJVSzV!#(&lC((&(wE)x3B6_f_x5H~9w0T^f%BG_bdD3oM` z+zICMb`c3m*cUQONg)v@kD{jT$L%i^EC9p?uc|^VQWIk6el+20$cB%ZV5T~~gafct zz6C^JG2mj&*xU`Go8gi*J-P}-ib4QAM_PDcZ}8f;MHPzW!mrd&Kp*i~0dP^g1KbP~ zD=baMhxi@$65wjAgLl~}`Jbgz$z5Bnjc?NtRiFQGt&GAnXW2K? zREnSY(pG;!;Z)>iR#_faXaKm+Y2mA*QcnR1kMBYJ3+H4S^&;3N9t9uzBQ+Vi@D3YF z!guQ73?7@+c|rc+%V7`10HUqZL@x*u|P1rE$}e zS2$EY_&m7EiGFxUJRPW_WV{%QOeD z{QFDIUXk)mnKqj&|6>jcA=70xSJhV^d+n9 z-nwWrz-)vegw@k9BO@tb)OyEgcxI@*bKp#fJJT;4$op9TdHu%B!YKgtyj@3>3CbA! zK~7Q}p~{pm#)qYRzrlBgk?Q*^V(2DHVbcyTv2j>ahi92-+lGU}RqUU35&aDlT5c-{ zR$?YPO-`j&`nnqK#Xi;hnN4Ej&5RNmeb*B?h2MwpBE)o2sSw0b-8&jwO*vz($-yDiySl%B9*#+$`snC%w514s-I?Ev^czJ> zExzIZHCq>_k1{wBQ;eHIbc*J^Ez?~%a3!yfW2L5V)K#J_8uycl=_Crve!IU19mcRY zdM>?F%jSU1JJgOuMg^^_9&+4Djdf5ZG=6FSo3UJsHvx5UW?(me_6sdl;+o!XCxKJm z>*#{0We#BA6O5772drCGS(>cTX8x2xT&6b4C zC@!HD(qgPev+DKJ#wQae04pBaDRNyW0L;&dNrJISyfkW~%;aA`98UUR4r+=lpYr-~tsbc96MBjVTE|y=)kb@G*7K|V45mrs z5d$uFdOpV6qKXX$Lw;! z*x}h;)#>bIrFw^yzMKnurbJv;QI@Kb4=u_lY!8zL*NC!Dbcxc`?o^615_9>sVvCc(Xs3bx z1_HvSCi`A}Qs;mvqgD&IE;<syZ1^y$eVXR9o|v5XS(X|(!D>~6Na{y(NtEIlla&rmmMKg`m?QBjl6GRxH{pd zjF#oQJJ#(#XuQJ*u-tvm_Yi9R3DkV&Tut^e!%aFI@jjOeUHmkd;x&GroT&UAmH*P( z1baR1h{xzwW^a~#@9_?5vX?iv#$~R&_gZJWSD4EFxUPKsKAm;EqN2T9{O#PpHWd;q zUob|XcK$Sn&r4F+2JBv3-G7pl>OV-LrcQwSmYZXJz^MvLiXv7kN z5-iU3(0L70WkbAc4=$s~XOz-uOfig2dj*|fe@%zKa85vsoV?p;@)9vA*?*ok1u$;? zF4WGTd8fYui3P~3P%mRzwC)EleP1?>QY=|~|FZJh@{PkhdI*;ww;Kp0sZ7Vs>6^$` zZKZP%tvk5gf_>Vll}G;XsNXw13`|6|fp-{;E-1(n)x}-TzVAqxB4xfd86b0LD7-$@ zZ52T1E8G_PK&NAn)`dMSW;8#Nu|l?hP#(+!b$HNRsG~65k-J}{n>?4dQZ>&k){U|r z&1}fV4;mBe)JIsdkUDm%Jqw8&=vyn#iw>(Ccpa*^lKG&=P1UhQ#p*<-U6lzvAjMKJ6BoRv^Kwd7_ZM z@cW24{o~%lJnvd9%=0$RscTy#xJ)>#zkar*pXD5zS2kMx@9*6o){cYtD(` z^yXMBqiSYg>$>H=7xWle$QbWc3$v-m& z2a5`Z9nq`i8?W*chtK~xAFQ|^xq(O^XD=~<&m`JS(XEZg&)=YC{)?NerMj2twc%Fx z(!2_@1isSZcM|AReb3cee(t-xJIo8E@80+ljm|}fg&cE(tM#YS<|SvV4XEX#Pf=T5 zUFHo+(WsYpgDj!lYJap@>FILCW*ATGxLhd=gNck@YqRCefV9aI8L8JPtvE%#+gcW< z47<^`rpgEXIO`D%T@`WOvK+Lb=E6;@EKXefD`Ci_^j+r7)eryTT=^?7GDE~5F1=A) zGNxkxGm{m1A~J;~)p8UPIxHrF9ed{8U;59xo^*1>u;5*I5FR9%$EVWx`XBce3=7|G z?G9?LpoUOQz53dS`%UEF%{BN=9|ZX%?M6$nKapyUQsu_6Jd`g%_H|(0L)cMZa^B=^ zSu_+7_EHJ1(@nckM3MCo)z7U@{Jg~?**yazNW-CJcUP42AjU9o^UjUWw$l|>M@b_+ z2`teRtyJE}CTwEzA}DP{QLZ88*(oZv;*WQ(2(RaCKMaZ78=i;qgd2O+p{X1?Y+kM9 zMQQ(fz#@pti&=kDH*T&om5>I|*OaH-kv6FZq=!Zag&GhUS(rMDxl!Wm&TCW!vrcc=kNHOAp$`q6eNHW~Pl0QI+ zB|ooe7Z(@3VPET%pziRq%DG?UU_#{B2Q3+KB}b!FHmysL)jQdk|4gbH8zl}6XNtyM z6t@46E=J6VEcRmc_8r?n&auA|&k6FBx;6U=Vu^S~^!*!Acn}Y5{Aa~xYOO)j3HKPg z2x$RE0lqc9Elc@3+^|$jGi%$9BI<4kxTISAH#IEG`h_|ETmryl@lps!J%$~JkW}M? zDeR(a#;3Ah-op%_-&9X%Ff|PR(;oXpVbQB75O4qQb{$jbq8#7=#U%b9KU(R5Nf#Rh zU{h>3j|e?*!h{2p={Y@S^WnT@`8wKY*!ZZgX)VYLUq~Fbhq9l9z&W5mM4&t|%>Tg) z0Eq&H0HP2o1`qIp)&})$ClpLz3U#TgDz3}5g#0tF-NWjO$LNy)IPVw0H!Q9_{X0N^ zOVz8{gMxIE$V~t3mja3H_JWXaee!^*w47T2FmH3;^If zQhWPbi+p!UBry~rVC7D@Fyu?ze}obDHtOC+)P{OILjRSG2#RRGCR?#6NQ*8h8nA-WDPi2ChR}kS zz<8QLFV4=08;z5@gx{QrYIgNaa74PQhDB?mQ*_(Q@y6G=QE- zonAZ`hHU|2MX!?XZh2PKDio|5=*Y|yBv@XhU?Qp90a$-Ta_+s&HSu4OB4%t1f0=?3 zecbej;3{l;md;1$WdX5!s(VdnGAfqFu3r}DJO7lCga<(&G5GMU`G3HG+W_RPnE;44 z^ixW$CTTOWcmbTH%^3nv7d&MDg9J#t1Kj{ZdaBJB6ML|}{!uq9EwZ3By^kqNQ*di{#o zRQLox9EkjKD~z2&yN{F-Skq%fdMrp6zB{+82di3AhQ7Mc>x2{H4dfZ2g!lSOIXdzm z=t#%;jgk9iNY?5LdUeliT2xD`6IMqJA;|C))(gtLK~({E7H&oQ(2^k4b6aX3u4XYv z38i9S*B9OR$HA5vs?UVmLe7sMXhUNWQBK5&4m*!91KtpgxOv!4H`>fJLJqk^@$>77 z$b;a?Xqs1=H;x>l(X39-alA?8Fq%DGMxj3VYye@y(VP4adI*B)?8PvEatZ3Q2j`G8 z;W+0+Rfkhk>q6;yaO)mkXg2@=xf%q(A~b8A1Hg9xhzuZjdr9xScx^vR6y=YFs#bfg zavSv?g&S>;7d2*{%x{fPi;|34ZL(BjIDrD056UzwIUJ1nro&2KsRjH&)~eK74~%ga zy~W~T1kH6uRIgu@Qk9bO`DA;Y__o3?)q=VAYc_8G5M_!eHu|{ZQT5BI*sYWp2?cP~ z3_%OJj>UoZGQ=tjPe7R8`zsDR#qIQrwY5U0$oDtSOodb#K< zhjJfP^GSi!xUSorPc;V&ioyyL6}VkEzqyA1q@qI9gSWr3BOtd&1&zH1Jy`9JX+q>33yOx^TPs>X<;bIDwc;984Bl-|ZX zxP(6h1$}Nu#3oiaPg`kpjV!WT@m+9HC(Rd?A??fkHpDBN!jywMAJTi|>Z7Bg#{o(e zX`^@~;W*si;AFfIDvYX`HC@0WKvJhRf;=TRmO1nh-M<*sNAq?8m;6LQv+p}|RZ~nE zEDUrj+J0+@5o@Bz+bqUJ24VlwQbI#}Oai`L@?&@#tPCn?zY8fWKq-)l>(`o*L3}aF z#AF2yoHa$}zhWVjCW53KGP}I^EC017w#@g#*~x~rkYwF<^4_PdY3|8CyGJC57m@2D zhvT<(&lJV%=&Qt-K3W+dGr7vv_P;3HzXy~K@N%hFb<}RHFQWK*5}Hwu(Hc)Wa+c=1 zh-0gYM6PIRavfP3wJIM_<*}`TN}uQQWA6*Jv#8Cm5?$Yc6njf=HGhp7K_+fy@8oHW zV6iX+*5Y~;xov-tErlE98?(FpJ>kd=Ua=)CnJ`lK;IFpCun3+S9}dify`1+Z+Wuqx zPL38O&)>9Z0R~zwl5Ro5-fEVZS-x-`DLK~GO{cbUYU7#|3v17LWoRTc*Uy23nvs2@ z=+*mge;fQ9M1!r7!zd73URkwzu*N6i7d92lQM;tuk<@)&z%-&eo-WNTk7yb7EtHAlu^!BaFc(aMc6+$}9<2{5b) zhW0BgSJq*0rg*p?f{oyc0aKUSrJ$V6ORS2Yr&d*)%eFVq^564aHzr3HD#NylA$Y=& zNlxb<&Nm;25EztM4-eggRbVC@nrO(?*YjlWl1;KjaPMugBGh zUr3x82?w=wUzz^!#=f%@RjWH+AIB$Y@7HsPsjitn8&Elvma6ji9y32aGqv!%$aLs& zmU{a0QFdV>k%TNsDp9CXZjG4+Eg}M2^p-64aRFGXURHFL*iL6zuIaXDYoO@8dQ4#M z?RMAy9gzQwp`o{DA^X*plEhIz(*;g2g7+dN8BTIor8a2f$&+L z;z*rri;DVJ84d9#PrP3if4d)}lbY5N#Plebf7h{p7sL0!t4%st-36~iImQiMj3}J6 zZJ?#+{i@G?M{mMbb6r@)n?!47i4~&WpS5}?%=Xbm3#rI52&rc+0C-T1nqKilZ4uw( z)Az3vC@YR8jTyk^BkpyV&WLXmwe=(&Xv?i}|H$4U>z2<|GgCv4{-BlM!ph;KE17s^ z--%s!HzAP7trGMD{2XoUD!Rdf)}lD~Ik{nN?#-(8Aavdnwg+f`D(}XmZ0f_F6(S)~ z1CKB#)PfB~w5EH5vEYcSf61e-4-q5$p=PM{j zO}wd2R?k9vo64$3S>niHV>h4oCmkxU9mrA`T`l=`Puu}xm1qv8g;i?{!n5W4L1Fv@ zegI1pw)fc^ZOs>Q229Axb@&Cm#jS2q%-9&Kkur1e)$C|s&} zjD`tLdk`2#wf`thd<84qDk6aLlrazf^&b&9ob+7)Ko$UNDFOicK~FOt^aLPCq4638 z^M#$f@#~pLK+pzE;B2k7)RF1{wvYWefNa29Ku{XO_*rC!{JRaN0wW0jqmU(OgVwEC zkT3IT9gu0*w*y1UDp+5rK$w8cx!>(sNH#f1xRWBx`+Zmw_ATYplAxXU24-fy}&-fPZA!Wx_1Qy@6;%5FH98zpwfl? zIB2E5VCYv7nHV|%0N@!81IK@003E@nGD0u>`j7+9xUT{u1M$ZZ_h7LRg(g4He7Hp;?}Mq>==F{1>3G3+m(MN^>N&`7 z4id^iTeV+u8jNnxvSvjmI}9}iV|(t9CM}v}0~BYlB-8jzl?*iegxb-0e!r{IR|K#W3u>(*sftCLu+8}c-@*gJ53=)?Q-_kH^`F1#B$>q`Z0K`iZkA>{095`109@SvHZ*FGuhdrnJQ70t@2v(NkktP?Qw=EqFl`=>uW9sfsXSo-Ao67% zDT~k`*)BmJih!Yx4)C-QurY#&k0!DvGXP;a(OxTUypsl}w?GY$L>||uiEFY3nYS_VVfUinGh+r?|1i-UYG%><^%al?4eL>*3kJr8)Vyq8i7}*BQ_v~PFgxNg!r;@vfkJs zCzb{z?Ww&SkxYS*Yu%h@qS2#*nZ^{H8Q?V}) zD^%E-sOY=d{m?@y+ zoDQPh#wF|(vrGN*=*3-h-v%SN!89#n$cbIU3E8Shi1=-qpsWFP{`ozB9dUWTFG+=k zZkU2vI@1q>zPJd_9Fhs5IuJ-I=5a;y0xy%d{%%j7!10iS<1zVv@c@vwQ78(?<-jBn zMNY7FG5C`9oaL+z(-a`K(lDVLJdX`e&kt70fMEfgTb&GUYxzJiw9+ z=ePIug31#@PrgHuA?CLJNfI0poB>v}5ieDY_W*-&&2WVktFKK_lXEB!-02T5fov)lndO0yq_&*>QR3{m(=D`>^{dJfZmlvVy0evdBKt>vm%|yf#{Yi-Oujd zm~N;QHFlhXRF(dn@@pz8TLqtlnJniz@!n=dFt za<)D#9hb%3c(*pmxL!x4OxAv}$UScJU&C&5?3s!|J(B43PlZk4nA|fyu+i%l} zObf|jx>~2jZ+%fpBDjn6;;=Z>C2h;w>F(jwsk30%(Icup#VL98g!lGZA?2*>u)CH& zTB#PbDx6aNm(z*G@k(U70-+3g;Io=gw$S^a!VeA2Mh~FUsxzaD-EQV3GcE$k{z-R& z7f)0Ta`+c=b0=D`f-MNQYUUrIkFX(>s5{B@k1W3XNpv+TY{#PA7?wllWTT=ivbB{X zqtO!&Q#B?uc>=@`A#nk|7-{@zrW#zBI!SG;rDQ0RQ$r_m#=Gu6p~X5d(&|{z&+sJ` z^g}XBMWObe@ao_A3XuK#KLHly27}NxQnSdUi?Q*tpU8-HeVW~62oybZ9Lq|+@LS+p z=l2K|Zd~uD%%ltu|K?~Uc^W4R$kQB#H!s)A@hM5Af4b^pL^guH;v7H?zcM3Ie@#ph z;h_%z;%+esp+-Dta>q}k8ebTr#2&K{`naGzvJQa$9_*4d%~$R6sUgK%{qj_U82SG5 z91Z=()leYDWW+?P2@_)pypZ}-{}3u2yMN8 zsjP>0T@IXE-pNQ}6i?u&eUruRxB~0T?xYU|N49O>j_QDOIH@Z*R?Ok5#4sM?>%fpJ zf^T~@e$}>DFd8otD6iNo@BL9UZ0fFCP8OsOIBrF>$t$V2~bn@~~lDO%!AU%w75ugY9uQmDYf)L*OkhC$}wri)#l@URCcX3>UY1x0A~<>5pq@|ks9+s83UaH&?gWoUG3fq?*Ui|)MU8-{5AQrGoEqz(u?Kp^iTap8RGn(UTO!T2W)WAAFF}n zbMFX*KYnN867MV*bqb`w6n=eVN{p@xuc@o)RDxL=Xv(#lW?ir$c*)CtS+Ex%P2`rx z!Clk(7WcX0PE_M0zr2MKH;#~zK!*PG3TsuUGHhH>SX#2LFZbCJyTa+hI@ZEL+LP*d z=gs?{6nsW9vU&)0>(ycDV@uP&Zwecg4&D`1I|q#P=<2f(rCne~*9)%3HB*WcXS__Z(h1MxPNHF#-c)gp(#F(-;((((DV>Bd;i zdp!M#vEL%`8|teWRz?%7SM}J!JC4XcE9kdAdo8_+6;{(R3uNQrDw7Fm?YB?Q-&tD~ zz)uMZE8m$_xkzp%iyz|_F311GN2Mp^R;~KEf!8p3VWb)?i6FEIqW1r3&1!OhEJ5#s z6*r2FSwOkKsK(dF(_GBYYpnJGcUyQtpL6O$V}QU^27CSc=9=lZJ7n&NF9NK|Q#15k z0?f}i+|(ArSfO2Rr_{NH6*d0k>6X;f;juciia+Iy4d*eOUxEO{&sstxJ!@Yqghu4k zf&@xeB98mlyo7b!Zn)p~BY?8)1s<9Sr8?OB=5UTGsU;hpJ5?;Uq%h}}ypYddc_F^I z)U|W*X%QOsL5fjgUt}qyILe>)f8}c}R_hhMoO4XDAD+H}Sap z%{7$qe7v8PID>$6p-nw{kB^$)yl5o#1OYV?7Vf7hj_OzR=V0fU>UaCuK@*or-TLoB z-7971r=5$!AoR)68n)I3cIRX?wD+!2ZJ;M%B1((~L^|;-96W>Emh@ZTf#y8+lmGYf zcf^bRDR0AGPT88f*p1$aWwH^}wufADn*9ze`moMclY8OHPH85IU!;tT7;?8y3AaUO zl6l6l+RFc~QQ*A~^k!8MkUtQ})f^giIXw!@wGQ;d9%dED5IQPCSa${_UBa~;?tgw2 zHqwv83=kZe2UC!+W}Qd-BS09ZDQOFkh0+(n@EvR#h$SVm+@3=W_r;WRVe%b2e(^RJ z0e-fxQNXa6RALF*i!%e(?#$^iF{`&u-7V6{!rujAckQe#!N0wMwJ=weE%hquyK7t` zG3{l1K32jX))Z8y9}|?mpEa*SZKt}u(sAoOeASEQ6$CeD@2^SA_#eM7b4Qf%rqo0k zM?E3vpR&Fuz6x>cnUz*VUPQ&J$Cu=bP{|!gXi>N@7zwMq8_gE*>l;v~_$FKWjdJ+o z3ojF7VUWxfpk{ueR`9|dPQykygUG`fIVdFS6+*INc#7IkTo=}p<>Y(T(@2rB@OVKm z@K>YZ-3vTXj-v2!s=#a6Dh>tk$wm9qCgUgn<=%{q(OG+Mp+FI=GN;!XwS@a!mkqF% z&DWZK3>-G@$Hij_{t@!MdTL|1>p|=_2qsaTV#(omd`WI$9Hl4TF1U~t=8fni9Y|y> zN*XtxaF(Gv>1(_reQFOP)-fI9r`V$54ZAUHBIw{w_G5JR96W1(303u2nET!Gp)9*? z-}888P7m?iV%+OGz%v`5!vG?ey5!5< z0>Js-hZFSwTmWQo05R=&rP%q2L(sG) zOduSBm8Zl>E2653%YH_tok|LBK^DCfKa=`>uP(<@Xm!Hhnc?c-j^@J~38iatH(0T} zRo-FJ*~c?5vEV_4fWrXwwQLsv%mxdF&q7pq=O_QudC<844FK500pcJCPYoi#@))DAF?<|JAG8OSEPSzI4T2*plmRhHP!)>a|+$y_rq`$@mV z&q*EfF4+56!a7!pO}yo!2DMDYP`iVOHaNr07A=f`O2R~rwO55{9G{5R^rbn$uu&gX zujqp{(o!8{rxkI+5|;P=v$bjt@#=i9)yLQ!97yJE?=aAX~Cc8iU&<=3QW)Y09nz`9vx-jJ~Mn z-Ns$8^_R^yz#KY~UK zg1k-dkpK{U%ayz=EqKX_R|f?E6s9Bi&;RI~#2NO_$2YXWDc4OOV@Xo!-v#^;RNY-& zkSxh=AfIlFWbg#MFXtduW;&usTZ?bHS63K5eOPRNbGcEy(gA4@t&AcP%3As$p1T68 z^)~oL05HTf8ltEoH|);YYW-fY{|X(L2Mxs7oJ4S3WBgJ9=Xu-1L{AT?%{=AvksZcW zqc8{E&iAoLiLtt}bo7`~`o4&kE@_`>@hXx7u)tz%$+*VTKUKD+3e;Y2FL9>`So#j! zUQUhQuH4cenjc>r;6^iW5$=XPY9<@+P)I9+tK~YL3+4nukPW;j3|Tz0GMs1q>dPaD zd;Ejidk07b=h`QOkr!`XvFIb|cox$?N?BdG(*|!_K_1Sp>0du*VBlN-=)~JNe>y{v z$U|qovcY%1*?HrK!)mM8)ydiC6-pT6ion&1sJPu~Gaf3+PyPg#XZ3jNqCu6eJE)eSf$n^BJd9WV>>^;$|mF)F8IX zv6!ReY`(rJ{`j1bw%v$a|0n@l+2cz+&NyMvL7F31OUL@HjsC4x@(_7ICk+dmC-K>5 zgaxZhkuS9UhD%YN<@$H{Tv4HWSZ3_|JIgHBNTFQ<5gX6nZRv_gl_^zn`KLKX(}YLO zH;-Os8#pxi(TUTYZSC8aFs^JKM}~MZS%tfxkWlIVeR9W!wI`w`+BuhM-A_MxJP5sO zls>+Niq(JZ^x+t7iUACPEC!do0)r&2j}5*t znC^287_Cy#YrtqbGZCt$&~}u7(!FUKMMo}b0x;2HnHS(8{N$BGTy}!TZNj(6Wz$-i z+`v;EnoD7o$c~osh{ z%CXxox=$&}S63q7bY}x3zY%4K{zf!MG_-)0Wnm~YnFEFrr)&+f8gJt1>d*12>CHBl ztZR6U!dNJ#yrOxow$+hQ-vxQMlP~>_;kytF+O^@`B*VyXR@FqH>l&r)G#0rFf&HxO zlAn2l!ewt1ZQC&VF{o!8hGv^fmu$hatR`m>z*%bY`}w71`aM5u#%Gb-R=lv!kKBdd zs_>*WKOW4r$4^vzBv~frVd&eHiYf|C2v^;p<72_z>Dupsnk@$uMIfr?h)N z6EPZFknE6o;K4kzI95Ia3u#=tj{YWwO(2UajLI?Nljfe_Thy<3Yf;Ix#_iQB;lXKy zr7&}Y{_aJ@Z0HdUTlOhdtq;19WK>1h=dZr92)rm>bQl$ahaPW1NH0%bx$ULQsZXx? zBS?CE2(swIOmH>6cDo`SSQ1Gz(hbsI0Y2CIT2PT~A9W=)14sc{h&~n~a2o;w<#}RS z{A<_$H(~$Jf{17Za04J8h=Wy0nH>Nx?tv#Ykw*VrE8%uF>SxLu0SP{>g_4qYmL^ss zf79jvI{VlXb8fls@g4f_ZF4pRbCl!=Xkg$ zwOYeiEL&V;*!lvs9zA1ZBCd?s8$mgSnM3x!HS9mdxdjmYS;S=0KgL*1djiJ@W0Lt>L_aIzXm}9 zLIQ=$4N6a9fqx>6gaC*om`lu1fErvFu+Z_5LyQX#!mshYp|NbD4KK~#kLCpm4G{gR ztf(517ljaND06I-kDuL*Ya-jq(s0(PL#I)G-hI#6UM9`mgx*FzIVlwyCGSvhH-?U} z!WkF{#nyH3#nF{NJtn2Sp^yBcg{-p_SVUvUTIDfLC6n|hVu^jwR%(yL+xUdEFe7Ej zy9ePVRWI>PjeKbYMR-&8kd7$(+Y_@KdS>nub3;DxRv?8rTFOF-8GYIdHFK>agn~G_ zG%O5?w)dilU)?_dF8?ZAekZ5@A1?^3$kOnywh;h6`2HslM}4V3DCD0zC?e>z1TFwd z%&V;iURZ#Xvs&VnHjC!=RId6S$$=vii@^+{$d+UR<9YWRVdfzw9=g$BMl*Y!&4+yk z28+ljVZ=wPT=gIl4h>PQRDx($ACip-$EOI3^Pb*Mwp?D!AR9V{>zEQn8AAOUS#s!A z5m|-t(`($ItkObg&Id8P0F)5u4vTmHx1B#UL@%r33tFslNQvWab*0HoY7WQ{YS*{R zZ}l9TMBE^#ho=4TF-`~Y(x!J>`3|OKDp1`4cSMdObT^+Ew$Qya{v7vWTPac z%-O#?83sGfl1)va4;fUguXg$*ao!Bpum85s(}6@)ha;nf{iA{1ce7^HH=G-p@bIPA zQh$+1ni8ET#%)gMZ(8ponjUHe!F5R8a&TL`8Su#;Gm?Xsd!Jrr<-Hl0`Dh%kCMTQT%^S69S0jziGuRg~oIjZU>F{tAY~t0WK8E zVRJwukGzq<#82~Wk8s?3Tj!?EnjfD##3T>}UpnF$vpboaEtHHgrQ;?^qg$M)-`Kkq zhRgA$b&s*?TDyxOInn>r-XMwzLVx=tEK6_OKqqjTZ)ks+w`k4j=-C_~gnP8^Ha=yt7qZ`zmt9j`UoB$S)--1zw#uYig8d#HNV-*Z!q5IbO8at#tSF z+HkY&xw~vKDcS*dt=PP-t_(_Z34qT%UBXMmOa8<-?0w7CnqNb&SsNK0IV=}lIxeS8U5?83Q^yy z82tt={HDb$#5`*FIng}ms=N(Po~v@zFltz#WcMEa=*NwQbwhG^cIbwrzJ$+qP}bv~Am%w(V(8V{6`bH+JLO zi29={^45)v=jP4xMCQrgSugfOWJaYyMek#{Y;cDBHqbmJ5`Gn@ZNgClD7G~(*5H$w z(r?MNd>SK@U2S1+8f%_W_J%8MEj9T_FW}2skSj02DVKeCI}K0M32k=j3rtcuq`Cs6 zMoD|F%sWDp7xl~~_$M3N%QlF6&>>|h>S*{38R=)0hSzbPxhyxRTiq)YcdRDqa1lb@ z;5x_z_V*pHP76rZF*6tpu8#z_fnEHZk(f?)ab2nI^%S8?YsWa43vu2l{Uav4e7s?N zdU7^>|KTAdB&XhbCGE|QvT24ao09nRrTYbHQ7$Lt;_jz1#TFh1M~+gKsnU&pKuTr~ z3Lrw?+>_0=e0Y?rek5Kh@U)I4=QG3i~ zK3qm`7KQPY(vqV75T8j-SofdU77yopC;+xLO-ZIOK=}PSzyd19kE)Z+w1UEkf6?R8 zjWNU+!xl?v)`)bf7I zs!fb#w-q;f`#z+dnmQ^kMWx8Q4&k_m{O|^CM+LVI27n6?MT*?EWS8Sz_VC>r7quAI zci!;?KN$54;EueWCWm=x6gJ=91XP_7`Q1PbQ1nH%;6l{E&uM38(gw! z4w)dwQm9j^oRpue8a>=kJRcJr(EgSuOu3vJSz#t?pn+s7{|UmDvqCW-&*q>p@8}j3 z*^bCbRT2x`uRyVi|B1k#Z_C&Blj2d8#3%?gGSI<~mxAeC;_m`y6zaMnBf7qxj9@gv zBy8#^3@rChos@R*O?UCAJM_(6!?NS6gmV4rgx^8juPVV>kENV;5_ML?I`Y&<>e>GwhC?5Y8^|j@up-GdI^Zna zkrFptCUrV>F+1#xaFgaW`(=@T{sU8-}bc(HOboq?Jz^LjQ;=1g<}~wo%YkGgf9%-THE} z%cC0&U#5LIOShzFc>W9!%<4zU_+}W$^JUzmD$;<=7?x{^*FKnhATQ%Oghav|;R=9X}|tH71HZ z$jTok^h=w1Ig|&$>%;!zdyaWWw=%-imi=-h>=?@LO5u}I3aW3^f2{NO1zl`lIf_m9 z$2BZ8tC_LkKIWabIMlu1QPHhaEuIxSsBW*86_WQ$f`;N!e?69Ud5tNJL+#Q(Iw$P* ziMQkKfJ>3+#51S=^|B!IQgyAXF{Hw&aZgN+AD7(~b6QdOZF+FvZl+{c`6*s8b05_b z4%UfTG`UhL(YL)55Fz|L{w7<99L0jT?Z)X$ChZKGq-CS>Td>tfZkEpSyF-63&)6Kk zjUPPv?}V^=1vO;bw*UU61skNFi?$4#*@jEg_jw;wP#+W3LK1`x|-{!I3nup$DqZB zVMN%l-^1y2ClHjzw`;YQi+GS&Fh!_A4tE_4%Yf5Gbo(_W`M%%ltj^BnR9i*sHI35sAvNYOLpYm%$&#LWJAv9>&RKLI{skU`bTAldX|oMy)gL8t)zR0@(xGO zzIum15&rJI_hu(i5bGN5W#_T&_)1aSZC{Jz_$%`rrpUn8 z@%Hmb%8|AqLeBVnAF3wyGjw&|FWRGA*3)OuYHvo}Ek%Gd4KvoR?nQ(JGvqD|vQz`n zaU9~Yw&;ROmsg~HeXe?&jxqC@=a>$x60ZcZ;XWbfg2bMNpI$ccuKaH5=SVG^aP+0l zd=4W+W5$Ia=%G85Bs9eRtKjw4rLmA7(p!BZ$?`lc8GM0sAemu<7R>gRNdKDO6QTunS=t|3T{P^T zl@?fZ{Ol3?$)+gGqvg?)yQrkk0=Lsdpoq>#$(Qizo#$^xB9i5yVU`2=Xx`^7RTZAL z@yAMs+i!%T3$r-Ig9Y4In^Qv46+$!GH}CfRBCMtw)SpT`*h|x~c;=)aYqs_{{(29o zUbj)>gF4Z?FNmJG9=bs?Y8>yo|B(fB@+KDu`KAN7uT-W$kUMn;^%ShtAj6syTh8r$ z6y(!xe=t3L(7V7Z5#&ofN+vR`9GYmk+0^w;B(>Ukyz{shh8d@R@T)CXpmtC0V}XRJ z@c?&le3G0Uh6$MBp9Nt~o(XK+ytQaIvl%QZE{H9D^t`si2Gw-kRo@PBEa5-zeO9!V zIAI`+Bbzs^A0>wt+*K9KcEu&8hBvP%fLB6-XUs?c=E{i5RfS|Sf(UwRHJ-@9YHY~8 z9#oc+OXiRq4rIm`bsDV?a_+uG$i28QnSjbuUOC3d6}VeC_urNECmSS0RDsiEhC)_E zP$_*kx1%i6(V7V(Uy}A1pfzpr_e(egZq(hx?^c%9^STIAFA*KYDksT)QaiJ61h(2) zo^dhT36jse&h1J3!#JJph+^0-R_nrX$t<`sBiroF<)!y9${Xi~6f zfIOqWIp8<9fi%$P-^|L>0sT>qqfXuN5bae}ZrRI=+72;`Y|pd5lDDU$jcVuiZBHL+ zi_x&z#>ZKTh{&=careYeE7Fq3TF-(&i*NUPogpb*ti{nn+xU<3U9DNyykc~J^EFrs z8h<#}HrO^jSdU{QDYNAMQ6fXNRQC<>PXXL`1`zK*QJQ3;f-g$NS*KBp*`B?pbU3e4>SY2 zA)%}y5!r+kYvcjY%U{p@wVY8Gr3Xpl(wg&oFgLxurR2O(CIYiG6|9U19;3V43CVO` zy4P)(DE{N#yA!G6S8V2*M(}dim0@RQdW)^28l%ON> z4b6jpoPqi5{S;u>C+8=Bh{qlIT_mFEJ00W09hAn4qnH=WwB!)K)AI6t+^^-=-#pij zp|MAGs)2{J$6}VoUySW1inKEBr!eG#inpaKeMs{Q_LE)*kRr6YW+S+yD1Wr0>f{Sh z!L-@`d|b-8YH5_r3fz#^bJA%dJEW`dxgq`~{4pcLx6JPs4X&+bzvD&JB{c|&QYLbU zL=?2KJNTh}ZUu@Bf2G`7YhkM5c+l3&$WKPjp%&M>F-GYAC$VP}=g^ZBw2=C%r)m_vo zR;7C-D;ESovJu*1Z-=-YgvLuqvaiC)jbLo*u_n(FaOm~fhf^rZjonNs>_IN?{$^A5X&?jbzd>%(wmz~YFRR!rM$PNeTeh4hr`G)_pPA~bdqRM z*EEPtj4%%(A30&Us!foY4m~M?`FtvCK|Lyf8D!L=C8@KMpM< z;>m%*Sm-7URdbicgqU{U;9g^|6|O&hntE`O6}pkXnij~)Q^^=>%rM`GgGLXW(&X2NsGJb5Dsy>U=_3xOn!^&Oy`=t(&d^!;ii70@EeZ1&6=Ez~AWCNuf^QO!=U*)GNYbV�!UekovjiQU!eGz} zU);n^>A&Mt5y9(_2^n!%@SS0@|JP!a-`~C%#_+G%)tARb!_>zrsQGgX&oc7}Ww(fh zMC{N?reryegC;dH0=uYzBKJL>V`MrpDQ2+hBZz`_v#K>OVO< zYINtvm20J5Bn}pQqoRySz`QD|cKM@NjLXGz>v*3~O^96Mfhy$9?KSoy*47O_|3Fvz zO>Me#hF*O6F7i2K`)6IB?<|7iQ5r>I;+ighFYojl*T!eg?T#)xHWS8NAXuu^W#iy< zum-Nvcz)Mw6M`b1ZgGMmF`HJXuK8mP#?cUHWqiq9&I==0DsIE)1<8h4FxS@Y_sm?A zWlC1v=!W-T2=(ORs*Lf$4k4Kx`KujOmG62mf(DfzBm}CKwm%p|4%;~vrS*$D@}Ipg z?mwTVSz6)H;jChGWb^nxU+WeOyM^%YUd3^Jv=L-0*SFia!$REBuP%J4@Tvvg73taz zeMv?<)EJ~NQmh6k^9!^Ra+7mQnBqE*lAo&YEg6N+?q*E`8_`9(QDv|e12@_J%pYHc zsi&ema3i>xyKakt{-9-URE)ALdg8UauA)8tb{Qcn%MUgfJGst5%=0(wDj`{pR&UQ{ zSH9Wil4(5|I?w>L47h{IN%PV8wI=P3V{R;t2&*!Sbei9XvQHy&|Msf&xEdpbDqmsd zvp(tzOH*pJ{sW5=qY26?9fPhBrAEuN+Pt_e*8t*?mJy5IbnAOl_^wjPV3#|dbv0AP zjOXyEpJL+VJ_&6yL7kWqLaMkoBC6mn1d${qOLh|RJ>s_0laMl6$IES&LrCb(!XhqA z)pCJj$+=t|YnCd@?+3Eijy1O{P+lQM^^3Z-U+Go+d3^@Np`5)(kFs&$pckx*7BFVg zA`0x9>39Bt`M722nK5c*wWA5|ce=1qt+g&Y@itEo;aX;c#v=rG&86Wg*$CfcQL>Xy z$_h9mY(g9GE9Lq@-DwYD$k5(GUyoO1>?hOQhlK$HG3hLgEncY&|lkySvQ<- zSY|^Ovlg*mzW48%`<)Ye(0lF?3!&y_2~A2nSG#yP)bzc3np#7m0(haqMTM?3gjapYhywkX)*8z06milXi0D zfDX|J-}o5Hpqt-l{oR!#k*6sKS$H_$_{l-mLc4SG(_OEaE>K0nc(UKNL^CY5V`TjI z#)B-GfOL-=D&VfV(8?c`KrnN@h=aYxp(5cKXOwAF!}g3P4K1gMOPjWMcFq}AK(5RM zRO`TIBB&G+ub_!$p>7q3E3MM-YwA*qcw6NnnBtu$4f z)zhXFlSg9W^t#CIo9i-Fa#$79?AQ-DNes`Z2VF~51&p8X70=b5ymOra!R3H$UG4yp z5K9=&GjiP601+nqz*=$oED@iE?Q8|Xmkygh8(n7($)m$f8oU$Kuq7Ceo=Dx6xDN0@ zhG~3{A4PTK3CYQowXcd8Z0IS3gp_ZaNIuOj)R-$<%f;7;+--Gfov{q0^sUXoZ^@b} zo)_b0lhh|YFa}Ff*XPjEq?Ht}2$zDSOBt4Ys-*Df%;gVbxMLf<%wbaEZ5V@9rYP=+ zH5{p{J(vq_y>=P*9+55jM5AQ9K@eLePW#FxRD^Y!m@&L zT%oLVa}1mvxF)jUo^w->*h`sYv>#%Nmc@s|OAAoCR~jOw}%F~N0Y^Eg=$c-Y;*MyiNb2A-61-;Yd9!^2-^(Hkoap~6|# zkx73E9GLfj+rE%Od4BM&g|Geq0Fr0AP{!Nm(I>V-7yrD!atxEHRh_A&w9U^~ zmpNr&p1HPq08hEdgNJlb0BT+J$0(#N%!6ClvzKNTrZqrmWLG?)!z8H|U zJsYc0ZNT2l8oDoH$Ww^o#7jam!iEgrL720+Y4)A3 zd;y-h^!b*&q^wC!2+y5ppV~lp&m?dO+#)5V5EUk?ZOAD}z2$7BJL|y+c{yPW#Vmlar1-iPqJcM)(NI(N$0gW0Z z9p^(2X(OdH z{K!0$=)h+U=%C_7)_V^`zZk+dmVbx_srA90XNpT znQZ!?sl|9zZNR808yeb1M!Nm>tHDW!1Ue(y9|Ko5zxTYQ()3e6=36G4wJ!MI7;d9PSdx= z#4_q^3~eqH+De%EfD=&9kd50nzxMA^nuYcN^ROX3MTSbGoF$kVWZkafmPgV8SWhff zc87c*A@G5IM}Cv)H=EI5d*HjlpRTizUM%5=DL9CZL9PLPk)|yaeT>=_cWe69N=blq zfyLIjGGEp4;cgPxJ}K`-luT`}L53*+ZS;>VSyF$iRUBaes88f!Y_BEhr5p*_$mI$f zXLX`ZiK&lK*rBj?QX<8myl;@vDz<(`En2I-QFpEOnK8Ci7cVx-^#M>>7W*W=|Eqq(j>iALZ&dx{}08&;N++asGaL;}B#h9@|H=kRTEqRBoi15Q-B;a1522R+rssn4Ax+v*|*;jF9Kn5F#nh`578x z$rE^lK`7Lm7~6>%Rf(>UKmrSWDuC|pyukJ;2tY>Gfb65q*5)C@^XALji7F+Eam36d z&oj-a8I(&4Ws(5{_sCh|G78~J5zI{rM$}R0A|+r5+=`*>>ki0N@*ROwQT^C>FNIiB^6~{j}57>!O-3-nxIz@`7_nO~gvfW>Q#ZB)yc07y%wIz!?L0Km!?MVfZz zWCgAt`6ZG6RJTAoKw&V=(*2K3eJRyWHv)b?*xV18>|~UiwphLis)MZh8nz5Uv_#i~Z4e$>jIFQ}XTwp*=f`ajx?bp#VP71flT62vxHzc|pv?_7(Okpc1QN*L#+R`BjYLHU%C6w z+5h+#@E=EQ27SDreZeIHR_r!vOIG#!SHlIPDf=erk#A zgE-5P$wdBJIi$0zp~}~PG4Z#%$Py30B%|br6aWhSPF8s(i7GxHPiOPX)j=6>~*&MLz z!s)d-l-W2BMJs*CKRH{l;Bpz8NVorWVfw`|9yRt`7NLi;qEC!6O7R>!Q{sTVmDD(W zO5cg2u`N@mEP|PyweuV!dgkt#RovQcwBET0S(aj)i5dnUsf1~ksA@kQPR``62^Z1y z2^K5(L+77$CJKb1E&OPSiAN{^1X?OPGh+X<(eiy!P`3gqUVd))WyVPDI$Ap;6qqO; z2SrA7>5!aUz%}y>rbR*BSmnquHQu%7bE{98E7K1!B8*Dk&MlD>ZOJ}9U5AsGu6TR2 zt-)Mb5BP{md;SkE)Gc6-ARJ7LNTe(8!nUCnh@gDX8re6d^MSR{pPOY5Ogqf zNF!t0z|@0Mg=D#Geq1ws)vB+z>J1KW-&s|P6Or8RaZaPbsS`$<>D~++H-}u9`_z zB@mQnmnzv#45UtT5Lfg3>?@wCYEvp=K03}jiETau4Z>iyy!>0Vg#Tjyv4DeVIMm75 z*6*dcP2zbRSzD3_OZj>gCi#?PLAhU28eqFkgG%<0%avK}ujh|6vshcRd=2}))bn-q zaMBk>l6DXu4!yJ~v^cdWFUG;g3*AJF@6F0xbn~RxQRW=0N5i}vTI#T%D7#?)Px zP*SbK&8;!JlDfrtTU#{`ShBke@k4eHKQma+O@@*qKlI5GDPol8gxFt%@z?W;S#Pi$ znU@Len%v{9Q!!krFVFYG)4gFTsHRSIWU2tGJJ5mB7C&U9fI^T-(Bw4npp?uZE<)kt z^u6yd#A7q@7{Q@W@}OM@bCZxr`+vLpqDNvftYHWANbcXdR*eXCg>J>{iQ`9do}blY(G4)ZM$|{suw=aSFwC#8#c?dy zl1MMX`>>;*3*<@nx`SMwqz3)b#Cr~+3aoN;6CBBPpD&rVZufNH)-2bGwuro|00+~A zUX6O%7v)yjXXG|(S$JWic=6QsI*=JhrC(X<3Xww9pvnQU8jD_!EQWI8j7TnaL&Dy> zz7nve8OoulPLiA5QXJLuk}kpc1b5`hseP1PoQJJLAJGgRdik>8_>DMn8%&myG%Uvv z6|j=a-*wNht@<698gW}4>!Yi_Y16JtPqrjyCZT%A_B2ul4pk1>Dq2v?Bl|65v zLVdb)Xke50ZEWK>C*9fujoGGp^?{`OEpaCSfQ3h*NGu49`as-3TFn3U<-Uq3-u7O0 zg4h7iMN)8}#}sJkdaXSn5sFOHe3$H%{5R}RzRw1&?gD{JAa$ff3Ic2_l(Dj}vmDzZ zzd>UF5N3O{`)_MetSFvEBZTRGGbN!f3aU=sgGQ>Sd|L5Qcs+Fl7t&g~t6Xc# z9*LCPWdO4f)*>ePTWp$R>vV3cRXwJ_7lJ=dc|70=EAlIlEm6gshharY!BJ46FACw| zGLk)e96Cp`85F65!QJ@#XkS-%4a0AI-E?B>u+vIAXIE5!a%ti$d;+A;nKWdg$;M?; z?_t+**xyqZkR{($^bd3(~G10;MV8ubYTw!8r7mrD3q%w2RO4z~3 zYI!vU0f>@Z#9t6e!VE#^8}BIjUc}VTi4^bO;Y-TqyHqBOqU4nq;M7yTWN zEnz{E?z(o85CY=xKfUzGd^jeo2z>_bZk@M^0u=1{C{?*hOay4PqcU}3VSQe||hS-6`dH;Bx>4K8MSHW)^txQWyYo!|CS@5O`EguuL>$FOY%; zJ^?TQKG2@SkH8%uV-9BC-GCo8T>=2so1motm;S}d=m^j-wctI(j1{s=tQia%&)wFT z2(I-*5p9fS)8%5{V-sS%=s|U(7<^H#04zgBu&aL3s7K#Ae%Q^zE>RIBVY zFdyjmawkq;XW5T@{o61ZAPgjZ_)R3BFodHzUE;H{LH@8tlqcw?@48x(XZ`dF9HpV> zy}=?aYoDN@q*-sHsP+UYsRaTCKxjeo(&7KB0$3O_;1&N$hz1)3KNwg`7DEYagFNC9 zn&3G|8+b^Gqe$@HV-9f)W(;13q$i^tBvG*M=VQUS@NyquI^M88yCT|*C>q`HJ})ca zCKd^HhWV>s?c2dJVZo53?@#?h`f@P2)M-xYa^Rk&@cWuF_;1-gCoZ{B>f8?AB)v1l zajU`==qReqYtiTsLn;+Z^!XYdl$(S4uL>S`Mk;U8W^dh7+^R%m#4V5m`+l4*EX*|?ot1yV~qAKbUSxT?) zaE`}K`C>a;htX{RBFoxVFZgl=_}3rcs*irUjgPu-7zC{EK?&<%^&LC<-KT3+_Mtu+VQYz1B=j;XRqU8^BC}o7X3>OglzgON=Da3FI?%CH2`uxQQE#I@rDy$eN zXbQc?*KN9ABL|1#fADyb*BcwtFcslFwvA$G1g?r`1ig+1N*%eAt1Y6=ig;=jDAq5O zo(Ji-HQW(Vrxp{k+GfQQ^HV7&c(uz_a*l&W2Mdy=*VkO4PJX5uE9Vp}l-?=nZf$Eh zDs;`e%js`6sD87#nJs?O9aZb5=<7H*=UHyAR|R8TdiMFEpr3{f5bw@>w$xR^6c!%`Vc@qP+;uS%YMkF!|xV(5Wos0?J7mp_?9Br@{D zPy=xMg766C<=g(hK9(9FDIo$2rTIrB$P*_h0N}SzgO&k6))*NX%-*4+I?;9njK%iZ z0{UCsMSzu$G>`#cnTpN943LlqfNLTCwa;x$S1v0FXcXeZZXQ^Nm?GIgLD1rsl^VbL zqSB1rrp5q3E}Q@xj2w<6iD7FvJC;iC&%1E5l-jp&S?l_H$SA53j5i0;@=&BJ9-0<~3~kN0nLQr{Qzb#`hJq3*^N|-}%Kv zDW^}E@(!iwL#ZG#i7bUC_~Hv2;KcLgcV0i^#|Y+-HY%RCY3jXTRE5!l0HCLCw%g(b z001BXB(Gfd{}?6!h&dqVKa&FNw|^n!-v{2Z$q)dwULaA__wToPfXQohFzT3hXhnUj zBY=D~42ng#4?xWm$P8=-7OVRAA2z2y)QCm`yHGcR0Kiiz0E}JA4LpycfJhMl^K+L- zk=MciZ0X;XXn!#mad*%0;lk=IFD)Lx<#`iz38lW23XG?H$CvjN-LchK1t0Mp+#=cK83t(9Q;)BCsHcCe<4TVY*b^(mOaq+i>ytK4sicR5S;SX{C5gcfy4*N;AIkKAQ61!Z)xSDc8 z3F0L*$Aqj*UF@<`?BX#()LN(^s-BAiH{1x$*)f9CRPyZDzI%Pxb`xu$0ER}3=G3- zL@j5O^lUe7EdV~g1_mzg9$Qp3(=2QV3-4S`{8s2aitsXD=p5YCrvictH_U3_tIc*sO{oUndo0>V zx8_H(5oskjvWbd%H(m`qWCpH7Q+zvMY<->El7UNUpi!FmCt)TM@=&#&$smkOokD|* zeQnnWH``~!x|mft^|}Tw_t=J)q2l*EQF8V^w%}LSs%f(PjEGG&QzV2L zAiCC3%YHz+c8Q?XkQ=TZu=s0K%oTh7jOYUZ`0j&KyUBznmFu=N=kygj(71NwQ;{O^ zlCFdC{irYke>@`~%WFmS@JodX*_clmutxU`GP+PhA<0&(Ugzhfl7#I9W(bVNoF@VV ztN0$&7IFw+x84gdL%RKalO1npkx$~J^Ip5Glj8N;e*5Sw$!Nq+zvgXN03gBJ`=$cSo1^mBRI{&|`4bWnO zPB#7_*h1ohFwb2wUQZ!4>L-~?{VUMFI~4%1`)GbGWaU#cOGEj2NQUP;^`FM{!Z!I6 z@r&dE0P7%jc&+Y=Gh7e{LXsiy;B!b#0r!lFq-6sBQBP;DG#A><@m{T$w~;#5WD2!p3nLiub^|T70?7ueFZ#(!;NBxBjx`|Mw z_94#hkm=*9rI8oR8P9$;|MIf%28o-~40nmBU*nvRN?quO$!Ib9GT|#_>Q^~g=qy~V z=*UU?%@*!toC5)+s9&LbeC^+qMo6PxAhyYJ8FSVtTQUIAzu--zGq_bxQ)_#=-D_)E zDFuF)@@th0#>^_b_Oo*w)Evd0Hat>to>}ca-3rV{ZHi}MNNBSz-iLC(`~g!0%X9Qc zVMOui(_i~+_J?M?IPCr~5>tJC&gYdAwxz00Xj-%^>5>fRYbExFi8HhMQw4Fbp!zhk zp8WJfiJ~EJS ze;BUh_3E+b?`2(WWc4IH&3>{F(i-Hy(Ck38Q*{Ec;=WE^Z*;jKebzPJJFGz!`&SG1 z#Ui*@=@+oo2nPcFh5q)Ma=nlnx>WE81~oTOW{PoNBl||!yuz0}gW6Aux;|ikFig8E zX*LK5oPQJBh9p@~nT#<@(4YPi^~fqCIx7|~X;!)QP@rJ|39s*!NsKP;2Vn}9mY2&Z za(LfL=Ic@0v?pXwJPx!;(;rz1@x>hRlyPG$Bx+jWS9}~qqJ|lp9vsFDp!_Rk4gR73 z&6*3KQHhjr;tMqdVysCovhAG6(m?&@ulxh(>0hH(paT&D$!neZA0c$O{S21{ zLYg`UrI8;0*IE?-tb3vWume!(rfjudpiOgX5TVfQR8-{$fSocjRT7jRXc~rUd*+oA z_d$5v&XY(C@+?zM)`GE@`fSD};6a0gmpKH?aahTE(Q3w}L=3SjHmYi$CWOpk=QKWO zJx;O3$Rcj5fWvfOAww^8&|Is^2$bqX`dUcI={1UO9h2%Uez8Hggd7%cBhqX&aB~zN%oVHbp%w=lZoAI(k2YKha^C8H07Jlho%V$h1K^*;5 z+P6vP2s=zi{IqrbCK?1F|A8w===D`nj!1lh^TJV*`4Pj4hRBae5Ohc;k*O=fwP24( zqU6|0452cv9^Vrw^h#5GbS%P{_;w3JHvG z@V~$}0pO|^xfK3;!fD`I5`DdS;^JZn|6&_BIsgQiX*=V|L!74~qMt9D=%eg6L_2raR(|ikpz_o`VMY^+rd!)>9Rfs#{UmMNjvQx{@YXbj10G1g(U2 zARf=!;d9y}9u=YxhT7B2S^0RgQ-Fw-`l($>cU!uf2|kW_t5t;q*5(mP-t8|Mg?+UO zOWV|;;dGL?O-*+7)=W!CAxR{oIOYBlhDO_Z^9y$P>pJ!%L)R;(k$P~vcQ8E|K|g4BvPeB%jhUBF?(Qf&Pn{G7RU!L$ zzejNY39G(N#4#RcAU0=4V_o2Gu9l^A#Gf25#Jf!CbdAQRp9fGnkKpaS9ep9X3h9=B z1}^2|IsC}*Q>oe@{q;kzF8Ielij4oBxL6!Gr?h262HW>x8%XRy*}F11kB|(xR6)Xt z>wcj8Fd%uq=>KcG{>i^Ai0BB$(W;6)z%#herz|X%>-SH3U?m6u5vK`1C8*hCj)$McRwqN3G0 z`7Jg8Tc(Y4?l@YoKHz&3RwDvN#EvTuweasNF>Ki?Bg5gd2%5vAw#{BlBtRR^{J}W9 zzODRtH%5pfVxNyUgqnwCTyguP8qFFy(Sa+4SR3ss3rXOgQ|P(g>C^A{GFQUSFs46g z9g&71fMR?DiXr=?*bdw()#zQY1R9Ea-@$Lhi-JPr1cm_G3KYoML~S5xVi?f=k>?B{?s z%m5Jxd?>gIiaY>NoFd)tVY4A$I0hC9EZgjON{=lkg#bjf7kU6mOgJ!Brx}Q?O%?r9 zVW^$)bD*f0jyYEh=@YA4x0*?g#r?7H_){~cKf*s;N4hwgCcRqxR$F9Q;eax>XvfKD)#aO)~3_`=CL*-r2?_oU-MiWL~ za>Wajwv#wXtJ9&*2ZSFwMY_Pr@R&$m5)rcN<1AjW$iFrn)$omqg-TiF`$H1is=rh8H8ieAIxGaJ=Cv4sfv+B~4Ms3TO(X4LFJR2rWc zFsuc>LRhvok0b4stByr0qP&Z+ZG&FU4x?D6q0pTK>i@o|M1w)DqIkypw}zB%mLG8G z_oCy`&2J~(oMR{*K4X!2k0xEPxAs#mHy6C>-qtl%AMrE^PI}1+&r(Lq#-y9zKF$h%-r&@H-1e=y41IxzO7tfaB zjQSMVBVV0oC3^1P6F(giYa2Tv0y44o_oYEKiWmu$*DlA@5E(8bWtSwNe^Mh>`GML*2KdTTdIhKD8V8g}d(Y}?H>MTJ zA)I>ss%22=;0{$)a`Kd8%j;`8XOe+&{-|*cU8zj_R&g<-l^k+fEw%_tY2p0~Ju2_z z{-NQy%#@+MDV{56LQ)~RwrM6G@jGeN?Y%(NibymqjDJ}q=su;&^e0dB-I3Ga{NL5= z>WosDSVhEtwsJU=W?z#=T8R@S?m3&6*=*k_ph~hW z)S9P`cq&Zz%}f1$NUo?=3RD2lnzL)Az2S@aSmDkp02?Tpi44}A1C{SAnefZ4^Nt8% z{9dirUYH|mD(j{Q(+3ng82NM_5(f(K+gHH)IAaBGdJjAF6FTPekdyN3256@*d1;Bk zcwesyO$jc34&6(lLhgy76wU)KA!OZu78kKUvolB`XZVnM^yXSbcBZs@33i zm99$gRpJA4RJKMRzE-HZ1VUs0$n*BkCE*2JbzrWzt|w^rs?kT^&F;Xkn50zA2#24- zg!Zn${w`0H{T#TNR~jL(L`AzcTO*NkK(M&5`_+4}7)ESw{lD1y3aB`mZQU8%-QC?? zgF6IwcbDKH$l&g-!QCB#y9Rf62@b&_kNof4bMAfb&gwN)tEYO_-nF}SRafut+f}GJ z+-#RJyeJ|$^^kFs;>;w|)};hD%W!;!0^{gT>0`P5o!0$VL$Z8qtZLZxmn`Zg#oa$^ zVgBgf9vJP>?jaIT-FyO{Q#K-`ti*lQa*EiPEqrOG4?s(h-9$85gd6bd8b~g8d;4up zhcf+O=#6uTgmq}r7-7>Wwc51R8LxI_HUT}p^}%nBdwmwV;DDAT67KKh>2NRY>+HLj z$}OJdIjB>MDIAbunpdAW zC^-6KucN2_yDV0N3=)>O{tK?*I`s5j$B86?5mGx%$ca+gj3e#~mA%Z!;l=a4F`=S3 z5=-f1-)ktJjM)o3vv97>?{>=8yeSrfx0T;1Dcnjbe2{Rzpo_~LwQjO(MzZ%AyHpR= zKDP_*xgPc~Nv(1PWzTSP#1Zy0!MD|`&fu#|!)=_EZpYZUY42~*VIeHt?VhaW64R{& z-mmt0jy|lRVbbpHZ9S9n-&Fj{&F+}rb2>Rk>~dC3`l6OTrJV|V2+Oy*k`o+{Fuayy zE#l_-?MYVml$llaD51#L!NI#@=&tcCd(Nn0gO;zJMgL^(Ub6cN`%?jOCG5mQK8$u$bjxug3jU@r<@Dcoj&+e3!VcIB0h@pfcmboXnqkfYy*%o zL8$_VyQe}Q+rhcHT=g8;q`h;Trh2@S_-jTV_~qsToQiJh z_;_(2_Wp@`1$|!7fd>S*e2$8>OFS{rU>)R55NkKh5K5UP#2%|VETjxotutCb{$8x>cLuU$s)_(bb=tiAk+nR?ynBa!2OTS%P*ICkfeI(jy@`r$Y_L_zb z(mUL|bTTjJv;7?IY>T*WNgQCj7%$>EMme-j7j^j+hyooKYEAKQ`l+qp6ll%x!tc=* z8z9%PNwdeKkxjz*($gO}Z?@yR@HUFrexhdYH-V+k@8_74y>dhfrY(0~Nv)^%V~ht6 z!d>nr2T~L9vad2mi7p$CJt)3QDBbMa3VG_paE@Q;taS5PsTS8nVj)jxi&jQezepW+ z;CLd0d#%bl&uvZNRqyQ=$$Rj58JtVdr&o?s{Y@9u1GykE{l%AL#;s&`7+HNWBoB#RJHc7AzG4L0BR@qBBKZ+ z^&^;h6UA+_Bog59CZ_8Gya9-yVF&uqTWpVd6~Z^K zFFAo=4hsADCZTTPzJ>LrX(+3>RO-5k;l<7M7Ot3^M6@x~B+q}^u4ze?f<<=J=f`zA zt-i$c116<|wYTO|v*$ESzF7s`M>h~KE7z$FQiVM(uzvo`wLJ%0+2*TxEJdo`{yubv zVfWot4Ezl&xEFlX;EsG)#$7(l5{1sqlUt(@ZJTc5XuT5oS&I!4)d=kNmx&azOi?1u z73l^M6`c3c7-SXpgyFoyS@5(%wFCrt18I|Xo@{);Ipa`!PeUs9&)@!Jb9~<&e~W5_ zz}h(U5}KFyz<9JLAZq{kMv{$KutAWQ`0nI;Z$!9=CwP);$N zCSeh6+Fc^m^8ZMZB9c2Z7tkON5bgM&em!Zb)-G5$g5I9*4DHjMKBTJRn-*F%2;#J* zOzIrI7(h|$c8&;@a(A0BpWC-^rCEAdOMKWcGh{lJqO;&FA-mu(m}3G5_XWe(-nyPC z`*_hgGDUgK#-$|9c|M+@az^8wS5RBjQsuqKdv6bt&_UIQ_Vr_Fp@lbhq=2}69#Hvl zorNy`*oP5DPn$VGDz-gx&hf|ck8(W-5b#s$?i@A&XAi#ozM#F{m26O z*EThLnG7=$$8rIP%mUhKo9k z2jPl!oHaBu!rq;h&D!aL9o4|Sh-z}l`ni+~$biyQ-V3}l+D=vXT&N_@8PTLu2nh#F z_>*l`G`}z{s6R&8$9re+GI=X%1;Nd=?RSYL}XrKXj->{?6jNy75i{ zIpv_pej|&^f8XC5iFHpT^O?YA!W6hxGSl}clfNA0($AgIk+YkJweL>T)&59mvz#R_ zlecq{GpGF)d|}$VOT?WsJIpk2O)BdaK$D`vCEc}3*R^!|qufV$;7haks^j#NqiRT5 z|IP+Jq_V@e0EgZK{Xtv(3~w@{F$nw%f1XEUqT=D?>BNUg3oh=wU&e#8{Uxj&eoW<; z7OyEqVC;gQw>J?`3DZWvh%>66&gD+bB`~ zZEXEk^rVHGdx2Z|)Kn>wzCe~eiVp%?mXC~f`Z=iLJlUW@)M&}!(@5@W&Nyxt99PA@ z=9RQv+6V`UJW98Li~;6T{Y~(5ax`(SJUD0G_{mECs}HLE;4EzwyeIynA)Ql)$e~s4 zBn%Lc|eFkrb?WO$oJ%4EJ zN$ZNxubp*#bvTlgA!tLTL)E^#Q)Xa|=kjDFB@`g#_@%x{fvI1xG!R<&#*<&hG}II^ zahXVcOz+fE-b*VuoL~LkOx5&9>qt?>8ot+f=4+ASvISj=)T@VCZo+bVfGf&jV|s6m zt-m*%4q?^VPv5?^HbFZH%&I;}+Kc^=XW}1&QMUO_7jvCmhV`)*rt?A1OsvS|*|c{U zy2F!c>p&?+$DznHmhp5>n={%wLtz{j5Vm^Qh~SYofI3#@cqmd!je$?WYf&0oUw4tt zMmaRn2PVTPj`=BwPOfSpFsN~BmxMoqY4sBsm#Dg$>T8LZjZtYkv!;08iV1@k%g%Q> zYeE|4z=gz0ZKz_chG+~^hSobn^QPmqLWS(3rIDT7i~Z+X|NPG*Y>@F#uRHGMFvDEZ1Vmqy8R&0eywzV0e|8b8Dp51w;kpcnDjk>n6V_(| z`1a7Y{_N~_Qm@JNM&teao0+am@L zgjkVryB_pMEDC~2hH zRrZ~!A!5*;^2oe?3sZkRsXPDO0uN<=--Pnq8HHU8)?p4jb8^!sLC43+50qOD^$2Mk zi#NA()akXPW;H9R9LhrNIjqql()leL)P-an>ZI5$k?i-Cuu{>{ecA@840N1EOm?t+ zAueK>N-T`nP`-5*%9VjUC~NXk56nasH*2m?WXr|G(c_F63?C@!siPIfS#mpwO*y~E zC*H1c<@(IUlGi1|rD_#y^0^_$jpRuMFA=rW+Xx1>N`^aXE5t@}^}fs7`Pv8-eD{~E zH6GBcyM(TFVw(}uO~8aGJ}+<*d)@gUT5RYh28PKzX);z((|EFpMkh`9{i<8%p`%#6 z^hWLE8|C7H9199ZnJuw~N^}4=dc|VYaWoVoA~S!Hrx+EC@%LNw2Ato?&I1IgYVrsG zki)D%`-81=&dxh-4x2#~|8g^{uxQ2acMi6m704cgMHyTQe@hRj+LR z7;V9PTrod+Beg5W2@rdEFpA_x0I-PXF-qDlfRJzGZ(_&gK(Ys~EKoK{9nxv@d@jR+(7yiMH{v zxth&Ia)+)W_|ZjgB8~Qo-#;OYMhHjN)HRH9y4EJ*UAn@8eNI#@6m!kr^LVJJ@RUlc zMfoDNB|*0Nl4CH_{Po4rED+CJPvjQn5b;Z>xD4oAejD;Ghj6$f;aFb=XY262UJ9f& z;wotx#cP2@GrGDh$$HKIoAj<0KE%^s8vna%*61-?cP^qCs^V5pkp9mwwYsnEX8fn1 zo?ibPWaam!&3mmYQQS{;RM_>@3iybHUUdy_W;~m|5WlFf7y~uK@vE17j8@usiOuo{ zO6FmlIjX_j83@GT%#$?e=s97NS=g(nR7Uo~s@jT_t{1gBNDN1V*{&WkoP$YScm`;` zsNQizNv#o&Az0A$Nsxcie!5`&y?DcrX71Qc6F>tBxW&PsBDQ%tEb3vwHBEsr%Acab z3P2P65ooK#KvB7!qO38#{qkicoj;R=>dcnM^Ya6JH}0Xg!Dc^M4`asnu#1giIGVYA zPTu;1+Sw%`k?oM5?gf;QsGodcNwXRXhmQ%$YgFK;{v6Ab*l4@FRMa^B@iV-e-wh_I z7GQE&tss&Wg|gM#{W{Do2%moQ^VceA5M$dWn5mt6xMp~A*M==kQk&0YPC_T5B#fR1 zoH`f%$CNlWrU6yIYrUn6G7k1t1A@0O{6&~9S;AIx-S-z zhK!okK8;M#=Ui}l;5l$e**tYpj8a!pPB+Ohbk|gQmlEf?Z%m!wfLkpxB!)h74fBvr%6Dbu$M1Q>`SLU? zumBrL7V(C0O}?sDvVk$M+2uif0g&Fz1u;1IOG-LkEn&DuQxhNV7=j852!l zmb}VisKX*zMul}*hDs+#r!)Zp-`lf%3*+0swLaz7Z)m(;(CAi-s?6Dn&==OJEjEuo_DqcA$V_G4Ge zz)F3^i__hHkzbja)z%x()v{{OkM1g&v+`)VtDVjO@cW#cU}QSUfqs6ylzBEwWD+Y_ z%8;ehgh@;6Lnef7nh>11?^5hRFN7Hy_VdoeNQB8_%~46KLB~JVu#C-!&b+Z&XmII~ zem6@)=M8+PC&SQ7Wpi6yvMb9N+?Dj6(y3L}0JJP$Vjk?qKG@d8$?_y}{Fb?rJZ?N8 zPG-)?eB2$G_!$?6utZ2~ZYCoYM$kM9TiVOX?QMAAfxbzpriE-JTDLxa4x>Kg5sH=c zbLn^;^Cm6Y|G5MvR&kl0)1AQjb%YPzD}wr!x~p1AvZ(e99sfkLZ#)0JbxL0mtcW0w zR8aA;lg!Q3_a0AQNay}Oo?HN8M(-tL#A@#+CO27P9{UEiK7b^2+Sd4F8t>_|d*)|vEYp$X-S%3 z@LO%qGQMl07w8L6<%2g&<9z#q(|_!VZ6CLRhgX*kP4&EirTFKrUe3-!5$dQUI2{^h zb|I7e8;0N9x>?j!t|@BS^?R^YIbIIku-nsFcdmhHg~Z!dE_bwXuZBnKK6 zjGzqs=Sdkn9s7Kx{5Ksx>r>||;Z>bXb#|sv*{lTXRF9S6XgN62qQR!6)pa#->bjg=8$p;9I(Nry@3L^^$mU5N{`pNjPuvPOJ@%pt z9Q0EYuVF*Zkxwy2j^T|{Vt47gD-l?B;b`UtHtDwD=W>BQlcsAH_<`lS&sp2hqx_LZ<=@BJW4w7eOM>^52fCqbq@D}X(=ZzFQ+$P){whpA7sTjTqZ9Sa1v6f1qt!3q z_0SGXQI?n@S_DzUM&`Eau@;&T@Q9gU&5mCQrcI4_Osu@p5Vsg3Zl;ZFGDD$BD$oC% z*XI<~_c81}-Abifu1$mz+-_wF8qtvmD9C!*q-rcHynbWXH@fz-$4GqFRWccjKkZZ~ zlgwY89rc}oM!v_9#e7Wqh;L|}y2;xzQvd$52UWc^@X>TND7QvbNO(E5?w7dn*nR;+ zdZoepS7G)m>Yw@wYv?O;9n&U9yXd%H1sfxMZO8`SkL98sDO-wXNgeokA?9Ka)wFga8^J(qv%7E8tXD*HMl z{N;R4$JSnI2+5H&C(WxhBAJU1x2~a4^iJ<<2nn4%HW1M+Q=q>p1B%X8DNOKAM@!@T zeLztoS#adoZy+xY7sU3MQr3icr00uwSu1!&{(%I>uSEvp#1?v%-Q<3P#NGsBwl8EQ zO-a+*5@s#Q_CG}H@L5fA9OecfbR$n3*R|?#qFZ?EPVU`qK6%`vCUr&nqzfR^@H`~I z(pZ<_L@Krrv=P;XuB>&#$4*WhUZXK0pU|EiorHpX9kAfSF<^|LC-5eChHu2UthQ|7 zES;K;zg2p-`7z*D;IE|t_*6>?;21yE z-Jh+uEe*JRi#|$Dzo1|o?KgD#IpcC%C$NvW7Mq#UcEz3UWW zP_caP1wVH7_IZ-m75Ml01liq>w~gH7x4*E}y#!%0_bb+`JWy2wK5OpD5pvTA2CN+D z*`NMiB+Fsz6dTYWOSIvQC8N2#0+EhlnV&837J+^tc4;x%Pd1EFwo+~~O-Wgy(36Ap zzY_*mX&iDyO^>$wHJNkjg{v>tTs%G+)wOXb%?E0-Bv4{|JHE&s4|3q zTcI?PJbJ_!#K*IPAC;i0Q zQ){elkH5Y`h}InvODKf;&I%^SYzDI!K2*RkZVURH?Hn}~osS9OqRCM!@EPH{P0&93 z=Xi?zARU3GTj1WdtqS~XRTcJ49{!E*>^wmxCxkUdjOM~+72-=XioDn-VONhK$)N%z zMAU3Gf-mL4tbl5x1M6m0oX`~k^3G=$s3`$&y^WHu4xE1on1$d{vy^%b+JmyG1gTVL zh>_0_!`cb7ItIEC-}MV_+4|simHba(!)^$c;$njvl+pa|=>eB(`tz4h6!d6$h=^*% zf+wh=mVZ{JBvFPU%BzvLF{e{_De1+?25H5ynYHI^-C;x*FH2Vu_JuBf8e_$ExC%E1 zQ6xrm>(Ogt5-?VcGljEwjm~INl6Mk8zl9UZh0`>f27Bo|8=2ck2_ekbaA+@ah*xfk zFGgwZG80g@nEDSXvZaU3*D0bcwiJ+AcOcE>EScJ z*S42@WZCUK|Ft0a;4^N(vwPixoU3)Yc!cY&eT`8`*g+X1y|`V`ufzjpx&>Vq7s$2y&Add@HVzI7|qigH>r~p zX-hWdKH!b48|t`CFroOW1)YfPr0E9kOg}Oy_r$c4GErgmv;kxab8F2W(*R=RAs#c^ zR_!cUGB)kM&Oe4V<62$Zr!~7eVKiPPJHlmq*gu> z?d;@THjNWc4TCF98oRxUA?vb5p`YHVH7OCsL19@p3 zxw$nx3;)+%=Ir1HYU?YO25~snyn!1|zf-)uCgYk%+1wFwGRKEdce}e?Rl#LUSY7+bOt0k$9K>T6YoJ@ba5Y>Gf zRY7b4@pQFTmKz^^YU4`I<8?@9_G9flsdP0C0Wk(E41cDz5$qvzp>)SB7WyJ#4|hRF zCc0+#UGx*^!uE`;`BtStWi|O~y;~@ABa;l9Y6ulX65fv#NFjQn&*_*D&E{hF+8QB? zFoCzk6)A;T{Hsrxnt0f_HkMDRvZm@fP&%h5m8chscn2)@t~4K2Uoc6X{Y25<^CZBW z#tm@Z`MZHYL44$Kx$awH zQCJ0xfrUXY@SIwwuL0N%VO`=B9>7`@MgoWc{sA-v(=F8RwGji!iUX2~D(eQebcz!g zXzfq!JP)bOQ`wqwh&!EpS$O$^4x^KicV5TB2s$&~Hxl{UL#s-88#7Y7m!y9i|Qhj7n1VYg!lHX}Nv@p!2=4v-Y46HU> zY7pR9hWijF2IWwywW606;MIBp)Ff!lSgpopJsPY1Da}_XRLjMX+kATb!etT?cNQH^ zO)Jkp-$Wq+E5EUI4G-CJfa?voU-eT1XIX)^T)|DQHz?xL=GIgKoMC4)Lzn*Bg~4SO zIm(355}WAhDstyzJmrbyHk~wjsPYA2V84|m5n#T>lT=+I5^rL$yF<2$m5xu-qbtUV z%sQ1}er2Sb3efc~)E^P_s77FC%?L zCPy@z9(Y#pfL2Qj9pfH6*DO;#0j(pRhPO13W+%93xV_xG46VAZlcoW#(MqKWk6XEsI)fNJ{-YSXwQnV08-2 z2O+@{6(e;cUwX<`0A!OdIJHR2(5^;^`|_Hi6gIF#<8^m?p5ijmi8HZi%Yuk~W3;V+ zA|J7h{=l4`e<7j4y#c^-PmsJYz-+o-vHM|kjC+l)=-2GiayP@!wj1iU@ZX?N^buiV zeIz}RmT1KrR%R$$Q31}^q!2yGNi_hVb?qYEOoOqodIe=RDY4`1fEKTM@Y77=-TI^& zc{xsNLe<(ZhdZEhbf11xHQ#^)nhVkQRq7cebysUhY3 z_jDO}WOhWmZIk(Zw?e{4VW0OVI!w%F8G4jRQTt~mQVmhtOe5mf(FId*_n@4&sX+Vk z)N%cT{h$80aI<4v_9|wJ<168ovY=BMg+y}*RM%! zdqiM#H#yjD38pP0l%$@|#NJSaY8O^;0oTt93hm9@sz~0tmQW^q7!?&3xugm4yKB+$ zXkQ3sK*h>M(pOiw0--CTY-YUMUpGW_=OO7$!q)C*Cql|iQ7}WO!FkjLiYyi|2BUrz zUQ5!7(wJe@i1rHovWVrPN@&$#!EBL;x7K3tt|w(7c#$pEf-|Jy5!B)Z+eD$m#PC9v zrnu|?jk2Zp$&Y-H6aYBx{MU!zzNi)Nl4$}R0K}WL(C*ZpJEuq}4T0!xXTQ7Qr1}|0 zpd2Kyl9!Qx3J<2{b-Z+@L&lj!jwR~bhj&B_{aQtlCrxS%2nh=+RWHB6TRKU??r2zs z-uVq{_PUOe!v3oGHWYJqN9|nVvoR z3!}c6a8}EVJph!FFT)Lf($q0cafTC^zSA<6kl+DCa?1}pC-L{9D#J!A!i&|*OWIK+ zA_f(%cx{lV%(&gG9BX8HrzOF_TCe|@d;M{p zD1Lopyr$0czV7W5Zy^#@i9p$EY@q-A_8@j>V{j@EIj=qHnlNR7w$RfoixG(MUaXNC zk(^}<2=G}ngD9`l9-##Qg`!qOk!k>;kc<^x){F+hi(I{({jr9*u7XN)!QP2**#lUm)HKw9kt95_?2vlra`#l3{HUtp~4K)DGe6Yk zX7r;1CaF^#O)zV7WZ7#TY-afNrD6?ROLEkwGYv;M>&~5;X2>FH++Rf5F5wvR&WRHU zYD`B`3U)RpVpiBEXv^9pJ07w^FZ@2XW8irgqgyQ~?<20~cqW?ZRmNA7g8cb8;~~Hm zNopF#XL6srX#NsFTT}6Y#c>VI5hfUU07nTYRpQsI2VN-PXdM=dHT)CGR{_$|l}=~3 zUje!LrXUxR>ew0=j&=zV)DFd)f1ewU}85;S0F5 zEfexpCPH7nTS4nJ6wL$jX1M`YhIPiwj9*ipCfl9I@vE{UUC0e_*`i>Vqq()e|_v@|jsJUoV6qa-*&=0U{CdrpE|k891`holwPW14ij^oNA^V%a{<)hA4DGjFldpS znW+CD$H5}ZJ}4$4K)2~+By1A;tA+-o!n`)on?lbYm>1miIlT3wz8`V&1*a-?MgTb0 zErr~+oJgtf0ThL>aQAicM8GR#Zy-h@=;eNPAvSIY47y!It0W7VCEIN%=rMXPzvAX| zFGFGI$ z0Gb4mUHB}>57W6pU9LG?^&q#)1x;ru?9$Uq6~Q3`L;khEo@?0l)QP=l18d@EqD*$J z0gA-DNLZE(A!qu4r(U)|6-(Vq-@ND3yiPWv=O4YtX#L04vc+073H2!JvGD~|G$GCW zeoATmef>1r7!binLMuJx?N0pf#Fmf-=fe0)yR*sVdHhRstjj|gU4gqBTd&HB1e{3n z>Ij&Y3tCDhKB?K8b*r!%OkI7>UP%H)dhgOm@NQ;&h!YY>QeEau@EY1iYkm7|S`=2Z z_5hdEExVqcfpxECor$jsJ(E8VR+h0QVrxhGz1LCUTnskQyVb)aFoPMnO(4(0=|>pE zDVu>ms^hMJWpDgkpJy!`&_cJ#zK*l8oI!S=zw4s9z*fgWg#mG;#Y_MIzzr~Gu#fzQAqTI<^x3uu-8b-a#&D!}JFCO)&PQ>B%vD?=wp^=mi}aRz8goz)rrQO)T`XWECTf$#(6Y&k~q4Qd@5|!piib zXez9?XY!H|AhpZHu`C^-yBd)Ffwu$ne`sy@Z@k@Kt^X#-h!b5 z3$}enT9-m7oLus>9OOZeQI$c=vCB}8_8(cX$wJZ_kUYdowOo`HU62oIs9m$EC?tt_ zoJn4K^-*V-K+_MaX7iF8yzw>Y?6Psj7Py6wcJ5{lo8dDehPR7zyfrJx#t$_bKh&uF zH*W3!ivIW82J~Ng#Bm_*e4_X-kx^0p*3jp2j6O;rD*%8iCKY%KV>JyVKxlM(lmrAT zM?*nw+s0`QV|zNNpg*7M7e}Qtpq3}9X)Wz`Tp35 zBOov|T2)6Jw;lL`o`*5fbC%Ow#*rAUNdSPZO3tcHz^9}?KE~A{kV-)-ivc$g0t2?# za79yuPh>p6#qG?ZT0Vi=mtP}g04|Q`J02r%HVhNO*BAsOdZ;i;m4naz8o1`9-y^0X z>@$7xs8cxh!c|=7^A)k4Irb3Syc%c_)l1fFf6BapS^KD>l46AaG^q}RIlS2JDR07?-AtTvCdSbIHmC8mw#&aFGB0go7 z;34_I?q$b9H}x3aVM2A8*Agr8)QN^24I7_^&5=TS;??e4A)Yg!ev}qQolC9)}oO^R8?Z>^!fLOo@1PBi;po_xJ+`q{scdN;os&PTg%%2 znyIDpX`KOp^MUsR(-p~Bwa69zhZFPPteD(?075^kD|way@Dq7dimbq8@t%KfIHfCQ zzNEi3X4DUQNwNAZ^M}`Bt4Ov}>-NxQ#JcH(zc-mzKHG? z?c%Uze|n98iQW4l_Gs)SDLyfHULVnR!no@88E@0CmBmVBBf*@#8lNMW+aP9h1d+nL z`>-{vZ$Dht4e^t@YMEWTcEk$qRj;S0J7k?mqFVc|!m=4!Z zn&A5gyleU@;(!RJcqvaSX=8cH&VC+XzWf1P)M z&Z%U$v1WQpE`}}bU~!C(Ys5)3pPYN4nE{qu$OAUA9DrLvrF(88U@Q>@2|s<^GWMlH ztOKrn%ZJ7>&>Gr4J^yC z2oa`zb;uYWsfL7@GGDd2C|{m6WCkKuKLS`dw1_jI^{a6lpJr!@ka7v8X(klv{E8~h zGcof#^ADKol=l5&Wq_Ht5k4B<&QDHf9%o&#hzdg7HnyTXSbr*xec^LYJ3TFX7i5 zn{J&G9AQG~yd1ZziJ|3DSBRLBBWFe$xPd=gm0oyN;4@Ye_H-)p3<#&`EX^%4N8sr< zw~TUrVJKS3lhlY)-hAb!p`Y;$mB*A(yZvmWb)sf5B1Y_JL@|Qog6|n@MOmcpshEti zvbwHnn%_~-;)O|8{;aW4goS3@X{K%yL`$NM@rtJ<_jI*|pr#J^3%Zk6*QgvrTA4{NW;xg4Fb9AZ2LL~t=<9%L2LXKA#Vjp2mHswD!Vw1mGIZsj5=r3G z*4jv{7Lo{<5W7b1MU@pzPAt}kd5AbdQFVSivZEwfwh+NSCbx)+dMIzVz-)JThUwd; zg$viOu7hT(LE1!;5~800E&I9%jS#t}efQH+l3-q;z3rn5Hz>s*|GZ{Bc4!0qBH84y z;_%pO+qWd&x|UxcfRXTrLL(mv$^Va82518S!|{YZMmP8G0T?{~qYz9?T=X^!3;>|o z13*Bx|F{sbOx3x6{qK)*KuUl}j)g>|09Fm=7kzTX+g1@9dC{Vm#aC^FR85PatnF?hoUD@rq>p z`tZE}myY=VXUqAJ^*;xc>9jo7iM_~&D*yd7IA9~G82}JiA^{NXECCZM5q2wB0GP8l ziGEM3zzO1# z3e5*%)}mxEh(jZuKj7gefAjzeYi(cXyxL|jYkDXe;r%f^P@50VQKK8_DtsKtEvj>a z?*w4iv>lg#&3Q%2tm6g`X$F^T4}N5VU5`IlNSL|a4B(gV)e(P*t}_~4?bLr*-j+K3 z*Icr)irhUwRLqXshy6g*=O~#q4~X;WZlSECpoNwz2G0VJ7J%4VFr0M-nyyX zK=3Uwn$H>RwE+rr3)n2+ZLLXTn#Q&L8{h(JF;jWcnl@;{YvjLB&?PSolpFlPFGnX4 zZ-OaUXv{J$2aiO$daIgx_9XJ{uk`2>3q8t~!N&T=Y;(@u)y={7rOZ%Ngpeso2&(5r z^TxCMX|dt=TD^}x{OX`c&du3>C}_Ye2YUc@CNGT=#E)@7<>qTz;CpCT% z;cqkQ^c%K!3Zky0AOPbww3d@>4}ww31ivl!H^eAJoDmWEi=07dKmp_8qpTxQqBqKk zp(?B&m5Vw#oE~dgf8;j7Cw+YFPWAASY0{H{yP_yT-#L(PsUv?s!AelTWZ&*j<6BOf zc65IfjIS1AWxC3ThxeDDEY<+5QB&!D$7^sPN5!;A$AZlpG>v{Xg|i|deZFCc_58KW zCs?uuc7?Z_U*=mDI6wu}%(m3!N`yB!Vv-g8xw%EEvyFc-MZcyK``lyn z@=l+7Rq@rI5n6)>dpu*#8WRn&;{@YiMevvW6O}rAqK%AiJNTu{$4Gtx0RVtyV9s;Y ze|OQ6!q{=>i42hd@Lr(~0CH)5CrOROvKjy=<_*9Gf%Sasj{SoB;A0X76qS(rIRpXl zJxWzQa235(ashzP;?bV%AFS?rb*>)-1f#cEIhBRNh+>xPc}5RbvfuWU1hsW&xVqGv z9&1TOGD`Dn#`ns(F)OfguepD&8U4}F+ppR2`h~p3lM8~HqlVf>r|%38+CcXahl z45T9n^S*_pV(g7{4vy@q+wRA+x-o7^hrQCjiYOWI6B%Qd(PLmGu9CF+;^DLaJt?+t zXDDYBwKu>uAp2}4h2SRlG~nd#gK5P_FHHQW7yhUJ{+BzKp!`pV{68Mv$2ZFp@Yf2|``qjBCSleo(+8C?y0$6#<7BLooXxOaiUY%vS>Z6aNSR=b zs!cdg0RJsg2^{pcAQV>(IL_WS23oaK*LsI*lFt(LMagPrRmTjaz_d?}xaR zz?>I^|4gy}tGMES?ex!)1^TZVIDq4C6@58D4umid%30wc0}ez`M!MdlipBGYNL;AK z^z=9G*JeQAaL~g-O!eTq&;#G#Fh98-)bXoVd#YN&sMTW%H}S1(fS0W2#VN$?sx6C7 z$(0vSXBvjj2Jo4_-x`a~iOK6n;Y4-{WY%4cKx};6WN07qGW3fM3piDB*g0c+O)l;(pJIJ1DnXU+CEl_IQIw7vkPb;Mdt?>X_%9|d4T%MIYkdg zhxnV2Bvwii7J|VXV_1{_snPT^2>(MV!2CzA{C^9jDwG|N-~loTSUWlf05;zpr2_yC z0l;PfR^|f$2D&`}WTlVIJ8~EM9-yOcptiF0@IPz60*GY*(gupSgp1^h91Th zftdjJ5fM=1me)h^VKy*1k&Kt2zprurw~T?i_^P|6FL{@V5X~>H*@HZT_w#f!>w53iawd!T{Qz zUh)`(eR5)Tgk(=&d_Geah_<=?b}Sl?u&s^PkW<#5s5{i6{tZ9SjJ;@W9fXUxETOdo zIX9N{Y*nc82Ut;xq=UIJVH?F^3?gOxU2;;o>7~JUc)6O}9uf!Np3$^_1KFeq69&gP z(*1{nzj}DXHd?TcQ**fXIoT07f+U*=!Lu_DW1wxN5Z2LVl%$Xd>xJM?;l%ffz>wLf z<#Th%NdEI6ARLvRCYZKN?9sPH`Uz(pvDqm!!*ts|gh4+dQkM~|(1MWJv5CsVs7@d2K|ADHUr(qe+aY6-k~*xq zby-R>02cJl5$ud`jAiRw^h?iTMZ=>B4aJmTiDKd*;S_Pr=A4c`GuC#ELEy*2S%QXF zbJk)dVykz6(EPLh6oY@hK|~IcF>$Snu)NB)e&N)aLK6)y(rC`hRL@}%)FDirjM})J z#a9kr8c+2dqUOm0?TsI!DvxH8w@-Y;e;N*9{rM;wy)?A+e*9nj#wLJmRb8{0Ap z&nt~5Uw_3m;HI3>Jw)jfcK?0nA^ldCy-n;4hm-d5MCf`~%kqzWO?37|vS6 zu@VBqN%T97#dB#K@5O40KnH#3jrjl>0*p~_G$ngyE6MbdDaiD zz0f9|ujK)Xd9~_e1M<#!vAq;wl3GQ>TAf2n!Ssi0X|_Ul#3RZa{5TjSVM2MigxvBQ zYmqvmF{etISSQ1JaUHdpmJWdmexX57P?t%k`0K`0_+Jr(;GzCgUG<4GW)isFd+E@Q zwXX{3AF!;9)UMfTI!Z0ws2Bo69PfV2gs57S z(@xIQgEgC*)sQ8v(5PUkanXEkRYS=cZ>qaF%+-T~chf);0zy1AGg_`y7!Vf_In)R> zfeKJ+|81IK0P5uEk3Crv5W+&h7fL?;%eSCaLjY)82B2a9U})F|10b-!gTevmb7*SH z4h{xhBB>bs3eoG?0J23n2=5?ThOr5;SH9-w{9!G9F4xW(fk3doc&xBqNqla%>u^64 z@^7yiIIPCn_jRN35XbT{>)%mMpyUk(zfY!&BCtqbe@-(B)WyG;x72di>ul*jMyi++ z%FBe=gIX99@f_4YVcCCln*KK-_LtD0c|x_BMqJK2QTd&WI!}|VDFBrG{+|lnUuuQA z{PW^pIzo5Iie3R%O!a;eYl^z+Ycw?vYU#M*A08_i4Ok1$ROoEq{d)3w2Cfy)iiTw0 zQhx4tDi$lAcZ?K7=0hS?B*~uS)Z<*T=I>%%xcA?1>!!=S;uo>pW!WwEKG6txpyYnf zD|}emNtwJ$-iHHAe2?r6AKs%PTbzUVV&n>TBtM{pR23DxQBFbaeL$SAX%8RMYNf}? zpS3$a^Zrcit-~yDWokF~IlmNP*o~SN*^)w>zeM{da`85t3Or z$<`j$?%`U_Pb|Lj1RQDzpSNu1C`{<&jiq*ZN6<;4u@AKOL>Tr5a%vi_+GN%OpvRrc zoC;o!yfe6CdOAv)!4@uwc$D;mzde7a23p=8!YQ1!cPJw3c)dmQ$3kY_onM_9;TSj1 zxN?t?XmsiszcvX6nLe*jS82hF`1tdWioJ$!ERQSCgHnQ*9$Puhp;7R z)NqctPnUR=cX_`gIy7{cvIYl|-ZZ|-eish8X;}^hFN1e#5j5S%yV?Rs9K?^bS!J!!$paY{pHH#wk9zL~^fociX2^ zky4kh#j1YWT{w&!PV6#z%caqGu)HJfv?AGSrE=PlGLl08XQ+loPczJ{lFc-ve^QI; zMJmRaLqM$(2P4;m{{YiCvDVHL%UCx4(=3-cO#GMv_X27w%RmJre}l3AlJx(1f-nos zSa{p}M|i7=KD<8on=1P|kwN_hFbQJVXa&QbSbpN<0R&n;bL+KFXKIP}Hqa?i)4_AA zrYT~!ry{*ejQRPCIGzM!;7Zv2T#?$KnK^FFky(}<{v?+BTl#&hvoGlRNaRg@iE41I zP(hoag8mO=`40-t6drIs0db&L zsvN_!17Oizqs_M@&pwsf?y?0Q%k|MAe3=d}s?kaO#-%>W@3eH$nVgs*WJD|>zYESa zm?%rPV8gStB=0W^+zpAudJk7)9?*WPkRKK?xQ1x|nmoAB_Y%jqc6{~C7y}GrQ$7#} zftqz4@f^~BnDsx<@qgt1koj0GL4OT8+Sn7pD_Gp3|G4|+ zr^jWKQ*g;&tC=k5zP)?F;YU`j=w9V+J?I@v-iA>j@#QCjyXJl(H?io51MR0q*WQ4a zKbYT3&x;q#COwJ@Rk`pu3E{q%q%KZYGB=tS(P&^i#VRD%Z`x(B{Hp!162->(;d^N> z`*4y(8?{Yp`ie8sQt#9cj{^K5O0=q5EY^y}4HbGgdk!Y-`a8Byn%s80ctZ9dgkK93 zC0HWG#(}(f$xZaxMWL$KvcCfkU50%rj))vo3$awiqJ?~eWFPfM;oFT*Z59LgABqJd z_Sm~tg?KtlzrV??q1y^`@3std{PJ8@p41?XW2+ux?vwtRFm=gs!17brV<@V-5zgCL zvgty5vcC7^->}jjWp$s(c!&nVVzp$hWY*bV#Cp;O(Ag*vTETNL0%tEpU}D_Umj%p= zWcB`F$QAJd>i;Jd$Lik;CKi^G=L{Z$G%UtqVE{l|2ZazUQj9skU26wzAYTRnkm6!^ z0d)12G{Kumt0kn=FsE^VSn5QG3_pxs-cq@k75xYO;|$MM%WX4&a(mPZLqvvY@t$jJ zOA21qd1TxN9jDV=6W+t;@%Om}f=bM7e;(!U!)q;~8vlDs_TAewkWS!hx>zxNV7%L@ zU`4UH`28Ct9s9imB}ZAiw8?i@+HBSEdR)>F9WBCJwlXS0Anz5747JHxMLRQ`mpuDA z)rZCxPVaGANiG{Ds!r`mXZsD5sX4Ba5eWzkW;~I{c=|-C$c*65=C5*jA3HLS@`Z?s z@(sDz;v-dQH8mTr$XI%MD4zRRL=WhBhbK3O(Dj5vds=DR$U?I{`^junT<=E#APo%ye+Seq05$+41b}S;KqDmOStN-dy`FD~zQNIqXQt5Hm@pa& zz;=qC(uV*bNW1B74_)nE4?*_uX)q7lS4xK@aLambs8@EGyjOn~kkUHcy-UzfZ@LH8 zHhFN912S_PeYtC~lR!2XWi!@deFSu+9-wJO13JIlzU{>EB%bY)5U zDODPoZ?_2+V9U57zb{e*FJ6u}0e|K!a0k`t{~t3a`DbYtSYL2+8i1NcEDTjK0Jaei z*AhrWg%ffW&YYOPX|-#{D4=lGYeYvzxA_qsZIdOB<(r$I{2YOTEpOc$|YT;z!*nNN4VKS3zAM>eXM(tfa)-Nnz?%@d<-H zit|c^2cZN$L#y&r{WnxgFkygMC{Xah8-v=lpE}{}30^rp#NyFSW zu+#1+8-wGVFnQOaMq!cgO_C4|uwRr)yosDtxnda!^>psnW-3h>@{wnW%!BsXl7|ah zYZFK$o#wiGiO{jm>=tSJ5osoU7B^C1!R45b6g96uL&8XdfcYWs1+&51XmkqT3_9FE z5vYI#_3x3?-$eSmc>n7;D7+FP^yi5|UYQ_7&IfT{_BxcZ>-&ICEt{1?I9v^YW9<6u zLSO1HepJ=p87}m>+qf<5iIJG=aV9z%E`6jirmA)2h_1#?Gv&TSOD&VD_ibF?Y!0@q zPo-oTffWUg6c`UG)(-YPpe&Z@(oZmfJ7^*mzWeJj_(NK}J|OQ;gQ!rh zd+u7%&{pQw>im8)y06mZbX{c1d4i~n{MVDuR4Zja;%j=k7cdhvQ>X}>II!r$&!To? zUzwGA8%~64VwIeC(qZkN2N(k$B>s_rGyzrr{{}|Xw5iC|lM9)D@{q99KsE%>t(BpC zB+NOKl0?dh?rH~$Mis$RgEw^pe_}@v2(b|MNtHH0+zb4E*_s_ZE*NU!zK4gg@d{Cx z3#TWda*K4hWzvpfiusir@{i!i{@mB)HX3*Q-lFcmtHQUhe@Nz;3yJRogNBNVZR4HW z+;30?*Pqmd9o2%ZXinL^#jH=a0qK(P)C$Yj0#qsVwwufwEHJPn>@f9pro-S6sAF3d z&tZlCD-!+_3;!E3{kOSCngjDvt@S-O*Pnmk|2#l2Ny0vV?t{knebrNb;cZ&uBME3~ z?a;mWX|{P*`Z!b|Rqt}}nH6IAx^pzL)pJ2d$~7F`B1N8u9K06ALO2jc7XGI8Y~Uw| zRBT-RW?b^SAkqGJJOk;g-Ix3b5b)8F$=B7i4k#2+SkbCREtLd-uk_Q!fHtm$0uC+oQ)*1ATiIg&Ij3O_l(admlGj=RTfQ=usj>|X(W(%P-7RH1qV^l(0AT}!^6ABa z<#w2>sq`1;mqDiu^BCGh+*d3=)`#yvbulp4XljG5SO`gC^?3wb%*SD=>4WIY^|EAk z?M|HjcHUrUdpZ=kC|^mT-gjGuJkv8qU;4X$BgWc7sEwMoSEzz=3RI(Vu1gyv58?Uk zNbh5w7zkYBOfz7eqBFeBt1HFP`B+Tit4&j*_P%k7;cIGVQsmh!VwY=*rPjx?K9z8n zi}AG?kvJ&Kn5&suBJmj*ylw59&4XfMDe(fH+W#dERg==oXv1DxUA>kz9OiMgEwob7 zGN}7qk?BcSg2D!IQpPmESa}U0pVL<}YzGMKu+x}crN{_BzmW;pobmxoN>i~ z!(IB+pte-(c})t{>BuW*3UBSmD#WQT=8$>q3G1o@3}pG-Z@^B!VbmJM3#>)YqI_7E zGAK9plAE2`E?bI2dg*d>n5`3&%8h=4W~X?K$cS{FKs;VY)zba)MX0O0u)cDFaPHQf zcd4-o#>S4ZuHqEth)5lEx=g2TaGxkGPgQ3Jra7{jylFW9%UtgEt_Ha>Vi60GwKn?2 zk3Sp|>geG6jD+7fR1kjOJt9$P(|~Sm{#wpjK9<^}k@-3J*RBHn9^+BQybKT$ZdHMw zJf&n-@eA;# z%#dKyyIOjf$=$y#Q658R>)JT1=|6#~68fs^ggL~KM%%B%8!FOg@-;x6|6tJu)45~{ zv?Wr^;aTPPOh*4KbXVh~`G~Kc9ZaZ~X%@-s>}*0|YodM{uQ@$Bl0D(PFAFL@TdfF+ zt0wg%?`M@lN2|%G6SHL0BZW&8M}?z*S6F(ZZHmbxGC_DcSGB5mN=_SV-EuG#u*{od zF@#8`<-C-et)U{sbuNTo;4B6;{P&;&;r~EL0M4(OvTLJ`IDS+on7UluT*UDgkAcwG zN{w3#G~c2@wZrU(g&L?10kHQScBq*&-+H_&HrrrBmU1wXS;WCmldZ#MM)?AatDY{3 ziM^9O`8gW7xSwNumxz&SR){w5%%=jUkpHzqY(&4 zncCSL2%#-;-D#C0j8@n{728^HS0LCND(Xc<{Gvd08%cIcV4m;D8rVNRWIHQRB|ux9 zWT<(?*as&jQ2(j#>xrh%j<$8tfk^*_Z0~`k4~1AmQWxf$l)dQ1b8d8?#7wV<{S9o+E90(3{~{x--<%rJDS#yv8Tt_*bGF{w`OduuDzXdPryJe;b6-) zWg%e2l^SSivqr6=2Lb?M0B>-M!R>)ipxhj(0^RP!a5$10NQisT*?qj``iXhv&kZ17 zh?#GJmat`kM;2M%X<8%}`l_F7NTZTm{>qGvpO@?ktG-3|;;YJ{&vJ zj{-~C!0sj7@eh^qaA?{)Ud7e>b2{rrl+Y_z=**cC&k>>hFaP?llB9n#&3{ra|I42u znY*;k0GlQOb6uj1f9}CaTtWbpdg5tH`V#0h$V$E!kl3$=6T2;ezL2Rgn_>V(MIkJ! z{sG*VA6)>8YqGM?2nNuT-iIAQE)%us@?vHvTCsr%0($!d?iljA1CXDkz#i;m*6KhI z33A<^zd>HxPC*W4a%x^?-xLGediNAJ87RYg7vbi(GbEHi=u`Y(PeBq3qQ(=#URIod`(DN3KHSu*YbTbWkhThy zL`2=`vx2(Q@1@9nL0WZVls##3=Jf{bZ+hKIwBg(Zy}O8hi6@8eFZij?a3fK3cgA3%Ow_6%|~(710#JB zQ^EVt``U>!X3+KWLv|xA1D2kNz~NkPYrf*xLIXC9_!%nL=v~ZC0>!47;jEmJG*%4B z`2(FFR+3Oye)k`5!n;LKbvLU@+DMF68h&U82Kxh2-LQroPFeW5H@c5tbb3Pa*0UMB38}QWQ}5 z$||riN+lXUjZ|3knyujU{A=_u__3D0)^O5}`m!Vt`3y_L5er}l6=I@ytb2NCH4RG3 zd7qEYTPbd#-8&_?PnL`1uf|F~CIs3+yg5jTw4YfXr^izC<}^C@QT@*2HWhbw+pvl; z&Nrkeog;E>tB;NI-DSPYgYwx?sy!>?0Jom;qfi@#ZnF0_o(iR?z%2V>7pH2&b6B!v zJ*0QbB5~13+qPq3tw`DK?mCX52!9UdQ)b#G*m_I#%@nugL)zG+{J1^G+Vi4ukh! zMAPpiIyjn)XerPquWzNJivk-dk|jQ=ow%*)Sn1;*Z>gyz^7SD#K==$Nm(^T2ugGW^ zy{ZF1oBXfndTSBu5!oFB%1{R+USo?Hy#~kgWQBdh+9e7|22og7h_VZ!5EYxbQCga) zV7; z!644}OyK6B@YY12R->^|f|5n!Sxm6Y&)PW9{C)mvYYpLGI#G-l*%+y5sP1q`=-Y3J z=Ga^s%08P6g3jLEA4Y}K4z>LWgobWk#(p-XX-Y}eZ)=KVjrQD-vH7B5Y@0t8@PzcK z=5jP%@df@&idx;eHJOrGb^|N8+gw86bdGx-!i8}oc%kk3U?TY`q_ zU4QF$I%vkJj{17aUvriII37^gdL(gdnz%*_^{Qw9Wg~9-r$h6?p z;S)1YHHB|OcQySkt^E6f4*ZoeTd2zzd|PmdH?LM~Zk$&8HtNe9EO>J&WL6yZ%HDZ4 zQ+s!QB-3zlqp;$~N)xi;2wQDOQO`Tr(z3Rj7}Gr!z}Lm`_*@(tn~A~qe7@MXZM2kg ze}L+VX5|{z`%|F3Zj6yEEx`dczS9@n&534e(Tgr|A7r=_bv~QmT*d95rN40?c|L#1 zo_3R@By|qc3DtTQs&(zZG16b24uCZ zN$EKgZ13U;K#g}>ZnanGX_Zy1un2U*o|t*EGOkC`_3295#AsHuO3J5@Oi>7OCRDE$ zs9t{qx&NSc{z@m>{;%bpKWe}b!2$qJFYssMR2~WWI3WNJ1HI1`O7_42vZi7wkk|W* z-=-=*z%`?H@%zcb7$9Huny)(|;ivu5rr8wb?TFX9+X+TGqw`^HPaK&fTcd_04vC7D z+}Oo7IkXybss3DF!E`oikyG7t**pAeWn>SafSXcLz9$$R6R;q;ZPBCFPN66x( zOD$Lw`c9fa<^E61ib~-pP_V3RP;;djhsXN#YHh?_Hi&?)gB=y zb-)`!Zi1V#ORi>NgMKs#;p5}5MY2KE^#PcyLt5Iv<+3qEJiNhosrrEsbP3W2Zbl0^ zON@qsg@Hm}qJ^-41w{}kzCbz*n?6rH-f~~+;F92+{&t&iLMC<>!ZqYw1!adDeYl&) zaP*mJF4M$y?0T4NArt&U4#z+q~~;iE8!EJmo@Z|T#y{cTxh zR0uiR`g-6{571{dXv0ag3+g%R~>* zB!wlQ7n0Q5pK7NhU;JHT>525+K$IE6Xe#Lx%D&+99k$ro@w6y-3D=KNpnT^|1vL^X zIzJ~~2Cg#;g=7Os1D<*kO@SIhNugVmfmi1FHOKMRae%|OBe67}A6Y6V&^AFvn?Kgv z7hv8?q<^|VqBnGKsM5=FH58nv=&*#3llAPtY8cK8t>5q|I-w8H8(>Xo_6JM4`=buh zdA!~zebr7$AG)ReN=&nj=i#!&(UZ%~tZhJFf#BrRE0@pwZ-#s*5_(XATO|Pvk-@4t zm-T}m=<_umIeP}abzw7jye)E-0|uK4d&XbGO(XYF_s~Qih}T1zxF&x%oqOiI!PqnT zO($}Y9Dt}=HLiQB>J~7X$?CLEibcSZg(tRp_EZ8(kl|CTP!9G% zPsA-BTXxRy>>-Ww_n(M`J09(A@O}g_#WDt_|tME#H zR*|@@K;h%bdNbQ4i$J*HU-qu?ue*zOwfX|56o#-C4OwjP^GT)1W%GkVtC=7S_JUZS zJ79Mk97d?UIBBWbshrr(7#HW6X^fL-JZY?AD$a3b_Y{sCPg-8TQBeqqj+@=!{%RwP zZdGn=KkZv7z+C^kej$v*{G|@?Q>!w@c$@C;}^GDXGo)HadM^xvL&PkCiDQ9Saes z|FR{vshIK06&&(K>=LoGW1p3Py?wv=VOM&{L>6J&xfg|ArR(@*;PI=s5t$VeZZGGJ zjD7GZ?OQ|&mWJ_qMJ%ub=McZny1*Vk{#b-lDjV+h4QlgIs1zM?7PlaV#Eh(v_6`#UqNOOkgVsTOLU zs+`6@7GPC8)GD;du{u4PKRsO3dAG^A#a@}w=$WMQ2ulpZx5=cZ%hNl{_wAv6ePv&q zD1LimglvuOkzXUEzXC9Z31k6EvUgCg&<`rGX8ya6ml1=mjHxJL0CLuaz)hsW2lxk{ zXbJ%F&=knP18^G(0XQ`PfLhXOjs9K1o|k}RQ807;&mo05vpW_LLI%R73xwg*ih7u??LfZzRxx{N z@tA=4=K~Wxn7!{FhSDeisxpAj7d&S(PuEpMz z6jD-*m>0{+U2m_TT1MnNRGnZ-Q&;)+&)W_A6zV93)E`TKL>6>fZn#oVM1IMPK^9!< zmZj9$Hec1D7jr;UY!gUeV)%p}a|QNRC}a|-S`6x3)HR+LqeU=|R!MW#>E%=!li>Lh zf5!&x##IEBz7#6`-*DEytnEKfsF$~j|1!G&ya5Wd{43ucD)+w*Xsr}kAyK_qR3r8J z6|QxPPbYae4&1vt@H7w%y92_5yJ+vH8c+5bm+~CV{3_@oNs=0_&A0r%kP;?Eg1vM; zI-x%(h#@#CEs->UKOO_q(R>HC9^Ld8mig2oQUk~lD(4PV&i{do{wBh|WceQ_F#gaM zIb(o&Fm!godbcEU!H6+-1=#ydw;(65d?IN_rH&ncOFc;fxJ!T>ZuYHK@7TS3#biwqy!pV7z^xzxE zWFvAN9v^5=`~xPJ&UJY)4DveE+km>wKumXp#tGX~rt0_oan)KaiZGh*SO*NQHnqc( zEbrsy;;Y<(JCvZ*3;<0)vi?7j5~ykPuR$k1-eL!Iq1-97RRTaq0nmor0UeGIfMoM8 zb_Za&3tj+NUZ>f>x{7qbC9m8mWr_oD)=B&@c)EL&^-EoLOg+BD=D$mN@1~HfTO$@>>&b(jX(f27XX?A z3;q@qCI}aG2~3yJ>%@$|#T$m|2>S36tIvoO4R}2Va?CcZ1P97LR7vT5HjjY7L$++m zo8o}dhFKyxh>+P74?}`|-vjlpbJlm}BVu5m7yPCRZ%b9+#+Av`U_=*CPqDA{Wkd@I z>qVJQ@WWlzksMwgj@?fqkRiO=xuWi2B41Bpzz_fdrrC+m(c}=%F)fF(YX1Nv|FvrM zFIH_Qk!g021ong}uL+IBUE@(+Ub&z@bhl(wmy+Lp7N;*D^royka00mn>q$F**^tpq zQJOgmUJ&ONZg4CInL|T073i~%(Wa2xgVpzCNRx7FnqHJd$uil~9EdY9wvLgBX8uZ| z5Fto1+*IzjLee>ugN#bH;U2U+>lY+PMMsDnn;r!`D~dLv=9C#}3qDn^(@LjL>4|5SnB0RGX1@Q83o?P>{wNuf_ zdbT&SKaJi1a9pqS*4nR;pM=MSEjqHC_ZZWsgi1Ev5_%{LZu{0N7Rso9JH+;1- zhI{J>uFzx?2 zX#es}vWVYLSZtO&j%!D_?Mze@l!3+3WP-8aHn$$}x->-xh6DUP7t6a(9ImDNvP|Xq zt!_h)zm3a7*|@>q?g`%=vS0Ro^2`ao4eX)`&QNEwyU&+^vqX(m zEd5n2WB+AY{o~2}+FG@GByZS-JQm(Oj>Bs8V5ejliz>UB+LsH57S{$Tz7$Gz!v2Pm>fuVMChwbP&)Rm)g!BY}*A8 z!I|q00$f(6JRcjyx{D8tDc|Rl;eE&^q2rdr$UC;*|J+slZI$5z zv0v!d^A*Al%=z?84!bwO!tDdCNu<-;;;xG>SrHDFRx|O7vT6(trTq8vQ$vF~c>~-S zdgZpA`)^;nx%2lPO&7Aq23) zKQMp&7T|LZz zKlM(KrdO!{oLi0DA!|=o{ha^G2DZ3D{Mq_`qJ;SKU96jU(>p!E6jB0`iu2W78P;S* zotflcvWEP*r>d}y)lbQX*p7;A?G(3c-LLkFGT|Dk?~li^Q8Az4-ZaT4CdQ(MiHpmO zvGagJ5eCeyvbftx36!04GM4g@Glkv>luB_l)w$SLxzJVK^Gimew4b0Gr ztp}unB$1?erCI)%b>vf2Kl_@9T~_YPA^P#RNMlH6G413B=gErYpH_O{+gc)uj4$?p zq8#oEA%B!yo=`=Uy7{dYoHq$eVvg3`86GMzc*4Ydc`fn2xXE3f@jP~?Uv?}R3HWAy zy13dqrVKjD{EWi%9_XW^VPH4MU?59)MvduR+eCKD=>D~Q&Ty0Rn`C=V(H87(qT;rF(P23AZYHHxQ|^9UwnNXC zwi1*A8NGWig@Yr^(%jn1S4p)v)m5Y80qL7vmX&Ftl`OAYRzKn0AY=F0R1zsdF(N7A zSvfy~MYPbj@$1eO9?`y<(+)nBh}J+S{oqX|S^+J-U@D@9&mBPk20Kw+cav*e!&JH= z(oPPy{@jnDNAi?S&!C#Gr&wBZGO@keulA=#Rh0?$xAlHu#p8s|OI5Y5t~SD4QV(kl z>SowD{hBvzRz8It62@wH4KSMJ!qPYL;81Rmvk*I}MWW}|RIUsU>ekV7nNEFz#z10Q zoN_+AbA$5RXz_yqkRmqbgzhpM7M@auRHC%Q$dsmhqCunuwDV&BnHyJ5!w>yS__MM>UL=_kpgNTE9|VNIW!z@1-|VN{-P`o{6@=%Dz2YH@jxkgxuu34 zVXsc43jTgFFP5MGgPKg7Yv99eX!OsgHEkn$+d@VmBGVfnkd^bso zjh|wgZ-2Lu>3W~C)SZ4)l|+Znwm&IkTMp=fjYF7>i|%$4C&cS|7i{G}R%+?t<9qgT z0+%tRh;KX0=4mK>R*%>s2KPX~zH}Z%E>^4T$BkN*(9)AQ@< z)U}z+3sV@wIvjZ#8;jkbe`^NkB>75O^veU=xWG2`SS8&q1REjYm@kg z>EVYR=vt={Lm8-T6-vyJG8Z!MCsCr<`9E0S{>tAyKVBdG#G-uJqv*XXBX6ze6~B(| z1g6SE?xI)(Q-O0>=HY0JUR5EtQyIn%TL^RRkQ++rgn;X%z(0#)(e{74QB=l8`v#31D z;MFC3<-q!vu$HkEQXHafVIYhEnwJL1Z@J<~M|1^`cJ@$cBbU3RUs<=8%?W){58Jpx zbJR!FOVMz@oisI1+D${UXnA58Vf#oI-_Yfy=1#aDjnt~OWD|C^cIWmp(Nj^fB=5+8 zD@QWT-3d%TD6zclZET_2%L*#1Y=z&oE_(0kDhrAQ}qa#$RZ(zy}#5jwR#w z`hFtTcIc2<^H2Ju4Y0bWEUKb-tG0In?jqJ+K_ACJFQgZR*iIL|Y@DPt?#L8z_n zY{|jcINE2)22{8lkLAj021Fm3(2G(~&txJNpO#=M1B~JC3fC8 z?%p)Jv9g)crE`9346K)zajjqCAPnX2V`4naS}H@%R@oE!n5)m-RB#hV9Zn?FhmgcM zBSgDiTY{6lz5XJC*}g~a@jce3J#QaJaiV=|6z$doIl-43DOF=KjyI1Ntb*M$t>R0q zW*XcpRUZY>Sam-|{Z8s$A2Jglg1y`d2-rL6@V`|Anpn_Yo%(eO;^ipFnfMeo0*KEZ z12(@8$w5{bG5UySB6}(gK18sh)e>H?J)m#%+qCZfme2E2^TUWY+;rc(4`}vc(>~sQ zUGzVS*312XKuPdPQ)W9xc{gcBo*Mf*U&I1Y{`mJd5y)-RqN%05unLcQv^%kdGMR!` zQatWfY0V#UEI&UVT5+r;G%f63j2`ve2nBZ!>~ALJIol$Lu5ZI8^papuatX2Oj2kxu z{U{!n#r+V;<)^4f_>z!pWStIYGX9-QAh_-Ai;dL57iCiG!!)Ne>t(daYjtRQO|67e z1DK%>UF0vXboNk|RhwvsaQ20#TP6z5a#H+BV_BtJrpAJa7Cjv#P_)SsxfOl|3Q^4} zQ?K2wPGVLbxJGRF|FG2~aDm~VKJO1A!+&H^f}MPci=BL7TRfAo_+)wg71CG@zT}vc zL6J><4(pAnSJ^u-SMjt;eGdwl{I~;8A2>DBu{G;Rh`+{`zDDv~DN9IAH*nOG6S%ydX8<9FD|UFw#* z{)pYQ2^o`)PK+9^^4bZ}Hn~cjd9|hzY}rUgqRQHw<4lj%k*Sb|bVf41U?LlSQxi2^ zD_ET@uZ?M%550?*hh@(A^5RjlVG%;f(Y1va{mGu0gVJ=qS0gDRx+%2ua;Nf~$v6*be zh>`MWM!PRQ4geWT?&|5F@y7_Ekqc!vtqz=$u*Nf*!cYp<3I(?7Och5mDLdAN5Z`lE zX@Pt2%a1&G%18XeJa}5^?|U6t4$QmVxVl;?-+wFW=7Y1?MGd%HEUz;Lzlh`TKZ;Z5 zA451!6yz@@Yi?7cCpMb9L{qE;s@lVTVqtr~ZR+@Wh-~A8S8RKIzdK`N5Kr%AS4buQ zf|gxYN1j$b_^#6w-az4*na+TTq5byu3xQ23Pil$vAZbQ zvLZ9ZWd{;(aBulx+rHw#brSwv3dup+qQna)ghGxygSJ$la&bo9XNY7b) z@acsItkX|8*NB1Nr=dOKy|g}f$`$4wF+^(7y*V4MpB-a-VCpW0aeHCt(7fbZ(YM@( z19~0$$|7kmLX*Bd^b6K)$HqMu7Fz@ zzhUPCgcq)Az3Q{*Ji2hTR_Z^4aZ*d3ZgMsS6TX27FODa1R5UMxSuejR($qunnUKNc z_N8qydsJAzrIcp~cxD1wJXZM{_$)qjD~URf%hql^K6_J`O5fX-$43d7<0dq+pSyk5 zLYNzMg*z+?HaYyQd^M=4klp4Vo2K$K;ZY~t*el|@TLFxVX zH}KYCn;<4{I;+GRsd0l2*K>pIMRJFl4=Fk)$MtAmcKYI0%Hu>DfZ&o^|CPdws>ZFu zN|nb~ZWwuT1V`vcV%2)wzub(Z3ON^t9SO>;uxb8WEh zdxSj^(X;rCKY+PhCLRN$?Xq_Cg*@C`{w{0~$67mO00+IH44*dwc`}*6b#(Qk118Fl zZ~=|V#9}pc)5EIB#8u>J(dj!}#V~3khcqez^fT2f@IHT!TwbG}L^)^GuaWyhRnkKI z1Jtb71z#JkMCj^u6!QJk_7MC-xVzQJt>?i$HR-b~*YJVi#t}TEtZFfllN}q8Imm3nr?6XG5mHET%M!6!7aS%XHU^q)yKE4BOOG z;+Nlmc?)XSq!H#bmf4KxV!t3#yE77DqL#e-Ge=>T+)cA_y z41sfGS&_XDY(C~|81MV&axl3YtT1VSf0@(XCrAcBQCT6{aJEwtK-_e^TJR?Ocn+z0tb)t;2tA zdc`-##3V&RU;K7p+kf6%-Tg3pBnbD`a-CH!zUMjqmsy9JD03v;#9T^*2<~rhync~0 ztKFS67Y0O?>(Y(ZuG2yp`b8C2SN@)bS=pkbq~EM?HjMngzAOyt$ak!_Su(YmtR8X9 zTCmBgI`Cp;XsL(6P)z<-7&)3n<|}?I(biSXdx|Fw1rc>hDi;MV-o70eW|z?HzZt)i zEeicW={BS-e|5;Fc1|EkK$q0O5%rbQYh?FsG)EFAfkQG7_2Huoi6>i7=kMA_UEo!V z5&Mr8`|6Gk$a~k#r609>^oSRD@3e`(?o5SD8UBPf&Q8r|GbksQc*YJ(ABU^J(Y>tQ zY%FV?XFBz7j2mz>BIrawpmgL&7h6-6DN+kj_xUv)bXy54zjRGbd5}^}eYj&fDcJqWFYU&XuFKdE5(MvBCFe2 zv=6te;TgJTyazwnQiiG!c^R37Yw1mC&8UvN;yY00Zt5Q2I&pdM&XHw5o2OWCdJ#aX zRVPhU1-f!Jy5?7I;ddT~*0hJ(RYt|pr_84Yo>ZOGV&8D~Rrp9gb$EC-r0>IwQ1z%;ESmTC|IRW1DvatEX5vCr8G;xb)SyNu} z#R>%L7nY6TZDj|QSr1jkCF`07$!}8O+XtD3_Nx`8^g(jnK}qOt81lLrdJp;uptIAi-a$pzXT_U$sC{y)Cn0;-N?SsR|c zad&qK5Q4h|4I#L@ySqbxY#?ZG5ALqPCAhl<4;q{xf#C9Q&OPV8pWOdjYt~|Vrdd>V z7f)69bUk%F$0;@7!ywrfnM7>J2m?Lnx>pm#rB#hk9xxOR(!TV)#+QWcygS zeu5Rp;_3T)TuC|cBi8A>O5A>`$1RK2w-!psTr-s(zzVm1Y4rZ1>Mz$IXM}N8bc{+g z9Xc@D=y4%Jd#!e9J5@E+Q1Clgw&b$`4fY9!W&I%TaM~r(Os;FZln{X(JPUUi94fAIMT_7))lsRR6I6C3z;g$u#p#-)E+YPDU)&q0= zspa-;z{YHX**(b+_HyDbd7Aqi(?f;<@ualqFGp|{u871=_55-w>o{W0pVK4U?KEtb zvvn*f(b6$SFKJizt)MU>#0mrrZJLipmW%{9MGMEzS*VItIxKJFpNWDval1xa%4Je! zK<5lx-==-JH?2?cbjiHdV_nWUkts$!8~N{}3wN-Z|J;+pwq;h?Z_wraz?Ew$$O0R& zhfR(daqMvLsl6jHR9Y$k&<8tzlalMHhq%cSjB091wlE{YPoCz8KO`qGJGkbFsPEhV zXt=Ky?Ak`?s_2LHZlH}lEhE(Y{HE{8IjK_^(a?T(^fUgPNkS+`)nJwDNxIQwZiPrZnm?h=UKFw45FxPKaJls=2@ReVPuLq-7cDZ#SSr`6-d=bZipJ<*)k7bTJ?l*;4THaiLdB?d zbb*G2Xd{g%Q!dm#qfz=YgI5^=2Ho}_=_2;P!;WP!ePlJ{Xv^Sw8kjQFILW(yq>JyR zQuy{-zEOnL;r)XhU%cxjVEsxpR&gWp^u%=&zglrVfX+FN6cw-eTxR%ib z&xckKpTD)Aw5Q-vL z2hY17EDC#9Zg-Zd75W!;Pjudn%zI+oxG)(CARDJ!!2=1iD8?y!Wc)Q->QjS!$49jK zC*gLg%wx=hccBKyY~S6G6h|!Y>jcvW6*e8-=uyn8H-%W1D>Pr$ZL$%Nw2?WDSbvKv zzVLC25X4xptz}}RtWIG7iLXZTzU_`3zU31-Yo%?EIuvot*y%*9aO?L>GUBae0-@)(CARY)qf)YP^1K zAldX8ur#Ur8-@vLws$gK?<=HYSa@KavJuXWDKHdcE3F~CPX1(6KJ`Jb-v^06mBG&T zRDXR`;7wFI-M#uQWUwdRr(mQ;=&nTmu4t?P-`gOLSn+V|+<%&dh)KyMZpg`G)IyW|$)Hz0RHy~9(W$t-72Wi16p6c5=GLkf(vm`vbWbLH2N_>Q zaY9a?)NEcAXA;1FHis2F$Is)}(1rg-tJpKGi7z9m{CNqco`QDaDfyEFg=@#%0b}2F z(j*R-3`j{Di{oUtSAXdJKsHmQ<&1|2N*DyQVCa~1Cx)1k@9Vcb{ypjXAJ)6L%TXQp zLB85PA`_-7hep<5ifjwX_%T$FZpb1LWHgSX!>29y5IP=}-l`nkcUYDLI3HkQSwGza}1 zeq|jl`y2myJE}J-{b&bXH7@MgUw~haVeH@}iNV4FhXNKRgH`DqVZ?S6%1dCHe9rkxEKILV^?@C};Wu`@!5heZFL?x7l zH3>=@)`N+%Xb!g;GgkP95-pPQE3SLHCCd<-Ogt*Sy||7xUOw~T9g>75C2@5Og|)pg z!zT`uW0AF*%L^u~0v?g4FKXY34ZayPO>cQC>Ev?sZtiTFQrzKV3rN5<;z*S(^dU!| zh~V}_-;+{WcAKUNlwo`O9XsA(8YQ%PJr#-}95;Tkhzu$Fk&h>$R6elo6lTA5V~b;A zJZv4H`x&XS<1+XX4_bk6JkZBlUNhRbP^+D!-OX-UTaP00YC*`=QWnFBRL%jC;QL3a z`4rQ-lvqw8RaZ+OTCVBFp@icNGtsKCsaUf)#Bw5!oizj*pY>9X`xD)tl4Pxtl=WH^ z7;wC@TN(Mc*E`1qrx}iuAi`p>MU*UNZftGOmkZ734#W9ueo~vIBV1QWw@&z-;i^td zzK%8Pp#1H?Lu_{>oip+;_!Z>IGAT70OvO}9WS;gDDozBia5}rCM;m`28UziL(%`ljkaYLv9H0QVMIaR-J zQS6qyq%RD*vutIQ{jMR76cvv$>p=Lob3{e-*JA(GvnCp9YU78nV@*KX*%Vv>!R=H%GmQn z@Q$4hm2$AsKJT%b7BKYXH? zmp@-Z;*vFk9qZ(r-Z->KqA=?m2GV?f%SfGh$B-pTY-dsX$Pjlh&(iSzwHR!9CvvM1 zYZ$>K%y5yHD$QoCK*QsS7yT_W@mRIB6cA|XrQhtnL}mFM)21o4E{YXdDR9(Bqr%U3 zLtYcpP-(8QLtUw0(1JM~zT&C{D^mntQ=C>(NL55cipx2k=0~YUR@^sEm7u*S@F8~s zY$F7e%=y_1Eec*-gTV3G8w=IV(E8ICFq3M<4VIp=&3!&{P;z)+RyShr1DBz&3b(I6 z-L6#uRivS~dF%286G*|JUuo5W0qB+K!Z^>p zO=c$M&vRWO!fFL{gmwL_K6s5E){{;voF%E)=Fabt)~-3R}!0KMv^6f4)FF^_FoNO8lB) z$4rGqi)=J2d^!7JR%Nz(*7*ol6~lLV&h+lQ=fT6tFSL&%=yQIGF}=Pz3eLr;S0UAB ziEp`mxjzGcE{8Qss_7pHs?Al1H`*i4m%eH6@2M%5x5hTQLDS6pF*mN7Xu!Uo6UB&9NB@)mERnTZIYLI!YKEGf!Jb;Dk%3k$Yu=GI9-7Yff@VaA|G=GpD;>w)H}uG23iQam zr*VXBu(1-}wVgN59anRjUp)|U%9{)Z4V84WrCM@d?GrB0c4=n6^L5n^d7~Y+X~0{= zhdyB;qvqNsd{CbrmwWl{gfz9)C-zbbH*9YnPVTbjD^^(D$}5~HtxwMYO>$Zs!yfI1 zeXF&ONk--Pm8hU33ZRFNyS%gW&fVc%RgBX~n}Ib`MGJ8_G+PJsES7C0_a7zz45c>> zS@?oKUWfaI;MY67k;9AyTyMm4j z-s=|IAvt@0XxYYG4Sw%dU1K0v>4eoUxRy2V%ak?zR`iS7W)gwJ=$y_ErRm)tlIY5+ zGx)69b2ped=!Y}F6N6+2X_>Chv>@s6gjKV*PM(es2m>pZe;NO%R=UL|@VB(_AS9A6 zZ+Cz88XPGY#hW60`Vbrp>b6EQ)q(lFL6iefmfBB{Y88aB6|?owurO*_Zy;z$#qE!Q zMz&3a%~JFGed*;|$chh<Z6Gzre*SP(E|uItG@NehmE?$jQ2DR;FVJQz12qpq?Ky zW#$iZ1*RF2m5{< zJ0%a$9zz&nJ)RmR5aN``+{|If33Zw#KdqU-qH3Q#B-psRKY4?U9eXpSyL=!Z?k9KD zub9gB%u+t%c_<&IWiIZPF5t%+`Hc-i+4ltxpcGJIifL{!Mw*ol6^7Vwl?IDm4 zMTkC8TqgohjR5*BN`_fQLfZNUFLu}s(U*g^hEc57RCP`g-Qg8-zn`at`tn`NJ?FoL zoh(0YR#sp1ISAR5TM8EpVnc5 z;hWwBjOw(od{W-<9j zQ4NeQ@-~8D0GI)7I5f<7uxmkcyZ{=(*5~#l6Q`atQ=jtk`GXlH69^EbYgf=3iPGJwPa^SvGM$%CI$=DC-T4a z0nsLcgg8V2;MK9C4fa0EQdf! zoj%li!<@&0a7Kxg(t_0W2?DywBEy0aqAmfzV=y2w=NkYzDyT-1qWIUiQr2h zY|!Vi8**leyIs89{CPGSF&Cd)%sH#^CmDl~M!A}$3%nI$9u&l{I&XHx84|HG$=KLF zjy`J3uR5W)rjP{VI`5keo1)#kN-@(C;w$E5&ExI&oH1A20HdbtLq{G}EZsTeCGr1% zCb3pSuU5jZvuH$g*og(xag|n7$u9Ayk`}>uff)hJFptroV-}el1s+$aZJFODcR@9x zB7#E@pcj>Rky7TCa0=zB9{NW>I*Gt=u=JgFg=09 z$7A6_zM0SZJI}|4?`TfpBj@VPw=xYH!;G9bZ7Jj8_=H&E7;R!kzuzBjU6hQG_U^IU z65+bPAEBE>s~4R)zWM9KG*2r#aK`D0I$CRa#hJdXlIs}+s$Aq^oDZ-W%F6NLt$H>2 z*|hMNNCp;hSAEv#aLQhYdl^-JOoliEm$9^Z^!N?M*2nMXc6^RT6ZW_`R`lG3QI1#` zF~!Coo!{RpkV>cKGVA&^*On!9U%$<_&ek%Pbr>p(BfNEdj~!c}%gfO4aXLfnQise zvGjsfbb^;eCBqIv#l-rMXXDLeRI5W62ooe|Yk8Cw;Ju3-RmLI=a?l%r*YD3AFd?Yb zMUdbC4HdEMf%_&u`CQy;nd9Y6CGwBx#gsfD6um~tP`}c|TBqphh6DULyxnN1HtYZF z=(W?ZQ-!aFDL{A;PD5+Moy0I2=U{?wC(^fSvE4HAgO0!YzecP?CR4*amp!u;xl(=( zruubs!q{$|GNsZ(-tDr>r*|^W75z1i``)X)yU28@)l8g^F8R~W4u|AK$S={S3R1`v zbBukpbu6tp)g_w-e7cs|ETcDT55%IaN*R+~BVAd&)i zC>0vqkf$0Gj1v3?E|C$r6Ho@;2t-pO1fZPDoTAW(f@`dAivwUN?ZQ7(P{x_;E<c#_(YK6CmAFvgN0+k01#;o!g5lxdGxY@Ch0<#leKSs2apr0Mr0^q;Peigx1`IW+)0lM4CEj z`t)=FEA(L4GH5MGklM>{fRSk_Uw%R_D#}lQq$q$dOiiGrrwUS4=Xfvj>cON>CDrOK zF0Z>)U+H|n>2BdV&j;ot(E6MZFW{|b7}4KQaZ#!fI(RsvVv5UA?aLhG=^J)Un&2Ud zWo(LHgjuXN=gZ92Mq#LPb+$1#Ke3pubS?f|T8v7^Eh^HT#!u)JUYY`?NKX4Dfc}ea z&{XgMrvDB~UL+%nh5TDWXbV<<1Lh?G=;ez2YV^;G|9S+VuChQ>uMGo|$Hpb47<5GK zxNn_w+ExpIP=(jM;zYSAZt!%b;uLviZ`52(VYwOkMIm}i)U4iq9H zETd5r4r*dg@-e3>Xrp&k#W%eVT!T^nEI|w(zjXUCRVG4M*IBm>@GgZCMrt64OHh!Z zfyyoSkKE7{b}-=?SoEXG%{rTH1|c_1Cl-j9vQ)9W2 zz$nykWiQ&mbXf$k^}XEbcB_Gq&)p&Sne0V|23#GAE)u0?f|#L*Jct!=#L*e00cXP_ z6zkVPPX@mUlEjWdfdkPpM#{~V8`&$Fx15E1Q1@@(c)!U87lNcawqG;QH zJ@tL~7-Z~JOpsJd7%}TI_osmw;gPG0q=7K(T{v1&(h-t#?4iia3VyYFT`*Cs|0zY` zpYSHBUiuCLDzvGxX|ZAm#!IIEI&_%+i8%r2Fa^HlhKEE`38m){`0zmuFbp0ki82<- zObKJ_MFC|pY{&t@)1hLE!*pPGsds^Xe{KC@WCWO}kQbEgR#Q7cM+&5m!iJCmXJZ6m zvU7l!)4F@Fm~t$+4ckMpyD; z>*gplst@quJiGbI%h%`~IWi>JQcLkR=TmXfk|!GrORU$OS?YmyXvJrq!~lQuIFhMS ztOX!oP%H|BAo<&kV7bnT^x?>Bt*+ zMr_65C-vHEyigtV26{#h2JnY>iSnSOYdV7(ylLi*bIwKtd)zX!DrJ9x7r5e#lLJD= z;%3}qweR-Q8+s{NaHUnrOhDGO@juF~-51hmYudmC81Zb7=8c8Ans;uso2`NdZzwA5 zf-3@OcFiRW);I|dxoSIwM{#@`L{3{VDu1x`ES4|!R5pT5JcOlfh z<($SL(&0^^`jmaJ>6N8##j~A`_x#a|%@ba!yKqI7ixpvN01Nr^N=1l!!*gbALvjor z$I2oix;2=o=VH0}It#mC%Am_jsnQNuTqqzL@)InLQ>|p-+=;2mci!6%#bI z*u;QoR4^2E85j-Rj(3SfnGAbp;7(KjYd$SKIt_$=F6YiJ?!&G8BkB#InQ3{JC*-&{g!#5+{?0}^yql@FmD)~W##6=ibOjU>n+8-SB z!@@(HmfLti_s1pFk70yniBdn!UmeWbuAS$Eeo|uOM^q!c?5Pvw>a~sRmRPs&W`b4T zj^Gt|=%L);pZ{`S55JqBmD*Cg1#WrhZ9{XY|JL#CFTzoIa*;2VsEz>2+|Fb$JJ0lQ zs)gfLgYp%dc38`P2T5ilZp_I6OPPG(7}h>`!725pI<1zUE|MvqX)|E9SJr3V7SgS1 zd9rE1aL0@$hpGldtG5umi*B-`<;|u;-YI(pk>{)|i*BCGT{i+d1x+hgTe=#*PFg2x z|M6{mYs?0|B6SRit#r?i5SjepX*C^VyG7PAIM zR|o(o>)e%WAOKNrbb-(h{0>?cN}vjYh=>K60pP)WijAR@*&}4N{HEcEzxoS}MFD_+ z_>CZr=fVhx7g{4JheH%=V}-T7y&$9u0EsjdQp+K%E?9Y!wYL%Nnmz{NEbZ5F8C6_? z{WdhBJ;>40`D+Yo4rz9E{6g>8{?ZapDor*aXLU21#JRJ4$U!axQ;agud_W|5IHSMn zRoCS^dK6MP?<7N#4Mpsy2Qd|ONuzy#Po-|BBwDDR{Moxta@~nBTJ7l%Ewj9Jae?ju zROL~q%E$k=*Lx|LX#}+l@C&Sg>H&ljsNWla=JeA*0E~s>7n{MD(f9(TBch;*73m^7 zGl6!10pR)hMC5cM1^SJy2Az;le@>|I6~5>4=YNJDIFaD{vT-f@;fpO(%_wHjBG%9d zyDFwF8{Tt5)2lb+pDP3;Xmm!l5K2aWX8yX767%^;94O_A(6!~B8l7F9*p}hYG0KFS zh=29Dyo7{XE&b*LuSVQyZM=mI&g!<<6LS~4F%-Hj#nKc03%Xyh`yWbLv#Z&ZI;i`C z{yTB)tWqlhV54THBM41CDS`0IQ;-(bJ0&a*1z3?>#YM`hfZA=Pp(4UI;lY1i{0h5)Eqw@Qh%skMNU&OK z6j-r?rCrW$`}OX*!oJRLGDch0X5T>sM&1Y~hUxTGmr{2?-vN=VLESj#u^41@?tMbX z(gck~%ewe}t#warBwDeIo4j$V@;Jj%Caq9Lt8AqS=x>A$aPnbw+X3tO;CqN2TvDTJ z8tMaltUEk))yT2*r{{!Q0{>}~t?vV^xNpu+Ci5f@vN2@#nOiKYRkKSBhw$)?9HnaWY=0-{R-{2geK#B=r&kxMhH*oL`Nbe98}*1(cKZm-~@3h{_ ze0)so^RpHxOlOK^r~NO~BOuLkN?@KC1W%1oxCs6*Q=aPbK}C`=y4=54r>UE;8z5HB znJCCtzl0frX~AHnOw&q{kxc_$3Cva8L%Jkc_wC$3Xt*^PfimJt47E|=Qs>|cOQBczlH;jGvZPRnp)Y(i)yqAfv2%;Bm%k>Q%6-bwo; zr2U#vFgcssnv`@4WxWW`EXh1R0~;{dL8VXbpf?Un%EAtv#~!-1~YERb-#$W=!K%x#JH#=dXG@g6)vpN zE}Ydm++)^o+)vbsYBgqosjJ~gQ))^(BBt%4Io8Z1ClVI}(ZH%dzKss0H;Jp_LL=;@ zr;1FY;M#jKb~(@|vbWV_O`cZ2O*f|8W7WcoGFGUmsOkdtMlqq)B;ob3no|RM0l>_I6@Ve%?@EH>^=F$ZqI^FA zV08iRY&YAu#J>QJF?S`gcmG zLqZR}rZM8xQahx^!;u$y*VEZ8cwngE>Sd0Dyb}l`a?#_y>+yR&0uB|07wB$Yz7_`0BA|8iLc#e1JeD%7STvF(n1>G5aJ1J}o+Pb!Ls+__ zlS;%HuM81FO3D-O0)6e(>bOR%gSSAy`);T%P*#jQyMJ_nP8XTzi**0FU?ziu{EZgLZtrruaA3wX#k}KDEAr@f>Rx#RE zpvlE)lRX|6BfV^)5P9e=#C0&@-GRUZHvMb#th*|Hsh3!Pg-uArdl6!loMv2Zx{0?Dyqq?B#{{7T%W0F!-5|;BX<^A@| zrtSuF?bGaT33c}#JBSZs*@iQ~E$j{;9#I+%^h1DuRp7`Q`)3mVvvmI_h=CCWuzrub z%t7NA1UAxC1`-Zx0KgLkkkFZ+A4i~JjwIX53@M0Z06PY5N2ed!naGv_SWz-5iE+1V z>Sah+P7>Qv^(1Fdhqp)cnQDqm5gXBOW3=7-Gi2)5!08Jr-_B;OYv7 zsf%p^^^D=BEr~^ECMGW4F3P9x>wF$K+#B2HY@xf`)-pk<%boM|G?_CWewNQi5%(-9 z?c2@+>~Eb@;nAQvZ9xs|e-F(5d!1d$hJR}X2tdHW9b+_<_GVpxv?wg!q^M(Wp!}k7 zTr5R50440DvT<)ri4N!7-W@*QP}mNEaHfIf|v{7yWCg{j%8ppO)JHMgUCM+|qx|5ws278qx`ulQnRD zLWgSgFOUFfxBl`CdxAFMj(XHy9wOaCCzh!6-SutzAz8h$s1M};!fV(9eQuvczi;zL zlqcGhn!koHSwHEsI~%5xNk~5>&(!s-5hx$FCN56wphQxYXGY3~L;SWq)@cZPRs@zJ zQR;;H(0K6Jc|f+N@#xeaSFL9MkZ-X3(38VR;O@Sz(`-uJXnj7X^kcXl6$!<5Yz^3~ zK|8=4eLcAxU5`8VU0jx-wT;!~*PTjLduZ5#OKT)=&#Tm|x1Qhv0fl5U+IHFTj`xkr z-=o695R0ceL^Y^z#k-^;$nu))$;cwK!liQ;RhBvM7$i+VJG5@BDK+Bw15%OxXVy+{ zN+h%x)`5U6WHW0b4#h=wzSffV^XYqpP4vy8$tZ8**lD76zh!@ zb?$<2PDa-0*GCl|Y~gUveWHzHh2A~AJ+ZTt9$U=YbB?{DpbrE{^fGg!9u1VYrTd}} zM2jrW!C#iO5AaC$82`Y9nK;lK%}v(sGd4vrGl`=uHLX^%WBWvxLR{JSjZx>M>h=Bh zMZN?RISNYouDW6Cci~xjSS8gbyZBY(PwBcx=?BDaxvI$NIdBHoD6Musc;o2i5Ie8a|wxC&5Djs8W8WNC|<$#{El z*a7N z0H%08%}t*-pr5k=xIRQ({-%BamF44(<@GuLpUb+~b?yGI-;qTy0eDg%dP&1-$iFHj zyKhz_`^Ho2ZNH|+t<+mRe+cG8VJ#m}jR~)30Wa>;@ zA){x9{JAAGsXgpE9PC|JL%?fJBrRLfMRyT4SQZ)kZq1unJ=r`}i*2pr&`*rzDYA-n zs?q&tpBiFn6P1m>3ppA@NsGh9+mFFEd0U-bmpA6V8D^W?RMnM9#{_qr#9>NTYphPS z_^`ZPCEcR9JFaDWz?yy+YMbpdwvcG@wu`z%ZpH}99T?=Nq;>N|fu-)RKMy#n_!)Y# zP`FszZhNXC(Hs_!O-=jvGC1x%;4kjy@Y<~?%MVT{d70n_`R|6%7ROTA$TYKs@2g=e zXmL=!>haeq3nz*?l$8sgKUk0!;G_@pWg6dxJpDG#QHlmD`Q69FiQX3$qM7h`%mADl z&^hD=W!L@Rp&fLgPE=qkfd@U31)UiZQ88`+#xw|Mg1{*uV~UzV(&A!YUI2~|;SD1I z#LD#2BG364%t-xIH>US0rUqS_iVCvtsxT3QZmzoxXDP@(*D15VdaLRi2kAU5;0I4tJ?^20& zrZ-ews!~i~nh@lRWYLZ$qiB~4DOAmb%gXMQv|NplT>3Hlw__;oFPPRkyFL6yj1>XH zQB1?zR~WoJmSy4V_I`*7$hX-Z%j3s!U$=X|5GL5ldxdDczFXUJ;(t@Unwl7_Ft50E zY$9x%_&xViCq1ey>Pk^sk;GZ!#s{8U&`>8gb;f=g9of8P?|f!kU}WFfF>Nm$wo^ajMW)On>K&c zt*sc}X^tyn5cU+{@)8E4E5s*q61c4aGd7erU1AVHkP=Y zk_EO8j{GxJXwZV3I9Q655(^V_^YEesPXLF;AMkPq6+;?gI8F_i1DL+7_G{{W^rED; zl(eQvDL+!XMvOfyb~%#3VBqv82>3>XXUZOdu*3fgVF0^Snvs0zOkIf4eG@S}aoB`- z*Zn(AiN+rR73v7*jGPf6H&cdEw2$t4w=3@kc{fB}3bJ;A)S-@!K`g!A;@^($f8g@} zX9E6LM+b80%dP%ra=w1tCwEez6{|KPSt(egL?WSudv(m-;?bGkxD4q=bUXdPEw<^Ok1dAG z+s^!IBWY{vs5`NQWd*>pAeZ%KRFD@>&HO9 zyaDEj_Wgp51-WTTs2CSM3Vq2UpSX9&-kdDFg)u1H|0xohrPXZt{`Ly{rWRB6O|2q& zAqzAEWw2CpvDw*C`*ZSNJTMHPe0jRY9wMm0dGzr{y`i4>^)-!8*+wg~c~0AT@TmV%sl> zM%nbn4!0I=nM7b+>bLqdSE6qSGQCVs?ow znaeo;GMhK{QU82S_@gmyI>S11YhN1qXR)yTlSDIEF)N7s6)~B9Wh7R+)JCH5?&4tU zU2ER^Yw~7`k0?o#HLAzk%zXIvhaM9F=zUmZhOF*xP;~PW%Wg;Y%?Tt+dH&Dj|JMfa znId3+)r;2M+!^a@1V76w3Y)@*fnoM&gpUL*li9`zU^JlY>3|9l-JdizCFm#_v7nHK zE~9b~-wFrs4x-|cExQYrx`F}$40zItQocg0toMp2iXSJt3ncs&zSnUI6ZCK)hZ25Y zZ*677J3Q^(*+&Iam%EO7BhN&*zrwktG!y8WOT3?3CT-9YSwy2ddyQtrs($2v#1rw( z*N~GSq&AiR;~9+NC#Um0X$Q6+%!+V_Dp!0niS%f95tzwR?he&9gqv@cd{CzPJw9*Q zA95FU^AMWqBkqaBlhqcg+@aDa;^c|agCoJyPpcSAy~dQAAJ^#BH|`QDayzg@)@s?b zx2xupu1Vt?;)HyA)I^o{x=CC(Z4PGOWjvNkU0jdj8ZFFKmIUybszc2UD`E-lHcU8Y zQ=Lav+sl$E@^QRK%oR|2nbzay4<2!j%|j{Ia=N~)kO0x|0|KCE11-|kJNC~)^xvBX zpkM%zX$+vG1OO_5DQIaHzyuC)U+^x+3oQp-2Lg5Z%2Q@K-`-r<&n%Hli?1da;+P$kVGc5}t>k*3Ez~}WoqIN& zfJ8sP-pGgBXPPhe%~n&GSa&i_8qYke)X0=;5oaUojGz^-GR|J1?}Jm9i#Wu)7r>AZ zvD`fqO1XAnMsEN8+~JH;Jdx-e2tln21OVVWRH5VlO`#X8nHWTtE~La$`nP?-sM~x8 zkcI%j;XelVFNXjxpvb@}iCb}S z8{ohckt2p1F9Hz%$$H0o_ebe>jv%zCy)VmZLm=EuX;hwlksIapc!1t>yV0Yfp|Bi5 z4`e#0$&cUA_2c1?{B;4>EqlEg6{Y-zIyht~C$GjBs=y>DyN~G~{QrM>s{a=L-!2Pk z=5w&LhQsNj2)Lw#M8!}7O<9*1SV)%EN~s>P2l`~fgQvC$Un+v>Y@bOIWi8R|~?p6#ec{m4p6I~^HW6R=5d_$UTdX$h*5+&?P) zG^GUi94r+G9QGf&AH@8{z`!> zV2;xW55bFGd^o3P0U~aX9bquruPC=6GfdS|qtacx5=bOa@_qxc^nS_zcskwxV+%fw zuXc121q05$LxsXjX&sAu**DsdgV_otOvjM&Q2O!^Tx+l^_bMl2?B}%r&NScHy_uZ) zkk?`qK|p2gIBDz^T-NXXff9)HzMt+;^CP-Zd3}8I%#dbwK9;1C*_d?9!<`N#G4m)l zfzK8XkCZv5eE_C$^guQRcZ3^DVYA0M2XBehiB5r2WVt)cEq=FwUq@cqYro_s@07wt zn<*L7*#VS`KEHltJ@)k>I#8i$|SBzH~3;)xu)sK90#L zlw}M_p1LQYXPn^n} zaWY7BHgg|;l=%=<-4f`Hj(`S#gBtjjh!-3{q4%wr(|zH*9lvoTC}|(e72h6qj3*gU zHXp@*zh(iOdwM(|o*Vj|vWwkuW&ALV{a%vVsHotuj%g^aLx}@u*?qpvZ|Km`L$AZR zZww#{7beVduoWv5-C_DpFV=4d{~&~AvJp)5@teF{*90yYTLi&zc}Rbes@kz)E-Xagv4yC`*kM1FVU?iK zUZvI&TEkD{Q17lx{qCIy?b7tXR%-;h*Lx}No>A$?`8sUvk;e?T(P78&Z!prA)kN3?v@bOI*O_<6Jejb7{5&HiHD+xF z?@@Td%OkZrA}7HB`$T;0`OuRkIVI;;?R(nLa=0{9MZ@pt;;8x)9BV=|4O7;VJLU%S zN9Ep~XN&lc*SEpMU-<6tjL?QfEfI^azE4elPL?=|r$d2oJB~Dzbv!A;ixrvXV%mQ* zby@#pFp?eJ0c-mM+lXFuN(P2_0t0#4oi3mFo(U|yImYgEYKn|?l&ZO{?rpDTTlI`s z{ynqofrIzR|4`8@S=rH^Rrnaf)Ur9@e<93@P}HLm@?k9?+KgABYb$hOKv1B=pF{~y z48+BhZ!D-k(zt@@E;3w#r9Rpz8bl=+Ly+oU8AKW>{;4C^Sa#B)VOKpVdt{;6;ApL< zvuLq=H}(tZS}26;D|3@Ct2g%>v|ucJYZb;a1=22+8b_A5BiMh(!4p4LjBr;1uuyd! zNZ^>S&sN${2F|$V<*Dt71jvRSzH|L1*{XfKR;2uEfEi!~d<`*IL$y~s1EHQuKH^V! ztBr!Fpr?HPZbJSzF1J2uEMj?RU*7YF#8NEfJ!-Aig~TR#eERlzr#Y4M3o;r<^XesM z0+tJQ#uZHTy0M9Hkw-IeMHiixSn~+Cg+ix(%{=Z8?ctBp}W;j6h^gRlnW4ftkh zrZi#sM?UWhjImVFuR|$(rDOMh2cb=fXMi8g1GcC>En%G*J7 zHAggbE*O4xN)i~%Pl_1&SvCmXgXQtmeECaTEK>mTApDiwK+&SpH#Y|n-z zIvIg^iA1iaRD^tiFl$(*FwBXYJxR zd5xcio_r-{Miz|qq<@ye0c1K9Qy0|W2g}H-6?p`D0ycl$mru_Y#-kI+PX}Si>7dd75b4&7jl>a=b zWz|;Q(S4mEmc}k-38Pni7O(uxdG%ur!iC&1G@FJH(42A8l%m zPF(dxRr5oJDe+XaI<`}QjE_OOS)zEb-E3W?@FSO1n^#{6_G=pDOtW zjx?q~)Lg;c2cC%7a@hm@S(2O1_#o4wAN#Ftra8=`H%Y0;dMh0=K}3DNayWX1thy#t z-PZwylE0>}Q#&179}?7bG`%P&DS7r@S1#)LE~Xh9wMFM_lKuR_o5els=9!c-V3p;n zRq2!SGwprtLeDoZ5zQ#2I~%IWbGf8U1!aQ#NxqI%tJAHiITL=l{edfqdCVIl0R~WP z(DZVZ*OB&$ojCtq0fCNW`{Qa%<3j|B7Obk{^H7_WqwvaUO7nh<_><>b0jnc)*}~Tp z%mFEa^&wY!ip7*`_m0Qi2+;|fo1UXFWt?9p2O?!(!P4$0A}6iaoc!(eQw%dml&%wjR%OIK$#W*C--VYFj#?LR9J%-k778trzIpov^jNP7${Z ze0WOwLBZ9gpEldI+^q2iNUTug^+FJWS$UNQL`z8U}`%_>E6Fxa1Cp~rB% zG%mv3#hvZyf>|NLQmZG-4W0E1^|mJIh*H^ERzx-V!RR?wlgr_2hV0Z{UIMLoJ^=FnpBDp4xJgZ%Yn|J+GlD%oXv4RKgs16>PEbhy^`0lS=@{I z;aejiCXtTMwp(1xHSAgNHz$#kD@I=L6Pco)Ff03+ti@=mtMgo0(_`Y)l$X?I^SRs! zmFYy0hAQ{WMu*>4%Al)dFroh5lhbQh!PY52%K1cuNbTocTJHjP#W?i4}%Cs}x zCpD1!A}FUkRTgd^VQy_gR0;py+{2*+tzSfv_!`_4F^;mN`1QN+jxcf3jwshqPKKTR zS8f8=G6TW-jyn)7i!O?P6w`0o0S^gV?UzGQo$~ISc;PIq#K) z)m=*_o9O;TsI4I5SOaq72vc$`|MPG9=Qy{!mD`ioYtmolKHpJ|D~@~zAwVn$NtN3{ zPD-6IuI~#_ddgn?WcgX#ESBKtF4=VYHQi&L>c{h%F0XK^0r@Pk^IZlQ9Q3hnr7q$g z=4_K4o8yIvyKJ;)SufmcmNemtE3%++gk!{wK|!vWKLzD{liM3U_avsS^WNd=%XI!u zUc#6uEhc5G^6$@>gziY>pV(c3G*9rEWaKjEvK_fIchF4K8}h2Qx4e`yvlnSp3SCix ztyct|!;?yG#GKlKQ|nSfXgC!G=bS8CFLrsnU7?$#x18*sYVir7HKrCW4c7;mS4~67 zNx700e^W_Buce#l)g0_Or8(b^MUill%<0B-X&Vu+bZSj|cCD76M$X1>7|xKVPG%Sk z_HhJ~pP5nFjjO7+S!0^UIy^aIXnOo=o0PpJNkI(%7I&2Qt7=!Gh{2DX9g)dR@v5Om z*0#kyg7YW5(~x@1rf^B?jfYiXzfO*m>?M?J>E#3WuQm*mkKw<4`3b5G`iLN% zkgBywP5foq*v&_hAZq~A_hu7(kDM+wdt%jSCeN*e?NZS4;Ny&PyKzFR@ddKyn%?Nr zqz2I$oZVAW!!yd}5M(-Ka%WSQ=JJ@xwvMVf*9OZ#Syv<~CCX~UlDsfs^K;pt1;NmT z&%fsLq6Os(hEBuj^qlMEPi-^zYFo8*3HI~w4KgM8Od>L)JvoLN8TNVRGg^LB{IA9cra3NC`$B@Il0pUU8fH$JvAn-^ zH%FcB0~yp1p&{FfNeR_`)BWU8g|;5tq=gWlOjE{nZ(;)~%AUSYX)<|T4i7$39eW+L zP#Gh_9|w(Jt%x0zQ1YurjQpaFmj{ePEMh$yt}r9xsJ6BSM+#yl>U)qis#iwTky#Ga zvSG^6%!GqnzK*k7a(2cqdS3e*3Rs_Pkm|fXA+=;@nMcz2U^NwueiJIA{u2?=Zco1t zN0ONXsDz7EyV_IRs0pX6JKQ{M_1dHF4Ev@-z zFO;#!R0k7f&w5iL&>!uN9})ZF6San&Yh1dg2%5S%?MpZ!qTB47mRJ|#)lork$NJnP z5p}@w;mfPx$^~hF6PByu?_2YaaGnw82&`;k2<#yHN^Yvzo5^zeNe!XE-wo{?YOR+I zje?H2MNJZyJ;!uP$Hs@ML0p|>-XFNfpTu_2M#y?n0Ze!12D4sG%INBJ{I8*=)jMQZ zpd^DK_Rpx?rw4}jyj8=Mi+&qJN!$Y1QgGkBzH4os&Uy!hs@viuv1j$;5l|1z(E<~d z&brZjIL~1%aQCt(5t0A2Gl#P~KyFF>UT|fw(-9$*iYh?oCUk%Z#i5N>N@XDSU^L0n zqDcrRs2ju_9`^I@L{*$J6V40Rj1|54&;l6vQG@ek5oI@gvGWWiS&lSIaKzbv91Q&M zv?$L4T!}_{IFKcNSkLiB0Yl%vn@o}kuGPPBwJfL(lg6D9 zkI`4kT4C$&dd?!2J+%9YeBhgeMB8_V>>0^D>Q5#Wn2Hw-%4|5qJ}=Yj{G)QiMA^9% z%sM^XI`u0;=x80RSnOo+it_g71YRM9 zD_*QBms!__Vt*RA63X85GGv6XV;aLTNln3Q&`9MWP@!Ew9aXA?W9=jX0ELPvel$Dy zv1JvWK;lO--$CfPh!dy9AIk(*a=`bz zOMaVRk`@(Zzbq9~~3>m!5tc9$=S6Y@sBfg zd`s(klG!fASYPeU_>v~Yr>Xivop^-4$b0KXL2iq<9mHKpt|c(lAH_KwOD@?32c8CX zW{>fhj@eHLw7e{R8N%5M@{xgu{)(G7m_Vbb)0T4Gw_1uL0pS_5#5xe!=0Dx;=JJg= zK+;2&G%bcaTjf14uUMzyU7dR0vg0AZ0qGdJbKW6WmEncH;={8yg6Ar8I`}x@QT2nn z-f>FtBSJX`_Eih(b%^>NFMoH{I3laz+@o?eD-i|T^~1G&`dP_WRYeFNoGKmeGq3!s zLmK0lx8^^|8K$|~4Z*xy_U{|xCy`7&AA(Bt$4J#_NuzJMS?^r4l*2f4EJ$kp;Nw3f zIA_>wuP;3Dg!^fdhFp+KSus*bR$n`5{0iNtXVK+$(AOh(4e;dGSRS_NOBJ{%fEgf; z_h$EW*Yd34E45f9r!9A&RBAd^8J*fGBxo8+L9udeT^5GudeP?>#!?w!F{8(aoA(Pf{(7sk1+TeDjfUE}HO_L^1uFHQimVouDF{$WLZ$}n3p>S>C%o}) zC{>B@uV*g~Idl0_+;K%jqJI(un{r`<@o0P&4_7zKLeq1z^f2nfU>SmTUfNb{oFC>; zn$}RF0xmIvBN^yd#nubS&q7N+wbo~@=QF6xvvqpG>KiK>R(#xyJ_nLwSZ|G$4pvVz zE+1+HcEGtoR4^C^l*Ufmx!@zYbhbTg)U*aeLwSh#TX(FqZe$)60J{P=v#6xtN z#T;0J`yL*@5Kc-oN~5l?nl%?i87qz+_ZX~~>l~4?+2)hh7_!qvUMIh!QGV-@+{nQ^ zFAIYHAYJGLVHbdwIxRPV-0$0yRzrl~Eh~K3&u>1~ z)<`aZD1r1u>_#FV{d20SR%DWV?N@-1Ue7Jxq5B?}aFTCdih%V;|us zF?QXY35$2%k+X}hugGkUBJuYq>?1}+-}uAqs99_6YBqRPGOEH$GUTie!$mz+C;YZR(K8pigT6!=waREJr3z)8MN?F53k`HSp(kq18J zOE5J2PEz8Wl>=%bb6tx-Cx#g@24vyI>k0FM!Jd9Eome;7Mc)j=DfDQjsBn~O z5iSN{)r%am*Ej^G2%j{90G7Aw{wrXq4D?+Ak> zBI+8(;Kgkba5ib)sSM$38+?0USBR{E5q}p;QSEsMB$KcXC~K` zQ(w9*x|y(|4vGc8fkB6q?rJU1MK#Lh=SzF6{_ZxOG5sr!6NmtTKsXyH9mMRyef1JsXuh?2*%E?yC1>4l(HGnRA{ zY1JD{nv0V&_l&1y#;Sas ze)|Kc1P=zAu2dKf288Csad}8bC~N5t6C%KeUlrZA-6ND-zrLl zR-fS3>T>jS;eIj@voRnBr|DQSScu|q9b~qaVBZ&K%elG~$}ci@dah%JD=E^?ZBX~x zv)R@Q)OUtd^#NYM^ z-$HSa;`4942{m=r-$~U@?3cC>&@T`0%R z5-jclop4&h!@86YwDbnn(dG272=pr8?^{h#6fct(GK3 zG=TRoi4109C(*(A>q}h31?It}mm$+N-ZWJU#$tLR_x&1rm~Ti)DMG#+k>nMIMttYZ ztpJ2cRRclh5G;n-J9z`!7O~jRw$wb^ZF5R4BZBW3Fz&mEdBq0;v?5}t6cU|t`mZjx zbqY)LD;k#Wy%6dodX?e9LXjmnV|t;OrLJZZLcP5EpC0+#wi7uPF=duNZNV5ZJKkQA zEFH`n@8F_2^QlI?*d~aQI`(*~!a0&!_U6{Z$}nXY-CkPTt2B_ddq5oPF_kh*dz23& z#m+vi!>6!{vUojKO1-Au;}Pm7dz!d=d2GLYSKXF-US158o;%GPKg^Pr z2e~X&!36_|b+54bP4?=>=j0iW%KCZ7y3(R&^SQs zx3y#Aia%A0t)xfKdVABEUU5?>q3iFSvf4-7Yx7=Q-L~s6F6{2Tq~}jPNu3k7Ob$Q; z=78o?3DWIkx6L!qW*O;SJ`9 zg$l>|U2F4WfuC;&mYUmCEVlPjYj}p=14(_=%}%0JVyqq4PnzSKpXt@;Jk zM9XF)k+f)7oT7vtAxA(GtX+>a_ z?YTlDY0+Emc`=L+M*M9N{>4?P0G@&gp_A(kpfM9zfPCiR>XoA1+^m2dTb!ROUO%XC zQkQ>YCeK9KC}=c z&$eT&qjOD_CmeRAgztn&?A_nRJZ%nWWzws`hl%omA3@Ky!w}IL{#GS1HwJ!5z8>t* z+i6IJ(TZ^pIzd8|%R|omEkui4q1KFnI}ggI#F(ZPi&#n#S|L3(4*%BN^rIB0{}xq1 ziMDn%!CWRshgK)h73V*ZnHcwjC7i*vX7m%IM?|Uo9Jio(lc_zFjKa>q8!MY57#~eC6 zq#gf^065Z;-T;t1O0lU;qvOcEkjRgyBf*eo3#R(Krt>2U;41!rX{mOlT71ww(vdO;`m=$g*f-DX5o-7k2-uDN5yq)MUD5NG2}G%B)qJ^R|F9Lt zNoJ;Q;LEKyTRz08*Ga)3m@9Q0AMFYD{me`|FUz6U9wN&pwBI50DQ>Zab-f=c znEz=$Vm`XQV|iAgBU-e2*5Bs0H3w5*wz`pp9?h?qm}=iI(4(Ty4e$wGt*XFT9KJN%@Lpck70HZD?B@J5|K9(e~)=P5)t zmQ&Wr}q$7}y2IeIY0p%Bpum-=9Mgs;h1=!OX zsp7YgO`&%ms)M~$PpznsLk3a>qHo`;`jTk;oXi_jNDy_RQe#px$>7>(CZD*{t|C+s9SX4(? zUh^rmv1cjNZG z(@vQtHQLljwT<*Tg?Efw^Lh~iNmTlSwd32FA*fX03Z^s9E7Zo zimZ}dU62xdWNa5{SyUd0wRnJUi2Hkm4l|yU%3<#_?pm(qXm>_AksB_H{(1bSDL64f z+ImyL^vM;^_QxouIR=QfJOv~SfQgI#g@g7u)ryJr&GS^eTGL|49E#;SY7Cd`tt$i9Pv+#>uN;9hV=*Mt zm>^_Jfeh8;i zB%Nvv5kq0dzCw@dhS)JFlEOjL-v2$ArwX{1xB$%}&#Zo0wb*=2@jDD1P@Q^7#mMzh zr@3Tm#gBZxLJZPPCN!Z5ttO99c{~E)XW-y|QxS6UOV3Uv0s+SS@{d6~J=1;IToz73 z_$2^Ch6d2sMdQ8D4~aEzN6viqgB3KVywI+Q3Uy(@B@G>E+EPIxn>_S(9>!>F*|?^6 zkTGoRd#^#z5OheE+usDCzZa3|Ym+nAlTIHv2h+tGG3-6%4>^F)`pz|J=3oiqjE2rb zRLz?rCYQzSbp6MNVZOY`5)E5SDD;~OfSBkHfbw7+7a&D@hGVI5?$vxLlx`gw5au}D z98aRsGYVvj#aciY2gh+7x4Y&sLbsP>COFYw)<>+u2RA*rn!V+80sq))Jb(IMSx=B* z!ruSv7dT1xGk7B!%KLNe6ms|9O5o$+KiiU#plSI7e^UOV`Y#!%pUM8&)Y}l0iiFSS zDgq1+hDYe;-!~~Y!Sc5WdkWS5a&bk7wD{uqZT$Q&fPt!Z^DQa8jykB3JRbaDa(N7&!oTc)?u; zfEP>v(^A#SeK008sNJ zlZ+Y&0IbSM%)bI18|JH*h{;ZvvSf2++SBJXI883PieT9~M%#5@21a0})a z(|_{|?Jt$U%Pm+O=S3f?$pX_>8AC`B09IoH{Uwe7jgj=xf(8PW^i;_>^wzZU*vb{R}RX-9t#qExc2aDnXEQ zQE`{3x25_=JDJERDF|Gn1T9QTm)JYlFL}E?on#L5O>VEhJKTOcM^yIVBa3O-5sm5*@GL&rWy(bTu+s^62k>UQglnSkAue$lLjga21TTn5K4WM1tcP5J1{q%RkF zPz6|4`Bu;Jz!4F`EdT)K3cnlLbwIDhJL+5oz*DpH2T@~p(D!6@_-@(0>gwqhhTq6U zt{Q0bhmOC1O1T>#o{Q5kNHXRf3tE3)U2Iy%(+_NFH-e`7H zyLkh&GS&Sq?frp@p(1kgAOIiks(^)hh7ENz1&Z7~74c>NPx-Hwre>0?<7~ZIx~3d1 z%AWK{tJ8_THUn3)H{!4V5B3GCKNx*4yMZKcJ-gbo%REDT(12 zAl5k<+A77j1#&}WmPx8)3AY$=pn;HfdVB%c*V1S?h70Lu@;Laemz1y7=|N)t-oS!5 zb>`n3R3>iiAV`b6z{^4EGc(&{*59j+ylG>uc0!%+(LL=qQ%z_epSK=ApK9RIEwhGC zeY}f~pf@jvla_?jr-Rapxn@!Pv~re1^r`MEF%+U#KRH)zW>$nVW`GM+HTGthXw~58 zK9&3&_2rvUgZhZoQqZu8Ca;Mig?qe>I5%KMgg+YllqZ>`3s1sx7iNU|962iegw}AA zA#qEP(SIso3d6S|oG_#4$OeVUnh-*oH!4)wO%TZNjG-TdK=ReMpH|M??A_PW2HUnh z&C2_CMkrilGs9>UA5`yy9w!p=tS&?ng?S$~gg=^DAkna{i-`0o}ml-f9cDcAPty(quw(v-L)|Tezq5R!? z)09-X5}83E60-N*jwhS@RfNG*mAwv}qz#gU4%8>(+W*Xs}HqeVd z*f%>D{T|s!vPnf+3_Q<)C)EgSFrN-oGISGv12`W5=u8oVPWi1rFh9DZW_|sn1$@rl zm)m{~>6&p4vHv-k#BF*C$l8YdiM0CnATP$p%Q%}Hpcv&DzPw!%7 z!&Hgf`=d@gnp%gd3HhMuFZqgs6m;nf zT{KVUxiz@j^LPliz=Hw#WKKuAL4IOlZwo$+bB-H}NHA=JLX%@ZLy%rER)wC7Ma=d- z!Rijmewjbc%&c%cxQ|!-yH9M-uk>yy|JV;{k#Ri0!YG|f8ET{(*J;>WBOpb>S_CIi zBa^T6Cn6^gFHP{UK>&02KmV66nhhER04xJxw*bIA0Q43GQ#U^yqGu3T(|X=@|7GtY zL$xsgD)jS5f@$*7lR`cFV9)|%e%h2N7NR`A&FJ(t-ZxtP7A^wTe;xcK?w?X_4S%ZuV98r z zpM(Mc0Bv9{l>f{60Brz43V*2pAk7;C{sG$sfHwLEgWL7^PA41vyJddB>Dg{YJ7--^MP-=@q_X z7c(g_z)xJWQO9}lhW_0$<71^<0Er|$=5&1vlQzD{uY{kFiNN*)<*~%XFIu^4l-T=Y z1*;tAJ5o)Cgg1O~RFEim5Ea1PAOBbP0TAzS06}yhAFJi6?*-JJHyGK({9>LR+&f5s z^+%fFe-J=hC4xV3;ZXbOKu4p5Ol2;L41n9~g18JOp$2$tOZNB6gOJuh6B||{UD~fp zOgbawB7lgn5**fJW#zNv<()&*y-C6e-8a`NwJuFO*6Vs~0S7cp!>LIPLG+MzzXn2v z-JA=^M*VR*I~58kp0^HV2)X^W$su|xPzhb-z|LG-h{?GA@q`az5Pj(Qr=YLKJkia3 zQ3`d`t(!0%7Y*~#K^hR8sE?oMgF5lTjQGB27fro0324pGHvZ~i-f0(o3t$Wg$;5TL z8epvmaTwsDBJ+|HS-fq@3PY^eJ6$v7#;_ub%N8d%m3&D-YF`#ztqFYqJ($9KywqS3 z>zoutnD4iIj$Dd$@T;4Rx2 zwc{s4$#3%J{bdtr3Yeo%Ur#aL{6PPdh`+*9nZEFkT@etLB}U-QAHlI9K{zGJe?FSZ+PIe&;;`y4pMdZq-qBU>qNR!ARE2XE`TxIxQy{sY@Zr+p)0>D>*A}@YflKeGOjWpru7~jZ%ym9_k*L2HsC=^yqGv#*& zTY3+VCZyA;e3R^#SZ6)HcdIRavJZ8#go`sIj4)vs6G@@;Mmd=!G+r_DMW0mUIezOh z9lG5p&9E*T|I)vaD*Gg&t-WXh&b1C=MYL4msJ;0ama7@{W~{hFir);Qw5v2GSO7oU zB-1Uw?OCHs^>{HE#(_IiwNswYHj?Yq!y^jF~1n;i#Oku-EB9*8n~jb<+DQ z*JQAb(C2m^JYr<&) zO*P|jy}w9~geuQ>5k4RYQvk8PhixQStZLQcrXe=1ArFi2)^FWvo7D&X`e(`k5ZNk$ z-xZ{;`zLZhcog;Q4MOX9f@FPuoBe+!jHD$m1;pt*c_7#RGX8^mKf-!BH;!h?%o2F2 zZOu#o>tIpp8M(>i-eIdz3*gn!Zu)lnYU*OFQq2}d;^ifgA1%ej$X94088#K?ojXG! z?`vt{iIQoK-NT(l@nvS)Xp-9i@2*D}OM$BT!ffMGuQ87YD9 zfGqN3tdTH$=71oFE!##>bJLIK9*_1i_Q%FZMCpPL z+SPLAqt>eF=89(LbxF!D7}ME8{9pOxt9k$cKq@fz4(Y!v6{IhiF;oCR1PIszfS&+Q zDyY4`WFtQwuyy|}z>SRqux3k+!G_8B?`Pg&!oT&vPPhjM+R`SKzvV9)X%_%{1>p|~ z!(?E%tyfghMiCh?yJjgV9fAumv={hic+6~Z&ET73peI=KF4L)kBs@MW5q{K*$5`Tr z6+yPyIsyRzfO&Ao6#k`sfgS)+Q~+!o8Ompnm?`+*@$>%PiYHg#K;&-$UFrcq%?d8E zg4-YgP3hHtt07m>y5VCq3r|Vi6(p8F&g;C;%UoJPDM_d1U3N+hDv&D`PBx83_Q+UA zVEZUV8CJJ)MRm{0gy|`W@x(wno9R1BXf_6yzEOyXna(*|ScQzjs!00aI;9DL=BcDB6tvJll`oLbljZ|! zL1)pd`~Rf{S>FNwM9UJco~S25L;nY(V3c5905HWCGJ;SSf2sN(7nHINVfsIa1#_LC zXbS)l6)&DF&->gS$MnLM5L!5pGiQvo? zaIy`1pgztRdw6DEUBonPM}Ik~n^6pdC7+m%T-H^uyYLuE%_^M1L;P;|>a?w)4u3m~ zAL4fCth~=ZTwHO$vk9<9#i&1)Xc!9M2p-iV_)YmL7Fg3(O}~-I4j3Z$#*AWCY6;LB zw2OE}$5M04Lx|2ujQR+#8%0Dv997|8s@FCDibwmMn^ zSu+vEH*a<+aitO%VBoy)jKyu+7I`$BFoPH)v zj0piswm{kWz~=jZUnMCex3-ws0%%J;+PdTq;IT7-B&0YCEiX=#>>rL)?EHX#rz8OV z8%P3TrN)K)cs_|}K+R59@AdYBO&IXo6zW-^p-Q(jFT?Mk5ZsePqQc@D z=(%cr8aEPH78|Hg4aw??OJVJ-LijX;>2`T`f4~oqqfNB%QZvP!PLcFr>Q}aDM4y2h zE{ycHi}Q6(VnHUU!jRlonS}j&_oc-HS{c%}UJ1f)=uJrYr9`cefBKAyX}xvWn_%_# zX^r?tTt6!nJk1`_>ChoSgb)CkkHX9Hf{QCv4#BGfaI7Z>=AZHJe`|8+5qxEU_mxWU z8fYB=>2$Iu+F3sb0>@dC9Zksr06o!ppvh3sS1tVU78dg3$hQ+E_ims8PoVTL0D-<4 zQ5u#z4?JkVdpyj%^ThS7Df;ENzk>*UC8UQX)U4QGN;UwWC2~!!px_JZY$}AZ1(@+g zU*a<B&-c!wuNnkcbC5mN%!r`PeMUCX{7Jb~5>QliFbdaZypz}{E6WRy=*qK|#nfgtYm53mh#iQI%f%=> zeD<*?o4Mw9U0^Dh*l94a3f2+vsC46 zNgf^@Id^eO()Y5)U^5PcrVPb}SQUvkW&sJFmTIoMoOd1*ZAEdSy;tPi)5#f(L!{q} z%i@uI^SvH8V)*PHuI)HQhf_oIl3+k0Fxo^8EYiPB{r|J?|CuJ@;T6yefKML~7YKeZ zQvZG7JCt~|acc}6IVWyfM~B_HvAwllWRKwluH-$qN- zaVU=5jT|U($?LBoN61NvF7;xkbX%?31AgHJScG36q|KQ!F!qUvY=M(d5%gHcgvaL{ z#^cKk%a~h5`j24OWgXF_w z(EFBbq!_GYa|&1&dC+6B;*H$p0D#<_&^Et?aXtXMFN2wpSQe>sx8_i3)PyZdGqK{u z7*Jdr#WQ|4m61NsJb|O(KjS;ad5h;fH&tk5ymj}i!DDr4$BJvSb9+I{I(D-k)3Nc@ zQTtD+M0%6u6m<8{_1c_Ut>g4I0lL*?)`P6dl3#4O=q25>nuKaqw?&aNrWgS&y-m+7 z^6U_Q{ujK5l0}9^u8E+;U5-u%c=cnU;TteeD^$sa!vW1D4% zKAbEhMOl9HC}faJGqtMv&@nJ?ae}dFOEEX|1`A&7w*=f;lxZ>yTL5D5HS9?*W+%e_ zIi5jmK-kT;A`GSGTules1iVKEo_iN9-Uog77o2WAsuwoOEQ`&vgZkUCdO8X=qeB@+ zEl=MUs@X$Y>@s#oShz{p=1%Qgul+?~YvPYG7k&LLGd~^NZEAwnu>13f+N5$^+I@|u z%OoO^yuhM-2Nr^Vd#(S98Hlf{AXc^|gg;;=07&+$kG1{^Ij}3^3hc0got*A>fc z>r2}Uca`*-B=8617mVX~?^qad=HN&+nLKYW`M`9%!i`xpMT?3KOo;UNa~OVK^P04D zmM}yM*$ifm9eP>en!;24aX3wzy9V#ExWa>rpmprdl&Xr!wi-pT(DTlRGfa%}5O9A? zOC*Wyx;a&JJK~vox}~$SKX?hp34g%_+}*Q89_R*(zlCTf?0<^5|L0lzzcm!55(Ine zzvsT@^ghlqBYUyzY^+hw%c%g#EyJ;0O#-DUeQBcO+YYtE6P-Eq=Nllgo=66|;6*63 zDUY_jnqncs3$og$6F(oy$j`-%>KGI3bxqA*b}6kq0X;2ecFhx~^=g?xm0uMq2ECav zpq=}n#0pSM;zLi#l@qSYxn=E2ZgK3H$?p1v$YFbau!CeYD*-=l|2?1CxcTM>lucphZ& z8`3D-1oUo|p`vqdyrDCDiJ_;AjQ@i9_}HNEd_5I?Q7}M~6WVNN^o%gz2f(b%{}z?8dA~Wd&H^}N zx5Ky*(c-p@QKV8qLC^ZUKsq!+{|qg0a)C|C1X<&c&ePO?^P2UX^rQ(KP8*JZ{#=jD ziT)+U*c6a4u&=nX_v=OHiedpT<4bLz*4^f}+Pojlm(5Ax_>>I#ICb)d`ToWk3QYWM z%Vld-S5a5?sE|~^P~r4f1RnN4urHe@nuA*Y|8wyVwI>Sz%0D2OI%|;Gf*_Lsg2rKc zAV6K7KY|Xzxf@}ti4aWzFif!84+Jru5Q@VFz@FFVwV)?|s3!xjP@}qKdR=gJuTMx< z#P<+fB+BXKK2R*{_*>zl&L2|q0H)FVWIYCqE50e;PCVm9Eo3H((VGPT+uVJWs^Bn>MXz&#T*)@Xd1%UZm0U-I|i1+t>I}{5NQ+qg=?T@V0Px3s3L;h&M zDm1on$b$)wa?b$gC1D1&@XN1(O4CSD#fndE$aGgWTpEP3z^YCaYDpqr7y<=aR|eB( zD|nnL@@m`T*W&cmU)LZ1bV!Q?1;^N(Xf~BT5$(q^>_0eM3^0ZSW*P;7ms^BRe`(^$IS2Cx4i3t_696wiO(60Y*9KhASfsG^_kAzK z7~=CpGB%2BHW{(!G)YMogaZqsmWaVdvX6C#Ro=R|p#~ska#&%*zXC4zq3F}V#p`x! znL0$?myi*8e&Ly@hej$Kb43%4&zyAqY$qE>AP|SQ(PRB`z39&u4=EAnXGYfx}hr=mG2ZNYPBR z{}i_XcN)N)NwETE!T+h$uTs|%fa@J~z<*ccp!Fia;_SIVm4iv;;WAFA5RD#S@P^o} z0s^@oDbAUceBCLmwS8c^BT$xmXO`)nY@Ewq2$pQmxp;QZuK1}N_{XKHdWRO*pYoVP zOmE;`l!`(Bj?gBcja8k(Az5|)zIp&_WZ_j4LNkX(8G9)%{U%b0}tHr?;` zK@CVK-bS$W3}B+#-5k)cP%mzNct=}MSwYf{BM1&A1SY5l7SqoE`Q=5i!udd#|7umG z7*g3QQC|nTG-IAf-KZQ!hvSCoV z)k7?zk60~sC{xE#a=e>8(?M88_4n%8B353b8~I7Ygm1_57O0RqO52c-^LYUZIW(RX z>*JhZ!>;Tqj@&!mehH^vknc2bFG@f`w9yz-KmloY1fq_DzR2c=cydp5HH(Yx&jgh4 zB>d&5cRFOb%9{t8oh9;hc$q}57{utOPLD$b}zs1!+M8E4!fo# zUVX(^6=T;#EqsKo5aQV)Mw{MnYj-MmndU$yxJJ!YLH?_c1eMB&g`05c8BwTwT{9oc+82MdFu#qxTpTbg?;9J!8c2+lQ;IVpMv~S zfAhWOlU(3*&PUP;x`)uv?z*p%k$ZDyLR=f7C$qsE(8v)BGjJS2>pu{fv1q>E2A^!~ z`*!?MJ1wEeLmcRdxftk|XP;cyWxt5&kA7i9=8yr&NpQBXm z*5*OT#h;chHTq*?HjR9Q`qGpPj}&YSdyFxs_zFAn4p*%2;O`UY))$dbM5RsP^m6(n z8I$yK!eR4R)Lc!iWUodRp+A*XBi)H6+z8c_U{A(-@_&@WTxO4MgmmVbs-vnpuY*!2 zf%@<=npzA6KqOs0sx|G=U;b>1Q@^R&u+XPb=^5G^JH`g%0%@+};@GhB%v~f&QV=vn zPQ;JvrPk)6ARKtX`B^oX*6?lK-E~$i+xD}H3sL(HHxM^7Myk%wQ>|OR(yOk zePW$}0j!T*Tabv6Kh zG@D!t6k1o<+rh>=HG~(jc;+LL;!A(p&@lg)IbrqZSEPyA)&{WP?vE$A)|{pa#Lp?# zefC54<7Ap+ZhS-tHKdm+kloIGED3>aNr)w?Ihpj(didOf7NuB7K~6}>M&Md zm%*Gm8KhiVlTR5a2>`j>;|3TXy9r3+Ya;^K2ANHHKDn`@=i1#1niXw&FUjm2+lE9E ztH7;HV75WVptdpM87ZR}K`{V^QEIf?9c}7Et9Y8f2T!LsH3Y_ly;nQ%)KC;B(&B80 z4r8=#&3~pg6U_B5NJ{&5S%m+Y%%6c{_#8$7ftTe1S7GFOKpxu~bnZMcbTd-D5V{qG zh;urmBuSlVN9!VE;zKrOu4n{jqb4UQB1F1vEpyKQp$hR@`N!UALl!bryM-v4-#$78 zMz*swW)We0Xd>>N&+R>|W^cEj<1fqR8lFO-9~}-~9K=p$q(p@%Kf}0q+};FDi;x}3 z{zTzg^$hVX5;D#a^MAn&_mL*tk%=joo_LDNnZ-u^vJGaZ0+^lubKwSDF-{i%gUz#% zMki>Dcd#|PIv4`>$td-yB%8puMH`K|g;8CT)9jE7N*CqNA@ayYqB;A*{X zY8@UuK=%H}h-p86Vc;jX{)2UtVQLAHn}oa&EUvSjx>6(}WyNQaKU%fpY#jO-RBPFL zcLeC&SH2GU$&c0;*xN&GCSyQVA?;s{J|){s%u(>?d423O{z5QNlbfcdQr%z;tuLBM z4)Y%pu>OaW014?iaOf%WZx;bblCtv^fFQbC5B0A~aK_pNvfw5Bytt|pAgnLbugs}b z*R294xv&h%v;I@`LdRpF2y7LPg^j?Elj&$N@KeI5($YZ1*vPvVub=KPB$9gFZf@9+ zhTr9_DD0lp`(%&Lcpj_v$3+|Gd5o+h;vl{2F4fRS=ZLFR<0VT(7i9?Us#9S5LmJQf zPa^E&eoiPv*WHViF>;;83!3+Y@_YO>%Q~&)(g0&)%y3tGl|p>g})k#rL2_GjR(3kP7QUaUHO$`BWety&d42Nt7w6FaT9+6IzgMw~4*oVi z2@mW%Pcz>qf(*$Hzgq|Kdu*TG#y+-*DHPS4rqyuEqd!8=EiHTjP83b;H= zK;jzdbd`4Xj7j_Zx#wm}cteWgVnoRg5&mi`M;-}*sCXDc*mCb^qyaQ~BS8(wC<z9Mtw6X2E9uJ!MqJnL^!zfuzL@iW!_5x3i^_2>jtL;Xcc0t1xe|@ zMjEGv)BU8=4en^yA$S{K72L3nWIed(EKOBt+-erN>H9do!t^WW4uO?-oOBsuwEX6F z>A>n581uD?0b_zJJk^ED!UM51^}GOYsBv}t6_&`cMP}@LQ&qGs*y2vO9n1IDY$MKxo`B`5wLiv>c zmo5;2twyxxXZ?X5<8kqZUX-v5E-%plj6v2z2vNvAl5r8Be`D*i~LBO%40rrZQFK@ zRY-F&?gCXfuL}xscsA1FhqokLf`nBGsHE|UK|VJ+Psn%}d^u@txZCLaOU88}y#A-> zMicccef^QC60CzIN7-!`%tMqYXw_<)DdV7mOAf7|zLFa*2y=;GHqB(0_84Wse6EBL zQ@fvUH4ZaT*h7l{YzCd$hW~(Cdy{ygt$}a4kzc`NgxI(^ws*KKI_8G&hvJ{%wNE^0 zDCYa<^NH?wcAfLRV|&iQHL$CE(r^hgi?nBl$%rtRD$KFoKDsVKun>VEa!>0Vu_=;n4-uUCV(u=)UvCNg`TffQ zSkPbZP3n<+Is(Ao8@PTK#=!H0 zmI)JOf}8Aod%%mH!WGBZz6M=|(j&bpvvPO0QHtkUQm;=mkq(WYyT6Tp*+boIeIaWNHfi1eD?@p#QZS{$Kf& z$CNF_7m!2&nYvC#Bm)3SFA8P^5D*yq0V`Ap$PZoyVpaFE8~ie?;Ftr#5m-r=xD-1T z#fHD;H91mj;RI8L$B5r@1S;jx@Y&Se>M-ihz3B+PFUK|rL}N}G6YwmDn|88LeAl3DHNkZYz2*D%^s|85wH zUxIlP3@8T(eA57vWY)%N$||9#c4)y*lreOxM?$aNFvEFL8s&*fQ38VnG6a-D8GJKk zB?c!2E!)Gm6C_I-+l7NSV_SgE_BDW+CT-QfUeU;(n&;jPwP_hehEl+bYZcXdu?_*7 zvw6376oIAy{cPy~(fx$#>c0#Qfc7DQ?qNw4YbxG%Ga-4wtcJTmjM^>=0|A?|#wJKaSdB|b ztWmAm{N#KRNk={mw!c?hzl=SmE4(oHJhEt0ibcAX5AQJMe-<|^G0hnInVta03S~2e z|6gj0|HE($+gpQ3VE;dA2;fJuiPYsfcBocb45Kfg<^M5S`Z*6m5zB@Uoq&3Tpm7HP zPyyaUe7Su|yW=zWNnU!Xn^PVOY7Na?n=H)+cg;kI2h06a&6E2OH0eo|lzdh#7E|{t zW;0ujhXI&>FJ>TF2?JLmLB{!x;8lW#V~SKE|KrW@R2h6+ELF0h2m=14f&)l`l4w=wNCSCUghtSv%*YAEx*b@2%2>;@_0__-FXU3 ze{(`L0{u|qO;&QGf@?;k)eJ*q)68(8c=l$)aZ~2D@A(4hOF)_0lxDM~+TLJcH_eaO zG-0e#d$QiTcQaDu)<<=QDnQubcM&JKVW>O zq5OLMZNftkWM_rON*ewb#eOVSSSa<{OKB_>Q9wfSXy9U4nqyN1Tr>uOBdWiA^Ltn@ zk@jsMH~4ONNq`4bE*#Z9t6nVFDFeZ?0B9QL;*@55Hz%_d;tOg=_AMm&B6`(Yl0o;* zmY#|xN)}MENeH^@h;&^SE#fG|cw_~Sz^pfmD5Prr=}xt&k7m?x_&fN%-yNI&rK1hz zKwKbe1?R2x{6c43+&6vWAl6eGiJ=dtw~wa26;dy*rA>}bP)O=GZ^zc=Oc{F*apBK; zWD?5flKpQJX)HsKsL){B<^Na;Q$7VwCY*R0(a!A~nRa1oiV-(b7{wxZ|r0`mWh=HJW!#xF;1psSREY z$VcQCV(6Sa`_u{n|4yZIemZNTX8420r8Z_2HoAvseII}A7d3K=lF?#e4%jdwpCVBE zkX1`murWd6VhXvsxi!T;D0Im0vlLUY@8U34FFm(?_(7lGzZORzvW&CRiyN9!nmnsh znAfI0AGy$wR&1*&)KUPpU!$txgk!rhmV%%<3M)3~o;U6%BILcCa`0%r6EaF4^fekF z{v!CnZ*z*BNahBibWL z*SBp&_v+JWiw%Fn6NwCe^hs*$3UEqu3#h(q^yXYY@I!zv5dDd_iUJqTMUeI;QDRuT zU9)R2SqubR-4}$hHz^SZOrfD<#*!#e$VAFQvL7WzO!>>xls6IPMyYvEz-i;9!&y5tam0H~&004n zXJHv-{m|?pvryh=iM<*Ph7gozg}o1Txa8oG{J`uG&)g3DuNg=Uw#>tdGdE|{_iuTm z{F+`icEF6^IXlC$trf9II$v1ACwif(QZxzFv<@!Ad^FVcKxIWShFE_>BG3e72R!~9 zW3kW~R`k|^DY>3+vTo1ZMi z_Dph=P8UCm|M@s$Va#6Pj;!;5!=9kMEn*%-YM)7)zx@FHucyX>eQFoE*D)^0JSY? zXutiMetXj_G9hiBr^2UV-ita3l~dPFeM8gIzf?fcAh1@dE;UA%i(pW$@{|wcjFZB{ zuoG&$7u*m{o_94xy;7i;eAlMw9{O~kLGik6Oh6)zBZbs#^y4zhB9txse{0$QM_SEh z>2ZXaf4hQr=0Ld9m7bDYful>M+#V-53Wf1Uz$i@4M5E4shYWut7E-cFM6XYRXZF7@%=lll??p4IxQPb&d zxpc`a1U+yDpc^O>#dh_t^;<-`9BV4gc@}Phr8Z&2;&+A~6-c|XlWSd6d_(wgYji2z z?lVo%B3R(kQdd2LyoqWC?s0v~{B`A6*jm4y;pJ_MbpBt*UpC)MGbJLXeAF`^)B&TO zR@9E@)Utkv_D*cZYB_xrJadw^G(|s1VTa=mr`N~Xmo{3wwGp{GPOwiSg}L%%2fQ@`~0&0C_D{0eQh7$ zkERR7w@rwd1Q3=EAYkf_?OfkwDvfStLL+Fu!77PUIf$grU83`Fd)m+%CqBt;+x-=n zhPMhokm`ga{)nNoDac9OV~p z50AC(8}qD)mepPFq!g?h%VIJ#3TWq65J-Er8LeYc2-WSma!G16>{4?Qk2JXbT3(qH z`NY5+PS);ES#h7Djkm|1rn@CUgAqS_4ruXXWjV#KfMGZ!omNG?$9HzBlXd(x{;QOI zDl+Dhh_!l{^B*x4Pq5g)FlQ<*@6R^W`n~_F_|u->>tH9knZCI(6;}wzD*=`-uyj() z%W;U{5UdcPSO)({|7i&)C`0b~DzjbOR*vzC<@}lB@=NxlV`vh{mKGO6ktuoFEfR_O z*N&U2Q}lr3sqLtzgSei!CJKti`RB;i$sW>~N71zD$!ph~5yA$|hz-Ga62+dViC z)jRJpzKnuP5>y4;u81dm7An8*p$zFOoX6yClYy-ZHPiT=G8^iQie~LN7-4tB8^X-5 zJFcE+vv)Tc$qguc+`bq%Y zW5t0KBv}335?yoa>UqEb(_i&J9b?%!!V@lo{?TWhM4j*&ep`df`c#G%l7XZ#NxtDz zU@RW&mwzlK>(u4w0oV$e`TGTA)X>8K;a$F=2*8F&E%kbBjECVIeQPn~_=y_%Q1Mdk zzv8fMb)L^chhsZfl6EtQnPS)>;)jNfq57pzuh#6V3q%5p$*pbG5uB@yeoAR>UQY#| zG`o%q;44E*T+ITG-psAKI&ZtXI4}GtZit&``W^0M6QR-NZXI&|Vfs-?$jo+zRfw+7 zb6L2B1W^eXY%&Z#IT`(t{Xsjtfh9#)7LENs?FD!H*rQraNT4Zv44!~Y`8~hnX3~}c z>%23B`5N^$M`PcYk@&$wC?^LqhXcM>daoxV@7d9Up@T3fb+c5z3OLqJ#L0GZganDO z&n57ONr9o&>3PmHtazrr6ON*E3o%<=py zR@G~SS^RBla}t@~_VWs-q1PWhEKacfM*RXFVBT{}r@L3B#7vcLFrZBcoIVikB%2+A zs*EVg()PxU=B5&*t*KpLi9+-((p*s2ZPVa2-7AG?ql`kypo(GfNQ(nfFE`t`@}AW6$5V zD)4lf@iqnv2%x41-18-b;?(pRps?Lx)J{&Es4^VL+bm+q1Fz+Yt`FaEJynbkU=v}! zFXz434s9(H6fr1j?w^&kQowvlc0^cT6CKhv{EXwA@qw)Ou4b;_{0`D^uvTBd9d(B7 zgh!)dnwzDv$t~(*fBY*b5q$9xhW^H@1tu;daW%FXCpeeKoJdV3C5A6KEqpE69le6K zJTEn3* z2Uf{pr?qsc#Kg@S6gc+WijJPGJMywqb0)g*=J~Y)MNj|FqKg{wrSHmp3{qZcQ8H~b zODr56hZB=DzpWd5lPx*X;wP zOT8A4JxRT4ws7vrVr#^*#w^K#7@saj&cNts^2uZv%V3p9h&$p-jYK+@owknW_Pv}a z%~kX-4e-7XryHgri@C`^k>v=c$8@pja5-2&4|x6`+x0*-3M3Q|<}2xtEH85%Ez%NT zYolN*g3?XFyCC9@G*VRn7?Td-dMpx!e;nM07J=;a7wUnpcQ4u*6pAh+lM&>*KpGd? z@=w*fhUL3~l~fVw<$lu?QD2~3P3s9Z&X<0AvHO8?$C4xTl9}F!vX);2QJal=sarO} zDdqB_hf|DF#2zWx_RYB?y5onD`!u-Wao0kMJXJtZ)*XJ7DgN|Jd_fJbGmBwHQD-of zWgn6pfOKvfJUyiEu?dRl0y;BRw+&8zp=6ZSl(lmV_lH6J$6`K<_gnNy0*LFC>#nAF zKgUc(>NtW&xf!eimzwODegt`geTq4^bi`Vm;`#kKq574nrv9R2Mfl97Sp6DNoSQTt zO${S6J;Bvf<{A})O2Zjyz!r!^MnJ}8|@ zl`6~EWXsp zf9jWNu{K@qo59P2vh&{i*P{Rdgz=6^3oCeGXNbgeAH5SqAFdh?LO_@4MWYB5g{@GrRt2-SB!IGU=xj$4DR)3yv%3P1zO? zJYAE0rgTA&AfwNZp86c$8|2hRoK|CByaAY!u|zjm)%%xBBOlT-s`UsXMSROcdtrbu zcrk>%_taZ!vaMfGWA9vM^Jy!ihq4_oY`cFh(1rpt!IeE{3rPZl4LNtj^xuMU%bMJ7 zmvIOGb@)g9q3{-SyI2--54#3Bp`Ste)|4x62re-BctJ6@hSxlS-_q)|iLYm`KaC+Q zS@HvCiAZ8PN5JM;dP@<@5N?}PgvGLKo|*OD#>9swsTW_0iy`^u_EG0m&-@&X_%%CF z3Ww@sGqcjDF!S7UeWu(nir+#IEzv5o6;s`3) zG}R*9q`Zl{8bul^lhkK=THJ}EFcYAIFtQUq%_r7%3B69{k?wB�Jv6KN7r|D6?|~Z46bd)B@x*r2TSjCz+j)=OIU6I_&9aT{oS)sRUdw#(T^XKQ-(G9!F~&JQ*W z0o}4kv6qrOS5$rvCh2hsd)NPf$AS!SDJFeLXO=mKO=PCvjG3^nZzXGTDZ9sBy}JU3 z@h=-nD8P$(Ok6*A4~E3j!tvHT=HUejx(jl~bSkY{5yTmtDZY5$3lL16qK!&dv1V47G-QIQ>I@7^sBz5zk*mH0@F2dlD^a~P?p!zWejxmiy5K97gOz(r4nM6FZU3WsV-u`8fu2)tE&>VdOBP22; zl?YYCmlqyn909v8cgB3`=>w#Td-!%R5>17|F5?&kz)Xo^O#aJ>mBPm4m<}4d!|ng(xTnq*>jf_>$aO?FtWSqkR$f=A*t-Ie`a^{51pK z$;ZCDLU@p(HO6F4Vg#3fWpagHj!Ti@toF6(+uskNLjURw0La9J^;LvfE>>y`1Gs&N z`owln3#sW#RLaAM+0N0BdzJ;1Y#Q)~MH5x)JCQ1k#R#iOjib)K zD?-^+kF`V0%W4vw-W6ydDOv~>(Pzu-y!9fLuz$EZX2<{oMf@vD47F2#D{I6wmo@!5 ziJO}Afd~kh{N2-i3`*0scB?D=>&52Biu_8tK^IES$O~Lb+DI-!cg&%*u5JD8ztQTl8FI-~)8UwDtBeaSj*h!H;v#VJp+JqOQVx2+ zSt^Qu+x})_nQ~^h0$I~P@&m%&*Ea1Ic-_n@=#JeR0b4>b>tqgoj%EUyKm4KO9HZf; z$>G?oCC9v`%I6Sj!#GdG9^CC>fUQ1KgC0L?V?D1BYB+ldhj9Yl%NQSFL6+(Sx7UGE zN)udpupWnJZ4iFxqCoSI7WAl3=1EPc3_|ooZhL{{7p=N=M!p=LZM=la&`02jA7ab( z{JzTel)f{$skN5jof~@~{QG^KWu~eTtFV z)SKiE+vQboeDz5dyNhOoN+A{VN*>_I|}?`J)+6XxP`vkoha;R1du#r1Xut&qtU# z@ea&VGI4Odefm4U{B#QP9OAz=U7PJ7P?b$Yr+4-o^OK8V*HwM!D5xvo@c0d*ZK}UW z8GHv_A@}^OMK(-{9h_*2AGIddrH^&61P&hA8&sl=>6BE< z#G=J+(=cj=>#ULhDI6>!$+*E-ypnhkH*d0Dl_4K6;Bdd(QB2D({GDPrsaF1y1ki!a z90CX4H>+MIT`&dG9j7V|s|0`DSo&m)=gs!P)YnZx`I}~XNzL&foZ98zZsrQYv9dIa zsD$?MR>B6}qkNiXrw8y_2x-4<*Ij^B-kD31Ds2Y7FYD_Dxke}AuN%nL zn`hZp-Gr2`ecZ^kukEp}-Eic~vwGf2zamrDjsjl~UO8xYXh@u9PF>@Fxna#e3Wr>G ziEH>e&SB(7nQ=6`GUdti$Rnqs{f!^(?iCei9P|)3VVpmkuJetM+xPjt%W-te^iMK( zH0G4%*(>@kL4=Py(pR#>#RQlQU+6_}JOJ7`9(zbFDNy-{L@aN{kgMN?A;+EuBHC!6 z%O`^e823+ZLm09a9(@A*1u0|*deK=UtxM2y80~U2ANA=mU9>6AfGfXH6Zy}^M7H{b zgj6w4q!L}^^U^52pW?sD!%wW-zB%W4&5U>oy~OI$utEZ%K$Lt`GI*6sa<6<>RI|ii9gkD68A>@Ls-e-&h}6IV z6E69k+^tN)VxL+wCE^6zcm?-x$ugLOgW-d)XlwZ{)LH096|dXPjmNlaoOA#p5TGZ+ zxa^}Im>c#=n7e3I?0ks8kAqfqbN)yzZ;Y&H!l|#1 zh}anI5xBW3>V|?p|G<}ql>g$CpVEXZ_pr>~VVLUGkfWCxDsbH8BS{rVnexQ1fA9$! zpcz7F@hqH{v4qjw~QRJ9Z-xmf&aF+3(!#u@V?J$8ZjX_G6y6E=1I z4omK_{&i-T>ED!YsKNTF-N~e&3O)=_G~rb$0?l}?MxX(jHlUVwm?=tK62{G%`3i&@ z#nA@yNE%zy@a^LlNp1p}){uMKdMi33<+n@#hyI3-T1ejJR}JP*QU=!@cVr6Wulyar z(V0bC{LYZ~EZ&YBsh?9<_@Wqpv44D*yqqy^v-USIeRX(Lf?Y8hCa~>tHs`=Q+aZQJ zMjA^6ipskv^jcG2ay3Kboeu&R%GMUIQyU%)1~O$e3Te6sG{Rrs8$M<*&x^0SsKD(Z zz;OPTa+su&>)qgrZeCW44zMuS&lYUFBnK5Hg_q_0uQ_0)%-XPG8=Be8?KH^biagTx z@)!enDmExz&spCxp}u-7+lO&bE4U=kbeA<42op)d6==Ve*R4_>5#1l_ zNt|!<_m~trXNH0$exGLal*B9H9-x`Y_lVz^Ix(b|Jn-${LdN-gauGv{ygv? zc&xlEyrVv%D(|1pSJMVp`0W15Rl;Scl!C#e|5V46oTV@Y##n8OmcYk5^Kj^@oCM;V zn5c#<#Ssh8`O@esLHK>4`QgUroShkxMGz6ur`6@JQO_b?y?v`{Qh7)jLZ|M>;eu!H zKSBIl6--lBRs%}?c;M|E(ySQ)D#-9jdZDkqv~)mG6Orgmj`w{CU0j2#WKIN$;=-St zR@^$h1eJ98C;r4{1)hCX`Sfp4z~!gTI&uO*GBSAaJLAX`?LRop2kg{@w(!D7Dm2b` z7+oiCPUJ97Rf9Yr3em?BCfOwNaQF9B3G}xbM#v(WY__o#iq!VH@blhHrJxEkW`bSO z7@J2F`Tm14#w4B&yLC@ZER!>@s5vlGR?6@~VDL?QakV`Q5xab1v@+Q@&L{q;Hb_!; ztd2@**+h1cf95+RrQN2kyzf@WSbUsd%y0?!M+=Pl=NFVtPB$QBufU}H-9g&1T3u}( z;EaeNJkAS_1v2->CvSc5D7b+1Rq{nQBE42o3~%H#rKPKei<`1c;t|bM!~~! z*dDI)E)uj23f12-=PmA*v~7-d8XNYoRt?jn zs()bvxJiX$XJm2bDoztus_;a` zfM+>L{P0OiXSn&L%K?fi=W~K3gEMhvn+CU$(nd)NWE^nQveYH0b}^S+|8Zmb3cnxP z={aN*>Z(KBf8Lh}{Lrb66guGaMwGLLqCc49T!S@ry<|);7Xj~r%BF!$PtV|tFJGNc z$mqlNCb5_Y?iSX3kN?wa>vfJqC|jO;sQRow3IEL&stvm74vc!hdK{NUE>+TrdRGEN zA})T2cr#vl8CqO)f{p8)ZGQ-pq><7UqQQhHb|_Oc)StAI=cRk55X39f=0WZ+1<}ep zruVNH^B1?H#;OC(k4L@OLPg$w-&O>97`)w>H5@#u=YY?f_zXR-6!u$pc+@=iFCmvw z@OwQ%FN%4j;89d_IaVfD&OA-!GR;PK`* z%QU!>8b3*19jI*qoKVe#N6vf@rXnA?My z?}b2M`Q2L@h8uwDP?lO`B&-%{r!v}2HzT* z2a49uGnZSs`1Ri2l4SO}1>ohMvGv`ZUA`q%SkwCzEXHMKS5vthC=g&nG)zaBtD+ z+nvDnI4^O#$)6q2uUfy_-XVgNloT1)_P$jj72dx5a4o{1MwL}nx<;O%2QJ_RwD5^3uEn=ekOhOyJcVI$%ue@>0E7RgvZt=9DRsZCqh;*1KuB9*yW zgd}Fz64VGw*v>1v8t+L`A;&v{@3^SsW|$$9hS6!ro}0f9_~4mBp?6)@8!6OK;;=nq z`2N}qGr&;wxQ*W#s((wc9E;@lQ|naIQ$Qyr`P1D7Iw$2_Inuvw{WOd|wUH{WTe~?w zxJ4^)mH{U(Tw(Z0m|W#QV}WVUTDRb2Xrqu`GngevU_L*lonakJ(kPMH#ekg&GmX!41$K0(KpQ zmovvNG#>Ads~gQ^cM;H{<`!S8_?hkVyjBk7e11YhGc|TqQ4S(yPu*=x>ZxqowY-sf z65B*^fI2gYaRms$J8nw_qi)gt$o`?U`XeP;ZatK8^+IyDHkrQ{nY=ihpm(K}RNXX5bkC!d{Es0rJ%LpPnwK zZr9_E+q+6jHllZHr&$eMmxW`nz7FbXu986C?af2!wE-RVb?FFT1gH_bd zR?hh|XQ=A_@jf;wmwKU?*$?Vj>88Q>8neYhJW*H%dG;u|m*oxOPC6|=j)xO1gzbXs zQ#Hlcg1gt(>&6W{#`4H))RLv%2v0uRWMJ%3%2Cr*r3!mw6((>n^O99dy9#Wz_WKaG zOgEZNX3JILxNA@CY0+PUiD??i;POoFPY$;(ENY5Ru zN9fgHpw11Qkj~SHA~F2%uZF19I`Go2N|HXuy=Uu%Vovv??6|F_Jf3N^P-v;hQRn^{=xzWYo89P2j zlq_;VRpnXph#O72j8b6Y1l#S#vt5t*iop~wllPxpDQL$`VZfyY#%`As`+BF1&@aXL zum>sFhxzT5T}Yv{=g>t5bRtGyW_vXpp_X=bx>oj6cpJ`iaXoW7492VR%*{?xLe{yQS#jD_`zAg z`pc`MQh(YJUZ;>YTMe|X31pueQ%rK*>|2tRKru0JvtsRy;J|J{#Y$@6;YmA~GN~4D>01L! zOSU~e3gFYd&|_>ejcIjoS<~cWP;ih1=PiH|upm#nIU;IhF%5rh6)Za1qRD-hD-kAE z0<)=55Gp`_>7){lj{9CjuxpcLAD&|!S-vI!%!##mxbt+dlcl`qhLG*QY3oLcO@+fB zuqhU6^A!5|b1wqPE*0bWl8B1riw%Y`V>sDVTe}|%{3d}!H}u;m*`;t>E0bJEBnh|U zbn0=Y$DuFnvcuS0T(;hVH;}shN^Ao$?S?YbvEfBMFKa2|b^;mk{mw*C-K>hnrBaW6 zytxn027QBxYH24C%!-^x5;fL2^kiz!J%(m@b7}!EiG_00e%!9PGT^z! zlL^TCTd<(Ip8qZEIDW~IZttpKqsK{V>ifNnitkj4PqNa;TsL=3({sR@t zmzw@x=s);Zn%3{C@yG&UwSvm?e)Y2DVGZoD#$#_F1C|0ZxfK8~$NF+@t~bF&rj-i{ zfEn~JVPvS|Q+I8Po9egD?sEt{;MIrZwUqpmKPiHX*s1!^o;(m@dS)Jff6m%d2rR6W z>W)t6Yl$rIFuTtZjlZw*kbhrVf%(>8QNn-Q35Rx6)jbF1vt5iruWEUxLg4DT7u?l?VvzR}t-G-9($S)P?V7rutK_Qf z=uB^#d@KRhwaS(-aGM1(7IT|KUE&sfOz!f{!E@v@Zxz`cA0fw%;_-P1U_y}@2_`RS zvd`9MBIUeM#DypWGpCD?lu95M7lD=tmQ54&jmN8m^0*l_~18v zv}S>}LR2CJo%s2od2NMhVwB_3z=ygOkT%yNNFfna&CFTlFsQ&yAhg$}$pC<=-d)S& z5lIhc|Gw0Zj?FxSh&&=77zHS~cOUZVRKVCnI7hqhy-x2BmPFMUT&umT5 z7R>?Sec}Ozt}Lcv?{{wTw#9yIs+Na2L~^(dQ=Ym0+(oTz)M-$v)3juj1EnaRuF)PS z2FjFK5HTkJw36{RiU1JU(4a~RPOvrLO{TdYfNY5R@-BDf9NavH%Xe%=XJ-<40;3<{L{d|r87gWzv7zmna`Jaq3(_I3xB^x0CTzSE4 z(HjjMBLIA*|39z&Ky}d#0m@t=gIk_T@c>+XEV#ARzn9`AWjKYAoh%=>yLFC2t;&VD?qq{ejb}9l&$>V zpzi-$GnE`_&jaJ80^kYqU^E7+TDQ50(#&u?Q*#^Rfr&8^BNc%eVEtBYQaH(G%31^F z%KOKUy*Yg`&;oJ+!3vo-%;=BVZdx7H1yMvpc?ei9mXse`Oi!_qA)ml~27pjl_FpUo zif3xO0C>L*$TU>q1}|vhucUW2%G0zKm(P(E$(u0N%_O<(ryVhHJJ`QD94E2q>d0o% zB#w)nPLozlDZ&W@Bl@6%)=JAISVqu+6g_e#WWg;*7-+flMRfJJM%dV4Mz~0Kwq;-~ zHOHlyPx=+zrG;j1OLT}K<7a!AHHl}vGyrrDtZ58%~>@s1YrhkxeehiqBm=c|-kV-l+j&+*T)b6z+z6&zHe-t(jmwHARAlux7P#Q`tvtiFK|& zWg$0WDfO4l%kM+M=P^>DX1kb7C)ZZm)xx1k8*qHgr*^kgFqOZ1r)833h>UAEqcjfsy+NbevB-3ll zk=M=$GdRFa34&_)>(5TMuSMe~rO5q7&{j8z6gnD9^kz62;-ZBSp68p=YXVi|(Sk(m z9HsyLSIgVnAFr*LQ+<qLni`nAE24Ivwbv-;&t~MxhYSQJe+)Ti*CN=2$l>KG*b% zFp?@-#!j~)Cx+4nVdw~Vww^Ltw3rVua&;t~WNiJ zb4{^{oz=DXRmn1f`3%FX>|=)!mGC`t^Z6yG3&TMXKo4kZEt6l2nAd8_a`Jzp8{cj{ zDklO4Tvi+P$NiO~IRo@&u34@S-8C#WM@wv?CTnQq^wt&&l}5@f^u2UqM&y?&?inQ$ zlMMYz9-5>>ZpaSF_}7OgCdV2XeF1d z0Zy^c7l%i|#$0PPLDsWgTuj`*8zn(1?FBNtQye>QYoMoBU%9Zt{Kt~FPSDU)cafy% zYfaudITh$d0sRUA?a`kTe1m)dT!dKFnwR8z%^f`zm49dc{RdpMc>axG?D@=ln<8Gx z3k&)|QyC~>q|8B}TYKW_uI%AvG6jPW_z8Ms@baK(jPBnfsZvA8DVi4(*)DEC?FR4y z4U}90b!?3Rvfz%hw=W@q^1q{_ygc8OM^F)bO6Z+MQ;|v;W*3XI9uq^I-7-Tf!25Y; zV(o=*XMNrh=g{{2_P2lh>@0Ls48s=kj*bU-A5s{s227+$rP^2k&X-#77=nkMW=6V( z1(O25V4Gl{Xbw+(RR^>bSkuKsx2@T<0`=ae$2H46i}{NK3q&PH?Cf?k0=d#=Axpd4 z-@ol0%@Q*X1TkJ{#={-saj5V}DOZp(QC zkbxdAXodR1_1)GD#4A%4+Jx$5r4gfl(zmTV9<|SeF}&x3KZc^eqg6>7HeM5#e=UV`%tnH)UkSXuS zf|GqpUyz|u_yg(!QhZ6By^^m2VrnpM%G5!5)?#TO-k)GQ8kDMHecNVy`E#SeH9VM6 zvP~YXr)@DFb$?B4uk4vwo2b@ z{5S)lEGpGAeDJ_-p{jb*bY|RjFYs}e`-|N}{+ia%YIk9|YHgR=b9#u3>G@%@i>O@d zdDsZ10=18WTfHj3=MmXY7+T(3Y@~MW&Dufx%aK~C#R3QQgix>v;1qN&?D{=?!uUt_ z1FZXg{}eycK>5c1h0Ora*1JWKE8`c0BJc&@ayW|#M$Q})q|vEB=q(f!X{6|A1CXYF z-GvS_3jPp5Q4*^(i8@LGAr#pzS_|H1llfsMzW7(j8BNrwSizGZ@e55HKnP~vxJkO)zhrm19`rcW380+oWein#v5%vBQROIl6M01}lzXHEFsXnUOes)YV~qc{?uGA!rojhU~9*l)>n zU1Zb=S91u=e)nImd?T?@ez2{%sMG;58%EF_vQ8--C^6%FyxS@p#o)?L<-E#BK6Lyv zSHs`9rv9uN%~t6JKEoidmnaye%A2Km(2t%#}>C zIB8jFzoM<$B{0^yP(-In+H80Jnxf`TIf~Gq(GT*itbXGeoGZEjj-b%RKG6rg;{3bH z3mxfoU4RO-kxa9`i}E;ri0Nwp{0w!!JmsylwRTeET9-mf+=l3mX3qJ}54voo1|{Jkkd>>QbaDV9u|D~J zJW48~h-%3zO8fSJKcMIGq@1(b^-NF2Q_RK)3eVPIX1k0DqA_ zWhQOD)YYv>4|m(g_!s$k4%Wkg!OaG|O#cms*Ovs=pXd`Q{HeJ#As-FZlYF;jXE{wH zl!WbV@9Q*xa1rxMC70EGVg)|INuhC)oXo=$=1`Nq%{dl$DRD zXE(Mm!t@gu_mK37D`(BWFQ4H*(7=SwsO)>y1!ija`O|ET^?SqAF=|JiG@NDU*s8yO zf{a4p^Zl`5Z4`VGl}i2BhyTR8 z-(|%=u(hB!$34mqYq6@s8Z1YLd@j@QCB}UNF0z!X_~XwY8vZOP)QeW)ZV^8$><~s= z1^%F5-V#HOa(i~!?{VnA%M-E7gF~iMdUlv$rtOq&PxtAER=AHH3(y&{8|!$NrX6ZUrVnF{f_j6Zg6^ib8ce3#y(R#(yl#R zrf^#h$u=6=AHA6lDsj#)m$I!k4jvwznPVWoW8o=hyuO^}@+KPoM36~xetRt<2- zAH8!vTeZZW2Qg1ZH@|Y`2U(}44T-jy>uuljQu7y!=x`w@#bwQ9os;yYCK`bIH!N3) zQ5Xt5vU0-q7gS1>4w0G@XZp&-Luy>2Zx}O1kF1WB1+kA4^db7GSKVt%WiAIQbjO#bHbz>gO z+bfnx^sAldbk{R-11^igG~42&C6SyT7VYV4T&f?VE$fqS3Y$Ol(!PFT*WRdEODCQC z5VGyYTLlFabPqOXtTpUjYsV2AEqvg2UXt$;Cx;Z&lG1*(wP3YbJV)N!C>TcAPH=H6 z)XF24dLR`A*WAj)a^EBUsk!}8BmL9Q{BwB}0KNqTaJbk;QK8-X0MHwUiDtaBXj#h> zeo8Le-21&Z7pVw5*B1=BHdW;+PC)QlvNczz*j(sJJtY@E5YiX$jd(6WPk{MmAjHq9 zoyR&=)M@UEy9TeP0E|JPo(LyGUC%+%FB~zb&~;#5c{fR%P5T`#61ADt+(9A#9h;VB zkQk@M1dK0EezFDKEzkFgYNWVDLmR%O=w6Ruoj$SS2>8S`UEAa0w=h({VJ(3?K}xsi zH-*Rv37x6Ij1#DR#wfVB4x5EV#EHHSAfz^3(8X~~@MMU(w{OmCsh0ua&Ow`%%I6$p z6RqMIjLA<^xZ8J0#L+NMQC9RXV)NL;J@WoW@6NPsYDQ1b&B~gvF@h4!6D_(8c$93n z1qthgH{mfLYIvx<#0#xw$FH}=L@{1%W~P22=~2XiI}6FbMxczKI!~%3{LZ?2vYS8Z z7s;m8v6n9Ig<Q%^Az#?-BRD-GvZpMA+RGmyg8+ZL4MY+B^{b**b#Ao zqaT>`BRWIvcDMM5jCskBVvqTdfmF5odnG>{v zBAlOEXheg?QB+XDwGT3Y(zQ7C{JhW0*N9}{#9MxLIK3va=>&&{s%s11=u{-6vFG^A z?sweH3H=Y8G19Uj1n<|u$(#c)*X^Hm!GE?V|I=E;0mC!Ds`W`9ccQt^@r5RCD~w39 zzCkieMrNJ1DGwl;NLqdYLgsb%ATyB!4V*G1g1|Z)NP0}-Q47X-iB&`SP)sahk-|ap zsq{Oe;8xV8P%WB8@;jtnfP+AF=<>HEi3U!l2=k$DWiF``?=g4?UD3AQ=E53`&Imeu?_Rb3UXKzOv~e`UoRLf!)7uVkRMABH!OE zuWll{@pIn}E6_5JGDW#kuVXiEW2~Ypl-#v&HLbUPNMoK0t<$O(E#i>lKwRyEN?4lvJJ%mx z@Tt-VD?^!#?zO);@vsSB$5f*W19L|6BAjEEB}1jhqm1X1s-ppPE)0^g2*C#&>}E)Ej@QksUPBunwI-ANA`ELbA4hq)$A3ghnxeFAe!l+@WLDH390)HX zEULSJ5N{53-k}kT02uFuS$ziY|EWn54tFAMQ6=%`h<)jgARFE^mWxLdiHN1#fVD4x zj_i*QFhm9$y#s9Yv%ifF&RuZ@ervk`fRgHnR<1+j$sGEFb)IC|0K8suN@#p&G=Pf! zA(cBSQK3{+1h59-BJ210O_mBenLGhIKCkW7=?MF>@w8iBT=&KjN{0w5JczGH@gj^1 zuXDQS#CS)}J^`w(b2ruSiCKF?O6%>5Y2TFHTr3Cb4EMy(ER@Cu!e_CN%&)(&s+OiO zYIgV;7J`ozSz>Vg3}QMtTYWX58I)Sf%KI18d-j=SKfqg|csRR|WPFO!G$kV9r6-ZP z`@T)BsZ2fkD#FyxTmjmt;xi1vEV<5FO~rk!xDZgnryLKJ^3L#v>FbmW`-1;5uhE5} zL^MKg5Bqvn;iHt-S$;2jTv6Y?Lz0;hSIqng^Q<+yz_&jRwH2+H2X9J-^0UqjPfUrWQ=w&XDw8u-_lUyNkuUOhaV?&_uV%D? z%rb#Dr}RJtiUbA=^3RGVCkP2&?llZ(1&`~YvDVj}55z4>`&oztkYZDZ??xnoe^_vL^})0=y&?IEwlg-e^@mP7^ULhDF5iW!BBz#5OBwEkkFq6^Ubya zxZT_T1~;MmW=fVo5b*=#fCWbJv^^2l*Qs9DS=QbfLvHZAA73tG`Q{T}yx=wRNZCXR)5o4%Gp75x(d{tm7z55^!P9 zRvYqgzs&Jkh-TyEvpN?rJAlSl_d_!R8JSP`v87OXg5QYRgCJXvOC|@7hj!=W_IYL; zao<}rrc}&S{=L2cwnVK58knm-Am1fg%>cXJemy(oo{^B;Sh6#|gJ zQ=RZ|rUf~dhk@8?iWtT_AHKl@+-fpL*lz39?g0puM)2T#m5?sus+Wl3<_4PqG>H%r zC90YNodq?4BD*27`m>LH3H==R$F$5p@{w98sFA29#I- zQp}FbI~pi^N;?D*nK#l_BUa4yAn37y=>9A-ksyw$otjNPl48bbwm1L6SHpM<9q*3Y z_5g32*Z}8o%H?dbQJ8+VK5*AKMX@Xo>Hqi6LSRmA3(O|r93!^j32;E88U-x5uQ54e zNc(X%TbBlk+%nnOJqcI$N1onJ(y<-9>$u)gx?&0rmG98hhAoHK5Avi3%yYXb8bwmM zg9P)UO~sX|y1Wk}$dYsq85<*&I&j6sRb9{!zUBK1eQ6oEb29!2yp!Q_&kwofwI2FC zh$?sr{J=VlbRqjL%QK-ER=drUlr#%_KMs`MEQF^xv%j@Ps}>=)wuhu?5MtripE7e_ zSXgOob1<|`rEB18h)y{qtL+^M)yN%IGf@1M##hSFSS0S7<#JtQeY%^|9{;szyWk52 z1|#9-;hrMG?>0F|j&pjWlg(klIrwZ_%i*8(S?JuDYuAQ*d=qB0?QfG$?$-GRcJ57@Hs1v5X^}BIIC7JyIM~v0+t~=h`k=9h z)?)V>wMSM`*G+w2cBFh2>xtQ}l@vwg4=XQ%jxFTlbIJ3nirHoh zK1Nb+eg?-+i>=2O7AC(kOBkjIgeUW$FkJbrlPK2DAHLQ~F(~i_f1?_V;j6@q3*%xH zq<@NzH|u00(MkJ#ru4S^0|r@{HU~a~;_S)FDYId|F3+q*%47_IJ9;eY_Z+%j@K)$0 zUeImqxcwwDKE!r-OzM%~g0%8`0ICkJ9LRdKV$0$ zZt_0oOKm`^)G#h;vwjp_A(xGgyxDd#{qopG<7R25Ezw1E(s?Pjt92?VO!<&=|4DG# z4dk4fA`>j?hyRoDsq~h$-fKCf+}A)3z+B~Lm(Ldt{t@gO2nVfDvb#>G;)0NzXC zb!ET;l!Hxz%%I@Tq!(q>4UNJUr^=Y1Hgc%TSG2~CC8db$)5SqYOk z;{>tlTM7FTFN5BEV7np1WT}>ifD{{$l6uu)fioa6)hqZ|(wuC!<)fKTfU5 zv3Svw>?Jj<=RnEUc%Z_!>CBAH;VufKz$KT~m_b5oWSP(qcVkf;`I<%r)SQ|x<&oZR z-(4(9B`OluyUyOpk|O1D&IEjC4fPNn7bxEvHL1}Nv(gB-m|#{SQ96?5EW6NUcQ5v` z9j6th0%$jad8(^euJ74@tqlS5RIpGX`D&aPfd`1`rT@p?lLsk_UCpw~srxpJ5;K%tTB@e(S$KfVHkoG)%6+ll!0x};2 z&C{GkyvZ@eNZd0MEGZJKBCwuS5AQtrevbrqn)dlhRZxue6m=t~jt+1#QX{_>cObL^ zA}y{af(u@6<%BVb;dI6wX^Ma8MDbYSk1QPe4TVRbq@$gGkBU_;`wW{jo6Nhig2X|! zO?|-7k#f%)J@~$A8Fs+Z(_AG%Qs=7J70Ur3=L#8)8>gb4BJ9F${|pBbmTsM6$UV$6 ztX@a)Qc%7=Cy=~f?C1!}l0qXsV~zzqYn`UjCrl~k;jo%>sqlTF(e_T+eb_gV(;EhH zp(^3`Iu0^I#x(JyB}(Mjot%&#e?bbH*u!pKtMtZhFZAI@8U*+et=2MEeGrUYs zBdqB8UGk7Hw&;+!Bvp~Ur)nKsIWM8iJJ$Z?3!j5SgE1SSfNevAk~lTF{eCKV9 zL$}l5=zeUMU)vd;oK@zM9dZ|`JK87PUm8<5J5(0@^--)!fxWz`;t*+>cL4m_M58E^ zJV>&hs&eMt(~^xr(@wbeMs`931XwK^`kD8#>hV}FfugM;obYrS-h;jyl5x%!emC7C z47qG@Ii4&{m^}SvoR!WJOT@##c3E(*-v$1LUxBBrPI?qd$entM*smxbq}m z)4rO9^B+bhhfw7)YU%C#nvX_EwGV?S@6%v^#+L44bE$40)1 zmKb1@0d=$zz)pt(%nkkz!l`*`o`R0ZiJ1WXKI?To!unh;GaoVt{^VjJ0{i$Q9NzI*-f9j$;GyEYmB zLEPK!10EL<^|!H%kTsf~4OP@1ITKLv0mzs^0N8^5znu3qbZ z&%`u#hjz=M@>Gvi@Z6|!G#c=HCVAA+f}Vy?uZNHPh&GL&M)duiB1cU5V+@5Qi{)(? z8wkaK)fUT_P_}`{6Yh2Xj^j?kY(kEVM%J#eb1phrOAsO^-r-x4=X1FhN-xq&&sWoM zVWwN{592ekM@im*c-vvmQ9q11f$diJsI)!4I2h6BI?eS~WqKSPERh#e+$EVlsnMSh1bEe!_?=mGPa*o7r*HqqQTc&t0Ecz2#c*j+2ItOhm@>aJ zWHudr=sOIV>1oT7<|2f?C5uWhjhP`qYv~2fEA7UdEQyax0vB7R!`GNEKV`AUbM*tO zFC)f45W2A7v<9dK_K5$W#MTR+x^Mg$LX<8j?({o+nhRKTuxTSe)=|y^ITa}Y`!wdS zmjLQS(-A6$2wTDt6a$LFUXr}5Tx$t>3`iPHH>Az4xbm4ncPQi@y2^{}uZ<9Fm>CjY zd>1G@mU;vPA4`vRr^jpUruJ(=d4)680?Jqqa4x=-Rq>ie3A zZ|sJ>8@wHH^8CW<3%3q2EC-$Tatb}*Tw8l%{Vp0M2f7I@yb2MB5W}?) zl27@944!IYi`vGa9e$dWefO}?2W_31TL9%81axJhENahKh$t4{D!0b?hdBqw!mJ`T zTQnsH2^0NgY+>4(4IPcjv*CT4AAnDy005vDm>Yuh?{wl1Q<6Xhq)A}>$(kYlMa~GK zXa8?vu?7N2ivlH95Xc91cW3SpQ$dur#UN-n05D_XD8jeY_2=tu0|Ajpy7*kMa#9=- zEt^PX4I!Y}H`yt=L&ADw7bc>BqNHgA(P7?P{tleE6v#zMA66a&p34;Y``j#5uR(lw3(5oGNVPM`J@0;xWBkj#&gjX94Z84{ZK(-LhgyEE9Kh~1Rd6E^~!1P zn`DdrpgG}Wwx}(NH+ZOQ6w3-3{?B~>@8wm0GhZ|UEdY3Ig#=jmT1l+;GY3f5>R7wP z>qf!Uk;ag&^3CGZ%`UNSE`-iIE3$cI7?;)1v&`X%P-?5<*$;aASX7fjHqm zEM5hu-%*9i07=yWk`NKHX8=iQm%UC*P54hZj(1_Gy3kMBhSs~Z{>LkMP=)jyPWe`6 z!p-`TC-I?fBl4%BZ#^Dz(4QnJF}%wf3?&8)fm1`iAu`*aqeEfpT8w zY+pV%ce8q__z)7z4~kzXQD`q)SR%!qRTa=wDG~b6twdV8p5)M$V`_ec#;ZD*_sgf~ zhXM5HAqx#823(1HzS~+7{)iy@=AO$ZlmtNMJ1A#!Ysw<&b`X&Bf(QEywby>HgQfs6 z4VtB6#51@8&!I_#%W;|GD*c`V>7x_SwPQ7+N9=lSC!Yw0@B zw%3JGdWNClHn<^c;Cp{&J`#yV@86rrRxt!DnP{VuNd+$!pZpL*aV>CoJ}KyJnFVKd z)URYeKa0d<2m5FlrpN~iX2B>!&SIx_=?0}rq@pBs0O$)tx<*EShIU}lIXhY?i_K{z zrz`4Tt0&p}`$##rsw}$7P`Knv;E`gg*ms+c`kZIT(B7o$5d7LQUVV_w46JWL)j)xU zy=aRJ$b|XcX91HB`Q0mN+|A#tZ#262xV@GMCT$lRMrm~TEwi=!$qq7*+(2#7xF&d} zz?Nk;9RwcF7sPU7V*Wj?{G)#jc2AX-KoA7s_XKQRNGUY?jOLZTQ~Y#+CqroRuxS4b!s}`Jz6EzIsb%w+!^&j~3{G_0=h?CAsi8 zESGT_jt|13Gj)cUa-h?m7af=rzl2{pl88#AvPz#ykxr$9Kg1fP7!5Hdb50^E#>p7ujOZyU#ammp*hmivzj6;VoZ*&GLND6XpdR|p zM`~s~P*%&d<_>1#&`s#O$&A(JpVJ>i_XrV9n6w$_?q=@zLr>BU(R8U{t~OIP^spcN zJ7}$I0II}44a<^EzM!!}Z1sx@=L6Sb2}3QCwdMfnqDomdRkLdlgBKyn(+w1cLaiUh zxB}*;IQ(5j{UgTxSNZMpAOL86fwXD>0*HH=0sx?>5Yd000{11cK1u*qQ%I2k00{kV z0Pz0*=w(GQqeuB~#Jz|XqiudSVz$}%(1OTh9!ZClRj}3`u2>L#Vm2%Z8bBM#S5(J+ zJo5!1{(gnQ(caDh>aLlX_0nxDbBz+h4WwIl@(n*Khggk=1WAn@J7egSI5=0}uX4-2 z8%;BbCfF~dwg`<_fhuSLlKc$X`94^TM(}#16o(6qQQDj8hPUYG9M_7O`C}~dl%IiT zbADi?0hJsI}Tw9ms0ljM6 z`u&chG_;F*9ZTgjnx)Q-E4HjZZQf}7Qt&(DB+e!iMz<@RG5LJ$dm#N>)Z-s@T8<_) zHn^TEds%D&sMXZq2$Ld~mHPjPF#oyAZAgGA-d&8^5d4lV@Y+jOo#ZoiXOrDYk+3a{R%8aO`i*rC%yEMnY-sH{x#_bNd}K z+%k!jcx*&`7@%@EpUpdd;W0v{Fg?*~7uH2|ceoZIHAQIZzYqs6IeOu{eOepT%qgOs zBM2(JSo1Zj8W$w{0d>YuBjdP2g~RO1pTvx#?8`84Ddkw%9zlhljPc+v5rlx=Bj zBdiR#G+yvDs(HM1e@dxT;L9Ksg;_2J-W|_5`ZrM}0P3h`mjTNV%ZtB#ie>>YZIcGF{gNmr6Km0ZBslq`R7!5?v(JC2d?aV+<g1EWy zI4*={_VHjMx2@;%h{!}DNBh~Puac2tcadKcso%dB>f3`mHr(UJMyrsjvXmj+MgHlg z@p#k&(j2YkgVGEdWLh6r@L|2`K#S@;;F=Sz#$50Q*bzHC-Rups=KGHQjQ{?A&Wo{5 zh@vnmZX2G+IS)Jp{{rR~{mbm#UvUT0-wXy0fU4e83cxJI+4n@t11Y@KQ^ND*A$?H! zGX!&k5Pozb6yx6ts}o{LpQf~KLskU~UpJZpAUQyhEc8$i^;1Ij6Sy#HWo`AcgcPBU z%~;~`CdFTuL>W~GHFsi<`UWj#m(S@WNFOEJt*IalG5n!-$XfD|rFCw+9n|0cOCsf5Q zR0QX8@azZ&`~=w|fOSKjzJ%L3AJlEy#gAvm)I$REvyCU|(D8nQ-Q0lZsg6gaW5_%H=MBaQ&(DBD?&W;8?7{r_9j)dIXi}9N^gODmR@iC)mcXgZj z1|Fo~z~T5t%0|9R#|Z%B&024D*i$V6ZA{hHEpB@FDZE4 zbqInCZ)TDcd;&ti|KOA9`-v$ENL(?PRzmiH5?UXAu#tud}XUK&P&FpmMk5Gx$XYi?rMVl_TladMRLE0=6rC|vQ@kOeHsFn3< zWT+kEabQ`iW9 zv+f}2CGh4=x|sG10BY1pX|FdSQkCr^<=B&Noj1h#0g$>=OU)b2=5)|fhCIekX2#Fv zjWByFyYSG8hd+shZOxM&NYT=NsM*FpEoUiPA%-b#@53_mLAR)T=-%C)k7t;o^Fz-| z4?lG2%DOaTQ|()$?{-G^QM`?CX(vEnJbs_nfV=*f|7!a~U;pl`;G>)&`(*#!8Jinq zXHa6e7@@YL+ZJi@h!Zh$N3Td23K&0FJGS^g@FD?aYWi);UJvJ0MHK?T||5{%@t#x8Eu!y{8@v(t3ci%8h`VH z2a$SzsVa~mLCu~cDKhV!tNAgSCzM!bBXToWIhE>1Tm69y%dv!qcMtDR>}V~@A!Y? z@<0;^!LcfklElKr&5Jw}`X@0AtD`&sfNzeycyu=jM*(kJs7X~}^e`E& za6veB3=|+-#?NZEQ3QXZ4eW1)X@$hphR7yZ5^LlUJ6~}a9{I>1b$4bxA@rv6&Ks5V zT4Z-#Mw~F~>n(go9OJoB$Vgy_`MZq#NGN-I2rHJ2BG(3(>ui#~FRbiE=>@xOin6sQ zF^s6ulE0^O5TpnW7Y%>-tTUdK4%M)ET|o_P6?vBGzWYvSAA+`UV%3vurYf=}rtiT| zRX`KgkQNC_WAm7P5Lgsj6DJl0x6hcL5*D{4wk6tt2SexdoYm){u6;s^J`~JLjUz0e ziBdV3g&07ahq|13PbZ(X6f&QZIT1; zv{;R;Pxnrp1{2?>@?uLW*b+0&Q>-wXr_|x5d*tb#;=nI-DNM9&2eyPFhxQdT=A-oc z{3+SSiRIQH{Tsyx_KuCh80&&}izez$ff#W4?kzzwZmhQRd{nrskfmJL{7_UHfyPL% z|74Aje#A1Ldx=#%K;^=8gfS&p?k*63Ulgu4ccW^~V$#NtWU#xPVTRQcXpo^^MH^7- zUblB21h%h2X#I5A_7>G{!(ksD2FFUr>{w^kR}Z)$Ffz=}oZS0{vlRU7pa z9DFtiX*f(0P1R^)M>&atgEZQcn--cCIA#S!4tKfW!idArqi%ikd*XIR3f}ucwYeaRiNbvD0>w(%0n=s3#Hr<8mag|ZKd3z0 zVVQK|vz`XKN^;^(@Y-eVyamMf;qVr3N%pNRgM9jN^578@ysUQM-!L{#=O(w0KBYxS z+L8q4BjtXmnZs*0fo_!-3l<~IL(k_2U!lE?5SvdJd<%$CuNpbL2~ zxVgit>tS6c!JQoMy}*$r(rS{`zFlt>CiKZ)+=Za*eWm(da~ zWud62$0ES*k^MYoFw>YxJvZF`8449Yzb5{PGmY*?eFRbBZ&U9f<)mr`i3^+wk!Y?k zaY%>=D?FoJqDwPm6`04=bNbZ@#KLUC$T!(o!;O9xPBLN{PVuwVjti2y4S#vU-pb#B z%my;S*G;>jT#j?5GmIOWzJ_B=%I!x4WNw$`fjRfdn^hK1{L4r3plQmu8w%_YgiY^~ zWs@Jt`nQ_E@afR>eXa!!s88?Kf}2DuwzCdxAlM`2Y*yE>qstqo!u#88PO3fh03z~YQLkt|R7J<1fjQ`)`^<$JI0B{lK0*+k} zgX(p_GaVI=V$birzPdCv;*5_S_e7^%j2+VgPz1*=$NNVPC){1{SMEtVOf- zH0hj@o{`(_$az_wRk3h4#CvAcpp6knLqnP^FX>Bu-Bj;RiP{K?97*R2;k1pO4t0(XQH zHTcH?-nI^oM$k}f0f4`CwxD}LwxI#+UOAuUI$@c#`aGRb8R5(S8Ik`xcsZew!N;aP zm_-1M+VTLj_dj4HSOF9<0N6Isu}e7e3sC^9+n?`n<@bw`e$G9R4ML?l?ty%4XQqq< z5|bfB#71V@H85qmYkHd5}w^A6oQ1yeh+Cq>2|fXV1sN zM?IKDjxLLW)g4aGLTjgjC4(@$$T*&>y1v}l`Y(O@6$8sU8Fyu8_r%EshP&W?%SP5O zF-D}iHPk#$<4crde16TLxi5_0`=WC%gMU^ee=)jB;^2^uP4YC&OH+;iJgIh(4q?=m zZMS2a9bBlkuSK@iWQo-E>9_^lUSHX?RUPGFcatyC zcl)YokOB19Dx^iTz{N<+ZAf|MO$PMTT22U3|1sDRcJ8w|(kwjO-zc9NkGM%v!DBs! zSXK{gAVk{IpJO3Y@efM4Er7^ZyDHx0zaanbnFsh!2Of)rzzdH|0T$N+F3MFGBz ze{_Qs+avpdYjZ@QI3%dYe zvszPd!|{WfTIjy(RFq)hrVdt~J4c5vVCAD9lbarl16AQIX1b!ok_R>byX$+dh*L7$ zx$%gVQ|@W6A;Z_s6I@&EgZl!Lh%v|vB~mTuun8afEmW6or@mI3gSh~Iwh=TD4bZ$5 zdOXVqLj?IJ;ybg89WE8fifE0`5srRpzBZ7`?8bKI0ok>iDGd8EdrCT~oHMJ)wX%@J z{MAW5v4_a*>s0mQn6+@C7&}f(oJ5Vp8f+*6DM-mWwZ^w@~SvY&BeSoB5N`OA}zAC5_0{rE_{G~P6FTJOa+{0Nq zwja%3>%bI-(}q2H_3Jy7DKdai=^zz%B?~Ga8MW7D1x9C?DWomBD3k!{3R$z^8ZI85 z9D@*8`;bK>Se${3RUT%tyZ!G2e$-}F*xy~-8jfL+)&)KS~I#~#Sg*^lmHcey$a z@0Ln4Y&@RUZl*jZRZZC^E?C8KYC1N$=B{CVqTCv3{_l- zWkFRz?zIOyD{7s}g&u1vEMzjW({P=sUpI)^?~}85uVxqDL%kV%IidMb8pSm;96BtK z6nI#n&mfiGFGV_LhR*(tiG5yXo(Vpj!Z4TiR8x*h)jgvDcy(gMnJ1I&430;DeqioY z)!(Iz|8aIiG%=_QAO^lAf7u&oH<+Xe0#FBS{`nxQm<&aL72OCxK@I>k{V~OBRCnfQZx*U3s!v$)7s7N`b+{%batUL&t5DD zAsZhEb|MHcinITVbOCVpPY_^s@1Ir`048*l4SznWpcO@pa8}&}Vb#R|G)S%@el;>d z%{MXeLcP(r2EcHWK|FUiizu8k3Lopesb-yNg~vS!;H#n4V6|1k=;#N!PjQX?ltPz& zBXV>4bhSS;+kT%dm|z}MY^A+{{+eqiWUP(IR2RR(Ce*xJ8K1i7ZzEQi=)qCgw8FFB z%zU7J%{*z6EdFo@8?&qGVkW;vClpFl4g4AqO$1RmfTW|{qAPJ$OUv72M-Xx^3l#6$3o%{d!4s!>3`XrFKV%aRI!Az zw;fc)wZ?JFwv3DYJH63a`Vn!JMNcgZ+yR3$ygM zqIxF$=pS(wZYhzy^J2&;Xof|}!9K-vbiY!VG#@$B4XW?r`cmrvPJr`hlEyT8Rws_B z3X_|o12=XL){{Ul);bWhHGzLYG{Sm@dM&{kg4PXtgTS+|%^Q4C0?-z86#*V#T^0-f?*ext~i^t5Fto79j<3-M_@;Jgy)XV7M~(Y_e0r08Yd8Q+(Sbx0C?z$Oa88xJArx`IoN9J zfGY;_g1HHv@$AEdh;H{g2a-Hp>7XRISl%7X5p(p zrlIv^il~JPgl$5=US!yx7mS`(_YpHCFzj0 z10@eAArboIrkPB3Ijdr#d17^n9yx16>$3j8e^#SZ=@$E6L@TR)IBc`lWj%p*ZPySm z6bF>%XdK*&1eoS4>PD#f&@r=F>0QPlv{mtZS?o=IK_l5otTZ*yjj;y3tS=<2 z92^3*$wh@QcD2%mb)yS)j73@0mNrmZ&aZ=ZOTJg01(9{bse)1%U4|ej8xS`3bfSK% zym!XoqV6A7Xq#rBM97}Rnc$fNr5M=+YM9jo!V1%-8U$G{i56Y@E~MRf9ht;NR*J?tFtjgo z!HNE5QX2%}sMUspmcOXe7qRXtYk7VV%)OF6F5|_oKc2H(Z%nMQzVlw7)z%zD?xt$$ zU+`;&Ln=bTv%i0FX3b~+OnO$h^=%wFsAAAB(~svO6GEQ7KUh=A`)*tHh6gON^>r1| zu~x&v3$?2clgh1D>;a3X$_DO^i?&`+?-bGOdx+2ku_BW_z&*RDI_goRYI(gsSkhG+ zi%CAb!d}P>wpcU3NP79e*063}%(tq8)=H+KlKIlD?LgNIN!{P<-4Ffke5?LtRb?4m zO&cPIka!@D9z`E|TH-KK|yL`%KUa8wI3Brcvn+|ZQ>FGrGo>`lo zYGqki`Za7m-2f84@RT~nGb_jw2b=!AV7Wl2c5{ohr6A5mbDQcHj%ZGNIt_5Q<5c0! zJu6*gQFA}i8xirw=mGXUZ${&}6H%E?l9?C$pIduNK{Ae2FYk-Y`K;yzk`teL8py@J z6fw_GWsYJb^(pF1H@nhQ9>@SMIlpNIl(eO0AgH}cXlj;YU5`a*%r&%ZYK zaQJ5-EcF$p?ruBw8IqT2S&SDAIj4+rv5PEZGPy>jTvS_0(yPc`DRCZeUN)saz2sqT z)%}u-qrE9zrT7e|lg29!T~+Z#tNTr;d|55V?oH=;VPogxfQQQO9IfIgx%>kXCsNG) zPZcbt31nHtz}u-GB#sdjJ6&X5knUyDpAh|iKn&C28ixts#}Y*;tGG%3X54W&)fqbf zuE^8U$}ssx5KOeT3UjE?OFs`BfcW^%-QB9yXCNHs7p8G0=7|qp;QQZZ7)zxByy7G5 za>KN*KlGD!8?UrJ(s=Wfkg^&`WhsQZF>LA|B1qBh1P#^rH!*MBey7Tt%}GOj^gM9N zaM1sntl@*a{6j4EXxxo=c1#YWV_$|q;(h4ngFX>jwzoh4`x7N*d{bddWFb81YoG*t z{V=4ZQhQ!!zEC=$jcak)NK6PN95(l2q-8##&;*LFk@I+8ybTq?D&{E3@-=E(Wy<%I zOy1W~M`Z=5GoSel>_b{g|`-(Je9xHrM3I80CG65-L_)$SLP%+4GM#YLr4 zewGMFeD0)f<@12J;B%?Fl7-3;c1N8sIC6HhIOop7fbY4{?+Zu}rVspAluS2NA{%f$ zKGxp*^V<6=TakrMFC}u^o-~U`BKnPHZ_2+^grn`cOn>d&X=2esmw&*vM7wG8Vjln&kT8snfhmO zLpTTA1XXdp^Ny6enrwI4CsJlJyX|{ZvEM69zY%^$QrW8zj;C0K7S-ZsbRu#K?$~?= z8TmV)8px?0;aH+0^Dm4z**ciP3`;VN!R$oD68Ex_J)x=OpvcC=J$@+H%uOPYA!cG| z8pgeInnrw0orIC1s*DBeNP;*JCsk`ggipmH==X_cl&if8C4x!XBe;m_T&X-Nv1{~M za!5)0PkK}fTY;pqwjV11wJ{IyMZbKp1(a+f8OUn~ z8!-ZWIaCsdX2$8Dk9T~o4~{--M^1=>BVKC1j;=~R- z-&R%yJ^mmXd4q?%p~)=8+i1v90+QaT5(=+BHr6ML4>{2f{tDcF8u6yQRP9L)uOlg~ z#(6$Kd!WG;dEu-W$F+3e^43PU2hbzlIzUIuNYL(gruf4q6O6|D%TIb$Z&4baP5Us9 zpOVqq5`;=^Zp?M2oxHx-Yaue9>H@S{97&RZnO>kZvM4)P(?!vHD}>cE#VGoLZnE&0 zSKc3iqaK{G5&vKIHbZvduk00Hhd_gf7?txucs}I^D%VGz@d1MC@OD$6v)vpR!B6)a z7(``FXVZlkxy}eGr~Y0n5{sTa#SGz7%Sn11egJCVAFad+@5i%^CQ95IOp+IqI5y)X zBo$gwgJRaQcu6ciWFm(bL>~RZg!42yLP8R;)%!~{k@kNECv~sz6uqlDk0u?9^MTf3 zoplrS*C5qG(@PGzwxbhQBP&#w5_MAJeaOP-vo%2UQpvy$>5}X?TzxT;A!HUO1yV%D z!Jowa=Z;-}sdxK1G7FDl{1;QlG7?CiV zkDAk-M<=>(Y--McxoOh;`;Qq#%NL8!1tDx11GSF@uFSwNLQd0Lk4d@~J3-86u>IeU z;4r@~U*O<~uBcTkLbq}>UrJb~x|J=MyVurB`^C)Rrv?K*+r=zyrg6|G$k*W?k<$1K zKz=>Zy&kuPruxcKP5C9)oK4LD+I+wj|JAqBIvq~62yQQCuRpzhPSuX*kWQ@x`2cWq z2RXn{nlKXSwT|#LFfLHK`r3FWLY9(>BETptbY=D81VD;~0lW}J*ws?f8qfF%x09V~ zC@85D`YlC5Oz-a)lLFOE%M_IZL)kwpmfJy7Lqa{`M08!)O$I#1)pUwA+8#kiB}G0@ zhJt6Uo56wG(#9EP{e*aNfS(IiES^pqFC<62uP=Jtk=l0(KMptd=hLG)22D?qqJgUZ zHtrKOOF_A>z~M1$cpIKI$b$U2S2MMTxc3;P02vr>?{yPf1*lU=fB8+NMPtBEJ4Sh!pgo*4-vqaGFpR4BgDUO6bAf+Ymyg#jVrgw+L`HsC+%$## z;V(t5MrYl%u<4DtvBkJ17c5-(000936>tFhMl2vn-@Xr3$b`tYspEgz@cy}7awYwI zlRos(Z5fiUBe|lS@WNweFPL5qB{_uJA)+R7uW=?r0J+v!6)ny##`0Cnq8B-<cx;$NZ0rw3Hpk5b2rZQRy{A z96!hm7DqisNOsa_gB4n->TyND`iQ@sgi%?>&?igrmi~Px>+|ny4kUWbv0!_MRVn{r zZDe$==_o?CH8T|F_C#xvgFi6_yD2Fx{}#9$o`>hafhPcf7UmR{8bqzG26K=?SC+y2%3A;XlX@Ra>4o z2E(g=`#z+~s)QFTKiVM{NAt>xjHr$e5-<`4U?lu74JuttmhAwvj9}-S{kkL_eo_lL zyoW_9O1HKQ4)8)YYf&wC1!_n>mHkhHcYNwTr0g|ziZ1M+)-dssmXj-R)qTR)|mB~7fzgBr~CK?NrG zghwT3($H9j*`g(4doN*JlNjAhgeH*D)-uUP0+$g{hs%~nV3RD zc^J{vX4LJzM}*&M$R(fkND0@;&o#r})7Q8tZ9H629!wt?)qt4n*fzFWwsX^N$r=WA(NBfjWcHVfA zJGFHNKA~FE93fuwY4j%d=(RYDivuCN2@XkRLW{F7DF<7I>_Q;oK+d6M?jmHTLo~vw z%g{QxNW?V#8#+`jqN*6&o9#3Bq{ZM3IJr>ZDMvZq_u}Y-2`trt1%Lnm0{{R8-3i^z zK6su>Iv)eW#y99v|JNtPLhPU+tE5^$M zwdN>4SJH?eNZe7c4SGKgBKiH~?}#!S(H6CFY2ChyqIH~E0Tn47e)9WD$Uq5i(K8bm z>y{ntuF#jmOkoikOe6ywfL@@z0txapyf7{@(@HRy%C|Lj+|lu2akH|ui`;TE;pI?T zvL;F{H$qP46w(I&B*_^WmO@Y8l$n#qJMibwK5kLb7)mfxkKlu`H_FW_n=k#9eq7KL zvGR=CQ@WN$5g+jgDQ9Zq0!R_UVLLo@<%c02HH>ti5Ns5y&X9ML?lPI=Ee$|)OcxRYo~}gtX5k#`mjA8VXGs15 z%+X-HGT(p3YNe<~y4&aET%}7>5NTD3o!pn_a206ki=w<}*5j^l8^8?E?$WJSD|0Et zOm}7FB2gZtQ)||zT z^+N7mW-Z4F9%?VPTo(WyPThgb?nPR(x`(glgX=&_Omc@U!b6qhb`%&QB>kd=9bIG0 zFD-KO6l1Mefq1Rcuf?aFKc-!n$nc||IY&Fku`ogFgom3>-L5rC;(iH#Aubp?3LumZ z9BFXIlEauxAheShfwWhTALB{=IhGp%=jF1}wRxIScUuyBAvO!6dQiKa_QI4S0;%%A zRgXsQu+1a_-K5M2)_`*^)q%3b!n;&h3v8&dxu^i@s*RlCuG3np?s`6?1eO2YVCi05 z3Heq5BW1I;Tj#a6aff5_ug-7A(!T7?Y5Sa_p?pv)`ttIbIZ z^qlHS137@$CO9p;~vtnPE~a>&_1wKs^~L;o?w+>`9qnh&y~ia*KZ4D#JKfz zD*+wEZmCfGe&{vu7rbig_sr;0$k0`R2H37UpZ`Mrw$7X}xCt zA@bs8A*h}o)jWx>?Kc~@*x^!6vQliF;p&F{oZSovqI<@p>=0(QQGnx9-&LgKN?ViL2}4Mr{Xh@#Oc?O@p<7B$i;GRGs;*kYw2Um_^`aBmqOhLO(z=o|$SawpoN{Ia}bEe#VJ zb)ZDhOiAWRa7P1g`vZxQs2&{tR$16nX>Vj+OnS{Y?gM+%**STK$Z}>4DF{)n9)YEL zxUeq{|C;{0GOr`$y;J>R@#EwWj=@rkN;^RBlju~2gG9U&Isgd}%?<7Y-%ddqV zm?^iM2-~xApQ;2v7k$d75(~TcY9`|gsd*!D%<=w9TuTd|T;YxvL)WBIeChMLJ&Q;Q zD?RnwRBsxSXb(qBI!Nz}&$K5J`stlBO<2~u%nQPv_Nnf&hGL1QY-ra-S=^NH<2GGC-3e#sNQtlj&|SzKRc$*xL}6YPXUAnn{%3|Awb)fvcI z0)M}aqn_Q5L#034N7vmGdspE8#PT{gnxj*!BLDwjv3vB0*TMpNPIg)GN^4meyP~Zb zs&{^b55Bv;^I5)XfEEW0Q+Bjr>Hw1u)qgI&=BhdL?22}b#m9FYRM@%8s18tijR^Px zt4IwmtZyaNa}ECT1M)cE_^!O*0JVLVk#KU0G}R1?mJ---Wn7vbnXbOMIiPI}MfC!& zD=DyA1Y?9>m^_0VLP*m4nsU|unNgB?n{0G@Z@nGrQw>|;yxX;338OppuDzUJ+znVG zNfb}rjlu= z2Y1w;oJ0ZpuA%#L@P3VW)xSUl(g$DcFb{O((!pb(!CBaR5~eh%LCLQ~72I=-h;+Jt zxZjNwtcYL#+-G>Oy)+VM<}8ne;^&Q*V`^pmO#q)_XTm3Om+Z?V{#AhVYl=hJ)C%m~ zJ4F2B$Ue?LTa1*%>q5Pqt(Ogu@lHN2H;MdT*|&#(O$z9zCR( zgh;VEj{jSAux4$8to0%X8fwCsn-7`m$$AkAYTc6J??umC`ql%%^?ra>^!ZKX(I4QD zz+vcB{sOIBa2mVsW|7a&Xg1H+o);&LfGJ}m6hj3hiCg14`}ijg00em~UY^d6dW3?M z3Se}=->HjX>Y)Z}kKxrWG()E!hV^IOGsgbbU(B|6EvT9+9F8L7OMvh~XfVD8cVp2u z$T1yIyK_uc{(G6EpEb+NeMM-x81-q)fG#gpd(P-TpNX31T#7l$xqc` zar$Mc(KI6_i-3T$M1S-?LDac3(#3MUJ4hiJpZ!rd!~SRXQ5%Y(Q44wDwn>LY)_=PY zk&gQUcH@Lw^1aQO2f-gW%@=Wsfo(cn^{WE4R58qJs{T$Agb*Got^}LcBJ4LB1|Jv< zZ2<;oggmo80|a@$UTshBQ3gq03utAk36v;pM}ph$Ab-)u!h$@=1aBv|hBo?HV4(!l z<{{USl5zofh#f-Td`*-zJ&CbR+TxKU=<4hKa@yH{w>l`;7#I>L6iz|RZLQ-Xg z+&PoYyr~6g(rGy%|22qb{BP4-k8?2_lMy0&U~H)u3JKMNwcS?HtDg3TK5=o%4(piF z=fPzvxI`f~Gt*8Ny$9RO4WymdvNINnAxYxhqZVfMZ|8T3i?DpMvHYI#KX|_`X6ZYe zPxO{ybE$DO9;YfkQahF9%i>D|FernZu16gw_@J}s_g|xT3&2_IPmn0@`jZ(1#RYB4 zyJ-32ieIy(%dU1_rvTzb2CA(zt2s6smX{Jg`@r}N%e|KW2%*vv7p}w-J?Jw?K%wqX z1nwt_e|e1PXARGn7i-W+PrC@Vc&C`STg99Pws83rJd%x?y6n0hUeWJ2AHE*m`uHcVnTU`Z*-RFC+PM1GvKr6FOe*w$-Y?+~U@(0Vo8>yIo1p+#kX4UoNl z?@}m`0_mOxYSLLvTflYTb7pg_>U)ZXQIRkkKW}YfH_)Zbb9P5JO_zF)a>+X9g1=Tq zL69^nVY|#aD3}s2d9Q_f45|^c2?m^s=M##svY!={$$9y6lbA9#qeaER?k~inlYje; zc^-x`HW~qV>N*ogSLxtUPK#XNzLuv;dLsRb7?X9LscNV}D(XjTVu%FxuJjJZRG(`D zY&lQNjhm!zuh|2OK87=$Fet1Bo(c6Nd||0&Tl5)I$eMy>Q>CRz&jsL1F2ebkb`OtB zb4c;*23g(fnGcrqK_j~1G#9>pSRJ;EZOb+By3BTl#gY|fOCPa!Z-if`yutaDe?4L| z-+0?(aP@`2%`_lVNtZ07!VPLwk8e7(###D0QKt+uYxava&!!)9AKy}7CM~!S*p0=8Nw_2xSeZC#bIitW zC!J7iEicZvq7o8a^0pu@X&Zpg8@X;oJ25ElNCT@*!PEHzAYeR>=%;V%vmK$hdtNR^yEV*e54)XVsQHFhbi$t#VI0($;?j*2@scSd(ym+Q4yOA{Ze zB4Ql)yaFOM5^l=n_Ok_qGI79+5^<2K-$jDvrnWzkPWaW@+=H3P8dtDRA+v<>T`c0C zkY4X;1V1RQ`T6Vwo~?QjtpGFGYuO_~%|oYtX~fGR4jiZDT4$#0%4q1FPnF_-L&~h= z0>$$80^7a3>yrxf>T8YAG7&?BQkQ4RgibhI8_(O@52AGkUvQLo0uV)D+zvDZ!c^}; z)os#%17TK-mJ6U4` z>h$>P(Jj!RhhlD#@DO~wqN5C2LF1l5DZ8sED8qk?moy~$UVPZx0AYCtISQ9#Vz2bpzTDo#mQ4_r$2_YdV+wQuNv;u-*cwdr%hCWrPm9lzGX0 zBYVU-H^q9dwEf?nL>im7x=E(KK(l-0JW)}9)i=pe{9`MC>@} zl>=Yng+=-Ohsu-(bcYB-lK##EBY=>eLk0cFY4a zig9yhx2u|nw+!Kl&-BNn&eNZx!le}0WFZC|B3iXMJKKb>&xt+hQbubf;tyzFKQv9ZD#Nn z*rr`=Da}WW51mG1xu!S|PT1n1G!+P)hZg#lt0x-tPvhShV6|?|OdV_Yn4N*LTV?x6 z7$?Y3_D)ushuP4pH{Wa6p^LEIo=}`G2w|CRT!H-xq@#ILF+RN17no6B!4Eg&eQNVn zS`e9js-IlqiKGH#(FW9JGa$+Gt~3S_s(2cTUg3?4+A3?Qxj80=k#lZt)E0yi)x=^! zh<-Z1xkKi#yGspxfDsiztJGnc2~iH=Xs+8>qOD`%jM&^xFq~#59F9*M2UwG)qyK%S z^Pa%cN2SpTQk&=Zb*5nJu4(c7J8}1Bh;-8GC8&JG-*gb@ryn*D|Q{~SVl6OiE=vjvECE*o-^~xdOUV>d%lOdzE%Z~ zCgs}ye{8b`mLiD7mjw7bVm>hY5ZXS4(>yc^)#{j?yP)28K#OPNvP;_n0-VI-Z7HvU z_c?u}0jHVyr^2&V(eCh0P2yd2FA}qN$;T_YoB;zCGdd1#ZR1 z=oXUB3imC-5ZdwP1d>GVbQhmj+yz*`HI}O-pnKJ+i&T~?n6SV zNg(;W)9CHzl4S2VfyxyBjL(MHmXo(vU#k)S9%z=)BQ?Rr%Yx9d4LN-XRHc7K)m8sw zPUqd;-S7AsKPD}W*gDd>n7xyZ_pIy0=2=Q)TQ322ln2wkqA#Q2GDCZvD)SUAW)Y{y zXU9m~|JXKKDc{~ARSiLI1a{`?5-NFMIJ=qyyZk4GO!u%tqw81nU7$OKLq5NkDpZ zc4YtvEi~02N-^!5kK)@}>NSla#TKmeWItWzrh(N>UStxFfhd>^JP|3i{g1VQ#*qnxt5+$`@VKJK<~n!ZPcNpj7aiCm zTYM)iRa%@o@)8Bd!?#pB_vIMxh1&&bAVlg%Z->(=tm!6ahS_(`gFS%N8?PFH=u63W z0>#3ebqLb3OfaM%5-_zZNfB|M^`0oD))@bZg!^-nA}1dKJAVJn{alh=~}Q_ z_ha@nuSkxY$n)J4p)4y))67A?5A#ynkDo_JuS!f>j#%f*Qv+D+?WJy-!K&xy$cpPc zEPHTOjpL3k9z#2~so4|ni?szDXvthAc)vcFf@PRp3qFJTkKY2WxEUXsZ;AdnUGmxU zIXS~t)GF&zsN_t`U`5)*+KHRtM5$Tyc^tD<0smaX)s~J(3MWJE)MSSzRm5R^Nf%i! z@tvHt3d`08UP%7?f?WpdKw!U8^$SXztSmBN` zk#ldMJCH((4&Ja7MgV+Ii*EoKsSsZ=YEVzXFI0a7iR+wnKaaA?KiIy(mHz??^#K2< zgu@_=+`FzT6YiCZ{0GU@ZnNUQdP*cR(1kJ$PWd&!T&QHWS0hykpaH%bF7K1DxIX>K zNQoG{%Acju=YhY)@OP|rqcU_%F#UZ~-lXxX>Befph+dI3nhB!exHW}?Bns(xrjVuH z61t>!P5<_2iH?$le?IFnRD2`QlQ(0Rdp6rGC6HQ)Tc522zi`oZMFjq!L@)}hyAMu0 z5o9)IM+vhKhFDTJ!IoYbq3+7FtNg{Yw^Wy4(MkC(o`#Yg+5dtzD>;|HjOB*`xbZuJ zQ<;>mOR)s3LoCJ1u||Nn7Xp`C**2>rW%wu7qba&CuSWCrT@qCD06H+k0u(rT)56lL zFr;Zc$0pOG52U<}^Y)41k&{ACEEh#|AKLIRLMX<`xwx`U;j3zey;FdBe)xD4ujhha zzZyEpC>HJIB?oB^i&xat8Z;`aPUort^8p18O^G`^hBWhe=73G8{re=C2k#O9ay_hc zy560kfGg-}L8~1&=Hp$A{zcJdSB^4BCQD_iV&TVV5>za4f9rTI7e#htsmAGWb2kGY zsU}TBR9QCBQE>O!bB9&3zYsNE9w`)(P)`@=tkkpG=Q|=~85|K9*wTHnm1I%Tsy6lo*3M;TCRNutSBf>Sdqh;lQbcP-PE{60z`brJ#AWy^Arra zZE;XBrq$-i!WOlNBBmz+$6e-FZ+umc{HweprB<6w0Zp)>^P1eGoF4P+70xZ>jBYo^ zuXaYLagDq8C?)e?mvJEevXHq@z>B`#1z%2)u*?I0n}Ijqz`u*EE=iMt!- zC3%L|gpLe>SGiO)(!|ZKan&bmnasHt994QORP_BJe`|DqP=^K($hp#sJ}9?BCCyoy z|KZ;>&kpYXf3g>^C7A&cs}zRd+I^j{-%~)-9X5bC*v$h{_zb=^k{VuBXTv#84P)&6 zPc4y^#)ffr>SRZ(Bd!U=U_@@p=oq)0HCoSirrH}!A?dq1XcMzvn@UJ#NM z{FaPYNV$Jx=zQ!^>8pDqnlWG=6_j#i%m%Y2Y@SotXzQO^ZM`P1>FRo)IiS7J?N1i5 z_i;?i2W2yfBs9u#2;BJAo7DPs*6Pm%Cvh;DE z3&SILwu(S}akO9wh#bR(PJRBmUmj6`eKBrGO}FLtwW^neu5Rsh9MEQjtE4uNKf4 zoJn-cwA(yJ@zbq*bDCQKx)8k|U4q3)1^WUoP--o5&AZm3o0uh2-NfEn|M#^K;VF4R zN`wyL3h-p+TP4e!4-HVRw>T8ga@`nf4@C~_vXf-)B_EDaN2U#gFq~R1kpkZulc*1B z@5wU#H*nvotyC%)f%Aj;R+?}j} zWiW3nb7jV%ZSuHofS2{jS0!c#k$E&TX4+pnWIQVGKTeCfkeBkgfb#?**OoUDftdxQ zTkX)4TL?c!`OFEbKXxhVd#`;W<)AmpMj3D;jgz<29Z6p#rHyoH+&zVyqM|N*nH1QyKy<{r| zCrtI+bje}gh_g*(e>Y<*eB9+!&?8P`|F-11Hd8?>)n+PgWVvD%;;yK=lz@w=IcL+N zD+8nu{OS|!*kh?fmlmfP|@aj3ri&yHJ@b+0L zOt+7$)igvVWvQei%pr$BIaN)K!R)I8~luVh%wB*e1J6jCPCfC zUG1b~*U|gL5+Ib~j;j1%UD=jj$rX0jg%hV3U~-(MU>Pcn@C)SZbe+G)Dnum-v*x{3 zqk;-5vtH4MhzsJ84{#irStWQx5@4rP?BeNNJyJiME-;6};yq`9a96=(WKSP|Xn~T| z{uXs;F>K)mlo-3kG=Y09akaGIE?a){$Dup4;4WOE6e^0394{7O_JCV5_;ShBE^cw2 z@gtD_$`c!Qt{j6)%d`HRs|>U0;BGQ@}Bs@K(+y)3L$R%Hf;G$%8u=>*Jqg$r9}ufJ{a z{jc=e*TP=TGVCGb0TwkM?Z?@)R$kz8<Y%35aZ76QcJUNFPv{L@Biv8-bHbjZEL!GJ1~^W^xWFvA@Xsm)K(fgi47ktT zBlU6H&iTv#@&Q#q@M9)*>iSg%s1V%T1q1ExF8DUM=hLY^$VqPuttYC6!}9LvHZvoN zP=ro2QnjQOoK95`3lI18_xG*QaxxL`9UVZVD@dXC;@HN`+IJC*;|^-)4Pop5){nk$ z?n{#}msf=Dg?YA*;~nIvErs^4$d1kcLbGz<@8mtrlXR$IPx~H}bk^-YMgFm7J-OMn z6LeCGwZH%%U3-g?7*`m7+a-51VAVIL$*~8?2O&;E{ifwTb>71^5tuvedIT<76gLT^ zhX?NE7Q21eC`kq0K+{B`CQPP{%(W6Te*w%)$5EOt1Ol*nm17Q$@K)$YelBqKx?VRp zt9qM`InA%}yPfvfIJ~pXqH}Ak^Q#eB zhv#QfsW~=*a>K`M&`+Tobv0Gy;a9xKqYAjlci+KGxix>M;)G0qtJ4s}>=aSZFHnS> zuDG8(jx$swGz9aj&GdBp5v!m9?=NdO<_xkij6Od9mN6@`oB%F(JI2%+jc*; zTZuDWs@P99=+@1NdyVUS32p+1;mGKWbD)$j7HA5{6(SS>i7YpRR3Prj`lyvjGVge9 zy&9~QS?cCLEsBPQA(1taqH8TWhhfZtdW=>J!@w(o17Gv?s(q83)F?*{Svg!A^}$Ha zt8ANb56C@Y2uNq4^r;_{%4ZyllQ$Y7dht=Ge5&_svwvtLXd0{!cLbC^*+jsB7+ z?iAh_{c2n=;f#D)!PiTZ^4}hQM=l7Ihn`?M>C&KGey6&eUJiaXyitc1uEs3YyRID{ z^&YM+e>T=7Pc);An=&mxfKb8$f1Eje(L*{mDCsaoq1iovzaUpsK_L_=ZN>%Y+;Y(c zn+TyvUhCpQla$d}Mn90k3ri$&BT4QXyn+?AQN@8ec9f&H8FnUFdDgJv8gW4cbXeg| zZ?`_2h9I(j8&}R??&K)&1Hde=_*A|?U1pubgiy1+sD zHUzYMp*wArZj1gxmV=rk-XCG-O!u$aG1%Lp{z{p1_o$Fh&ON60iTrq?&Hs<17g+ZO zf-tmODj-|S^=3ACwx@ZQRYDKJnsM1GhyS5#r`r}ik7Z%BI_r8{5tB~%O+F0^JRePA zYFyW4sYKc^iB+c|iEE{AKlNk^C9ZTZjD3%U9I0M9Tnto6-Y7H1|3iZaECmyCHK6nH zW2BE_D-O1xyFHoKfnkpf(VVE*z>&w#d^*54C9U4yv2J~xh#P`;;0zdX7x%5yeO+yl zXK4@D3{YtU@3YGM#K=0T-m@j z1N*ViW2M)Z;i|At51(L=;G|`D69Q{j!>6(QkZy2mdA!{Y)=n7L{sRKWwD^FE zbHu|obsfiiJEjU8As?~;@`spE(5M1K0^}G}5tC3I!+y2etjo%ac`GB9u_a55hRyVw zbJkd)B)yDkTE1{8Y?l5nt3Lvpe@<Xn)iAVyH5$zwCBTMu zgkJ7jcsBXR*NC)Xca-f0fgZY_yYsGqkL!Uon_?bvULX37spHSEm})l4eO2P}B@mor z^Ke&K5RnEdG;ygd`-4OdTe6H!zwMR=kBLqPwY0SG7*=c@U=n0 z>J$@PMy*r;#d>_wF~u?ta5`M562^v|6q&aN1Bzuv`+F?(#`Q<%*y|*bYzerEhwfH% zypKEmEik{EC$FT)?A}?ioXyQ+r}p;dSf8x$oXnN89uB7p`|+KMprM)1*+*P(*(_^f zj4F-eW}jOQgvi3J379EETGKX^Us8WYpQpDNh31WgRwj_LY#YEgh`Cm=g$ z00Au}(`wcYJ)>p@4y2Id7kK`un^;lmg&z-#&EEE%)6t>&1@B*V-0Ug6)VZQ1RGOq|j(jN4guo(#-A@`0>ZX3euuH>$sw+Og6@$?UM*c z$4Li3$a8`j&U_VCVwb7B7u*yd3{{^yKa~okqMDX}KUVU1 zD!FTVt%|)srXK+s7|pRDyvqpuDs|7|Y&ej12Jr;SIL#;_m4^tI;PUzCjs~UeOEa@O z<&m0}i7Uffn>${NC=8?x=Wm^Fw)%RivWP6WovY(rquHWX<>|dH&eQ`9lLVfbcNlQf zNytRKRCEz#OO8JyA(4ksYe0ImDGKEcUn8c62NegnO_RgT1G~;S{n+F%#4gj0lao>M z*XaBAP)iXTNS|s`Zi5=+6^JMY*?_}G>C9DPqA+5ivN&MurQzqp74x_W3gh3VsDLz89#Ov_lQ~lvS!qm;_=yM_^tM;FQZ`E!a z1uv!Ih6S^bwahzQ&xN-6o$Lpo)x+9NHE0x;Zcs-nPA=8R9`iN~?~?WItgq9u)B{10 z)1lEJuwJ+z9_rp^b`oxEyFR9F-dZs)w>~FDE3lTr*k(v45LF-Tv0ZWW4#748j%>Pd zK+D4nP2(bHBwuUCPQEC0| z-55qzavHM0MghS<=Sytz{t>5fi(!+VItOJlgX2LGDuFqFCwSs}?bR}aEM&Wiw!EfT1WfxEg3#mta-Tq-V=#8_5* z{pPn}p&QhM)fF0(4XW={jFnlGR0+?0*4c;r^HTcS<@lfA@ZN!yXHa{Lq{d)M3{kESjA*HV_8kME)ybNd>E|qC)O*z?&AypgfvHw`QsDqZjlF^q@`Vf`2%o8U-GP!>UnLoNa=WDFj`N)+ zwEzs2SlDgg000htQ30g7opSTvb~h&^GZ|(kF+M{b8rF!_6lVNwJI=@601~Nm5}CE_ z)%Mu+aqypjV^bG^7t8Ma3zA@|z5B6Nh1PnKtL=O{+<}@=we9EzyY~g9ETip#pmwrd z=%<{k>lHxRhZ3cD-V8L0kseqXuQBus^Cb)4>snt^w{^ZxGA$*7K&TL*utK?bx179@ z!Gcgf0Mr0QxDVlUP0NJhI$MN%SsYhpHOMyH!62PS;D*DC-o1QZV@gM~?Sg(9qr<}e zgq0J++k`Bs`oT3ff2LTyp#FBy~epR@X*3rcRUc znfY<^(y54!-;cTkrAHR4@+%DeezH&TdvT8xFsXlz<0Fixdz2JluNRD!uIN8@hlGf@ zg*27>ON5FB#oX`{_jktCFhjP-%5vCuO#IYLLYq5N6!iB79E2e<%k2ly%YzGHQ`eS4 z62$+vikHdLRHAk+`iFNdb{HKL;-n#QsR~OzSaBtTn zLW_=cyt`8k2;xFTT`h!rH_)_8ew?!+^RuC?MQ@PpjQ);)Rup7*1O-=Clcxhu!b>*_?M=5QGA3hSA+ z)1X^*GX_Pi0Y{_az=6~#^a(ba&Y51*fUTRj{olo{uj`<#NYcbFAChay=uxq!rmMYFMh;J9BA~98x43l(S(>Zu7e|N5f+82fLezs46^Ua!_YsxozQ*$X-+r{k=PhU2 z$bg0~bm!75+`OrYXP+w`kLS#xTNj>DuZuiavaW>*L|4mO#j+G!=z>S=RXikm%{{TH zYvLd?QUNvnS7HipbjWv;B628YY#cg$hMTMh*Iz0EuH5I)z~rS(cIac01u*eV{_z{4{(!`sYhm9Op3lsUj)~@;Pz=-sY(|#pOP#~5)$Tl5=1J~U1 zWNwKa4t1_S6K#;yhsfFhML@d0A7FCd_xqjelLGs_*byQSx;3**fy=Xj4&dOpmOj;V zMM8YDV9G2zq=SQ3x~{za`sO0aG@^q#nJZQBGqUsPomO5-i1%Dp79Bg7Z3iPcNl(oIDj&q}S^oLB_oM2U8Fl@P}RK9MyVk`A7xBvhf$`TjT(4MfL^+mo_vkQ_x zE)=CKr&2x)C#0!wi_)eLZHkshEIPLZlXVLKw^23pxb9B389HNtg3~loW9vC`p8*<$ zVf@z39hT8K*C+FDu)IM7bAb@x<9ae&Kj+$=LTZ@iT0##qAxm3k?xH*sZvm#RH)CeI zaacl_JoMD5KMwc{gtX_q7A4`KYrDze_JsX1A%TG;EgY0tV2bvbWMNjAWPH6C*B!$v9b+v_RJ zW=Jdc-6FcTnQd=u{LR2yk@Tl?3eiS#idm(nf$z!?59ws;gUzjgh0tXvv1$ub?e@3P zPv-t_-;|e>g#dE~HN*p`8k@jh-o3eXPr#Nj%L*7q7j-F3(8av2V#cHBrb03@?`KB} zTGD&{4IRfZuL?5J2ioO0Yxd#0z`Ii>c58V%kzx4!H zvjLiNHO=ou%O(O27p8*2lej+80wy{!)?2( z5%BF%#0Brz^!!!?M$yo9-7K6nu!*1Gx2NlsX%Z`bZb(4Z8a$|Txyr62xS zhz?Cx1GdMLO!bSw_Ju(m@VS=R--}=)f2mrFyc0w9o8qh7kXI?~xH(CG?WrAwWlx`x zgT!2P<>rU+)iU~EunQA>yOFPK$b~6^F@=2McfDq%}c5Ncufna zW%M2-cBY39<9#qT&zC7&ud-!p7z0UMK*zhnc$l1C7<|Il;%X+|4-C9X# z`i@o;X+OsAd{V8j?=ddMUi)b8iWU*>#Yc^cdE{xLDPy6mNC^5~n!&TEKK@e`56kdW z?UB|Yp`Y5Gg337h80&E`skjpLQWW~9DH*$ek$Q*KLyIC#anjuDm(si;>5Hd(A~5$T zaughyb`R6Sj-gcsXuNzwCh{f?lT-OB%3!Xf$aP|R7{Kzpegtk5qEO@@7DJPQfN;IA z1hz&kdNSX-4LAZd;|McDi!VS)uu#n{ck(zAJTx;x<$y* z4>U8U`!g1p_%x&OaoqL?2Sba)F;OreLwnBF&{`ip9@H1Ize7 zEd+@hpm`A_MoxX2#aF3|psa>MhxcM01_Ae*>;LVLPZ3-G|BABi-)3B&ELxiH|FfKI z;eh=y%QqyB_Eglfy1|l36&8W|3wcdw>f?`AY*f&zLu%aMdYm0XbIMZTF-1tk;%Y;6 zQXlY7CS1>mD2q-Yvsp&yPiHONY&zrLHLh_ut{8X6=cq&{NmQrYwPl}d@Ymj5$A7%i zzxj!L>FR7=%&Fw4OSAU7$rF%&;S1Dm}Ez1OVT5x;&Vb*pvI7I6EW;3RCvJ_~Q`+ z&mOX@G^EVGx=fFSF`eQ|B=q40uF8{VlrKa^osk#+T=&>Ijj*AVE8F<5UJu0%O}I3! z=I9X?A8GMtaZF9ZyBXqPOqjC|g9aU5fh-eW7YTnuyf;0HA)k@_#ye&*;(}w=5DzYN0W~Xk;3VF%TR7HbreG*c*uk=|&TLhh~e` zu&wjI#@Ytv4P=0}T&3gLmiMXdrD`l?fDWaI33i-dN40xhkRf=X@xo}0Z?$<+1PRm%`wm%4x| zsA6 ztMBSYx)N)Fm6ni3P zAJ&BzlJE^oJmP0+h|xr5ZK^>eSMeC_%+%f+{}7+Ahulxp*xQQ2@~*1J0;{GHq9`>x zL4KVZ^dDk!rq1Clp*Zbx%(uW}n1$R;wUETRSmiwzlhwdMHXWkgpl{D`3)w@F79z=Y zWlfoKWdc#)V@Xdfxd@#>E&9wB27^%jND>1>8XK-<2^BEks0Yt0hA}eX;WMVHBwm70 z;0thHT^ku+T3~~;bV6IHYQeHSER!)nLP`7g-D>{~@Bk4tdiCK!Y#mBVHmj|J6lxwG zK&Y#BkT7+c1km`iL0#%yOx~Wz!GbW6uOstSld~Fb1?V;hv%mU0zOM3n<8i)cg}@tXe$oiitNJR-Cs626bhnz)N^1Vq zS4`|QjNFpQL+O0ehN_}_SLd`Ap!AF@rl&;{MCmkG-_#pF@EqT9$mnKAe^I9&)tHD= zx%i`UWRA`hlL^c7{}0}OU!o!dE0a5?I7VI7n!(1kS%|ZzBoNjbFrCx-uN}CfyR|Y- z_BOerw;KU@P=0Eqga$}fZ7NEcU%dtD4b7ZNEg0`KOSn}N5_A_$wfZtE6^t1zQ7ySi zQk5ZKd_jM-i>xi`_;h&%H#1vZ1AiI@ml`3n*XCKWGw`eYn8LXzFf|nZYDlTnlWa^vc6jw*Hacb#dx_$0t&; zXik0nh_w|11rrrJ&Wc;Kwz=iS<$Of9R#Lz(wW2|N{cta4(bJ+>AQToV(9roKn=+qi$}6#+7Eqn%UCC7-iU z95B^lUFvmYB0nSvf2mm6QjXS|7tOT`->iCE7^MKF<%J@ieXgbk#x@j;Sdczh7I;<{ zs33{Z`SO$AuPp)`PuMBTupCyY{w9l7fq^KVZ4=l|KcXp(J%37(kL=r|?4lxgu7!X* zIzL0$L>1TsMtI||u(ok)r)h;KVpe~tWeg=D@O>K{$3OwYlfEaYYW|rIK-$tqPu__~ z0nHvL=0xVN2Bbo;gfL?0mdm>)l=-R9$*urJX%&3;J{qTJqQvR@ z^TSjex!~%hF@LebV7%Vwxr*aK-6e7=zY(2*=w!+so$1@j6+g;XXr(C zY2nLDS1#cc;eFibF&P^vbY#0rGTJ>xAq#J*Yiw@*xRPN*O~N=jFe;N3(O6HE z@B)~nC>?W)iLQ-tJvQK6fu>ZFsIyUBfmeG(!bOMZ?J)&vm|MhS%bw?4)`ONFe+-Fz z+SV`tcQJoN98Ddh;phQT+Y6wC5{gD$Ycj3$Lo_*&isSLY@MOyOihq^a0^Ixj#T@!d z!)j!QIAo$PD-0S(#&dc+r2f5z!dGOwv_d7%JCvW;z+S@(o@e5Z3tOtJR#C1aXZmrv z!zB+((Y7+q+F5ad+{i2d!3|fKd2N28$f5obTDoYFhVuU9MsDGlI5x$@Sz60p!ZXk7 z;AmjuAuDc2@?y*L?P_j~_6a>F*-J-JZmu5XD2StNs6M4|%6ZR7y{yLXt4GLC0-$nm z36{@M{Z7Vc0ecF-ulv5c^M^k+*LK+wTie)UjrbWH^O%)La3B_l31)8BT|&Nf5W2$+ z($db4TEA6SId+=W9tS6REIrHvwYQNpjKo^3UcNmbuXV|+dXp&g76l1B?mGf9tlm$!vUJ9-r@us$*u9 zL6D1P+!ME)E5DQ>5AMMmy5X@&Q{~G-hcUx`iCjLENqoK#H^7noPXMk481DECZF3kYP5k?N z^N2U2ch$k$f$R9g&0^gG<%4h3B38C-6TG)eCKVtVFwphGXK?HTk|lpJYSDII!ET`t zg`Yld2mQW~^L%2EHmHF*rP*b9#Xk}H;_>gCtjNgA|-f8 zt?GhqBOmVblVv`~rk?o3cp+!xuk?OL4Fk!LHrer?r2qVeb{)8Hq%{4SN(!3I$i-kn zeLn|K`!eRh06}H3JU4UQ7zeg}E-;qWTe8UiC?{OTL~R5`)_|dta9N#?RA`l94 z4JALrmBg3IXKbAZYp}H#rDYA4sqzIo?_NhG6NL@(g-SLOUb!?Ftirw(-aTDC7SMAJ zrh%No6NmO*GzbrH4zg7Y+$WN|>AqhKLscj7%~Iw};&HD|-dK}OtO{b`bleco^?iQ> z(0_H26p*7`p*ba^#6FAIO99H`fwHTEPML7Q<#tB^{Pb zwZSKyGd-D;2Adm$Zw2Q2xcQbpp>zcK6&L6!RQ?y>fGX!3jwb!vZ^cwN!&W-4X`XWJ z?9|aDT%+#Rj*6jaH<2UoP4S6860rk&?Di{&s02vMF zi@su1@$ab;tO^^;iVs*WfjNQ`U1WdLeWn!RCDwy2JPEhXFWdijmyb6%x7}TjVfym= zN9nqQdog??lddaG@1$UEwXO=#KGH&=wt;*rivHbaQr8_RU3ini7#!U{^bc~1ReAh#*kv*s;9F_1tk zt^F-qGgBpPuYOj0r-|Bs5Pw7`QLtf(dOyh??l?wSm$Z>(#lqs7s=UOZ6D)eM0<{|4$ifMKoa>*CcE zW+P1WRxYxt5!?|QzEWopRAcoIg1Q&;igawV6iT=v2WlSzLV@wuG!1T&`>Paxvm|GQ zCGpXCS3`ge9-2AJ09yE}ytwPgb0?q#q8nV3S=g-}PHbv@))(r~Sd|X1GP5VE(6kN?%l=xxuTxK9h?$0W z>NuSUw4WMs#y3qC0?r}ygNq`L$tOS?nrf3kG3;B{m#Uv%d5A})iTgoqD8okJ5^4Z> zqHrs+(@O@kbU|=n5ABIo5G04|#`2e$F==w7524aidf{v+j)`w$ES9jB$o*0TzcOm7-_k!x zyvQ~(9J=$ka4FjDj9HS+ukS-LC`Mla?(eg~{QC$!dqoHo*=7fH-(|fGt$93Rp zxf;3?&QG^{n*QR>N7f}MI@V|YL_Pw(H*slj)2~HflmRY{)wiYptF~=Bq8`Z-s9or_ z(H6RCZ1Z)GQI#+(6re3y4#k!_@5)YD=r0M|dr~0>?uwCVVA5o<=4vBos5d95LM78# zfqpJBwKOcO=Hn%0b^ElJ2=BT(Y@Px;O~(u>7lOl`sY~GQH;-AASmqTnLStJ_wIVM)4TWK^T6)#}lr4(Uka` zV-=$d0KGC4-m52m)oBn#kD%V%_j4r!zMGPYh8)?WL8x8liZMHmI1ckpe0%8O2Khk1 z_pdMMQDx1v!P0m<JEH+73mOcp+M&Fc7ZN6z8Knce?hk%-tQF?Ov zNkB`^$?eg&0H^6^FLNmD=4m}WztQ~7^G54ogc9Z&@H^a7Fa8=-+HvCB{JvcE?$TC- zH=`iU$rtOjPAuFAmuN(VKWGA%tM$i#3Y-U5ZwL3B6fx#v7LUHxzE1sbOt8JrYa86| z1?kyt^nZ@(?!GLvm$w1VoVJ>ER&Fv4w3}8ue#>29y1&XkBZe{NEk$hD6vYX$Kwj!f zM^aj#c1YKS_pbpan&m-T3#)j-X2X+*(zAobppq*%)JFQU@rL$VkD8Ckpstt6HLIjQ zZXP>_u1^J8s`hGj0tRiK{NCo7K)OxCO`J1%@W)AbsUhDwPZY$-d6N9#sZzF9`~3^C zwf)xFA;g;cT-8hJ^Laa#w0--%T!caS5bXQhL(c?mpTJ(M1F>+WY-AgL(M1Ko+=AAQ z?UKO*`JS^4YETkNUwoVELdygK=3|=S+1ap{M0YsYr^b^TMw<1pII*%sn%as5hFuWcHB6=B2A}r?3hZuV9 z_iDKqhv+Ud52byy04kSp%h8(A3iX*5I_A5Ytfljn6W@;Vlv2 z`wv>U8XO{~WQ%>(J+7LyF3!G@4?=~B=$2`lok$Ot#(dz2VawxC{aRmhE}?@xuLnNj zhCKdcD6QyyxAh+`M3+taknc2_X0i631%pq&($XTACWIU+x#}>wl?vZ{B?cJllx^|; z-?;;K%<|Gdb_5l-GhT(~BF3rErGhOoL}!BFqb{@^^eS>B*=)1#>$Jv_Ds?>$u>2e4z}jt40Qat zC_>zSK6OmbMw?NldVt|;=RLn4(lO-oMev@m&Lvfwe_ys&KAp2K$}s~QZv=^Qj^O-p^VUe1=H?Isl~2_zEz>^%=rN{3I~OJuqcHF7a=A8mLwo) z{UOVzFHiu@B_J>G|^awsE)l;ocG%@!=LsV-`G4mi= z-Z@3ny_cJKytL*B@<(@D!s6);VL5fbiT{)kvIUQDjV*@m{}j}NU^`9$mFkqkH2Cu zk`p#uCVs$!=MK_GQtYW=Ryk~?8Hqm$h5xsk7zg{KjP4~*O=palDojKc7&Vy zZ&_G21?klP74M93ga0S8;*|kjToR|4sd{Fb4ZIN~D%?V1Z^U->Sylv6Q+A|zE(`y` zQqHSh zrN((1&g#!|QU8fWQU}?f@VqBmS>$^q!E1L=%e3rtEn>bfXaAAU*SAND{~SbhOsbt0 z2-sIIY(8&h=ry3T0E<>dMGbNRlEA13XPv3es?FXqTQPKFL+HDvC^A?i-}Er8-O5z@ zRRdm;qIV$o3>~&i$~~yk|71oztbP}qQyp&@tNZ|sVlxaJZRSL_o{qO?Xx~4>IM>=Z z(kH5^mR_bPg(Ey?B8n3Gi_i8pnIRB1b$a<>i0I0E5|9u*(C*w6*LGxs1Qt(_0Z`ck zYzH;>RJW>DB?jun_xMg}QPS78vJL8KOw>h9WsWc%OM;;mV2~W0L2LOA&|7qKj3+mp z%G~Km_D4&*a(&WvL}e~QVOyoHY-qAldq-di)}cF@0WSKN7# z8#>)q$$T$8{WR=bl-w7cxQYAu

    (LnMp?48u?sU;d#Z@Vp+eyVC-6LM-b+xEHw4 z0omYNIVn-c$u_a{kAEddcgJ_xR4F&-Kl0kw+ZV@DYCCnb8_p5|INJ6mPQZR;LoGK^iGqGnR`KO6y$aVOw_u+LIZ#drVw&-x9K` zpbC|-L0+K-PN@JP-T{D_EqV9?U%b34ldA`*(qCpbUbk8};n-kDDsgF09 zqC&D{fCE9XbJTG3S*`m6%B52_g&ZjS_*d?fGe12#H%PVM4t;nITQBJ)L88$_%xswG z-(b#J!*r5H@hs&mQF;i`sXrOLImh5@cM?^Ua|nd-yNr-;K&;D}KuqZXO!pQMXEwa` ztRD%JQ+$hsQm-qt)_7E%?||T{yrQyz{h0Qmli9Jy`r|{U?Gtm747zj8$l_f%5CfU= zYZoYhhsLyAJ2{wZh-==-wsLSRHqweS=U&@Sh!X+%wa+NbVmc`3hVjoI_>D5sdokP7 zi~JH;J@*$!Gl46ez2Oi*d4`lr41g6@z4yfKMa!6mwhLwsG&YZ&%;?7XKE*m;4y;c`(8 z6sbF(BHBxkHYebLpu%ufEvD~HmE)-KWZTb!gGsAz}4v>$DC6P zX5PtpTHq*#DsvKk8R_Kt{6Xf$TnGzIIrHxXy+I@qEpA_T9{rb)yK|SF)WG^89*S6H zX}*&LGBvCrQYMMr>8BS0TyhKFvSBq2-T$Sn*boQsU|)xbdTt!5z}!*A`MhuJqJi~% zhD(_7Uwl%27*pwyJIutgfG+uY2%Dh@53Yt)3(q%le0h@|-ww|gQhw4V5*IIMC`ERQ zf8@rd6c#gyNWJ(|$H#CkDuZMoM^SCHhwOrE(0P8xa&;ZHNEQe)MJPW>RI zQRml}Ffyp@@G$gppY;L*!X;AiC{d6{is2C<>K9%KlM{ToK&Sb&0U`rhoDyvv*KXXC+t{L|HZacHSOgE*v`^iAs_w(YvtIbOym zp4Bm_Gu)H+1dh;i>5y2>cCs?NVWWgYUUr=+r>lF2%tzzDv8AeGJ|PH9?Q$t;2x2Kb zC&5BYbj#qmg(g@XJ3zSeWcW;xL?|p&6W|Kbb?0$?5Vs|Vc z;LHGXXWFlhfXgdWqR27VivODl_S1M8xT({0pOkwT;t=fG476zqarGWhcHs>5vs~-O zsZG=2JAp~#{ai=Gk|z%5^D}#ykuLafQatzx((j%(VLYWl;~?&{ zbrgT67YfbJQ1+iz+XW2Pbo^WILM46C^L3-?V8(6eZuTAUE?Z`CYQ;&k&ksxm@2iZu z#7CpT3g_1RvPdyF$x3skJ(%P-oV2TloX^jToRGZpB~n+3jbpZyaxR%JFo*sG_k&~U znf%bZcZ|H6?8O0>gEIqxd#sC8?&yZ8xrUgYSEtfCK}&?)@%P~-FFH`Oc{>&TBT=o2 zzP=V$V8D?ftqfO~R(getTQILHg-)0Cf0S*w1eADM5(UqfzG6yeC^6)c3~a$jdAM8W z2NI$fFmUBH&=||Ii)xg~4L)-2nuZ6NjMZhQRK^wrzLKNL zNi4El!m}Xv!|RWXZZnUp&*a@89!Z*>AN^ z*?yBjY{OQy!_W7iLL-}Pf)IlEq$5?Z8|-CH9xe6bO!H8cgELC`$Dp1E5-N?dwq<4n zwaLE-iaM661zV00uHW@?d%`DVz=$)d0H=A1VtF`R*`R_D3!|Nr0*pDtKoC&JRA4ML zk3b?F7%vN^WwD9(Hr` zMhxGlb=7-zjv;+Qm z`L|N+-GUlg%18o-K9jC-C;-%uGIp6(ZR9n7i*_Y5O8;xxDr6|KzaaC?n{3$88u`&T zbZ&3fh*%@HiK~!vfE2wDybrQL{x~g#wM=cpfBGEBgv!38Iuy8DyNU(7c@!P*JUs&! zsTB{V0EZY7bZ+!Nw>&5KhC5?p1w#ZBOt%5|tG&O_!ev=dZBA^MyxAo_`)3z}Tc|F5 zu_))T`GUf!XqtjyMu%!XVmS`gy&Yg*7xn;)h-}ShxrxNl1Ms_|i}w4gg1pxo9O&Ne`M^s42j{zspgDv}0pQIrpkD{6RgySYfKb?fssBJfyNfl(NVDn& z(mlb3hslo|t8{lckqV9eMd0X({2-d}gN&oDEU0ZgM~T)+&fACaFvz!(Va7xusuOlUY-lPN`yA_PI<07ZG(7wot))0`M?@D;9{pm?#CbsIXKq zF4lDA)ubwyHvYa2r#$3$PSzmXw9|Er;!fjx@dO$>g6c^^HYK<84Y-u&?D*B1C_*zz z|JvOEiFnu=`?MD-!oK~afED~Cy$DgZjcWpqEQ%3tk8K_=uigxaxk96V8F>@v;e9!+ z1NjQ!$gt&PgdS;?sy@%G9;3+d!Bv5QF$nFcBTJ%H&r`#XwWN=kZt8Sa+(+qT$9`wg zp-2}>dOiv;5;Gpx=!3;I(%~qajKMWXKuW^6W2bd!?tbRm@l7hD69N6N?OG8P8)1KFTGMf(EXQu&J^jG*xUtDO<{$YHoj8P z3Gzdi6CmVT?%7Ko9K^8m$sY(h{ZjHa!i=+gF(LBI-XYwp9!4NNjSfNCo|$`lA14## zqeP(`@>|ttH-sM>fE#0m1Gh@ zO5dum#yfaMi`zvqCuF3PKAtRd`-E9r^NiHdvQ9iNI|o z_LZGXW0~hfhf}p@zwY|M;R@xPfLm)J%q9L-z$XP260@L%qgj6(|8T~tfAlT)Ttt$llrbf=ZnA zT*$ux-{dc091kUVGd%8Sc`zpHtJ#77A}vHV0R-ATO=s#{_~e|~_#G{?XOf-HHojh9 z5$^j-bF*^0C@rDPxi{gZa(^h)*8SgaiJ0$fVSZ=UFhil65e2>dXL{GQN!*<1FBbeC z(uc=k#K6=R)@Ld}?o;xt`yGNTp8DmyXFw?6{=pl;XNSwiu9n%hju=Ik2RtgsN~Chl z2FEtSfX}~U7N_(;m+?QK1`LIux8^6`iN6#`R55C9(PEaR-&a;M6<%1MOx2 zR0zn+5np5v7U!;$}}F!gWW-3*%c2GN8~^k1kYs&#IZ11T>^R%JJ=r_! zLs9RZ@Zny1qZFz98(QlM5C*KipWNP7pqP22(|fX86Cvd=s*)lPmW{h48g1x8t}4*I z2yhNyG<9wwyxBNetVIDj>loe8J9hm0-=HA|wyk4<<`iisP8^NEr)c7&8yEl=>|pEL z`$L%PT=#SypMcHyn=o4-1(Wa3)U#wN6hMO4Ka5r8qv;spLmL-O)|&i?uRrNdn70Pb zPw7SE>SV*#f7!9MQYN+i4Ju8d0Mr<}++-mIyfHp4Vby|J@ML9DWkumW)E2LipKk@gi9|edrLKWUJBDZA~4T)UH<>l4g zOz5~615P#6gs`fK+UxVRAA~RpSEsgwSINgc6!LF^2lY2q@ArQus(PyihEP0!8mey&=HdCTIHy{S~MQjt<-4R1ODb>@YNIbcp z(iU7?6>DBm0bLw5l?N%{Wrf%KH@BvU_^{t04B)y{ZGG)sS;U(CqjT8JD&^Yq-__A3 zm-j=;nBAFEqR}y}fB*C9c%*=r?oCIFuH#|H_lQOsgPsUI{qBoGrQW2J%&Ker@N40@ zoPh-59Kp*utN*rbr?R3N6N>$!@nFgC?ZFc}MyZMmOV$ywhaV?0?+5LlKn|WVJQpd5 zq~Q{iE1Aj?@mL5nS}!@yo2y50pv+``F#6Jj9+m$YT{RAOSXCCu3&j(>3&wLo%7lDr zj3mir==t6-pMe#jbiPDiv$Rs7#c3tU)^vP5kpE8H8My{ zqo+LdrN#s@bDAoq`qc2+3TC9=zk|^lc((|?C5Md5SWf?6(tSXq({xRoAB?LpBO_d) z4V8t02E#5oB3lDxyPtxTUv5Sw-j4b+(1}yt~10bLJd>@K81v#ppEjJy+>*F>qy5s}1v%(ksN^_(fDiB08O%5K5yB zhfSNuDU^;!a;FFodU0O7Omp5UhM|xjzOEWa&#>{w<#)BQN8cG@hu~@Sv0;TlE4Lb>u8wMNr)Zd=rS9*H$PKElB- zHoB!1UK|M|YAvzr0qI(15mj<+4?+~DIsA6v<;tR-4s|A_&rlXfS+v+Y_U?h)xQ%j7 zHvJkxYbSHhHOF``Ia+BBpxG~pQK{9ej*c9(MI3!)|0fbrvsZipbuNJ06i_YGpjWmd zcbQGmx~Zd4%D_p~cS_w#E!^CoQgQ=7y#X+XZtNIoa&D6mOHcDLXwNVVFdM0HcttTS z4`|Qebf-db(Ok5mgZ1-en`|yC4XIv^rr)f9;`XE_1#u?-?%Ph^eFUv90*w2(#51#m zI8>|XmihW6wH%JF=8j>@yVo_Eij!Pf@6OZkUzU%$wfDmnpDRIHtGX>TOJIWG|DsoR z#i;W!3P7SguA*H#d0LtnkwV*6e4R!jRP?Thm_wPoF82GIE9j6B43nXm9}W&Ihku*A z0w7^|3yj#4ZjZG|{~bTPTN-w;^Hs-3R)~dkmWQpdioG-~T;oGCt4GUr zIc*w@XS&Ifvbm`EIcyPZY?U$1>Yw_Sukp_*9V(g|*h3DEixsDE%+i_7% zrR={^WzN+u7~JwnZAFP!m7DKv2`3i*Wk}zWmbQNJW;5>bO=N}C1kA6Cp#~iHX6WU? zKi#z0_s(%wi<(RD$}ylJtT7HI^hLgDQjde;NnkLyf6#Rdw=pcb4WZ`&#NR>I@0t+lVxbqQ z!j4=4<=;MfDI#e*U2H9Za+zj6HsBLT`1ujWIzRs^;CSwBYeOcj#sYoif4K|3%$8Yj zz$+Vb()%XhN<2Whqt#AQVe?I%ikpde~G?tGb< zPAKO->em1Gqn`W3N*$DHOK)>#|8WGI9eyZlhBIVCEqG&52-i;eJmKZCZ#xbT?O08B zQGUJQ-9)b~m;XPOzK1swr{>b*=~(t3!g{`1;9?Y~-D85uOA{-;0s~1lY4hyL2qwfk*3I<14zuf- zINV1?7p#&JX(L=0J7CO|&G?0x=i8c;(IEt3wi&g~3PT0K*dJE^^TiM@)JPLRQ;yY= z|C`m3Lz;%bm|`ayd@raS7?d_$SQn&-cXTtOuZ_94Rs)1l45`}h=%RI|Nm^JyYT-3T z$-MFWd=438)`8+aJKfxZOcyHYDTUlo2 z?C+PM;B6{={WJ1c$=IbqL>za@m>^YNY1c8#dE1SfHh+1w@wBG+?O4{1FnBrQ3DIUy z_}BhSGvflFg$R=4;2UATuJ{CR+m2IbD?qg2c3{we*u9h3h!c4J70o2V)7RoTtcBgK zFnF1kmWGHpEYq!8L(q{;Zson7aM-rRL$}?AUgR1;OS-1%0ukR zuG?4s-wltuDza!-B|b?<{zx5_BNpN|7?sOR!HwSW{O4t&zL5x3j?tp@n{XiUbe6)3=UY9X`UZRj zfK_l4bwUqntk^=(yELE@D0REZY+Y+7 zH{v10bT%t6Y+-y9cb?@zOw+yF>d{?%Gn8uKdOkz%nz{?a2WkbIZU8($!@r+NVLK;S zF9#JNz)wjISw7s6#3XHS*FS0m@m1KPMST1FdM`fDE;LQ|e#VOgyx-c4H1ylENByxg zH8zvAa3`ng#<|w2<_19nchF45-JunG9(_CRNgX6@pZ^}T_vQSyxUmb?^*qB+ggXwk$sSId)hnr6gI;_1Xa!va1#P;Op6SvJH(LUzJ2lLfP)H!TJrs-d^b-wrdll%CvYi)D3 z#S?|W^=U-GE>R?w97+Hse^c6Or$zx7+vzW&12#&g#;gUi?c!`a5saS=f}LB^xXA(Bl6dR_-XLZ0iMM`!GBKC5+K06&t*S$utYQ zKNmXc()I<*t~OM(#g-ur209z<$B$;?8NV=Qm+`mSCj(B&lL-<|zxhu_G3RYvkK=cm zgkUhQ<7}T_)lVr@s_XI&8rsO^Y0z!$Ct zK$l=4kQ2!Zw2k+?Lzr>U_b5E_{k;o5M+T&2war}@VE=yn*zs6_LX6?97S8S2TKDC;fWrSLe$3N&)zt)4 zJ__K1M`XpHson?@Vq8+Gr3y&ZwPTgc97W_mjDmS{G2K!^(Etnan>IT%O6-`GHRMrc zRt3C-L|<3iabXP>5Ez1y*Z9@>lc>@Ll12T!nJuxRy3}ZWG#})l5~$knHe(Ze-rPq{X$R@q8UeQwvmH}`lzT{S3O5FF#mh!|bK8m2w^@`CU&y()Ihd*rD!l=68d_@At(;e)EYnjgnG%QhduKxdpdRxK;&VkF<*%#wOF_$&cB$O zc7U3P_&|!9VEC$6KOyPJh_Aub)L8@hKiV2?1wUND`;Ydb^-k5zRvaI%+c&^<3A?vJ zszQhI%_~;#+N*zecv2gD-I*t`{c_!rZxwRMb>TK}A4&3$QA&e8qvB=t+N9{o{Y_(* zu>Ws1KXx%UHb`9=S1}kN3po4t`Bfu}QI1Yt#rtVQeJL9)9 zqTZYUDcWR-WjL6;%w06(%1?0)Undsw7ie*@u;u~p__(lqKFCw|nQ$a`Hb=s|6>kU= zh}NnAMCAF#!}LqGGIga+-ZiEyU=8`W#Vv6B8cWctZoF=5P*f?}Q@Q&#O9iEC%vu&8M{ty^yhYy}$@O!)8Bs9a)=3$K(G!Hw4TP{bNBr4C0r^RzOLs*OdC7QumYBeJk3pNGY+}w(o;Z(qQN2d;0iZNK z7!ZY|PSH{3Wb%vbftplS2ud`254~o4f@D3kI2+}D&=ecXz}=6$o6=8|){G8M;%dC4 zFNJc}pCBKRM<<@$c}OjqEP!k#ttO|W84A=+!o1I860T^z4D)(0ySa&}%K>&kcJ^gV?4N8g_r+ljzkFw6?BMu z=XCJeIfPl!LetrGqtnRb+wBnSH6t{;{oO z6VGD-69zVbCb9^(bmmi~y9zkatc&XFhpf0~mq>+OC0g;oy^FJtW9)E~u)N^7zwjt@ zZYcwjWdOE_D*pm67X{jPK@44GR(O>7f7KUnOAX5(c^)K0^pVj7aa7Rm9h~zOYSU`H zf;0UPSA3=$?Swk|d}V|4rF*#W{q)`t+GCt@dHE*p1*j5?h3wM3B_PzWL)EH?4}mg% z=FUTnLaBV6lFg!LQ1qReiH7gxOi<6cTB>>-i~%jcQmA-7`FTV?tM^%|C{*bJ?09PG zx;KZW%~gFaqF*D+I>|6gk5|(F>DYdx_)|dQ{IxtyO7Sh_G6sL^Zc;Mr8uV}63s82XKF5c^Mw}ydg`4G-M^oKWGXDl<0x?TW8(Rs+ z5*wOzr*B3SXly^X58iK;DcpYKGBYl1qr_tZU`1QWVe==2ro%dCr}6+iyZ5)t_IRsn z+?kG0h@CT44F2@d#U{0Zf2G}3#P5P4WZR6DX#R^8s|m-w^I#Zk*{EHl0%fB*mo z!M;fbZTM=~W8d)+33HFYo1%+oE8WJWqhFC%&1}WYChsz_U6O+Hkqm$ zM)@(6A=Bhlei`L?fg>U*>D*n>KGT#})9O!t-I(k-E)njz46FiO9^E-NDJ2071nx|V*&m|8sUtV4d83w zx*fz765Y{Az3hNXP%VH4@0*8A!-zfX7xD0w&H+~!zmpQ+-mw*8$HzMARj?9Fo&d?n z0do2l5C#ota6R^=33A=bFS=FK1x$}nU7gcgR)aX;m|&OtU9uFyoOj&})S0#@#CIg< zp}FSMK-FQ-&zc3}vR$ByrW8`eS&94!k91yqBx~_U6kHxh;lwB;rTP1?@P6i(`b~+< zXiYLVxAd%Ux0-kQ*V(}GWnv~e7@M6vtuS(qe97Q_i$7UJyo>Y!lH9MFS8?*nWE4kVvAP4-U3Hrh+05ux~ ziO=#zmtVLKn}=IHj&0DHZy3Zuotynayd>H>WP_X_ znmCQ7`tKoA-4}{>C0?QW8XpNPoH9e?HunL72E?^k+`JO*gPHJP7sMu@%?NP`ozPLw z+=1avnChpHrxP*Lum6y6y$1y-t- z1sOK|h`L3z(!H+0zoH5^%X#LJCT0%}_D+!Y5Jj9<_66*?xTgu7R%+S>Kq*o|!*2JM zgl{hjM!gNG2S)Vg3x*zg*MRYUB1*Hp`94E{PB%jMv zkN2Q&v#+gN*07`AHCl8@W4vbC0eR_BB(06yZ;VvlN^>CNNYbVC`aiRLs(W-uq}R|? zQ!+kM`p`}4=XnVTuAO5vu%qdnyyWFojZXya0WZ78?tZd-CAPu477?qZc7LDF=BB59QLE5)PapBuONjZ!L{wxviVMbm<8o$oAfAR!8CAXkb3 zpN41+*jLncc3y%Wjz3)6U62l`!<^rgl2qc9C<=|@OF7x>Yoi~^Nu-Q{UrhSk%)?Wk zC(;nawU6V3{Cv~=%1V;OUYD<=V^Zw*CmWMy@gRi2@Asn-{^($?z?#$0IsX91voXt4 z|3LOrdm{O4j_>rgp`*mGY>jd*zsvJ0M= zu$~@TfmEZy&@M7MJ!09dxaB{L6<24*Qoj?N&|Wr3w$iseCPY#-4X@vwBixb~)Gk(p zfMG+&#huV+^0J?!<{D^YVqMfJZb+Dh>BZpPv<4qS22VaZTTBiBy9&$0kLlv}X~oMC zhi|Vt{LYqZ$DUl;nHBbt|3l1&zm8mb8!P$8#Su+&O1>D~*I;jD4dOdKI`hMThCZDX zv9aBptI%DUqtaT?xGb4 zQP#k%;wxhA2SJyq-lD3G^VL@bh2Qvu`AMF$M9_bb@&4w;5 z)pyH3;nUm^R;i^axZ1v{@os~vV{~p3cqN7a08m+zg8tsZ1FcZBZxdhOc>z1wTbAYV z1C3iu;0dS4alE`OKE-(7IZglnw%QEfG0cYdD6f(K{OGv8|GCEF=9eH6KkJ;bfyc*` zZ2N3tYm2>OO}BhknF8SIj9Cv60>(1GSd;$C zlWPvN)n(<$6JT2@9kd5jc#dLMytw{ee+yQA0GI*)!e31hPlA_^rwZ>@va>;mmk;?dmdJ~=%8NW1+&f~N za%}fhzax#BFf6u$K;;t5hyfM5K?Eaq4i==H?x7QJ%NKdN8>ktuN zb8|jJ;Fs+2hG=!e2;CF9m2Dh_LzmlI>6XlY0M4A};Auv)1Ccvxo+q=wM_1kNri>3^ zP!5dL?IwWmic#o$nK21^r2!X?cCNjX?E`lPqjL{dwZfO(HkAdUJlC@9QA5YMmCS{G zkjd9f4JmmJKC%!I`MX41KnHH%%Cq$b3bqyumjD@P8?Y&fj4`^auXU9f!NcRY70hu< z%D*xct4t#0biL69Ly8Q3^5Q-B0?CJe(ZFkiW6N*!d1F$*O8ajS1O%7q7X9?(D0b+d zHdwc6B$Pq-gkze$QO(LZ!yIh`C9iOUxq;U_DCw`I)Ah9Tjr?oK=LPfCVcEmOV&lVn zD~B2aDBCzc`a{evB>!0JVNSSO0iZCDJXY|*-hiZ5HuN*In%EP?S(GLX->v`G?@Ez* z;5F+ohdY^oAF)et`<_JYW2(dJ*(GlTxHXfhKGVr0_F}&(ksYzH`hxBNjO~9xrU|md z;zbIf4xgpdcd!j#j(K|N#Cs-igiFypxi|7*NX9R8-=EgUlsuvk=b^+r46u1ZNcFID zLXQF>SaPmy{CF74k_op`#V$NMGvU7`EA1kY;R?7qr2q zy6a?h#^aBZQYd^#9ahh}-{vVtq8AR3dEA`eZuDI$Q*TLy}L-)_8QcY_S%t>~LHg)vr&AE)%?e)jW94*F}>;=vphDj$D zU@#p?&Jt7x9oPqatZ>8V39V0OJc7ZllKj{#)htZF6PG7qGk=q1`-*X|Oa?#Q2ZE*++1 z##6D%=3hM8{nd+W=gTD5+zvBD^7-`@)`^O3aSURvyl$w^8?OgO>dJ0PzJ6w(b#V8 zgao-y6Q#%kJ9ipqV(O3zgjWa_o8EngKI}(6nF~kXoXCq%qhCLYsy7PG%J$;sPbpEw zk93@B4WFSR`jigf=6We_2){tu*JF+v;XLJPbqsxw&Evi{4dc%vTCnQ4_Q(>iw;%99 zpE3IK_%`h&F^GH9R}B;0xGdCJX8Q+2O|vm4n5A*=K?(ybK2_ZKIL4a7&FvX_k zPIJGBqsXnwy9^tMTF%qdjR69HehYcpB$4@<$D!f~rRxs7>6oF_ zc%60EuypM_VK@9#$wpqw7`x^4)1zT1q+Al<_{_r{c@f@PY2{H%TmW2H4VX$Kx4>w$ zP=?z>PZMNol==j6_B@bw|7*~I4%RCcj91$Qk{Psly z+Qm&8a1c66cpUHXUq@{J@qWX1E`*>bUkFS}Wws@h1}zSK)gGOZGAsM+POXt$25W$$@?1j;&Ca$AL`TB&{bxkp3lJ z+a;`Vqhs2WFgl9+ZpJnwv^CS3HIV-xy*!Mxpvl2GGCG{0v4s3t{s9YJ8zayN)ojaX zBnt{Lw{u<7-X#*Rd|P8zXDpT8W7HS2BMTBR4i5>{L(Jvn+S1b^tk_aIU!$qhLe-py zr0~QyP9jd<()V%b1Q@bln}F#$M*=+G`E7k0Of%hXt^gRmgOFmGD#U&6_&LE8tkK#A z?5EWHCGZF>5rC;bCg#nXgPLV_ofkfdD7gJJxc6p~Gv|^wC}?|{#H)%--NwHP3nqNd zZGuryCib<5RG;&S(#3f7NMAo5FxTSmJ$_G59sGF9_y2I+B_6g{H{4R49*$zDKd8zw zBi}7AG}6rZK%|bZb#q?!{lW%?ui+lcW^*2Qt(R8(CH^3-x{Un7E~{i}_+=b04s4(1 zAqGG88AUCHB%g`lc$i=sQJ zARI7owzu|7P8Qu&1b`i{dF~LQx1> ze8n~@LqW^=YyF+g5huJ{<`vQtdM9Y1yw7+ghCO@&k;~=02oE<%^acS!^ zOL|P4#q;{2VP~iQg%5BA$IKZ&Vc)s4s<vuc9bnghLSq6kvTqWAdU z@NG-c?b-J6*Yr_Qf3DQQf)e-Uxtx)H|6+$w5GsyyV(>cXzi}PiqD&aS7<2FxlTe( zg%pUl@o?w!J==p*_}6%W`>*^UEdjnRobk-0kO;`217dnAgarLf@9&5mlkru`hma3b z%@b#n4nSN?kzGaQAQTv=y~=|(yy8}KB;ZS!6GSba)HWNVD6_7l-xAn#CImS|PW_~M zM^nn zL{PLbRjaKZ4kQAT;PvVz7Df5((emzU z^;{v7Py)eorXAp3=HjP{NgW;RGh*dUIDx9JH@huC=tOFwB^w%e1HestbzZ3=cX#`` zdcdKTuFllt&@%)eR0^ez6*|Hhlg3El2=s&2kK&qGv^#zi%ixO>6$@LY5!BIzRqGsm zKSAd)QbHj6#@w$rhE+6qrUq#FoEJ*BEM`S)VsoZszw%zC8j}_d$k4tKYK{$clN~w& zQ%Ad4uIpudV zkgaN2{EmS+K{CpmMkn33!UyR3nJTHs!Rxv7`HpIL*ueX)uv7@%a!xXsj2#9akCpbS+LATHmGLQmPAVAf;Rrxc&B7mzn zs!?(}Z5ZF_l9TyOVB|kbE<2w-q8gkPyO}f>%j`Wi9ss*Lj`gvq)wE?8m`?j%qJT z)`ywc;A==$+#XKP838PauyswBka)(SRHmw|4Q4@<#h0CaZ5@)&1ThLSaKsZu8#!%arYvyL^TMfflt|X2JcGO_p_V34z?nvQ zWJidk)ou(vcr0)Z!RA$Pt7=0@nHE!}G#xoazCVd{J2|@(Uhd8>8w>TnTOP=dKcUdY zJbmyjPZSW?0SBpC7zRS}-hn8ZV?f9P!B#f00%5ka?VK)_u~9)RG^X-{W)3|3EgRup zUwqt-LBAa99HNv)8wM0h?UP++z$qrX>?V zZ>qlV%GmH}r179mA!qTSV8GYBxSU4AdDEIE5)114E74C5Yo2!$-kw|r9e;!`SVJ#t zc#rF)(nU$hq>s04kKSN2wzRT>tZ}v$&w>{L!aubXmo$F(x`ZZIm14#Fz32X(r z^w+K-BtYCrvJoD3@t>WXBvIZiW`#@TR@w^Md<0UH=$KI!canwc+><0v!h$%tHI&eG zRDNI~f2pRf0V1!|aenmsXVw*CT*~auqr+(V(W{ug1Jb-&j1ba?)eCUXz) zBDb3PPb_G@qqA8HBqr^buGPVX1VAw?&Cgqb8YA>@bCBh(k8>4H=PO@){nQOV7KDW( z1!Ft>7dNKrB|DRq2$=nXq=a3T$oAWk)W%rg5neMaxZ*=FIXantv;G!NU{Rz(ezC?S z)5?f)uU3il$)u3ff+!zk*OI?nPw+>Z51MK1H!+liB?zQ863r+)uWHuuI&r;vVvBXE zMK4+61b_aoYY5x9aW~DgM96nb+&<943EikW>@}8Qf-&AXBnk&etB^QEryXafP!hwS zi1dCyqp#&y@So|-b0)$?vrfFoYmHIxk^Q{;T;<1}FbE~l9!vm)q$cv5LC-5kIu~pNh){XIY z9Mn|*N+prfgGSVG$CLkyf+kCkFaak~a69;%qI&T{Zld7K0IAjS5U@DUoagb0$hT!x zN6AK=kyHD-wV>KRh}zk1eA#AkL6^Uz%oFbeLBbS1%WFp~i5sVRt`+{1qH9}tynKST znF?w6LC`c_DAS3OeX`z{7MC!srbRXs%26H)&#MOW^y08L%*+^MX?CL$F?<7_uV z?NN&-zKGU%B;(1FOC=mi6AU&BRd*f>wJ13vz<{8!bbck>R+#~WCh5>oIaJ-y>N~=o z1UmybZX}XrMrNdzbJDRPEgxsmuUf@HBJar37m{=1uj-W)^^fms6 z9gye}O3Wxo`;7Iwrp?U3cu;i-^R)6@s!lk!ocmxmQQ>hZb0+oP$`U~hKWKjGG$D4S z(MhOjt!}1OjLf(3yvM8QdyOFdg%-JEZ}E{`aFYf0K%pjz@-2>M|K;3q+r@_R19GfY zCD>jHlPou-@`;LdA#CPELOTS0GcBiTI_J3r@dAdg=A=MJGU1rkr`ND0kCQX*8JTIB z1~>~22?!PC!+c9cx%t!RxR~ z^g(O}$zDvIb56!Tlv4D}W;prqO#m+}VOmfo+N=sM^fP1Hww5WZ9;zNi0LSA>Z<8j- zXsYA!;iAM3OJvcZx2A;wTOrnnpy2a$p_sN_YV|JoM}Vsl9PKn}9+2uR?mR6b$vqfU zPAf(}CX#X6Ge8aJ6`3XuX4oyb@42D(@~o}LS;Sh&xi$nT>Xdj`2{;CD0zG+1#mVtL zRdS~NhRh=gE+XHwNILiuDbVdMvhq&t%3H+xZN}E$6>|+_wfVh|w?d5wVHdX*4Eh5% znA{M)41_S5;}}?IDwkMDkEJLjOFVP+PN)iOO(p@qAR$iGgrE!ed!E*NPo3Io=+rc6 z(qzTz(qN`odoUr7ycIjIhd7rkN zpI`VN06a!;y_Jd4E|qBDLk0`Lux(5+Wv8Z`Nq;mnmac0r{$PQqOYxKS0ANjJmQJ|m zvcx86F{qBaE((H(q!<|W0|`EufE|a!cFpaJ-YP6sYMT7Yk3E6W+CMR-B~#VveVGX9 zd`B;utO_jHGvrev43`;NcrzW#QG?vG(np8itW~S9SJsN#7K#4Lk;dmC@CP^cA&r`+ zpszGW?PdMZqXytWLU0X5&U2oz%A zoGU^j+@QX*vq;1e-!ja70E5!oYvsyrmD8Bf1E^)lf?)b-I!B-ZcJjbo zHIZ7ckAQl*!oEQD7bv816+``&i6Zf0BzgA-e}{ ztzti2SUtkTW^M|`N?yW4ZA0ys|IGv<8s(+*&an{auab?lz&M-8`NUpFDvv1Nr#(t54BLJEwz<1pVqyS0LP$s97(4qvQVhYg#@> zNqE>kfKC-u&jxM)#(CUFd+@q08z}9Ame5PlY8SwqJyZO-FiGVT?BeW@XC5@-08K47 z^KFMAr8sVKf^?jvW%ELG4J)=;03LtR+v2W6%JXX@^olCO4eGVQhPk>gS-82PSm*XyjEQE#5F zrUAS+fl^F@;GtF)SnztU!(HfBHL7MK7xhI}NHCBH_!F&M7Cl>T zB@2l9+ZJK!&P3|RPU!3FwnCRcB4EIV7@O<%n`T)L%f_kQ>t~$4^}eRAt_Yob|VfT!VX@ZGRD~L zsPr^CSBbuG#=2JR{OZtex$6R3=?_c|3aC-W&lK^L$7nF4X>)5v18I_&Zdi!MPSaHt zRu&#iB`%jl000WQ$K%qV5eazf*T4BYMyrDvIg)^sMY5rWh%}2|PX2sOh8^iT-aX!o z0ww-Nw=+ZErCV9uwQ6nBxML%&({E>|AxRtr=N}DQrJr3g=vZ`x2eiARTv7WfiY62? zcei_{YtAH#x=ss)Hvstj=A(9ssW#{5_k1)5jryHQFG z7p7aFv99nU26%DrDuo2DnbGt|GX004sDJz2pzM_toj7QVPmDdZ>r!qfhDW%nrUIkaqty@sL2OJk8`xw!e=ajbaC< zHK%?IpH_!ZI&YG!Q)yMsCj0xj_=pC)oD8=EQSfW_i^BrBjs>kf20TexrfF}{xRxBT6{YZ3|#?W9=1Y;GWJr7Wb>Y@^{ zRHZ`w%sPJ#qYyl4c{!HnI7z#KM9&gwkTNL%01Y~j3TYWSrHzN`JlFtHV#Tp!HYK4( zEinBMNsNH%f3Fx)@9bvO@^Y&?J!*U(1>scnAzyT#rnvHruz1!KZt#>RU_HRD5|md$85FmL_E!}aT=K0&=oQ6cIQguC$M^7#Lz=Z;V`T98v_ zt8zZ<&@Ly!i>z`Ra_oH+1{H=IgNfKXc`uTjtOi`l**9xmvM8WvdzR=t+idysi*9!1 zxm6nrZ&@&B6bPZy;-I}CRAZdtT>U!Yw zk6|z+0D7$oGJ@zoC?&zJf&q-!ucIUBJLJs58;CNw=->=+zG9b{Pv?8qW zlv_@2m#b!y8Lf%Zt>}SE&uu(hsT{DIJ`%C3qkw>Khd-gCmfVOAH+I7XR)vgqq}4TH z71cLIt%h5NSg>V!xwi=>`bG0DBuKF_-^)hw=flKFRY`UO)zLzUFoGv;dk<#c{Z5gY z2JTkXSuXCXSI437)f?gURL3VmKE;d|SD}p}Jk^(<2R_fX8_pXv`XK>uI#^8lFkF*y zZ!owwo6ZKa9CE5=w&Qpz!y#VnuVe&U)JwcI7xM_M4KJut~ebLxl>rDIOs%(b$Me079B^N?#0 zj-DZ<2AWJD3>;HS`gj;P3#xpWBujo&1|?K=bbpziM90qMyKH3%Iu8xxb|@-#G(AZk zFkD%WzdlEQC{@$^l+SZ8&CxsE76XL=Lf5z@6$am(XICek2>{S|pNg#!&Hgqugb5?k z{5E%t(Aik8|MAAA8E^-97zp~k6m-c(#HyX!zPEU8oQbP)ssQcq*2W^^9h*0dx@~Av zouhQY=kxR1Kdy@c#kY~w4_KN2ahsJ@W=TvjNJ5Q;&ZS6Ius#QB1?E`hcrOB>?pZNv zxQa15`tu0H_n@cVu}5tcx*(%PNHD8Rd1@Z*4Q}vPjBF5Hu%?fos!T!O(Y9ya#@L*w zGw;>WlRYa~B_8oQ^Q|KGA*Eu(UB?>HRC`e@am`F;3EF{}>?@N=Tq>4O{u9DyK--T! zdKwTjOctOL#ra5C%-uXJ?`LhtpI^~@kO8a_;9Eux?E2NDXH8OngGmvb+l=mp5CTKd z7GI#~C7q*bQF44O2j*bLw}&O7W{%mxXXtiZ)3gP!BuPYr$qLi6q+ZK+&yf*<6%%6J z-pzd>J*9J8v20ySaB9FCQOYKL{~;9w%!HYU0#7iYlzn)T!RiDj6ziV!S5Rl)LBYJ9--J zQ>onMy_9&^$M+YzaP}XlV)@(++Zr%%&>;nJV(nV++uBC`J{W#-Z-6QO`KQ;^se(l~ z0u$mCtYGZU@F`s&n3Z++LNLB9atxVUCmN$D*7DBpGU4pBWl!2r13~CljU9PWNzeJO z%F$tOCL`cq0it*prhdDgw(vWTW??l===wpQjn_EW7Z5TIqNn_@^4eN}=Xpe}c^FVu z5o$%?)1HU_3ST=`;#|4lfcCjqXMcn?i3>uF%;Hx}fxNtD_&h=C^*XAzI{Adpb*q&& zfVp%@f$!k>x*TjOC=#|(6p~+r$%y?1iZrn(IJQ0v<*)31Hmg0_C*RBxB0Y$8Ns5&w ziCfJ3CKKMPja##e@}SR&ur(|jJxvsCA^>s|{gw#XQ}!gCD5OjF)BR`h9DY(%E-<4F zOr7mywi#UF#Z z4GWnxu(*0D&} zDuJqgdPY18h98-I#<-+L-W9}~z6eCv);qAJMU(6oyAQ$k(=qe&aK4JqGGD?25XGAu z;c!Pqjzr5OVhJy>8OTND%Ej3sP457|u86+-aHa1X|I$5e_%DAsptFoN?#ZYpnS-)i zr7zxYBVN=U%3CS%j7iI|OJxU2eMDW6IQf7800RMiSZEgv%_UX4Khe38pC6Pc%~t&_ z2NZ@{%qAGlxzY!Z>N6$G2I?(epg7VCvq#C-T2ok|kwpSC zkweK-&X^iS^eP9asi>P#T%0rgH2OL?#@B@y7YV9v4KPxr^P~Kdb}C%_x=s4SK25LB`ADjBbnF5-ZUv zFSPCSxDFYm9<^N}nJFAp#AWKDn3-AJNbG2RXqmT2kuWw32eGcsbi-iBGhsIr6BXuw za__C+Te^+ie2OS@6$#G&X|ZB8LJ3c++x{)P9N1#|J3rKc0)-fo%634zsZQ8hdP*3PndSU{S{E}uyQ29)4|yV8Fi+d3)D=S$)@gKuD;h!rR4GV!1hl*UOX(5^N-I}hMth)W zGk&#V&KYw<3VRwrDcBMPFIlH8I^d`o09pv#15#)nWJ+eoA8LM;Uc=O3!e1hd7kYI1i)Anql z62K;yxvQNf{M{eBP1FU$ zIbf03K^i}=#DY)YeD1=Ky=`?r>bzZ<*QrgDOgbA>!{~yBp05;FBdU~*3HW}Bo93WPI3j~ml5sKT zW_ls&wyO3nJr?u`YqR6{6^@LBMAW6_`YL;`jl6#a{H}1I#0iys{PVZ2+<_OJznvhxVn-E8ocem|u;>y59p+D`N-)Bq`iO6GVQ{YZ%gNIUieH|RgX<|f zhK>&@WQqFpBS218q}Am*^tTdS^nha!-`Vf#5gd`7pQqc(i!FAs?>chRiT zVbJiWB%?CN`kjoO8*geyoa37M1^&FqudXzNc^fCZPQ7hiJ*h)X6T>5i;2k1JO`vwE zo#%c&!i*ZBQfA;Z>)As(X3)P*&D zOgOOuN}X=OLAI?%Ze5?CPJI$}esxKO6(Y|7nDPoGB@6-AHq%|R8wQntOHoC-HEUu)t_R*YDq zUNb4kZB=2mNLUXn0+{*8)A0J$dC)VK_j>+dQN_m|g(A%eh^Wn)}?@*|*NJYL8q29QqtIT!rBE zU#fCC|Hgjdza&^@Hdm8|5r=sbQZ|X)Uf>;nA4dH>32LmsZScl#IkoX18FMN1nlv%B z?@r=wR2~yj6{{2*Y-mX2H>If(Z`w7Om-4PYu`exw)j^rOgQL&j_l;I0fL;daIW;TIq83LFm*bVlavBUQ?Q z7So+eq$J$fDSAVi@AoqqNL)q!7$Aw!XNbv5sI6+!kL=3h3`qPJ@a^Hob;(E1myvM9 zxaqsyAq44HRn`^aa{YWM0?e_qXqiyC=Idx*PPmW8aB9~22BT~LH}Z9Uf5xl~3%#Yk zB!kCAg~5{V%qVoKR#_OuEURYps{iSG1^A~B$asQf0}(W!HRB?5^*OO42vGvfkgko5G1{q4g5I?oBnt>KJ2Y>e@ek z>0CiN9>=}72n0gs8Ql<==$B;bgI+CZFc5oy@L|+@bTk@Gf=pVb7HI7C7H)vj#Q+1< z?W*^%@+!n5RAUflF9EUL`~|$dYu#$Q?(8)+O!`~xvtwD2vE7=4kl%tF@cp~Zq;c!9 z#~=iM>c@EV#fYi`0Y_pcBZC9}@Y>y4+#x3-7@qbpTg%>>&dDzY19|Q$_l~18Yr-9un{HFF%vWxRMLYe;Fe*U&9B9Aa_1&7^LuEQ zgzKPv-Dt4PN9mQ6g9lfX3h0AaiQJ5%_r0JW9_~YnpxT5 zVbItEX%ryG_pQcBJq;vB6a=B2eS6NFZ1RDO#qs3pEgk$y!c~EP#X$<2tAwv;a&|pp z<>i{;>$?c3yN2{L>HPvPUBprLYaSqT&hMVixm=E5*f|zecacxAIv(qh%J3jUr@pa%n#uq||VVG5O2SBPXxAhUwq*`=)QF zsmg$paaGm0?J!{Di8YnWS3J|}ajySu0YR};dF5Aq_qrGN+|2W7`2oILWWx2c9Gi2z zK`MbQAs@uK%PoWJmspre$s0)8YHh^+R(0w;wKBC8GZ!%A*`FtA7pS^T#U$3uY$5Z7 z=4fC*hTjO~iGl+uM?I-xYk5st;0QPrdjlKFvy|LHP-++)t+mRZhP?fpfOrmu)#WjE#eK7_a_8 zytWqXSNLo){Q9cF3x9a~b=+;0_VZ1>mdy96E_{>f4(10|7L@H3Yqg3`1&B_F*#&4< zmt1XbO0oSQ_#yf%|75JugGGBki|j=c=6AW|{9jDtCkOwAbsTGYIt}= zQdcY)9qZfKyb)&~_mPWwsOBzVPfO%k3t8<<Qx^K>TKf$m#@#E+^LTT_S6w(?ID0j8`~#isMc`ry-=m`-&eizsQ19%K~SL1dtWmUdvyK%)X1 z0KinADGvfV;4?_o@%H>BZy`9cIUu~|oFGLuNQ$2{n zdNBc&I9Fu5e+1ecmjlm7Z;Iv8`BS{(O__>IVN;h>|KX8fAs1#c6|j4LIIj+qar8}Q zr%Q9GN4?aF?r_B&mS~Bd#-9;X3k@qGo?P62(}Wj-z0mjWX~6j!(eN`gTn*VSr`8C< z8z8{9tl>=?*%^5zQP{MjH?C$mQUojrCj4lu7<{k7wUG74O>G{#uv@T_07*bJiEo#vHWGGiVvFz~XdoQjdR z4%CNc$MhA!Qc$Hj%+ppVp=`rnMDq60T!Elf*AkpLGtbN+i-W1=kZg2xhJ1}5kqO97&1#Fc#nv?HnCXY+Vzw9y5S3-K=p@SY7soo9x{`v+7ZB_Xu+0jHEWG+gW<6(O#o&R$>t(){m9V+B z;587@UX)^kvbhNZ@(DM2Z$L6CXPy@uBo|y6j+s7c{#laOm;}LEpa8dEFC6$jEc6X} z_!;2c-H`G1S$FI1*#5ghd0T&u)a(38m!aK!0iP?Ai)i2S!Ya-k!aUYee0D?(YjPJR zO$|~P56{(?KrGsAjP8Ui60aQoUnFoR9wr3Wi;4DEYx7BOq}6KaktbPzfkNRsp(acm zf=iKpe5y?349I8*%ZgwJJk*Jr#o}^t%r+>5dXyTBO!u&Q0$e#2l&b>%z!$79^;Xct zRjp-9!Z3Htm(rO5rhM;6=9D<=+AN;Y6`K6Exjy2{ka7PoSSF#BEZ46bWil{QC-o%e zzP_pBT-^ot+rN^+&S6ANVwF7f-(L3&ZyEwKKQ>O)7Z1#(JWY@lFMbFp7pBDgf^Q}EK?^JXStC?b@h&Q!;{gMyv z6Yol7+F0mcDBH#q)^LW_;?E&x>9CyrO~;_`=vCIwr}(pUZ1h6bz>B%jXv& zvC3+5&gpH0`HA7zIajpIGoGfqEqGQEwdqv}OUY>mVf|glICs4okjh&$<{SUHpX>+a z*^ORV&qO2j-n4iy$`I661#C$j13b9`K;4*@SakXg4wNxiDEFhD)V{;$%o`+8Ia^3DpY51||_Qdmb2jNI$YCw{_ryM96 z6OHF4Xn|71jn9T+Mkn?+=uT_&OB))@jK762a1LrJPP;d{ua1=@5>;O1BE;Tw-u_Id z!F$JPxM$oIJ{injfLm^zQ8bD~KIMn$T0db~m%XvLyNgngNZz0d-#8l;gD4ge(3@uZ z6efOxp^-wDD^58vUkM!D&AH@$??DCg?gDQ9ut71iHt2pJuSP*xB++DqA*1vK;7NJI zh-()ta%-=q?A9M-A*ySR{QAT?)N}Bd_Nm?u`?)|^Owm%mT4}R$G_kg1Ce!8GUXf9! z&}JHtpvTa|P@*;JIYiO~nUNt@>Y7Yrx>dYat1SVqisW_H(yFQH zbVNJOP_NYf*=g=uU5~BAe%n~om8xIF*qLFBOz#m1oR`sZ`fs!RIV68fz0X`4JVG6N*_fw&6T@UVJDAKCj{y*-9 ziBZt_EvUQQ^&r~CbIQlITou|4_y7PAL~H(Vv79`Mer8u%$GGOH?SMB54KObZX3j({ zIefoj$=bPUK9Rox2c|Wq0A|iDW|w4ZdOCMgUiN?nk1Z_ua0TlG7N3kq5BzUzFOn@y zt)Uoc(cEBEOZs_EA16n@Z1A+3qG1-JCVZ_GE)lWR5Xlp}wHmI~#4}97Rl) zvDMh0=>}qqUTJ#~T9W!>Pz@FlLI95PSse97d}4SFz|7V&XdfG`%fA(D^ZfFN8~xOj zO^znlh*ebe&NjW)%5=cq7S=3YsVV3;ZXY>n{TBcq3oC@2R>tcy7QX4592;t1Svarg zX4nqpM@h%n&^6aPutC%{JXWOGjdIGB_RemL0@S3mDS8*Xm+4Q2zNx?6 zWLswmvo6v`%;r)lDUY(JNDH3l%|$4tP91_|lw7OZ@oyy44744qll#JA8Joe2oaX{HE5fWzbz!lRF`2uZ7@+gmfRvJ0;$E; z{V0=N&AF0etxsTBNOhw{3)a$n^EDj{pfa0BuY{lEbS2taM@;)ND1K!Z|m{O20{fEiP-k zj|D+G!p?3Er{vu&Dlae2>}EiQ^bi}=#JP+2{crBHRqcVBwX<9#aIK}3WhhJDi^gaLHVt7%mM~TAE33>jik4vQ@y-u0klx*oq_P?QW~dRUv^$?T_$jlz#p6rrAkvC1tSwpI zfKdARY$g^mF{WIyu0C5dZth`t0u>U|0{}a1cTy(s?gUa z=N<4|?PCIvoY}cSZz}@!Z)c`-9lg{PELD2T3H}0bb^tY)U8URrGGHGJbXLOHmuF6f zw%YqC)c%-9!{+FGOGT$ae$%01C_-xtz%ouSrQAF1{gd)CRWCSA801Idmm|d*fZJ!U zpi=F>^ovwQ%AV)#J$T9^l}>{Y8-GRxw$F&Leoj~un^BC=2;pZh=7&Yb`VNXp@AP^_ zd1%lGk=DtLU1wCgO-VJzUU`Q-Oma4HXj7TH(nkmq((5u;N{=5j92TS~#rtW_&#OLq zSJ{DuYc|6Uwy|?18PnMP44+c!TiTt-{$ae2^46GL!pohNn?_gURrTjX?|f(@l`=#wSm=+B| zC`_^D$u+6_lrK5@QYkDwTo7m%{hlN`HS;VE>Nj<5ky@;iMszemK~AlCnu7sRG>m_R z4ozT(l^W|{oN<1zWaY-n*z!+5{FBk`YD+hwCVMJs^WH}(@XRGKc85$Elb;-rTh&E| zs%3hwB#jK-aR}D+r;}+;fJ?`gb}Do$==$N)%A>d{@~*9D)%~rqsEIpU4u>LH#Agpy zb!*-2$IGxa8c+Nmn_YwCH}`87m1;SiceMZlK8`)7 z*ESv9yzkR|^-I!;77GSO%To)YuCv3vLT%CD<$IXR<8bI2JF`tk%PmN>T1w3fwk8ux za89Ul$S@#Yvf4x;3S;S(Qw3qMdb=F4^D!Bz$p~6w9!OpXbdDD9RP)ht19HwSYcv~9 zi7VIgsIHS{cz(YlJq-29YI0kA&+&b+XcEMIW}vBYSGMWwJh@Efj5Rwz;m>*^#R0rNXfMfZA@nq4YR4kuBP!^ zSXskW5d)H%R96awkpQSTgyd&9=3`ykSK(}xx1;3cf*ho|u1MUox|h z2#(RV;ay0G*o3#`!E+k3?;>m~p#X)&tCjX%!I}e6__U39`$%UgK@j0$8EIys_ha@z9!h6ZP$#*h{5&)E*yJ`e2+%eE9c$j#u ze2(JG#hWF+n+l+c>TSqaS^H6z5G_g6$Rv>+q$jI7$ECEOZFL_ zr+_S0^w#|)gJ#>7Ye6q}^QAAHYP;G=>W{x48`09>dI-GQ_vbX{h@tL6rrAC9j{XI8 zYBHaD!&*bGAM1~>>QWop65d15nh4T3IPuC9?tQ+tnXvJP>;sN_%zHK)49P3#M_ven zQ8HT_85t6mh^+kkL)7R0qFvgg27L;ADJN4l%|RK+KglLZF43_+0F6OUQIkLQmtW>a zhlCB00p#=*Oa5b*oJs}bU9?BQexceH)eZ0w)S(%A)9mAC$xaFxRQ>N0fZ{M=wMnoM z4PW_I14@}WL^sVfF-bCed#QNJf1ngZy%TKUSC*A|iN8gx#^`23#;bK2fc!KDRCb;l zq<1mscmA^QS9W*|vfmP|#qEQSOfCbVv3UW)vAxXH@s81pl8-Br2Xfwd;QAsFQF1$( zo25!Mbso>4aC$Uc5j4!jx^;pV6*?!6O~*B2J7tM&n{w+N_=I`dczp{TSc7q2>Kqwr`KSavj?niDR))pnd@bm3c+O6=9uM zElR>LeuK98%rG}KBkD1u9a{p=Sk~3>TM4YU)A&dgL`i0#ftsB}77F4x4cCG;_{vd; zFNRJ+l2Z%InTZFBrpgkEeX>0qLIE^tPt& zWd_oPLoOGlgb0(@rEfMbS<+_^f1$fA2KcH&7`>rgb+wup#5rweasSP6T^o=j!4ldQ z)A|b^^qK&qkT}MABZR&P&8}-2LOt>`iCoRUI@EPZhzPx2m`R>)(^+7{+T-J-zngWy z6Y}paOe)9A)2AEh-uJ$*fre`_-@zFipHApw4Rjb3eQEOQxDgDm;hX;U7_oNvcG@5! zsUy?1`M0HEYjSq!pbJ~sdLcBg5zglG&n#7DdS2Mpz5*I+mp-Mv!=G&QL#XMGt@aq( z_Y>){`g!|R7qVFVY!xa!%=kAh`1(gUB)aEV|a)f{VGLjK{3PM&ua~l>$)++#lBb{%&%DUm9 z2EnU{(hcH_MKW4@q&W|uENx8#(rQUH%#@Z4QEFPXu`L2*KS@pQ zd1t<3GQc*(%ZLck9-g0mO~b6mR2NzqmZx~j?Ok4&XI62pTcM+eVOkKNj{BE*unQpM zj%SZTzmpn$i8*o>d`j~5KOP}`Bop}%F?+xIAD}&0anBBgw=}R|QMaW?%?7CL8nubn z2Ig0xU33-Qtq-JIlBA{`RM8M(DjtS^eQKhbD}3Vqd(g*4`4M=VRDW5wfM<_!mlvcf zh88*R7xhvoXYM*xFk3{7ZyzXEcTsG{IrGEUke}~lC0N}BeCSz{p;q{karC|j1uzB%4{!p^pV*bOh zaMCd(AHnU5uU2A21QJvic~USwaMODmBtYAB7Jz@1#k;~a+hL;?w2iG zT9sABNQ{I$7zNW>bcHWSDbXaeIV+wt_so62=H3dwDscVZvDsdis z(FZ3e^p_jGn$D(yrk;tLZ!DOGH=Qu>N@MfJpasW%F$uWppC8zlB?~j`9IQX!_vQS0 zyFPm1lu!1aJ5b!|R+%g;KAYE2mOz3BvrRALG}&7bcMC6*pa`V^1tfPH^62#CizE|J zJLm4tk}1&X&^WI}DdQ&(;BWu{5H2fo>mJZ52Enb;bQA$K)PDG5dtOsBQ>_Fd+-7># z@mZT^2$}tE@54|Q=$*Z^w%S}E=H#Sf;m9?NYm7rRb%Tvgp&>>k$J#nh5fEN6nH!;lr;9b(gMzBP+rf%y3O#+N2(P@txhkgja7)1v1GU!qBhf&3MTHH zT2-j$zW~|>wV0Svpqi;M3JvE!+kAEYN9|u6tPXrfn>uWap%(IMOkG6u-vsvY> z>@|41%i-f7^}-C&f)4bdq|>yV`LKB%(2lMF@E&w$TUjMn@o)up&pu1i5t)d1o;{6h ze+*Nn=`{y|uK!dHjqy7uZ47&t5tlxllp6wC;X8D{GFq$Em7b`Su8tJztHUs6T|azE z8GFe6YgDEFmfp$oDRwf#48B@NyZQ{2@vS8<5|XAuJzgHa|HGrecZQt4s4~ONeaS3| zcoX-cDh~-mVpb%d1HYX2bjtBlIAv-%Oe9%Sp@a{J2bF1Cl}1Nj!*#WD_f3p@XtBYn zFD5@E@Bw;yLVUrJSWS2orfgE*=8XIjQt_2e=4Lbys*#x-6a8=2YwJ8DJUBFDPYx+zTC~d~bDul>$hQOV^`Agb4A{~sN&PXrw<(bkMLmfwfuqvc z00096XgQ{oQG@|Sn&x(6AN|F%%kfc5Gwv}_D3beH*b#^PnR2^kM6otU6AmW5W=3tm zm?8s1rhLrWfRD?yuQA{@K|d?}*KRTAYmUP?19omcN3Mk^>-NrbVx@v9XG2@BBi`Ty zC^S*G(8oij-OQAh8vS%$BZo$yaP>&O@QA=H^M=vsP!fc(3ukF8lYu!Md_0ycDd3GE zG>4=krsQyqSUCSt61qR#SYkpn=5SajE{%+aI42}*_F3$cvE8p(yDcIe$(G>o_`QP#4>8NV$v1%%%phcLRB$XFW+UJl+* zR@oq!TJT3I@i}szEbDCPI&?O$<5$Lu&X_?9{86j@sJgP0T7~^~sJU@bhJsRv2f zi~?^T7m!Fu$28~F6_arCI1Kma542ob{Gy{?Au;fl{lJta=Lzg+QQBO3^_?heb8f)X z3Ul^oJicAZx2p%d`;^4U;z^85`6DL}clgw7_DL!R+mai`_Qqc`r>?9RrF;N!jVv#q z)zdl%VR%c5Nq*yd8%6k@nN!=#DTns9I!H`58>AE?OR8D6-su0+JhQG znDYe&QO)^dG|}el84hUYHx`PZG1nth;poWyYm(4kw%LbHrE&guu!$(IJM@FV#4K;S zk1_*_Cm`oO^6gRzSnb9>j2gbPWQghf2G0)KS4E;y$-o~S+L?Fcg3diw`;{M;V74qf zGF?nU)UC`(s0|M@!=LMFbJdwo;QiD|Pg@EDp$bLaxKN?gdSWFBFuQWgp-lYG`akKG zw>p>v?AFEGy@A1<72jkju@$M+w*BW~+x)XFiZ5@zy#P!m3qGnM zZ28skj*Hwod|u@guLz2VDrT#Y37;whRQEYR_585$9m%O^{X?9g=`3hQ9x<@D zG~9glzaE$G5$W}$#DGFWdVRF`O(9wXL>|UBsj5-(%eGklGD1G#FcJCO+*8$F5SO1f z&atT+2&Qyb**W=sQ$aqD!=4E|{{C@d{KoMMnj~qnYmy(IvA0~xNcD;WaNaF#35O&7 z;dLM7osO|BY7dCr+fEyS2(Y}GHp(Lpl-fpBO}OE=PL8`fO##viM{1OYTn8?FRfSqe zeWktegzNn0>?6nHGPcqR!%bI7fs=zN+PGh#WsmNEG~0~%BAfLnMQ}hh_%I}N=cm|k zhNu^_V1dm5#gT=wm+CUX%iWaV<;(XmncnPawVc%5-1c~Jl=pgQMW+^#r(3_)g@Y>* zU<#=JvMZUWtRs3L&yhqN%J_5$<0HL^6+mcU@Z3dq`t(}&;1(Qo)q}{VA=+j_*=`N7 zg|n%uMI5iZ>jY?c8^56&u63y<29j^5C=`H1?OdriLHC#+mWn!b@{Fk3-jes7)%{bR z9NA0#GEU5lOldkp-_@w}uqtbG0xjk+%w_HVyuwP=*t?gV4&YqiUdjS@4Hv(1fyD=3 zQ|Tpr{k5CEh7(_Juphczo)2q!GxHmoS3#Glj^~kn=CaOV4>QlymAV!}ghf-Ls1ur- zOO>MKG?$AwN{pGmh5FKx(P$VV%W(g7>^QvUfb>+C#f@IUa0nvi`dVzJIJsVdAf6oF zfZS@T{b*STMF6$D6n#9ZoVXIrFj;Da*_)@6E|HNwsgdcBcJ{)T%W%FsTq_ygV;F=A@Db~%&8D=%@sR{w*^Gz}b zQ2S@i%-C*g<_T#f2~UOVpdZ*fC%WCc%^*K3z0JYZQWQIHULi}KSDMvrof;f_n?Yk? z)bKVcm#BqzMcNRluY+bpb8fV67IAfB?cmVS$;yAth9y)^nN(tpO>z-nB+)qgIiwjA zs1GLe5qIFb7UuJZCy;*%UlJy379F?~&M9p+5fQK|&Wy}5_>vD}Y{a0=?;CQ?83Laq_j~EMoC%C z0$!-PWRGwlI;mz4qyac+FUxS_;vi6ou1_SU_mUKZ9Ntlo zVvZTJsjrsGToJ$L6-bGhl$2sLZJ*5_4JXA6$1>?2Ne_3}VMUdD^#yj2xq85M8)Xe9 zif-e0v#oaYOdG@Hn5LpOU$unru~p6yb%Hj!B@FMqV^0F7zYdI;f)S-uj*qV1*P491 z1DHyHVmtsP(C03r9_#IT?&byUb4)SSv`~CuqiP6Fz(!E!^_6j6BQA1a$-H`?| z#%B(DGmPRA6R}w*t3x)T^@LP*hSTe9JC9yc`B+xlVU!+2g4woo0Px_UO7r6(^mLS9 z;6Txw7|iHU3xHdhWo0|Yp zd;nA_6=v-13%8^FPgAFlmv^fNqJrTh?&abPf4O}?@92s@iA6OcadR%mBEn=x^{vHW z1p4cd@F?t1-XJR+YPSly&i-|AuIoh<_A)41jR<0#I>^}BXv@{GL2#>%<$SsTO*MeJ zOk%9HwEv@h_i303k~klR6H)2>u=ds~GMvz^LhSqVle$WN_{5RT|7M_2y0XZrAYucU zOIrE6=S#{1JxmL3DNM?;b$h#|QF?)NnNf?mm><;Uu(n6@u39r3R0!!R_;g0z+K_PT z>L~e%G_vae#<>e34jHC9u@@yoG`!?B-@942_U7o61KE3O1C!e@0P04|PD*Q1r#4K= zR~^bj{a7LE=KxGqM2)L~r^&@!kQ8<}*B(z>juv#lrxRk#DEV1ayb3%zOfS{VXTpd& zF^9Ix3_ofz9I*Pr3EIJpqlSSN_*aW)4(Fc$H&g|A!sn`afB7ny-L63EVAXU=;KJpe>d1NUW$$OeLB!u~8+kgN7^gPk!Xac>Y zb+RKGu_pFcK&*$SMK8MW&RIxDa~-i*Tr{+HoPxmR!?)wctujrKLw)mNE+BWxi$zY{ z(@tiwkyTtuJo-m8DX|ZRZ1nn?QPsk!sWaE3N0}U-Nxx%oZ3u`_%>ZK{Ib`d$G)z;p zbK^HY!wkTF4=NXPbO>h42`xB^A;x=tfJoqUM)QK>u^~H~AJq3kTb=RHLIL9!<~(zGyZnw%}dUOdput zs$@?Fh)^$R#c&IS5^V9CnM)Ym$jxJm2_?B#w;=Ucq?&+5;dB2EgV*tR`2Nv}&ga5s zg!G>ri;AKo5Y2;TZd;+vdRGX(jdBhEk!L>J94(($LN)`prHx=dK8KE!B|Q%$yao#= zL?YR%6B%Nl&uf>W+}=S_j`*0mKR$y?B3IJ%4#lOp5>s2M zKl^!hSCe-cjtk zsR9W9lKM9Z({%eKsgDH;617ySwJLY~E3SrSYg{ta00m5zf=Ix`g5YJQxJOic)8_sQD5EPczAvg@i+K-lC{xUvZbyJEdrk~G^`YNSRQ&~i zF63DfTU}3d#sJ3J)~qqW42f)UjppW^NET*rAUTv2`zxoht3k%PmG04A2d=q4FUvb= zx{(zNPg#IH%D!jH(^U2l%T{@@FIu$nLRS0@95QqO;3=+G(!3p$bA47d~PHfyH|A-Nfix%pW>I!kilNS$P%avtH&fIgi=L>xRb!b9XSPr zRPZ}WL`6y~b{sc(x4!1dEZJJh=Qe)T{NmQbSW3G8dnM9qfKE-cIOk%k z-F`!)o-3G=;FUr8>j(FttI`B|Qv)8RZb z)KDNRJ3uW*w;Nk-Ajg0TcIR$2DTP;GA#h>+1ZGizU}yt93V~GUXpMu2XJoHv4=mDa|_yI>ogB>x!iSb;;m8+pn!c zN3+l8@qumY(RT;+K8LPKmtS8Sis=JO+ZP{za0v`iQ1g9OhKEX=_=h|m>;)mS99%3` z?d5?a`Jecc2gh9g=mnh--LkU_2PK+N`IDM_LF?WrMy+N-fqL{XnB@1`uiGTyYrm6< z*i*Idm_(V}3T)vKo?~l8#ABCjQPo0`0)p_a1%Nh~=ih0_Z|cRel@f z`{)M10S7-xK4D|m;ce9|+i9F*>gNVl0)KQBwnrZPsAY$?J?cmtYdh}VCr6$s0_iZOU>$(sSwTW*;Da0>tq^L63RJ%jg2sw^sL!Io zf#+u(Au{jnOwCn~gU>C3~5ThIheagzC&$jc>fa7UsJmo(ic*F20NaKOC z5$UpwOIe$cu{FY;1UEU`DY}gHQ*w(Pm_<6-xR zh{7+N9Y68T51U%kF0bl>`YCIi&m@+-7LcEDHbyJJ*5jGmSOLSG{0B#;%4J8tm5+V}nclCV8fG(@!p9r>A98dDqMXy#_c_8?zljZDKqae% zCKi>(0~lu8cULRkn)=^Vuhf_Wp4&yyAn6>Z7I|&RsG`Dpfb>q#x>E1HcSih}oBy)( z1qA@M?7xOZ-QoOk{bknydm@Xs6}?W}5w)S<-Bv0i@mPiGq_iO(Gl$eSGUy2N|2@47 zIUZl+;I;d8B*DWMv;JV_0*3_BBE@@9sJn6h? zGD}8uOC7@x9LYu*1kuAY=no5W7Bqq$zZoFabwe%!I>%I8Wfh6?eVv`5n6U_ZYYL8h9ev@>Bgzrs&Yr5sDC{9oTIol;HC1z z(I27+&b)~YGPfk0R`Sw_giK@H3L) z#@ZG%c32DlJBt$BLoMNVH)K3I#~s$)YKc~7R}B*aak_AHMS^PC5~9flS@X%4Jn9A% z{fxVEF-7BoXeCqkvA_hJ{m{$~VE;RM=vY!ChzXQFTAPjB}egB}8+Q7eAre4LY z)Ts^41>1j4jGl0W_hDNet>QhBeOju%iCLEUAl)S!DM?$3f;+dLG&7h`>)vTjY)$ho z3pai(C=v+8uZ4f$u5Dq|zh**49-~&6)GAc3dI*2ua5)gSA#*rPJfhi?8dhAT;1P({ zKXml|@-Rm*P!=*SIXeTM;l1rTG+%%pDH@i|t5Q<3luG<4P55)wQ5;Uq(WU#0739?w z<4QSD#4#D&GCO$Tt}|MjdwWxl7g7U&*vE6E5)#Ruhu4VTm7|93P5R=l#wk8xIrRN1 ze;k2%OZgOIP#_P!j$Cj~M)h}BE+!X4uucW?3`RfZj(5(HVxfwc#2D#1`;^I`%Yy@J!0p71$OtJ{-3Dr7jfy%Q9K-0X;WbeQ%Yn4N~cG?Rfr3R{!?hp=V)|L%(pCQUq zsIO|5`mGBa!?0tZCBh!$Vq543V#LUctq7bge_?qxk;v!ShIEz9O@C|*ANp8+bl)eg zCu*q)?2@!bcI@tvPh&g0(5bM09Z=Gnw6Tq0eUPCxw06+lo~@bE_9$@K@I>NBP$*h* z9#Xp?w?yEC%V7>Z-rt|Om3j}6qTIR*<(?9{9xA1r_sN_9^sz_jJ?MslFcGAi{jlVV z&iqo}ghOQtKtNjxD+-A4SV`X@+bJv zExG98;VT;*3V@ZGS)M>dUM?c<^-p zTdsp&5eiM*$?QH^fx>`^gCe-`;iTQ7KmohESNJK{e7>-oPApa5V2sA}Ca`FdD2fU5 z63K_VLYRGjO&4!jf7dd{vj2fNO6dD_HJWZu?Ub|Qs&(GDOv$RMgnO*@vY)?bONN^b zxVS$nmr{qo57DtW|83$>6ls9citnWaWSJ5nXdj}`#jFZZKP$XakwuDq;EWwy&OY$o zioQ^=+XTxZxJ0z|6Rqg;dE#r~TigEglwLc~<_sc1fBT*Bt@tjL6{IisJkU90Mv_HS z7Jp|6;x88#LTlFjWL7-9@HVZmJv16v<%x!Cmw;s{IL4F%-UyX*eUy9HQYAja=M3oU zuU41e#b*~elz;oOdf)^=9HL*yM8C;D(xhoX6#1=;J~0z@V$hNxp5G*quP6XaEqDGr z<(9^NOng?G>XV>YHnm2Nfv3k9)iK}xw5|prX%wdS*GCNi$@+0>Cf{XBtm+MH zf}WI*PEHx4?T=3Wn;KFjq{C5$W@_o0%QthrIj}u*l(`DoeT&PTZwg>D*;oL&qZ!$4 zpF@Z$VJ3|)EQpc|OJ(|4k&db7C+RAZ>OQ*nYNh4$jxQ#wjr+7)PP45>MfcD}GFEH; z+0^0uha@;E^QRhbWQ%pzef>KFX<#uawh`7it?!HCOq!CosWhMN*fiP_FFr#Q5v4d3 zM>nUli+f-}q_#&Y)J}lm{wV=9Tv6KciEF!qW)CGU-|9c8x`kb&;)9ajXd*%RBTH{; z?-hE+1%KdP=hrQjTx3s9beFm(+yfiJv%=JbSVEf~2B34^LgY;UG5u9G@Q4w(q6g0% zf7k1}Tp>ty;&m|f>SHfnzvHyS|N9?kT+Cx(NFO7t%M=mByqfaJRpz{ z65X+R`1Co{oK=|!0gq3-l4Zw%-4W;)dSp(n=%#WXo(Horod5(L-PEg|;;wR&kx`B& zfvAjfK$?M)SJq4)%}#UE(#FCtWh6Q5qMfZC<($LKUw_vDCN5kh@<3G+i&ssMIbq{U zeS?LPQ9RZ7g%FYTe(z?&yh&p2w-~*?mF$Of4z<%NzskZVxp=m~b}t$SUu%fS1x`s0 z#4G4u66L<4Foqd84BCH9o+p`Ie18cXm;&jB!=q4q!n>3QIe>ub37&s_0Y*X-DEePu z|I_f$80gvlIe0zTmm!jmiy+KeFP*53=-c2S%H*O{vfQcr^uIRi{~#6}23r92|@FnYCf z;A!_~fB*oOtM<;Ga_W6<#0IJw{GS&_|K!I%Hqv#pmqFY_>W%^WzY8RQ(5~E>@rv=1 zOhKtT5`O`N$b}mPXx%ZVysZhqe#x>CP+MG;GCh={^;z_i2U}Rjk?YJZ;sFx{o5gf3 z=-3GZXH>J4i8MS))IsrH^0h=g`lwy-6#xIH`U8wgp72x<@6^6jA7M6aSI6gZPJdG{ z1?rTy&$YWTQNYX=T~JYx;it&f@q`5B_a#FG+y(G_=(U}jY_Rj@z#7~e;9KKowu{}F z_IIT08WMj_BlKK9ztON1N-?R-rka?=SzQW61rTt&khitE|U zHd-;g3EPH8kEfRQ=RTygmpfsH1af`NE7ad1iSM;t3BWw-lKK-D^?$UM0NYjkbw}~; z_BV?JlUH3R8Kn;;F1ZOR1G8Eu5Fn{69Yz?`^UZwyz7btqE2_9q&6 z*%Q?c;f|YBc#b0iq#!k<|26go)C4!FHfkXjL>-M`Lzoonx)DzlbnFgAGzaz$vku}n5^>pGOw;MO87 zJZOwjf;hmBnDW-qbGKrkL)m){eU<=FOiRKWj#|Ix^Tt)`I<(3UF9&+B;${{oq40#o zF&<^zA;nEc@u%(9?4F-d(*M5N9*%AzS+&;>4GN)|J@-Ti-Vc`-lMHNnEqz45)MuXk ziFZFRAYy13VVuwyHF*mR2TqS$cGkm5J6xZ&iz{pq46a``D=kQ+^-KX8kLXRVq=#N# zIal587^@dHrK3eI8NH=`DiLXpWdYsz`h=tCr z<3KVcS{Iq?o*{=8hYv3B!tXxvo^#NJ1*1xTe!aB%r>#1scR~LpGWXVGl zttb7Zg_%Cjw*KxH_*9RKhOfUtVF|44;Tcp81i=l-ukx+C6~s*2k)NMAHVAb6PW>ph zlX|lvYfJ_?4nh<{AgA&oeipq%3AIToaNRZa<{N0@2TJfKg}Yt1H%WPOM#6<+&DBLwDJ|Bd|Yox@N8`D^e9CLEx{S2ivL(p&;;}h5Y*| z0R-Xo5X^-(muibTKghjbA4$~THFy3uYD-|@yYLT5Jm`A}wy5R!&shj9 zq(U7WM=c?%*D$C-uPk+Z`UepoKd3)=zdD3yW>;q!sGB#4K){>nVA$-ZKEpt32MPWV z5)xNINw?B_FNAJ_Ayf-V_)z(=jPzgEHCcbN2&$K+{CY;m99IQHluwQ#NRE+R{mJ$c z-4-DA6PM1kVt2P_UXSN9FGQa6&-Z|{)7_}y6Ot_n^`QK`NOa3__RH%@!#yKg3$v8D z^WsHGN}OTfEzcR{h|kyn2R^->lGXc6WQY^z$RUBJ7R53wi+XorD!KIc%vH<&v|rJ* z_JJ~Qr&bw8I1w4Y!3`TgQqs4vuaux+21hiT8hY0h81B6ZMp~5&BkhrUK3?@fL;KGSnoa4GW?NQrS{(C^ zqd`hjmQdWj~@V*@`4v1z`z2PuR~u1*p@_CA5J zOM@QY_iOUX1Bo1v1u*1&X{L7n&xAd4tx~Us1f3(_-+%~tX)tKN6ejU$mQ zYkp_$KIFmeZBxbOy&U=U7q6K07$P=NxJjeP$qlhj#sEe?*Z>{cav3p@{D~qa?h1TI zxiVdy9#vC(;jfKzula`*UY7tbn0+i2dOn{2?S-PonCWyul$d%6tTNYdwUPP>Nal+e z37Tt^#~WxZ&}j(+aS5X#PuUAX1vVQfs*XZVr**g3&DUE$yQWma)ra@d;MCamXATw6 z)j?07_1uADXl=FN&Kn}WruqV(hRXwtzi+#&2#YY6r44?e@(}Rfpo17mg^?o^wL;T6 z(FF?9Z_EbFyliG3E5dW=Da54ZQR*7JdAFhMhd`I8)`Q*JYJkZ}OGn@hoaCW73~NUU zGhTMC0LNzQJ;%^h)jvo`+)V@BMqO(>hTBU_AgFlB`gX~v?r)uW;3ae)lzdEsq1tFC z^;XddIq9$fcS+sCtmgl;EPN5_Dq5=w$l;BAH*0z&Q&4co0M?}83oQkSW8aStt0kH{HAI||Ww-d$Kq)1gx}Wc%$GW(t%}5U+REnN# zd)5^N9qFgzB*S;G%OJvrBH^PA>W9FOIL%ugGs9Gq*8;qegh>KeZfSByp-O3MF?+c( z%j@?C0Zrk*c9b7wa7oR($AAC;bEu*#Q0M=E0J!t$q5jL7gDY;d011Kx0!D-nx0ra}At+t(p7){iZ}|Ef2Mvq0 z%7j0yEt?#M*<=g3gF|{T7>;JFembo-`g8G^W>-J?Z4wuH485AZ1qVqg9?}HOLtPgI zUe#!hHiRL0Yqzi2r?g6;1U3yL7yqk_oqxG8>!%11ehy3L7&7wBptPd6kv`q(wVwNX z`z?eq;DWQx0{Wpqz*8oSlg@{*!gqeWNL^a8WWNm}Q~Y}t@>wj!LhLs$%B$TJ>pk_| zhUp8s#VVJ$Mvt}7GAQp*`onTvXi#TuLX?sq`oGC+*w*2WD&%wN| z$!|4P$0Y#{atV++9y}x@TR)^>^}r4@E~sICi06z>pw~G^_5N{aGuexW5hSbeTe&4& z_wKnZ-~!E&u@G7B(vhVSmA-M_;S4zu81h}w(_|063_5_y#g_FJ>~2kK-U_1E0cccU z$Rwp@Y)+C<_?eOgCpCda`1BP{N*>7utEr5+e|D}l#XXxukV$nKs)ji#3M3LPetk2RmHAa=V}xLVI@1rg}F*U`IeF0@MYhS zvlI878(*I2bg1P3dc21%`jah*WRi>H9-=7>S*qMkSdwP@9|jIP`PBcdLU0IPnMm?d zK<7&}2YS6ybqlsxPDMS|T0&+pKAB^Z0o-vx5?$rmlDBR-Rz;}Cyztk{1UMEv{ zyOUeGet^2jpctmzf{#_Q)HO?O41vj+7IIQejoV8{03_e*Np}9ISA>F=H)6ag_(B6^ zo6Qswi+xVmUWQ;v>{255k2=jE8YoA;2>?oa zqw%AK8(^LF`7$p&;K59r8FdExsR8lyK}kHOdqCAxuDC&X=cZG+ozpC}NlT|QDzDuL z^Xj>$(j;Fgepusi5A zM)IyB>4VGwGFS-3UAVK>4t+INUA4-?Rh8%iLPJVBOd|&-NEld*_Ph^9pkzoepHb0ap>i##9y!o$UdDVp4e;c zZ=jO`DiKE*(_bzVR+)7~mc%}|wTci7VkXn2g)wI(c1FKJ{Fu?w)B&XZk-EE+Q8RFW z({zKlf{jj1y`PXPCQN7=AL0wWpSpzu8L;j{Fd$m=#Ym*EZLfMzqn81&ku$IIsFx-YLXsYolJ^EQ)Pg(>(5+{mRTBa3(UvP`~~{vOLNsMUfVMmBBPmU zA$h3NdwhxTUEWtj0H{#-9FIDO3Vt4vPB=-#-B;yfP-TG)_jDpQvE_~BIwUz`MBxQD z*C0kA5LxrV+mVzT*^mjWIv8+5M@sz`y9+1~JLCK+RVbf+1TN z3tzNaH3?D38;LS@SunD(HU9s8aJD366E08CrULbbVu+Nq%qRB*PA^f*u$~T!b2_9H zd%vgef~F88pgsMD8f@FZ;1mRwia%GZ3Y4{2wd70Tp9u`(W2j+%r*PAlqch3 zu{GZzcoVK|YN}hvV`(o?`>p#+D$J7aHsa%1*mF9M)PZXQT zStE24fa{z&!$YDd?ELF_nU9Mi5Y1mWhUHZ`** z=FK`%B>}eo8v@?j6=Ik5jIlYrR|WGqN?_?w=|g9Cu6bR*;2dw8|1e0SW9ImV){d|+ zXJ*TOe_1+b)1X)F=j3%X?-Yv=qsvs3NZqjU4u1KLEFa6&5P7Z=fa!WMsCnAK>(l}f zb>PV%0b$M_4+tI#5IOeQ^|-csZd$O$(q)@`RR9QJ1l22)K$57S=BX}aaGJ%wB}GPZ zw}+H@!-4x$ORu}V_gwr2UxzDxd4rgub#*XpH#`+?Owt3ax&syaV=tOJNLg0r(0LiWDY z;ZHOQh{M1Elc$_^c(P7;U~znVwg3Ml>N?{NL;wIL5Ul&1=_D9L(G>|b4e)~7`A*%m zdFsMG;f0L}k-ZMbf)YdLFnOE4fK{O=J=mw2;9A)ViEfnJhTy0OxMolzAI?#m4m!_w6w*7@O3V9n!}{dHT=l#d@M(1HJ#f~-{Z)EA0_-`QV2Q?RR_#i6Hqu08CGNo z%$#N#+~?$U&NfMaxg5i9US~WO>PsxNMn~kf5(xJxTc)vHoA~kG>4H;nM}jgnN~K)t zF@yB?SIP2T#1ntv2rI6XlH?=G_GVPO3c3`nppsU?gT_-5G}1wyE0E<#MVrexdG?>b z@vQ2W65(xS0!k6TTX{Fw=)yf|zhq1v#JfM=-z2hflK#5JBHVL={)QIGB}x7@6-g%Xb$%f8gQn2>5pMDsC-}b>(t@MAF+p&8KqMid zKCZHRt$l7t6N3dt0MDKDVSJC`FKsyl3@~L78AZtiIE-ylt60uk)8_3W@OU(&uasaq zbv)=Gg>bRGh&9CdCT)B>gDy}uqRn`6YGaLI!J_mnxM)7^ftxiu<+h3VH3Yzx>iblbyZk6v1GlAx@u^^HC_4U)dyef%l!ao;y@h$S3RWdCfW&^eb+wVzc4ls-ea zI$A=32MjEZBAFq^m`2$tiGi8Ti^k`bwq(UsFy3jJ)tq$!42fXUB5-xY&2-TPB^0*3p0f2dudy*ach`>*pRv0-1bEx^K2ZzyJWo zZn4y4`jPIk-yp&Q%RwFCvEFKnK^EiU)}J@(d~K$(eFA!|r*z1~{i|K)p5?)B0_=R# z-=yXpsE7l_2)ZeUS{hzX{58!`4Sn`Klh++}C$$2@n}F`1N$+eo zBb3vKfBQrMzz^jSC_46HHof>lEyZTZe>FM^9m;Vv&h}W^-QRuwdou31bf>jsEu*o^uOlV?MW8SrsN`D^wQQZ)!6J-x_vR@XLGxm}l2D$u+-WA$w+peF;GVv9)PNc-|k=XG#=nwg!6h zt3H1kZNQQsXmw}q=N4^*PeMsZdd|NM{nG3Cd|ELEy>dXj zw!CzIgJ-{I5D(A@P}ChgW`o~2q@fZXdY-p!&o6z`m^J_d^QD#LkN^M}-+!VNpjUG!t-RX`X}JXE#aZQ zIX_X;9OU6d$X-&{H#xUeGPR0%)vAUnDYM}fda;RTr?4D(cL(dCz(z_PaD5~sEYsOQ zE?UEp1|)<~5t(i@OwG!Qx{f+5PLHp-Sn1H>sL=P<5sh22?ZbEfdEwnpt@F;}<3O%r zjPM@0K(HSS6cWLgp{rRm)|(II=$9zi8gnPwL&FC$HWM91%(clT$&&hw+NMDo$!MT*Z(9oA+TTw=LFCJMBt_hd)99`KC*1N*UL^opfDFiF1jf5$&Lr z#9nVwPhI{sU{pHv(oA|IP%fvi6nb}fjn4t^`iK3rRf|A7$~thMVrCdyYhF*IF05%r z$U5Zo@cT@3C+O0iQI_dcV+`YShWpC_L-J$%l;9}G z0{{R60_&^wI129F4p#GxxL_aaT#LMLyHy-Fq;iTVDH>5=5Q3Mq$3I?Cm-D%7=$)ev z{b(oT6SP=x8svGs5X$tJp&_N~aQn$OAQTQIgH%-qYJxBjpeD2jrYq6L{G!S25uQ0@ z4e7J;Zk6{>$Hi}q(P$*N*241LNDqT}MwlJI?`eU(wW(dEXO`WJCD^()k59q#w7&K_ zv$eutI05OEqm8icoeclx%1!YY?P+@u0AIVrYBg~oa6aG6_3}631~xKS>N>3~Iz&qt zZhzn}>tRSA_;01&t_+lSI1fm9mVY?Nes_y!4=pPk*&5epU!m~{d#ALhK~@RiJSJN8xy@v zJ@p3XB{ozN}#}|Cw*=GC|>xn zVi@AVtZ!Pr_8l4S>Kf*gMt_I0rwx8_r+YVKoJathR=YAaSnlP79^Il!sFyYMDB>*5 z=PZ#L?*1{xR~Q$9i<7LG=eKkpWh;hOOGELfTqtYyxrOr=p*zX*TIw&_9bHE${@_C( z)wG#V2`y1g8%7a&_i4u*0{|XK-g~`bJ`P|tM5S^F!>!Slqx6hym(F2^b>n^Xr5HZ< zxG4Asy{2Xc%U`jW*%;LIT{cuX0&vPM%2ujeDVwcg_r_q4I|HQpd5vsZ(zMXj=vY%3 z(_l;jLS=DdqQPBv;Cz$~XhMBIf6`n{Iry{sqX(MXX;$GhQZt)c^ z6BQe8B_?ol2DZSX@#kkS9|J9I}|XoX*#6>UzPc+ zaQ$!CTmG<+^ndl^D-yF;KLR&-gTTB~GY~BP+5#JrSthTbvMZQLA;I6~ty;Hz zYvSqQ`+7MX)GK-cXeH{BEDUHQ8%9y_BQ+tbux)Py&)B9U5v(OhllBF~f{fy1G+b{6 zh!L={jYd`MBj8b>;dw;6ImLaC%nP&DPSvOmx_e1(!L2gCe$4QKdb03u) zfOEl!%fnp>WLpw5xjq1%aNGvT;0@>#9tpP_nOdp<)0mpJ(Ekkxe-pO+;i1>7ny!d+ z2)`zbf6RaaAt9ZtB^NuNJM>zv^A8?7Y3#hovA^GDAW^LjKI{x_hw0)M*^#z#s5ON| zoyRMSq?ZC0dS)IfGSYbkC*E^LeM2?;;j}pVzfyd-&c~;KMM0?roIlIs z8z22&zyXn#!iAe(%RM_(U{G0-`Y_lCpobXPuvZt_K+pDh!}Lz_G?`i(gNcS!%B;dA zeGUc{j|acV-^;gVSGjxdQyZuQ>sOSLd!agVB zSKediLWqyPp-8kVHj(29vYTJIJ^p6~Q9c(Et}JiE*PQEpC4=FoMR8k7XJI$TZ(zXR z>?eXebJCXqyZE0Z-k1cN4EV`4oz# z!M?1cb#h5_gh=jv@_S?b!OFu8d{fguHYq137IW43JFrzw0v6x4RdzO!Xw`(8r?$l= zF;Ih|7hbM>`Otn;8ztN>g8W{Pg5t%zy$XjQdZupc0Hj4vARxbqW5 zeiWzDOY@iD`;?7!Rl}dBRI~R zf;e%qQi&v>`89CO$_=}#yN68!){*p-#zc(n7hc|;jv9E!F3F}^AM)=(9xYhuBL)D7u*!s*$1K& z@V5LR%bC3VXh9}?AH#e0A1V>R&fr^jio6%5hFYW_Y5>BT{jIphrwIPV5rgSku=sX9 z$xd5Iy9NuK(}ipOy*Ig=K_|s3Hl%D%?PefVHZ&$ezvv)Q5!6Ubhdv1n>mb+}t#q74 z@yBn$hoKRqwW1wBJ68_a=ib{p%&&se^Zy(yKN;MV?oyc*mEw#J&l><$Gkk z43kj-l77su#l2FR9T}5haQlKBAWRIs8eAUUUCL#s@$A$8ch&%yd)%`|o2J(EcUGuk z)QjJ76l&@&kIhFhQj|aMPkr%x*@H##IXE55YAQhM+2?=#h)c_UDG4WhBV*wMCa`Vw zl;@WRj6leVUvs)_&F3B0JdqbhKxY#0-j?sR$a4TcQ532P6I^{aiP;yeLECr5_FcpAD$K#CjTslCWQ=y$3A$N3QI<{jD^gy2YiWCJ2E~mj*^T_z z3OIvnZh~n=U^nvLK^#glDWiJMQQdvD7>_<1I-@Tol*BI{U$o08a_rz5RI)f$4(?bcFyryFOZ4?OJVxPW@aDJ zZl1hS4mO1IMQmEi;OR0;m>;CtPt3!C`u0R47SQY37E|hP#dKRb4+e6W4|xXat#b7e zkiA5#tDVzY;7a!Q)W~$mr9L??FZ3$5ZeC%yM^5PLKs&6^3kao@^mE_e1%?>)>+tV8XIxgAsV}RER5=S*l#^1J&l@QqIO)obJDPG#C80BYV}evP}EBr$t;7BM7pN6 zx!PK{Or#Mj=dE|XmoBqmk2;}fD3N-I1j1`}j8TT@l|8m3{BoTBQ`Gwub}!{eM*@yn zBuz6I(l{l3z{5l@FVpfe{VE))z6MSD5@DG~_mS56EUSaW{FwaW2+ZAPE0?3yJVEMq zP0Fsyz;J7H|EfM$z}!d1=vi#fx1ghZqj!mS?^ce__Ne7^$>}^Y zRya{aX)kt^js1jCs8Wv5hCt&D0URs9%9VxjWk95zy$)vXG#u@mphO>amm^~4)t{;g zMTNeb72xndDGtjlPExFKSDJ?6VgCA!de(&jD=i?~AI5z*L3WD?3PdU>94!0f^P)O! zZogPM0&-MX4`Q=AQj9sYk;Yl>d+(m9_fnI6VjBY~0%+q;J|*{K7N7;2HTxzwjgwRET1OLZSauJd z7NB~df_q%z!~~0_UHXHNnyIHp8Pgkn$2v~nQH8>8ZGPn$&l8*omL5FuXHef%)X>y) zRd6sOc&9vZfs;gb&&1jhFRSDyk9Di6K5#I|w2qo5lT_7xzCnC#RjBth60JZAPTbf` zn|q{I0T?lgr%os1Phb&j?kwj+@u#AbHDDL-zy!hE%kMgS(_=9yv-hr1_ z$8)pro$xv|YZU0z?_td|r>Y&iDaW2ylw- z0%7vEWGo%ylTG!=DuzvTEJW?`x@aspW~1gEFTSGx1&(YeoVI0Dl{f|-DCb1xk8|3$ zw@%Wt)Mo<6d&w@9t=Re(?)Qz69%|tO4Kv00RI3eF5+_ z;qM9iSGrnk+n@4*kS^m+oZ}YU+cHvfV50B0fVuJ`T-<^uSnYKfT3!Zb4t4xJ;POS! zyuhQ<-i2IM?9ob>0yGOWt|-|zPK?9qLaNT1feVI?-`|wq!o66;1$d76fn#C?JUMDP z1%F``)65+y!l$jMPAFUR73I-IV_#glL!7U{&+-9C)wbaK$n^~7{fkyYt0}A0!}E^i zXSQ`5Iwb|tuE2193)P5z|7BSU?P0?Nu(T<~hhb^^ly7%_Jl+uvzPd;O?Q_1Iq^4b0 z`XxoyGNqcg%)OjmEa~Z$X*0ShGm|NRQdI(>)gai_O>{a@K-z zdz`129|KOEK*4}+cbE(TKO|Q00ucW%Yi79aw}cN$tjafFLz^BVj@x&C(8||AZ`U#M z7>WEgUW!9L8quO@(%NM2rKxoUeo`QGCH93i8~Pwc*xTR=26RyKhiuj^FqKQ(>=`s2 zOsYgreJv{CA?e7!kVUnaxKy*RBlz-N!4Z|`*kU+I3%?Jt*o#$UJd|L-$Fqt3ZZ&Lz z0-N9aRa3@m>&8edfM{bg8~$@YrlLE4<}rLXF>t)777g=#$gv^B;w2;7EoR})&v7|N zfm#(B^~lQOXalH3ZMO;)Mi)u!rqloc0{{-(J2u*2ZLc}Sc?dcr7`=RHW{f<%fZLc7 zk01%H8|r_R>l~@kZHReLT|#)gZMhl(QD>e1>(+~YeWo`0XD;n)6MXKMb57X2rD>=_ zT5fo3t6yfs+!$_CfMB&_lHH$CWTSe%Ri~E|26+kUqhQor89LcbA=BO>cy^uHH)d4l=xpPGen~)I=Z#|_A4W)|cZ>={p*Yg=9 zMYeDwC`RSBl2#M9-tg6~O$GT>-s)~*~_v+|B0 zE*I~d70fqHXfR8qNIJVI0Y)?*IbQlK1)&9S%56eEraBP4X?D%-oV%)7*j@F&2z7@` zot>2|g~NuRa^^0^dHB^E(ht>Qc9>XjwJ%DxJ*xT=IA%!90Y9}?O&fetK^{5K`X5G6ST1)*iL9IsIj z8mIqDEw?{M!}0wjl)Weh*4nwIzaDYNPfhzp$JMc!Jd^V*zAA$wX7&0^QX7^B;ZvB< ziBmU@mif}mzhQDQly*p4bz4K0&Yz^W9R%vY01XVfpC%#w`vH~VM-<`X;W0G%YiV6C zA!HlZL<5y5WBltsFjZIBRBU-CoBGWQnhR{aX|V?s!t|Grut9G1Z|#`1(F4Vo;Qe+&B8f zFC56v^S&!2pjJmsI-&KHhAjt)sc<@>V^bU6U9e#ImS3w`bs;WUz{bdH=d!~~z63_| zLO6k>#=uLY9BtoA767JE$D(U*yD_Ff$qzPawJ7wT;VT4{DbuvduHirc00RLd;xh-j zwn&{kf=Cq5s~yGiZws9Fmuy zUS0FAsOd+!)C!KAsdl?4pNkDhu?jz#y0iINlJy|c)5D{WcWhqUx@x=Gq?A+5l4FQ6 zRsL9D2c-yKL1M#ml8hbmQ`ew&)??0y0H(s82BdZJ6;WD9U(fKH`Sq9xI*c&Jcfsc| zjR=+WdJBM^Xf22~0%0i|nJg*ZpE-KES0Y%?)6(d;SYd)yrwoyTN+My7;Kdt{{$?cx zA>m%GX!@`|*uburRi6Dsbm3i)QiNJ?_gX-@&t+2I_G~oDT=JP#1cv~Ruf)C}h|t5HN^T|*;xdP0ILqqs3+HBeFpqP1`U7Vfvk{X4qEWDtyF zdkGX-j}@zyzmnyMUJb84bewVFxg@v#yZ`kin1otr-+pIv?UMdfVXyIAGVf z(5kLCR1nJTg}T&`fHBfWVI)dE1EYyJlI%hHJZfjt;SveG^DfP`I^Q+Uv%@0O(~$DW5;X zhtbqN$T7UD`|9(D1?MO2FD&9awb7m>)54JOc?M1WQ!I}-LI03$0buE{$aEWLRqaixYLfP4jaU1^|p zutH@6yAqCuq$LY?q7e^N*tG9jK)s<=VLp>U?KMJMn#5);;*XI72M$FDH^|Ycl5hIx z0{-u-#~m;w1_0uA8(jxH04*~y19V}Da!x2m?K{lQpamncE zdt|v60evS!Dub)sgYd)UOu11S00rCIIZ^+*4d`+RQ)mtU8uibox4|8z!i$h2%(d*npU=C^SKb36qqtmah=*`8Hce@ zZ_vYn*+m-_htw8<%SJf10p8=(j3bWZnXuL#K>!t0`!ltBCb;3(_%GSMW<*h1gy`#k z_%sV@Y7l1$bDMxQvC0ZckgNk=8-@JgM~VT7DTo&gIOHE?ogJ49c^oHslt`vpLsau8 znZx!`%0gAcOC7_lb*3z%UrQb+y?;uRJK@o*%Ly6;M|hxu4{(JITcEi-rY^t?I*QuP zc&xJO)t&vd9mz`eBx2X|Li6ge?tlOQ0{{k*d)p=`BIAHLZ-(>t1nM`=`%coH0(jc7 zBf_4>Y988Z0M+*eH?i=$I;j|i6yInaDYe#@EWh+MhkKBuBQKBSbnFfok2)GA<$O9w z1s0!no@DKBMaq`L0{FBS+A|B!{~1+S5aOCe_xi%-P}TQRZk|P?Vql z197wQL*r3(orJ9V-{G8KjmR)yUhU|cMX81eYg=1>g}9eNZjwhY*WEr^TIPz@GfbVA z0jcX9TI5qaQI`TSz>s<77;Cswh^-Ymoyt_p_t)4+y8#O5u68_&LCdGRzVKQ^+Dl$U z&w7g;<9e~4`fOaxr?|}hX|~iwom27ZP-gQC6@NF3}Vd>iB;m?l^hK+uvuf4%xa5*7luH9&0Mj~%yHjlajLUiH&;P)bYW7EqB{l2p#_m_fxegZx`f5uhqIN6L%HS<00093 z0D;do&?*w#TpIs?l6Nnfl&jOF8feGB#^Ya_gPtkA6Xsz7>!;)Opp8U;pL3VjF|l23Q>ij=Zl(4j-2$r31fidN&iW+R8at1tU34= zVT;&Aor1f}q<_lEd%oJ1)w&fSI_Y!RJ3-%vXEjk+RUj2AlU?n`^Y!f`$2&y4#u|Yd&-tX<-gNAF^rgn7xa>NJHDvAMbS0xD&bKxDw zfr#=!rADJ@im~{tsOvw+NW{MG<90iUt|1>a`M+A2+W`|qvE+B~NKN7{UQ)|)k|7s= zC@Ed}3AN61L8`pZqVyb%Aqys6)m5Wy`iLAxJ99Rrg*HNOc9`S2B(sWXvrhf^;5=I#vnid00RJ>(3K0oJpDe^H34K2 z=C^VTAJA~an0142&?<6lvqJ;L_H&VryVp`CV$$=5*92GP6<|9}{|rtn+)GtE#{S|% zrTJ2ZehX8OAdRBI9A6~I*$}U6cq1X^vv-zW+Q1jK))M|9#O~oXCBfuaE3m-g1xt`kYO74k8b=0;+C|D?THMPvgQK zqqNQei4hYZ{frsuXMlYQ+nai6-Ag>wsDJH_8rC_lMrY5$GFRy6apt0~6>0wMZ0*cn z9z~D6C;z&0m%fV1Ol53@k}M86yX<+@27>oxX|KatNhLZWln(IN_qid&p4yFVubF@V z01qDl7+3mN+)EBk0i@>9SEq()z$;<<^;u>t-VR_aVu859$=+BvA>GOZ{bU_SjTHHx zQNfy@<$SOiWn63B(7~P~zdZ~5ST@&eWn4mwzHyZ_{?cjEptn=ArCSkL%}b(R(w@fi z0|izGjt&~ELb@{q=?iiv707t20liR6x{vN7b0jWeJWwRzCH>yDceuvVo z>dxa*cCKsYyGY}}ho=Im!)HIbUFYEn0MD$$mcZ&@=$(nS2bi~oWMFKW>~HEc>>Qm* z1nWG}nlnnO~eGH^$9EwHNG7&G2-+jZ+wJnsgWT#-Es5AK2dhVHnGy%o;$;78fflrcWfb%Inw)=GfNiWy#ZdJXQ1fZ67qUFD+-LVM| z$b1iV+uv#0#W51~#Lu^EcSH4Gq4&MGW;b$V=Uw zdL8$i+;^eb_pTL^k`r*3ve3DP$}*P>c-<}lzIb1V8q<{eT|iNg$i1ja4UKoi^F14C zJ|bOjr;&8y-cT)+iUWaaN(z<{^OT1W@x^za*JPJzz8~T{RPNukc!{s%zIoi0f!XlX zc&r3=CReBJzAAbGrB8m-o6Hx?3m)SE|NpwY$g?~9#gji4oAXrQ;OhwZ_O|@B4|+A$ zXgV1&+{aR_&?|jVcSm&sh$dKZoNVPoflk_Nk8F?82c7cN<%hz(OfpiQs3yhun=$7O zWYYOIATmV0@7YSJWK8>s)6?29f{uY=^zdBvo0rSEQQ{$t`D+fK+Scb+&YHzRNutx| zpm9kqvJ_X*gKD-kii>CL+V2@Dg>z*9B#qQRPOWt1@+%>rUKe!Esd=>4V-FS&ls4yw z(zju!v%Dd?XTpt$l34s8G-k61zGn%0cDPZFowfvGdOt7OEyi^>MRoSZX`ElQ+sYOv zf5ygh4BUBK=RkoR5hBMLFWFN+G4Je!#+=uSr*T=ZG;ulN?Ach=+zm{iw!{IgC$Eud z$7wiJfM=ncU=jO31^DYSBVC#u=PA!na2w65xpIi2>PFgPe{q#D@_q=b32SiT3Q#p( zSz(t0qVG6$N`b5w5@q~z8Pnb1mtnoM4R*1;UhKKc%p47J#;-sU;D6!_t22OJlnGoY-aI=0p<+WcN9FZf2rKCt4-@K~L!kMx^eK2Sks^E)3Kr!W@ zzE3j(Pj=K!+^(g0tGG?!VTgV$8dX@2=%IDSm&q#3t1PmzAS2!u!hU1%n1PWK*xvfds1ks1_ zQMkTf5$#(rw8E1={$1)2j2A!EAuN{ya%fPlM7N%N%8=<*Osw)xadQQ-&hQY$;~p+e zb6~WUr?x=yM~eKEsHQqFx^8a+1;`L0k_Zd#4L$%W>vZWBaah}V8zVc-+fCZGk#r4S zE0jz|{V0yee631nWi_`FOg+n(hMG~~em`8aece9h%XK!9J=E1+vC22Fd$j0S;fk}D z2-Vn~#&VZCm;v}>*DLa-q69!VbnfBQZ}zKtisj7&WtZUQJ+8WohuQIcbvc8t&cn5k z&VGX(bayewA#wH%z`~DxCRSAl_($~KCCDG_UaeL?IS=r1U#F;*I;fVt&iDDIS)cBK zmo%yr1MKViB0C0SaF*+70{enUDg752(a%ccI~JW-5zxgKMu8L>8sPP?uS>0@P*lO) zObm^Aojfm7##r3DU`_6LYc>999-;YA*`J2YxP)l(#4b<7vP8PU@y`F1K>BMLo_FTzxGhsLAA{|>9QH&QI_!Lt z-7&l;p2n;*%nI zrZwsCM*B!l(7%A=%DTg2t6UFEMV$UTvLw&z&APMY0EUwbe)O|C+_yc#l6;#u*JZuH zIJ=S2bbbX=jr}MN7qFHr5@iXRJj&hokkTZ2=>iK;nA(zi2N8{oW~SQB?8(tTS~|qS z_*;>4q4ySa6K~kSei?g49WCHZyc0gYjw7GJr5@{vNw3v4&Y(|e*+v}KZwLEwVo~H@ zS{z4SvHC8K439wi?oKs{!qMlKB_i0v5Knv_ppy6b#XkR?qhU_LmF=kvH35c0Uq^U^ zj7$x?mC7kyljJXDLDNuVNuy|Cp1O$abvr>729W|tJdbnRqxK*_=En)Pq^g8(=Ixh9`8t(SVpqEsmL7ZE_O z?f{Gf#Cl}-L(N^;gPD|X14Il_yFG1V?JVQXFFO+A-64P0KsOAAJF80K+jc2wRZEgi zUaLTY$3pd?yG;e~WYVz@r`1m;&Ao69Ml2zdNj2U^wQIfY1&3~Z21s}sS2DZeXh;jg=^B(+Ndf}<= z;9ST}BV1Vg*`Hq+=k~8@;kOZ;X4r{sEh{HS7d#tWELH zI%kp51b5j{s28XfAQAvDSkFWh?uP!E)Icn8ewWEsQd0(#0#^W?`a96U)EdT~|PkeFD6QmOhxlV23z)raFcm9O&Z|0;C<)-00RIl3^f0%!SVZ@1p_dQDJ>hB z2Az_Q+u{FzBP>(~*6OY^+d~C~hDJY72M}ci^yg|>1A!h79Kd@5RA9SMiWKhd+A*=b z%oS8~Ikl>Ey#sJ&&(j8aVryfY8{4*RI~$uD+t$XmHnwfs#s-^YlT9|c+23DZ-MY7G z>aBCmd+OA5PxmuD)0nN<8^PvCud7&TMF5nrJcAkzLFV+!!@0Lb_=v_0{*5~W)*H?j z50vZza!|$Ka}~9U!h=E0VNpFa-3N>26a8}qJXqX}W;;1AQ)-1x_YYX{z0|`DpA+t& zU1OE@A1Otd<;MLT@ykJsxBkgWZdkK-Ol2v!hGKQ#C4trSSWd`_=Cc$v>tC`!Jpe$L z_E#CTqvDFc*o&{eUzw9c?OD98jI-K}D<7X|ZfS!(!^0K-?T^O1s|$MH7mFhQ4h0d%gN)@iP&BAop;Z7yfzh(eT9H* zGmvXbx2~M*AK#MR?2(>E94{y?_VK%VSEYvmJDH)|8pNNKrGETI;o-LiF<9rTY)Cvo zmYDo@#S`Fc;qbai528preV$QyYEu2}1w-4FE2+ux(rEmrCDqfJtRPsI*}l9_x(yKk zfJ;*WZcc<#cBWsSi_8R3X>!?Cd0MUwC>?`#S=t5V&L1MRFStr(<&AG>4t;bFPX5Fp z)Kkj6>`>|;f=CgNzki#C5-dBr_xq{7(+hy?v`FqyPCHjA^Zd3gSbL^8`ZSNrgUGnK z!tahn{SL(;;a?TqmUbrOBKpLhp5Ym^iwi+Du zWUFkFn7ys7b?O2VAbP@#%wQ2h-eenla4K+80_A%26FicvyHAaz=;@xp9gnHx`3n> zo})QxVh$J6S5PL{2TQ*~0E0O7xYvyg|yw+V^zDyo9rd=DsE}V z_ph|NMJ04I95)F9MjNQynSZ=eLtJ}vZ2aw8&O31KPFGOv@ltW!Pce7~eT1?e)TK}F zr4tIIsESK#BeQ-jr(iU3IpmWrh)gF}T5kyOmLe!X@C>mGxW7y}$6Lr4?Z_tzLeQUn z*-HWmjOohK*#_AYkGdzCvOHya2(g{nl5ndfZw~E%SMEE`{Sk?ihmE`>)Aa6HUz#N< zq_;j(6~V7CVmV%=kc<}AsO=TE$FU17=tHqhAVSg}rm-h8`zhdNp}qQ1U^9bFa&6Mh z3$5tsPYLO~)?dN^1pDa=YtsAi$}(WxOu1#Rrd8Y*1w7^}!r(RcljC%zB$}`CRN|G= zT_?$w0tw|9YiVH3@&Vs6A@ri^U^lyfZW7;*WUhGz0HD^#$TTdd5ej5Xd8!&F-qf}l zHs!CrjI+%AoDwB#^}0jE+jtu0SHSI1(?E@4L>Iy@dNX^0J<;teW%LpelQ0>8#LT!j z`P8!rh09xjYOBqF(n+~#xo#H!3&!&0~p zgMQcwS}3^locLe(RgfNh%Q)Z2Vq!YtWHT<^7?ls>N0Z<0nuue3wWPT^`Nqh2wYaesn4iBqN#Vvy^onSvBUBy5#-kNv;+?df|(VxzP3xUcWCe#++ltF;t)-A~7XG zLP{ff!TO+4P@*7=ob{}?Uc7y~`uU%%_ABTN#4W*tR(ne6n5+U4@d3(EQu%UyqOOk3 za)@j`ChvUowuLUz&oE~qP3)Kjds8?t3u=o?-r3Bh_kIKpYQZ@NlF_}skHgFTsb(qh zd-N{}`t|o+?Qv(172=2mR+V92O!_U8SxK*mpkFirXoNl^f}Kvf_XclrGtUynZ)J|q zD7Tp5wd~Y=BThf8^5|afmd&dCKZ1P74#v%t~d3xzK5k zL&4hZ!uE-<{t;9Cg>If~EJ-PULM$wAt;b~xqCVeNkdhN;8ZqzFzVSt-teYnE-poT?+oEbhh(#tL&oz#$h1Mg<7s``vjq~=Gw1! zi{3`-9l!EC$te>MZsu|K^)o(F@4$v?O;t0|223}*=JUR^lgVd_lQ%{EWi|Hn0Mduy z6>Mq!odoz{kx9&E!#!E-`yl%eI~$W+?y|r;0F(uz8s0NTbq+~j_Wr=$Db-SPNL$a8 zT3Z#IFoixYi$Y_JvObqeDPcfXS#`LM#H49n!QX9|;13vc!rIu1&np*bVZ(hXI{pM> zo`ebQYbeifcC8=}%iN&CO3&GXDdZ3kv$=prPouYscEWgrr~1>rW_|5{_1}~fKt<(aK*xeTQTvt9|{B9%a%9`(as81k~lBa%yST5JKbgA~ATlG*7`x52a zdzXgY;7TZhe0nh|B9*|tLO5%$GLw@!e`v7K0GHkmkIam)mPo|oDVZ{`^8Mr?46U@E zC4E$hU)w{geBv)yl(7z~hx|U0o`0}?QIiGhhUtleiw4gL$I$nw?5WcgDT|Y(f-I?u z$YCLGX=i^DYzGIQriDYVMr=7zAb!N8S!HL#e9GtR1`UfWZrsmh`>=1w zvURx52gETxtHRF008yx2`r}9uyP{^@n_q6UPgeG#C8Sox*e&bEyAE)mRLl9JhSI0? z_DfC~0!n&CMb1#1`(&$k3lL zHA%AEe<>mVU`Yqv$hhco)y_+(^TFMx!23s|KCoYQu=W{0oG5}wZBrcnDK{?H2lW|j zI>^EFX`IU4or?_3ES@<6LaTSkfMupkfIs^zH^*rzv0q}|Pf5b13A^@Y`!kw#GMK|2DSv^=hT*gq&l%Bv0!Tl? z9c>v>sLz=2RVv~%_j_{3c;=N66prg*x0S+2Rmb{eu#r^oJwWW-#6rZc^zOTHW&$ZS zkcqG)WUH{H9^;8wogxSTdTD-qH1PBPE zf@YYLzM9fP0-&%l*VK;Jb&t1=h=XpP!O79~Z+jo11Rly%R;ry&TU~^8l2upNb`43j zq;%YO$viqfFkTf`%`+H(83tE_81T}nqccP>r=Nv0X>5=ySMU9-8=hAyK{iIm>5x7o z>5totfYl#$(u)m%eO*1_3p@Ez&}gec*eNSAXm-%k1}D0}%@0z~>Ea!#$^AZGZ3<@` z>#h|US|t-<@WU`t*EvwNU`DrwL%YJmlU_&3g3`u((rO{oJKSj``g(l7irOj;n)@RY z=Wll)>QwAnod|;1?KR4@QV{yB`T~XGhM&_q*ev{IH-)Izv`cmcit+o^o2%yPPeh_@ zdFT<=EY|Z7uCW2&`&hDY-S1U)mLXqx*kzB<%_*=u3MIB6>$|JePjGbJn4!s(I3z~6 zo4*8p1f@rM--#qw)61?pnFlcQNZ&c@C52!{-Kr20{t;??GE>&SPYt=88FzFDfarwh zSHaD&PC;QYIYni}F__IPk&2Za1P-h;zWZrOc-KV-{#*EVs`*tQB-}Fx$y!eKr@3Vi zB#MemtrrLe^sWnI%gtg{mpdnELQow0Y4O7F+VxZ9;F?LxR;CNv!2u}PYjwsz`Kj`2 zYzP0kv!YvR6P zDWkn8sBkQ6joc&Z=7C$mMqVo7w>-JXf}dumQ6YI+;TI#7p^O|Tb|%x9`dmR)A0f$R zV^%{LB>W{rUv@{-b61rGu~6N^d~U#E*>SLAqct~C1h73(YTe+ z_piH2rsoT#Mz0zCdwD}j7ymn2;HOS<+do{h{P=hPfaveOL+^K>M_a7Y^>Tj>@~ zFy!jsO7gpOTm#u``a6aw9YP|{VdPIODU2X|gb|@qxB&Nhl^_3b5FFQSPG5S3L2Uph2hJJd-)8+#tB4jde4fdSj3&wi$y;uDK+Fb?UQ48xYDESprz!qxaKZ2h*#70EQrI2m%;lC$)ueh{lPQUk>8_4jNhayZRmx;E%tshtPxWJL+Y+13r z6BWm$28iV~oy#L5qh=*?Upar84V>T!@WqpIum-8jV)p^S5_#u(wrAARwP@uzQ+bvL_!X4omyM@m9qxYKPTyYmAqQcR{b`K=LoOaDX6 zo`M9{d9X)fI|#|t*I~3H_Htc)+QJKP4CV;pQ+OU47mfUxoFxM*@ddc|4Yyx$sz$HI<@lGIZ7()X>_xbp zhEYO!;2{*bKV{YQJ^&I7jQD;5p7mZg`;nnh=9w}KC2>ND z*2W&u3^NgGxPWB#;zZ3|l59K9U>;+|ER{$pt^AQKXrapalIT$1C8bc08VIzwHJYsj z_+$pn;g5kwLc|-F-_>BN2{?ToA9Zac-lHoF$0sF7zqufnD4K@zb6tHd(pn4~R>Zgd z6P{V)Y~q!BqE?MLzRUVq%SaxP; z41(CjNcHq_TKFTl` zfnT`Ahd3O%ZrW9s>l{%{oVOhLkl#4_^KBPCvEOBjI;Vee-08pVE2jcW^>`G_XD%GB zwo9&lgX`y{NNTf!5tZw*(Mq|$G;I7^J~k~O~7k{j#96@`dOH z#{+`$bAcNI?>Qux9uA@RBCCeC)^J98@Y^d9$`=So7u|S?iS6zo>RA1OF}%XkW?rqA z#X$T>u~UZF{Cllo{(Xx(w;gm=#j19FlAFRWx)ZDksErC&mFs)`OhfZ)$|&PJyJy}{ zOu|X9lEhHYk|bPU`a61FXXvj8tU;=o)%ps;l!t$r`SRy>{KEj6?bQ0Dn`o5G>afGo zCK5;FUlJ>pWH+{+D&X4ORPp{0#q|37aeD3gs6)>b$tltPU_deLBhr*#tTKs{%9$uo zV0$G-QOF@^??VR>`(8UDr$NLKDF!Wd!ec4fVdqT|aT+%}G5Q*6iN$^d`KuB&uLrge zTwcc;x+pr@YgS)HNeG~Mj3&2Z2@N#7WvY^OHkfa|Qjonp)?bcVs49Tvqx|&gf^!w4 z$LBTC8v7C&l0iCmB7_ian^lNV$7b5G0?#3M(_f+wZRYG%z$R2Sv8WBTeUv8=l6A zao7@Ae%m-jHq?0eW`j5CC$7;@p$h^R(kHjD9)--K?9E2kLZkXP)g+l4R@&j+>e83e z=eSVAU=FLxr)>owfGg_U<*V3EC)4bURpmnmQPS-PC*K!y`S9Npx-vXc^K{aSOF#N9 zzz%4{nojb4IZ4WHQ^gm|Zl_#!J0MjkfC29~?!$qgY*&Av?^8}lJq)7k&CcNwiTmnD zp*u6)lKiXqRL#pk;rT>}$Pmo8@AymJ10UMA;_N02KPkNOEBrBdKQ9E`zW@)w4|?iT zd}bcfU4WdTO(hT6i`~7o6*`cUSkX`17Z3V98Nw|48)m(u5Ou@@HSI`!6n7J#pk$>S zCd;Y^AeN~TXVAf3T4U}D#1PKx=^ZKSwfO0%Ap<0a{$PCfG?ybg3O?ueEeENz*-O!I zt+03bR$t!?BM)6$HrAVQ{6!cG@&I?F@NtRZd`ieh9%54$@@u=bIjTk~JNftPtCM+@ zEc{>0Hr3^ZGMK-9%5*L)JI=>m)?E#l*BZklT7#$J=rLtMV`am!^-S`BkW!jk+@xTB zN8YaEe8`6xvj-L5HE@rYfgtm#&RW!E)uS@%?Cac@he$P8ofWkcjmpgC$UjPW=F-7d z#025i=yXIj_nI)(ueS{J-9cRVJe7&2xrO-?~*WGJkdPO+-~MD+v~xNX_yS|Ok(sR)JY?%{lQ~CMF zRn&fYM6q8!+baxu(QiB=kIhxV3p>}|ICj6pwES`0QH9@D;O7!+ad= zEKU?(dVUUmE*k-6a`Xf!niSvt;I0kg3kL#LHJQkuUglX8ZjUMyzVi&vne0 zNiplpLzz#YW2~KRQZAv#V2RYCDGT!9h1#tNo?M$}TASNseY{SGe(&|KqpRrcq#cMS z(@z{Ce}byV;al8AII& zVbK=oC^kfP%XI~J>QUk#MV#)Z3|4*4o@#zCFwUZlSt-362r!#&obg!jY4O$R0k$2q<>l@c}?s|C%1RLW8{QP zuqL3`;Xae8+^sIDm|A4`;5)AHt-@M(@S#obS=A=y*) z<f2PaH6Q9i(HWvf}Dn_WtcDBlV}tTNigQ z-CnOq!B5w(i)4z=JPNv8+q!%M3hf4L8hW9{6WdSyn0e~LBCQ{Z>>Ndo8(Od8b+af$ zS8)JC%aH^;*drRd3>q*0jMDdf+tx%JDKrODoJ`S!rZ-Ra$0sv;N`YT*@LqzFo`pmV zqvw9XHAr;jAK4~=;lo4d3R7@^`Gm}<&#)6X1v1so&3@b<6{+53bDfvF6APv-G%obR z&!s#V*JX-|ebV#$qrG~~>A}cRl9gVTM~ju@cZYM}r@CW1sK_f*t!--y+j5+mAh%4g z^G$p_3J<1cWUu&P;zSyX(?*hP$W;Y@Nrugbp|?M69T=3n$3S@jT$K#td@SzUl#NePK%L6~#CLb$xw^u#62+0+4 zqE$<+qUDDWriBjSanN(crlX4AG(u{x4KVbMC@K?Vy)i;^4ycPgJvLP}don|PRa)2? zM31#hUFfe2`f!G|_vBr+;DJ=WkhUM+d*M-z87jBvdFuM&u#3DBx%%8HiJ#@_e{>rp zzQ#Wxe6_F*ZUi$B>0QrGW9h+b%^Y_`C;E(MtJ9L`lP}n+1m)?pNa%%a=JYFz2*|gU zQQ?W5d5owOXvuM~50~&vg}6K)0nrvQR$Sz3-r`J83<-9@ zP&(rDD87FCCM?QVL29tHu#vcBp@d*lfy^kyhr|;E%h7dUMY^ZFL#Jm{S>e+46_xbU z?eG97{#tz`3Nn67s@rK`zf49(y#=i349j5VHJxAblx53rwyomrT3IbEJ(s5+1#q3S zDCEX$5U)`K3i{?NH{M!9;?&W3i2CV%B_njrz2fe|Te@W`HB_JmhrgzjatOO3G5u^! zkd&YH?9U?TLqfpbjfP$y#DQv?-N7F5%e*3n(o8rua zuaZnd8wm1XW2!SB{3ew95?;Vi#LxU@#HW0MfjEGPW%DOqO}vJsZRvoMbncUw@nvm| zMvg%;EIcNkaGrjH4_m5q#CXUhx{lvmy+E(a_bj&bez@Gtte`n4DhB8sv(>b0HxY`Q zA-&ocTgTr#J}wJE-0U4=vh*yeY}jmpI)vU#c}x?n=Pz+Pj3@YA7e(r2z+Sxq<%NGKTB0Yei}7 zSN-FrI!r}z?163TPq)uBQ43zh{U3P)vv>CL2ffgxVG_1f-D7by&Dz*eZkkk;W~2N; zcZw3CD2m8aja?0DRk-+2qh2)q>^U&s-SkI?%EU}?4&Zo_!(P1&%eN55*hTW|_n-_j zj<#`M1#n>sMix*k-}F(rQEItJ1e14&Kh?X4tQo~f78bCT&?xO$ja!`lrdM3YqjXXd z{qjwbtcWtqTZhYe9S@%5^*8PhNk|@*I-ps#2OXl=OX>IhuOs=3W2iyn?V~zk8zS1i zGiWaqbg32k2OoFnRzwqlU@d1#4~?ke&jAV(Zd(02FxwcJN$EqI|DOmd_83h!Sqsv zGF-@zp~y^MObj*L^XmsGna19nDD-3FTq)=|+eldURHnw76r=n<#4=7O2igA9JAkwl zD+m-?RVxC0p}+nHO#E#N5T+K|AKT~<7HXOG9HY@c@lkzq30g}qB&`hONaR1!PZ6LC`)i5p5KYSZ?X3gNaPf)t`{7f zm+F3s@IxDcHmS8Br6LGWO)d5Nfs#X4dz4JG^7)rUz_&nRkJi%_%rB2~eCttG*h8An zVjdO6W^#)6*oM}~3tEtHNT+fj(VxtugUrc=U$5m)v8NA)=CE45@ zg0+~~eAVSA+o5@ejvr?;g8t0@ zsa}Ihk_iF=`lz<&`5xDa%VVJwFlg4kcJ=XF326we+u8Ugr1&YP;`H;@d(UVdZ_v^$ z3Pu4g3+p(NUw-t#IZr{!ya&-6`C@)j9%3QG zCuFBIwgyklr(Xr6p$!E&>3J$d8EWM&*m9t2V%6>fij<}--(RN)hn1A6m4eRXMjEpd zd>{<;Vlro|^SFGav~}3~z2W5yY}?G0+J-6?`SU(1#P7zjsX0l@y(y!@X-V^LH$4PO z?kB*hEh4c$ItkxZf)Nx)7_S4xKRTxjeXE+HWmyCFj}{Q5`#s$ha$q&2rc`yvjjd-& zJ;$%SbTl9pd88Ga3}<9%d=;C+XX+C%_)yj7F)S}yg6Fl{wkS4r!URm8MBmd zF6$OT-3Ri&C_=oJ_c971iZwH$u(7{YqabQ_pS$%p?+*$LDsi~}2HuAe?>#+;gexMT z>U5rCl^d$%$zaMA%Zl{qq7_NJ*Plt>Y@?8HN(w@DAE#o`q9_+iMK;q zK1J7cb~MZLpmN+MG{d?kgc_g@erY{Lqn6~zY9o+DwYc(hTr<9$M^UC~BF`GwpQrRF zYn$5-IJo&u&*41BExYW&94H8f?qz;vg0(Fnj05JO4(gIVakO{r{N7!kd;UK0=C;sx zJ*sceb|DY`8=TxTL!-t+fNV5`_G6$dJ_btuzXSCbGACrhA=RNh#-r)U0>6JoM-~$0=NU162(`?dGH{D(TTf*C|Y6>f3$&osx!}Tp(Q!cD*?q;FdQ2?%!`uoD3kx9 z;_IH=PU==Wwd%|sG_Fvth{#5Fu-ats>@|*TV&_)5vVG)P6obb!PAL+!8+x2K;0&}! zc*SgT`2%S7stKWGu;D{BJ`U2nbkV@ZaOX+-ec zW2}~-Q&omGgh(GYD@eo#t78=Ys}mHaf9I~hjnF=&!ptAQCW`Pmb0lNoo1sk0;b|8i z`G|9K7hC7euWA~gLjjOsiBz%}lnn3XZR;knk?Q!tzK=3hlnR~q`!bmj53+r;v9=Eu zzU(P*;l!b;FIV|7I*l;7dka34Q40uCU!^$KC$`u62vU*8`tmYbc&R8+$E&^wbL90I z3MeD9CP`7nm5P6nPvf2%?nDq{Q3%9iHbOIHi{2BRN(zBO!evQp#eN0#5J3qO8c~{8 ztT>y~w_s_quc$IGSwDJNvP)4yoc}yHv#~R%bo!C%?7u{kzR~WkMs+DJ2nfK&k+2=y zdUPF&-c=?d$<5{#O%uatvS}B=^jS&Kh2ijZa-IXAPL7UYh7mH=66n-agO5M8uwq3t z@3&-KN@n$aB_W%}^Hb*}G-q1X!U?JcRH=Vb<2#dHQf{O&8nO`Ds%3X|s)UO?0rATv z95OG|?WsagXaoaTplY*aaDb!Wz@xhLw}UFWYWjk4r@EDTzYi$CvgCjzUZDkVFhs@Sz|2~H#GCV z8HI&*6AhswZ*n76U!sAM>!jjh`1k&NGZoZlJoS&siz4k8V=-P(jNZ=Y77J!{FhGmx zgqZ$%q$Os)O`W!bSf-HP1mfW_`5c$F-C(JHsW0`pW;k+Gt1K?2OoLG?jbz{L;;2U9 zaX$ekOTLM0%H*Orv_ZlB1@DutCy*Z_lLnsX9q9$8j7#*#S@T;tHB%*%R$X|Nz)wAm z_=7%84762|&TN{HfK?;^U0PVt39E=y_ec}L&Q!7Lnh;8EDyV1YnyZrP7NWkL4Q#Cd zML<226Shk^QbORlodeZSm`TxvbKp}+fU&LoTvHVBmLiqYIG+^nPVx%vGyo`mz$loO zP$o7t8z|@;b2^IO{}yT>N$g68J@Vke@kE!&H(dXg_(uW%T>yki?-YPpJo=@8>qG~f z;ta``n_MZZ0R;K~Cy z?LzS|DcwyEn^ufRUlA3NITld|j0l}8O&w_gnYn`m+L_FKrH};`eCvtTpZ9NaXW^$S zCuDDHqfaLvXYkJJq+96y@anTpV>xVZuQbt0r5&Y~6c{^-^oZvQCwIBM2IK2++yltS zd;{(@Z!=RN4lEO$$U`UTzcO!c*cQEkWYrC5?6<93m`jO*3zuPDt^#TTg^ zNhyEO`F!grkGN{Jb)d&t5V$o(t8Pnz@yyUxtq=A(s`GrFqPt{!y)rQkueh4*bFDKY zf+qG2mE7rE`5eQ@Lmww8rDJq^5jjJfb^Tn?pUuP(`I~}w0E;CTCs?((fmd1+Rsz2w z%-X(nGZ>$h|M;AU{}+S26Z%OaBy}GvK1}Z3timDpQZbVnB`4dgm~2hCrnYFe>TYf1 z&A3#GeKe1q^LOXcb$@G)ck&SroH4zXicumD2lZwjBe!)*gQ1wMf@;Ctk?INx*6)2C z8V!CbU}Rqu0;Y6T219$kTl?MAe!mg3N|jrc*vq$W0EHl112=dh_{=AjD{c=>yprOA z1=CfDh|T*uRqSb>6yO58hK#vVP(wvJwD#SoE&{ZC<XI~(BnOg<# zV~oDbvV`YPWM_EGN;>Y!yR)OCMXtTTS;0A6Ge2Z+{N( zeE6Db8DU_EaCvV*D?=@&UwG31Kd+ZJx6i742y3E3Z2ca0e!m~GD6_5d%SHUa*etEg zc2$qNd#ZyAT;Idgt<}kwQJsvww2cE$nq!ydM zXRoVKHM%3eVt+m}ZKn($&SU{Yp;|reG4OhZ^F&Tw6e&EXA4TqhMo7)IBquUSz$Y`j z7h^GCJ=}p=PFIYq`)f{_3*``94gG8C_!SI5qWxQsK5&cL5CBk-0T2)5dZuD3fVua> zr1@2IBpe26038pM2IzuE0}AdTqcdEO%^&%nWJD_L)M+G9<`dCpH}bLpnF%l?LlG;l z$ey31mDqZ#MZ085rz)?QcEPf#%=%@|QDP?z(%YSM>bR=BRfM_1YMT z=8D{%ZQC(TO1?Z`O|gI-ikAuPy3v4i@r-Vd!^08^k%Yc!o>b6wxfMW4lgPW(z6E$SmV&?w0H z6=|Ch^zAb6M@#@%KF#&U>4Qk^W%@G2vgx2lrWmui#}1z)1Y)fpp>dJHpOKBr;GNfk zP3DO&1$hg9|fJXZgzbiy=W$*P6N{+~7=1Pl4d4X{chzlx`N~JgBYam$;!RO z0Dw{0X2+2E!cY3jELT5@MX){pl?UA_vH?K?y4ZL_>#I>Q!?!^i^lyCke*|L1SnqW*GkPmWia0P~0LlEK;U&~{d0WzK2%4r)WOZ&R( z14>ge*SE6er{c(AQp@;oX*D7Dh`wahb#K{`3$|twX*%Mh`iMOM$+J?8;~Q1^a)vJT zlqe}rC$u@%tA~d4^jOhXZ?)cn7|gaH+{Q}!jaO-8r@V*vhkmlA2uHweUSyEE~bIA>NK#lW6#PZSBmCXy_U zBp7P|_;Z_`obe}$H6DDkH)X$4U4$00uKrjjpmG#D@nVoRmzvBUosxN%I!ya%khe4klNPYZ zY7Q}@YL6eks6eVR-+ZX;i`}srmgvB@q_}>tU`$Xk3wLyB#4IWjwn?0LnujQ4a@%iH zfBpi=Z^o}?Yp=Lg49@3YeEPG{qkW9cYvRmqeZr{|<_W2WKxX_Uc2 zVx9@%q*R_n`pY2L>VZ+2_Z9wp=wrKFxI8&5_e9q|8Ziil`U8<&g>sl|>KOo}nh#X{ zaM>sVjDkQvg|*<{yZ^P%FhuG8fA58;e_BDN#RC-pxVQs=C}(L4HVa@!2|`=~1w@yT zIS3E0j*_p8M$d6=Tnjh#C#f24oxiZIzSWhyD#A^IZ?#)UBNrYSZ&#JJ6arumWWQc; zboUtrfSdjegk4;PP*0Vd_?7RRnxr47rwECVGe<@)l(qLMIlmA;FOc7ToROM_b)FK5 zEj_zF9ZVV}D&fkChB#v`aojTYl1DOLbTWY~ZvYa6eK5oA_vS&z~d<2uthV7?hXu6EvZt!7w-dSfK8AbF4?mG0QBFTh5vE; z|8oB0S_sGoX#4?0Ys0_q5HA%m8ajMP8R z#eiwy_YmPwu;KE}-U8kjbxKqs1?OymTrzgvJ7%Ys|JyUS1f4D@dsW3Pv%gkeL&~~a z;<}g(Ugf+4mn-rc6N$}Z7; zjMiT8uX%q4C-bS2(pXc)9QYxMM}Up^gT9Rq`l1*9L*M^5ZP4L=2?B{<{4ebwdH-DE z!`D6sA8ZmzcRU~8XbDf4_9q1=A`|WW%Eh zKTJn8*D&M1Kg?_j!`C8kWld*u!j{yevLyhxJxJk(oK7PqW=i9;+DVuSosCa0k>qpH`&r3d`I|Z<_A0K-{m*LSYM7(N&W+~+30{Em>t}HtO6JoJXL9)L* zxwbxz0lnT9r@BtVAI+s8#i_7V5;kfV!k0D6SV`-Qr`~%;g7{5~p0TNY>yzpP_T#$I z;L|C6E3{`eiQcc6$Fm+!7jfxz{1Ke3&DN-k}Xn;B=|kgKhf5RHC8u-#_o$o5C-OW&GOl&MJ&WL@(vcZa^**xj&m@Y1zw zyWThVKdX#JQK1?o>Q}-_Jcqg+cdHbH8}i?(Wq!)aQ|%ixqiS*#uv}d~z%jUH=hm^2z;5))q8Zo8 zXyOhxaut7dUc%s3k=v8SBSRJnc0jQ6p!yx>Fl5tYyyMJ#TN6rn6Q7A7;`#u7?fWaS z#F zC$7NzpA5WfC}{&W!qYPKkFd&bAgwMyph6@`r&g491RI+!Ypz9ae#{PlhOgnu#rvX` zS=}3YL=9%q)PAuQ)!v@*)BL+7j)&lbd&99TGt9mxvrZQemJSusY5=L5gj<=s*Qx1` zOPz8w-ECriKVHdNF;~wdulA$6swSkUCD@*e&av>m=t&gSj6X0b(eW zBXoKD;i3NkwwqQ!TZA6qr~^A+1SmU1{e!$0`h;c=WjCXsGl z#vf}74caaR#(p=&%;ATSorCUTqm)=u$GCBhm@Hgq0H(nYCnZDpR&T12n9nMOmqv=q ztLk22vytt1R;{z{-+%k&b0t;2Ya~b#X;McQhA2dnV~f}RW+`O*GfrR4VuWpC5Y!|- z#MKHHiOv0XkQI}{Cy3$}5Gzfn{cN`z9~2tMNC5J|S>OUBM{4r)f7lE1)Ch1t_ya(i z%@vJ5!K$#QBB*-NU*>@YR;?9@d>8@{yRcNC@?bQTyMG_U0pN)7e=oqnek;+quuJ`% zjoPQj0+D(M`gP#|yN@%m$ zg(_#~Ia~G#nq7WjPUyr<6~k?Uq>x0MBn&vM-u@uTo>s^zY{UGV32J057WNEoKk3|i zOrH-Q3Gn0r0O-eRM~15U@4WKQ!~%%@-v!TH6&C?HQ|;kD-Tp5bA5jq+$+zt{|4;?} z^zjw{q0N78nk)m^!SIvii36o~@#FD&Tfg9y#DK{b#S5M z!K+Yjf_#mh;?Pw!pBPYd1OGnsevAV(xZD!=`JD0gtcr_2O;*TgfTkBg$r|}WnsDFc z7%(5HH{NiAghkj>ltyR1Z8@vQg$ApK`4c~kr46I)Ku_OX=4C(9nHy=*QRCi5xC){W)gO;n zWlpNe-CkH}hQ0`S+a(?N1)4tCc2HN8&?igxS5LWPuqU$XtM}oH`5xk@saPU5qyWFW z-w6u1ag=pb=o&@KojOsp97xe^4*546)sXnA&w@Vd+WKNdUxP%j(48yP$96RZbNzV- zgw}=MtBy|PibQ>UrM)-1rgy1p_%K0<0Z5CGQ`$hMktx`tab27 zFh5zQDu^+o_lwK39h^xt zL1IxaY$+N!f;UCsJUM5fpUEA9{)NcsZxqUbJfW%rE^AdKkwrFBzp)q>V$b=IBUFmh z;X6>(bt%6T;5qh!$j*IOEg)G!Im%VC|K2V>8s;_l#{m16Bq1I>2TJ%r6B~>^{}mo+ zY(`{{pr?*q@Cma0W6Hda@ku5ual?$A z%sP>tzK?D5cnRE#PI#BklAJry5qiM7XvW@rLG)BR*>20eLIH%_*_QmNzXk0E+!856 zYhW!;A!R({5jpam_0CMZJ|IC=OE>^Bv^sY>^dY zRdzGBiBIV|XyXN==YuiQK<@9%e%C>Of)7`kc zySuvuhv4o3g1ZH`V8MdBySsY`E&&oCSdbvWEkJ+(0rGc7?wy%8_1>+YqPq4ur>kp! zd)c?vmctx&@I@h8;n{{DO~d-g({(&0-0l>oeeLx^Ke+&$C zj|@+qSwwP*#Tx>;k+iMTVc0$ZNico<{Y)>+XrQ;v8n_s3dMv9>+fi$VVwpRQ-sl_G z=A}mbb8V>*PvtLer(?LyO%nBr*qkwuKptr4L=4M7QINV=Xa{f*e71fviCv3-*1hDb zu+08G$nOcaA{8TLULX_mdvMUFukc0v@dyt`c*C#9qwcHJ(spNNv;}9(mFXya6&X%} zCuTViO{lF2K_SNcPZ0k_(x8%iV%?9_DhmDs_->DZMmQ}D1MbM0 z>t)7>Fg$Llt>^P-!gyD{J$@fCk~s3+bqcn*G|7;O?2^#dF_Ec&SVz@2dNj=W#BV4N zByPV$EM5h`@Nws}b0-;2Vwj9B#Z(@(zYm4*g}>R?T@DV7D!66F!Zk+BIN7e~VHK0# z{NOl`??r(@6B+vSJ&W?Ce-*~@kOI1wP`F-piATKc0HH@g?dH+x^u- z-3gH)Ut2m}P-&rUu)uEq z7TpCYYNk|V?4Oe;Ulcg{EsR9oST?%7H3`_-nn~}y@JWgg(h-pb5b=}k=pBAq(*E$A zi0Akq1dE+A;p%-Bh=VbYbb8bFU~#!oqUiJ4wu+S(oP_mcy+GtPPVem}#o3Ox$2~(% z;P{nKzkv?O@&7a+2sBVv@^_sg*R&H~8o%I! znM*^<5$6b4*ag6Vm)c=GQho{pse<_Xl&-5c?X0(vh{=5G-+K^iVEDA{;>NXLDJfl6 z4=}L}U7uv(M>!RJCx*09S1k~Bq6``<85Ffn8FQWmVuzEU(vyemh`AAHobfxYr5CC0 zLkVB$*eXid0aDRr*#_)36hJ>H&k*JR4gjC)kB-NQbQ)7h{T&4cHkj9-E(afZ1N?@i z#sWYBZ49nhAl;Zn(8S1^FVbP;W>ezCZpijtbg5fV7s}(ckErfw1sCdE2U;_j!O&;Q z$O*nZN+Jp?5L7eg`&r_E;mw2f5q2Y!!J`qn&UHnYIq~w`h>)|8yezS{kP6I;1|vW> zM14)nAGuySfdo_rLFw5Oi7dm&so&_?@B9qL1ne_4_^TkD87pKrPsGjC)s+Et#1Mdh ziMLIenbnwfYCqqWmx}RZ$C-eTvaOya({!3qC0c$c#4}bL?8z7k_lJA?3tY0k3IO(p zh6@HftP8~9Q?Jo)&rsh);2LQhU@^AFg1|^lQ4BCMC$9tBBz9nCjoCPRmyk!Uk4S?6 zy`)9cw5b=Jen?5Mz3XEyt*+Uhw5_vRS>NYbemhh4jY3;>`(6-iF<$ zu!(>ehrBrr<_c2VjZMc}ti>-XSm0|`cP>jy#Y->;{YWXq?E~!v0DMoHv_qQ3ClB4!Sq7&QnUaXs?1`7^f&M zpH_?_rx|Hl-PR5{Z^$9qUF7VpjeeW{WM#w< zWnR4Xc+8k8XlUqqI@PjR|6sX<53{T=LwBV+0B)3=V`{Clu5ko?!?B-5&3K(0m(;iB zoar1ZrIPWDC!PE`usIWvEFL2)e3RPejQ5SRnKpE_YhCaum9S5hq@%b*lA>~Xf4~$} zg}f#5%$1Bx0F2RHoecmWGzB2R#VP6u8}8(R`!DT{D`N0-ea$}A&L;?{6vDM@$xLYp z%&ZL=Zw5c}P3y4$0OTtK&s|H7?MYuy0e~WvtRCxhLc&(CuVc^|Zkb7{@m}or) zi?qfXH8qfF*y^Z5*6B*Xp&AkFg)3dXoW`qWL21v<} zlDE0pdPV8p0lP;HFx`0yF}umkpLo&FC${?qayP&_ZI>C)BC_@p(Lde=&G7VF>bGnX zRATb*R@%B4ITS-!Zxx^!5m#>JclEu$qhD8wVoP5WzFKlEnaxpf zhC@&{d>^Tw1ZsV{k_=FgX{%ooE;0Ts@~^2Wmro~70FV-(?MBv$c^g%2Ckdw_rP1y$WtIi{5$l@NxfLY1(w^_jcd z8#wNw^m?b8QgQGkT*k{p%0T`id(Ud?c-tcZ(hXcl*J@yU3f~%x;!3A<BE_9^CLp7xC}1FIcx+TmorWIX+I3or2q)p}WV7QwwfXZ3*s=jYc`u4*6^HG?&Y zKis0-RM<^@$eo^>&IlamUy-7=Zl3o2AkRN{85s%3+fU6)t37#@^?H9@Pw>53#SbUM z&gi+P-Q(?#-(|9tZGxl)YZ=LjKWN{$##-w4C2&&544@;bOEwz6gce6f@7-D~Ho{iZ z+KUHJ+SC@PL0-_PiVn)Ncd+;~s{YE9$r{q60VKxE+qNT`paC}e5$Gh}^B8N`nji?{ zhgjLj)I=8Y0@x6rn1mgVg%?hlSmG@KoMe z7((tpkm?$IR9(AQ`+K;n*3i-hh(@OD+x3T}F=~$Q~j2%f?SR^)J|AFdpEN_>bP3?@XMQzM5{4Zk$Ki zb*-JzeR_K^{U&{|@eBKQ(odV>tDjt*E^KrD>U3XRVLEwXdw#&sFl5E&^!jrRGYJ7J zh4fmU`4ftbk7jYIlM!mS9MkA$P;;D>$Z}vf`Q4-c?$RNE?9YFcb2*<~VD$a+!K#w} zQ$BY|Y|3KLXaHM2{THA8XT(K|UL!(Q=Ch*$C4gW>MBV|(ku8TvW3?kq_h=+@q$MLaT~tX`c^6Zk^qa3`mqd7^TVhJZz3qNBdgWLjKYKD zA!=*cV%VfH;iZ{N>68!chW(|p%GWnY^A%tcq((cz0lZu%<}LNeCKVKIcBYL>LnhiRC7b%H32m>f)Imwf6?>faH9^k%j{4mZ~RwylI96^PfEHEo-Z&SXUWJk89IpEg6vqTjZ2o5-p zYd_Hm3TL#zIg&BZ{)te(yu2-c=lyxb30>2fKO;t<4QyIMOnvqm8Tn0grOkDQ>m~8% zM%bhT{8<1IC)&%K@wODo&x9?Gp}SqG-@`7e*DSlU$7mB5ejHtgm+&QX2KqNev1JHT zc5?N>u}qA{Bsis>DFn6j@(DUn*DQT-N)IJuTjm+@Fkn8sSyfn6aO44$!YrQwa#}c zFX0*}0|(eV^gTRnT?vg`aMq$%F$<8qZHs?KjTgPxWjA}JvP1)l3q*Ah6F`_*Gu|7f zxt{3ndf)AO5p8nXVk^y^FN;!jy^v69kNL_7@xx-cJ~%^4Ic&vLIEiV?ncGkmdEo3J93I-Zxjx)`d2XR1MXo-c-i+_*>P|Kcpnb; zDWhKuxJZPdRN*I5638!Ve;`cR$BM8+qV zQ1yMl8deJcgcmEc1-hMoPUE7p(Xa#=G2WsD&SlCL8+wRP{EXX)ytA{7L%~nIjIhW8 z9IC{oCD`nvYSn_C7gcY1NkB!;2FmlRvHNT7U^Z7wA4)Ljm}p&gL!_|;VhCXXfS&4e zbqE?5V$)aRwbAWP@nYz(o5Jer)sl1B{-EcIWCaZx9wKFKytP zTgK6{7hzteG}r}Sq9G01Xv?HFp6=(vdEeOS@2C zmp+$N(K8s&P`Q7(y`SUdQkeB@4NV0=wP)304YXH*b8Vit)@D25@a;s>f4a_L1T6Gz zw3I_fj0-wq$L@bd!(S=Ww51CGcoK|%n|HPeF<9C`008{p78lvXAjs!C4AuWeLy;YM zFcRoBQ|hsR4i~$4y9fVkE6(IFj^gV@9|Dva*FmI}QJG1(NtV|biPN8PHs*1tKH7M0 z1;P$-+WA>ContdD&z@~#NPoaMEv~eVFDv={aeDUE*|tPLpau-W_frjeY)M_zcA6y7 z#U=m=A8ghq3-{~@z~_aqdq#GOYBRXLJ$1m|6dQ&c^J8daa9&DdJHvf89*r8Usvccf zl;!B;Dm;h&7J?9nb{cIkW@*h}pv--o!?Nx{L4Np*(Nfk?xG?hN+7J8fq44ljuo21z zof$(5&=wn;J78}jJ$dD0_UhIxu{aZrtH}0a!oy}?^fLFn;4yU6ctCmnD1RHZ3FxT7 z`UZx)>y!#k$(zYOg%%B`b&V3BI?XhcRY&uJN5JNlG*CT#cLY7$Q6hh&A$p$K8zF-M zCM>8yOZ?sh%O3R(4V3qCv~!kqRfFccSF|i2lYZCBw;RE5-137TI)(cPm=jX+EnA!@0)h6)FiXq-!A`Ii-l8~*lZKnE=mL8rI)|H(Au zSE7dwq1@t6HUZ%G!T5anjeGp}-tP~^xPx#cj;?~3d&FWV`*KqHYs^=Pl;da6R#*k_ zm7cEx-XOrtkm0g3M;PBwQNUV11$`gW4Z7E*gRD%dzXb*3C*)LID1pm2lmE`nt1&?C zwCo@$N+P8g-*Bt|soBuyZN!scwgGc#-E&#&Nmg*9<>)z!G^KjoCvuX5FKWESc_Dy% z39KddL}>bRpYTE6r}C+H_Ws^Vv0BoWb-@H4#_{mTpN%A0Ps2G}9yEBmW+Gb2F-grz z2W$m6thI)5P5a|z^#i}3c(szO1Yr;YjuSQQ>~|(lL1@y`us=hOWgeoDM7Xn1Ppyp- z#9|M@j25k8WcMn%QQFRpd*8*fZflfU69SK;P$DJH@+kXy31~MlgkTt=-`d#~v=v=Z zTi4>;DC%qtmtqi3Bq%5nw&EQR;93EiE#hHR8Vg$WfrY9!F;O>F8>zz)B&kK^Y~mj8 zmA~$fECkhxirTb%$I#%lMA_2gjF@Y{7IO0z3(6FjHm8dhkivCRA2HWkQJ3m}QJT5F z!B^4_tEow>mbkU;n|XP??Du1SeE?TBTcdzDyDWdyjen#zY!DoWjM#_QZq7SN$MD zm5(laRiD&m{X1SbJJ5Jt;x>0I9R#8wd6W47l>GOQ59xxG&x*9BLhjzh{&eFUR-neA z_%K&3S(*P_mUjtvw%sP$^ByKJ#@u60Y zTc7#8eyAxe=ML!Zq8~@ZjR_&3lhn3VxSKn<2YxO3>aWnnr|P3bTB_B)D)sQHt(xTc z=_KN05A`XX*$+TM^Q=2z>HVl4J^%nqpu8BRztMs}2mPP^vik&$3c(Ut zu_J#*1;c-h3I_pb=_RPp)wloYIRv2g{@djrk1#$Pz`yb0nJ+-a&a4611TLNdDALf^ z4~HN}ab^L=UK#LihyF?-jB{M~tw9vE2ct$5AyFmP$=YgX5Sy+!o8bC-shsp$goQmv zuEA}7YQr`Cv7u}`bq}4d`hlk_DOOfjjlJD8XeI7j8v9Ke3@Z)g#Vdk+Cr$Gx6tG zu5kWN!vXZ>rJG`r1dswbyI#cTyI@jn=7l+1#sQ~}f>?t^u0sX`bRw&%I=<_-uUuD8 zQ?Vo|2xfHJSBQ_P_r`n1^u*5c zvQ5;})Hp_kWu3uAC*9t@b58|XpFq|KJ<2k6Im8YTcjv{oh0zOEO(HCq5rbl$fw^h- zO*ugzs!HI>>=W?jl z6j9Mn*iT=X`yk|+e5TD%b?Rs8UBg_$B+gd6AT^FHeyzz#~-GJ9+MC`q9 za~QCOsg)Uro>)_d#aSpP!`t7%KH@Gxi7*&dA}^K2zaW}4|0mcS{jHrV0PcN2>idt1 zK~!VP)}8uF5DHnKOYhwakes&Iem&GrNB{&DX+!kT8}ul1uK;-84!kp!r}CBxeK%6G z8^B)0^8H*v^gI~^UBGJ!$Ai!QlO6{Gb#nd*#cE#^rV9?X0IB*q4Q)lQzIh(Z3x36g z<}O`pFPsGg=S;HNRWegnxNp>L>#2n+pwG=ck-?9r$uF5eUz92LVd6$)qQ7 zdD~bqY&yK`+*`YNw$?E8Q!jF4d}$O?83o-Pl0U}KvDH{)c#^FOi24#QavYU2_J#C> z70jUNnci0^V#}T)m-fgp7L%73iGDZw=ED`<%YxxeP;!EuypW5PK1}eFGnPl2!{!23 z_u6T?H@nT&B!rrz6{`rllhg17yj8zc`_`3aN+bjsB^DwC@>`p9f2zW%Bu9CuGp$`( zApD6us!k1jEB_-cIB#1^dRoE!T;ibJ0=rG9)K>*11}z1g=v! zT42zYJbXVH`4p0-j&cjbXD5$z$Y7Um+`AUe)E56r zcllH9!&cJ{uN~2v%e{=IiCOMG&*cWP^t5}|PNEX|zQPCP=s}y>B7Px`GgBv0qYBFe z^pI!BEVqjQBCx#OOp0e;8%7Y^Y=X0?Nyo{Fk8d`x=_xyv?t70ze%S+zko_ z-WlTbuM0_W-T$Zz_`qn^NRtYtnWo+%K!SnPLYy`T0ICUIOXk2!xW5UKRw>w?7Rb>iw6TZErF~?vF;Gk@wW7jqs>A8I$#cK=%w80=q^ZuU^=`d6CdnOx zGK3AiKwZ2<#uNfdrD%*Iho;QGrrUFl|L-vW0K~Mx59o=L{v)p7%b?{W4@u&v(<6k& z6g#)>gjy}B0WkP(Ud90i0L@4-WyBLA*i*7mfkbvrjD$!-f;}Gk=DubN)3y1`gfEom zE}J-yvm{kRoi_2$SC{C;>s_#UWwe!4@)FY4dsG-26zLxrTgfn=05hNv(}6Ph%;+)m z*jl)+ETH@k?Phgg&!3XiOg0a%V%|JOd(*n zcBP_uv$bk!9#B0KqquiblzpeC@7VPS_aZ6tm3HZNGwEv z&Jivm_30w0f(hB05DM!(6qeGz#Q*;V7Io5VNXqxd)!@)P<*6Z#SnRa{JpdrCv0OM5 zP6LqYwfI8z)4sroGb0srHSAS$?J7Rjp2{s@<$)9X+H2+8LFTFUwm2*2dU*V=FYo1bUilGutuqi} zdNxOXx?&RF%7A1LiyO>B5kY5pa~=LCME{)S1$Bfe^NX*!Yq`%BAleb;S-&$h-|jAw zYlp7-V<``Py$w6^VhlpMsMd9VMb%jChdxx*VBBNkGXctyE2Es}k6Sb^4f#8e_W8S{>9&uhX zCLg!)mr4DA0{Gu38PUG(pq}aQNy9H)0}1~6gz&I#tfFc|9QmC__?J{Z!`=>A)pK3O zrhQ99iL5VZgrg(OF^zol1YW9&_^0x1%avG<4<@z5*sg0oX1_6#$`=kTv_eT)9o;s5;bLrMSLPWs?MVx3=|bd0Qp`L6UHXiDNNel2`EP7)vZoX>p46&D%DH z`o4CRu%-q}4a^mPq_ZdDS2ism7ttJ#+MjgpGWAk5IiGk6Jpx{J(g;Qihf}_}k2+`{ zn$O)zWaWkb3ti3pef4`fC8ixeOFXos{9hA%)Dpeh#>+-8=Lje!ic@hxNLv#f{i_rlzrJ&s>B7 z0IY!&SkPC_t+;F&7hIA>KW>Agd%}2DPKsb+Ull4M?GSlirY;}7p~sO44S8l3u8)Bq z>6R`jRQy4NE@Qfxo66$zz^Ku;7mc(_Laiua>=6-F#|3)#i(jwNUPsoqr zlE-lIO>Q64M%P49@-Co`@7#UU%97>Ars-ggD!8NW1$%wJ`$5X~LDTd;hN_;;0iD$( zxjKIrK}zP1dxW%KAtjDaU+bZqEq#bH`$qg_*t!>b!H2N%;HCIz4V*JkEt+y;?nLFK zAi%%eJaANO6VVXsC=D5#KMIc_(?=pGaZ@H;V1??-M5zWZzlDZQCaYYdywfXxBOSoIwcW z-a*wA6e^Kd_8U$7Bbh(zx8?Y+Yy-YddrERUH2#)9pHAJ@_t+FKN*~XkNv1)gQ=`b@1Du+kfp!v0aVlmh29;05@ z+yNf^*gEMJHe~+4+ zaKthu7c#p47TZVQw}mvd{}0ykPjUu6`$J9xP&xA3;|Lg^B-Y~@^F+0=+7@Fx?NxVk zaSj6cgKj870bs@&g-XMbV@4puR73c-aaI}TBb`Y#k!Z95rePwL!bPq-+npuT)wgHS zj1cscO)X)xG&d(3n&*}LjtR)Yy5sQGe9#aukQaZBOzl}t(gQwn-zkaQk1s0 zl@y{sF|QD^n$bg^iP2YJAn?ii>4+O$Wa{KA`;NUAr8?I$L(u~tF%q0uLZ5_mKU#qf z`0v+v=mQETEf%jL?sMdST;$K>_>BlW7Xf{PW=g5hZvUNeOrM|kn1VlNwG0sMqb2A&fpOfk zf8;ZipHa&8hX1oZ>)N$GH@fY*oO2hiLr(dz9Wp6&{g%ak2})+o$z_>fQdgBsb?<&b zu%DCSTFRWQahti`?WL2eQ|@|IX<@nVlXpVNC2Q@Z7Mj(X<|i1DGP%n4p3yXYX8s-; z!JUk1Mfrvw<=wjYLa;@;DZSP|qwU3g3Ak#T$`M4JpX(_hWBDV@R2p7|%NA%hmD^@QyO3rpkLA*RCm5pY>F(Um6<$X$?DQ33Fk`CTC3F zJNu0UCf6vXhL7~|;yJ2-UD7D2h*}FO7pwzPO|q};52o%Yyldg6?9Z;%IR~CTgp)1n zv+(4T96-`f3Iz!lCo zGcYl?W4)D^iq3{AfOoAsrv!<@C)1bcLr+#eEEws=USED7?c>%QEiE$_1?H{3=Z;{M z*ozyLa0*6GT#?j9SL8BS)xf=>?f`6FE3}idu+J`o8kZy6=(MS_A)JU1Q*?e?#&zjJi11 zGB>2k_bJQ1zi44N*3tG$xblIrZC7qpMAz(;*{(MbHGls&FHv##C1I7yvs6B@slA0@z0Yx{{%k1n_$>%o&8<1jBq) z;>OMk0zw9(C)$FF9aY+{W!WV{1hFI{h5GHEX`$98$a?Ba_|mY!z2~b%AhNIPb)ho; z#wmw^v1Aa0*eVm%MJ6)smdA$*!&N0;V_|U<_(FfBd3*9D#TR)ON8VPIdoaQtff_5E=Nx*fu7 zLcT`64>$I=TeiXXRoBfv>~|-%+KZc??&%a8@FKhyw%sj>#%7M5-!E&AxU%mO*XljO z{1}5CIxvZ$HmO8Cc@gy6?>*y4l+Vamtd3(yl*DIxis9u-wyc3C5^yBQ#V|FEl|YMp z^wgk~cX>$~ew}ey(@z-{DL*ED-XhKpA%fG2LNe!K%f_mAl$Cf*FL>qSgSM9F*P*bd zFb2#n`y83w6Cf5(JgPv6KI3I{Dzjlf2aC*-x?X}JErjyBduz*g%d9wUOa5mg9o8yu zUTn4dF&nUd>fMPY5o&jZ$=W8Hv1}?7!Zc(bfYU4y4aSiX-rEpn8ZWDf z9b=s%116j8Op5jL)2~+iw#|?Dc$GT$ggaY?B`CPPEEN7M$RwqK>dTsaAV%@xOR{|x zVs)z-;!KH%y^?~^tV4=XyWrBW0<9uq4Te~W7GL+)cY{p_9Zjj;Ma%J3!uVw& zcI)P^J^fin#}&+8XR@gdCF9IUDCF_!tYL9_GaOrT7(YL?kVz#1y@xOi^wAw>Uf;vj z@Ayv{((wOi8iQ_F0_98OwH^OnwE9g_|Jlxf((vmVJX$yj^##Nazb@YNfUJOlT>!vp za-K$@A>{{x37$^fzCeI630p*?+@r<;Xv+0P;b=It&^JJM$zDq`jLh;i!;Qw+pRdM@ zZu{FnyC_^tlCr_fMSEn;FA5W^>~Oz~@Fn1)T+q5BS615ds^KRp*NL4{_L~+JYP+yT zeatHN5>p`8CEVf3H;7qIfCKtofRG7t5zDRgG+$lU)8$w z>LcAJ0;m|-X+)}5h! zvaWvM%naA3>^Q&7t7M4IgdbpxvmtoHrB(d4tP(`-G{4iFuQxShDwiX5(~e*yAV}@K ziT79-$N6=cL!;h9K!S~unf5z234>yL{!c0_HoR8_@6uM7x7T7sI%V>h1v%%!s8<@H zPH7gD*IV;1WrzQikwB4?SZcpXPgXo5_!%($Tl>%40nI0fu9Y#cu^fR2FOeG9s^UyU zP88A-TNMXLta(4}zLKV>mZzi$j&4QLb9|~4lMeg+&Z?TTeFnw(&R?U#Lp)w=6bI=+ zFiP`aLERGi7LeD78XRR@pIB=GO$GE^FvhWH%oKDWx=mb>K`&jOfq7-??7qB1B%`BN zAheukdis>_b6jd&PSOt(dq7^U>08FI9dtbf&;>;``7fyc?Dl_iALxwAe=mN2%%RIB zp|Yd@I!57n6!NM)eCV%v3GjyyG0krk>>U8Ncp}~WE{31=hit8|;UbPLI{e%dT(yh- z+GZ2XL(?B9m()+bfSpn_kVO%xn5qU7->#2d!l~fSk4upU$td7LE$hAAG_BlOdW8-` z^aA%`&yS=7@tBINwBY+b5Hvvthk^3mqWmpG{T~>NlQtoue(?|Q`+DyI;m@NBEl|&D zr8lFOqNKW4HH*Im_*Dkz7|j;k=-4u>HmPM3vyi?5-eBSd?cMhT635+qah1@U3?aS~ zv5$Lh^928yCYn3a1zXV|w^B2%S$v8DtMIA}U%?@Rc3xkaX_{w6v5@d&Lxa2OeEd4` z4_q7pVw9w`ejCB_MU&bs7>@T>JE5$ug;N%#QJZ68NQxlm+vnyO^49R8BW~}Aztrq& zkLWKMH4D~~^ZtxU(Q%v-(df$2?HE~%&y*K4rKAvkYC7i1&{c}9hd}hA=ft>zc}G1t z?5(xsEwOs{+A?KSQsuzDKT(y=H-TOh&01L(N`krjBho&D#C<$_y)|mlSKLDjXxTH_ z-!N4+HVq?7UniM-NQmANm$Ej2U&R=TXW*!Au#$jzYO@9AiVSu_xb7f6(~MaAP*Vp^Vk=M^2_#|J`jXx_40D$(riOiW7Md2Mf#t1lDKyZKhHcD( zgnY$^zLJ;ANip)1h862UK+Kt@ve0qP#iADi0nWn@=V#rbfebfS!eBt!Cu)qNC?*rh zsqq7N`onM+(P@)*Ks+LstGkXqx@1SUA^l-~M1CRyhzdbbRN+&W)__l=!|OOSO19Mp z&4T&rw}TWRk&oCSbr9OFU4_yN)3a}VmO5`a>ROh@*S^laA1)4ndXptZtBqX^5bDx|;%38LURAlOA`feiyE%N<<43n+>)_&yO=mk`ov>7` znXLG6yAU$2%`YzzI%w@$Ta%W^j+t+|&ic%<{2W1XgUH$Hbs>1Xtnx`HAxBE-F3pj! z-`da6P$+-_D1g7G0{;hq-%36I2jlwPC18(_C9t2M1-aO0iApw@jjp$cB>;f=1j{x6 z_!hASAFQ~D^6fv*UahAyS<|{A3CkJ?x(J=`@N;+{KflAI^#&;|iHwJON6QboU2W2T z?@EC+_nUF#>DX+zEf)fjlY)IZb@%lG?@RLWXywYYAEf9TO8n-Vb;qy)+31&{%G0*d zP;U$RCXw}a_g~o7-!?UHdM~H}=zw9+9}<8u+W3nseuvFc*_TC8q>pJNZTphK?$L8~ zh5ZB}BqQHz1O%;d+1Lamb}g9A8lK8}*o<`UDUsbDXax)HtX_*p=d0&tg;*FGQ3^uz zNkk&y>6OE~Y*PgcI=uQVSNz#s-Z)3~f?@axLaKf)rcWF>pu89Yh--b#<=fAnZc@=s zBXHatc)vCvzaH(EFVAFz_dy1tGq`W_TLL0xRv}&+gFEPrtht#p6lm9blGV%4J|&!{ z=#>w_jSa_#o$BP0y-b|bY;j$Eg};lUmx@kTX}7%Ou+|pB6y*h^DtJ*dO zZp%?0#|2SuUZAqsrGuV! zlbC}yL1J&IZ?Z~-#Jflp`{ zvc@58c|SisoI|9kU#!Vsw;s=_AhIWR6I-9-jXql{L7&}Bk0^^s+|p)7$Y*RF)6WhH zvd&Zkw4SmE`zK{{459||3HhGHr6}8}vM8{w9o$W&tBiO_u@5Z$W&J)=1+W%Sv9n9$ zjn@1kPta1%ucKc;%6NYY7l6x#(%|2P3W0=`{AzO?T47xnqny2#ooirv(d6b1$D@<_JV84wQ_xwj9phDthq>feKm$D2FHU^R**-l zzG-#MYCxuvG_73_k9?4p_D51XxL;jVuG+?3EVRQ0uG^OsAB1mP7|->Z;qbN{;Z>w< zA>~j-q-6v&P5i!o7|dUM+bJi3-S}O2JrJci z2=6}>WXwL-b6_VlR$w*}bQ_&~mrRvt_C8MH={BZVAHdNEQ}0M4imB0GNZQVt02-*M z!(g%8q?b0e9(!AgEa*o}OVYY+dO0+U)K{uDOW9uyua{H~f66pB^YZvw%Yyt~c3UoF zjQ(^2^Har!gK1$R+#Sqe;e{B>+vh65eWQsdo_D+AHzdYmPtoCHI+-kF+_UT823Q$o zOxMqG4=*1~bns+Gwahk;9?Lz_aOO|V)IAyCYRl-RCe2~Lj%Np%9k5hZQ&^-H_uGfd zDX}~=iZAj~qj_&De~MhG_j$Nb1WCaI;l@Xd7RHRDknpwkP0m`>2jx6^?grdqrZiNX zQ5Zyj;|N%*x@fVtJ)Yjac%G)hn=H8xIo)%MeI*J}3@jzsNJbGX&-Ku~7(*x@2s)ly zXy?7MBX3!bs1Ne7W%68r^HRDbblw1?aq)ymX}Q1m&Kgm^GZBc>3b9bE;}z8uZYL3* zX!($jjWQva)^zufJEnfeqTwSLb=#FtF3xdtY{SJ?F#v3cPwI1X&BGPWz0$`TAz0$C zI|NW}2;_R=nZDZAuOw%*5S9hfCB2DNCKJ%msZvF5@8eL+4&uiO25S;-Opzo}CKI;1 z&FMa^KQ;nqe?d;s2$e2a%!`M7#1A^P40WT$YI{J^q+r>M70FgGdYudC~zM(Z-(|u-c8Ir%?EQr$su$}fLdH|5LU8U`BBotS_Z7>y&whIV z8x;g+189T#JuP-tkY3E$=?4?aE?zE(B1dFr06~OSEOg1CYPXSf>Bhbpehux>Q zU-zS7V}H*R>Iqf~TVJ^6J?EU*^YH5gxi;25-!N!k94($4A2C-xs~y z*QU10kvor;hL63%*&NqmAB|Ro(tsB^P6*T%g2yfvF=0~Fo%WKqc;=Df`VPKNzZy{( zW&S-k+&MoL^W0qKu!HhrEPeed&p<1kuN3#n6MJn0SR5_e+A@-`x0B7+#M`c6)r}I} zD`&OrP4=M?ps^Od19+`y(t36++P5iIny^3SocUS=rey6T%fi;agsyf@d5!q_LZWLg zq`tpOn7_hqY`h9aD6bjhBlHe}ir!5kZ~Cv(2Y-Z^--KG>{9oDX{XTtUjFNiZ5|(sH zPdBdyC>;EHPHG#=VPge=w7|W4?16bG4yV)lmIe7v+IHI7SqTKqI8KmRAGKXXWE)F5 zw3fOZlPqo^uL5L^k)$tUNZO6b1IXSzc**IpmhwBEwfR-v-%J|5q;bd4)$W_5UbVMq z!mI6PkTZFm9uc6>1~Y}x>7h*M^@LQ(OeNcpz==}h^`N^)x5B8DmZ8unBC$MCPHmb4Lry z^FF9|7y{)j{ac~^KRNjC)&%|hwZ;MXvn=?>T?8{y>h>gxLawX)`O1I7N!H*-MZ$$a6~0~~>l59-aO?k` zVEOAn7l*Os|8^5vyktIxkp8~e>_3tLdI7M^6ra9cIHwByCSw-9I@zb`=jOST3pL#_ zv@0_>8vwSTA+5CY4em$-j&;am5ZGQ25AXWDcW-%lJJc3#OzuO@2h^ga+ef}m5~Nfe z3*j&tif(K8PdXMyr~J?jQR-aV!gf=6cSlg_WLreCn;yP^gI_sYeA(yyp%eYsQj&_CFs)~* zl5^-5chtN54S0bucqj)$g#Uo~;k?St{bz6^O>#8Vi67Y^03ua1n+7*26l>J^Ghf1wy%r!_j zmX4XUT>Ooaie0#^$L?8KT!_m#wNu@WEj$jZTP3oS-5^Ja_wNbB-s=3 zq{a&5{NVy+14b%-J@x=BYA<=H$buyDHYWe%#cBXRq4OE~`KPC%Q`?Nn@52DsDg1Gd z=Q*?i3B`b5Y(o4$`jRA&`?zSug9ITc0D|7gugNwD&^peg2vD94R_?~R)M%vg0DP#^nTu8rlfENBv!W43m#!+bvpUk;Tk8p zdqi@^9!rM@=KQWUIX@A3Mp<#V+RP;phMB({(GYZ#Y9s?%3eYM(bkWHH}v zMp?v~?2x=h#2ndm*}_z~l)@Ex_*y1%N0E`Slj|cKg&N~_bre!3sFIHInp+9~$%fRC zE+CCrmVrv{VCIWd+OjZkFL5V8~&puGLR6Ybx}|1TcvpYxl)Bm@J^YkvEp zgBq)yqHk16E2XR=%0zbV4I*aE&>1+v=W2QkCC4+{$P{(gbxYHh=&MTH|utuEOh(=2iu3 z@!A7kEH{VN0-5l{-+Bp$Vge_-p*a9C#Auwa!Ntg0tpMq87rT{7sSxA|vj`W4Kk}m@ ztpb<}hRQY{Iw;5g!c~8l@LxVb2^IewCh+Q!hq^%X)XGb>GlXs3;b7ZQ_|VR)UtfE} zy8-}+>8$|LKKqvKkiHZcltl2N=rxE$*D(pPk9b_ahoKDf7{W((k+JgAw%f zlT#HWG)pcWcb)O0N|cZdfPoU)#ST#30m{F0@h^p`f3NGfiT~;f=n#?;2m5~UJXddV zdz=U|izAcRmH+@QM7PkRE42*nxxsWamIQ5rYiLB07O!)LHYyXCR`4LnB6H*h7TqfL z=vUr=ajGJVfKD|JkF5%M4zetUk)f{CBA8IpnW95TRE!bfMU3`Q7R>#L*Jw<0+{e6g`-s)deP{N-;1ZGlpeK|u03ngh}xHANO z?>;^%Zk}r>x<|R#tSU7KfE6o#XBf^#^^61h3*g%tW>RfN3=J^tdIfQbzF0nAcnC`v%$?=3lF*cw1iGdIo3%elH+o-MfOJ1iSzWJZ;~QS^HrBmz;AXRFnP!6TqF?HtX7lxFFw5e}|3D93W}IUA0W{7YH;({M6N7 zZp)BJv(iw1EdCr5rOt!;!zuw{c$3phlEG5(7b;hKn>MY<#!~NRIxC;>m*npt2TFKn z8DA#lx+Q$cWg%#$D_eTB4NqekuEY-ac{jN3e&Q>2FKj)sN5l?xaOoOck>a*t54RD0 z>xABb|8l!qRnb-3zH#aL6Z^s7N`JS%ro}!Jf%X>~HaR}&81)O*Z-=qey3lC}kcC9v zxx*i!>z6p8yMF&8)&GyOuZ)UwS=t@k-QC^YVQ_c1;O>FoGPt`0cZWc5C%C)21OfyL z79=EaC;Q0V`<(r)@7}fe(KGYTP+isibX9c;lug>dUqB>w{W0#_rGHF94YSNU%LD;* z!1YwbLx)s;e*!@(onX$dFKqU_&Ax2DZr)oWA$T+1*ehs@!OjM8c3Yg8OCM_V@r7Uw;?8ptDXIzGaGYb1+w7 z^E*?+n~*m{(zV|_Re3>nJVM`Ofy>EKCNfXlU2eUTL`zd0N5KT1kuk7H zMOd#=xe&?Fc5*H?$m1Tztt-6vwdD4Brw|lYEyME;utBX2jl)TuK(z49woysGlP;owpp_K z9zN3uy?l+$bvN)8+4R(lfb#9JHu|~NwmDa1a2@(*bUtw5r+D8@iUCOkZd%nkwotBD zz$be+cIDT3QwmQk&qiVxhuOd$uG9w^%Y45BG?r-nkpxqxvC;^|wZh!v5U;jiC_dZKePSS??9( zxnk%rv>(qggiX4Z`R`-ms~hU9(5E~5OeT?Ggd`QWF|9@RT~W{g{6{s5KJ`3UE+f2F z_X1StVuqAY=8j=Qwt&Rnr%nf0WVL@o;{OWi`e1>B=Yd*c<4nl~My@F@`X?MJcua+qWlWH z-Uh|9fBZjsOyJHhVdIxz{x~@i;QzS_|IPE?gY%(0Z4c@pH5(ESLsBpPAv0*4%@Dbk z)WM)HPvicH!=RHKD~5f*%@u&id*`XR-LU0LMu)9AMPM4=7NUy3gZkLVWMUi>vwU+2 z{3_Ct`hfxXnVQH35f+X>shgL}Ngl^j96NVnQ(10`1cT4p>PJ$|x0@`xs!){x6pNUk zI!QvVo|fm~>Wds)(;dOUf?+UziZwt1)K6cT3U2(i$^z>$FRg_eDuAoj4l`PEv)2j=rr3)hPJlXCi+R` zmrym5*a6)2UUjvedE|FafdghWA+fVn7|(C$ww2@ec;i+%`lq#-&t2=hOk;gRM@E-{ zQ{30)t%N&4_yRRg?|vf(L>WdY(xyKARV?-on31y92A&z+wc77eFHa37-GF zJ^se~LEbmUR=g{;Mv@DJSp94i2Y|E%kdq6U-T+|FqJ{iSKR%bnOGfV;=3Wkc>)1f{ zV-&@ti}A3x)*q^?c|V6;dH)$=E17Wfb`b8?gm!~Uk_}+o4xJ}b&41}*Uh;VYvn}TF zk}E9PX-AP$y_T=MQqh_T*Fi+ohFtguewgp*zSY_ul@pYn?wt=8B8wlt z`Xc++hB+D7g;bPW@sS}0BBgtM@9A>p2?{w7g@*F!)dPsZcRUc{IY_YosXzZsj(%|8?@*6~6}H(@HEXY5zR*=>!r9gzR=F;%6> zFrt!Aen@Tb7Ey)crY_zCa+d>nWX^?eh53XW^8E%()Q^vcne3*T5<6Bma{hwKnnOzp ztGU;l+;dLZK{VuW5kNo=c0p@fpj6>}RSU^!ml=R6;YmDMRtQb1^$b_2(o?yt(qjo> zjxT(g`3p_~6^~T7FBblyyZ%{7Mn)#QsdB|`;EK;}3V_D0IFu%+9Re!rX!H#h6%+@& z(|u0wQOH_glMjMpHo@}2nF}VuLKKm;;c$TG_if3krZ1MrGp@+r zYhCLnVc?3c@7bI2n$AjZ^f$->$4l?cNcw}fIvO4rQqht9bi`*;8;>BVZ$-BD56iIU zpst!`U>gJ*4_;b&VKA@d__9;D8}YQ3Bjoj6*(&7qK%V}!p0Bmr!&npT2ll$NaPXaE zV|5ok8NI!huoV;!ZH)X)Xb6MO0N>x83n0|R3ovW{gw%fxbElC0L-xOgjSG|XTj*$U z?o(A!u1qM*gRablir$;x2i|=`L9v`;honSENXx`niSj*eXm_}IXB$mDBug9HGU&^^ zPtB-fgqgBAdk3(VI$v16(Bf8Shfn|_aDT@d=APeVu2ju&RvQC%e?a_baQ!a8wH*Cf z7H(xZWBi$d?3Up0*9OgLlw8*(DiOjD52wRuvJJPkmc_Rg-lMu&Bic*MUz`wk)LW9U6)!>YmfTvoej{xiuY9zAc?NQ&PJ>agWzl9VGJS z?hl-^V|B;qAuwph{yFyyD@gt>iCpjOC64^m4gdf&LKG1GFHW6*ZlHf@&A*}hUporY zQomwuTaWx#Q?gedJNSM8s{(*bu9s#CfUGQf4}gdq8G?6ZTtSfpK5nXLcCK2(>Svx8 z^Dow@%_T1Rsb}L&3mIZJxk$-CG+wXikRDTqI+X6;r?I>pY#chp{w$r%bbw~1HG)Aj z3R*VZ_oK)nPKF=?Q=JE%^e`;H%j+_2|WKB0{QB^?xE&~0QQXg|pez(`j^MQjlSXZ_|dg8<~TI*!>!!B3OHWr|oQ zF8)Y+4@%Uu6L-l;>c`_rjA|?<3EyZ?hU35KMysn6kDMK$W^57w(~6NvS);Y(noZUA z%q)Y^m~O@UagQ<3Nx{_+!SN?KMCJc0;@S>9*pUBb-C!E%k5%yphs^i? z`1?(0`X78C0G9@u7o^9OU|AdGJXpE>lfl_MHR;CenGDDf1&k zE$8>R^U*!0uZq+~r0MOM=sDH$@aQ=5-rF(vQ`8Hm2ut`KK;G36hqGFuCPY#d!r~_r z3xpnFsxQShP?H}mzy(*(6a)>>IXE7UmDYj0JYw;`N;@)M+97qbTJrFQYW3Z>@UqD8W0zcUCv83 zLPwau7$G6mFmTztGTvAGB|t~BsN9bP2PVFW1fEIHfoaZa?rdWnr#pI{PUwdqUKJ{) zTHe9CQz-Njq)hv=_45P=1e(j+IAiy&D$er=ST9Yv5^IHGCUwWbCxiw~QtgHu?J>V| zJj&HRzKWQmVi++cNd%u#5}GRV01vKPF~}h-V0mKp4tBjbKhu=!mc%+%VnTFPP{9yp zC$9Ix&EzO-K_2uS7&IZo#S5sE{*1AIbymPt{vl=XHrpkX==(iJkXKNDg4vpLNhP@f z@OD506hT11WZXYi1DPt&;(HO9?T7Q$?vLAyVf8{lB;at0J?Kq7p|YRUf(N*LCof`&^)hCz+Sv;Z(@1;_P#jsEGd4Y7%vq|ol zQt%a-V(%oMq%m&i3k>HtnLwM{H`Xj4ejx^575$K2PtYxra}1$?;-0@b3FM4hdgoo( zV>_Ee=sTHYI1`X_w}9PF&Vqefb&!*5NF|lquUV>UX1mK?t+$1T7j_`iOki40IKP+Q zr|2#_C17-Rpx%?hCvlq%E(vCkMkUPB9zd9H2~h%r-XT@DVJcA9XYpA{B4thY)C>Rs z$5!++qG9PpparI23ACI##}PxL{3o7e*YoFF{<08r*-vW|pE%z(X&ocmPP zQ_&HEPFLxitD!wEDgSmpZv}qX`UqeMcS=qY2ArS(Z~sLCShD}qAN#ft8mv4xG)Whb^x8sJ2=;Oxmx7>nufD{P zadIaCATtsphYGD~k*B6N$9SI5PnfPzi7Yb|w82r5%!Gd1_IJd`A>IVP-eU^*psZpS zEsIqjm4mFn{~1sLCM@o62>YK<^WVu5|DqLwy0xkze%rke<^Uh!d@Kq8;6d#NuWN(e z_{=mpaPMKB8!orxb_@Nw&pa@%->vL9O}eO*;optRg)I4zF3Ei!=YVaj57Lt(<(2^M z;V>G$cEbV&+hmhfJ+;;aC}AO7mME#$`oS70sdx_a$baJF-)BRBt$#TGKiDY`1R$IK z2V)`P0EN6FQZk=>d4ohl(<9ov{p7^~?J4%iv6T}zR;x=qS`g?QGNKkb?~SO?78k(n zmha?R=kMtgst@P=V>GA9xHZ3mrmyIZp;I{#@SXk63lnAi-qde; zZLSdu)5C{TyfwQ6K)M|x@laemmO7?zOxzAzLHZRBU7k#~Y1um?0X25Y_av(NC2F}a z(GhfAV0cmECRn4I2JzIr%7%oHNtEP#Q?20uD%GmHwtnvkl((i+Ks6&;FVOvtEoFa` zYS=}B+8rBIJxl#1ALoNm94XK(8ONm3mkpL2!xYb}e$t+E&4QD!JrZ2IUW#{IBGIuV zahr<~!sy1Z<@7V-&mX*$fnE%r)=wTi?meKI;G_Utr5#D4x{YcYLJC!?cy?HFyEr=W+EU!PT%Q3IzVa#d9>NGag_ zw-5HMOY zLrF%p4l{}%L1shoOZi6948_4+WMvoHlI19v4A5x$35Y}2O)Np^g;G}~EP`8|oO2XU zvz`DH=aKeZ&&|Y=SKj#P%B2==8(9jBNV=`_?|JY3cFGCYjEB9APG9A^^2wtS5W0< zFblmM7L|jfpH!9IxjqDslw3gHcXYiqCW zhRn93cAzq5&&Su+pslH|fb`Uzk;W4>J%~sX`i2w5(J|6HCi@z+;?lT@sMf zsg$8YRgGg_bi99fN5&edB&57k86hI$%qNM&H2JGYB&n%a-$pGuWU2RCc_Jx_2wIzN z3Qr&JchFp8(PK3Z*##a3`<*<~Emwx@ZI#oHxU2dOn?p!4yvDa&ff}{v?fi^q33;_! zAZUI7lE$I3wOKm`vyr?dVUAWEcIewzPfm7@ni8ZMgij?GQLNoH)_b_DQsqdg@CEP9 zDdX~_m}~jo`9%H5Q^||cZo^f(*Bh7$!NSRcv(%6A@VEY@Agzi=7vwVn^dr;X2{}lE z#h6G&)B!~S%f9{mWroE(pZ%QTNHkWTmhgFJR^UyKvH)4kFbeL<<2lqd_4yuq@Yop!UXJ^9vG0hM3R&y@tr&Y{hoD6`{D5@Q|sHus;Guup|D>b&F+2I{VKdhlfQZ{~UOhQlB$nZ;ANX>CQmFvCtMy?s!r>%CzuDtN=-uOe3tBq4-N96?fy zC{ZiEaQf_y8m|UN6FOol-=h`RDHcEfI)X2U6iTqzRq>(cV_hM|5(ij23Vb=Uz&(gopVTzTToB7p2M%*F%^MavTqWn4Y( zr1x@3*9GnvlOc4}2}hvU&0oBu#C~me9UnE6s{|Ng?Sp_Jle!!9jcZVq18A z+x#+uhz~R3)1HMtS53WE6pHJ3)rYi-*s`gt5D?&@y%B=QU#KW#@s6P(c|PfA zGTl8|TSP+fc@kx;jVDsLxWfeUNZ{LA(XSx0RpQB|ex_ zQUtY$O{z=^H+PT_-~2wuK_gdH;w%3UPb+OveinbT&uZP588c24JEAA7?`(kdCQ2@0 zHmN&)HE@`hSIA%7t^iP+77q$aNR4uI$&+_&A7T1oE)>< zB?v5lAg}=b>S&x(1RwG+?HV+s3EfM_;%m&w#-=!-&=62@h!U0WBMY~oXBI+vtR(jR zs(U_)!#}YpRs&KP@0WeNlX*zX%)pLp&Q%0+8hDh4-hxyhhXs)spM?TBW(_S@a}EU} zlyh7Qn)HzWkrHT7^idaB&ineoq1s?pM;~4L`x?K!QO{_aFE=wh zD(VWQ=(s)GG1!-aTs<1e>x?ir9j^2=A zFXZ15kvq%|w-DYNfv3tLX@SGHX-hM0eh zvjAl4@<=22=yO~(y|aMawZvTTzP~n28-Y=M1e5!U-rPH!eMYvXe&>c+yl%HRMKFu(Z@OPfu2vckEc)v zH$66HI1<)+>TD?WM+!M>BS!yXrhs zLvcNiD^<_aBPt(j55CyAgH$R)KC)JJVz~V<+9ePQG0@(vT{5OoVeLO|wQFB?iF8;< zOEKo!*_tiw3n{_#ZcHlQC2XB;?TDhq>vojHmOg&ioJnaq{U=^fe?W;9O&rLcp6o_@yU^PL|G; z)(P&Ta}<1r3Xf`2#EKhq%?opEQw4yOvYmBOTgc7Zn06~~f+k`gx)llTnf1sYG3@WW zBHm(aF$ZY)6ZMs#rlWt5mBCjYtRFd9ML8jOw&WLhs+fBdJ@HPo!7LQIDQ{>=bU;hA zyUd>5M>R!3T~Kp~y7?fPI1z1ucEXn3em>$szyJ7Y8pKbzsF7hA>AgBT0tY+CPNt-w z>D212Eh{rc9@ou;V+}m8hzRwal*$u8A|pqOgU_$(aM7Dv0-l9)5@F^1EKAW&)j6(0 zV|?rFQXm4yVzRyP1Noq~7B17{Rg-Mzx%vfME1@uH|BWl+@7o-HFrWTv+AQP&Z-D@4 zzfYc`Bajyf&_jSV6X^P!~d$kL4R z6X6P0B<)klJ=ZtB2mhoqvH764A;?{v$y$aCKTb99fm~18hhs{m-=Skwy|@kAO38bh z(d^zJM?w2YU39ILqC~BAC3#Y?Cj4xptcEV>#c`9zUx#2ulG{ZxE=Z`6$_?{vRJ#+2 zA1q)C$B!_xew1XZN->R2N8&U=lWl^!5DIpn8zqw^C!q47gxtGD1)8ccEkni1@z|T8 z%`&!|&O%ba%2VGg>H9i=(KXqU%CUNxr4WSh0`txf%)7r@U;ivrO%MF0>QsEFM06uy zOCkeND0Bv4&#a)4W$kTRhzccEFDoran0JD^!f4}QfhZg0EA0U&wjPl>8R3DaP0^fZ zG3MB6$GnOiB+6l@&QpPkN^*1OgItO4;dvU^vh@%<691_5Jt4`QBQiU++YZI4o%v*q zMIUJW_|aquDJ^}I;J$;NQ*Ni28CqD4S{O1fyo@*Fu+0h(hFY+tM2=L+FW>2^Ag4t; zLd)>ZVTKx0VEO=qFoWa`j+~+WTf!;z&uTJ0y1RVe5^>yQy4V=H;wD|oZ@7dH(4%o( z>y-CCj>qx>kJnowL=F-u_+;+-2-etbYzH+jTP@%2V6z(u^(apczl zs737J4ZvAi+JO9FDKi{O9o+Etj^I8_Jc(8fT~BIo5zKxkF#Bu&vc>ZX` z%JXgzgqU0c6Cj7nRv^!>FRsC}kz(FriQ|@j8!i6coW^EGJg3aD;H$WD7;Nc>4FB-Z zR^%!oa|B3YA9gGdI`N|*DRHW&E%oVMt2DJ2$rmAZPP9hCxvGy%1^k2A`Pruy@Go1N z$)8RcJk#8VlUlcarTdq1yYBszhS}oI-0RaOsrNT%TqIDULD~j6e7JH4=ES^ zVaff;H=Sn$PVhY;TO22|7k@ym3UV%g0vBx*N)Owf&s}={)^4 z)x5B^Ze`mB(l2d+`$&5L*z2SXIrKb{RfGIds=NK>j}Q#5M?Eb-U?jc(SW9BG`2uKQ zhjc>M{UneV)b=63T*4hmZo)*@P8Ze03`HA@neyv?t5y>BWz^kqmf7ob@Y6CAGPKb+ z1FYced<>~=P}e!qX^AguF*W9wVPv~m(kdxAW`1M1y$&>j+wo!kf|g125>GkYQkOgk zC87b}_>bHRVadA3q;j~ioLgr4T&MUdu1Vl%CP)_X0_i_&U~oDcIywMA`_HglBmr_! zo=G%Y3!NcOC{gUx#C2{t6hF1Fa*Z9OtH3fW3|rWtTmVwo zIkuPGyp+_3R!7?pa)WP7VDSN3oHX=0t1$+u{yW?q$JXDBrYmk$Y853IKHgJFTo~7$ zIpE8QtnR>Nm4^+ihv(fACoB7x(c0OnI+0C0m2;981CX#q$6?oV>QpEkUw=3xCidaHY*a>==E1$%RwJTp$GJykpLj9Q$*>u;vYK3O!f!}MK0$pKWNKTnIFN3m zC?&Y|!5j9*N6?Q^?wwV06;$nMH!S!$UwGpjEuv^R^KB71HK%v$m|V-@K41waqN)z- zMy36Gz7MTFCSEXVR)`;0lq*bK_2-sm2{;w>QjU4%y*b6e8DuPattB&TOW7q==lzPa zH2fcW5Ht9A=B6ZVSwL`!ekip?*zFg_`Ja&%>m6YjDg*jjCPt2aYNXX-JRZ3=TD6^d zZs?y%)q(5NXXu>!;62F=QK0l!1s`l-J@|OD>YI`#NchzOKPoVJ??I$nsj&f0fl^@r z6!Iyoxj|jGad#T#LRdT4MbQ=V*AeI&ExBjYqF78lHB=&s+d7mCe14bu261bc=m%(5 z;@x*ane=WS&4u*~gBt@ngWhz*mETE#cq3ntStV29cOD1BOqXunH+5HmqPo7mqqTc( z4%7BgG}Ogq*6iL5-u8dbTkH5^dVtpKUiKzKc^DF@LTO5AFf6%B=(splwMT$)#Q?>ZIJpLIMj-Hb}f>eQuHC}v!o0eYtngw zpf4@qz5a=M`!8@a85DI1HrCHXT5`Nvb=z0xk;pJ?yd>Rym72Y`S=YE~P~G1yLwpF{ z`fq7Si-ZVcm=DEQJ!Uy~WPD@{TPV33fiH7o_w&*)m-6F+`-RU3*`HSe!^v4kQ+E?Ja+Po^A%;fX_n7=GRf(grK^69tCp!USn)vPW-2C{YN7cdSIgE{k#vM)*M_hg_RFrJ~u2+7Edz}9+S|&u2Z@(%`FB^jELel&Yt!RTDx(pN9RX{K2!3_bY?AfruoSulId<|Q* z2{DI6k_!F}b4UE^Hs-Nm+gLBEk8MQ9!f6D0)|@M>P^0*WK7B)!l$#wdRhV%@D#|B-@x0NYcl+o|n{OGOWoe#y@-*-t8dRGSCN;l)t zL*nT3OxnA|eg|NKV{s1hG*9BBA!%q6YBLyzMB&j%mRetjXaEtXk55A;9sR@#;dysh zh`SqI(na&uDDaj|>@di5v00{avIi3hf2)Zsse^);2ak~P{cg7ibD>R&^9W{Fvq(A~or3g~FV4gvUNq&EGgaXV{nAnA_2b8L z9(-Dl&Zw4h_Nt;RUz5Is2^N5f|9wemT>BS4&Oey&zlKXgz6DTD?*Z^2VXMU8tQc-^ zsCxk1qhjETMR=lk2x@RKC)hsRMhT#ZQcM$NW()`b7d>f2CV-p;1wdr74%a8{cI~FQyiL2%K;o%?$0VKZFl>>v(|aJO7J0v{)BRIjfZ&i;)Dj z=VwjGIr8(NKb9gRP4q1hq+HlfJgV*+0HLzuDf9AZ6N{px4;n@L1z>=gZ}nNA)NfCX z#YjsKkZNcsZPQFZk0g3*ha?2+R*A?lQ-c1N8akv}=j%vM7oL@BIOJE7 zxu3#VWN)$%VYuqhHFcnWCE0l)$`_P=dO8vqsz?HOs%Orjz<~QFdPah}od^&jRbJ zeHAsa3gltRc#)i@1Uq(N^_uNpL`Y@GVl!4^b|pN6U`!$O^$ z%n4E@>6~Z@%#$8B9-D0P&^RE0%Y-TMq6leaC(ZZME^JGLtft_~5+x` z9jUFb42J=1ZO}?u!wZjF+fW-mNmv>RECd!(BwB-eR(+d?2ykc=NUuiJrDow8JtzGN z0r!#v48h9*VB^E|`*xKi%3eHg>Ht5DQ#YlDwv#+t0Dq}-iM$-nc7HRf=H%*$l4S$d z^rMW$!^aP>j0^zGxC59zNYL_c6xbIpu>M!P2U_Jn<)r}p#{jC|@vGE7-vh%JDf1s= zR2b5)$*wz?u_Q9v{n#8ECqJMv_5qLZ!hHb1=Mr{+BB~nxFiiI6^JY{FH(%~|1w{ZB zI#7Gvr%iUJzZ?TqVgwm$Ayt!%*r}l zt^lahg7rB{Mw;gXk~%H!$d2#HSY2D<$Fh^sJZ1G;HAT7@j;%l}2GNRGB;m7sfz9pA zT;qUoWgVOeMUhP;!J#Y^w48YGB*F0x&dh%Yb+urU{|x<501R|WaupyQa2I0ypC1X4 zg9i{Cx@SeKY}hX+;M9VqI#N6kfLQVye3mh!+5|uhNrqXH+8m-80(B}TpnVUViegRY zW)FboZde>H%DnI&A121=RN>b zbncHUa~Vd@Nj7#P8YsKm1mx0hJ|Xg{`P2$8_f-aN;C!o}e_3v5!-37veJUZv5&CW; zNAA6Xr^&+k)m0KdSTmSl%a`S?&gn|TjY>>stfm0#3CpQo0(Ia3F$COCZ?OZ?$*FG2 zB?CnI{SAzv4HH`lToS!7Ckknj6@{}s65289R;tr2N=o~yg`}cOM}(A?BBA3?z9Q$b zozrlr9A%g{hbK6m5cj+uYRp-l(P3z05YhD%2yh7`%TQ$-2@YTPd(Gt|Yb4R?nYs5~3^uMMNurTjk) zoOi_Iu$mIj>*f#fr}ioX+q@8(noGUK2|&#boT<6A=T8@v2vb?96W+mFfwsXZ#Tk|w zM&!rE*E7ZHYFj@d;oFJ%gWaT3-c?Js*Y$IR;$lOkZn0A+M@#jCj6gi;VfAORhgPuZY2OJjhJnVq!f zbV=L^BhFNxB698{!$N}#Q(I6{kRPD2+#SYZ^I|>le1Fc{Z`awak1eU#ujSsME|g*N zA1W%@QX)5Z>k==quyc$nGCe>;!P7UrbrC!%K{hQIFB>1jF6v-qRwO>^ZHG3>x+=wJ%q>3ac2J4V+j1W)u(1U+uP^Vq6+5Jt6HQFUpz5l z=PTRYTIMW*jARj{fT%5<`K|(2NfR%?%;s zdhDQEFuv5a5(Fl?)a^f6oV<}QGoWRxob&M-M7DZ2nnag=gJ|4RpAh1Z-A|gF_t4sc z6J#wCe{0Xt=hwgVhWSl}G9KidZ2~;{-1P&2O^{}&ae=6!z~kp|xqe0V6b)30h}HL4 z1ibNw0Cp4|AKo>Hri-C9gCAG#=jLzjQ4h!*T`9g6wA&**)_P8f5hK9u1YU?Rb`UFi zfBV#G4xn>R{J1v!ImBDqp)yxb09rNdXfm2f{>@k(LaIe%d9m#z#BC`elr+LKKmf&7 zH-?ucH|WlsSt9c4jB6JnnY$B6_+pG-vp#6KCDDbFl{X?e%(@`Uvex_~{m^RbJ*Yg! z*_oBR^;EAjJ>*Zi)h2{J-CtvJG`%BjZ|3hN zSE{@bXFos9DYRX>AF`nDd@Ofqhy=8xpua(NT&zSW>A=Mm?Ro1?To=HWBQlS0zD_U! zHT1sQV+Zjw1x6p;b`Pe)v1-3^VS?gP(o$AiKXn?(WFdFu4!&W?I+S;}}of zsfdAOsZ{@*ODqj<0f@Z|H99j}rP4d=CtJ`;Sp-W^D}}4lFci}#hIVjo`dBy09te0! z8O~3X%3VRDF&Wc)GqLx&N0s&VrX}}mWtF9PUmIEAa7V<)NoJIBFa~7Z)~>R)PCm5n zFV0;&xwUD;kQ&kOQ?!v!yI#(dALXTbY9g3++*w#VXjUm%&kABHJE%D1Sq@g0;t5>W z3J#mZ*Cj!-%W-`ZTlQTQwMz+pm%ajnLO1onn*UU# zFEb-}NUx@ei*H5S9iD>`NZ@CYp@qb6aKL|m;m9d$v}pB!n-3$k2}rTgp#EOG90C)Xm8qKf2-3W95JpaDyGb5Dq1!;Ofa;wt2_JneJ^P zho)zfSZ&SiH?>TcAU^&U&s;QsT9B%LHQdd)`J&Puant6_SyA8k9#i@jU%sE+dE(+y z3;R9Z!<^{8&Kc(P0Y_$;ReXtcO>V>&>^ltgzTkV-X^6n4PYP-jo|8YZ!pHJ+#NLKG z87PkzcvdRpRJ0uWc`Bvw!La_c_^^&18wAI;tfiETWo zGPRDmco<@RkB!Xn>Il@TPdg>vqKj9muPRrk%a- zLOH!WT;XR~adz(nq&~>&I>{di8&KSZRXkqJntLo0r9n%Zskf4g^{spH?&Z0agOnl+ zZ6?&XU3(-SF2>jwOxu;J&^CBJ1=18nQeUN#NB;s1(b{bZ`g3m%P~_65dOD`6ZX8!U ztlu1N$(|#Wd)ef#&NcKy8&q7Wa_XYj%$qJh^H&sb7OGM)OLBH1Ey(e#?RWDy9fv(R z#p^3Yh$$f4l(wXp8V!#5w^}B|2w1>!`ppdWI~XQD$Hi*_EaoQ;Li#SqDSA*WvsQgq zSSOUo#fy`zthYCkF?1B6#_U%GDbg7np!_dbl1$YNFpMoLvZmfZ+2(rp%ws~S-jh3_ zQhAzte&p2sj?@zR^lQ4&s4ugN7qxL@f@Ns#8J{{a>({R(hit5@pEoA=rsVKeD$TXe z$XlYrRGQN*ds(=Yr`#Cd>fb-r5*#jL|H#zXwkFbiLbu8+eUqglOxKS#VFAPAVOA&p zJ>jsLfMgTCx-}nbM5l6|=DI`N=rj8BjscM&5B2q%5@7Sd#Z)isk*UGZ=P~W9h?N9J z(QjpRl?U?7TOakMq`aQ`>^x(Z*YV)lL$5KE0u2yO6_EYMK=GfRlfqJp_hpEP254q^ z6Bx5|f)m^Pa`ULw_RHftDQ}^%T=fR2Oq6ISB*|h4`VzC4nkcQ=@xsX6Z@b&Xm zHZ3?r)wcP>cE6Gbl8Ii^gGbcXAXeR1m^vl-fj8b|DIe6k({6BvaTcvvLbnJ?}{PHx=2D zsz1_&q9eu-k-Z&5!==P1f3Nw4tk;_B+D|RTMze>R_cLjZtUg$(b`i%#X+xH&A(u{l zVKxfL;k**dV33`FFUocnHSGO{wr0|>7Eq-h`cgHRo>ZY1lh=m!#+s>(#xQK@TVZiK zaWFwYoCR;Zm=JA=EAL&d@Wn-q@`f|}&$ot#ai3;a7$oD1{OqL3^{a0om@6N6cQ$&^ z6;8_oT3hZ!v`m$ zpK*@$B{}Yr2O#57wtSun?-?IWieEAG8E!5(OUxTgg0y6M*rGX`pKgT}F|a|fljPgl z$(tVYH!O2rS%SLsqEL$gOI#W|69Oqm+QcqdzAxiZ4&@z`o64HY%Zvu-+RhF=j8=fS zZlNDI9;}=9-q?EDY0}z0ek!bxEH#anav>2kc77c}QqoucuwJ;&i`C!t&byaT^+c!P zdqlXJ6sucqP)b_V$i& z7et;2!;#|Di8SKn3D_YVbWwE?C)KYZ1;43y!f~bjYF-iz`Y{ZGB=1fn2n#j2vfv~2 zoPAb0B`bJC&SW>W@gp0hgfxXQl(eWmo;Ga1#KnC@rhcQ44xnM5Z6pfPrT5_`8yT2Ny?>LIf>NmaM;>IPd*mV-gE;a z^mBIujd1Q1tfRuhs@KchvbaQ9?$OV>)4W!2c6zX)FxZ_;g8e;V-=X1*o1ugGLsjvm zzpLzQ|IF50FWVMDakfaS;KoPx-4#=*gta%xs^701&M*3E0_EMWySK839T8b}R%6-! zS(P$?uq9V7XR}o-hWnCBK;*b;XO>c8`6(GNmF|2CP5)_98|4CRs!LgVFBSqCo@r5j ze>9G$3qO4N`CY7EFF$}iA{t|LjcJFs#pBFhn3#6^IJy8hf_3~s@X3stw8|sJYD_{3J-wf6-BIYTM^Gs?qPd*M_ z(c#3BtcUV1t}~V7aw>}1(tv=1RtfA@$YrAP`#7WSnEkx(OszjVxC8R)C7*Ox4j>(L zIW^L9axJu%m_8oc<&rzOCDP}t&X4|}aDeowH;(IhZTE)D`~Z&nk>UM0PE2{XrQOW!yhMNMwE%Al#@7G7%P?|7IETvs+q^s_bSyK;xv7hbBGTij|4& zg8L>2 zbI1*tP~kXxDQf!d>w8tzxF5FJnruOShK}DY>4K#q=Gf%`keA)M3+8$_0s@Z=bslDFMJ(jCrUeCBnoQEGi0(#Z&0e zFC;jUMAJb$x9Dq#52F$LD4}ykTx^Vm0Hz%p#Lto}pbN!BM(nL_L(8tZ;rufLW9Nch zG|cuNuiO|Y9Lm$o01Grc{IkltWSCUxmaT`k*y0Q~LAgn;9273oRX1bk=}N)*u)^zJ zwUbA`cJ{<6+xv=MvCDos zjc#-mnu_CtTRScV$Qa{%K}6)dPMLM3JRo028@#W}F# z*e-F$m3-X#8a(#$wR_eO?66dT>OG{&Ab3mDH52s|M{K_S%|a9N(yuhT zv><1${aU6lY;H*QAr>*^B{`LH#2cf4DH4}7dIWqjtglbafO@6S*crmUOnPJqLhe3g z=C9H?Ll2ULxh;oQVG)n)6v9ExN@>&0% zC715*ZbTYHUAm68xXSVBqZknR=)Bn5E=Nhy&M5RecR1SBL>{J;41d++ym@44sv z_w3ny_kCw)KJ&~xG0)6A)4P=FY??e$P&Ne}{~=1ZpF+l32UpeG{{{_+N#3XrCUw!= zpFbb2Q;*9ddhC?8IFxQCxTR{SnG-N0h`ldxUz%q$Lz={wEU=S(x6yCK>u18Nr}C4c z_x&~asya|+ODoq$y@oXgg|3)?un{DCrM?pWOyZ}!H>OEN#)LPA_snA$j}F!xv8|AS z!Y`+@?AiDE9Rb#UOiwrlUD%2qh?3_XO{y1P%PtP6HRfTmFfP$5(nMeDxcPiNnleZ} zHZ9T>fz-G)wwKs3>11lA-lVhrvt-faG>bVWYc+Oje&7pj4;+_s!e}PdYu$+4DZZ)e z7?XIwqdE~}O?}y((MRxw5E9&_!PU2@d&gw3cFs?tH+t4D<0OcfC=GdS(`$xtgQ#uQ zx&0mSj0d)nOM=W|#6Go%jDvmme9l2!asmhC`w|uGl?m@t)57uS#_PKuNGyMb;snqH zf)_0E!pgtoV~ilY>P!iz1mk(8e2*e)3`VU^fcG5t=~Re)ziP5V_LIQ zXdspEo8D^XOE?j*xVT#Hmjh%2e$7&*s>U?)UCJWX(@{UCz`<_hwza9B2L^ zEJsC``;=&kwf~-0Cuh|WpKmYMd3!s5sqyjEso0ghXypT|BTPd_b`|xQ%76UOaYtHF$?BzIYxs-D`Yi7Ko*|~|W!t8XUYMu2Nx^PyuhHw(ilbGdNC=*^ ztm8FOy(p3l2y!$3T=?pX{bcHzy)6G{kAsqs8&j2?Sy@w@;Wi!TR5p3Q!iMrFoW%_L$X#Y2VX16TBY= zFHE73f(iX;4D-zTx6S?7AI21`;*;S&m|7No1 z7)aMefaS+yH*TiGTTqnM(f2mGxSrJq>$%1LmSqOU@x_dR(A#7_6u(lg(96ZIXi0+DEdN|0{e*&_Z$`ljVRcQ;nBRkys2YF zwALj5B7g=*V8`0x8kxpT~p#Vs`k$3F#~p zXE%FR+<#Q`+`>Qc4@vyF)+JoIDS6fukEhMdq4yFhKO)<_HXYT8(L|rYF@97g{ zJ`(W}cC6;)h2PC+!K-iFUFxPs&2Aa$alhbpV+0?z>c?vohqVM)^5jiBBklf%WCWYhC8?G_DaEAM(#|;RUED^ znE9^4#>CtsPZ6>*o_9~@W}48FZ`~h6&h?ShTlHb7G3OFkQ@o@aF`Anp0SiM@FvP{4 z$}Q*sy{;d61h=ValBkZFwcPa{XB{L*DayX!%Pa88?2X$N70}$6{giy}MEjOEXURX2 z?qc+7O1m6iEtTrMitc;w+;PFT36E)8`~1&T6HO5+ndP16tF+%vMv;wjo3c4S=1cbOx*nX?xXe!X~eFy|XRa&tsx z1b)Q{-ucA>l$!_OY_>H`Gof78cQc zI=$MYB$f7CO`NOb(v|Y?O{%ucQ0|{kr=xI>s2>ijPgPe9;Gt(fc-BANrWQd%dB+@| z6fIdW-k1h$5(D`nNutiqzTuPZ%&i;5-Ygwr-Sh(SIlEtelE=ge zFK(urJJBqE<32xoP(`(^LwnE2U;6zV=ES0#7sFArlws#rh0f2{4>IHAC;F1pS$eR?uiR3WL8->oz1Tl!>f_OV$AmJg?(+ossZg5p6ge_4NlM{<+INlr(E$qSfjWJNuO%ug7(-Z;8O*#<-ppLuU*fVuwQtH5pKl&L6QFXgTPbuft|_6+ zV6N}9YJWp#6aJyxBZrsumZ)60^c_l0(W@@e12(t)r5u4?VQw!Dc#5;v2S;Rgn zvkL!)HRgsdoLnESS+5!_80*q^Z#trJMo(EMJchY5(%cnTD{-+&Y+`E|I62b!71Gy18Ai{se0$UplI6|QLX`1Ap^|z3y6`r)wgtI!*X+lkyYC1>4z7VXc+!6Q+d!WF z(1dRJ%IBz`9H&KOk#}%yDD|q^bl>Fj`*f19XtAQhI9{IQMT-NaH4@x_L#~6iNla<#yWBNxn7N~ z&ekKE<7BDhYGw>{X0rp9Zr8>--E?x%dTV&bJXi~(Z4(t_Z_mT?lzTt$Q*E?seH)); z(5_&mfoqb zkhF~{ZvNuaychux^=$6l zJt9{}(V4#(Ag}n<-(e81Tb(9a(!4Tdv*68d_7stwg!Ph6UC@dV{B$qzahE zW@~~niZ@8rgxj(UN;9`@(5+SBugli;vCHJ(?}cUXlU>7hR;$7awn^Pd&pBN|pPx79^0sAuKYw44RX1G!mtG+C zub?|yB9AjZedoU;5INI!HyJ@l)Oy_<&o6xBL!pNMZe<_mTJXnoPXR(ciK=}AuzRzx zw%~?Kue>)n;lg_*voe`MUaf8#dxqCD*_mCc2xm9UV}0Q8yun4Jfed@2p!l6o8z}AW zr>z#-sk#zxp4XTbba66IR&~ODa=ZMio~y?d_v6TC-N{3gt13MOo>DroA zFRsHinXIHY3mGF^+BppOnECDRGe51nhW5b8hQ7+L;CdJ@bK_4mTUhP^^}cvxA2xNH zsiiyu~j@fSAJ%1q=s-1f8FgBaBeaoTg_Uy-( zvNhbg8zR}`Q(a7aq~)JlHBGm>?x*SoEoF7A#h*C(@P9NAMh)UMOyLZ`hbHi5cjd%v zldYVW4A(+7pIaapnpVc{<*8`Iwz`(PX5gvEWUarQ$h5(_cy3JJE=1evqStklg18SO zh8xYCh|u~z-93wW6tZpox!0aTpR^CrEq9nNe6nuT)Ba9_+Issro_|TJy}I9R2A@4H zaVD-E44*3WY#1@I49O0{Lw;m$7dh3`mZn6cDH$c8QB)g^S&rjJ$Q@YE;MV5LUSK4^ zMV;R_wBt=Ht-)44her9c!+_`^oxhPVbNz&QcL-A!2z>SOu)*f(yXjb}Hl_0hjy^sW zRd?9vSR!sXs~IN+!ydu*gC{MXTr~5=c|#ZWn6sVR$vNlDYp*#Tty`9q%dqIJOX{AW z@(#WFa>ob3 z!75XlvQ(We{!1GAj#kQFIIHD`p|?cC$$Ku|ohG8W%4|I$QzRh~F)l^{i4tga$_v>d zfBe4#7!VG(X?PBy*%lz7GfgXrE3CjN?sc=!kyB>}C$#4xU)oaFE*H#{(GBWWqu&@- zLwnhKTa-)VDjjzRzNh45<2Ug!r)RGF*pgR*6)mVrU_wJm;day*+M(|bXi)Sln-PoU z3S0+mexl?g^1*Yy;=BiXavC_IO%-&!s@0#liEY@;rE2aP^sqkJ`V{mvj=;_L!j-Kf zG%}5a8ne~$m4PdTX-qD=)2ky<6$K9w?G^Xk^!^fRpQL4TA7bi23dUz2CG{;Q4?FUj zX*US6Uk%x_pIOQ>mSR}3<#B7;Z5_6=(EG<&0p_Q-mgZ;le+X?x8_j)JRy!1nGw8qx zW^H^~W>=aL6ZwHi6Q{RIm}gq{aeSQ+boh`L74>xDpvL1jtdF7PZg^!(1Oa6GB3VSu zt6U}5NzdWEEye(scvEA+%q@j%N`-lxa}NvaQ|M{NZU#>`=2iL1YE`<>qI+ns?9y}| zY1XMp3@sf#n$}QeKgK6-9yzMv!_~@8Esh?=^0@uUC>@0JefUAO8J~{vvuXI@Ae})) zE4DWA?%l@9U_DA*$FgOk;$B$_i!|zRCIc?N%ayJju%fU(%RFH`|6c8c7GGr%0jueG z6Y+>8;LmNCYhYxm@Z&c}y{^#WB(mzRByCUST3YMK#n=Z;wkqkMw}aUTkh*NX1UCWt z2#StEzTvU$s9iP|bP60IOArY#c=_&#JUYM3kAfxyV*``rqQyFl7}^O^I`!oFHSDA` z%#By-!jFsiR32`IePrMiI-1_}tadW_peMrYGU52CDl|0sdM>YwQgteXy#m5M`rqre z$T>sk^Po)sUb#i-j{5!MGltj~Toa=AXz+UG%Nv}=zrW}|A@pzFU+&FL;eGtIQvN>L zqX-{p%Q&Z#_c#E=LbAp~C_uVR$l&p56@V}0SjuPfH;PxL$)6Yv=aJFY3HE%$9-cKx zjCl0njQN5*c|-Y(%&&4R_&ePT4<|1qPcZ->0Rp=7-$4I`@ShhjbooQ?88f6On&XJqtt6Q6vw2+8*x`c1e*4o zvw3^(VdGQWeL#%r&V_&8$8&<t=YEes-0WQ-~c%G8E@7(XnVbkr9yTZ0P|YM;fXN4XF~zFN<%lk0My&)>PKh*W=W%WXXieEebuluZKDSS z1*cyEg3^o2;_#S{6`nBd41GC$&v;<}dgUq$kKkR|)bGht;Y{YyD1|GLun0&ZLktoA zXT4yp4yJ&(ko@7Jcq@_BJyMq!zH&~i*N!c|#(*wDZyVfbC^ zkRJnpwj|qEECsE-We&ZDrbf8W+9UAh4z4QR8Q-DpTFp8C+(2GY^rNGL#746WZ0F}@ z#XPkpUJOxa@2_t2-pH`zM)NRlbj7j$oZ3y^E7p6>uMA(Toi{|FvBwgBjtwgs?qsd- zChLxixs&V{Aec@06yZLKV%0}R(d14Dmf;;)(Ao*z80M%uws{-83&r)Vm+{wA`m6Hp+6Z_>_xHAvu| zO-*>ER>V-9Xf4gGRhVeFY|XK>RL>iX0BHPCh+!3$4^WRlhjI2cV)6CeeIkJyhXPoO ziD>iWD3DDV13yR~O(!H6uXmr0;PPvIeUr!ZtK)Q$g`CIg8F4|wOKM43q6M+W*FT|# z>Xgk3Q2OtEAHdP?O_qb5=Y2px@$S>-c6?nM;#Gqa{G2}wKv|Qcs&hXdpRx8$Nast4 zTQI0^imaIm0c)#`hQstF(KvT?H>*s4cn-8mpXNcer2mv$w{f9mg6Cxhct#ur7`K{E z&0-mH?Iv(~U+s$4vHUo9tyr_Yx`Jqik81X*9MU|g%+@iNt4PKie)m@ENKL+%kSH$6 zkmg2fCK0h?d}Q3=uZ}AwOF0zZL&F};V%Wt4(YfT@gqe7f9xpn^6uK?9vB-dKo|-)u zfU)#YXdtbAN8rFd41Kf_OHF1vQu7K-lG=s<$Mvhd8~+zk<>@Hd$aJ(3qE!Zm#A`-e zjaSpFmT^xT{0FH%Kj^?9wG%<03&-$#=+zB8f~ARJBO2}9F9-r?N{3hHfrPX*kH!95 zc%VtL1QqHU4TgjY9F|u8N!OA79DaU=5kgpr_+*8Jfuc;N&sowF2H-kedZV!LK4;od zJ%JW@EfmpO9XWxqK9c#>w1Cb2frGn4$9&-zsu8Sx);)A$%JOSY)`g4|@R}0(Yu`*F zsaL`7C6}ql7RBuRdvgd(vDJQ&AHY+D!Zd{-vST6yKF$i^bPGyGuuvdjaf`_ukMdcw zBAV))<5lGewPiTt%@cw}I!~k)cK|vI0?zR=%v60;UT@w^RN^~I zLG&m+B}#H=$An1p9G^VV6eGKk4~z}?%%foy`?F8jF&uo04ze2D#=+kTEq^?ss780= z>Mlc7;24)J+-O&6E#$(3>j!bIK~oVxw?NbwGL|#W>{tN?v`o>=I~_pB9C*qp$z&JK zq}=!jqcTPh!w}1f?hLyRD3sL)Hw+~w>xdtq0Li$9RMIx*ZQt)#6WqcPE>;{IKaEyb zuwF5t$YW~wU`ONUb)P<Q&*oM!Q20C} zwSAqKJ%OX&?i}mMjPSdN#Wt4DkD3);mh@X8j|uP7sA>`BzM%4V6Qot6zU2YC`s*2o zkC-+?Vf;({v7)jc?d7vFN@TPhj88r#&*Sew9Ww;EtfiX%_7iQD(9$XwKm0bJ&Xc~! zPATWA`ZW1Fu1xo?`>+#;O5l$O&I_7`_3hd6hM8ZX?qtx6jxyxyioi2CBnZi9v~v|- zoZ^3Z*!J}!qvt)jNUqZ#p2I^AYuDyuUwPpcnjZ1`CGicU^6HzWP|jU=7itQFAv-_i@!c`el=zwJvMVi zZRVBe*^PU3LL{xBF7V;o*Sqxu*zY_a{iblPDyi3z#$niUb4uq$(9fYCVb74dUOm3< zXBUQSa>O|G&-e%TDKt;|;qxLK=e2F;1vI$J|FxwKyPgtz$} z8nWIvy?%XNcy&NNvH^azh=XB_Xh2To9P@%ZjUiwG|IjQ;`(u|-NTTi|iixk!nbG^A z8G5C4-K#XWy;zp<@@o(!Q-0Dx*O;9~y1@z*#rZPmYw{m+@GnzV{8C;+Z!|LXe{56u z%h;lSQ0*5O$&BW*|2qv&Ge1+v{lAg}g63pygDX`;c@*++lN%X#kcrU`WuV~;#z<7n zbR!_r7PsP9qXh#P(W}zpC;*1sD666HDr`=qZ@8*+r;~I#u!faTndVb(NcpIAiEWvz zz*`6kNP-o`;{Ts5OaC%x{_8@^jtt)gPl=W4Y~>OaWv2UImBA?qYMf5}7(E-8Tn&!V z^#M1cRLoZkl?36C{U*`03#Eq5K^7CH6}}WR0QO~JCfR5f!-21(ZeWB(>MKM@ zKm=7Bv_XjeSb{MA3;@`Zp<^j60ANj1hyME;)OEAvSOzCbTE1>@nI9#2)0)vZlQj!o zU@22rp-NI1F}*>|YLA(5{uc`yYG#1O@Vq8Ifb@i#D&=<$^Yxk;O5-U+{l^VRhNeyI zk6-{(c5*;X%Y_~QzEmLwBv526J}QQO1pD*cN1|Qit*JpqIE@!^vBJcVB!hBXBx;YI zRZOiz>K^4OjupDZdq@bo%I3um{7(&PJ6Yg>1enV-&=BXJq@}w-Uyl0nP;)`+gA_oI z#^iYju!T9IrRW?nP@HuMVdt&JcU_~4O6+GF_RiPz_?+w;^w*e!Fc@PQ8z?W#`3q}d z6{@(jMeRVF>V+X?OVeoTo@-*BUxk3Hq!;!BWhSs@5qRZM<_gK_(0kO;0}gjMdssl} zk3h4lttpO1Q?W>lhx@j~P*-Xl^>M(TvkwM^4-4l7~ux_^ixwZMkEY+cnVJv|%C za+SwBT_U)uR$QvE7CIr}UWFy});bI8-uFR%9dpUgrM|H|R>AgnzH-gslmyu0!A*Fg zUuP#e0TS`u9j*wRhX8$z8C~5IT$m#-iC|hAjv}6+Z&I6FbG64?>CSpG=-U-c4Vpff zm)T522ru6+L9uBq3@S`uwoAE|U1LG2x8+DL3zr1zL;t_r5t)+sN9p}Oc=+x;1b`9Z zD@_6dRun*cRvORM`V)ag?g-G?so~rd8uQ`Rjc2$`_jhpb3-v;qT&}A)6&Iu(Y|hPu z*t;~kHM9`phgWm-iRF`@a(~CMcaYPF!e2vyz{7AHT$M2(!>$4aE;iQ#xI@WLH#s)v zi5us#ZkHOEjJ?bX!TP?G^nNtRdwtk$3}0g&iQ#@y?8{X55dgtr-_CqRCM3wzD~sAl z+FV7Tp|DE6g<~2a!7!o0>tk&)w_kSZYq_MY8R}0rV-w~cf&xSn z1IA)>xnE1<9I>zuQ_s^yb<*!hLrGxIe|0Ky{!WXLO}yEbM4Wu*kidii$vm&kYOSmj z-C0bF0C?qFmf<&`ROqD*4W|GNg$L=O_bWC4kZXO($9M>|`0x^bI4(A3J5m#Cr80HA zO`m&Z_RKUPOYSY+Ni65RbLD26jGWeMRcn#MC22vyJETnz{D%zZ6_rov&AGeD%|S|% zYf!vLV&xghyk};+Ji|MZs`qh(LzFh$MngsJb%@A}V(}aeE}B_8$;0$5eWoTONIv1+ zCMBlC?~UYYTVa|k;JdmWM}xl_3PqS$JaJW|s2TfC+GCj4!XC+fkjH#}5)|M|RcuGP zW6tVxwSp`oC4JIV?Z$<0N%s3=`sDievKh`!k3d^Ot@#7{EonT9%&!lG6b!p0CCB$Z zvr+E3&MZ*O<#4FtS*3GN@Jx^t*~V7rYQMHOx#+R%=7bc9Dr*he8iDB>0uiZt*7Z||$& zOAXP_j6+Wd0b0BSrsxy7j~G?s$1WdWH|VXGU%tRcqa{a?9pIxkxdkTe&rd zd$h9yAOyFlRY78@mA5r4Y4VCR4i{*6VJDp7$Obz8h{$K$t{=Hdrm$wRyRbeBlar73 zQDPY#ewx^F(rv>L@Q`GLYSu~+8l`|E*`ku)K0zp;3)DI=LP976`PWzgzfz2j%tR|K zK-?tP28_2EMjGyT8S%KeD`}qb0*SS9Yfp|8`FHyi7j{VQOe7JJM+qUrrVTr_T4h;C zBy!!E9-%y|oXThzB7EGk%X*+VYy}h}!(UWIhyCV2sI0F%R$q4}PaVS0t5Q7|1GESl z$C)ApdMXQ-`&c>vDJK^_f>{~|>aIU|S@+N)mbh!(!mb>qPEiIc01}(Ylc_JOM9IYf z`xSGeX*$O^As}K_?h$`173g$N8vTTpbxifZ%xU=6Ti2x1n;#NOCNhv2s@NJL*Bss{Z5QfeAt!4v)R8KJ?c9i)S$Q8&i(Cn1A0?LXa>@ud}p>AP89l+{z;D@tNaU zbH+UhGTbI%`|mvXs`h`UWBhdy6>nG%ds&8Y-33c@31F{&|NTH<6%eT#5B@s`co*vOyWyJJMr^|1 z!mkWn9h$FYzaOE4UZkE-bcNOx)2xMxDw~DGm7_fDi8zD-txI?V zlWZ<@o$t3R5t2On8%lq$VK$^?l#r&A=in#l$HPPwl8-B|nYm*lr&P z*J6tc)qSg%C}^?u`B<}9P(3Sfwq-YgqEajVlabu7;~W&OT^()PqLJO^E1jnzy-V*% z(2E=!?ll`h`SPCy;;{{kC1{P24U!zYuuKD)VZ0owcmV{E{>q>YEDr0+@)MJa!D+U) z?z4lgm;6uPaD!8Gv_isA6!$Ag&I9aG67Q)Pe1 zqYx6bcmk(ttj1f4O@wzcF$5=E@n>85A3$vgdmx+F%oTx_HGBD*&e6C;4PSwk{Y9Vj9adIeHPYIBiPY@8K*E^@H%V6n75uyl-$ z8%+4*#>~V(b>$kOwe*OLzfz8V7XJmmh++FXqQB=^vw9 z(P=F4vI$6lEzYchRZSttj~m89YUU^Ehuy660V|oVI@sxZmsG{oSi9ljcXDDWcM0@+ zIR{*kMu_7>;#=Ai9Es*u>&;>0>wJ%y$S?N_Ut;uJz^ zmO(0sqfo6N^XkQ;ziM^ah0tN2|3JdGy1an(TC1Xj?hI)L#}w+(dj5Ha;S10((_3nG zpdCi^&gqSU{z#ZHWUT#G9r5v<202s><(7foTIcbdYc8Jw#w;_|DI_?4>;u66w0Q8E z6~K%_iX|-trIB5bbUYwieFpXB&_hv( z<UsUiWQRJp=%~VH6=HHX*}UG$VuWc$>*b46?-B{xe+9oV z`|t%K)9*I?*C+lYG^*C?Rsp3{Hh=3;N-;kK$d4g?v2yzzxzEE8DW=W(+9k?Bi8Wm0 z=uq-wA|6UVJ7W5W_`V_wuCL`I-nf2KjU}hWI#HCush=BlBwFcr78ym~oEc~H6m#`0+i>4ui-#78^Iw(6OkeWq$>7@Xo;2aswylOHN`wcxu zRqL-;sHMYycDTm5t~C{=b3@a@4=IQl@V+SuS9RaUp>!6sm(!^uE}E(_*bl**`oP%~ zcfPS085`xOqLR|iLyOi0YpK;w8NbFE7%#Tx7FZcotM{bX${ndCgs5X)#DV(EnrzXC z>mR9l86c3)>^1Zz>xwO-xYx{p0`0$_PgVQ;A~tB5C5o!sHjn|7z2GVXx?ErzEK z8FpNXUd>;ipg;l_rc|wPZ^Jf?85At7^j=Fq z5BuJJFQFR_!0JUMZP;Pj%`$s-%g)R&@DhwY?^n)F)IEVK>PoLZ$zk^&)SFBK-uc9Dq}x{F2y{ZUNT*%bgTqEvTsB)DoF=f`KbX8tzGevZA0tsL}M3=y! zH%w>SG|B6OKXdIYMnJ`<_{h94GG>6@8%ygAkzFbka)Pwbk3)QFto!X}20*VA)giI2 z1elc>e9z*~QA>kp9+HAZ=w_IlwfZ2GKaIO{bydA&Tij>!#pD+amUSO;<6i7G&Jo!EK?LmO44=$<_lsQ z>WyAmguczWrXBa$szk@Yu0y#0J?xMfGst+{`i=Y0z%j9t{6uO4cN~oJj>-RrY2|=TWb+R zVo`s+Y^IDRE7(BWPJV-Ec5{@_trfyy?wekVW!c&}>$1-pMc`lbv3_8;;8f-ex;X5H zjcwSX(5QyM>?j8R$2y%Pg)((&P{m$16b&%XBH6d)1OdIhJYZesm&Eq&Pf4xVc|oL$ zFnWQ;O$;icUQRQ!PhA`TSuePN0G=KBg9~RhM247!kho#jvY}oGF+mrCMvomO+)l8^ zVa1$!y~wRV#h_1{Na7=lVc-xI9Dz=%V7W~AS^h#JT5g8M{nRr4_`NK|QPr@bwbB2@ z-}uB}{edU|PG(f4K*QeZvfgOjLwsGIJJ=lHQG#kZXRbQhfpUQD0BL2leQWGK0OXNWs{4T19&O4B@H64?Ae+7;fOs=3G12c?9|}0& zph2-quO$i^;!;>%zv6VXneH4SQ~J5>~X1{}0fAiU&c+%PXJXV*W2gzdzB&_OVJl5r3zG zpu%y=uifN5T;MKl=S zh}H{8p!NVzc?x1ZYfmi~jv0Q!|EWT-sh|v}XaTw>HNQSH z5T4!s2oj-N(2=8htJLh=c!*xyP)cp4&{rhJ189Y48l0?ufVsbZm{Q@3a-;+plEtqm zjp2YPSDzDN#v*-DDg>~2jH6Jq)ejL>X_YXxr5M2G`cVKRTSk#LngWYeyZ&H5S{b9+ zMz8B~am9|d6HF119sy+##z+4_u)i@vjexoEvk~0r(|v}-C%;6AJ`GrJyl9xdhAJjP z1w~QQkDfX{s9>(lV+dtq{tXm|@k*+JN6)Vk89;VWH;?5k1Poz19NGXD1bK5Ys4X`g z`3@o58UKsmc6BqpoqLM2@C{K;ndJM`G_X;dwRyHZ$siW* zT*)W6R{wLfj|Lv>dy1)XPazq8_+zJ`R$1i!J#QiP91ejX9M^yky2!}%*5TLV>*zwF zN%s3G)qR?yVFrcnB-Z62!J-R2ft?(Y1=gZ3^Rl{L`^0bU@gTq8_Px(p2x%pZ!TK0U zz5WC@JXRS+7=v5nZR9)z=c{HtKyNUn$Z_{%#pgGFmPhIcM|6og1&GsU^qwy)E&5o8 zA_?x#_05hZ(*(o~hEQA#JTeFtExRjVCQMCOXVoz;d^`O?TnGx_1`lE1&w7P1Y8+Tu zs{dM?D6&ffCiS%Jd&&*lyQPJb05~R)b!K0iB`nFSuuY1L&yFHu(QB7*Ee6+zj1}2` z9E*}dWJK$IoY1J_L9RY)2tc_X01Pplo)-RZWW18uxz3))XRp4aD*rN5tS7#Zwi&=; zeBV)3!pZSSWca>_UWFmUi9GebYD@%_(S6yX9gRP#knl9K0oIV@oQT9kW}q{YE+`I`a0hi_v$x+G?7#l@UxJ}J}LbXNr!(Ml}Krfd)? z)iRTggwc_pljdV$^;hXN_tC;JBO>;3=UFU-K#Q!s=B)wJ)TvJWY1sAyErh2x*|nzru6+dM&A_@O0;9yTQ0@l zgS`W;Olr(AwQ>RL>+|b&nY3aqe5$kOwFn`uPTdVANPn%tq9QZGb9eg}&RUFX10~N7QW8Fe`Rkt_e!`9`b`6Msg^J~T z)BQa!)3}D6pZ9`P=7?MC>B-F>u!(?$k3?4aE9YB5N6(JP)kYoU_^s`F1n^{YyN2PU zGxm=rXx{~`;BR5a%D?O2wyo>sCT#6YeDANk&Y41<^JV!b$?9+?U8d1~OCd)Gq2um) z+7Zkx{O&JjGs76wT)dT1-_ISw^DHR!sX>~B3cn?LF1Spr>Ky?LMLs8bPizMb+}=}f z$2b1+yU`JZXhUC9rRcQc(kOV2e@ zwsAGJ%dDfv;Km8MA8Vg`G%g&@;d96pt+4T&NIFhH&wR*(H%(H)sq?k;xH4t~`p31` z%-pm8Y>jsaTg8OW9-iM^j&TaXJyf+yy^nv)qz+&QSMY~jw#4E5tPH_rA&w0a z-$&jRhUsY;rYvUV+-P~#_gdXrPRRJEdL*{u*I{~bw!HtG`QD>Il*=8%Pui8*H4mLH z6iAc{-iQ)p|FU3ajGx-h%usueJ)$LJAut%qs^549NpF}1 ztmyF4s)45F0NcVoB(Tc>KHPy+pB>{kZY_roeM*v{Q1KlCm`wvpn_}ZDop>>l$vl|( zQE#7h^{|Z^;!L1RJ_Zsre6~vA-TJtEIK?dt>Dm`%m0&j#pub~A&Yxtb{uV=NEH*K+!#v}&~C(P z-^OxCdt9_a$D7ah%7^=H)5I!lrNbs~Og9Gmg|lA^o0!;-e6qWp$;68ZlsSq~H*Vm$ z@?#|~d_U<@I&0=Z-+MRqbkNW@Ry=m3#;$_8>9Y=RYfFNA?kYrKb6C;Qr3rRP;ooXU z8i_u0aJmYZZRNhF3C$~IwPO}f4^fsz$FH;4QooDlfK^cX_@u*hZnUj_(s~uJ*}~w7 z@kHFr?J!j5xc7T~EqjlDkW>fX413~vBceT0Z;1q?E~d+Je;Ug9iS@CEi}ZpNR@ZI&H{P#= z`Zc3v64UMMXX@!X4&CzP**%*U{kXhxH?_l9uayXqheo3 z&psnWP_jFKdA&JmqOpDpE%0^R;)x zzUW&z^dR*uJa%sRflA10fUs@hvm{W@HCKy_o3?UI1xBMuMq-`DK`*At^FA^+d4Fu5 z>v)(o@NI}0^R-&PRem-DMx$Q3We!ANL5RNm|Hs6ArNNdD&?2Ytw554s(U^#O2LRnF z)@mriBLaq7+*v5eepKyrg48wyEJUI-JoJ@U>JvT%zsJ4mq=Qwf`jZ{=J^!+Qa&f`g zMQ)(Y0KsJ9S{S>gci|nz33G-YXm4mFD!TgII$DO+a~xlT zKmFR(S;ms^VJ3L_L!QS5@~*i?`p=JxBa}$GlGGZ_^*tMN>H0NPhOUG7ii5@m{%fTg z5%S0H1Era=GVyk%Nt@d;OjN!+zE@X4>{CtXvDw`rKPZ9IKNER z@dKVy8-=W}-xwE8=8(EZu8I(>B|mja=e||ZEwh{9ctKOtq4LZhuAz8vV~MXgYrohB zTYyTOBd<4B_lv*}|Fi0i;8Q&*T=x^!mnkc>IFakPM>*gs`zp5YMv~+F92RXOL z3jbk>6DD?gT$(ws5YmYs$GtBlMz1YOeZX z>|IM3i)NBeQ*_)Dd%pB@c81jQ+B5nkij66yP-AAZ7wop(<4SQtt`{#F2!?KbEw^-< zEh>H9z#EO1tBEn7^5*BKFN0){R<^A3IEXCfU-J3MUtNyF1FBgtFrSbAxvUCteO!=kOViosUmaPd z3p+xFSMr?%dY2Bw1;d1Ah`I2oNU?Sq6tvtJPQ*Rbv2Kok1oZD%WXOov$aQN+e<>Ei zg0zD=_9}_9)^TPh+GqN*^@M+cq^yvg)AvCuM|eVs(=Z&N9$>g-+2pN6AU{yx01Jl5 zC;*Z1&u9TAI0sGnqN5+Ia*E;BAtaU1p4C#xB}|j0W8Ff5wQ?FnVm;>_1x))Kb#|mN zwRfWPEb@Ui;}oe-krQwU7k`+}9Pw;yJNF{~<5BA>eD`i5k|X}^$in{3PZ&bgF&K|` zYpxItPWt^Bz-da6VE#_Qf&0o8nhj0H$vZ0> z>(&=FB|;LlaRvq2H^W}ZZ&WN*WMHWJRk?0gEaq$S0yLjkb5Hx%f&vN53A1+?4+^7i zzsP?>7x-p1S{m>M2k96j__p4__?evh#P&^A;eDR!-8b4 zkvx({(2@HB_2gbBFAkgO;%!MGJF+bJy7%NGvRLcv59}Yma({mgZQhwnwn~UijY{&} zXUx7UKZIVUsKLsR0?>V@9SV6G(io=-H-EnB9$3k9Pj`O=Cw@c~wcQ;PAK5vme(eUF z>FTeLP)3J3_h%|=ZBYwKwDSrHilYZCy3H0`Pwww6e5>*1Hvb;1zil9q$ToVFWfJ|R z3we^GGPCm@DRumMm>>Xt)8%K}k0$|IxQnlPdixc}0inRBBuX1MWeyvpn-;#?{i^9& zsPEa9-3P93*97I2lusA9BA}TJXrQb_Um;TN>#nC3m~*8kE)vV(;Tk4I5>do1{M;vr z!+Q99&nD$N}_YnGXiQTUKo4AzEIrHPX`eB;+ojo_-xASAq=J~}UOr(Qtc*U?w zE0ETEK}zUt*OD_f1~W9Io=K0~Lt@dhEv*hOgf^Fi12h~leG+zOD*%?5sVU$3p4Z9H zNMh2A8TLPju^IwCXCd=wDn=x-q7u%+ygT)*A z{C%u3aJe?L5aZJR`@5H2&d&YA!;YSYjSujoer*GIqTTOAI$8Jpou$yrO*x(b8(z!a zRp7reV+g^KhURDQSbN4k(Pom6ym-((BoJn6f6u93?^GGZ^d{P=CJr)y>{1W_V|s^$ z8Coz&th)rcCP?6dS_d}T#M$QxeKFp_78A`BGuVmmy?_=-M*;v^VTG8N=F>j`{x+j7 zrw?V*fd`c6AESAU%9nug20uXk`z|Xl8NnPUGry;+v)lCd^i{e!Q}+fDFTHZ|ulzh3 zw`O7${vTuS0T$J=tPS_fkaNx%$x*U^GJxcak|pO15+&%6bIu5e5(QLpmW+S`l7pZE zA`%q@B?|w-z0W87_)YBzjfv2(b*jHr}2-3iVs!IcU@WE1eY6^x`38gy9d zIjJfX0_F(-2!VjB|6xY?7ofnt=l}Zn2X3ehw_l6?fg15RaEYIczcLhik3)bVgA+>v zfPLuz=uw2r;AI62?=C+JuP#B*1-GzZ5g+L+k1lUW#_3F<0ARKN0Hi}8{uK59Y5el# zSYtx}29>)60^but_YMWbEAA-R4-A6uR6wo?ss=KrW@_U&YfW~J(2@D|V-5&RM_0fB zG*$eBzC-M47>A4~RN)nD~|e?_!Fa!?UI? zkd8Wq3;>`G!u7ZC{V$)pe{XqSt2KkpSvZc11xT}{O9*gYEV@T@rCa@YrcoOPT8mBPaJ~Af`~s9xfF6L?gILt7V}C$ z*#sdJCK}c~0N^)db20wn-IrFUzj^n6OGgcj^Z)GGe}1)$+*-T-C7#}b3codDC&R-k z8Ig8#kUqX({!m82#CF_)8~0TP!Q-@{vKC)XifT;^YSs@z=};`1p8w19{vd;ND!r?B zNNE|e7U&N#I^4zeIq3xUt_5emIRD&D2Z#$+Q7vVEL!rc=YJ zIMmY^qX!x9>}80Wn|ay$QjlCIjqS2<=nSieIGiI-IdIW*j^kJ8ND7~V`0w^a^(1JI zMkwmbbCj3nR-MR0ZNa#M~S zwe$PAi-v<3mY3r=PNs>oqHl&j6=UQphWMu#XR{7qPhxJ!ezkwdc7G*mkT{>c7Ol#P zhawY=DH-0Yq559&c$2{}cDh7V{UER{+E%8mpMaFVs_EpaiSa94Nq5VtZhAm>TgREt zsGB*AQrgYi!{L~-H0xgRkRbG13G;*m)i|t+rsJ zf=bgSbYW$BI=LWY&>yv&Lni7;grWMPJ%=f#Re3{G3APcegv;WNMfGg%BYNuIt>ywo z?B=G_f@h5TQU|Y92}nK;h_f^Fqd_BxMYe$8AM)qln?MFan0ZPI5e-_mw4zx#CrgUW zMJ>K~G;2xt_8+OOB~HJ!I?@icVo=h%@I&E*-R^i&M0;i6Wk!07P+t7^Bkg(8*Qama z*eaO4(NC4bC_>TfemxusBrW>df5pCMe*nfRTsps%;v!cwGxKiR&c40zqSZFX*(Fi! zI;8W2A<|s<=0wfyE+2 zb|#n6J3D8}#c5~h{H={+TD2@@qe9>j2m>30+My1^;J*CkA*otv$9q%m=H zEd&D^f+*D=?GGPT!_nRobt&K5TNJwcoY8BLz9!uf^F!e1tZrtNY-YWu1cQuVu}0${ z+NWBUY5}g8y9YIczHCBCNzoZF>#Wwqhk}_(3%tRp0kOK+lQ7#%8mi3VPU=r%96Xvj)Gjf4=hPp3Um~5(eErv>!ZU$2F}(MBsmrnWG$U;Ngy(YB2SjHgqqeQwpB~XHY1LNBV{;KvNeM~T z7aZb0{y_9r4j$K*ap&F05syKMMYt?3Ee+ne30l)y=+ll!lZmlcNveuJjq4~&$`9+$ zwE67jB;(P)YOPq%Jz*;zp&$xNFc^3pz#+&&i=UBV*i9L4*>rX4%q#v%22E>?UwFOc zIl%7K-bp@^>vr$h+mpL~rhSNaomG=_ZFl%Uj%~9HP=5{hv2-UP+(>a-@bA^K~+p|U#r7ee$R>Og{x`KtuEZr9*LxlZTW;NU=Yw$jj5#18Pwal=#yW*foNpXu8 zoxGwp?;eZ1?BtElI12sg*!9>5f0%lAS29Sf;Jy)iW$>lxGodn(LXXS3_=4=8O((>9fJHq(f(hXcBmGxMB0 zey*W^36tCs(izBO;8K9Z4gy*=z+kWfia%8*0RBgd2>Hyi&JfHCfk*54yiHlAaA@yV zd|o&Z9er(^80>|cT|9vkvQ@A8Bv&Urx=Y!v+Ko`yQjx5xZpG%OT;_%@UHg`tu@}wb zdL!+`hi&wh3zFZSM;4N*PXxl9P$XAZ=^H-IXWgD$$|N$J#(hXAokHb$di0q68UqP= z#IB2g$pd3wvu1avnMW|;&MZd2)}5Ufl6fm8wL=2O_LZF>;j|F*Ct1!%H;Yx76dB6| zER>)fqU~n>JIq6VV{u1l$==v;ALEkC+3Y(X5<12zy+ab*IoH7pdI+gQFCik3LPYpa z^=r)516pJ-<8WDVQ9mAXh2Mk}D6*Pot&fehVPu2aIG*98qB8JFoj6icAE0tQ#U$~ZTpv_bq*YfTgUBUIm>P(x@USjL5dREmBdY5P% z1$`6l<~Ex~x?6gbS<Omcw!Oz#4sK;2jobJ}wpMvnzEhuDU?}r) zhGbsda~$fYJ98y zOloh?+o3PNJ$h3cIW?+I6xP<@9{w^Kku~3QM$T}nf0aqS}&|KY|)B|U2%(s zxm$Uz)s0bKIMhsSP@BBDN@3`xBac~m*{qE&6*CeI>U5BLmskYTsLp{aS&Qo|IPZbKE=f>=r z9jIF}V=5Pl&oR4ZzkV8J8cIIE)SB9wxDwvWuae%4!KB^5+V&0ypQGI@j*ewFi2mTo zxZxutTEw=e=W=Nmd024u9fvjcw_{4yT%H(x2U|@cQ5bl0o(y`)die>ZjAWd4=V3p( zfNvE;4MaecY%V3n-+t@HCI7Z_{M&EcNt`#{M%4TNPg~wrZz-T35CgX$Z-k5Hl(Jf9 zdh#jD{V;3nT)g}I9cbUnYG)fZxM#9^F<(iGI0o^Ga)xU@<~FQ){XX@Ake;6N~Z|9X{-T@(Z^_!O}3W%k_QG5iWV376@|2G?$ z{p%>#p{nErZYS!B`7@0Vtt!8BU>LsKXYB+;$`JrI z)(rVi#8(4~?JfYL-v(!;NVKqmdb=~A)S(yvU{jZUaUURpI|!hJg+Mfb1rU%k*%*t# z?t9D7ibe?EK$HV;^k0)W>As>2jYL4Z7Bgv&^eoLLld{v;kFfHw9a zH@gD%ZD`?4@~?H2amrsq1U9#h@bv)3b}8rJjSy7H?^Tx6vZVyxF07#i4OlVqzBEfT z(oJUgfGUJH9?3%M)1YRn?#FKQt4x5Le4&}q0BU%0;2kOe*7s46Z&BU)=g$&9kPIlc z>GwFqM}XQvcsE+Qf=Lu|;y4lRGE)R}f=`y5yP<sefB$IE2)~{pRl{NvEy@xukL8E-+*J8#AWicaOsE-vD_HB z&$lyqI7LmeL-xF&b@)AZOIo+_6E`2#59Av8Uo^Qi9cb_w_5`l!46xneun`gTa7M8i znc=0?uiY5Qmo=GSzlo5;Jlpc`8L})SXI!H`oLO?@@TbPGLwLrBvfK_?lGM<*R}e1L z3vrb1OD`*#+jYC8H9JHv%q1QkUpQEyO|a*s{}N2C80FFS_8fIt=8nc+`#8f;EPiW< zC#0Z6OVmhIN=-6G>1nEpL*B}!N<^GZ!bDCsf^Masji)hydohWgP`#&)pi!YH*OGaa zwIQgy{M%}Fj@@*bl4y=n@#4wmN3*A?vz@OJUWvSS`z40Z_o32a;SG``e&GL3*yi9y zt8G+6_lXN0x(WRQH-NwKZA3QGFnwMCvk*_y81(PBJQyy_Y2WGF+UZJF;NTYX4XXNt zM=Xp;lG3pf5nhj!-`|y=3^~QA_v7pg@7ycA&1P2~A_+O|Am9W1Gk4xEKwdFCRbCr1 zJUvdI*dAMc5QjP%TB->^k)5IR|Mu5gzG|BX@ZKOXU$Czf0vOpNI7y}jTA-HGsMQ!~ zjv#KCZS`jI_I)VX`Ei56m4$ zAJj`IMcr6^H^7Qkb8Io1P8iMVG{(cxR05lSZN15=C#X2%Vd3oIFmD`9$75$l;&Q(N z17N2x0>bl@xg4o%_r2)-Qv}E`S+3$rb^%5lHCkCW+0?~GYQR&;(2eC zHaEz#U9KF3f`V!|$D-_YjUgxB9J24N2x2MH10se(N>6CEcESq8dH-Ija9xh?e*`Uj zWVH+hh+&eAF0?NY4}eC#Zm$y;0^ITF0p6;KF?jse^`UlHnR|o2oXQi4%5W0&Y`!I9 zAAhxiEZ^MO`EeVxzeC6NGj{?(;E$l8yimOdV&_s^PrR4Ng!83Zd=+ zT~HI$|6yYMFB>SHAmHt~(*-?>M7#MLznTocVI(#MwKo5PIg&Cy8K!;Zh1m2%3hjy^ zi@M(>5I}Ye_a@bP5o=d@=L4$qet*LeLQGOt|7hQEFBIUUnvf+Ml^+IZ+Aqd~Iu@+1 z_mTokZPo|=vGK>Zdy#1AfFWM8h_ucE;3T?=`%}}bKZkHWovj-|@-G1@4pXn8VZ($Y z3Ht~1kPVDr9clx_G{s&1Xv5z){&w`cB>R6{@EV(*MiQf2DEcMd-tm9kq=+9~eW{t( zKQ_x-Pr(UbS_`yDh@rnENNa_xXDBxbxHiBUg~`mn4&h8_zQuSen$DE6P)->I1jBC; z0k~ed%Xsh_G~mB2L5|F%i(A*A|5=tHcu^3%s{flY6wTTCw-^FsCeX`&qb5BB{xiA> zpNqwy9C%m4lNoBR|F(3pF+slD7Tq=gdr(?h^(s^v{vtpTz{1`ZhZUK_$Q1!#a_s_O z{_z{Oy=+MIU5b|i2+HsuQ2t*g(OvYVXDGtj6lJg)dIu|=i+lDtl$yo%8I@&-B$O@+ zzDxR;*#AvIM{Fh9X|C}HHLu4X)$>s>5i}Zw8YDmyt>`OLI0ATif+ybi?rWER`lKB& zIROCltSh?A(YOii z{oe%DU8 zt-&tzV=kE`5F3eIdF&%pMkC*t+sbvr;mDb;c{%tK-*s8yk+LVR#4);kEW5rMJ>7YJ zT_0;atBI0z)y8gMrN8ir-X7m19)+&Yckamf<)`PA+9ET9_)n=avBi#DKi}WcdB(7( zq&;+ntV=HaGf#_^?OrYEH#RogmXMUGfqe=#Z2TDN1m=mlnDLP?std!nptK(gok44_;2#_f#+7X1EEkQhNe+m@7JN<uC%vrF2;t8I?wzXkveMf-6s~vCwNx$w4ChI3pA~plu z?P$rlD6YFX^mZ@BK+}(3I)pU+g|vO8A!fZC5p05{K>N9>UpSG}=^dOy;|23bLQ%)E zAg!wwp|CIvrDzG3C)!`I5u`cj4~SfGwi;Y1-q((qtbO^3pr~Hry(d#K!5b{IBcQT*>%vt)v5_=uDpAx_bWdf;q(22|i$iGFGWDE*l8(<0onV9T4&DP`zjn9gdZo@J(W*olN?~hagP?wE~ zEd)Sn2~Z5&jD3?=Q`2_0#0e5Duo;%tJ^;)ms^zJmQ(;B=&yaxTh5wQXX{k0qq25F9 zyxe0$y8OX${(=EHM)zEP!c@?Y_=GPLnNisurt!VyvXh|;ahlT%FfMYSuQa+fen;d^(lt$SzrI4xxjx#gvv|? z+EIO^EITfG1qI;Oq0W^cx~va2C(8uDSLh?CgaF3>0q~L~{^9Y9#_*b*Yo~iF7_*y* zitt`Q;zbm~OlGtdJh@bDf zQ#}0QsBD%D?)IKUa0$S5F}A&`p}4g{0H2Q)GYm+Qwj6e2rh{xZdQEcr0QXK~8XmY5 zykq4|m|u=xFPaRcrdYsAccA`;iOS~6D*nB){F4F2^%h<-piCNu@v3VKE zkL%-X;9WA``;sTNSoJzkcb%;Wt`0_oe(3 zNV?o;tqp%xiufCIS@B#0$rLR+(H)h8x24H>^$CTlXdHc^?B~Z*p7u5Zu(7Hxg zlSzaD$!Tus3Tas=%y$Gn$GrNFm;?|rKL!{Iu~mLXL;Gk*SUfsk#;q>W51y7p2o~|L zroHrV9{p;hrL_UP8195wWEuG?w@I5w5%tw>Q}}o{gxNGz{bIQwnCrY+r}FjzHpv1!a`^~ttJZ&s6L0{p5ACM6XFLRK39>8m7x zQeT|-+6BY@$b$ZT{)W>kAZfZf?J+GHt>Qi31uQCia&#Qb&X9_;LFYNEGDzI*`&}R$ z6&C_EItNyuJ^Y7e^uKV2zv+ec<-9F9JktY_@k1LRmbA&Yy?&Fj!viyEi6Mqc=ZpIF zwGFpVY^1-4Jq0bGr(iu5yHJv&g$D*m#EE|!Qm-TJt6?Pc%dR345Id_TK0-l;Mrd}H zcH0A(aDNX}yhetjH2Z&*y8H=IN)}s} zN>4f&f)Vv$Mg0jmlsb&~cl-p#-GIx2cYN+Zj@r8&m!A(FAt5(=K8UFxU`|W`AiE$8 zWe^75KQR1r_EVS5!Df%L0d}SKWgS4QB=dFz?*+9w&3!B+;HX+7b!>dO0^LH0v|m=- zYMl6x(&G4wTwF7Ok(r9TVACRP`%P~G4}in-LmcuPM1(3^s~Ss{!>f!5E59EAHjVK9F@5^`f`7M+zmD-f5lqTj5?jT}LBGI< zEK_3;2>|ClQ`OepU-$RlidV1O@&i3Gh0pGdYV2(*XTU88sh$S_n3XLss``H_2{_$+ z;j4ooUI{3)d*zlsPlh#t4HM%JB@dPwX=tPWCLK3SvtrUdzR;J8qW68-%`qq_+yTk2 z=(bi;c&t2}*bk@Xc1$OIOIIk>1>+EHhO(}BeDhWLae1g@ggdeoujA|AfVK+C?KO@%}PJ!!qo`yPYz zhh4DvV$GQ-ozVKozT`r%it4(Y?4_^*%RiSv|I=juPj?o%k%U-q#Zm|f-eF)`nhP#u zkj44wpz%=uf>aLo%V7;SjS{o{fFupe(j@S1t^CxR;~o}<4dAT^{a@8oKXAGWVfV}S zBVPbOGPAi3;GKQlp{rDYa#cQr+5_?$N+ar297Gd-kd<>M|W9Slbb3V>a$r8X1lkV5a2Z%ca3k_GLyFD-+!^(rnQd4_!0p^BHK7?;yHrI;%pUTI7q+|IX z&D!W)u2zg8^Owi~*7qAfP+f|1gK_}_EJDm-S`U6bcWQHd0)k>f8m2J}hUZ0G7EdpW zn(CVB&lKwkwokTQXq`|e$0+KqX7US0gE2x zjY>K`7P&#RZUB~It@N@+8$M2U)`3e?huj2{wHy#Aw=z`G~ z%5?qp4K@l9ZuRviZoN8<&+6)FS3Y)S^-D>fKkm#)dD^BVNn_UX?PR;4xvgHx z(lDU9;u-qXd*WF35}s?~+QLMoJ`ydS?5qQXQbAqv?{2V!V^G(x;6=(;T)}?!0d6Ur zEc}jfZ7Z6m+d!i(a(6?hg~06#4_kLW{A0AvWRJXQA-tgDu=%q+Qd^#icH({5+(-@1 z4EaKD_2yce*}mE!`MU6YUE7<83VE zYBoZNmMW{Sq8DP=J;0qKp1;jpG>akL9T@-0`m<4Q{*ORD#}~8Imar_$ReP2%J<7?= z56^2VUb~5(l*U}`0^IX4j^w#DjUQg@iQWciAQYjZ7MlgHVn#6p5B>b^?g878^gm9P zVvPrp&OOnYWGmhCZBs=mkAC+jM$y}CPF4MAG$w%d1bO(J`t`se62Jza-o=$IxEueU zp~?R=b(SI<jWAxY)~rm53$JNnwLFnez0 zUf=3@h4QOb23MFQBmMIL4tZS#btba!#!tmB7~hoVWd)zDmKR)CW_?D4kYP?FC_QHd zi%+e0%mAzKdArS9vs{qeV5#+8$iSF4QWYPuv#b!gi~9zbb(R{H^i*1d{P7#3LPE|M zR!Kw`;8l0hC&!zvhBEmYR{@1%*KgW>#4rgq0Q$KJP?1<)Dv*e9QzanN@4_Pj2nXtl=s3f=_g(2rxJx8Z z0kU-$6u|wgQLzN2rz(L258TU85M|QiOqP}7y?a^TJ177YElO30I(z00AWmkogg`+i zw19t#w%_yf4}pQPc6tT~Z(d@8nZlTXK>EW%h}8!2;RAeaL2UwPY2bJ-5?H*D`{6o^ zckTHDET%OWI}?CWUp}$Qd--mrkU_{f6Qd`O6A(P>U_Odny8IQoU@xS*z-6WZD5SO^ zpz04EeR-GQLk*HJ4_U2i2&gQ9@yYLp1Rt+oV)^TWiNLLU*u`tEu~r{9cVR(1_?et7 z5K5~kGI6`&A%FL^(kZpJRa&)Mfnyg<|nb@O6qSt^j?Q z*;6iVV^F&oV~pB9qM88Z53c=4;diT;BIRYn>Oz^JPn_WC?vz8W0@at#nmaSoL&~d6 zl_fkW&jR2lnn+$0enuixSO^Q`E-jG2PP9t`pb7ixFAwo80oquC90(+2bPV`gs{KzU zy(Uhm6U53Q1Ocs@;AJIXHF7do2N+J?AzVbkD)!Y3Rvj3Cw0ABdp+L3Uc&-n~$v4^x zP|cd4GqWAKkk-yzKu!DD1{pShU~6nT3Xl@r`UQnjSBp{!2yiZ=5I&VCozYfvIsm64 z1;LuItG7bR@fjktL8w>&5@G?Bvblkg|3e0se{a`9X~x2>zX;G?D*3-Jf(x#h^!o%- z$DrmN5?YokJ#&u+pSaIFKHY2gZP-)Xi%y0HOdrp+m);RBzn?(A7YI^lbwjLfrZB$a zyiK@nH~opLFlu}jQJuNyY4|B!vhf?Eanc8$Q}^Og2i0xr_m1?L+nFD&MX3e(Gpc1l z2-cMdWs9@;5&;qXa=Abmj#ultwx8=h&J}HM{gC_WD82Mm`E%{|>=o_EaGTpWO>U=Eyv0WxyhO%yf|u z^~6cmuc&^kfP~YZ-7mpL3|%`*5T0LpLo`JwGcGiKVyLniw+sqyVxsU+tnZp>VA^U| zDk9Srq||vzd|&nb5fZF-?x|jcT$TB@T6kv`2;)E&5Qxx&g8lORJK`u{$IxsP)|R{r zV*~)+EL#w!e#x<+tXhAi9mRkgx4%|jX~KE?{m8fI#nr)tr?Pxv*xETZ2$~mEB*Cu& zGA4aOHXCqtbfd;vBi_d0Q>;2G=&m~@W0aino-y{&G9pF9^tFflGlfIn&ao}EePT_7 z@~P)U_kI|w?O2pXzcYS?Pt-a)JH)H1&NOa%u^` z(rblQ?Nd;H+>%#vi!;haaq=kG&zSj{Z0UE+0UYn2s8XxC#Raj$Sc}hijWKDzvbeWv0;^(cDxNYf(ZH(-XE6Q%6SbPL*rXmr4em~ z^V#ngF=?b`M^hbD132T<7|pT=A1Wn#uOa*v*Dkaz_fpHJJIod(M4zRU8sSAx+T5X+ zjN!!C5qqDNw3e`2faA%~jCtXWe#9+w@+#B+fO$jM?JjKw?$i^*md(bRh^qm|KJsq0C#Ju8 zcF#%GS}iebp3D_}J>Gbi95v`0j8JNGU*U7$8rz1VmcP%+Nq>{*`YPtB_;~5-)9g(q zb1RE)Hk1snsqZz_KIfGwm%B&V{0-?N##k0gUxgSX36hhHqiOw)%#M%SA?SYGmPm#_4( zYbM!m_C1Zv>9wEJ?UKNG-bR|;Um)%|7Nr2O8Xj0d94{nZi8HnTVkPiuAf83uUz!b? z$KV0JoZ<7&^Bjt4iC_$vyWmOaSR=N;wz2K1zmx%YdiplBd?*uHwC^~q{TN~5G=W)z zf)0RHWa$55yuTG`7#AgYmr2Uqth>wO2f^2rj-Iwihm&*5xwk@SuTQ6SET!dRyRJ#c z8do?p=#)2CsOH8SSbf@Z<(UYNo}^TVj@?*44C7O?TK>9Zwo%{ zk?|ORqfe0x1gnoFMPfJMLBj)lnEji-a3RDx5ENN)p z{#8k!C;z0E1*GcN-AN-)Tu#ftR_7_%AH>;rywK+0H0kCLTvVbiHT$OhOhu5ppwozd z3t$Et_(zKhRuSroHJj)60k$E&loVU?M3S}$jOw`*vauIc%%P~dP*luT=u1C6%sG5b zwFD*NVxyODsge)5ac~z{zXZfbWcf{YnZEJ2=B3KCWf)`9!E;EUJ+lWy(+I+M52DF9 zuYKYEz!4-jOhJ9arwfckwVIN9i#Lv1_9737M>TY>hM~?4`9YlVAr3pzjM&SSNG^OH z3YQ_#q}~{ORcQDQ50cDigtEEumj>bg$b9tQ-13+G{}QbTK>Qq}x8&EWehVQBYFCY4 zF<(;qaFmTN5ID#1`pz)ojdg;=Jc^xkgy^&I3EfK!_LOYLxFa){6&EtyvRK>z82&z9 zc%(C_-0V*yGxcXH_jUxZr&UOM$fVL6+ZS%(#4hz6__pFm1$1n<)}J3^e8qUKlcSRu z*h%q(`84lb+{H{8|JhQcMGNAki;~uz2XYMuOdDXvUUv*5mca+mp{ zWOM%NyQ!4Qi=PIMu3c#?&?-r)BGwrZf;Un!EU^7D$pyV#YZE$G4OHAx>$|Wy3|9Nr zz2BN5b!qco^0Fv|`h2J#^{_5DXK3rMW?0^?@?t&tRp}R!_)zEN>AIYA@<|d!c^-Ue z;c&7&I4eO$z0{CllJyfhoBr4i3&x8+9Z@RZ<%$NqbdTbPcZK2vh3Z!~hZo=2kT<_d zU3`??rDf?;=OL^-;9}BA7UQ!5C6+bYwIY6s_muOdYnXp-cu$nK_NI<=p|I_62sc5FoZb$#j=si3IZ^BWd|n|IU0JPY35y&uFZ zKU(LORDa%;CYBpphn)NI>;4`8|EyI{NF0?@SbxhyG9~W@1im+7nHf{={B{=m$ zE~$+ueff!8M+yzcjvBmqY`^cov2A$#$wU17z3xBg`|8wkjOoZ!tODq%C|RlduSasa2~u{@#9ccfw={R-gnwkUh`dY z=wh{1-Hoeq*fIIZR?p>3jVP9j#8r$40>~<;h%$*Uw8su`#~(f)X0enaH{Sm7KJC_?4(da6u_G6<;+@UhxZigkKf{(DJ#ij|r^2nG9=d{xlKncD^X2EZd!5 zea^=s!&F%{wqIv0=lO?)7THqHapdB;uY7?1}TrT z1g*^l8H;?iGb)=u=on^a3Z_}E%ItTf&)@p2)S%%dJizooOY=KPO%dUY!Oe$#C#+k! z6jY(}N-j!yRpinZyk-$?bX*FQJzq$Z%gqj6K~|bt9kF&;?;kq}J!69>5oj++?CS=#pQhOo}NZVS!NaQmw2G3oNTUH5dIw>WOt=|VL%Bw~-sh+O*kdVI zRj4snvK6nU_#UKpDK(EhD%B>$5SQ&>MrHYGcd+^&nN_l{efp}aX%zP+a3Up9Dtt|M zjB^y9lG%`8dNIO`TOUcXi9-^FFGFGKU@{T)wntZ-)zI- zvTld#UzPFw>8#YkR=>39BGlVh_c6IuBgwl^4JG)zGKJ)UZ(AMS7PdUcCZ^B}t|iI;#Y6WV{m!-goz4pDUY9~9-fcCQ3Hh)*i< z;~XgDIc#3P0pxBaYd^ADEg@F985+(PVXKUOdy_TAJQTJWxyb3}+#rlJa5Yjh&Cpl~ zOJwH-J3dbQ@&fT>IWeb=8}0{UZz$W_9xu5VUl}TW9^{2PtMjla4aR~kOyfJITwOhg zqRbKMr6YMkwqnA?A}3);CTfeh4>6?EP0(u0gjfMOuGJFsxd^I z(W6Fehq76?cuLgfGk{$fQJ zVym1d6$KES>#$7B`@Eo@x6AR7kPA=AD>{&yZ&zbe)w*=~0KA7Jx0{t%N4bxI-P-WB zHdRzHl$C^~MAV@_1Z_Bc7xM=Z+S^eS|0`|YSdM78+ZeN0cE=)W?#Ll5X1i#e< zFd?(G^ff=+zi<6jp!jw?a@a&T`j<8DX=Zn@WTIB)y`;T&Wy|lcb7+-jg^z{f}Z9BeG`5DtBIWiyzA^gyA0! zdF__(_!^if94FxV;T;L7l3RLpJqIa=3X%hTw`ezGy`pqBR{{Ld+e25C@_aGgykER} zB}4Xz^bm_Ge;%^InwE+Ipds(xU^F1d_0u1Bu3fK@G-a6-(%8LL`=XDepi?FMFuIs3_p$qYGSNd zVy2!o!~Z?u>W`f#Qf&wMwGHGdD!;NXbB60FfSLkiStgsGF zOmf{Qm-b>;RWT3ryLUKn(o(c8=BNA#H2M?Xs|4M!LEj~w5;M>}jw()xq%pWY#d_4J zc+0rARDa~k(+gPwY5X+@3+S-(%z~sAfs2zAv9J&|germ!=Sr3_jvKRId)GZ>gf~tQQbpI{u25%8E$^T;i(8F`i%EYLRjU|pv z##CjbTE2I;>y8;kLXu5VcH+x+Z9sVOQ&_)T-gdaYhLTUEDS-bW^E92nT18_OO^c@; zbYQLA7)N_Yg0^sD24_4U>l#8#RN*+nv#=cFrIyEI~>RErzxFkBw|{BEtkWjHi-At&lGK$ z>Rskuhz1=8pOickoK*F$r%7;No%}jusd843X%^0pEVQoMKWv#+mvE-P8d%7w{!j;a zM1(33-JsCFs;d8Fjeo3%N6N=?V?Imp--O2-F%~lH0_K3j4}FokasgZ%bmIfd=e;^3 za*XGK&$1C^nmF70Jh3uz?s{{z6G!H!9#yII*!)^MNZ}xH%8N$0%=1gRc*a(52edlnyuEUmTNLBNBq#~ zaib6o+l@07&gu3@SaG+q2Hkg+K>Sg<1x+RG+uG@F-mDs7$%?oARs2_k!U-M1uQXg}_xaF1mpRw~IY;eU8lR1WR()Gq33l z-GiGf{<{Q%Yjn=n>RSeBvXS@x;cDK^W`(UK7ME#!;*0d`PF>D>j|?cnn)g+n7I)=y zC9+1}N%s3m%BmsHBQH*A=)s%)+D33A=|C6Vdq{=ODRi6HDcGCnlbnwqe>(TT-CtYZ z9=?nkpA5iyjY*KHScVGuvPL83bNOk7?vLs(z`N z$m89i3~_&&7+A7&a+*ibf%QPpcp@b#@UsB5}TsF6uACqK62@PmweZl@BX!#v0q(tq=BHiSk-qj z_#3PE&jO9`Lai9LmjXX2qc4UVNCK5dbU74t(vDw}&0$74f;ZyJ%4zSejko5seU#*= zJmoTeg?RG0GoS4>bHQdCV!~^BK|}Cqx?rjAgD1g>ZF7zlMi?t?$$I|WaU(+CEQ-dn zx>As$xpKwftM+OJH z(`~0LdTHWtn>?4d&@Z=6<=HcF-|Jo3)LFyq)~YzQ!MY8bFV@ye>N&GbBK9ARP&3|0 zrhP&*9&}Im@oMR{y^OSYPUh2Job$szXCKhGXS3JQY^YorUOiCn`L&Uc(49t%%)6w2 z4m(W~c#3tKa=Gq+_+HcjcY-OENEg6%z?p*-(i2$0OT2#&h)e3rxdGxTqJ^UGkZr@R zYLW3*O*#x3#*`DsN4I;aBzztx;Bm@ED=?>38dBq|>J&~`wMiD0uUBsGA2iNRPLAi^ z{WizW+V)K_AA{d3mF(xIGD`0iHD7$=A^6$8UV_(wa>u!wPbq-n3K9kaU3 zO8Yv^#i*cdufGh=vgYGI7{axzq)ZhXxnSRU*KT4a-8YPO{K!ca+b zmnc|+x}d$pzlO(4^*>||0RI(D?DHb{ZJRO^d+861CvlwE#Hel~1+zhR3*fP?dJjPAO zhDLeLryiTl&96MU@H$2VsL&&>@-Rr0IsBq3Kc!XKXbV7?3)6n+b@@KkRP~8+Tb8SY*$}oTs2PnM4aM; zVnc13)EUZH&tY`51N|Q~G`D`?l%&oDlP9u2Mt!^6k?|w$MJPf7C4mLSp6o%AB1bm2 z<1g|2NB)@qI3@!+ohWBCi0N+&Z!*M52X{szx!;=_kZ$G!_( z>6C2j3aRF36Wf>A4_@Icz(XBmXn{f2r}eQeH=dy9`)xSvcx@)?TAz5rTJm* zc9JN~x9f6zUj-%!W5d>kkQ%r({%e@wwhKzk(o-@Usz;BxLU*c-UXQ-DLt$KT8(tmE z*kz9NBD9dwSRxYHQlsePqp_436q)`YD6t?l8XFaa3{%NfZpAKHBw?uOvb?8i19MDX zCqS31c_LC z`YhbLc~Ii`m1`oX7)HbNPvJZEhQe4yIm=Pxeh+?qd62t6?#^XurYAHUbh~{c;UYhB zI`(0H+Ryp=AoBS6jC^X5B-xZXo2m*__4$}=AThSWba zxlBoAw=bS^aPryp6EmkZ35FM`d$@6Kt7GS<`FdP*b0J1d9fEzrev3v)DD z+3>B`WZL6wZ-w6|@3%;s-nIGlaPLv4P9pQ+8R{YP(c1WwC}*Fvo_}2KwOz6*rrSE) zQ~w`b{}^RS&~*!=yKLKLmu=g&ZQHihW!qMlZQFKrRdw07p69%0eCOWt-7)sqKO$pf zMr6c_ToG%|xpeadBv_Q(vroV*XEZpi&U2osDz>#~U&E%#Y3IZpF^ked@nRt{QIg%e z)vvK0%d5M|*+MHs_6Z;RBamZ(_NZTMEG;G76r=TjvbPt9AM*&*D_EJ(5zB33d27{m z>nRfI(S1GY@C)7BH(di*n)2z{JRr>@9!CDjPto)sH7gxu z{}QaxiQ-~5KpNe^q}+(qU^`v+YTVlLFuajb_-(mWRx)lXVh4Jax#*0X)Ep4 zH?A0xm4a+;iSEPK{(E3^ETK=q=$H0A#1KwjgKHSzfB4;g#sLXsFzM}cD+`9Il)NlG z;jO$;D6pknP}~0|GSE$miW5fER;R^e@Rgdzsw4HG3r{GU>`4aQRL@Tsv|ld+kSE%6 zDq5N>)@s;Sic3|u;|y{}Ph6rX_|MtnvS98A?EiqE5QvHah`=G)r~o4o0B0IRII|5( z0(zgbQW6wosz7+{`OjQ@y3P(&Fz$^?MH9Frcq9J85;{;QpA9J?2O>WflUqgKIsiDh z)+^Z#zklP1AwztB2(aj_8lx%0WY`xd6xNZYM>9tVHhmVP*7s==be?QuCfTOE<`9NT zbL5LRKm1N-{@S<|BAz4&X%GohYz@o`VZkh{RAt=v>DHg3%AK6^x~{rq%}Cn!u%k(09KFr^xo%(%gB~k5m1BQ_<0|m!K+cgd9Go|7_FuWI-mRDSGBRZ=2J=xB{2;S zeu}R^>nYAydxPWn6qG@(b4=KAEup+J$7Iiph`D3@aF}AhF4IPm)#Yo%YS!IHM$u5%3Q;+7}FDRCPUB z>EJ5q7(kY(ilDllu=Lo6YG~kU=W!0fp|lCMk03bg3{iZwV(ZbnL6JUU0xJ*)ODdKI zBe;Z?!ge08MR(NIXHD3TLf`CF9d-pg1#d6E#V56s8Bdo~Ood@t0{eW|WEs&2O;d8* z@nm8Nn&eUPavM#$huLsg{L+pQhVLdQ697=^Q~CL70c-!f{;B^T&++|BH0TGeYY>Px z=yU!yUlxUUIczAt1WHN-Xd4pM@m6M-F~Y-p0lg`HY5=S2cv3!^ybN_P-1#1!W{8O2 zga76MT7ja7pbhqU(iin{kI*$&(P*d6f+CX|rPx-2rdv6$++KcAtGpw@2%%+5u=}3r zW4jZ357YKat^RWayYC}H-@>^b2EjmbjLGN4u+U_Npi7^jnSb97b|`n@#h1so=N)8w zwqtB9o=F&Z_PeAZdT~M2tW&1 zPk5(M_p~W^+oi0=zNybEsJeE%;r_>xO2EHAHW)g(Iv~G>q4l_ybxa8hwfgqTMFq}sWDL{r)^&PZpqe0ye=aM|a|^VXVRJ!Gp?(bJV77>vQ-&^afag~I45=j6 z%^v_N$0w_%$AX%a>rpz^4-vHjt^fj}%5u}pyhj{S8wWawyUA(Bl^r#U1@o$3HXj@m zNaZp2L?fAmyVn+6KuSreR!ZXqx&pc@u9=|@cSAhGaztCChF@XM%a4L943EaFnD6o4 ztfgb`i0{kr%O@YOo|s-s>kYJ$!~*r{*P-=x!DMvGC7GHa<@+OP1;09YT_&iK@^e6e z$M|F2bU)MU|J=F#s2xeC%mJCVzf|UNtS*?H1OQw)l@NdAjDguffqDoJ8bX(D!eWJS zr#Ks)NQcg3MWC=KeMtAfpE`hI4T2OSQpHYL!XhIVz3dF!#U0^Fo%iPouZx-cQXOG~ zOlxFrNG)WWOt$MAAEY9IX(uoe+!Sz_8g|nSG&4yy51^ z=}>cQ$+7gticOkfm0b|6-bZ6OBthNFen|@+jzQPCl?5z3WtnNn84dtklbd(wR82aw zs=|(9x+t^Us|?YNgKr0+=uJQ`sF_GcfLn%LbrMjJs&Qzguz{Na0NK!bye}k#IC?`? zJb^hE)lx4(DaILsw|A!(e=(A0BriC)hL|H=&>G_m-5)PBHURKncs0w> zbU92o(SR!d55jWRIBx#-hZ9-+-y3`Ulq7NS2K?YhABKm1tp108;76a2dIV6ygf>@6 z007AMe;V}@@R<2OcUb=kc>Gia{5K;j#E()XwFXq$a34VY2SNK2hHYJT^;)D4EkCj^ z7YU^{Lh}337A5Cq$*vATOr!Z%8HlE}M8pu@-lAp&#(>cmC2E1>9<7gY z$c}6r{CP6;r*odFyL06<7kB(c=+&j5^WcrbaMkhvRv}GRvWFzbcXs_t?0*I6Qou4f-MQH=F8)y@! zUG0%O@gtD{%-9aW(T`Ekgb2|3%}VrRE0Kbkv*7CXWC z{1{??h7$y^7%pydvO$#g7^*@>bN)*8HXI=|&pORcW3{@+2RVq9R(xfT3z&}jCbPOM zzuR>dnnfe`2`FNB(+B)?fQEn^y-wA$p(gW3W^V80jpRD$=x#X&>kMO36#)3$Ow{=b zHx{amDMI3rjfMuxk=?Wd;Oj?5b|mMC5#$XS08nV%+Csa`4&&i>x?i^uJm#cc2!W<_ z@K@WX07yZ70I+iOKH!GA_(aWifR-Qt0C*P6U77knAPVpc5kKL<+ta!* zcqp{d%lZ7f^GT6x!RFELS6snwDL{lId>O_J?C4ofXj(A5IWellSla+9CL?XQ{czyj zPtqzbvVFFwbP52TlY9g-ol7o;Cj@mcpbGvxUR;Bge`5Z@oH~2BBN_zM9+tx*2@N zp@Ky*cS%1E#f=pD37RoGU=l^hw766P4-2p?u?NF!jpIQk47c>ztZHkq=WXN%J zo-i=jLhHqEbF^FYaMXJMh>DLM-?MuI0AMOOTLQ93Qq{2B6ab=UnUX8e3QYK)8+;U9 zbNvj=j>%6}#r`Gt2O7Yye4Za``pImXyL0vbedh7sX8k`))-NmcC~XD+(D;AKf$%`V zK(GN4YA!6$rQJgjND4reuqd6DzX1TVnE`dMACq83flccYw-6N{_0o#wn`*jGP^D{TJtR_iRI%RBBPvWT92r-KB;so&h zhU{J0=MRiYeR?qYSd~hX1y!DS?f?3XxyZw3)ZVz5PZllsw{@Jpu*%*^7d2_^8#^OnNgXBsu~mk-p2JKAL~T#H$5qSyvY z-=2Nfc_K>$lQ*I(li@L;O6YKy)tGV3?lh98MO2xGy|%d_s<7{)O7eYthE1DeSbb%4 zZCp3RL&8n(;$#k|(|YkgykQaxkXQBWMn+~nx8>p+855B5Gyg+i*M0R}P8s-~=kmcc z79f;K7iC3%pc7XNqF;S%31n+6*)*eh#)#r5Gj;;TGYsOt zrpdIAu^-%AZ$kP_eeiVF zW7-7PR@kNm!GO?1R-nkNn;CTJZ;-md(r5UP2rVLm3|h;a4MBl?!Fm~&oXz1a3E!{l z8u)6B65pF>IR%fCb~6oz3oyqHWo{iIKv|CR@e{wlL4k}$grX-U9iyq{Z5(vLxlV0+ zHGAH2U-CO5{(fSWfwo4BS-|_&Qo{Q236L6*059@^YTAfKbdkEA0KMYMHbU#)e?bSO zt5sJ)gguZ70Vy;N!yqJ$(A$UVQD5@b_UNo+10&Myv(zNeS<~oK>7(0omp`%(N3E01^bDi3=fx;Ot|p2MwJ4anMbhEd?KQXF72G zEr|OR1=za1smStQPH8t>n_GFeh6;0z70hFng*1)>VcE}{Xn60Pe(yAzo8a9hh4k+< zqZa!}nqs}VszVpUG=PJKW7AQng{|WYt=pt_V4N}2Z5vfz0lPfGo@z5GE`F55(tcLG zI9!r*{jVVA6Y3Hcr-6z3|B*V zr|@KGtpLth#Whhc{MBn)1HmGWYN)hQ;gwdrh7ctx{<>mo#}+#ETY}!zofM|xja78F zPVL7UhOkP$hQH3V_6ke~))eH#F;vWPZ9*1tAdxP9Ps3@76aS0q0}O6ythocI#8;(K zcJj-d4)CG3Rle1MW}06wG@j_xs7Tk>_{2WK7JqAlKown*#kgh$xuT;{S@TqIcd50s znwjvRZ@087yV_oka zt^|qOR=-;p8*!R0awjLg_BIj;{vKv-7VjF4Q7*9}#ib0qts!N*L%1hdZwj>a{zbE9&?BtEIiG_J>S7VjM#9 z{Kuz~^~JYW^U0Ib0kVrD#Ibqt-RGi?d=!Z#9}`EE*(F_3QTlB5M4aZZ)=%8_*-4el zViNZPIsD=EycxOG#yCX0an$m6twwSM(bFO;eW!gCksFPRoT3TgEO@;tM)CZsnU%Vg z;RKd>m!!ajgn1@gREsxo?d@}$6P;@w*hEWu=JBEPh&p+Vf?jV~hh;`L7p>S>JcD&i z)Ip&Q|93Uv2MPMi{rirX-+MmFZvCfZ9L0Uv25~l|dK!liSaoHdYR@-s#hPM_<+u9V z()PaBpo{!hj%rDiWWh1M9RbRbUnRXk0%2we(8J6bzHJ2Yem7w^h;zA^AB@i#@CYS_ zUKlr4EN+yXypz}$&A!d0`taXX8TQsT>gjLnVBF0O@Du4iszsndV6R`!&ZcdigW>3( zD0&$v7oM1b)?bFmD`ngqLZeKQBNQKJT1f{@cdB0G?(C%m4BDcZ(xFb&J6b2uq7?f< z!?nK6bh{6$r1|qXX$UW_$9Cy9T7Qz2J>k~Q1Y=JpojB$vBm>l~%AxVyPkcO)rb5dP zm#`tO;bSIuq<8t3!jt|43PUxFfSAa3CwPEGZw22_b<*V_S|iDZt^Kg7?<7 zpX`q}CxzZX8N*-uhtOV?vYL{?@zI2!!e59zPeJaE{)zxW9yH2CZq(u3M^YX4&C?u* z;!0P_H`ce&^NydMjK1fw~ zy_688YhE)q_(z(CaJzJ5*CmbN%#c&0B|nrgQD;Soo-{uKIz!97Cj-H+b=oiJ>qt^7 zd7Q}<)6n8Ntn@AzHlBU+>;PR~8w71hg;R7BBsi|6Q9BD8L+}w1+6nOeh*-Qn2EtcF z`5btOn79{@3YFX>Y;inV>gExQN4r^=kJM>!QPQf|&X4l|W|(P(+7P}=!3e4&+&Q@# zw<6(S{Ei4#+C$c>frN!u zC7>?m8LIfx8;x7mB9fY@Zm0>_-W$66}26^WX8Q-ySevWjePC#niIno)!wF zidEcbAa6PxHbASP$6)ir&AXQKj+K%T#2KH|r~a0HhWTWNrXtsTeBe;Y#PgwS>^a)m z%z&M$f>6;u?6_A4;$4rjfw;*HCQd~2){_F6Rac3BHo=TP=>~3)9GcPaxVgDa*=(|j zEBDMxC}U@n1ey)_y;**@`9Ez;Q#Ci>xO2SToVS$@^%S5422qb8M_;|d+n^F0ts^Y* zPSP1N%n}_8!Sn2@se$o+5n_7=hj$f>(+qD~j41*q?NlH`*YUHhP(&ke&Lez5Z~0;0 zm3FCIOTyQYP}Pih@(Fn7_oI34S7VO0xa|E~5o?E-BiZ2+5TBHo`|Do%GDwaRGx9zu z@1<(5h@C6@&JdrMG{1oyB4ukgSRK z)w*b~0n!=FM25`x%*9-BicWhQtC@ff%Y~2kcr4LLjObY~A{#7_mUyt*sXhiFxkc@G z$xd``!720l&)xVvhF&`Ty}gLqa#b3kHYXN+DUGtuRNC}Et1Hs)!&CcZ;2`{)!!&lK zj&l@atNR3r3ooz&e!TPD_-&!3Zxc$guVky)veSSKpFXtj<+cSbJh>J~J9@J^{%$|H z<+#%Xxf;+{fP)JJXP-hQ1M+!G+$}2uokHi^h6jaET2d5oA0>^8>Ei*Yz)wQbE=19_ zWu*n|*%zp`T2UdHn;Xnz;APoK)Kn1Rb$*((O+jU0A>IQK7u_{kaGsH6 zmnhZ^d_i$CQ9k*wAoH56{=m(J5iGOM5D&+IJQy{aTsa(iQt_@jdav!o4R>gMc=qSh z#Ud_nS^31mz{)SSzbLHIf*o~z`;0aoIJvB2K_4CJ%q`*V&zL0uEKK_wR}^iqa%IT? zfK>%Y52bI4*m!xmR1$z6b{@3%Iz-v8o|88#TQVF+AY%++rUf8eRJD(gV#I3YK}WFeZoOn4iWLOX%l5y=bkN`F2bFd2C0+a635$jn2z|wgzYpfHyH3Ldo481l6&SvDS)1 z|Bc(P4qYd*PoHGIhk0A9q&kw0!tC1tV>9}6J$N$CkPV_ja;G{+a$!KniUu0(4Bf~- z)u}=Z&Z?s+*B$QfgsdK)bR0{bytE1i>lQzA`+A?_X0EIDR?p4scF9^Qgun6W)wY2R zpCAAtJz`wQm?HVN_UVw_m$y0_Gu)=#qStE@@4zo%kbuw+9yO&cC`BLA271)zvy4vi z2#flz4Iv zD-y}f^sw#>FAF;E^S{4!F(3lx9D=?-=dGPMmk6Xc@>jA=6>q?;xJ3&A`(1!J39-2e zW-dsH{F8|GTym1U22pK=7K4QRg_T&SF-K+XW?xEkNpBf;1M70&KJJ^>=PdfEkUlF) zcsah_zq%}EI*VQhQFkIXDTiwB(5g{xGAsv+JWkMmsL<8QGbEg37`sC3JP$@p&RQQ{ zXLE(Tz0oRU^Y4^f{KhxJ1`gItYK`J@_ep#U7m_WTlHR1_hxFPKDIG4FC;P|Nj;`fCNLrvL*A0hro}}B^_*rH zmY0KKZS9s7Zexr(q+i)G;-a6gcT`;DM-kk=ljPUfYt0*rd6U%KU*0{E5VpNNlV%lL zw;G#&Ef2VEv#LoBInq!5LrDN!z{6n(Y%r;(=*H$Y?xdZ=)K6)K(?DW~UZMkUpOZafhZ4Ac#0ZzVd zUQC9n;UW2V2j0xI0Li}E0Ha+Wp-TTf_45&`%m_MhmGl~x6-E;qp^)=Yg(qbeqn9}C zxh}r@h3AR5x1)=?Hri;1c7ZGmJ*wKZETLpIwCf+w_6&Z{0(Fa}A{u;U z9jPI+t_y8ce(GS#aEi4DPNzfesqCAZ+`U$2E0wl9yy8N6rNE(N9?L>P>fgT-26hHl zTxpk+*w*cA2zjB}Sv7C67$4v(YPLaFX-@`9T8s1jj3yiO>#yJSNNjp*r+k8_=@XWi zoCB@8%gpngMfD)3C0BI}ssuyKZ&y`>9g+RMbUX-a$n}%bE|X!F!G5)ODusUL$Bzak zljJU@exDy#;X95zN%!A(PoFCNjDSb8PP2k@Y^IhsJ^m#=yw{maVzo3NnKG_ zp*LwDT_!v!Xg2~3IGwY&JFEw4_T7vecOB*oHPo9PM3EGm`AVZlP|St&G%*@eUaN;x zk@%hZuziR-Qy)5k#d6BlD_unSgAV%8(+1QR2qN~eqBS?`ZMMIJW9}LE>JhMlix~D6 zdP8dji!Hg0aj6LPW@X0*@s+Q#vswc^Ob~@}q84^5P_o1RD`?IB3;2{}3A%!R_(4MM6latzXssKv9K|mkl?-? z2Q%_<7O0Yqn3fDmyo4qg-VJw6NT5TWJ#WH!J-^`mX7^tZl$wr%e`|e3TrWu*;_p zl>AvrK4$IvHc;?>iv&v=&Rd(klZd4p;ju}2+lp(^eYegxJA@^zny(W@tRI>C4lQD5 z0>X!FfG{dz@-hCNH>fV;;hH@p&xeAPa`k&SbBtd$W!>Ra$p+#bekZQ$=*o){xFkyx!pq4>9moc!g24 zminGJMp~XV(iXyK(0b%6p>;zmje*U%Ia0%a)j5MvjmUnnZ(ps-BeuQ?bO{RpM{2XH z(`Lc%=bX?<^)=KJlC!)Mk#`LD?B(nB)u-gH&^qVFnR1}bwfng~eeqR{HEbVp7qVT}?cGbbkpmY7eh_9%yHaF^}&v z=Q?GEh((M;7Y*p3T}mx5csbY_ZrWrck@D^ z2f_0N$WCp;@3edPg*{r4nKN$MHblKjRfIH3%i6e$x`J~wrZjLI)HFqxvWgzip9564 z$l_q#q-g{qok<(CA~)sbxC$#<>y$5BFg^5A?(>~AG89?(8ku~hc*Ie}{9Ur73z`2b zEeX_=DIfsxPgbgX+6Dmmu5m9IfV9WA{-x(Q~RvB62!tms3PLM_JPd95D%( ze>G@j6wQI7@PZmq?fT!hTY-`U@(wa9aGssbiy3U5eoy4a>OX;G=3u!N0kV zMl#5z1JPI%>O^C=V)&s}ZK83ms*}7d{v;0pw+?F=MT>Q~dt-p9*IwxH)X^g2ia+TuB ztz>nJQF#-Us92tbDgJFCkKn*AA@xMzsfs|vEL%kb5XQ`kV(3;Ri#OSSjXZ_V4Ua#~ z8r>1|UFsny>aeU2-{8_Nou>3hwcMk6)m+GFu%9<1eykYYd*mSR78FWiwJ0e*D;Rym zIj3RWMLWYfTQbS>astWIb7n7fb;WCby8)KeeL4+V_{Ys$&V>6OZA`n7*fuy=|53{m zJnW2SEzrw=j}Gpx?nngx6;Tpiq5SImQvZf~QFDlU#=~mBgM5fOy|L?!$S;VvnkGdO>vc08PJ)29ulfu$s;!1l5XWJ7h?V%yO z--wmZro1Qa_^}4mDYkLUUz-O7ZM!CnvTK8Jx=n z^4bdR5?XI46TII*OuIAK`ZEYXT1Lj}JTc}tyJ=IJ$Y^I+mD}Tl}%0)TyYf5hi0m^IrPRfO>j!ptEugu3bG;!Cx-M0 zU^D(3Z>U}oZIIPKZV<+>A(v`9(EA;TnpK2~$FXri3-$=tTQWmMj|GX~Ey;c86>1qC zBWgjzA;HgGrT{m@lH++IM9d*8Z1n9=lxedco29CJrRuzYk+fxZXt!yNQap!Cg}NWz zD{8Cwow^i9y$EJBv^_}Kfl1loN=#;qist)(IAL&p=b?IQ?L2JPaTTE*t&aRE z2|`Nca>F4-R4sn&clX;dSXmTAALe2aTtTfvg+~Rx4j8}GVjk}{6Ns-2H^2qK{2aBt zy|sGiqj5+r9(LB-@FQ72t_aZ!1a|(ZYkNCVao8mUpIfl~QujUQM@AnG#ulP@`PZpJhc_7uJf#;4{X^4fF*UJLGe2?=s z*Gqn>XApOBv3j!1^L@=Zh~K0i2ru=yao;fm$0Bn`+e~q|c@F?BLNUv_nGAoGW_K7GJ<0c9W}$$F`xdWO1~}~n8QE#0b9HbzS`X9|MtNAt0vg|N zzA7q=zFw-x2pa5vrZe$za?W;;Ca3Gf5|;EKP(sLJcC(=@*5k!0t?60J2WOIrJGP3{ z45^0|+#8ha)w8bzAO4R8!+};39w54)qhCQSXUGQm5Zl!0<^FoQ3HpVdxusyp_Y|?K zOyStCWQZdun>;fw^!vo&G(bExf(4Ze-d=|*S_c#%>0nO|hc6~|XuJ`0Jsh8d>x(CT zVuonV@>LRd6~Q?a=|c4t&a9z&ke|DV@HsLvC_xXBV17JyN4dGYRz!YmS?PF?nu6*T zdk`1p85%WOjF(N2S59?r=_9#cNs3V(tt{crc983(@GRE+GgGA>{&5R)M(K!+(w#VUN`b zq@cuPEf3oNYo~frtR+YM7gwRrVANQm;=g`6d|1lERg%4lu`Zqn1Z>7Om1$qmTYOp+ z83p>Ykc*`v&_4YuW z>ow!nj^ zP>obx*}?+b+gz^i zlG4qN+H}SG_UDyUzz9mP_j_0Tm`5!+%9ZX5=b0Eg655Kf2SZbMe?Mj3TM9e4)Tpx+ zlsbp5fRlc4z{;f8Kb||xsoV{3ORg<0`ehF+F8lJeO9CEp9M9!2@zGyZVT+Xu{+(ec z5`Is>I$7#g4I7mNl$)_3W2_9Uw7Wxhl}&=vFm+F9=9l?fdX;;oPlGqY^L5{>(kch`czb9b+pz zd{~U!OzZ#QBy&+W*y@M4F-o+>2wc&Y0e*Js?%$Jk$kdCM+qz_p)1<#+jn!`6t=EG@ z)x7_`O$*nwb}sDc{NdtB)oeys=QI_Jr}Q>KXVSksMf@I5uh~Tcg(aglPM=bJIw%MY zo;qBjF;uzf;#i=L1>`b?^eqE)kSHqln-wYc*i+ICH#ib&%gWXK!wJ|behOXL5aP8M z0w`k9_!NHvT|ImV)VHjGZ0-4T`tVR=+<79YQnnxH4WV4?PD-rkQ)f;HW@|q|A)BSjMnUE^al+xy$x3#vHr0@g$$jPMw0IX}_< z*9F?dWdOc_8*Dq3lL+o(>$#MaE=l@2CA(V%3!AzAP~Cl=yV~uQk*n9|58ZNN#>FP8 zJXqKoLrqU)AOB+SSc(ScuS=i8nLSnKY)I_`++649t2(NA&1XnA0q}S2 zX-z!R@d+`1A9&NsasdVw0C@4C&eZ6s7%*4o%*-MRyZ1Yj4Vg{8?VvcW%X+Rg!h<`;CbF+K){;_gvW73 zoZ`jO#V3Rkrno#&Wk;w`av8?f$As;Pqu#l5C>c2ee=rKrDDWzXiK!t{z3``a9f$*0v>?kRGd7yBTQN z7p}dot+x!pT}EA*JwD%#`IZO9Tp^B9xu=2?wANK}{4hu2fN>DoR=Eton%zQ~8B1ED zyxsk2ZGuw#7hl>=->}(ZFc5}x)c?@VkIpg+(ZG1ddXfH~mgpzNLv8=A3}dJ|o(dYT z0NN3DPRxw_o?wx5RtXl6Sz5{d`*!^6+M&*V=#SFZ$Dk{Cvq$sj;Xis>p}bk=tp*U) z&?6yuz00?xoSv~$>!0N0mBr$J@>lzr70)jR-@Sl7?vx!bCUoI{XOh|>#bt%Q)#tC9hQxuW5Wv^I#ibmEqqKy`~a>$R^aE1i&5PKYvmBw=K3#))v zP8gYB1+Yy>E_St%q%?WN;D6MtM$EfSK&`Va3)jkU#;=ZIWh^RK3pP)fblQ#|G~&+p zg0ei&6olSu_Z|z6vNZgF)PPTP(lRUrx{y{8M$o!a#M`R7LWnq9eT8&E>Us`UnBem6 z>hrACghJ%@@|S$WzU!X~k=U(<{Yqs)Fc`sHitGodCH+EVvsRns`67QS8t1%WkKoGu zV|#GUJ!v^nuC%$9fbn8aUEwRJ8%jb0IJ}ka{(gNv^|Z%JkFlXf-Oh6@A|-gsjN}?8 zx>AQQk_aCq2CG|J_g8L9DBe;BMdh5Zm^We-}%=b(7d|O->0xnG0)>GQ84H*y)$4MJo z+^=iznWlDg97%KeQ)*iZ@(B#<@rgK@u}BFsdP}#l=Jy(_7?DJn7uB)HyLpJ-=*1!y z@7emD`V96Wl@Z!M6h$#*`D9SW&vIr<85s8U;#M6B2-!Z>Y2(l83^z;0hB3vrAjuEn z0CMkO>)pbf29bY~p=em6n&!$RsnfV_+`TRV+g3;zSRZ)yy*kSrbmx^0UMgPhd-VaA zUNTABLNE6Bqe;iirKe6CW)>}D*pp-5OO6Eji6u-;;5M#9ilwtfUomxFoA1Qa$i7p8 zY`BsZlOkVYW;uwxL$+LUZx40iTS;SnRN3rD@9LCVPsp6v zP4PvSRtAiiGsi=uEO`q{o*g@VddzdnJP;PK&5CaUrfgQTs;Higqj|hNkb(XMqg+Ds z6)I29W0wq@#yZCgMk|*vW5CgD{52T`o_{MuU`@CpmhJxP3U+4S^S8Y;pn|xXQ!~A3 zeJ+me$({Ij2E#o$Kx)@|d8?^g@pyXg5SOHeFHw$QgOQ7E!fMRh9+VRdsoaa{xuW9il5I{KeR= zNcFL>OUWhlPHsvrWamKz=P<#_a+>#WvAX1#|AZr9mvx0eXGlE4X<1t!K@eWJ2c)Nn zd%hPZ{&V}-X`<-Kt_GqjOHgR7x-<yataw4ui- z#A5ovk44>2x7Nfk>N0!fx|-D0sO}DA3hw!m1=H~4f$>%}@CFRXM=*)uOBa;kH-&dk zYr^3V&X2ysDspKd|G+jTUCdyZjAV-zDOL8MFUgM~P6kU`<`vz?UsB}_6-bY^eP0YC z;P|j1$EIJzb00Wpln0J+xM*Xp@vgF?MiiK-@(Fm^YmITB?ATgdUDjV6ttY@DLYiM3 znn@>0X&my_(xS=b8!#jbIXCv-z5CNt+|zF0IPeEAX|n}{INtdK5R{=zMp{jC0|+j8$&D4={J zETiT*>$X#`CTdgRzjjDa>h&cznYo#i;BQ8ih?LoiHT(( z|NKiFocEnu#lYf7X%z>B9ZUd=uS9ps4Q5$*;7go=dLAjD!V5WR%JtI%(=sxhJQ^%9 zR^$U7jpbtN&zY6!z8NNgx~`h4xJ@zkE{eBN-9-oKcP;-Tl|7mWbDIqY(iC{UcAk4& z3IuGa1+WD#e>yVt>2xl=+CoH5P`G|SMu0oI7C5=CScR9vo+pdj-}w8lZW6K%PEa4> zDS@bOQLHgi1DP*$;$LKP&b^|NWnfihN_8Grs2<@2m#_(w1rr8$&Rx(TuKS*ex29D` z@9qMLUVh~?f(_R}aHm*l8c1g0Zi5C$!`K@NtnJRk@SSHw`axAWloxG)+fpviXd8Hg z5*&o#Sdt8?|6c+1=%p5oTsXv8&OzkVS;k9Gu$Q|lVMo{i)X3KuG42~i{>4S3&YnLV z1ZS`(7-1KYgz{y)HFbZJ=H)fpK~tC`AK3p%ON$iwwqH`;t?1-7$UZ}WjJ<%6sZ96F z3hFixMj~Ymf2AcIc7*Xe;zCPjqThyuRw$b@Rzz_J@GN5JX49^qW+Fn)&q zO+9PYrif>O0iDAuqAUX{cgZV=xol#?KmQy!;cHs^JpzVc{pIOmsLlwPu!tF_!cV5# z!*wA+V%Wa?Y%)G*Dux)G*}H3z@1e{3H$NGPw?{MO%mRl8x&Ltj-n0T-0SzI|f^VEX z3y9uPg^STtnrKKHZ8IzvdF}V$eIJxA_mQ}0F3vLT(o86<$ceO2cPFNu?!$xcHb9Ak zNj1~gr(=msv$X!Ug&iJ4V^lkUmmPc-1?=GQ*3SNr^qS;L3Qke2GC9S?u$&kM?+;0A z`!=EVLw_%-PETyWMTzll7~KT_4u&Ww-;VME3He4~p=`bUxFf3#=I3IY*Id`B4S^Q1 zZjsGMh`~vQUT3E7x<53UjZY;JP8^-(rPoq@DlOcE%0bldwpPi;fT8wq{5sA@{7^SP z9aw&73a-WRX1)fFR5P$H)swd^gFpyqjE^3-y&htV$ZTe~7kC3~ny>Rte(zqz|bGFWgj2_!7 z&xk}`j0xiezVpRQIf)$@pN@}mJ>-s#6Z<=J@$R5Z75eQ;Lm0xRZqh&9uRy%l8os;R z)f`)saUxL;!(+e>7Vv1*Zz$rC2C;#HNIi(2X6! z_sRr~i^&_ZDId18J|vzu9y0G#FER2Jen**Z8pME|-|^b7^N7bS39# z*S@T0=XE2p-na|7^!)izxP=$j_F}FQpkrx;W|t~ z>}L`T?5ZxtP7uwgo)PuO7c4tL-uyScaMrkq7UeISg}FHUKQhhs+`3=D1JfPV>D$ix z;;Az}SIrqXA4T<*I@_($=9YP=+0j3TMq(;#RP?o@4EOvjSnh zv!vvN>89Ci(mmz+WjC^PuQk@Naa>eKu71Ih{siY?Q4cf1qXhY~v4>Xa-?Tb~Pj&hk z@dv*|x}R*k1rpBlJ(RXb*3cyyvkgBLaDG|%GVw17)lF`rRJZD1n^v2I`5x~+MmP_E zWn2?EPJ$f$Tw#{D%pAzY@5Xgxv-V@`!8q4sS6oFaCsh&=z;%tZMICcO$Us;oRQHJ%ZV){=v-KvI0;G4913rDRfz-#^*T09(y?zxoh)Kj z=mqqpj1%J6swfr=^7yiDLSIHy5DX16C2ZR5C|A$uq4~o;nnr0jv2L3rX~+6rz1C<2 z7S!t3hN5H^+z;wZdzsm`qb!B}(eu^{E@If#$Xf2%6~mso2GlDw5P*kucwdh~q~}Db>HdYb&=hi6%U4)o~@Aw$ON9Q!L0# zxSYH2$GerxsEKned(i%xliXCm?7W>bhj%}2@Nx0bUiy~>EZyCeb+%`-mB|*oKa~0y zbYhz9Wn7g0;x+-0R9YzQ`m7bwSQDdtOn?ZGce{GRuG+vmJS@D4NFt3#N;oEx3OQ50 z^J*|sUXxRgxZF|=pg-dp(weU~O)TU0pM^@+juRZDWXb>NPJ1CyF%%!zdHIHgz1pVn{Yy{A>E_sx*3-^SmpsUJ54*DP0AC3oB2op< ziWnPkh*{?@x~SKR5B7v$JwNXbXB|xT#4n+}%k`i0>1cHKW~vT|5nx0xs+tf`yMmwiacm1B8i(C#gvdUiZs#^U0S~pOf7B zmKkJnkuc&=6<&9YG)~irAg>(asZrXpe!-i;TOqwkLjf@K;(zY8GQL(rJLJ<#cG zxlv2|allvvbDzI{6;}cy!fqZ2&`)RKE-r8_xTET!sdh1&!2Eh@h!fDN-kb~etMfe2 ztxY?Bz-F)UBvVgcp6`;uDbL|QSzV7lF@8Mi@LswyZnSy{E;Nu78rt&rD&Fz54+j%P zlNo+Y*g`U$WRL1ZCpv_LUSE!ns82r4eLBW5fH7#B=kXAqG#Pl1RmZ4+m)c#yX`_m* z_a{Q9BI%~Ut6>Z_l;qb+8ta*5+p-)kTUYXBT~jzk9^3>0(d&R!A=JT9+GrLsqL;!B zKVREuZZrv2)QL)`9&TP6D|loBsnaxoi;^_y$_#@o^E4a9*g_( z%d8T2SW9`bNxnu53Dp?$%{#))4z3C>X-JrStXVH>RwYw0zs(&a01 zN(VqDH6-6E{e3az?<@8Ev%@AIB_@A*N|_)huv!5d&+ET*saMigkVEiwpiubHOv ztW~KXh39~>n`if(^M7Bo5gKS@bzq`0^q~pATcrC*Tp_pZlL=)fpS@0DZm6q@{Z;Pj`+EGB#8KC)v1wma+O?`r|!4k`1MF3$$asU!ysMc7dcavDE;$W%$zsaNMbgX%!E zuOF25EX+`mruE%B5K(px8Hi%kgbvBcdM+f&4^~lUZat zFEts;7(-Lk0?lAFw}c-?BjM8F!5BUHQt6D$>PDMT&-M%p=l#enH5cE=(+ySD6GT6~ zH~ zfN1Rn47e<3MJXH|}(&?h=R)p{C^O-LIa1Qm)70uPu?XD_=?|po8NzwhxAsfy^P|6ZDhJqmidGDg2zfP_XXRB`4`W>l|U=`*4*x#dYs5;6*%e9UJ-flX$ zl&yr^@g09W%)SvE&rMoiE6YY}qB2uQ0g7>gV3?iRkxD8UTPi#_bsV4<%JV3Vsk5>l zB?a~6uRD(eF7ZDadxvfufRg1Jc$bGm&|j6fy5E{wIYz})?WsMk12rpeafV<{a{lof zZyE>Hhv<;Qzv#?rJ?i9cj(#P>eHm%YU?QOe(3Aj}#A%@bg4-qhv*A^6(z85<9*?UvW*(R1PVE$Pjx+w2ShKA&hv6pw zpvq^j{K7;yZf;3ropI`hKc50B`JUt|sw|IrMlB2IW;~c9&6JPe|ITBKUAmI_2lDIj zsH>|_oa`bJvcWZ~SVu!*mPTcI&(Yrn1aj2wr#TyBrG*)TPEOqeVZf8a3D~^@#P*?~OhxW1R@Vv9ahn3gP)x(yS^$(h^F9 zQ0Y=8-@@BUl1|bnKa_U*#&$iwfug{0>WgnHU|5_fEgU7QHF+3o$ zl9w|ucm^h)Vg)IVCjzi4zV6thsz%kB#a*Dvno*Rh$kdS97ga#zJr(C z;{Vz#6OQ2Dq(PMzuaHv&^BxpF&aDfE8m6sC1Fu}3~VSI0YJdol8|8_RU zmLMI~$a>%WX{;D!JKY4S962NFX%hs;a#ww0R{k z#j|UEVm=qvikO5X&KE!`r4B8gKxGB2R)I+jw=~PHF8v!|0W68UzF~s~GoBRJ8VN=w6cmR*> zK08u7yNvT|fbkU|QL3D=D(2*{^EI(aRCXLkrj}-%2BMGvj98)sh}0ly^ZY=Pu$uoo zf5)L@)tWluj^@=t(wT_{ z=pph@e0_5BgW>~GdW>$~?gJ-yN`?8&U2tZZSPH51cG;-E(O29W6g0lo+;6j}c4d7t z)G5FQrxNI$#LDnay}^-*tJ`ELzm|TT!KN|dD7TR+L}rNL%B?$zATt!{%LO^cVeetq zVhDwBO1wVDapg1qKE+)2$L|^TA=FpLFR`RqSgM7H@JqMrkn^rf2FFQfU7RCN;h>w6 zG!HVo@QJ@EkR{~3Ns@b*bbVQ~2@3-d1VCI2z6b=&$eMVdZB|xH8}{gM%7e;z^d~*M zy8&#f`UNK|nCA_Y)hsNoQ<72~fBs z`n3$laQJVYkoEmTA|vIbVC{)Sc@Tc~DFa&xP7q*q!{#=12Wq~~umlgW5`?9=4;O|T zOrcrHq0+8PP7nof_lfduvrY17nxiF>D+gq{3fuRndIJ@0uYK&0Mk{CA+S&5Do1>Y_ zX3C<^uN>JqjI0U)`T5$Hwu!8Cv(BQmxP3|RwT}3Z8(gII%g?3%_`&?fxr|>uBtcJK zuM)|6Mv@I22-~`LSXi6VWFhdp@yv%1(LTL#>)=%)rH{~wbSCy)^*dQop1%J1o?_83= z!|uK+{O0{t*313y=G3mbMS_F(ciL2SO~qg%Bvk#FQg=%wjly&o3~&)c_g270!%dY^i^||v0HAWdo9d}|U}CHc9n{i=%T0CSz7j5^^QzD_ z=Vu1Nkmn!KzW67XcxI1Xdqkpr4sy0nXBzieA9RXB>S1y!?ErSK0025e^td1aH@|V; z?ec#nX>_Nle~J4?X;xVA&8m8{Nb@UOX?qu|O0pLucmu)DJIW_ z9@}Z0XIhBv)?qN$n47&>lLc&;;bb~<#s!#GVq+7Ai zmfKEDTcWPAx(?T%Cp`cl9(E4ktH;}*4Jlm_`1C+Eg0hfi1*2dh2zaECA1GrDE+Stp5s|SIp7Y5 zih;-N?A-m&pX@ebcq;p>YbnNU%4jeZN2{u6DsGkgwPIvEGnxdvxF~>ZZX3)Vj-mt$ zE8tX0d!Ux42+uAhRyz{L^lK#$d)wyd?vN}lsrigF54x=!t-HC;m32|k+*Ka@uWq#e zm2$e9H`OxyNNAd&9H{ro%fROg`2g-ySfMeYA$)g~9MO{DYq(oI(xlQa`>ztL9| z=d{CvQ~{t@6@Gb8aZ}_`h|(3`S)2dZJj{f2tXw#EGAN@U7CM%=j+;Q9w^Q(5tPIoi zFG+Xa(jmq#_@hq=|L;VuaIAiSdt(f{H^Ya_QNc-MSeZPAO}>|}cs*DiwlpTmb2zLR z<1~lc&7h0{U$I40?!QpoCRZo?KntFC%r)F^qo~#=CO>-b9~r8G>!Ke#`1n0`%~eR= zg?o?>5?hjgJUj|EIiv>Txiq3ICR1q?%%!#U70G<7Xp^jOozEywQfZ>Cu~GRs&Nn zh)jSv@iYB*boUrxrgo+2*yx8)lZSDK4?vGq49ALOWlHCBZz9D@EF6W?@NUIOj=N%t z`|3y3r-4Fm0(nck3&$~?_ZJ<>3?*T+o@`Es_!mIvgW$_GMi$e_bbF5Z1ZJB?+FY#pXx z%W_n{r>@U=Wdan*riH}#l z7psvr363vqJ(1im;!eBtug z0!uA0z&E^*5()#peI>#}KfYR@py;nUG97Y#RfTVFX}h0xKOlUOfXKqa*e&J{alGmn zU4eCKze`li+>2lEt;fHgednXIlBI|afeq)gF8oWe91i6m$q`O>h5SEXOi2m}+WZJo z+AAS(?62w#B9rZjMc(C-d(AXX{iL$_4;ZC(**p~Ic)5yQ2^h&neqH}7ka`XxreR%t zV*AHp{?uC>owNrE;$pB382!=gDOMl>>u)Z@04uCk-nmb+Vt%n56l<9QGG@;B*{jcI zU_^?h-B29O@seizN3D~TcoFJiVU4DKMdHx%0qQ7>cW?@WrnUFaidz4Q%z!V$k(k309+yB_0JU3L6*S=FK)qQHBuM)4yB9oil&>)&mK7Sob#%_>h%lkd#*AtRK=h4411;sf9LSx zubcb2DlFs=5lj;Rh>^7y!v6LG2dP` zfVw0)Lo{-MlxV4*YGw_b>?f6^Wkw^pGJDN$r?cvuTSzIMh-F(Vd#ja2MG<;pM7-pU zuXGkZO6r^yr8nCkk?8ewaj}t0C5tipK@}naX$>3sZ*5;|{H6x#U%y?m_!g?^@O2 zLfFu(a#meJQq&oRRR^yz_=p}*S@%VtBW6ONrUj>IOu zB8Gfp-9tcw=e@SmrHP~pC-UEpRjy-cZ!9KUz&!wNr-5=|I`$`s;}|ZNpfnI!y+t8G zklzQj_qLpBt#8fTh8_tV%A)n-6grnNX6;!K660jp9d{a5DZH;p!K6-2E{O#J=m{NPdIot zQ@28QICcl>;GCNp=QVlYFk@SNz8QZU*4vg30zAOzaBOT&=dLf=7B$8aW@+@cvNH~q zmt7~BoIUo8w4@t$MZSSlTIgk0)A0M!xap2fL z?;p<|zGWa=x)%Q#1JB0@WABBeo|M_KZ8)kclz>sfZ&uh7_N7uo4_tG086g|fao#Bx zzTm3Ndf#OBl}8YGMy?YUGhNMFjYw;W70CHHDtxsp`)BQ}masQ0bL^PQl%IeC(CsLg z5Ab-vNkZgI;d&7eIIfp?D-F0?^PPtK_0vMD^i6qxNMjMg2r+b9x9$)nn?=CQF2*?M zc=)b!K{fi1%~2nQJ#0quHEhJR(VFK?j2ANHUNZL^y(nE58#nP8I&x&ScR_~y?pxs8 zQC&DM(T%6(?`g2BS(h@D+Ka)$s$1K`j4yi#X4W2rZPW&I(YA2% zEj{MmnrIapBNEVAI&6%&RbP*<#^UUwLQ%1pIO#82TqHSLqR0p{D z2|r2V>VlZ>84qtnoc%=RMEnEQe%JGt@PITI9??ETHF>J~hVV*r5!(MB8{Q8vgZ5cz z(5kwK!26dT4jbWar>^S4vT`Y0EU?`Gm4|Frf8qjx6wm^uZXmN-S-9-tV7%ucNpy>_ zUf=9N`E2oF{^&NLR@f!HRiFrU_y?ErP9E8_AQ!SfQ!Zcx4&NZ{vJzw{Zu>;q@8*Kp z)OU-je9>k*sw?dNFw`8lf~6BXr`R-pmWIrMZJjdmH6U39f4Om_=i@V(F z1>>b+H%HRXj}w>z%*#7PsP`gYIiIv?^S98VTe92x_#m-iD?FEnf> znHlv;f&*XhQvB|vb&ac7$vX6wNfo*{D=AM3w*&a?;36y3M~pF++gxmj8jElk+Ivpv z-IsD}555Z7@HP*Gx9?8*>Q08KKm~IFcDEqf4%anaE>|dl86IPo#Pe6(T(9`c=_({a zi*c)fK{u9d09M!?V{wDroRtIw^_(p(DSK`}p+^x)QBacN`g97li1DOq_ev1~fDZzK z`Q$X%Y@Nh&z*|JkZgkK$N)Op78T$)RMFb2VJxXY?6*zFK@5dNJ9O^WCwq98yBphqX z6}nZghc=>sN>U72sLsjUkYI+3KdKUP0OIgH3~U8KNjcme!2;M>$`(hRwlrC^B3TxQ z<(*Pa|5dm72eL_aD~~OG2iOC)<3s5?xK2CHlcHvH^KMLV#F~;wI~!nUS_V)dHTZl> zUX=J?SaFgJ-#{1i;trb4aCU={nP=et@~nCV#v zM$rin#y|lrIDLnBt1P@z2?P6RV#|@6TDjp!lE0X}dOBsofITBL!{{&m!F-J9rlFju z4~R5ehEzCDtg#Biwq>S;Hk#8=!dV(E$g0N3yL=~s*{EXAdNHAmyhund1}S5a*5Wrn z@0!?5KaQenbZrO#xzU(T2)&tpXn~DZ*!q-_Z{C~@yh34BHz#Q-c{TJY!^y{Y8u2nFL);x75We;b1<>EBK4Kv{Ez{`r)Ra%&${2vc zFYA5LR^EOiUBUo-gGPax0-h{S{eUMtSVYTscFtH)Mo zQ~ij7kzYPL?-sL!!}sckIgCx6>w(X$U$oprx|RW;hUgwZXHGR14Ha=8R|_f#QohjZ z;vNp~8C?EmKJFSFc&ypcF96;UhGc`hJYL7j(%07b9~J@EqoQ+8hN9#+T&YzMswtIb zClac`oLNOvYo>)S9JY@|um=iN@-JN-!Um&lf?%vhiV;K<+(}UV7G(AIUwixr%SdI{ zOtp}1CPu-X9%F&4h>kr#ryS|>fBWnBlqy?Z3kzK-2sg?#l#U0A^SEPGe@A zYD4xOvB03>)xG=`(4?&?XeBKm7fS^9pn;L31<7RmL9k$H%k!;HP#QcSY9C}_HTs41 zK4`csvH(O(&*k-LoY7RNnmZ6?uaKD;jYgU7+EFXh#3;yJ6^fD3UOY?tb9EV&Vf^C`INs+s{6`7qcVdo1@Sj34Tj|gp?xH!cFl*y)hDN z&^?Oi3hQ6Ns~&FXQNO2(v8K37g2(lY#$bBTI`^4^-&Ic7AnO8lP)c7oB#T+0JVUTX zfweX%r1ieoH(WVrVc8m2FjigZ@y$WcaUY!XgYnclBxc}j0Zi5&Z7(3=aBW* z3&|O74dB8$M8gSMZz3L(j}Z(=w=M`9t16jumKU*=`&CQUk?>5!$|CJ9b&f3!JFf2K zBXT{E;V=yXnfZ|w{Mgl1EIslfZ5+CO{{1H>QS&?Ar;g%?w_oVLJ2yS03J9=MpUj~? zFD}l&2?q3+pm$jRXl;?V)5a&58+)BC*}*@`xWm91X1o9?GQ52!(8wjc$Oj7_5Ck<- z&tC9*7;dGK|jy{;%PwTEOAO0 z_4H7kh|4uE+zHgE_}oKz@wT|w&T!wrQEG}J@U!SMZ&p6nrNdviD@b9Ysg6zWs6jo? zuw>954V!pwf})_bE~r(1$W`kXeKXmJ;Q&b6kXiPQ1?!B8OTrOTMdF+n-ooa=q|3={ zy7HwYPHAqlrW%|5JuT)qb3eg+r#c;M`)&2MVs%)eC#}%g)`AYa-@Xt){hwada z-;|GAQTS$E#1Z=l21Wpk51+!|~2 z{sZu8@~v-_Twy>NSK=T77H>W7d8&u6!2e+6*z;^4^_@HOw`+~HiG%>r$h`;9GryN`P?Y}7D1`?v*POL)x&isyGKIQmuS3e3P)?ub zc9@tj=Me_hNTVH9BPB6phkW4!;cUK!f9Tf&@^sxvn&iADwid>tz8+9<7#7odV7alD z!%NtGRh;M`vdNfuhA=?$a2P<0(urn@EM?)`n;-xrE?&-Z123Luxaw4VjK!H<*=3Hu zqGip0bR_pG;2Hs%t2*#N4zx4~bO|8!cH6D4F}al~+t4)PQ_n!dBLjx$gF4(6Wfb!7 zYWcu4lyRzOSY+R#{}MdMiuX^=?P*&K#dv4f;7|?f^A=0u%!JEh`4~nm!kr_(I_3Y+ zh;UN|M{9lXIqW>wovk2folErVd}UJE-urhH7pvd+@17Q~dFMRI)H{{?E<|;cHAEgh z$hvIrDDW?0c3=~00xB@?vJ7A~BWoauaNVp}{7@3!#;!9lgGwvDxXYq{QUZBpV-2nC zdf9k=xnGDQV)$}zG7~F0_()A~DXhC9rn}+G@7{=ATToo83p8zO5QXT8P}9y{Nj}Ed zeLO>_GR??`r3CJws@_#EMQ1gMIW2-U9`G_3gN4+dhJD3BoM|o^k;rY?bT`bv%=0o{ zG(^@|X0NK^Qg=?DV!3J6?=3+s8EMTQRb_|T+an&wsL81$MVTSA(Y5t$2soekZqN>$ z%Np0@O0q5|Ncxqx+CObpZ3`+!_mj`^@do6OqPpx$bTz7t%x z*aO^CEuXyP*+5Uved2EUvxywiVOp|@e6Ks%ZtY!WDBt35e?_@l&u{IQLp3+Oww0VK zLg1YKoLB-*BQO8WG9MPn_Nn0YiC9)BRj>{EHhy)e7V7>v|574{m9Ob{u%4tbA7`KC z-S+C*XaT;zVn4hSdAD*OKmVf{AZdU%TmBmFK|lZAzJsk>fp+#mCWN@=v+6Tgyl9jh{*kPq zGkyeqvB$0ZPH_r7cX9M43Tje3y?I`!L| z?DYu$lIb)9mdt8FLHEIqOn@qTUUD+XrU$yxVSyQm8?b~HGC5mow*8v6w;gnAFz#`G zJtw`Z74zkC&y_RHXYSj{UwXH~ht|%=1m()fuDu~Fm<7Tv<5oj^|D(N>tUVpZk3CY) zUf(&x2!}ikVFCk}28Oj2egNwqk(;z*7gVR@cF#GR9489UWqwE$avE*9*m+jVzl@`Xk;#Qu6IH4)pys)wuD7uZQQ8|mhV4me2Qk@; zhuS>%*oTi~79;bv|9I$!>JjHs%HeWu1fja16%se=T0xDw)i z=ruGn4Jpf`_t~T=@rZyCGh0>YXRLgQiWIX{y29^9>GMSjb8Wa50C-3flqUu*xyw)r zKp^L}70H#x9=5Myd&D|OPfXBFTs7-WMsxY$!=Y6OmG-q z@OV>0g9zU5oTD{3`*WV;;?A9S&IE+N0~5V!c6kG-7Y5oJ{wb#U)Nh;Z9?lNt*BNq$ z@5y|}i-+s(W<6~()Kq#ozPRvWazR*`w@&^oV-Pw|j)L+Tg362ZWW)eCIPJSMSgZ&c zOYC>9GnchvREqSFd{JV!Y1JC+m3WX~`)TxU6OUI|^UM*%Se$@j8G?32q9y(tEK>C& zsUxmMO%T6>-Q8~pzoy8b$r_m{4|G=Xf^6XvLI2keSu73v`*-gwL9k7o@c;cUa0Y8a zXTl#M_v~)lznZ`pns^P0ws#!YelIoU&~W%oIhn-~6f|p%kT(1h$G2~`v)Z^1>LI$V zZi9^txCBk$Q$hQ|m0Q$v@6RKeA>g+5FO-f0;M5I)>zl1)CR(}_J>Uf%py(ZdB7;BqII?u>S2mZ1b$CTH^B;G@nbwaFbLDrJAd0DKK%c(C1Y0IohqKEns7iF^K`h=oN2Nb{)Mf^@9*5Z!}#41ccC>2nE-nPkS z>Mi@bSol)rF%6_H*94_zl(&3;R3LD+MFCwc{Zs)V%B zMfTz6*_@sNmXV;O>u{|t>Dt{YbT_e=!n76FO%q&+8L8Q6Ukklo*KkgyTo)}VcdQQG z(R_=U{@-EZY=VbZQ=ZnL?8pMC!8fk2K8$)=H-%Ttt#)9xog!k&v4IY%x#kDCl_$tr z8N-|tP-(}2Y%L+?`N((coHp1kmSb22ZLwblZY)2T)~C_Olr#h@A4YG6wQ<+K7jjb4DwJ;UM2QkEk6OzZMNJj z0z0;jmvr=_pOBY(&8k^2x2v@d<$Ji!qM)sUenR=aC@kPFMD#mga#ri}-FnDy$%) zy<-eTM!_tcF&LWR8dT?o_Sxz=EOv;m|MM&->;K`ha!5l#A>UMH%U|Ylo1SZ7i7)HT zq07eqa(1)iUrlTFJEj>^$2B*e`i09ac4%yFro4DD5W2mtGEuCwsl1PnSTYBe07l}@ zJHt@b&FOJLXrWFzpqy1t86C}Qu2LUPDqxovIHBwGR$_WXsII2SsA+ADU(kVY`!S5* z-379n{|u$Kw7w(SsJ#fePhaE$9uapq4pyzj}+%OUWJ z{?}OBqgFFXO!A-E4Tj)AaMfX}eufS?YmDW-9+!sIp&92%x}xKN@cJc-&TxOW9cqx> zn=obya(tIUK~s9*AIC%uL%jk9GANN@+QA7VcL7;9_`^3f~a+@@tLPUv}zX_dQ;iO zSujGPMmvg#^sM*uV*pTVrRY+`8>?Ao`SQLz7qU$5GTmobPONLT+4 z1}u(rx!E1Y6PRKlRk+4M>{McUz$Py>=W1zMs88MQ>s|^KUR794{5F90k-)Kda69qw zZ-^A6V??ahsY1*{{j=%@PG=C1W)@&%Sua|=_tH7%*kWGzsZ#&-3E!qOH4$jm`cY2V9!wv<&&QkgA=7=>y^s@-yfx*j}HYtkh*sBF((4)Ah zb{+-Ob`ACRMKB&?xogt2BysVUW^Vrz>WRvUS5>$U%n!$-wAHFJ-0Rz@TT$l|%KvOs zFcB}L%s9*L$NcGdP8cTO*C-LfzAFX`n+59M$dwy^=3{vk|M^I)q^hl(g1w%yv;MGr z#H9jN>XHTu2%by2=L?6nQ$MK-QN3gK(UozUkwcUO1>uqh?+1M4K{?kQD@LI7GO|>M$SEO5R zI0|378(}Oy{RhxYdU%`I`Q3nq!QoK z>9J-MpJd_4I+weIby}>A%?14FyYO=H4E)=tv0J|{o+S>)ns;u!I*{oO&H>tw+@lC~ ztPnG%-J`HfogjV~6KSjp5D?6!PrB!cm_15+2ks{Ra%{AuVZ7aUS}nL3^fe6o+KyOvPhlqZeBFq;ypG)bR7iDMLJpApq2)7c zTB+Hb617OF{ly4y$<_`yi~+CfhbIp^H&qme8%0X}HQo0JI#I|K!Ib7M^j)4pSCs3` zg!59vzu6A%(;`aXmRi^gA}g8pY)_N}a?uhdAd@wnFb5s+hX zYP8*OZGV=$Z+A4GY^5;7t$IP2i`Kzq!Yo*XA-V4gSmxY2fp0luQgNa_G^0gr@s?Yg z)<7s2mf$*-4iap$#sOAG`uW#ypaQ(fsIh(L{%u)hI&aUr=!(OnM>3ZXX8a(4t`ZOo zaY`&6SOcRFnO1$Kfb079UcDXcma-Fu5$=p zYk?Lrf8No&%m|z%y9z|R4 z?x1EOHq%&Jm{fG{bAiBp*F_LTzPh?_GT>MuDYSgH0?E}~BD;u1BbMKpfA?lqJFuM4UD4|J>OgK-rh=W#4kRbF{6no0WmKuSDW}ov;PN13>5eL6Qb5 z*E;n`Gh}%SUf}A?R#~NW*aPS9BI9C-(vQ_xFwLig`{D~9)^!N(vJ;4#yb21+i5CvZ z-DVHe!!tmFHV`FoVzGfYU_eDMz|QSX!*)V3401X;1x9q+I813LVUAi$vTOnB$lK({ z!rG-FR!Am7LG|0D@4K`f%gdLi<=Y#hB1$q5y=ZRt#V!!?+@M04w`RLwNO3cfH5myt zXNhXSyd{|$UBf7A0;Ob(?WA{`M4}~F+!qUY}qrrD|ENF`nA&e z7}L^@mMb~cvemA|vz>Qt`JQ{jeCIPQlM^L}VI?+vGApPx=Evu(9wLMJNv-o;nqeV( zh)M3&eVTP6YpCh+G>`FjJEai@yUYB6|1X~j&LAtM{Afq?@O0p`FRvr1D4JA^pnd65 z3mndzg3&JQlCTs#ws6SHo^+`XA$?<4x%>q)09h6{L=f%&KjR{PD?Cg@3F>q#gbG_1 ztx0SuNHkfu6Qt!)lmcq{C-h|VtvOahkDssYPOJQ{n^uGUO49O(4PWDk&G-(;Uaox! z&Bk9IpBkU?+6VpC5YTQ;IW9g5S+mt#W=c@-*EKpF%|^yP5kbyPQC25en0T5#_GLd9 zDNkr}J_^#fEc+klxx>)jWkQqi!Vp8*@7Nh||=y6!L(fs}5SuQ;^u20MXTLHhT5f>8xX{fM15x{!5UdN3J580>fKfL-?q z#fRSmtnhAAV^ck30jJ(mD;ncaY9u&WF~+=v;C73OFpr<(hvlsh1wZ%<0mff`EPb^f z4=Jw?BOrPG`ATs_<-AUsvUP=4)QKNHQIYHP7c03jOoy-VWGa=~iJnKZLdZ)&rVIYy zpypOcz${-iLEO+=I-H{dp2{UK79%70bJ0vH)?4T>046!nA z{vy+@XYcMY6CDDhS;f11In4mrtVh5j)z$_h;+Z5GoIawPX)kfi?!r_Ex6a9pwUKyf z3c=jCiW<=DZu*jF36G@sIWp~nQPXAdteVT$D<_$W|GJJsYRxcL-+=sY;R_zpns{eS zQTvhfJJN(IAP#VSoAp}6<|LzfaD~QY81+~A_InX%J13s97fwO?N#fqCC!t}FktsPN zXN!_eCJG+!o8@EHj1YXw1yiD7Q1IONLPf0=emV%y2M^XmV*CwzGNN%?PTdK)0~M|y zFt^zUiw6O`xKL5oxI*rC&#QN{8Z*zUB!%Vwp@C)g75l5rbkSpwco~cU&3m0DQJh(~ z;oVp5Y2-vp;T1Kdr|xUkDFNFOyqMXDuUVV)n8LX`Gls+4-jCjV=JVxsJ8TcW=q90b zwr-rRvEU{X2^rUCfUh-ttPd0){s~f^0|?f4@&M--yp-XeQV3$;5W|ma>J6ACEVYwF zNX=f_CbIzj@Ki`6fFInWMLfvZzn&qkxoY7i0>Xa!-C!B>_giTKdHu;NB;*!x z`iOCQ#55C_3JRLa9E=LU82fxWe4C?~Cy;G3(p6&1sq=NoHfTP--@&#Nzk_$R75Pc= z*qT1HtFSwsdu{YYu-2(=cI8408=XbN&6vQjCS0TJ^%>l?W6ZD0@emuq@X;ZUa(LbL zs;F$DUNo2{j8K0gDj7@n)GKaQuO5*Y>t(z>&*6eqIf_4*TdZW3G`jFRgy9~EjJY-hTif}=e)QPX{6jB1b*Pn<&h}6>y&FAvXbJvDyy53Mt64m_96M)( zez5l#7^%qf`z0zjxK=y*g8APYUp&0gI+vTm+&!qFuUJBJXp`=4qBau~dX$;kS>$hd zNs{mjTw3Gdq(J~pLvrN>C;;J|3lY`3-0=9t6ACYW&wV}sWuhS!^4EEcvyS`0RwJT> zT4hleur4?V|MMQo#e6XHBt=_GpEu0$k*nbRi`L5^JCnT)O>Itcy+aeW!TcS9f3FtG zsS7i3{_IL#o-xd>*(3Sn4;h=H=)!1j8cCL^YE=)K9#c%XbiVq=#4?g0v~GxPi)KD<8>-j46zSB>MJ3k*K)6ePz5MN&flA_$Fc^p4!qIcxlFvTb`M?w>D za6A41G|mzBv`E7m+%8;{i`YTyg5u@l8;A(C_tc=KGQ7*0mL}I{AT<{Q5ELvw^T0Q7 ztsMOp5UO4Yfo`o#dh)^j4--3SHkNo+g7QSxwZDLGzz4Hh(BBg*ivQu&3n&M}058UR zelfmL0QpSo`zo*6VYUxQB+ouTATw$Ia`;_3BJP$8snh(@p-lQJAAfmVoxVE4rI#j! zGiALS$OF7tYjQ%j!eyurI}RT(iBvD8!_o}5deiSw_32B` z`PiO^baHU3iw@9T-3jo)Y0*r=YMMjAkv~{U?Zmw4>YXAP8Ar>oYSt)A&y+J_`>^ipnS}vxZ&65F3 zG@>(M=#C`O-*e-&wLm3l#CI$Y)xY(KIbGkws{mp-<35yzjx&u4^TsE^iF?_>6zqTZ zN+r;a5S!59UKk+@ZO>OhL$$qUUmVD2&EwxN`6c3l9-)nZW3P4IB02cBuADi&Kit5B ziuJ6;w@qBlC*dM0ub2~NlRgsBCkBV7GZzYj_?RriJfn#t+I(Txh*If2Ef*JnZ(je`|$iJSR14d5bkgq++uoT^=K!PCjlrgB8Rq6}1@%ZC;d0yEq-kgxFQa-xQ20xy(VT)2SfJFP+ttNc zcU5O3**@V)OSkOenooYBTtV!8VN2!O=Gt^F;qE5!!)iMxc^H1re*oM}wN_zn;8ZMd z96Mhe5Vc^BW>j?3`cM^+G{_oBG_XettxS?ZCMSPqSHhOR;A2l{E~xNRZqb3m1@ zvXlN_jOZ}EK%zX!0NA}Ft$^Kq&7_2se(L%O?GQ5&SUnb5^P)kdtJ! z{)N5K0^Wl^E1} zDZd`w?$zTu0dm=-0`gY}9YVwHQszx_$VIZK;Ri#!w6dkUiHUa3N9XSxH7 zyVJgmlcVv=k)8r!r0T4>G1y=Ysrbh$v4{$x6oLBduig(92#W7O|UKoE@7XTr>QciukZBImUMJW~HY?+meUxBObLR8kkOx?D7Oh2z* z!9@tI{k0(PDYed7)wZx61A0#ivs$HPB;+QoWc)-3ouWfGpW5I8*1x6(d|qeaVUrB^ ziyN$?$~*bMn5Z0>1geWDdA<>=g>`Et@4<#Up#DY2h%q+O@YGAR87 zE#QR!9o+xpR6oH}E2Nwem^pMXI}fwp)1O>YPd;ZV5VKgymZCmzo6lF7!V4_Shj-OM zFUSH~yIB8issTT7|FqxBjUQM_NuPSA(bRN3`G?%4$S8Q;VXLRXT%(xrb5L}49HXZP zO&{9}(vj(Ob7t#pZPXGdVKWStwVn0ij>lZ?r^c1Fg}$1XUZIE6@)R8mNXnfdFdje- z^s@un!JhaFGL7yp#pte0$-jZXemwXwWs4%!lf16=yDsNc@ zq*>B$r&+>bZw4W$lNWVXFRGV;={rap-M7S&(~qf#wZ0}AlC%K*91VHzrQ)jJ_oNEk zTzOv4>RpwiPC3v1zUCyB#V#S_lD=n%uVw|(q1dl}O_Nj^*Q4|5!1Svc<_4`L? z*an!%cFYsbVY>87jy%z8XgL%j>Q4HkoWt^@zC3IKoZcYCgUbov-Gm;+a6;_q9s+VR6N25WucTuMDr9})7ud~Cm`{Jy(der}W|CwP%-4ZL`Fv!`J ztt#*zHV8h}q8M3)MsL}3-g(!a`|ldj{hsXfv=cW+vGfzv{bSnm9qg&MP}c3@;|?OI z7=aj0f(^#;*rJ=%&J*`&c=KW%XP(&u7ZHAW^vAU(i1nRY%b2v#Q7yfC;h*>-r5vVf zEP*aRj7Ti)?Fn-iT6g7~`?+(9T6E?O~*j|s?{B_ z1{6HgGYV8>|JR3AH(1Y3dq*O-pM8#{7j?D?UoDQyB!8bnWOOnNX-HxT3W(i4u-}!&eNoq)7}Z}*FddU(s0wi zF3hGYirfKuo1Exj7l@$h5nTTF3^J@mrx~>VtPHM^oy zoUiKDu=Gecl<1b*{=B+E9(bECsMm_zu2b8m!Dyr=EX9k)sAcJ9AEpJF<(2Qc-7(Qt zBs(&yV9%{(}zpqOHs*^<(l$V!^<{mPz7#p_5nE9e?m-1 zy&Q4khUu$xnP5Dcm3;YK@E#Qnv;K->!3yrEH62R5I%q8FCq6$#L_o?*y*Lvq*Mg+xa4n@rHgR{boAhmNq+RqZ%EcPTTS^ zNik7CU>;sV{8o45qj?GhTsv^Ee0RG}Ri@f#I)*fMyMN7@T1+)u|DHG^G5zu2Y_roS z2Q*iJebMbyFiroPEdtJMP}TcxR_b}3H5)P%(C5OsH4-DJK5{Gr3*H(zY%9KCCmH9D z7&s>DhEP%ssJ9Rcy8fOgozm5G`vHDpg^cmC9+7jDzhFUYr6H)4fe!--&danR>pHNY+H7%1HDIRr-H7z`UfdBn z4eDq zS2!O`H<#sOFYR_Pj9KZ4BtTs=Imr3R`m3=Oe^G;az0qY9OD4wp!6Fe3ib-5h1o5Ml zq|O0rRRzIC7g`6=v(8`$BSnMyd2|hMhIu^Ck;!st!`->h=BP z6I=InpC{yOi0WAk+TLr#nEY57o4kRdvTs}ocnJaPXd!=56KiBx5*WQdGdFvRH z@Y`xIEV|J2phKmk#Uyd+n|Y1Av?xSCY^}fOZX*m^|M6bOIx027C>UM|`waEG3}AJw z)_L#?QoGlQ3{`^it^I3k10BS6ZORuvUjc#$%8#<+S%B;iFAQ`$ef zZo4g=e3XWx)?(?Vd)+w|4Odgg{<-qFLHu=D=OiUV;>uAW6yTZ)1_juoFDd^qOrAc5 zFJ6t}jt<4jP^R+k^wA~6^;8D!Nyp~_dt@67;)sV72|yZ`ClEKwxr|h}Rpo|#y2<17 zV`KK=R8i-ux-eG%hb=>2pP7|z1KAJla(<9EZJj78jb#6dT4~?Z+F$60O>;R6T&k3d z=kE4d{fERC(|t`LEde3|PGzh=+yWgMz}-}pd-$+6xeb?c8a(K&U5qrv6yssX)>kKF zol_0;)2Lh&-WPUt`mjOv5a^N9kbjfrru)=!OC2P(OxFvH)@>R6QL>vE-@3jWDy|Ys zDOa)JzoRD=JDxhna05>T_}UT`L(tnW;zXh=;d?`v@97O;0p~MIy1Vg@NV??~rwUUK zI|*W{{J938v=X;$NMjbZRCeeBy0ni|eUO2OXA`NrPs}l$V){oYW6rNf*NTY86m0N~ zYJr5CJ=EP5Id`J1=U!B>UXMfr&gD_8bTD|CM?g!myn#0MlDryP|+pv-*uxGkpR?4m;}~vfQk*eSMKh7>;2%2}zgy(E^>c2b`gYcy;PdpXeRI!Wx{5j2)KyoV9ne^WOck0?%$)np%k)2#r99eQ`Xtx;a?!Ud6?^9pkeWFEi6~%%DJzkZ z4_Cb@dHcxIDU(B*v(Z2uS5G*}Z1R7?cnmiJ)cz|}{|h8-^KXX|!r8U^GSuu6KWqF8 z;mT2ywTtC({D~ZBl9WO6lblw6+0TfI04xTg|B2ZI3%@*_+%I%Ux*-riu$oX|Y~w3_ zAP0WXK6cu5Z+!F%&m{^SMqBo>20C`v8vOP&xT;Jv>TzPKz zWx@L@@;?)LjTcXRc7Ocku%E2zcb09^-Fz3_HA3v4?&$P07O>M}Dh?0rZ$>{$-X9Y2 zzwqWHFcB$xJ>?+q-#6_>|EuC{>v7A>PRZN?gvfoegp?U3+pvK28hD9Bv|x{kEF7zHxC==Ze0*=xb%?SQ>iB3c2V#%|EuuF|KmQv>G|s3 zDFGF{xrC!t*kyps=T4js_4)Z`x;gT)6)Kew0vSd+@pJERy9JiSLR>G9TO(DkB`*|O zF}!|hf4e9FwEOn`BvX_uc)jwuoIpAOL1#`2g_WlkTPV)NqG?7ms_wiP$7wu^;@aFk zjs)gWx(_Nh-AnX*>3^y0z%VF5ZF?s`XF({`a79Uaev3Rmf43>p`6I(AE8+RUj0w|AMUsd zxG9?p*M22Kr8&dlZUlsp^iDt4wX~(O5rOXJK*4jh$c0`2BYYLpBdxyxg_0&Nn)+BJ zD}_46xGQd{O`XRb-ZLIy0li22y?4&1qO%IfK={nf#AQ|(#qj2#7)>#3DUO2n5&|kZ zrD*93siU#+;;R7!MB4Tzd#!uy z7D!l(tm9+IG0C#J*d+Opt+Sqttk|~|A8T?z%#~lCCaPm_XVV_va zQ(k2I=m-w13Bikk@0x|$X{6F$yihTkClI>1GWFEbcA;?^o3U3`o>QZr!|~|RW=iY+ZaSCu$@gl?eLyK!q~c4;XKVZA!UZ^hCPFB~d&f5fxr_mq4+U|v%p*jCtj z<@7&l!zRu-?F!HKRa)l`ewq>1&gxLTUop8}cZn=Do7NbcF;}N`b52M|RnUzzN$nDr zH&8K0F5&)9b$VnOf=h}v9~u<&qjwmdNDa8`%Aagtwhm84ntb25CgS$hHT#xYpl+b- zbVsB}!!0t}hIX*Q+whW$;E-k*7(K?ZEu#3)V1w^7==EjuIVm5wHKooq$a2v=GMq&A z{Qd%2@w%OF>>iomX@$n#`Yn%o^w~Tgn7jRI++y-V}*qn13S)ODbc015H z>Uz$GdSNp!4p35_C43n~bSaQ{qfDT$ch?o^!2Ozq0rZ1t)N~EMUtZG|7_$Rh(!@Un z*jSz@bITZE1HBLI>6b^JKXk&zA|lh%9xd+fvYwvhqUiWAY!y&se6!E5N_MaN$|uFg zO;T5@Z1U{Ss0b_>_Z=S#%=(2z%xLkA@~VL;5w^8S1aIf!lfVZ44Vf%Lgh3NH$<1~x z{>M!+CJ9TPlM?5jJ{-Vp^eTn~gDq}_e&eo*3a!0fvqy2I&qer9aP~jYZ}JO>H#iJ& z;f;ZMJ4_!HKx}4T1K||u=p7!1UrYaUmZ5cJrqr+{x$GaWhxrW7PiDf94RLShtqQK6c{D zF;zTKt+6>wi8rQvv;syXZxE~bG__Y{+oYZHqayO(T;ZfN)>5K+v;L`It_U&*&^x*< z$!bmyd^B8(b*A6SWtEGgvemFxXfpa%27?AbzkR8aC!A5iW)xDK4wIlX>$gI_)=w28 z?-wyJ&cdHm%XSJbyS4xT+L67@42j{IeVab%(_+`mKWuBjW>TPNIepnV<8|A=>5&j; zh?{A;04V+lCU#)dPi>kz8Mj+B|HD^I45vStt39c(i?JtlB<)dojUsF4-6FIv7b^LX z^2t&X3DBf+ePSZi?!L-O0Bm_^i~^?IZb0=KuK2 zUO5ABmu3JBu^{oA9AF)qLpg=md(zO;*0dEv6FI$K?OvKTI6bbWbgKq;Qtl zv3bIAK0gqKc2|m&WLE}4ITAt`@Q{Kx@6Q;AO*=mOAc(|VeH!~I2}9F3@0z;)`PDF~ zL3-x}4XJRd#LsE6MSq=ijn=&q}r znE<(uv<+{|E|b*)NHM>(k0+R+>>$lB#*ZvgS#ASf3*Ml%s(g0_ z=Hp$0(0IO)eJ1e{*FW6=>?ygQMOAr5Z=wzKcH}BMBg?3eaTXQ`B|yZB3aGLa^!E4_&7Pwms-yIc#Fk1eR9Mx zKVLp_o8asH1xxIGn_ZgILS)n`>5}(zv7+b^KgtkL6>fGE27m*4ocA`BduY1#jpdg zk?^ok8Gz6@U7%@YuU^0it0>=qW*o`)oF^6x{5Wxlf*>i~gRylM2N%c?`xc@O3&OZY z)}lz=K^s&A{@mRLu!8TX7&^Eab#_vKXz1`k|Bl1i7N|(Pj`Ng5X{yMkI;b$w<2W?} z{lYRHDqTg3EHJ4?a$(4?y30xxn8u-RxLMNSKTc|wE4fdEQ`Ln-<+ zifJf60H31RKZ2Y?rj;MQ6xwWdl(a!| z=EM6X#AZK=UM`<7Xbiv)Q^H8;mbSJ@vy<3SryBQ4**H*~B=S zxxYk3p4OA)BB5GVCx;Z%x5580U56y2rrJsnF~FvsEh2d~Wm!}%-!ccA&lH@6G#2qQ zEyo=|**K1YjG06hR4Rf}2O;s|a2usPRn zb09ePB9lyAWH$Ux+~y(PLFP|{fxUV%bz5Y9!}I3Q49~gO^_PNczE5lGd@esAXQA!v z{xF>W-Cb+ruI&5YP&!5enHK=`@#YaNo<;xmMUYb+f za;{ROM%C+g)YpR6eA#^C4O%Uth$nE{816%`ni)EG!MOV{1mk#hm6lW_e^T@H4O(RJ z1o6p)Q+?u(IlR zmZL|^L}z}*aqD=c2shvJ0qnEotg{I;vZ~|QAR2>^4yb}ME6=R2;E$IqguW|A3RSwA z4!{74Q8X(Hw1O&uTq>igYbSyNi)?}f=%!!fVAqEN*jq8>?weLS2ntqm9pH(KZizpl zsMetrq0ksAVUKbY3znPs#|ft{(!A*5B!WdyTW#7M{-QvfBS%?(X!*s(Bg-9*&Tg&8 zZ)IgmSJPrOo(m@tx)tMp=7B-ndiez&Yjh66O%#6$;U0&v`94O&?+;C_d|S5j5Tsu9~9KqNbmTN2k@H(Os8y*E+QP>dls#IVvv!Hs+_Q z>0^o@6CVEadCg5FFKb3H(u8{km=gLfKxLqO+#<}Wu<7iJxZ7w3pLH~r8&V^N%Gvz6 zi|QIS$t{S;SBQZo|TxMjw`Hl;415af%=wNqI(OW^c}y{>fn1er})HQ$oNK#QKgNnmOx^KZ$5+e&xGyjmX&ae5NBd2$Svr=6WGDFjHiUsqh1q~zt z>7NPrW1R)x2o$>gWqE96G4l0@kmndC@1WODR>n6(Dg#jsCku8AAM#yb^>c3y7e9{J zJJqJ+D{W?(LkROsj$#5jSZdTDl%G*dh+Nne8mbXu??>o*O)ww8sqDq+L_PASyCoj@ zu%rBXwjK;RlGmlWj&gIZ=pmfX>*6n|G9ZF} z3FNz>WYNSe$p$(RFNyAUV`kO`s4h5 z+7Ai#fJ=(1rP5fhaG~rQ%&t_o$62XrN@b3;RHMZ?Dl`yjS&@ycF-5Ak6H+aRwdbH~ zs0Pn<6Lkgv=R1PX6%Z6?C%L|k4dKGu;1(!qVWNejFoz%gJ0j*YM8}7=W(#~fGWQq& zctUIS<;h}3_Ib3<^dQNPQx#e$|4WiQdnO-K)ViEQH)qVb5NP`z59_wLA)6h(vbb zk^yMkt>4W!&Kx>DII<}>x!rN(uIzZ)RG__v!S%x3Ax9%y5bFTJ0yd nW|kW08G0 z+_A>G6_J%_XuYO>eTWh_$Ic`lH&An2`R9)CEb`JCJ{@1X4aY-!gT@TK0!|~Q1aUH= z9Aa15j<>se+2K!oYR_A#ly1EhF*_^#Lnf{`S+huE!yR3^d9!iMb0vBjs}s!SL|}$A zGJBMEguwmqTw};$Z%v!)CVxqql%EB*8yQ|2+Y)sY$g$%4jpa)Je6-*t%+<(40NNN2 zL%wFlP;X;{5hE4t8SJ}d6+C>CZRBsu0TdVUl6uWsX>!6MqRS@greloA9$2U5rI1(W zM_Q4mCH<2YL?u>jlbUPl;2uF}*eDQ}T8-;{RQB;=9M^k@2__Mbsgi&;a5gqPLG1s1 zKi|KW6Lmc8_5G|K>|_&Cng{i7->&6>7x`@aruJu)6}C$M0jEponQQn6Xf^}9zkkmn zQkD{lPxdY>z@@We#Sbz;5cG;jr`}4qD8bXTN|2%GH6W)(=?ee3V;Y#i6g~C0)eF=| z2c&!KpQ!HGl1VHyx4VzCx$YIC9D#H1&%6W6I;98MLwQ{G&PqLk4mTqa}~+|+0O%&6)|1GBg}A;u8m{0*%SSt zMMFKu5vy`^E3IqMRuYOelC@yiE4uPuxhhpfmH>15ej`ZGt>n!S%M3RM%! z{uO-Fq*VoDg>EMSN5$zsn%JE!W$lm}RcLd1TZ`eMqnKUch0O9Q5%)3QO4pI64`!YQ zQLJrrCbpTSR2#G&-SOOp^lL)Vqypi;(Mc4NkrS`~QKA3M%#9m0Wi46l)k3KpbBBH=0UB~m1*tlQV zSx^|l9-$&DPiwc!eSIk@@g}h6uNanV^CeU$9Zr+X$WR>2oBu4RbGvc%^2$tjkq7&A zZ(6dc6h17d38gj7S4=|2ujWrg*68?;WQ478-5dpuzK4S&jz5TsuSY`mUQH8F(sP=NJvO zZohWPore-`Y+s*4JtHDdk4Rg)rp9syx?Ss^_Ce?V4Xm0GK&Rz?sfD**CYJ~_NWWUA z1Xpe_iQtu8EH&g^11-ZPz%f=XdS_lQ|6&LjNU57?0&wlT!K>53Ra>=b?t?`OR%^nR ziL?dSz*_Oy8}p)1JdvX+u_~3wdzG;tMO!dTtw4v3Ph>Ig>SG_9dHyYzvmJ2sg!oEvhdm5QKlg{Cjy78zy=dXXy~TnmLJ}Grm#EQJ?esslsl=6f>|^&WP9Y z6!Ks2kcO==axc9o&32eEvX_-^bBO)P4%#@Hk*$VAq(Z}_q_M3u{P$2#AyOQ8kjKA< z%it*3hnWT0+t&u+TLB$V)2Cy>q`c}t#)=dYsOMW#Wee>JlX-i1&Mb3*{r&!#&$u|# z6h#{x8KF<>0p^%OwJ^B;#Hn6ZfJUEd{;kIm5FHl$G(h88Rei6NULafl6sMxU>+u<* zH+}HYo&EN1Q&2qYb`TyPdf7h;0(1C{=uz_V}9|(qtP00A^n;Z?T0xi5y-M^s8WGYa^+wyJ-1J z-cOWVh3+VHM;$zOwq*Qhpe)9Ia~c^}|LAStR-iTT0xPF{S0ZF|JSSN4v1&k3W>qdq z4HDon3NZKUk7x-=Hye=!D-?xeGz+jdn(~%w&j_1N(o1rI`drt~u_2Cwi}&yXjAL+X z2_a)B=c&J58ghXEDR;VF+Z$2(Iw zF`#BR>QVQSSN2HETiF*UV&RScm_8)vh+l?Do&DIku@IA;yI}Z;3cIaR;&v}**+Nk; zU|B;|g2v4ju}y1cgUG*?)8Y@9Vp!w+OkjIila+cE=!HC-BRJBzP$&o+jxEhb$2S0Z zKuE%4T^xmU?X-aD0*+ni=;E-_R(knqk+H0jC}Brd8&#oLffJv42oD?0LRlfXfi~a& z-k(rG=6x~0(44v@o+A^}#A`MCTjb)3XFb5m2cy7xz+qa)X!?%bD zxV@V=j6oJ?upHcFKU|6Qsl9UuEuy{=m1~?8p#MQ2_pgpgj%ak;MP-u={LG5@EZ#U3XN7w;c3(5gLEn3_G)RdukEK+ytr zXeu6@po8Q03oAzgB^IIll!*A_J?6j8#oV(5eD+A}6^?%NE##>xb;_2rZbu@ot7`w? zbUZ+&rnol_1kz?Z+NPUFyalJ5slQG?T^0oZ0zuFi159t!%YXbnX+VK}FL_WxYOS66 zt_aiZUs^*DLI#^OqTiU_Zhm6v$!WOI6zNeLs<_yP5@rW{ys6C@ZV^-BaCuxC3Gb<- zttHSb;@nXJz6o+jaR?0{c}0~3Eyq5d%%&|iuwcsVnaq*a_vS6(LzPUrGMGx|Uo+)= zGxq(ZAwqgZB;2ahdXJC zn5%6^6|df&?VMnrT2l;@FLBFnK{0R;7v>vU^nrV$>jM~X%=uO!AKwqj? zo(YK*FV>=w?9V|%d^aU{mA?asX|bfuvBy++N*dZ;rzizd>y778F7OU>_as_nMLYBd ztAS0H8DL*E3wlubCG{B4E4&{yj=h4DUQr}~ z-Vh=p26V0~*X>yuT9ei&ALPHw5&(5p3Ms)A_;0tA5B-1^9nn_7t9^nF{y@YmB*8c> zz(MbDd4ATdp3)&#r7*BvQgv4d!Mssn^Zx|hL;za~KLA~4rZM|oZl=&UrAhi#RKr}9 zRk~fW#M1{Z`EQ2a<*o9fokI(hUxN!=4KxbvhMSQ?YCTht!TS9|%V^D7LP0RjPs0o~YT3+t z=g7)CWgXKVH)7e~CnziYm|)sYX>`c(-&b0( zy$;4vY9>k6!ikWhYxzv`wpgPrUtpWjdIPKVj~O4N0UrIf!Lt{h1CmL@;&JLx5G6Q# z%oaQUJ$Qv(oD~+70V5qFE-pG{@DCJ}1`ekGX~MeUJI}O4AWVm=tq($%K-|5+yx|M< z0Sc#X#i5V#(BgE|Hp*X0dRex|v3j-pO)wI)^Afl{5wnZr2#t07 zPcL@?m|R+H2W#s?D%oF`$Bc{O;=;=W?TJ(rXE>{5b$CfZ1Wt&fkW@koiwT$fSI&@s zIG4xv%**M%iKcr0pLsO*2R>eZmhd@5x}6-~#{>=P=^v$ulzB6&Gg$?uBHO>VtGr#DfDSQx`URQ=d_D0IZEj7^!W%$cV|yEIN6Gh+2l9CqvG@4w;^YlUkzU_Tvd=L)=V?hH0*p` zZ}EpduC>E`*W@uZH`_RNxxkGYLHPHE5trxIqD#0LNvcX=QaYjCMNZXqje2kb!MobH zaTxvoa%IkTxFLyq&HZ zTg0K3pVqg9N4CGFE3BQ3Cs=j@0qG_=8ctxx z7+$*Weu_YR2?2#Q5Zsm*l`#uW2;cgyjV4A014fAWBS^az1^CWY88@ch>YW>`-pV}?rn)+Z@)DGLup^afX z=TYqpBD~=)oNu1b4&(6ZRE&eZ3t>(9UFxU}^kUe-CZVD8Sxk{Sn#!|S@@kAj@tyTa zsU4nqknz%O&OPPp&oHZ{^9x{#g!v7k`fpitFbU^gK9Ivm*m22GA_byPPkSEQ)i?-m z5!u`HSo9E(daYBVxUhV6KWmIZA3uyuEBuyKrS zGPHoSsn@pSa6%S2ZJ|Kz%vwQ}He^YGHWp^oVSQ!O!mM=k)UOskqc<8f)H|81f#|RK zQhi>B!7OH)vcte?$2weHzDAc0>yPqckDx-&u!Xbji{Z!L4vVq*R+q2X$%4+ox)rmH z7j;m6)d&!*nGy43zicU5RN=*)#YW-3Q#78XIsKZK=U?m>hfA!%Z}kHh96&Cm)B->J zM3dWhbNw^u^_M2TI$@1J@j%X9;yASzkQr`s*?KH&1d<}T0lD`6Z>C(yzIC@Qm*^TZ=eI? zFb+U5iJORlXHOBuq`2hLs^CMmg#HhBIO%@esU)CDK+i#0sR%@=lW3t+_KN#uN}3)d-$Mtx z62fWRyOY=7&7$2uRLU8%o&w`MGm+{l<7o|-YU?{rkZSapmXeX~ailZV6BYQSTPRBb z*}U{007xKe14me9;0s{dv{Z}wPo%Hf5^1mPO`de1)#{rA5C7onMd?qRm+3#Fp9AjT z^M5M>BZ^J3)UO#oC@`cp?FLo7m_w+A;UEwo?dQYHK|6x&cqIBPSF^l_b9yCoLT5=^ zQKd-g=J?W}Hp%AqNg5wlSZQ$a$*I|lxp1AGXKP_~2umu!Bnrl$EQpqoF`#BsGjvzV4Ai$jqz-A%3q;>gUmdMkXXA& zQl1cicfMe=~+QF7D32Z(JdU!e`)naQ=*qG`i-S z#C_Tgp@z4JKQJ$!pmC)!u`NbfOkTUE8C6d}$J`O9VNv=h!ofUytCE4o*VoV2Eh zL&QluW=HpBdCXiPTNR@ZU(x3N%zd4@6Ad~DS*eZHHFcvVRPic_i^@fiD24Ce^uT*` zs#h@f8Fy zdZ;sSM3w;z$m~x7mfdBa&C7T%mn!t)voklbG~%Y&V2{HMq5!Gq{FeOJ8EXV0C@@@C z2IynK8LyPZL+?qpoLvw$^b+GN*Z{ab~2bvuPSlj|lhK4-goMLut%&#)KA%e;F* z9w*1Y>%5Q%Ax5>F@{8o4veY!FDlPQ3c?V$;#lUnFa%Ca2V%ZmlVxQl^!!Y%i8QPgk zNIQt@W168QIz6fzNI$;)9D$o(P2+^m%4LUJS~IR1{VmXJIQ@xJ(_Lug^D#l{{bIWN zezCcEky8B>Rp-4c7iRJ)$~c}#VCv-R4pXrZ0009300RM6O(o66z9NR%w`wvapPpic z@h(L*^XbS)#8z*l52a&PZM$!32C-`@|H7&Jk0j9u5Y!A{gt4#SgOORj8ZoE2Y*>pR z+oco4?7%5wuyf$rDBjy3z4do`yeX!U5B3V5X%`T>_ zMrH1;`Ilawq-Fhdr`eV45_epK4>H~BlJ?+rv(QlZ{9`uJ?_9VsEtz(28OX7Jt zJYJLd<8+YZ7+AZf^nvVgRfP0kbwJ@VQseW~k*kJmu39Z#fL!w(c^HAdOG`my1OMsXl$K67eocf}{Zy5eP5v)t=y11Vxm=P?nF2cECn?!7bMiF%31^R~1%Bh}zI$2<4tQ4ug z$WI5GtTy0wkDz-NwK#~$U&6yBZ1BEAoOlltMDxj=J#da%AN!y9!+62vV4n)&rU36Njocm z5+Z3Eod`Q`GASHUvT*g}^ZB9WdW#obkz?;CwH$L2BD~JBtDH8{j&&t$fVwF~b z?LjpB4;A(lpJYCF^(ZaG$x_nb9Fc4sn}Sx?eZjj|7Xk;d;e8&Bldu*Cjt;2Tacd$l zZF6SS6RE8pqY;gtc4y%@tl@A4GS6BUcno!#>lWVFOyvqn5rvi~%YFwKPLNy9zWj!3byewd!k8bv<0*%1G~TA9JTk z5X}}?k2WjS^K+p1P8=%Yw*8`?mcYvz=?eD4hiN7UH!eg(Y`pu|uLQzxAFyzC)8XlMlCap#1qQxlcOi25PSZ(HZJ2V1(}Y_)ee_&) zaBy~j=A#T=!l+v46OE6*i#vmucV>+>VxSx_cDNF<+u;wG`Buim6e^ zru#VaBg2FEln>Mbe}a0;t_Nu=?#|cJ9(g}1a;3{X%>%eP@#qraz_PF`wm;TZH>R>7 zXFU#KV6pt!sQx#PwB7@RWY{J$xFpd^c%|H7R)g2yuVR$=U`V@Eo|Hl>JZBlYWoiw3 z_~LiVMZN?wlxgLn@%}9lOm3JrEgFzgJejNoP3a(FbPEl(`|3fsk z4VbFt3a8KJ!IYfaVwk6l0uYx^K7-S(Vv;xcSEO&GX<(7xZcV$Nm}eMrA1*)c7uTf5LlHTMchKE z%WgMl&dzL~DXf{6;U~FXcRKsgLTiPYXV2W~w*!MM!6c6Ndtr8qlNg=%Ykh>ur zt?K+TXN~=9Wh$oI|Hkonjgn!R8Kgi$r-f5Zo_jNdQLr*rQw&vYLra4Ji0nS_QK41< zvYKk=hjtgHpEo+}Rlhd6(rYG6I>4r)>`UFflK2#0e&_cew4)qsh~E7~_@%~fxSc8s z9SP&}_-#4dlh!9=-wcp?bqPI+^%c};8Zy10%xUIxg{%OA)`9D_(b_&YkVW~kT&D~K z8c280aEiHUw^^Nos7Zz#U@1H`a77Q|5xhUShaX7h%{UN>t z!C1aG{BNw&8+NR%^BOUXG>pTOkMXYl6n=g_YU6hgqk_0zaLPgIRN2p6KK5S&>~&w@ zp!k_#$|7IS94>vesq&?hQF`BX8;V{^FQb+SJtKN++8Qe0wA?rPvETkDANkNbT7OO1 zJf0R`)ZaK|l{X>|J$;7^ULe|f={4yPpg^e^@`B1kb{Bf5zo?$kLgyljF*~DbvvGG1 zTbx8bF!n~uC+YuJ1S_GAVU*V}vO&l(8YH`y%~e3;#+48!$^Mx_kS2IX|0uVX^PMC9 z^{fwF5GsGpurD*Fv@v)3i~f50$aj(~Z99ImeO>JeusVPBQUk07;EOynahw@Xe;m0n zcZ(^e3zOcLuGzjwUP|k2I0X(zhZLMv=)C1u5Ka*zLc_TV!Y->RjZC$v z7>8CJWd0d>7B-~IE7oDzfjpb0q2+%V2q9O!F^0Cwt=#!Syvw@1uwh*NydYLU$>FYAIFtCDjH38QV3T#tUhDMq!EE2#YF)1o zEHytu)gmluR0aAZ)4p%Ad0q2ezlGg~;<=K(MKSJ2 zN&9#!_x4RRhak)9>Imxr=M7re^&2sA;w=Z?24EcT!??`$5xd!^S@!R{p(n`gO(BbF zfcw@MyivIrJU7Z5ycT8qQSbZych`q{9DMVMUnDt0n(Ga{tVfy!J%5xYp}hp|6~(WO zf9zN9eK&bP*hBf5_gQAx6E!@M^15|5P#Aw(n-;}qI2UKONH+P(qbnP-O#f$KDzZE< z@mp!52pUo!H8h@&+v3UpZG}fI-CXwaO`5}rvS+!II+XZy*UkNOasb+aiySkyzq znmGw+Mb}8J&$ZE8a5QVD^YH_cLpVxVO?(Jx>`J@`rG{1+KmDGD9Tyqr>2Kq(5al1Of!mpwxk2`x000C*cI{6Dfbezj zNCzc7hR5(*x@y=#U_`*X-v!0<^@T#0%7R0qpGSPbF{=#^JH&t1n@p3n_Kj4^qm_iq z>DeJF1$yr#1>ui%yqn!Fv zCql0`UbQzXee3?b@N!n;)G;y?>k#Bav&i(=+Hfy|XJ}kwUJst`1bC+B6Oc^v)(5%9 z9CZ0+b+cQ+fFQKMMZ5*cf_|-~5VaCyt3%l+H_^kZMl9)swOfKWmXQR~7~BSaZsANu zQtrxm-z68Eoii$ii}Ueu4R-XvZ9rkE?gI#bD#ib5E+TW%DX*^=J1Gqtany`Zc;-_1 zWGY#jo0C?rRUjWB)kTT&{a$k)_Xd$nQuoS)P~8y*SJtDDlu4ix5p_3Yi)*!TV<%t^ z(ha!=)_moK&6{X2)W&XIR=Z+?{gdVQZPyq@VxAgfM7W{u7+moEu< zRGzDuaj)VB!cnUrv8QDsG|!VHGIXibX*+5w*>h=485ZFnLO5{T@Rm`udr;g$G`74~ z?T2HMe(7_D@XKTkl=K$~b_w0dF=>EXX$Qcd6iRX;o`eh7WLXqsga}yGGT`EhYOa?c z{WQYtpDOz>-h}&7S7up}EqRC1#q*RXr_49|>A$=lcOCH)23{l>+Le=-j z20Sv#{9q7u070`tvn)A>wD&95z;Dwhxs(j(9R7{{1_5;zR*_!LdR~G`zk&SOJaLXDZVG2(J%M#?Nd#- z4O>8=;98MRix@o7g0jwoauOg@$Y#~i-c&r#Z%RHs(JRSaTCZ&6>bus|R)2n|Op~RP zdD8-)8zHhF-Ti>W0cmu6U1L~mDU*Bb;Q)e;D-fTA)7a2>cu^!DCIU4Y#u7d}{DrWo z@>fj1ZEd75k zS|-@cTxhyAC}nFU!8jlP&y z)l;NO1vlQBGt`Sv=jQ3feeIN+CY;dP_6ZXri#T}&e)u()VDiz2-QtycBuxo6Jb=v$ z-N~U1qho6OnPrn2eK7FAUez>Hs{Huj4dw-L24;y4m7x{3I*}y9|D~}UXEHIksoz5= zcKVBnL`3DjYplc>dB}uY&J&#Vc#EE|&9rs8voWxIsvaoU9o>01Q480X9v=en4JdTk zR~p7^$QAi?09kS|GUF3lk%aTM_z$&CUU7L&}?*S~(@~2@Q6~=D(e+y;k_J^X{OK z%wVuF3~HBPGz9&T?uO&n)dS*;GXo{Y{Uly`oG=AAnHLC?6Fpe&#&!2`OX;s=8R7aK z;vTg2CaKEh-wZ%VEs-yF#C)JsV9e5Fd(X(gYx!(H;jVFX8?EQCSFIs@SXyj#TCFF8 zYN0k`1U+?;yVPFUlO!03oc)+_ry->wOxE@O9D7|SMcp|EO7^_wVVWg5HYsWGX)lPA z6)6o=T5wXVmD^azc#@mjkmC6p&A9dE(75wazX!%TfUBbY!g71c!|gEhTq;su5AIL% z4VsA?<T2qw>q|&t2US)saLRtxWJY96PEazZ!_;`z-vM)5bY-WT|cYNy-VJ#Avdso)gKy zKm1|L;!G5dDWW_n5&L)i1_nZ2mULoc2f&fu^?KcW0BQy7wW>o+s*nfcDnN-mmf8n-+>#N%IMsw0G^H%qGTgXb$ zM@Jvi*MJ$!fY+RY%>!)(dpQu`F72Ey3=ps7dGC}1R~wZ)B22pK3?%8J@RC0ClurSC zj)@~oF_~YI$2M-^IqjJw4(de$F!M#ki*lL71O#nYUkC6YRi1-xFHRwlCPOXqltr>; zizp55dYsRWrJZb}^Z@ieuRzzM+>CZ$-fy6xVS(14hmJ*s*FwGD^nMmI|9&Nlo4(Wo zP`ix?!ZW-))p?$%o=i|0?yXu$v_s%!QYy7p5sgnvFLhlbuVA5x<$Y=>xXlKxGEdUK zhOsZuP;}%%Tem(hvtn?uP_f#Un-CvVP;oaDJ&A8!mmuM9PdJ}Sd#0?^YO47 zNc7xN`15gE5>3Q1PVhR-;m@GN*LIIjVb)@49UbH21+8(d7>i|F6+rRDpxnBJ%)_l` zVdVPcir-K3cxI4SJ!uk!M`thUMp4svN#j%S2Tc7? zPGLXa|EFPjc=JvWHiT+Mj_*Y_Ou;+y1;R>*%*|u|m%{l`AecggX0skwQfA6nC0D4l zKo86qQ)z>JcYuVJO=Q9$_Ug}cyG&V`1{ffcdte+50 z6L~XVKX3w8uU;1xS`IT1o^+(W;guSJ{qBev!XnkAt|`5Gu+Lh!$Cr!8Ir_z#F>Ltk zvUV4%5~WoOpAw>I&&x5J^GXML9Q8Tj46a+aRPk=8VSW4MO+}%U&Hzek8W)QJ|qJ z0cUFc(c_#4A?nTu;|38XV(B`)6*{mx8N$N`SUq)RV;X{-N8ES>^&bv)%MaCxF&r=4 zwh(q>aOEXt{M0XEOCTuyGm2LtzH2iN^7-ZB7P|ufOqKwVDY;bX<>0YsJag970HB?V zZ0lo%aJ;&P4uRP)9VGtt0?-qDRzha2@7q7cE&!&~Dizv4dYoTkSXNZ2C6cv%)v$4lZ@xn$gk<^@$8=pi>-ROzZ${-_lGmHy6i?PFpTeZ zqbJzpLzg>=08J+ESEsQd1OuQCeCC!S!V*lJwSy4y?r^U3HB}fZmb%@A$3j{kZ9&MH z^B9bd)S6i4HPRt@cc`n+?ZNDyc?|h-02f%HgI(R5FSv-!`te6L^{~obNIHf}c2w*k z=cV2Uj*DS@)OJ6wy!5k%buiRJn0xN0PrAQ${>{8evp9-7)r6ZjMP~-$iggp zs^4kSGCF#_{~77C*hNeG-*v;H+Md99f}PS;E1o*mJ8I0llc2M&b*f6`@llRNV!F4d z{=^wLghA3L8X> zzfNWDegL&-hxwud?pVx#p*R8rJQV&fQaW2O%-%sdI?Dt7rcPCzXJ2)G>unv^DvcP8 z(e-~3_h}wwS{lz?z@^@!EXeudwRwJD3-7s{`dMkK7H>V7*jr=%*E6>ek$c++`-<%Z zI9~s6&s7(Xxt+$%R46v$rxjnX17n0fH-4;j38P%6KTCE(y~c?k!Bo=DGqQlp$*w9J zy1kkdI@xk_X@^EZ#9ydciKkwk!qp89oucu=Hu^Czr>_TK~KR2hN1Z@Duc!bjTJjrJ6u-~Z?d{=Lcc#FG(PO!=`<|EcbP z25%N{A5r+lfFQ{?KT#Ax;TUe|%`pGZ0c#Sh=!y~i67ff`wczIKe?{ht21&G<#{N#9NNgZU zeht@+<9dyahVH*i&7v3&?s;Gu&j9pA#*(^VK&4Gq0X)thER+>q#KRm z_1-Q!A;s<05RB<{^pLi2yqBnJeH+VB_&BG$&4mwY8Jg_sC_Z1 z1=N5ZDsQr`8p5%pV60Zv{Q;!qSpW=D;V1w5@tj)|l$q4FZNAJ^wod2Ua!hG&2KvST zjE8slebk~RlURa*D4veYV7cUB-A(m@=5Ncn1Q1YS{@B-**_E%AN7y&`q@J2`BpNw% zP^rL0yxGe_Gd|Ym+vtl`N)hFq8n!A;jTn8JU51;Q4o<=)r6&+no~c;RRRyk%(3o)P z^d=Ohb-dKI=FD9ppWEI}hpA<=K=0_?&o){4ulcyvU9sMW z2EaPPyOJ?rxGHIE@l}qo%+d^N`Y+7YDF|cN|9dME3FfQi>s^-A#+{fmV5(NCR38dA zv_b_IOL;|M_bHF1r(S1+3bCjd7gDLtKoUNXRmqeu@sY#5RVxJ_2vO^z^BQt2b6*Bd zO~5I`;z0NvA2|wNchK^0%<+rsi%|Y|&BUv_;K5vp_4~;PkEr6BOjNz=5)v}q_Ca_2 z>pU3qZ$afCamxUqzoXBdnKljEg{edR5@Fx|Y(3VfCIc@tH%a}#;Oqi2CZ7z#1w23i zGy-@I9M?Xs=@pP7KQjX+W4apxo?n6hRb4T64gL8VG`z*LY7=znU0>E5}QTyF154!U3Ywgg*|JOi!hoEEXx` z7TorY!tH=fyUDti^-0qu9Qagt=cZ{QHM?h15G*EgR^Q zLWXA8D@8iP%9Rlh+sc}KpoEGW$xv#5p z$7|uqDYa9YRr!bqSC7~YIwHKDoJ4e?8C^kvhJ=fd8$Tjt#sWCDsXwfdqNR~0#JwjI z%?^`(@adbzlX83?kRl#xe`4*(r!)577(@u}y%0EK49Af2DjoGAh64mLllePUnR3Rpgv7&f9s-)8VsjTHko z2mKjitw8MmfIc>P zD-A*XK-R{^hEl#+q}ai_DnDOSDU!xuheoWJ8aPvhWee;8eiqsx+z(f7B7ZV`oe;iu zS}mQUs3tX$y(Q4ChA;naM0(a`?shA~3W`IJ6(h0wQ(F24oh{^-Xq<3I(a>1Hs$X34 zt%7l;ZsNhX>5LYH6&}o4IX4Rq|+ElIzvSl$^J(=6GQ<+n?cki}!8~U&`-CjERoaX0ekggPcfNLwX7{Hk6U&!g8`!P;09=85FSeiib@|TV1pZW8VWT+jU5yW6S=K; zmx?5VYojRdan_@7M5&K0p!ssP!!){`Q!299M zb8HrF=CzboCj0jw-HTcCBjrIEy(%)=y=gYFFo9)?fP!+?Z5{M9Y&~*C9R{9K%KzSv zChhyTJMY4h?lk;|&sB;Zi<~Zx99Z+PcW-H%)!lQ@UCg)vdo&rwfEs;X`da(3H@n7m z4NUD{Hi`|j;n(Ah&yUQ+TmVQuDD`7}0y1Fc+5F2ejBxq7GGZ9>r!%Yl8JDtZn_tRX zQgUuBm&*X2>{W6%f;+ZycGxbCAdOIgEd+c4Pe|BpInM`%A~Je7HXEis)0siS0_&YSgzhL&;_+E+>&jvWP49)p_QdA3Gxn!N)+TyzqQFI6{PcN zF!Y%Hi)9fY&^ACb-r|^la0|Y9_dfBd*mCuLw%eKUT^q9njA82u{|}G|)&G$AUUTCJ z<6o5yHzY`G5G<2_0yLWaCm4l~nh9iRY##&=UTd0<>ne53%H_k2?4 zqV?3bQWKE^+LjsIsh|11oZm$eow0G&4cn|gO5({LFM7Zmjp`M6ls@mI2N&Iyg8?1+ ziM1?I6WTA&@B)%YXQP1o?2L69LKagkP9?C+d!-f{&GZgB=U_P>9Op1GEa@sz&yCno z_~K_jh+5jLJHm*^!mm%G2w&Sl+svkw@r9P_1thFcs9jUWS~2t5@@;GtH#-AJGGfq( zw^X%+6HlUR*Dk!149FO~+ZX3?AjHuSKI=?jnQ7fG=MrEzdJGS(Xo;z+YPmCEo?!Oe z=vFu^HWHx2mZFjnBn@RtL|s)axf81>+zvm9GZ|+TOYoL1zsy#17Uq&f?Oasb@^SBs z4Tnp7A+H|b9ssrMr*<%KvXD@-7(li^?qm;;p-@dtsogl*=?V2KjG(G^dQj|pt)_C# zB*NK>6&0^X*0)rX5C!``3CjEecCtP(rn+=(*q&z9=Qkh}DAY{6EjZVz-<5*`$uFPm ze%Zd%UzO2Ky@nAArpE+S2ElV^UGt}{Wt6-c_GLOW04Nx3f>^ut$Gmr7gLg>E{-jmrJ%} z^fosJc7B3q(!t1%MMe*b44^bKrOwtvoD*H|eJK)|;DaX!_eD^sgtDO^ThYdi8~7Av zDCR&CPqGpAl9e>^Yfcu_?GZL}KRj&Uk4o8yu4EF-7AD7g2>%R z-sH?-40Ax>C47#B1geI}`2>KjKzGN+J^{mL;Qa?PP0R%%y(HHAaklBkBOk?qeXFn%bgON0lOF0A?Eq}@#5qFW`mwBg_zoJ%U z6kR?;$sNGNm}xOhegLhAWlt{8PZnMAfETilKGvds53{3EaOEc7m9ZXOft(~Rvv9X) z-iJ^iV!$ARFsK8&e$hyEB~iycFkt+qPzpc|6cT<(#ER0RqV65Fw2(o!($4j|Z2z

    _H2hWu~L6kmd&J$Vt5z3!mLDBPL+WV&f<%Y#XaF!6WSFJUF$CzGJ8yYT56ynF?4}6HRFM z=x6^!1%VZOR<%1hYz5HR-P>PAcFo=Zy)lFQa{LG9#NHWL=0Yqzv+Yt?iO1fMWvo1r z)!i=)E-z9R*8h$=BC5f&-eG`pa6UJz78vgSZFDCIQ;CA&GCYP}O&w6(WqSoKswA83 zE`doEs@t=i?{fI6A9kH;`})do&hyV=WZXeE34VZaJS<3DD~|!w^)Ub}CpvIE$XuNM z7wIZ}TK-@Dhl_AbJdt6Fv-1)bWL-mS$!+R{{_gU2HX&9P`|VT-59)-q3_0-(m6~RU zZk}4#+;(XdB*~ZAs_e1kcpEo*xY0D}koj!;zZP0Bd*Jx_=U)Te3L_{@;Zhq^ZIRv8 z_nNo_;-e)O#bz#%KsQNKUUYf3kgMvt-IGF{dJcqd>s2P)nbeOxrM+CJwVwyy@+wMcn^j5-63L>(SfjWIfDh;8NA3*@tgf z2=)1GpLZ_47QnpD#YkKi6wzQd6T+7sY&p=X$Bb`_~^4KioWu4hkfmCyv{N z$qFOANR~A7>^x#e#x(wmFW{M2HbP4yWL5)cJm)*<%E)4p848anOJ|xXNP@-#4^n=9 z?0%X4*1zaIJPh#q?WQI*JA9Gy87@-hxI;&%C;~gSN^3ax^R)#+dUH+E4=$zH))7Y_ z_?b>!ANgt>m97=8RF9eJhU6g6_&rfbw*^Z$t>b}X8_2ruIIiFU8hIW^ljTTo^6vDy zRmAVy6bC?6I!;4HRMg64#0fJVJ|pHQL}WjjDM=fX4bXvus8`494Orx9!iSH%vmxlt z!2Yz`aA$Ke8OCHJf2fm1M<#WlDP)0&Iqsj!L~CX@7b>5DP4PI>}t{9<*s;&EBoS+@2?B7-ox*}d09(#}2{NjQ+&%5;(! ztHZA5I(gu2wl~^Kt}65fh$nh_b!M-M$K9Gh+*-ggs`^TRDB1S(S)hWK4w(DUiYY>* z$JpJG5YJDcx06x zQ)Sk(cAJUONj{?;zQvQZ?Cb{f0zF=o-^1{#|nq zBLw5^%>+WocAu4s^EV?ubgXCS(`i)?jV@Ye#;cY%osjjuk_@Y`gvwo@V-g^fz#jJy zXWmJ|5&~bI+4qd8-?OeD0G%p4&;SEWI=5?_*k{Lf^63E$Pr^7*DRf>8d!aQC%QL;= zeZVWy!>HTT+@=r**2{Zms0Sysql|Z8Wc9T#-!(-xFL!86s*(G+Xp+{_Zh-?+DE^-= zn@fljX?JMT00093I}rr_o-#j+au-%`zcKx>ECt{U%c}_om@ybM8BX&5__npbN~T~E z9tNk;y2=6Iy|13x+d&Zw?4`rJMNN1It9W-&(5`!!gUB|bb9Jp?`eyuJeLL`5Jhvxa zx{ur~t05EhG*oyj44{M`O*PgMQ|))_4z0}mT%_8F(L~_UM~t0ogV9=u0|}sEi^v`? zn`2~lkeK}!H6T2(ocRj+gc!g~r6Ju64W@HnNz(NlP?OsZVM<)xLB@9(Tnm&|!o=7b zTzp&HyhYjFN@DYvnXU^=4Ib~VY4hm5D77-*eZfJ#JMl5WyomDrO=h}n0|mb+g&2+` zZDqRlV0dSjm1?eGFW*yL0DMnY*I>f!=-DKeGeJz!*;5jyePmWd$NwtCLn_6rOOk{c zn?m?J0Bt}>0E#Nw`e<~Nl?1XR;8Qt+3EC|Cbkv4(mi7aOyWt|2rj%<4{vfKv&+Na2 zIzCKur+UDIbVkhF^ov};FMAISb9s^P-a47LVf!tV(o!>(nR>2c51va^#g_x;u9tqt z;^=1lg1P2fX9C&dA*!Pl!7qfuJOI7oY%*@Qrj!oL;!M&V3UX~T?pxubPF?TQdl+OG zgYAw2C}I4NdPA-Uc zIM2)nX9t-aklY?nO#)k4O#>pWICTv*hBmcts|Gr}6C%Y^Y&dw`g3?Q_$8Vp4>dt}e zb*rlnxdroo^=u zf7A;{AGB`vuV_sOIiQKRM2d-?YJPe|QrRN~p?5L=fi(9{zpQdy1v+Oyx}8fFfhDt% ztYtQ55&jE4FF-Fp!s*le6ET)w5}l!{?#CW7OXYJ` zDH>Bp;kNbjUQ95432{&Om&4oa=YMuxICjdZUHlZ^$Hpw^bljbhmXaX*b#au?0M)zG z^#Fv>i*{o$2_+u7mOS{+2Ko1t?BzT=+|~<=)mumM!lmPT@SK^QgtLB^jer6P{D>%1 z_-P1t>1>bFlddCmDNZAkv~b~{kC8F#T1EmM`3+Y`(UCpl0>yz1`4E>Kfmbkoqj;+F z($g6OO0cN#bNHQut$F(lmJ@O+1h{~1?39gefQatt`(*flMu=ts79A^V(-AaCG;k%q92pYYzt;P-aVB)#)U?k=1pM4tp0_JqjZXeeiKNIv16d`q(5RM93qFE z7pP*Skz@9H;5DXlP^^-5?69CE@G#!u#_iA_?FxqJ2+|#q_x-xuNcR^?yKWl?KZ=u07UeTLhEqyL;~P|AiF*27@Xa0e zREP`KD{kZ<(Z5lY`@!>%XG~f4c2>V^TV?{lzMy6;ujgjDd=Xye&zZCi`hjs^JG9pu z57#3Kh_>lv4#-@Pxn-q*y;}k)4~ZB3?Skp=>x*8S=T{jADQFh@>MDmcDlf3fgMCG( zDek}SX&*}JQ-&rs*Y^GDe;{Rk%j$AG1(G^_|oA0XJlEZ*?JR~#dZd7%0X#B zoCy2HE{1CsiVl+b7Pl;8@GK@t@2}E?yomjb<6j`ge&UYSttSc1)`rj4#Au^ znZ$F)=1)?0{c&tieBdHseSF@_v^S}Y6D-FXDpao=XGVHkw|kd3K&k;JwXj0n%mdql zpw_eSTC*mn**8F-WU2gscQ;mYev-;ooQGgPO9BZ2^Y@0ga7+ms=T&#}{uCOa%-L*t z;|@=+1hjzabWdU_q+!5uqeu2!%Qi0$&GDXKPMo*rk5t))M!2&RwZOn&64I@yx#c!7 zlsPWD^~Wgzdvp+6G002SS|9FF1E9ePS3IC9FGm0CL-S?d3X1^unvPN^-B)$}$`6FW z5kPHluJXFNaY5^z_hGM{lqtYW9H#cVNuV93sZs=;s2ByJFv6u6%53yk;*q;fd0ez# zBG3E+QiLJd552r*Ui=W6d z=DSl?+RFy!UU;f-*^LtyDaIB@&D3Z)@4GamQXbZYnEC1yfn1!$wz_dG{>-g$K94BT z!));AX~op0tTlH@ZfTxv_rcC--Y}!q>CcGk>EVun$hm~Ox9ar-l+fxeV=F)T=i+<7 zL=3qW*>Av#Yx1OM`|JCEcOxd~sP+Q%r#~gLtSYi4&3il7L3uyHI?M@O1_}*hr&gdT zgoVn}0~MPU5vCz2Dy~dmjE^E_|I*B?BO{qlU*dcnc|iwC;k@>J$VkMP zaNUqVFHP_&3{@5qS3uRH}?Dbf~p z`hHEYE6=j-{M=L@Iv45P`Z9u_jBCJGLHo@0sc0O+p9#szoaKyJYTOPP)>IHHbgWp2 z>dwe9|GsrvaVFT@@8;AeM9V4sQ;KpkUF^hGg7$HvLlSfFpNFRI0L}w{=%7UU3*j-J zvm&6)ql&j;+xSBBl;={6qZPRHo}uSAfhL4NC*S zyxfZBBCBuRXV?J*tYvHlRFX%_(!6)Bn2`FJC_Pv2n>|TBf20BaCvbDSP==c49dw70 z#Mu24QmYNJ+prcx4s=3rsNa?mm=D<2BO$=%OZb7(MG<;+QqZTuXGXtBq^4^xmqN6> z+9PXBMBQXhkt*BrRD)h(q}KOGnmsxo_unYmUBJr44^^r{03=X={TN~At@u06HSp0_!%XsOC;?c{VMK8;piZU@AgwFoelx*P-hw3Cx}Q-JJdr_1SXM%nTmU zcWx#ik?E^n)lZis2QVuRVbMJVV6QJ=i674eBZkb}LEzDsmWEg^YZm7Vw#DFNs;JW@ zOG*oh8Be`|6Q_zi`IfWI!UX%qIA0xq8==`vXvnY+6N6f1<^0Fj4U(iy*i_1&t(07d zu52evQR9jYVlmHV%1^W0A;Fo-%T72a*QcOH7jsc#;S8Nua&=)4vR>DN$@soduMDBM0Qc>&~!!N!31U{(& z`Bnq?mJYC>?HbSW_LX>G(TZ+E$;-2f)R+K0?RS`Iprv93m7X;0$?}xIeEpFD369ez zo(T{$ne-U)F!X3B2Kw>-?t%8(S|q^F@$_66_){yNWW*Lse7;-CkjTo_i8Ip~u-J4< zvTM(|YHGVSL{j8mH+%K{KzvZm>M@jJ{bNdB1M{H=6=%9Rq<3&whbM+Q)Pgq?z7PBp&YY3MTxoE1u)r zlkfBQR(5SfPlBt?`f-(G=`E|yExU50{j1=8U7cq3NLoPzEm{reqgEECOlY-q;PD?t(xk30}W4ieE*hFKpo z!YRg?=>ed4A@#j79je&JO?5m}a7J$D-z+5hL%@pO4<@u2?3uc>K&Vpf330%Yyc=GE zx&Ofg(upD6u!wWq@=fXN9&~?3WRK1#y1e*(6)QUhqd`Lpq2o=a+h zu6}VwN4;TPUol5P(yo}#SYMwQ5o^6l$%AB$YIaZ-54V590tA9Z7Z-VC9AV#lOr#3E zA&x@OUAMXPYt2q<%a?x~oP9}nuhEExJ^)AJXmZM=FNZ3@+>?E7&Y!(Oq}VqMkq%wm zYa0BQXfq16oOt;tq78Ka|8naeWBPl1&ih&Sa7@*m&0(Bf9Iuy3=(HshOwtXS@DUuQ z@e&=U^TDX(OIE1qwfDm6EwW_Hl-OM6OJL}Dfk!-%tzGA=7(!DG5Hf~awbuiWoOU|+WNxVWeov(rI^Gh0aVn8&-7b=*XQ=WB;;%I%w2YT4)PaB0hrgh zjea(yQ|7X^%l-%BOPZ@C&Bsm(Fa~SrSk$o7Y~&^I5H`nV;OhS>#=0(9-$`j(NL>pK zLFA!8fPwz^P9IZ^Dpr+n^#BsfwpO9=Mo|0m2F*ZlFO7QSdiy&K4en(watP@ztZ5%+ ztUMcp*3#gdlD4;vqT_yN0>O(7#?r>@W3aKHvkx-PAG~uL7etDj>wMxz1@;vG@Deh!^RH1{ z=3;#+oK!2rqjJ8O8Ik9#bOmKgmH!n|0JJkQS!fb-|;}Aev7Z}bmr6@Ut=N* zOP5g89wb{!xP5u^Qc6~8JCZ@>ac-2x#%(M)_N9CRSm+SpFGz6R`WStx3&3+OGIS7g zg-f&^ffl5)Pj92l@>5C@o+J#hnBsz4>0dokAsNfqy02vfD@wj=I4O{Q~^#`pySD7Mj` zd2wEB4T6o-xl6u95?Nul_#`^_oDkpxgL!^-sY^1>lWfi9M5S*~3I|QX^Qk!D{&UT}VjRtYTeQW3F{Q zxu~{)#d=%blY6Oz&&cUE1-a;_4$QifCPo$HJl$ZLc|YGFk*x9K8k6hUzetPtQkNA)^7yv11znbCb%1+5bDd6i6<7Jk5u5N_|})$X_b3 z%Fo>y-rr=9H{ZVKFe-a{T0i>NT2U&EwG|K}il-Uy3eKXA;f->M407VLY*Gs7antN~ zy$#IZkGhM%u7ed5PAWw$}*P&CWmG9;Lj`f1eCQ}w*>{q zDHq=`Aba7qb3?%bY5#}uf#N`qPjRJX%co^HLpe97p})}ncAO5z5OJ1NQ`<|B^1_F` zt&%#%k{AERk)fpGb}!76AQ?yR;b{e%BMu9>p9T8>pwlEV{?EhWw_mHx^7K(>g~UQP zw__-Gi1Y_-+AN=>&Gusz&1+r;`JlJ;l<>VvfUD13z+gnK0>eDEQ~n)ggF)xB!k zj6?>@ezi1UYFzmKOpkhOMm;5#=2qOtH-&o(FZoL^@Mw#rg`DBqk=lBH$I zno>Hhv*_jmSsBhAbq3*x+a{=>(H!?yfj+b}4wS7Lje{v>(WpUQ(kh;d0zU3*fE)dc zK%yq8^qHIVWAKRZ?rC|u9`cU1Ao;pI3tmJAU5Y-fR)~4A1H)*(IeDysy~R&w9-8np z+Gi7~-*MS|45lcYE_@|RM%7qVBp@)90~nd)SS>ak38Bi@F!NlNOjX%&SXou`(rEp6 zke>o2Eq&Uw0AfI$zxI6Ro@F7%96DZU{RP0U2Orw`)yf=&^2Gu}ViBi@su6V?ChbjiL*@ZM) zkJlbU0<@bLsbo#xmq!Nq_q-|AqchX|yEi>PUwwH)-X$M~jd(12^)7djTde7laRkQr z&@Uwcy5?(IbOd;PlX=g(DKU{eT-GcQskYqnvypmeTZ`bjGoB367{1>n3vJ{Gusx46 zUxb|$b`Ba0aRFB5b#~OfA32O1j7>L?g}C?xp8?3bRSa2&9e~TOC`dp{&?zE9Ifp$odQuRx(j~#1>78E%obb+ zReJg&VQT-ob;s6!aL#-34+^TF$J_U)zj%01oeg*&&fdc*Z~U3TdLUSR?cGCqPL!)FpEDslz0O9!3Qm)HXh}-AmLL)GYBFwduazmP1u6#q2F$+8qKqhO|ziZx*1|AHqr( zq}x%Fi{&}Paf&90@7E{4(KJt^#DB#2;^1*>+Hs5&2GbD{Rase3@r6t!+q-HU+%s|s zTWK*U*#lvv^~vu^^hC$!LPT~WhrNL|knxATzrB@la}^6rs0(Ko_&d%2)l6o&-~w$$ zG`1`>5cvbgt$O&jZl_6}4WF3~kIGddqzON@jn)=Byn0iS7Oc+O*7=UCK22lX$@#%g zgHqpF#j3~yQg9P^DjdC9FSW`Xb8fE#1V>Bo{&D4>dKd#blWl8Dnllu zIHsoTv7SD7{wA>P5Ja#(wZGg(;!q=7S8XPDk$X^%2mY)xIs;Ug?;+RcVy}bT0`k!% zw3+=-?FhGe(DB{D^xTWals#e@3KjnHRt&1S)xNno@z%eEtU0v&pGsLe*h)3=D7hq1v|$UCWABAz

    aga=VRw636JK?S&GIYnnb!gEFQ!eE!XQge$yod* zK;)f3QRJPnhQ@Hc4_PT`viPBs~N~nEML?6#a)DYHh@M&mfWJ{}qM2!rB z?Ns1_OH}0uN+PYOBNcghgx`+k6DT0wE6`Y7HH?$Ps15MWrQuYaQ@ z^2oacw9Z2grnR5@p8)25{`5KLLxKqh@+>T2 ztLqo+-A5z@6_v~(2}8k~O{FrQ5@#DhelUifLBi>yv20@1-y4{UQspkbq!iDa*1YEtPeE zeX&O>k8o%~zm9k0RZYZ%gSkr9MWG@1rr(udDKa!-qWJpOW{k;25IyIGF_c2FUHwkR ztT?iRT5-56etD}QsCc;O(je`W6+R#7eh)6ZbUB6F_PlwZC(f>e!k)aK6EqXyS}9CO z4t<&c;C;tppqG)-Dqvab8)WEvJ`3)xU9%M-T}W;zTScvH?08WSKBl@I^Ox!WzZaZi zm)Njc)L>ZD{=zLci(xU#Nb;&juhp_jc@OVX zczXc_eKW0x5iLh{GWh@-K}rlLktSJM6~R4uFT*)79Ld(g9}iGVd}xU zV9gJKI9Jy-pcj`3;?6o)tQW2z=kl`?6Pxz>;PxVtpT^Oqgp4{+Tfe6p^L*329EsuN z2DW9kV?!L?*G5R3%;}msuIg5=tT8qklYP48LL!NqfiKn0CV-Xx=`DGj+P^R%=)(Y! z^|;e)u1ji)rpojb$5A0jj~?IP7nWKZ0PA&=f4!&VQnEDI`Hs1Ab{}`REB{SK!m-J< zy&pQZ3UzqmIlnErVr&>SR5KnnDB^~srl-A_Q?6%5wbYpkp)e4vK6M>HO-dVI=ue8g zD9q7_xxp{Y&6ZVMWus*bgd1PqD%+4y!bH>mJz(IPIfCL%UM`r)@&`gG;+G0q=PU#~ zEjAI_Eh8enjbPBO_5RgK6516h3QYQ+?w9mRQ^C?kaJtbIq2dVz)MG8Fa$z1iRfph< zmwg74|0uV{QVFMijz%ghBf!T0dWCW02r&{;=uuVP4@)f=xRup#8Zdp>&^1)^t-6st zvi02vbiU{7E+=7=0+@$3q{Xc1nnzSsuxE-F48?DX;Zh=EWKjv&u%km7v7h9iQ#xVi z4O!Cm@37w(XGBUIlJQ1_8U58|n9fTRAV8I@a~*lz%D#26;1e$5XaV671hir5*t7>T zyRQVx>VkRRn^<9gD{o7Zsa4D1buzavum)Ku`@!P2e{G7<~k%=79Z8Qe~!AHRHu+HIVPU&G-Vw@<>^; zvG9~607FAsnlS6X`EF5gRkOCj42?!FaS5XqRD#J# zN!}8q)~Zc(5Tp#Qb0Aty9-dUn_R(1o>O~bR-?5`G(T|b?sZ-#pk5p(ki{2ikEYb*G z4CT7^FBlsRiC*z+ArMpTQNic>s0bu+#O=I@s!J7te^@RY86O_jvaljA7oSsQOju-+e8L^s-*d3e&qr1ofYNlIsZ)+^>c@+Tm|>sI{%DC8u21l2L?Tg(zDzN z#?>qQiP>CbSU>T~F!ioyKxVafrc|8;MavqHdg$D;@?dG%V~Ue37rN=)mA0JVMCmZEURnZ~AJ5O>nyr3Z`5+O2b@jx#rBUFba zR0*ADS+8*gnQFKrb+YdNkSqf|E<#&G37k8g7YoVB_ddJ=MCJchky0{-|8Bq zF)kfQCks+f<)t{Ow$lrZ+DSIzOjlN}3_)7xKK8dX^IAA4aoI%Zsqea>FBmJ`xBebj z(0V}#@6R0Q&As3c)e`06NPtj~>YVG-5#14}OO_Ae1p4sE(JRi5*GMD zW_smzI<%E<)i)mS$h5eF~m%b(#9@1{OH|?_nPyI2@#V*$9-~+=YHGG8t zS`*|JjGRP($_}TW@hjZuj>?-*&+=M>`a%_ExsR9|f+CVEO%gu^8}-Z*&{#5xCZ?{^ z&xzL|Iy4lqIHw1k5ha!z%;_@Nb2h1IkEyx8$i$M-<`$c|@Q!~>pH{FJ-Euuj-967qI& z$)p-W!@8C6Q%OW~EzB0JD;Get$Vv(@;BSOty@;N*~x}*$}dwrmrpta8!@3YJB zX;!Vc463lUrNf{NG^~xO6%dK8$l+{h?e6di9f;Q$00Lpp(DsW)jPc~29dGP0Y}9cN z^%|A(aXvh}g#LHjFt00j*2adO%YnfrL3>^TRbcguf?O=lP%e0A(g zAWgp32Co)Y3rwFop`|UHkZVyx^RY#R@w6n+(d!-X|}rRPE+33 zPLo{Hat2-MeN1mB`}NIiz%;rg760ZlMw7dac6{C$!L^Ca? zc7XI#D=A^g?M^#T>rG!e(Ik)?D(IiABndYl;XkLzrp5khhrX zf91Olct5C}Q@*hQq>Zoo`LkJD>T96a+tIwS++1ne5(-@y1LAZ-=}`w9rh|FR{S%9C zcX_-8)H(bMhR4T=bi$~+_sry%^TG=O?uJ4IENu|FBYLt%g+jfrW~8;forYp*rP4)p zrAKi*kAovZs7skroo@hy#`QZGH|)q{3lbD1B7`C`>*lCVFW@X$(S|p792dSRF(rX3 z4uy|S7Aato=^K=bee9lixRNQ;MZ@Khuha!H{(kfDuTLIQt@gjuDj;~iY`Bxjj6b;w zdOxPSSmRm1aCLCczLmel`Wg7#yYtS~ay>nULt-km6BHj`Bbq zGRpi7?IL1^*}i2zDah3G;0>ts(EvKsf+ex}LO(sopw;{C#uMeO8B34@-c3~t@`m+Q ztvV&}l7z$;!MHCJ&A-{K694cW6VS0f=s2?lCqAc5>;Tb_v!>1KTgA28s{ubn00e$V zuBXn~bB?ubcDBDkKKSF@Rup{@H&~uU zd*}F#Cv)h{AtZR1FkTEL5{1ug>zY=nY&MRJGcO0k+kTOi8{fG<8%~{t`keHE~p{wr-#ZBmj0gcfAxrG3anl!2L9LPKT3Gu=)qt`2zz1ueZ^QpoD~ha^M)3 z9j0KN0>1d4xV!#PzhYI{L{bOkQ_$t%xB*cj`m0gjVDm~D)^mkZM=6n${ixAb0)Akw zc$|LJ2jWwuO$VoU42Ar^;O!a%AO0>V&$T5K3Kv5R^sBP;Z@NM%#syEz4z@ML>~$n> zOK4TW`}KF)?e6+}7^h?d2+@l;_Bq-c==He1Gayo-UF9W5x1?R4)ewbLqM%HMm?JPw zbDO%Zgc+f3T*Zs@OK>J{OXzM`hj5zxy|T3&gGd~uWyeJD{Cx3a;&fF&ioVIhKGZ;? zqS<2@$e=r)+>ck+gZIRKZ|bROTkRx*38@{mB%kAs%p{M!kQ>VNkv*ZAKC?){wD^#j z^q-Br<$ZTru}svO^ilp=B(!xvZ9?f_W96^wQ6M*IYteCJZlBYZ^Hx8FNDy9#W{3yI(H{47oC^=pU}m6OyTP#6&5c zV$|r=Sh4h}O@`T-ELmHCN)N-0nrrr29sj|9d6;)3sje9R39Uqdma)>=eUJlUcV0)8 zXR6mCBnS0))bp^W8u^yjTd*6Tp&4L>;>Nqz7nS$uSu}5%G(IibHSTr;R zWgRJ)NNvmurI-}F*iIN^7!9F=Psy#DU z2fcC*_Ks(O{HH1{@o-a55n%)Ss84>F{vVt&s?IwZeq%=b@RLG+wbPqO9F>GsTtn{^ z8l;zYJ@JKb>fY&Yr6riz6JjV@33YR*xT{f7(ENtI}6EsDZUX`QER(xWSW5R)`r-ysz`1|Cp*{Ar;ETUN}Ds;sBI>2Ydc9q|N? zE5@#dYP<1s+Oa4}ebVuI}N$9#ms5aVli>lP^kwLD;tU}|Y2?j`iop{M&c_`=| zoa_nArtf1RQNiQE5PMSfcKo1B_b!6O&?h@eJAlU~kbc6ZP78iNBFb*cTK443L%l>E zyk7K>LX{hTq|+(hiB1W6!cH`IUER=OyVeB&D$L}ge6OCfH@^b zBgTBZsY|rF6ij^v6%kI}&fiR2id8wwOV2~op??8N0Q%KdSVCffPRU2KZ=JstKztQj zhOG62Dxx?iXV-i30=|kiH+Oa{d~+WkH6|c_Oz$N;_-V?c$<~Swx>!S0FC3rJYg;V6L|~y(UW%&3v8UNq#0u*2Dd6_ z2(RE)8P%QBhf%2x$bi@YUH{;C@nOs{A?PG#@3LbMO4;tgn)G2o(gwMNF5dQpm|+G& z-orLbdZ2|@e7pRhf1Gl(WnY?2s~sXIZJ(jE$CnKu?gvdhS6rrf?2YhsT5zI0I%KOqC@))#*sN|K{N511m=Ad9WN zdp^w<2$sTH6wu;SGs1@Za`(haK3LKY3a{zbL0BmL!=X$mRsR^rRQZyN2?@W+!2Vp; z_82YwZ;%OGql86AFpj_YV@}MFBwcAQ!p>MG%lV zk~{0-kmiGQNT8~Ldy*dLjbKXR0$6UE)sR&SYZIMc(wU9HYEgnh{u|hAL?oDH+>WR8 zsw; zm7ckEn>C(0ndw+MUU^TYyuVG9i|NM63-qwHsfbvMX-UzRp6WAlI5v&Qyqq2enIQ3fFAo)FZ~3oA{93n+6%?DpVk zRK`y%qwioyt-`}(i$f)KLw%qsc+lUDykBlRQe0#9dBcbM$Aw&1pH^hdFc3ad9P~tI zYNb?i+G?GizQX}-shV27+!x4~?l%GN8hEqnmf;WOJCv1a4Q@WxR~G8P-c(f8y<_5G z^YtlpwMhYASTc1DA)VEBh?pmr|7S4G3@2gjV+3QiU9g!e8H1jUc(E5!9BN>HU72~e zjwfjP^r!up{|E9quoS(FFcoZ%20I`K-08qp`7fgz@a>2mt7t}KiC6#;>WF-P9vmh2 z!9CXm$s{y9lh>{P|6Q}=MmfuA-OPX3aKR=)v2U6pqXFWx2NS9TlH-(*=>CDe&M zDAG~YB(|i!TIY@00FPgiUM(ky-=YA08;*VN^Y4^TOlX(?0Io3ZYo*g2W8OqzCnC%{ znSUf0@PbZ``;`$V?k}a zI})^N@6TKm^}qOKixa+@|I4I#4(>XWhtoWPt@fzJe<@pi7Fd)vE+ zpuHedaTW(WawDvG*6M}2=53C$uj598gZ_=uEzQ3G*h`vO@V3T=e1|u~HH>c{(^-`@ zPyhe}035OL)(WlhAx|T*MU(cximTn-9%On(BrfAe^o<|EUji3u%p}p`mw`Lt6%(N< zkK|VZ4cy07it=M|TK1vk<5whG*=-HrL#tY{iSHuA?pY`dU!wk)O3JESRwOJXjViRRzA!xK=dh0DC&RyLHknIK3b6$ILiLirq zoFNkG;m&GDcuY!Z4-;M-o|cAjMOhnkk8p&W9S@!Dgh~9yB6-Q&8#LPZ+2%(SNyqMn zzGp%vIy*e*lR{-A{Hulcow8waW;VEik`MSwNf2%L2&brDa$i(0NP%s2G7dTr4x?d7 zWv*_3KFn+jPvC$x?Iuw-<7bEB>1wF_8@O{ap+$dKFA)LI^Qleeg*@hu=zss2IENY>tu!UyF2aClBH7!Rw~gpIeo(bu zzK*9nbWJO$IS~#AywGCs0n?aOkmCJEnmXy%(3FAVkVo6? zIOi1w&nS;fq&(%^3M)fx1ZRz;&RodHRMreooWp2kKCxL5&+L zTMSUYy^L&&TW|R>SZBi3*`qot5!b7bSayhX5RTYg~S)y#+7m31VEO+ZZgu)IBNf|rU(rv`WR z-Lr8PWnS_Vz=o&t<*6qp>&fO#)&k|ZW%x%3-JcQQI3?RRYj@>54FdJrg>rbYeqGLe zVxIpW8JBX?F!!+r?QO@oX&9&0v+y!NcUWxB3=Shg)|sNo`wr&;^H>8CN;K?oObhcH z-znNO5(n1)+Qbf0?l%*+w|FV=xK9x6FFr%pkd}>gn2DBG+SP+2B&bm1&C{<8Dci>9 zs;fZ}Cv#J=%`P5r#DK!D_s9ig!pHTDk=fn|03{pG@aDZT<8Zn?)t`&A~`boYO>}2aoT?-JTwYoAGrZ%CO z#hAG39>4`kv_vPNWO4dUHw7a@FytIm{FJx(irO3!mQ_l!l7W^8FqWT+DuzO=QyE93 z8BJsbTT-K97`orw?^NNNg(1y#artN4^Yfr2!bcC(o#B>5gYhg&q|GND!1i&Z%d~1J z{hFXUKEfXt>{i%o-WU}xoL^)~J00093myhadBei;f8?*35hJ@ZBkV9(53vEY% z3INKx;PbPQYL4-S1-lsMg%GwYzJ|*J`qW2L%CbUleg$|0zFm#{ao{`64 z3CuXYFxGRBwS3Z14XFv9MqRmBCMvM(bbm)K8RTmw0aUn31%jdwD)ul`%C?FrEw89? z2!0EoFp217`o`od0T^?r$PGn*Fdu`)HIWpY2@CZlqplI3JO6Zr9-yidWuG6=h&Kio zwfl9ztk2ZP3|4XOuiD|>lxE^r>{4cLrP`h*cqMO4-tI*w!4X=m2Fn#y)Y8Vlr0rtG zJ966@$gF_v+%hb!eWYB#g0j^SMw14V3dD8uMsbgmrG*tIqc|QVt$_B{U!CL!*spNr z3nOsb!&x%*3W+Vb17j8jp<&i`fOxemyLw4?;Vak@#VbglK7l2GOm%;(iJ|b7>`&~+ z((=zUgbmD|^IjWjxqAZ;_|@&K=r4BHmx}nZGKnHbWc^0v)t8Vd6^N5>qHK-xNE}{k z;(B6%k}szDgpQVAHud-~zI=-NI5zp~^9N|1y)9g}7BqXJ0uft_me-u6a{w93lD3oX zyn9}$r|T;*Vm1K&W#+uCv$0c~X?Wa4i{PnIS~RDFKtB?Zaaw439d1l^jK3(Ml3y)Y z+=TGQbu1gk$mCL1#o(-drTrJspkl1mD716`8%h7A)>x{V3oPQOMBkKxjcAoNrjGNcqIU4j>`X3vVlRKqsK?p^Sm zSY^-zDWV*Dr3*rSZjZ>ii4ka_Kzh`LUwn}IompQqzwU~>1_PlW{>x}i`=0A*dKDnS z_`7r3-+#>`7II3H?n?VzzNh7@jMjzXD8ohv!l~ZB&;^nUUOC?ejzU@ee9l~Jxv={g z*PT?(&;WRf@5HTLuEoFL`#a=oovyb)t#BAdGy~Xwuq=?lAG&|3s}U>ZvX8QES>~`$ zcaHo&wnSI$e|7W32NSbxXY~U+w-3aE zf+hbxVeZ%L9^O4F>;gnS6X7`fHuH*ro?}LQp=21~2oit*0GLcT=Il2G4vk|9hbI(j zU-gx6Po5&F3b_K+`h@|C)~SM#Foh*N<|oK*olCji&O~LA<4_*mfk$E@K*^TG{WGK@ zge43y4ZHjO$5|#{o(u{7wW5O}ka)-~)Ar(usKrZ0j#2d3r2)$ZY z!-Vo${QKl;eyWj)1Rm-y8UiA0!`1Dy&ebToV0?fXMOW!{hT>YHJ8Z{G55(`?%O$+h zd^vO&HOPQb16+qxA&n6!zz-ZrdI(1m-)kLo67s5TB)(!rp9PeNk{N&OE6#hs5wI+2c)7Fk;0;W`wQd9*4cG zg{SHUio;6yf3IC8uE3>VCL9S9D@|}lCW}`t3#Yvr?pwO5@DU&!P)G5=Zr;3ai^>4L z+{iLFA8iiposC*^&eh|WxuV#$pXK#TM_06Qytx>hlC}RdW}v2Xk5B;fi&CdKhXDY3 z8dE2uX%J!tMHeB=I+e^m^lu&alQQ-Dq9{vzxJJ?FpHs(BJbrq@tKI@Sfatc0p#Hyf zC$oL0IG^JCTVOAmaf|Q^0CCN^O^AK*^wE*<+3wAlj+$R*&*ff= z-eKp5Tg&e1v!gadAHjA}Q@-3NOH1=Vm6NuOr#jD$j;!TwwLQP#sp~OqDu{F?CO!;E zrtq%2(zv1_*2mAzhJ0q5C%W(Se&oQ@W%|SLflq&ZE9v>15hL~XC2yA3QnCPF&6`>v(iITbb3Qq zsYp^%Hni{7N)ZmhhW-U;r*@`s##6SRx04LU=|Df$MyB(xdPPQ4^B2Iwdd-ozF?}?7+%-E`eQ(ULfj)e{jpber@Q-h6YlqibHJe5i z#dyU5u1;Lq{PN?iI{!(|7Uzu|Q=C*M%XKZ&MZ3JrgLr9QrGhhjUfNM?s;|1}I_DgXnnAUFh*AC8no z`|}k!3)_Y`@&iy#n`d)4E>PxUU9O_LE)_e3?hELyDwf*WoYu_n;S-g@d9}g*J*!@C zjvVPY)U0@6i-FqzeGk&+&I&lV=A!#(1-c~~gLbJL z`~hLuNJE`mHc%HTF3VMU6CNr?_&LdM@R3m`c#PD*j442YERIsguHW|m;R(w%(q za%-UocqybQlUt8t94i{XCVL=MbBB_^-i_`}_Zf&^954u~CWz4aVXKz!eo^nEQs6u!3e#v0mtvw2SpXtYH1{kD%OYdw$QIBY zc;t;{!C2^B-)~CfIgRTk;WVyAux-F6=AVN=Ozb`iAGv+*G-11LA0W|t&MGFM( z(JFx`oYL=^x43TA#PzbApEE5afkZr+8{JNycz7Sdy@NqOugR^9c&WvsD(Yf)H|R&b zIDrb{MrES5m8Z0gTb8twe@GE@wJv3?xfzSn07S;Jx!AH#+SDQ8vw9Jb&IHFvJmS;o zSq^NRjJCbWl=cESM-?xmG>HAkQ#WZ@fa|*LEjLTm`Uo)hh1F9)xsxqBJ94S$;T0jn z0*)IF0J_$FFwf(KW0If3+#Ks>@15M=5D}3cRSFgZoE>~-;Oa^Q;A$Pc+zCd0BVyGoBNoe{CJe=cmt zSPpbg7=41K$eYAXCfnFEu|5;Z;$n$VW(U5KAN2|qa5Ftfexsw70JXJ~0*T>@ce_o? zy<(gEh~GKxmzCb!OI(Mcaep>*2YnM&bJ+bB5mU5zD>C!bp6z4u0S@q03BmoSO4bI= zN+pqMxd-8H3ANzvZ>NP|;n53ew{{P4sPU3L-P1SNVa|$T^c~r8#Q?Bh9%Zi#mjVch z=KVXI>GAA0K&}0nIQR*UWkmxPgZ%8-c5V@l<`4eN;=ul3wE7 zF%G`#wZXA)S_CKX{3w+?oZS`zW!-E6cC%2g01wFu9SIt{bz+IjlVwR zbwWp7G7Ssp7x}Y7RM0;1#kIE;IlL_y_>QHZV{1HBY$$0`(Zx%FSem-aW%GffsX`Su zWgMZqwM;J}j0O`cT}Pci$LW%?e7>nrfOLn=__{h28dEsO7ubjUUYczKf+#75rkrR} zs?YK}7PbPr<_00ClR!Qpzy0f(hGw(U7HmEU#%7)aIz9s1`y0)L`7r-7fj%#jxOuIA z8$ovwSwu5bW9hKzUD^jgj*;7Q52X#uGUfdh01G1UATL~&Yc2fHQC2lf*I=qI7Zz?y zRSg8DytQCr+;jAtjMn|5%xu8X2J(qd$>_alaVH5>AL}dh@A={9Q;}JFZ1`q$s76scmNUTRG0h`RN{3RK;9(MX6xSaYxfOX?%t?Dx!~XQKl>T6FJ%N z$HJHY2*B5^aTaqqDYlom)C1`R>7j6=pd%vcq4`;gBs#((U=~@BiFXE9md`4#+p?4PW(fc;~bZ#bty-yA!)br+@r> zJ()ac;f}uik0s8+br%Frz{X-TfUMf{-HS2TRA!`jFU+sHM_`(XNWle2jZjtBX9(0` zw^v4Fyb7Vv9J0%-jBwsqA$XuKy?>!RprHM7!0=~!k47VUptT?b2kd6t@uxBTV0=A@ z_`>seO7A%lIE$)iJ1UQ??oB##vJ|Cppaybul=s6|sAhe9=Prf(@A#;o> z(uz`R(&HfTB(K*;ffW0?YpUl1P+tIMw2RCq{mhh~_WO)NT`<1&ZYiGo4QWclS~LWA z>c9X10{{WnMqgHH+5^~G9LHyG^*z+kd5pYFNS}m zf^&c}hG^8Ap51I^2Y*avExX4{^P#TgyWSfZdUEg64fKjS=X~F?N`=d;t?vhB1KIV5 znAq_75t|z}WPjFs?WvXvOmq0T10C)J{CoKKnl;V59Gnb{h>KPhIVl0X{(##kqwIwg zU;{era)4CN9_gI(jzzj`wumF^q&=`w+ASE+ds2MRQIa?l%8FQp@J+lY5bk%Bj>8jP zHc>2^000939eXbb`0MCyip)`t+ms2|^_cFAS;-eiAaY(!^?RR)mSI=eTy8;&Ql?si zJs8F6sz?_7{NZmfF>97v(TeH7{%$$c4vBQ$dyTV~p5$9T z$r*w+mk^p+?DSmDAc Z&AjuoW=@%T>+p_nZfS26<2z+kX#;5yp?s)xI7qHEjg{q z)One&)#=)3Yx!E&)z%a~J@wMT17MDg?xxB~*H8s0EIhBm9Fk)5sy)e(*Z2Tla0QL` zo1Zlx@k%_=^RrHO{u^PAifw!)B{k9x9pnv-z{F<$;UkP~x!`aH$!ZKJ1CdvIQ)MXT ze3mjGvLV%Hzag*3w; zSBl8o)6r&6@xfbE&CPNQizQ%fY}E}qyn3xz94pqAm#xcET}az`*0X6pwm|TrYuReC zR^_Q4x_9NuBbNbtXFAg{dZ2aK+$BG6zx#66#g!tqAxf^B}^N9fF^ub z8elxT-G!51Uuo9EJ&-f3DqG0Q!ELA!_9wy}p=j_QvyFojv2!=8FQwl_kU7SCEC6}@ zO$q}3cloCrojwq!#~pKk``6T5MA0<(yc*ESQb@n!9M;Y3{2Pq!9^d!s&mz&4k+&0! zOxY4LB@|G=r8=5{$~W60?!~p8-Ec9d0CHjhYiH}-&rpK@x(*YixP=1z(m%XX9hC$g zaemq>9=c@DIF^EE@aMsYAZ1SgQUR2S3#sN7a3(gZI|uH&2G|#c8VPRq+yDRr00SR= zR;)_;ho0w`ffKAPU4c0KfYfYcK`{Jyb#+`M&pileSv^fo2^1=0mw;ndrI?FlkVMD> z*s**412qtwW`6WszH@Gl7=gE#m~ajk<%8Y4WQ7 z$3BC9E%+Z1Yg~~YrI$d>O8=4dt(gzcL}T$o70ty3h**3iu6nU=9D3@SO>k>G#o`sK z5|jP!E?%pmG2lE0Yw$=9F+b|(aAqq<(chGrUNQ^rlNLwB5um<6F9?|)IkRQRHdC=v zVg7CK8Tw|OKy;#PG-YfAz5!LGLka?!4ioY+U_dHK&6u%C#I2wWa|4;=jU1{BM$v1g3BNgec!(r z000fB1z-7Vi6o?XvkBe4C_lv4nD>u5JyYG#M!dk;?mN{M3a4>TQPDZe{ z*XF5J2mNTmmcnM9nId0skxfzpi5*^&4 ztNRiQ6=qDz%Rs2rIcLPH9JI@_DKogFZLdOZwf(;;ksJYd+du*P!Y+68z?)FWEWoFb z)2=7r?`I~bCAmG|s|lhp0J+m-P>Q1vIn83@{yj*H=ND{dI-k%tB{VTcn3S{OoeSQN zlth+Rmr@1YjcDK5Caipp3=6aI&;S4f01tZA-FtsLWC?`KYbIrIbWR&$-a6ge8Zgrl zGl(R~dxTRsWy_JI51cHW@coxY%EKrT*+xD@K8B%eeLx575R!B9@4x!G@&9{^@X%sA zWPxW%N9k_r1Ts&48jI!x0bjhsB-cD;bwQQ)%iJB-v-utC;oCqurc*w??3)~>`yJ7YhXvZaS67mddAm7$IIJl1QnuCBUlN~8KJ~3Kx&8o zOPT4BFMakJur9^TB%=-FqRItmUEfZ&pguR&e|#I_?<(zL>iQI?*EQlkDl>XRa<{1!FR;rb{gUq z>F)DK4~ZU76(}xZdwvXcn?A|Z@6gw8Jtb5Ixg%m64Wb>SXol{1SVdg9A-4GpbWg4S z1cmjPNOxkTf90>{sHXP~@D6zX8pmkC0-9na%bf|oz8f^u^h!zd8SfNULPe$=G1Q%r zknga#IrxyKA4_jhAN_r}tV-8($#2;A>Cq6(xQ;LS!V($e3I&&YSLGF}#-emTD!g7M z$GmV);5DP8)yR~i6`?uZZwGwIdEAmymO#w^{SNtaC+YeV~HDEB9ENQ8#@I2ld8qo z_Tdsq5gK0Oi;A)Uf4jnz!SirZCT!u)buF?lE?6odKg+HFos+?PG-OC}0UVu}L|#~L zblVlFi?aL)Uf7AB`#wt&^W40!p^=ojYR`kq67Y;@>9F5I#pbO29qv}JgZIn^a?jJe?$}Bhogwe6RMXa5PBozmE>6h;sAq00oi;shx?BZLMzC6 z@UK5AIR{FXg+zMZRMvD%Pt52jL(bzeDjeSu(fMnEvXi>pPdGcHLk3_|E6-?V8874R zj5l!7EmkS_jp!D1ObJQyIL8~ULM9b$XaEK3e|wsj%s0o{xDGiG@!ky;V#SMK5Rd< zTZyS)yn~^Lb%|$JP+tk5U`7zajS?owq&M3XE!IJw5a0Tz-B6zCmkgI{653pA=V&My ztC=gpaEG{dILQYOG$E^myJX=Rx4L$c+_zHb8XI+!`Sf2DDCg0N0U^oGP(kmk%VI79$z#sb(mMlE&T5ZmE%XOz_pKB zCbqLGEM-+`)W9ZAWBr;!mQr2`B&DvdEEW?$e-+o>Ld1)wN+c; zwBv<=neIplq3IDOx+x$a$X&qa7qz~ue+}|^E_lB?ak)=;mhDDZ33=x#)A0^TbdqypLX))zHVGg4EMlBOm*RnbS8oT22oea}N z??^;S98B)>xyWD1Pdb*VIFZ7JOL}<8DhLrb@_0$>IMF8}xhNxHn-^Knm|{NQfP{f{ zyF)4Ewi<93Y5a%NmgcbckX0>FsjhKEH}AOaL0+&CO-UF(c7n<=*6AB9QQWvtDdo$H z1{j;zQm8f(eqV?lGj_rwS!(C8N*R2ceksZOq0Qdou=@)cq?kAq>W}`XMifNh{la%m zeEj|uVU*uhKBW_NBvg136Wa0UQ|+GU_R}bx z9sY^E#6K4daS=5(E=+Vk>TU0Et56ZqTJDYs-rd2vvwkh7$Hq&&<$eCXbtKEO8H1Z@ zXZvj@u4!$~d*y|Ak&%61J32J#V>2t~ninL)5AvVrP_((HCm!#tEovbt(k5dk`O-pT z&c}Lx*~}2HC;JE&M0a#RFH=)5;ZLBg6d}1kl!GD$LWB0oP5$<;<-t?&uL$VtII|Hy zd>EV(p?=;0F-ytpTZ37nHSS%BoTg8WHAf`QV2N|ax|Xp-`L-y|9ox^K9wATtlbhJd zm2*KI)GrtNR|}gbpJOl6p=!%Y6+Z;qFa-|1&G4wxV%~On&MYZw&M`U5UuL4YHj5F5 zI<{`Vm|_M|7@tw%6c^KQ$Y-{%5V47uq-xEp&Fq}}x)%v1tPM0`{mkX(Ft$)_^J-|W zcIJw4^8dMC)bOv*19NedCuJ!X%w}qyR8ZdgcB=+%NS^P%yS@4tZ9KM5NQ}$28;nw? zKvtk{zk%hbGk!Ybl~D*HVR&Z5MIxjWDqo4%7dd^&8LW+u5lWc#?msBY^?aYvh>>Fw zQQ(YyL9zFtJA`6f?$Dc)06j@+0;`*1q9cyV=)OhF%2MI{{>O&c;I$V$_Lql)1D(ox z2jkME^aH)2$pd2lfc_8!dZ$}-QDLMn#dM~0=t(n51}LYY;kkW%0Mp~4 zzz9#)cjz48UmRAE+KX-46hWy0md9SRvmxJxeh}PVd_OATScx>I|At2#hkuMCI5t@Y zGE`*i6rGr)h%b~eZ5)XtqB;z6SL6JS&ss$DE3t1n`{nZUvpuGe9M*S?^V&@5b1>PN z9vO+xhzs{ir1Zj3MGj-@LPX#1MOa)j@hd)OJMru>g3p(h%0Kf%WR@S?#7H_xEahzW zzYk~R?X1F}wtrxrA-AzotpXMu^eu8K$X`c_WN-yULzYAn^C06r(14+jgUin=w z!h6SVBtwm_Snb%(R}q<4;Fzz9@>bdezecs1Q!lsg+aa6GT^GoTL_zo9##iSUI;IGH z_NCUvE+f3mn>DTyeRyYFLlTNb-ilh~9K-}QrK zI^w?bDq_#7=B78goPpIU6dr6rncfM2{7U&-f_* z$va;$t3h#1?d%`p^xh59o z&_a%yL&du%%&}cCZQ`x6X54LbP{_`*gQQ<~hoq(

    E&Di&hXLIPy-ma7bSZgvVph{n_@9eW&t%yD6;rR%rn{hvc8?_$lepQ<&Eg+fu zbJ3-K(<iq{xj*frHZR&1=gov{$m)p8fuVDT2QtNKj)&w0D*|M1#XORFLBi@fh`pW$*JM zmR1tUVu6BuU*UC`PV@)#01e#H!qU2>-gZi*9ms>Lq`;8u3+aZ=T49GD&vNJ@1A zg2!PKlz2e{_qhw#1lmnsO^f`}K?21(fa+#Mgbh}Ses-*HOZdKX{DS3JVwC%&t(5F&1y{$E#Il;-S;q(lM52@bXY%&~5dYhbq@6CxT ziU0!uBKfFvZ6HVT4G{JCHFu3FN zxvr7dv3fGSgwuDaUlt$()9TN1`)sMwR{d~SCrKCy2zal*Hw^jaoK@`NSV!o(uZ!Zq zcYz)P9P5bCss2^ND^^21Rj?~CRCuuVzmmEkoP=sewgGoxH>dre=~(`}@`Be+Ej=O! z3X$d{=K~}g2Hg|Z#jko_%c(8Y6c8!8C%2%&>5^MEb#(}t3w(~@+8QQLBUxY@D^gp+ z;0+O|0XM#a42@wb3Y2ISg+smT#dj|R@J@e`q;gop*X%Z+oRvK`1M!LizVpE+Y}Mz& z+hYiO+U!|}@yu^6=FJBFrS3T`9W&5NG;@A6S)-6ji1h3Pu}$T%CV)NK%jWmcAjTT@ z1oaTue~a_)m5H^4Oc$86SWDPn_0dPoL!P{ysm6My2Q>|>uIdb zDp!iHpZ-ywc=mu#&aHiR{w(z6peChTxTc~8CBl!$zi=X*U~MKKH8FZLdQWJ_am6qF z=ZDvU{XfTZVRkaXbfIiXR$5*ulFV8965Kj$nq z@t`}OeQJp`0QwP~)e~f$pYchxJ(1iwv3Uh2Dr%D8QBm95B|2D>B^8!TB1Sju^)-;i z>U6H=Oia?T55c`sE=?AB~IswLvN=*?+hJ zI=9)wh&7%+{P+=i_{{FRoNWH~a9~#(eRfi*ebr0tu-0|!+(Ov)CdCHqfiKv+^CsS# zVO*01BauF#?9^&*?v)g<;>-byabGz{Cl(<2n7Ap|%4BTRf0D_Ejj!g-^~GcS$m7Ke zJl|%XgQ=+wcq77)u&tCc?p;46t|7P{Rp}9F%G{Z4H>+3K7O1+>2sNBn@2|DsM1wX! zPmCkaJv?lmmsQK|`UqoQ=`QMVYyK|sxoP~m-9eDajy4iz>svYJTdqvjylKxra^MS2 zg(x`OzFibgIt07eQcid4(u54L>bm~;fuLg~5a>^u6F_Cqb!aAg66W!sN?aq9R{0t0 zoRMXTw0&gMZDrZ>D%8b-lMg0cWgXhUfa&@xBfg0MhFe^_U+9EHR%C@aQk)=~%G>MN z3CDAvMJsnWf5&zy)D#%x>9Oi(X~c(G7*p#hF5=k5-EqFiqJN>zGs3upk4nHeGOdjf z*r$k}B=N2c~sO zC8!m_KJD)J^eT?OVYyzqln(oUv*MtXehsD$L=$*6X$~JRkL6Z)cpv{K@w+6Cc72)c zlxIoeov@-Pit~TsxX~=qj6jipec}gq309-8=yRzhd_0-sXRTCJHvLUy*YcAh={A^2 z2b2g8o9`a3bZtmbn2TG(&7nOhz+Md2EPYl4X&*V}Nq-ZGh1!L;{;9H%LH6VWKXNH1 zsEh(zBu1*r=IK6TnR;OtJn?1MxW1h+F30Aq;)&xn=>e5nmxLxyrX$blLBLyp|TQJRc zeNWFkB%D%5c7Jt(ok1N{g1tUCiTC%GR<-aBpHH)M*E4f#>VH^bN1vNp!B8$e!0Md4 z554Zxe5z%E6Bw%-+b0KxPhafwF^zkpQA`ImW=e3FyVv^J;qtK9Ee)Nn3$r zJZ&85*yGPklAqwbcor56->CgCHj0+NHp@sph00{@FXr2rZ_Mgtz`l>KNYgJbZc(S%*5utCXrh4S;sj$es${VUX6<&V!w>&=n z$M2)a`{NxB5aoYyz)75F;6o#J{_lATuDnPwXW!Y)KJLZeJB z+V4);&f}Ng`ms_LuGvRCP_fyIhu>57@`4qC%=-%l*N1Wl&_*g3<@sh05IZJLROEdZs-=pf_;a(o}iSNQ6u@rCZR6`hKi;d z$zHZm(aT=AvWQST6%_le&&FPHK=LhnDV%$w|BvoqX2_ow666oa2;+&cgiVvBRAbQ8 zVIu=(?(B|7V*13MZ2Us12Zttpwt$sqcQ`7M9EOV%@m; z)sBjLwb?oPy@vzabV@R-#Kb_VeujNbzd&#k;Nnyoocyy@laqZ>1@@q_Uhx;#ZP%h~Ow`Tjc z$jg+w!Jur94=$?mcf9nj(sUkGq29n`2Mb)^zjp}$$5;tpIrrK?)*r&`%1vRx+;9w% zynzhiDb5*k0yl5rKx*g+auOu z-VX>Kt-W*?&E$|QJ=+NmIMg=6ceo}NdmYk_E~cg{2yVVlwFc9-Qaei5GY$MYWL!{m zPn3a7$?iG1?ccb0-8^^#S)w;|^aivr`ER!^70i#(|7eo`jbg=nUsp#n-*Fhw`Yws>{|UwsS)Z0twLtJqTs`wbMiwB^418Bk>ySCa6{@R^)71 z3IuR;J(l&y%zMXarzme_0eaJI?-brG!rdwV{Eh_4!7jX5>Dat<6-siXPH3lEI?W{2 zVfKkj-8Qr&XV}V0N6?h{q>aqs&AwCn%8M(~`cnlxOfcPF@(3yE!LlQoh!Q*%?H(dG ztJrsc-dN*e)U61L4R#Kq5#JN*IP-;{jYK7I_j^kjX@HNy@6KpbrC9@bRccYmUEM}w22M~jWLDYJ`Zh>bANRn9&`gbV}O#xplXsUOS`K~0|_N%g%oXV8byp>v13?6VH32P z+^r*!q;I5|{Sf^w;w<;9=Z0Szxko+J4k4dI?`LCy1b%2e=MgbwV& z#L5T$)hDaCb14!6v>DOyYofbfK&+moYsq%AfgzqR>(hq>4*;l-n9h`}JKQc5cC{q& z!+BFod_>6%YWdY}KArMG%G<>o`|+ESDPUWPkCj?4Y?DN%OTvP2kkhkwbC! zM9{fRDLe8*8M-*OTp#^IO+L4z zW464A-zA?b((lp1*=3sB4N{Jazu^q%xBHp)M)oXdGh^*BGOiUNvY9+~Gde%xj`z?A z2Rrf3OFdpt2nsQHlp8!$D+HZZRaa8eda6ERMdx*2V0Rky-I-Ao(XSglE?dgRf|ZMUnHxN zy`E#iyF0poqt6`_`C$4z87l_!XlGWaXb@VPUsKQYIiiFY9LpVkk>RbFy1qQ@C{=M4 z<5DkN>M3=)1jjCBZ0D36q|#4qJmAOpzA7@JPK+Dy6zaa+tpH$)ZCipTmcC)M!`vvE zi}_IrMyb?5X^nB0%4NN;sMTyvL z^i3LLwEwNq5dGT`cWR-p4wS{pKG2=gjvknfv@Yi9w{0L&@9UV>NS+cq9bMwi@l-8K zaS2)H%hUYjhXZpCj9BiFZ+FNGN3ROjO6EPpo#7aHz*D)m49n>arGjA%tTezIy=9t* z9$JF;Vc|oHVX@j!XFGRbIqhSt>&O<;xCbt5HB#96C}8`(*wG_>czdo?-Y1Y6y*7m1 z_-j_2u}GB(6`*>$N_f0f}|jZ1BBKYYu^kMiHU=UNDUiOyfR8|vWN#5(>N5#2mV zY0c17aXn;3K31^hhSHjwO=5fRzg(%46>rR1dKkc4Dxv>7R{R;sVI4kfV~yiKj_VvL zB>f}?^HKA{H(PCqSEfZ503!@KUA^z<$d@}>3Y?}ElC;hr7jl*9KU z#8!D5D?%B%gW3WU#loDPmIj&?Bt5?~;I0mQ(mU5|P$q85aSGz8IA+<~kZPz^`}Hec zCNa(8NF|3CH7oCX{~Z}=0fpo5FHYjma7T+%{>c6scw_vA@Ut-X5{)1b4dBWYxmK!b zyA!vb9@*b*9vIR-LlC?~6y|+9l)czXFdbjWrrsQ~_+mFxsW9IhSh`44iWAI0!AFA0 z^`%vcsv*3~TBzPM&5_Ud_Uq=+NvrQZ`rD+=r7wur=2@9tuwveidCznsHlhDU(&rds zz}{9Vh4PhFXvD|!=h6%mB_$Cg`j@%pd)Y)Xx{y5P0A>5cY~^oa79(Qq=>fCYG**gZ z<{Y{VRtmG+Ik>*cawm-h^&`zm_P!pE4J?_SOCX_;owO1hu?(3XO1f?As`+6(l6UJ< zje#a%Ng2^3OEr$_edX-T>PGS@Tg0{GGmUpIz&rC%$w$qu?5u$S2K<|&={e!1xs7)( zdyxabC?2Ou4_yiVexk!IyM% zlptsW!&CtPBgqtxabR>KYX@psUqOvTA41aX*iKrYHfntYysJi3D<1vMsS+U*S*+2i zR^Y(-O}}HO!WJGae&BTOwvu8$K8*$(f|c;?YANdMba~Q~_Izh$&1yH{>^F(K1=FhI zcD!@3dg|oD@KkBHyoKwReN|;+NZi(&*qDw}xg#Jz{jQJ-_h=sl znN=X8l`7>h>HR<$=L9NgN}|m=#sC>;LMs67;WN#9n}FplmkclJsW1Uys)$JvHJ-7O z>mM(^1EpyQl&&2E?g6OU#vG{+-9kDc|J-Y4dDA31w~{G)GAIUR%FHdRT~w|8z=%3D zoWlhyJ>z9wWTMy;2VvCQ;?hOAqWRW*zmsDZX#>{0w{v?34=${(86MkPL=+eVo1Ya; z7_>^52wr3{JNnzpp~G7hOy2);4SxF8>oO37$Tq(nE>tfV2ba8{DE2!`x$oo61^$na z8q?3V!Rdn{#XDdC^qRz`arLW8aDPp$mmz68H-Y_2RJ?L3@09t~IHw*}_r$__r?4)a zG_UHRmb3H9_r3jFl~>Plyklzkg300Z+a<=UH%x^d<8>`uq~Vvlkwp zrIa?$GnGIx{bW%U;`LkqnnYEyHg49w+B^-4kcHYnf&G5cT*k+T-A1can3iR}4b8p# zbJ|kAuD97Bul{oBvThQ``85BK~uMtm(QKtz#eGo`$JXs;Spk{snR zIx$Kq0K&GSv@&=0oCIBjn9);a%T^~V3QuoO&mgF;RIW07ygJCtg7o3xj{GX1y#OgV zPRFL7sSiHHrt{UMM5=W?yu0H>?2Q_q9U@f2>QE#Bok8LWV$ zO{}RvyLdvh>c!-53WD&!Ks*~EF0vmm|1+P_oa4p8^M^Y~r}L}U1j$Y!_7~+s_#mCX zL<9bRiRwT#56CQh_65NCOOOz#V(V9lMU^>9js1DXs-jteGUL5ZD0vTRw_1462$G4^ z5}G=d{+s`z;3C4N!&}}f9JOwrUoxAMmitF8gOw$W&~TT_!i9&amuhL8$ksUcDOXWf zV$x}kfa(yVm62dyD;l`F5vNNF9DZBf$!9k39oQil?(KIAC9UkhYC$y4hekMj-qE(t z{;lM}83D@B0*hhJub5+b>Y{|whPgaOpTGHSzhPK^(l;>Hqx2O-xL&58RJLbGfg7(8 z`)zp?mi;B~b^W{Pr9wJgeTUyNY`7=w0k10TB*hK1slCFl&1ZouWX}}r!M`6`sC9X& z(KmDEP)})*=$)n+Mh6=)oA{5IT+eSz#xPHjV46AC*?p3W=X}TFvR|?Oydx?X9s965 zLS!j<;}jUo;!J{pdoHsKc{RB10DJLaw=&421D4B*(CWGjn%|(?1Cdkd%`mkB&ER`5 z{R&}FWSMkfIivSy1Xng)`yL~JFv?i^)5%~xmpW=7J#*?9Dr1HIOF*z@$l0i$)^)1E zQBya!T9QoIfHPjDyb`OvHGwn%-hySDMr{#&is3^-O@CKRM|-nzEUB^k9Wtm#|P zENoe#M(k-S1gH?W;4&YimewWt8zEA^ZR+)W(PChGE1NJe=?nOh5$+~s0ybG<=atEI z_iM9=q8kg8gYJ^W{~$KQpoj=ohdWQ_7-ikZTW;{EzpD>8y1;wK>UejSk}4=(NB{A) zwBNzutcgjq`%c;|07ZYL89~c2)|8np8Ih_2K+t&~I`;H~2_4zwmvNo_sXFdH!J>_^ zJL3#tIZ7yNhFm68lqkuyZhUq*%;-Jb(Mf2h7ue!U>k4#8_Rl{st#;Q3VT-85mqwtv z=hkW)ojz!BY-Jtq+OKH*4w+BCJR^r}Pw={|#Usfn^`Qcmc$sEQ#5MxXp$ltX-k%?l zlO3}0h+PSqfo#}`fRG*FB8%6khF%vfHsgQVT}ULuAchXcu)`Z8SxLlIksr7Q5HCUR z?3-luE|^fWO4N83Bse&P&KqpAnPW_7{*toeG}=YrllbQxwpx&A!OeZNevJ%qUBcDt znMJQWP3?i(voabO!`knkOin9>APyiP}s@@AMV^uX_N1dXY85ia7wh~rWUsSJ!RdjxXe zvHli8ArkBHMelHvFZz%V3JP+Ft)E+;$juAT8U#|r07{DiD4{6f%tr@z=rv3+07whZ zxrT59?ze8cJ#^$hUSO%HIM=^mj=rIV>S+V;4*&ps1LYC0Cj2+E{=+h;J@Zln=fzP- z6%Y>M(hLAD3U|&vU})nWZ>n|o3IIURwRrEBZvyhHz$2;^&$*Z6KLwyuTd}apXR=$A zJ`R|reiFx=NR|dK;e;uOfg(85@o=jLN3=ALMJBp#X?{8AE&E-ys-`I*Xz<#+O>4 z*arqA2O)$sK?reB{=X3d&61@Y`29arKnTH36!zLdjKewwKnBQO|2Zp)ndAjcAuMK* z2qrXM!lU#v9}sxqA%KE=k;yn$m3$%=0Ry}CP;iH2oOF#G#y~P-4TTZ6R_c9Fu#WYS zWM{vzCiYCt#1u~^78@AAp#aqZ1pmSJk8$uCwFLkOV)!AkfJl{VH3djzt?%+zBYKCp zbAlmfLCBEZjCeM|_fI~v2}^{%P1}wGB6jbzDh&8 zStsc>yRmPIP2N)DR5$+O=c~Y=*aFv{d5_K2$_SRS#2QTZ9%GFkaDy>3+{b9pwwaD3 z?Pc^*e{$lN4t3ZDpd7xrro+99@KqeytTEyRK}8T9{wi}DC9j#e_$wusBrgaB_jYkE z9c#@>z+FK63(9;1wW0Lax&e<{kqBn^*XC0WzH5JkbBVyzDHvCY84T8~6f(1B$OMKD zZa~>EEovy@THTqdptz$**tF~y0zPMrWuwzCd`iaTKW!UTp3CKkM5m^8%(u&OV#*8P z%~Kwcwg&iiyaeI0FENhX+H6_OSine31L1s`2-P0H8^Fj66MI^BUXS8mlf3qXr1 z(GFP1ARv#44%TZ_()OOus8lJZOK=F5DKH})R^saTMxq}VSBd$AQPftPJZdpv{lwvE zW$m^>iTdmc+d3^L#}Z(UrUo?CCZDpBAKrYB#*$OwcksmBUtuBiUR zAKgw^Vvrp1@#-tq%dRJrJy!RzC*2X`9r!INc93n$GRpHN*C{}~s<^t2rjll&>C%0s zFEX9Cn)V((62y_2ny&8Mf~wbo#klsK;LY-_WJ2Uu(Pwe$2sD9hZRYC0KmA%cf&1xm zW2NyMCpkU_p23xQGZV3b9!VBC2FA1TO_8m3^PIITJj)+$=XR@T;;WLN>ONw-pZ(P0 zv{Z>5bKo(?E7nOsohR))Aw)?sQX;j=s3x|5h)3d#u$?rIDU^GF_YJ8ZrJm*rk%e~} zdM~IImZ#6o(7TqKD9KVIp;ew1l}K*fg~Qa~q}cA>hrHiKhbar~-2LrCJFQycTngLV zpVq+EYm*WlP!MzCDKZ`|nOCUQ0YyXMD|NcwUY(i?9+_*md#ZtO*o4Be@u(Y@2}{>k zMBECJR;}(2w(nOZ$8RlkwqyM7v7LG_Sy5|;9SHwUg=AK9q?(+;@Omyeh4@%3S}VT zxBsVxvZVQPUd`@{rwyqM`i$iMU!}kYt7-X>H2}FfArFdRSw}Wi)@Cu(4*-3(`LWz- z=;!eDOhSP=$POhXB)V)uPW z*J#(peNuY3j(Qypz!?&mCh?+eG$TWNp|8{b+$|swN$T^>s?yZCib=8>$*#9l((<3B z1w`GT@Jooqs15ZJ8{Aip?|R+DZq;1ko}FmYFR^(KM62djAA|tA_q*;zi-t_ zSgzut>h7pzUoOXxNT|vCm^(g&R!6Y6VEy~P^ulTb`cF|z%`i>mi!H#|ilK1NDS9MGiDXyZ)=wr87?qQ`7 z#bm4UoOUXa#h;H)TEk|xPZ*YFfO(~C5UhjH2i?$`)Am8U3hhucIn9`q^Awe4LiKl}#dR0EiTO4)hlp`q#}A+n#G^!TAePCV^!{k>GQ7Mdj`iFeX1GiAYGA zXi)(7E=QLj5Sl)ybf3X9t1@m)FHD=sqheqxh$WzE4%V!(S`8@#6hKe|fE@F!V-T&y zFR7lA39=DE$gl`9mu*4YAZZ8y$hRQ9VOuQcQP6arOP z_@oyoi(lSEj;#QgoSd$JZKM+&8)0kq1XfR)i3bC%oU#K^qFv8UyNqJ^SMkM9#uZo2+1-DY>hMLTkAYbTh*De^68B8R zMhW9;eM-8=h2=QQNVkiusuSc=0YI%nh>QW{v7bi%cbA8-0RATw z)<2S=O#khX=wWaGq7pF)G3fUl=+*#$&lT^cqR3?I94uV1vJ_-6#y!l zeUseWZUeV>00ePpOSZm-vU!66WX5esY}oZxXLJPsJiT2*G)dhZy}UJ=3IGsE09>#V z0*m1_0DuP}832RwI8gpK90-R0*9{bw3dJi0z`q&;Ae_wqD#Lg+OH*{ND)e8z3pDS5 zAGa7_`PcOU0MvbxG6f5X0B9p;pMS+!phAP3n8E-4g2-(2U4qXq0YH8Lf}t0JL81A7 zu>?{CP4>TGphWpuv)8E4M`B2vc^a(>)8VrF?_dyXX7$^p2i?CS*@_sXfrO;owElAg z?BsY{;vYD>uR{n|;*7^%(q{pfJv0Zw!9ExV;spu-lwv4*DYMGqN5dFCaj`8yUfV*l zHR-~fqhH2yj%;nf35mo-IPIkX%<}gBRVc^;mA(gn;C=o@2mo|LnLKX)1q`eGyBR$I z;}0RA6+(dh{~`dysbLJjy8l-}0G^~*ReK1a2yRl$@lJePSGN-Q@GFe1&)5eHfYKqQ zpvsESc(DBvelg>~3lWM{I|aGdEJk7p;;dffJ6==!FW|DW=u>gRApro^njJyo5|l;+ zAy09C-`IPpbM9t5rM?^h;ZMiFBYa~h2>@I`m^|8V@UQtn1oZ~UFX-AdV$vPb8nZS4 z8z`)Z0RYGl*#fd5z+?XxZ~*?0Vh8eApn)Gm|8OC2AN(fr*We|8%twQrTy^2XKr?4j zUTEBB6T47ckZ6Uw!dk(xHZdAxFQ&9qX8JSH{_@=z;JKM(T<-SqA1CA? z`kt=S5#iDp02T`e)&S@`cnDNPa@nze_+XI4{Ro`p- zuuFo4#UaC+YoDF$1C{5K*9TK@f{s1>9Nf+&6T+J)dBzxFL=Y5%5vE(%GV1H=4zmHr z-)SXvu`J{6@?p{{Qy4ZC?McL}IfDY9e$FEJo_Pi`7w=+YvQGE)IB0&hebi}_hAI#i z@C1gl0Yj{(vx*_OufFG4;xbTnRchz%uWb&vpbkprqkzFJj@GyNZpX|o3~~+}!c+F) z^JQQEMtCyHNSU}pmL1#q(CKn3PAxXibx3(B2kf-3{pNBvOC#C++{GP>beB|Rf`PEF zbXX-r)UVYR;+w`Ui-6k*&mF977w+*IxNdn{n2d7lfXTM`v@cMkl*BIt922=EmTL@; z|4lu*-6E>bZ#TdOoe@`*zh{7{%9UT8KKmjP^()=H3o*NBPRVE$d6z=3G!eP*%WQ#4 z8Qb5Lz3#(T*jW9qI`w<$!}&CMB1lg@_3A?1kzdhzKp}~(&)ZfAV0X6pp91zDPocHO zov_g>f3;bN$Ptdg$sYoyp+id2L#3qK0{r%2&3RStw3kxns2sDEpx^Hb$_(*99u+jj z7dg*~ukLa=519h$WYs#Py$fDx>EdZqKm}WqgZXg$2bR%2RZ)c8HuT@i+O)0{g(=7_ z@5x$7%llz(EM`T<_&D~1vp#eqIo)VKrHU2IBC?W=G|%6};cPx72$a(lD%Na%X}mAw zcG;!*!|d`I;WOUQBg%;#J8-)yp9<6dFcTr#=@quu{z-rKGgyrUr*2$c%d1~B6NB3K zbMfW6FYeAii2~8;*&$v)wBI}cfNaI{1eoVUAu2ho?%zeIToKtHm3&}~uFGJcSR0^! zINc)I4ueQCo0`4_!@#bb6lUo_qvAxhY=Xz4-}hEJy%vW}3{Ppj2XYypK!!03_&L3xPlJ&`qiY05tvn?9y>YqY}uzx-*cox<5dsfr46! z_Y@OPLakIBY4*i~0syH408k0a6Q3OW9|Hl}1ZHqr*a4srfTDs7@PX3MJ(L!-V={f2 z=?OSSex~3J$PDZP0Pp}ZyJRG?YJ@VyVrkc)%#-ixql0kk*cVaXNPIP?s8nyRQ!uDu zRaiL}#{ljU`11YB>Z`DmE0wU8^zi9i;zu;d*u1}shvMHe=I#T7P!${gW6U5%1@~Tz z0)S&DZ7C4OLcLT4$uI*b-Vm_;5U{8J3+%sJ|7YX#q{A3KJjY7K!d~@FNa)( zKK@q(28I=t%H3H<2;?rlIc5Nk4F^zcRdDFgeV^17ODF}z#sJbDV^;qzWn-Yk8g;Yx z)2d>ojs5qPeir_;o5u+#b$ZR}6)bjyadL530K^$N_}~KmSFx-Z0JXR+Yaj*yB3=Nz zX@V`~Az;Py=(g2du|5zUEe5>lCKZPtInfDIE7}!#1 z|8DKC{LAH$xUcmC5l4M2f)h0}&MfEMu7pUi0AVBmo9Yfz@!z%jZni*m0f6-YfIiC= zQNBHZ$kQISPV7Kn1O&yr=g)b`B&e)w^4&u6#!)Q@f{;)M%9BvI`5%$_?~4AVhqBj@CnM|_5=e!IpYY3W9u^ua{vUT>$Mi%=Tlk5o1TK>zSC9sv+hl8vtL@Ti&ivp~LqJ@C+j^}Is# zc(9#W_7qiJ4UWUOSIike=Ei`yAn=lO)-V8+1X}0@4n)1pH5-GjXIKGUCuBrTFknD7 z>(V~}Kto1?|3q6N_J84p_&FBB7$!ykFggF*gQTYOJl$@g!{X zdp+Sr4ZUVbs<@nk+g8(j-E@p54SV2?+puvD;L{Mv7vXr zP{|lr!gY|%tj~+2q_Fc$-@@u#w0CWK_GqTe>eEe81vkk=z&$wJIGiTLk2YYsX8tvF zdv8t8x15X-J}r0^62ZY^dXfpx*!cQRur4%y5^ai)5dL%VtZsV*mnp_ue6Gut|;&r6OSqLJ4Tfh zPZ)O>xK3c87ifp05cp+sF0=huQmqo;3eVgJCxPaD%mqt{bW7 z->TTt!VJ2L&2~{;dycF>dZR?Z5D9nKrE(ku9Bnu(r2+;t9kW-7Qkyk0WJYtP)pOxg z39&Wn;x6#Ie952QYy0%^$zQb)dM-0oQl>XC5o?S z9Vq=*lfixe!5z2D)JjzW?+mntjojsPlGmu;zr*iGXy;Aguer3s4!q;t|LK-W@=ZIh^`JOj zm-Wtsr5V~8tnEjEZ`a{@y->K7>*=wEdQoQU@s`K)CL3PmCeWnCL-68GU8*G~-T5%= z$t5`2>qLc|XQP(lSt%iwYD^7R@WGr@Pfb~%V4rM?51=G4) z%$!nd`L^f~bWYXuIY%BcSCdQVFn^h}edo39T1HJ7XBj-i&ve0m+SHCjTS~ z0lKV?H+gNoYB0(BFcQx+dU(1stR3+$r`CLbB7SzKg#0IvDbibaPp-efw_Zx^Oi{*3 zYlD2Mf;aw3TD&8D*st((C-)Ao9 zKVE!peoR3`<%YUs?S#MoWzK_6VjPkiqQEy!YcRls@|)WQNu^aVT|w9KPa`4uDN_EF z1We~@ms`{84!NnlFYl6Y%;U8PCAZ@#sNrN{)l;ww*M7S#p9ewPhV4irUIs`VOC*#$ z`(?G~L%+>krE+8|GneFRr=3qwHb{43cqYMdM5_DjQkpJ)jr2U&aiCAW)LKh#PHc*^ z4Q-;7?2UXsh!Pe~M4YEmjow_oUqTND?7FA&jq|QJ2mZU^=i(~QecXgd9 zYM-Rc(8wF^h7QsTl9nW#8dPTp(@Iza6iuEkk9+5DSxfl=YdHpe?Dq`74tb^~#h#2O z%(%}olgC7o!Qa=g@(4oI9Z9nR(#r*y%84toZ-cA4F>{|fxbQ}~W1&P$&z-fdC|mEn zZIT=9ZOFxd;HSA+Z7FA@ko_)QDZUu#9yrbfJf<8A7B*W1GZvOlV+>6krZ?P=6qJqv zA1}XV?|LEx^{K$J_p{# zT2V);SbL*Ihv?UOzFcp&*@Urcu1gFle7f%a*G3c9n$Wg~Sew9eK5T(YHJ^@`snFp3 zqBQ~eNTO7;oz8OT6~)FOY7UA36|T;-$4t?VaDD=#OObDKIe~fN>@$5+KQMCS%7$5m zu($e%$lLycs3r-c&Q77r9ui`o;}BPY)heOS16ahTKIhD;273J)FT~u`BCP5A_w|_A z)*Rs6#Wr5-lvUAB0D7c5M}t@@BXA?#vF%i=r|WI{W&8%(H=3|{4)X3W$?-N zU=eL?mIRyZO!k-A74`Tvk+QO%Uu+$qK{@dg)fL{Je4dSMd?Nma8-Irh@A=@Gl`3qE z1`?4hj$-zo*GAp7ab0@{XNSq& zej^lcd|q96ij3EOcI3pLzBW&wX)4yBznRdJQj@{@^mjMe!J{cN^y7~-IubP}!E%r5 zcU$l+RE}kG;1Ef!LH0a?4!)Hvz`9x7{UhR3U%y=)y`2C<1p5bm&P!gt&a-3N(&@LB zYc1x|eIt01nG$uQ0^m-h?C#J>$KoK51+$c>QGoi=CNeEmJNWmn>L~lUQWzp-4dV8E z3g5r_`7{eoiKtx}>18w;sO9Dd*9ds>{aUyP`(yn*3x%_wuwVIwkT2SbeLKuXvu}SS1ir4QW)Uf&mLpth>b@vG7|pw(aGVCUksyBUBQ{~ z4{cBMg-)Hh=6@c7bZR^7T9fwl4uh0w+orWhz!@UOd{Q_q4Yd3?(@gPfPK+fGS`(!> z)kES-mQveBvX^^|s25hqP4Kku1e7?I7MC+LTdS2xG$>$Zgs?F}C+%`TXpltgqhI<6 z{Upc+5S?Geev|fCtiGMU9qCx5{bs_IeTRiRmw%G1*P6K2Q>v>?X%D7(`n$=(@Gi0=p&n zHH8x+U+{?OvT{AOx2-&B2h5PQPqW%6&MH8Oz9zAyU%afAK@TIW;Q7+!Itlb1H6uUK zREb+rnL8_53ecSrKIxTJ=409wR65yQ#7cMLqWY0)1rnVi*AwzMD_XrO2`JD-fw-{BCP5MR>|rYhs&K?c->#95B`{Ypz-sm!uP z|E77DB;={q=5J@PFp3WU|h0*+lJNo7bYI6km}nzez++AAreY~e}-Uo)qtq(&LkLJ37a>|f3T=U53hCu8!)qf5cNY3WEim~u_2x3ih5pmh`{=dIKqMI zr%=RBB_)keQNzlwK)W)F^Q==FNqovU6|Gsok=!NehSlB`zGZ4v=0#8u9B{Jwb zTVp263KOea7k(4TFPazOFm}E+54qINFkxF&68X>vL3btKgv|eMc6)*O5vWkeOqZ~X z*)&Yzw7IGEIe&YtOg&ar1R*VT6>vTc8D~8cSt6!CUx{SWFXpCqp0qX^>0s0nKeJ-Y zNJEByC$@Cl5=ZBu@sPd3>+FgH;l`I+s3py&V^ngSV`3jtNKE`L;JgM41}Al@>yWe; zqpK-R#uVdcZOVX79NfkAc9(AWw*( zn3ar62VTvMqEYp-<}}^DESky)O3mr9T@VZKR67p6(Opbhz!utyQhcZG568D^il^P{clZ#ndTdJ{jy0| zhYR-I@8H`iU?k7k2@|_kpIR% zEbg+6YxNGsoXf_h9*#n`HGBGee2_%so*c0qV*`q`&Pv4I97*Z$Q9d`$kab z*mPuOr56L2`l9A{S<%zr-+3-bohnGg4Yb*!H;(tfL7kK?n~ycza?|4K$dr_52@gzu zeCF(;zoP_dd3B-8^R=&hoj4n&>r{=gBA^A60Dc_h*~FVDVN>$>jgAfj^yhc$LpShG z38u=0$Wyygsx7)=sg%_=rn$5)w7mnI-XE1#iA%^KIIQVpVoF&`49-!{E(BA90$i&n zWjYFZZd$($-;+4BQhOxU7mhfuQ0CTAz+ze9@s4GTKMEOD2sz6_bDoq}wC|}KJan!C z$BKoV+^t1j=#O?@fc#HZ=wV775l_aO=PR<@+DozN=27!h{ptSWQLV;*WA(dyH&Wh{ zO5M>h{`}&Kl|DISam`1ZlbZM)G*r{P?|9mgs>S#>&8kq5b|p4sl(&njybgpE1k`m| zoEuK)VexoJI$A2K#tcE2&

    Vf5-l9xOBN8&&18Z{F9_C?SQ#h04fu;yU~zU4r&H>5cMsO^Uc( za2S^N{N9laj~^UQENl9w2pK_!p8pWkF%9}U3hhJ_1NKkT{7gbOQc9Fp5HdctM8Qfw znj4}PzCvX&#(h7Tui?d^etaxcJ7MRJ-w@AiEEokpyzIn&h2EK#m?1k)t%ONn*Qn>;h0{Eb z{6*n&)H-pjSh~{;oQe}Vehyxk6qamNxF_CT)X1*1z-T>t=)fiqr-{oszrl`G@Ta@) zrPNzqGnN(2Yo0?w!)qRm5LRLw4Cwe_m8N=u^MTLBhGBf8iZMVw$X=~JZ?#l2SNCU6 zE2(S65KmOl2FZn|6=XLumPl&eFY0b~#J^)jHB5aAd8aD;yJOS8*{5V)&q|aUd=-zi zJmOa-uaK1sQY08S{r%SXFxIdjakul*&urmzv~J2N z4UgLgAurG}OKWVH9x`uHhpz0x9>@(F4qQo z3d5efoDb0nF+F{XCT}v$W;?)soR@{bSUtN!p@K*W_5gB`WIJzA|$K_sU~B z66Z&D<#;5HDp!E6@aTQq-`RGzf`bfB=~31G*-1hyZAw88Qe$4RlAEn@^~Ob|SsJrAS2rg= zCwu^vDx#X7+yBDt+}>D`1MGBo=4$ElIQ_)wqE4~4h67O0>QHk*AAGTE5KuInj1N1A z*Ky-43^+FUTt6B`vN_1ur{yEVQ8#iKDa&R)?7B#S4U1lgZ@uk&&p6^SjYF^z-r0C7 zCz_-3R!2=mGsXDD2pTNVf;)3c1|wb-xFRPNQtZ(Rk8gkMc7osqTXkaOhE#3w#o`-7 zDkEAWh85Hd1u`Yiac?X-dg?eqbSl&SY0*&l?`7xb=AF6!l45Emgu{h;NgZt@_Dm0( z4a{YXsAq{AhK%E8;g`%;XyRXBid8hdJ^Q` zY%AHF>}vxbeTtV*mcyA%P7PEH2iqV=`k8pGSlKwGet@}p1ns7O%c3{afH3|&)J2eP z9VbDrb4=iElHgMQP#w8)$t^O|oi{FU^_gN(bjRG+Bloxn+4iuhPegNw_bfcIN{nop zkiuarGf&5VkAevV!Z|QDv-duFMWO!ML)=$Ij4sKcRmk;gsO=|$fvM`i8}p1as8~0$ z5|w0A{>OUdnn69}Az><;RdL^8=>slb))Q&7ibz68+%7bE9wJI7q%!T&TQeaKv8Fw^ zB3HAa9_@1iAu0?{+YA!&qokDmM@Zqwlj)pAHJ&X% zw=R2BzJ3bYNJ0-2)ud;%i0xGCL<-#oIke617y4(ZAr%oD96b&CiCW4mLlufPNTScj zr%+V=KE-X_5ai&rbm(qdYICaaQ<~|&`VpjkVVfoKRB6$N#ar7zO9 zLXwB2IyJLv{2%cjkwl{+mT4%e-o(Tp%|EWkVL@O#KScqhv>i;VbCRq#FMn?_y)s~5 zEl2|(heY`eTZEHM&k5%br~Fl9_>;mrwq>b_)|SmilCXM?%u<#Y$KE#>$^G3(BB0fL zjAmQPF6P{)PBk~wx8o2=5NY~WM(cGMjln*TKFT*d7lbyS6tdXNfO{_qvDlF09<^*68 z;R3L^VaHjO6hDRN{2TGx!$~Ve1=Rgo|0=g^kJs-Au|QkbX3)pvJ-yg0Qa%Zoh*q4VT|R@X z0XZXM7%uwDK>eBOI+b<_F2K@NK10!(rN`txCsG^Sv--N2I&8lQmN)b%%f3F-#w9VBR z&C3sq!sUfSJP2aA!YdM%k=_l@HBEP^zI>R+K|{0Vlx$>~Va-4gXWg^#vjP+wQv9-)8~6==#$s!GRpSq)kPg5?BWBm)6se%hhs}8ztd!Xr*d(vY_`RwFMmD34F~(544`IM8iP-_7L%_ujoTc`zishBa8@UADM$jp1DmQiTRu)^q=%XfM3bX_9lmr7NBzp zT~u25f>-!XM_7+Is?*KARtiV$4GPGZ+9YuwK|@-@d>-${!DWEl8Sjf5+(wiFhh(sGF4 zzgiIf2lOQ~KM1VeW04V8MyoO( zuPcj0LY#tnLJfZRNCn~;HSFat5)RqDZ@3JxF6l-O>EB{^?g(Jz;5l&E6k|kPiBD|; zK_AMCMquLK?l|29?6{&WaoCaSETD?t9rw^1GH^Uwit!@pGJeX$<-Arp{#e-xkOX6w zaI|D5z>d^6;N04-g4s(yJZ9*P+#TXM@OmFf#$AV9xE@82;qR-LAaQ#I8KCD=`t!?j z|A3k&lLJ=h4)V?T0^FC$wPg{NC*~;XeBOK&G>PFySh}&sdIP*4oD$yGw9{^Z;%6n@ zU~IslFWsC-@Y^~iw?fyGemVcb;CYCkw1_$b1#Q6?k*oR-)E{TS`D$ZV=wM#k*cY%fRSWj@KZky~@A%Ctm= zJJF7-PcgV_9;;YA#W)&|^8P>d6<|eDYtr49>>07}eAj^0@K0mPj3U9BA~*2*AS0&( znQ`9e3Up^v&oz2=(>(Rye+2tc>FLDbFGuyYI(sQ(xxcj-_=X3V-}^9qGT#dZZDP5& zPdEVNroM#P4(71l;4gh-GT;jH8v8=!xw1(?eB(aVrslz-QTNS zxQN_t&MAT-8TM#pI%A333$4cfosqdTp|OT{wD^rZ9{>4xhv9-hQ0fk=YeYta;|VE= zCO&`k2Lsd|Ai#~IPJKCjCcuo=61Pd2rW}Fkfz^Q;vJLjdGSd{frSXF$EW-vs+(zK8 zD9&{2qVt%Yq{~EEs*VoLjbI9>f2wQ(cd)$7d%>_4 z>==4d@m)!ZAWw5V?skAyD;?dLWd+NG0 z#=nVj?=hoQWn20ZeqDx~DDl#YW-zjT63}HUMELH|*R?@;y4RsH!xRsm=i{6r&O)bl z3KIu|MI|KCsKf@)&Te-CvWnI=3*q*V5W5!U6*8|S$D6jU(eGveBW`s*A!ysSwZ<ZJ>SK%)T3V$M^!=6T;Fi_)fr@RaA&aKg- z_(ZyGs4{d{IYj_Pl1W=ekm~BaxyUmN=ZFwO-F&zILT&I=CF%_Q9?{2yYj?YNf=j37 zf|uLnEhs;>G1XeW#?khpVqOq|IXnyz`yStPH->ZnOzG!+Vsx}hgIB$dythYJkF7&Q z8p?wfPbQ6WWVMYA)P219Nu9EKFA@QnGVdwb!lC7V$QWJy-oCOPzTd|d$0F*g^DNwU z{_Fda5atkCHly4)FD?~r+3lMY0GNREud z9#z{fEo1fJ(WNk|%CwwFLfeDM-A!Bp%;oVfjxQvPo718*ndLV6Db+yqOUP?;h*n;~ z9`ckpbr{ciu!haJ8wfQKhGUkIj2 zvh=!=F|sv#ufO0Q#rT@l1FH?fUIGO#8c$j-s1H0CNS_ywb+<8W#Kb^NPm8$OvG`t{hs$5 zl>~H{D=jxIw?$}a4%3erWK0QI1t73Xo)dm)E~6l-gEEKnYe5{7c$bw?eK6nZyO${^JRvYAhpvBgOqU2 zN+{{_{ZrW252vUBV(^}=DeX9!4JbxY)7mj;>du*4Q0x^5mSQ_ojJg>D7T{7g{3#h3 zvR9=yI!nsS*=2m75P-l=83b#3MW1ZFV@O(YW@Hbu8YC$s0QZJrWRpEqALxU{5_;lI zwVbuJ&V(Vl$7dHp@nV$=H>+?hWt6rnIj1^4pp!IZ@ZX-Sy0Z4~KvEQ`f^ z#6LIw5bWJq0P>(I#=HmadY{$)gCkb8digRaGfue|q?b{=mVd{d;t#{d!M~aN2;QgHV6JkYV*coNV#^q^~hw z0Q$9w!L7XW7#20J)>ExGuxvDY`I55z$=p!q{z-(fLFz`aHeQn753+dOvl?cCai^gk zgw=7mWrh@sTLJ+5p6fxs(V5mJwd*I(;9h;{fY4`~@1NYpE&vl||Fdu5 z4U3)x0G|4->u)5U^5uVY4GMTXqD)i*9rDxlGN&yfEK#)%B)q8dzqD!FGKNvJy_8@= z0rN@H#XGA(0D<~zQf`pwKu%+lgCrOXR@|!B@)Bjl2$bgBSQJ#3XoMD7Lm~}sH{0ZPikQO_jw6*}4fKe!~PEfrpYVh^dw2ACLFAGi_fBbXiMjMEjf?b6>UK31x2x30`Qn z4MO}&X{vSh{VfAr8m*p_7Ot5OK)yQgnOhF|G$ZVwOmm5drq{g#I8ndCpfkxjt<84~ za8o8Kb7ARwg#dt9rxOt>1#Im}o&ccFcL7S@e+&Hnf&gHwf_Zf(K&}RWV8TR@6#(!~ zLN&bUW8eqCpM6XE_ghlg|65Wp=5GafPYi(V{>McDWSn#AFbvaV4O{VePk8e`0~X#< zWP=ogKs2fX!_t}FayA_MIKU3Z837;zSeY2)>@UzaSRNw>Zho3tC?*=r6y&iAFUN%y zSjcTHeV|W5BHIiuEP~*E5wN~|;Sevd$U4d#EW5Rv{FNXF`Ag9ulY^fI&nj1+p4v2Mn#I6G8T7 z2_2J-EkaaEplVa_xdc%L{2gu~#_G3>w1RMY{z_^={+g25I$KEqeBVhEH~{>K{0|M> z6p*t-y+!aDt|MM%B+zveM&N#;ExPfUY6pbJTFYw)xeox|g^p$>N+bEr-MCgnVgmpa zcWy}$YrTm8LP9_10sv6=eY6MwymmI9|F|svH$wyzQYcGRvilp&`M=?uK+LcI7teVS z`uaQwXN>dL)hfH!gy%RgE`mihJ2rgkJ^AYdVqC`OmzPvzu@gfqoH8DYRBC|jn`cPzKs8RyLpJLSK!@qgEgfZyB?nHwOgq6C zGhW?nQhQp{w%2+rjO*~B|HM{Gi5}4F{upI|?L`q3z*B32?wVTb8-5dADCP%7IsqrO zsBhv%#*p?Jg5r|+5TfjVG&v*fyS;fZw*Jll3g1@E=`UmU#uDB_J+qj4dlnF?r5Pe= zEVbAe7siBJd%86V?~8M*4Cv6}Km}55i5fjx25@sliC@NI+wPhV3|&w+{5rjL*cP8q zjzZ?uqxF-OE%T=~L@T(%DlQKTKY(V2gjRn<82Q-v(KXi{j)^+nnC%M6YA6ZLf0@O6 zd?~V{KMSXyr22Gm$OniYRgOpdYx@*4+E2z_i(j7He&f(9Yv6fH2U|-4-FP!pZ0^ld{6=+8-qR49R9=vJeq2 zrEd3KXcee`$MP9F5_PkNMZ{titBJLNiL0oF0dKHb43u-8?k17*jdkQ&;H+=cA@A@v z!ST}DUURN|w*>qI@fxLdj%@nN3={U2dQuZsPw_#5%(w#+b50=*gn2KtO*Q{{&dTo7dooVzj7&DGQrpCn7c22#{}uQkYQ-=1h52`G9b83-FQd8H3> zZX`Qg^MO<%4RhVId;t(^TY%WWxiN30?|WG!G-8hh?*30^z6OtIdV0*y zx#2>xVJQn4fm#1Ig6>O~4M9#vg*Z{u>V1%^5M|VkfwfoR+7AXSDFQwOHErlJh^rP>6F;UVB8t)X zuzzHnP5eB0Pa)G0odc3svp-ZO@q;~cYUBjr4#w5_YOely8==kz{J6l1)sNkJWKp5C{rJ2CLohI`qN zKF6^)uiL_{a${^tP9naes($bD{Wc&H1A^mZyD{}GoFv6&;B11 z(tq4eAH;};M(1}MJsq#E&3g^EpIvNE<4UD`IKMLF=?H6Xo<~cJ6sV%pt!5<8{*K$I zK>Q0XA>dGHRnc*wxS(FSKXP+a1j7BL0Y47xE_cu>1ro08?%iOx@};dy6?yZVhTG2P zQiU-@qK(DGfBBgbs)Fg)JvpJ=s+dC=4R#yyD54^5$mFRkd9mYZ4#t0mZ-#TqlW?q~2+cc_pHXa#R>&OY;@R;^jI>QB$P-?O`8$0PTIWm+X2#cAhDNfJ% z@cCk%k~=G;nP4{>(t`xh$>+A$m7b9gPyK>kv-5(%luU|PqQ()c4SognWxOm3Cr_#t=>ey*B+Ajar zSg8F|g6u5wX(CX9irtlu?GB1J!-u-d8j0<5#=`cSV}cU$OeCS zC!@873GR;;+h5?lGD!c!TL!uSbB(K&{~O^RYyUThz~K^~nEi;(;64sSG`8Ck92u9# z-xc8FFZrc-TaMLe7kFKq3uuD>4o=!@KCNZ@ebI94FmD2yl04xfDQHl{oZGbGcvbp_VtfL zR2C<(oL^u%*I_G-cf>i^>1ZHt^558R?BU}Le|UlxvH~P!YZ}sb+X=d?%Hjx0e5`}! zSR=8+YzkFucZpQetzG)SfA#M#69EJyslRo5v6@tgV4cH>J6{pYtUC(U!YI3UJdrU^ z`stW0L5BqIv=l@NsF`_QGYlQX2f{|9w^~VcOuLn4%mM%~#Y1|viqY))$s>0llzuim z4cj7u9{mIn<**>H?AqFR*#_SMClK*Fv+(-X`_%vF{lED?0I-n5uLS^LQ<6#@SDJxz zUl|6e}ur}+_eMbxPYK>E9oPzI2F>#}bH8omT2BnI4GluMGW$v$fJq8(JTRMrdd zszLBnDU25@T&17Q-a}EwjDpEK0}fqF24MzS7#1D#3AUbor_4g>ARs30I0#s);olCa z8V1APaW>qnh_s+s##@3>V@mQ#gm{`!=9Ng7@Jp6HsAD9ug`7JW$gfeU9%e?XVoaSL zSWO}FvA{SrW+RB|GR|(w6P!K@Osc>PZR${!hY%r1h>pY)Flz@VfP}(3G6{s*VShPr zIj-#HU&TTxtg$2O>0bEb0QC<4(M>q^FA9009j&zhm<+$QZwbsbfz$nO$^a}b|Bu@v z7Ps4fe}7lJX?Rc0(D`zX4gSp{J$41oAjy7YgJ*Hl93p`3LhZ#yC4ZP==FFxC+tsw> z+z;%XV*aFDa&_R@qEY$NPwSU^^xs{W|P)8$$**hFZXV6Jo+6gTdKg zD9=GeFOCK2J_evL+x=RZikf37$9@|yockS~Lll22oB3PWbpNlisrtWb1D?>hGI{qa zrZG|QfG&LA0GJXe`+VUQVDj!*vkldz-GP7|6zWTvWKkWtB7mzTYaGj+Ag4JU>^Sua zE8uE`Soc%7UseWRn(pyKt@dN_4jpW_-JS42=#Y^Bcq;_aRItI_>|X&IyeqmO#)9=3 z$0T|ZEBtH)aU;z(NjzN>CPnp5iZSN|6r9=W-O}#9I($S2_2z?di8&G~AZZd`VhU{l z4q!<2;p(Q7G{P5{_+@lEar01Mk?wgT3BNG9aSQiN&x!;^nZtv`r6Ap%_ki zeYi;~l-%Zms{>0!&HP!*GnX!RiUBag=hB$W9{G0p&js)C!cp1kIH&Hf>*tGmEy;>B z0FL4#3v9*M zb?_hmZSVqSp)f1xG;p%~5sj!A@0@u(TBAmKR$9DFmNW*08tdc%ukg{w*bKR&Cb9dk z9H|Jatq?0bMe#d&<&@e?DfI0B36tlJl8LtS|B+00;S77gEM7GgPT2qr{d6fEj*>Y= zKhvZO%p|RXyL=smAc>;elHl90{G#?b0o1BUbH90nYDhz-!vizpYwxRCOAab@ zzq?YYBGCICct`ii|Ghnghz0+X%oCe%Wp+F52Y^Bpw2K1I-*r!r86kZUuTGm~wZNDn z!Xp0X163=zsQ3>N<=*yUuoNMn96f)ndzr3B?l^O4<>CVhM=)TwB;sFv*1Xez2Q zRj9a%`h(x!2R}q#wZ2*NvI74Xx#9FldYZ&ThY}J-1BUAxL2l8sR{ch{D$6iV(wnz& z>rSs3-f+@~#CR_;_-xL=ik5W$nH0Uk(A&+uf+_a3@LbY=Pj@@c4q39tJl3rxf;a zM=>89Q}EmdV|mykY-#k;xR=?=#(|z7^t%wcy2HintVQJFQ0)fn5*@$auMDQA9r=d6 zpCmo*$_!-s&i$dp1>Rs;YhD4kEIW|oU(Du<^)PdkXGp`h&-<%*WUIa)jwCW^(EQYL zSTGDV{;s;%)NylXNhAbjqcuXt-p6TV9r$#ngV393AS39U$a*li?5Sl&UVi5q`L$<^ z#7aFiYOz61nQQK@_@i5U@u%+^1!Pf0WLNL30ucIiU*_EY#e39smOF@kDSJsq@e=8Y z@(z#_ zXl8`L2YLnUwH~-=6m9+YI(vVz_m2)$LmEXxzfhuqJgB%|Do z0$GGIH_MuT7!^yHA~eoryied_o$wGC=o>*#I_J#&&@*YiPfo9z@`vFe@K*LNBnu z|3=*-f$j>)IoCek;4;?sp==NGoQA@p&Iq=M!pz*T_kqj<7E^tvF)o!Cx7b~b(Um&P zauH?Gw6hUz8E^XHEvV|etj^;2O3N-H@e9nYhIIN0*Mw>EEjZ2%k}0);F@>^W%a(l9 z-9EQUEIp&OJrAp@8>JWfbIWAxUslp1oZiI6?i?-1wTh-vn^m z$mv_Acs$L?e&25PHz&@>g+i3cPP(6i*a+JbTsA6MK83j4qxU}~X)^`1NcOU9mJB9k zG7W+%tZlv$cf7YrLPYD;fz$o`1(noY_euH_|IWeQ@QK@0=TpiH<)dm=6lyJXKbzC& zrs*d^>a=azGaDmxWc&6GEZN2QVd`CA0&qIAZ?o2^V<}3Q;4B6V7Boxyhj1{3j&Ac8 ziw6jAJH`I{9n^&2E5Mj}QRBJ|4KciRO>Mw_@-}~OL3on9YSfiEY_UY5_|njhGZ=-A zl{P{$%+-FPu9taR#El>APY8>M8&yXkJ0pwFyhv8-FfGBmw9~-~t&W+xXo-gg0tQG&EV`g@- zB4s*lE_e<8^sB?(8JC;kG+1;Rb`Tav!R9L!Mwb*vI90p9s0Q7xO+f94pnirt?BNNN z?|0x?`lU<7?*bnLYKi5NYl-*=uIhTg652m3h>e~(>6Xl*qcmR5z*qsaZoFy73e7Yj zemreuli4e4LMZ2;S}vC}8mi5;$ zsm5p*kGzwa9g=bWg*r-*eyic;dn4+SzL#e+@beVr;?kXQBSJDCqfQ`$bvz(H*E`5j z6jQmlS!T-u0AM5j4r3aCxh^(F|IL(uHTApTbl-(c+hzm~Q-%(;A^YoSYjJMOgHruE zs|-*YQv*1QN((v1XNSF8|t z#&V`0>QqByPCQf)eAMIwk9`B)ZIsRx`vkv@llg5l`ER4e{BNV>|4(`g$7~_ast5yz z6qU#ma6y}D;o!h!1JW(Q)-=0I!f5i7?cJwM*IQoI*~`&4(x_g+ns52;1R@1uNZ z*t)D-ICO4DFTkEw!NFi|fCbv?MzQ=w4$&`v9s9uxK@g3MPDDcV5pdS{+`-b1=&jQ? zEv3$0)8!bK09Kit7_)773WY8mURXeiHj3|d^b7~eu;f3a9Rt@aJ&{lfJ8NPA14oie zwpeCO2^Hl-TMn-63_5!=GkN(@Sq3j%Sjzd0c*Mq+QK5pzRsGdMR_GIe^U_#-+QEHk zfNu`Br%xf<{f9oBxMv&YGfwKqC zIwiYlvzjj-OmAqtT-QRJ;;gkw%&HU}c5v<-sEH=h|3`rzoCDkX;DEZ*88qaf*$H|x%_uK~i#u~zHM$2CmAib0S7}QF1Nt?2J-hP>9?(f59 zcqBp@K_v7mfheCsWb*_OUBv;A|NhA&+Z;{f=M(+8JoY{9O3eg1014?oCjr5;ASU&u zDSeM(w%eWjU_OE!CXFmY$gmdMSgSfU3;+b*abhFgMs)xH`MYThSOVs{!u=nC{?kMO z&_!~F{h0hn|lt(qFWE>Y?2ldMI)90VBD}h z6zf6@4sY-!Y@bcVUs8^0BYJNJ=VqGi%cAKR0b0W<8WpriOc`YkM*^UvfWVPG;u)?k zp}@eBP~FsrgV5x)Y25{Y;81xZ?50S2 zr1h?*FI_T9zD@Gx>se5$lyQ%m@>bqc*U$Ujx9vo$jcHEEoD5hiE4aDK)_APgA2r3c&I+K&~e3NU6A6q8; z7uh)&n}kLNKTO8#w`LT*9JLC=Tpr=}F_!t=0{}7K12rysAO)Ci9z^7IOC;4jbcjz= zHk@86Es9a{m3%>-inJWLsXvf5Wu*%-GXIVU5>xTg&?Q_?OeY~(zrb=PMI`X()V6vV zKvnY-Qr({dGHjF1U}1~9istC;V{X9UIvNd!|S&#Us043?#TidRC_90 z$K8?4*f7+U7{&!FP94k#UaW_|#qXOh-6Mmd6*n%hrf=yNASubuUSs2c-{dW(T(f@z zX@pLpkdIy$Qb!~VwxNyW#R(-T$>O(l%cvl=1I{Tvk^@kGu&|{5D;wg^1@uA*TYA5% z@_e@_30?cGni7P6OSRO?_~n)!fAr24o+QH=dqYN}w7K?D(aM_pL??GfMxY34dx<+6 zdcsg8U)MK^eOj@c9{5!mH~KvJ86ILym}BqxH+b}}Tt8XW!Fx73t{N@477xG#-$@^! zI1to`?CCG9kn}M?swW|pns8W12dK`5^ssnWo-(SZ2Z7F7N9O443VLc~!hY=?L9)e# zI)}VdiX8Lw5k3Bh;cX_9{K8!m__Xxh|INR-)nKbmmsbh$4%!ew&}$Wa#6EpcDZ4pt zijRjR5rhk7DuiZYl^3N==sGSOopyBtB6n?_#m`!P@{&w9L)J~6j@sy8In zu10ZeWmry~aPjv9rYq&H0;K2DP#+EmvoBD~WS?74>*Ja4(fH1~Ux7S}Dz;$h)o$&T zzJjE|vJc`CxE{)Vuc14v|JGX)V6F2>R%YxYbW_EZ^YLTYrNshj5@A(g0Pi_HQ{|LG zW!0~;=6&dw4?*-UE%)`$ql#Earx=LVd35_(^{pWve%V+dP`lSjhb)D;!u#RhOEN;j zduB3@wJ%xyW4|6NiFHr7TJ5@Fl#~075%MFKX`@^vbhRna9({%)Zc1~=2Y)`uK?;eO zrWB+;YF}sM72n;Qm%#LMP7~ea793GcwYLq~V{+|c^%$c%zx>ElP)x!LdU(V;3Hq?O z+G&)qU!e>OlolL>S4eRp)M|3`s>j>t$=7@mgz9l`{|*t(g>rpuTnb+N|8qyk3;ySm ztCgq+b1Z~I%9In6>@D0-oTAGWXpn&C-jN1Xdm8%5ckpK5 zmw;5-OBnfg@zp24Xz7>08Q3Wf*t#ZOIVD7$2o+r^RPDsodqMqv;QO!Fj~hT}#0)EP z-ba*r_$HO&4A)2`+7RoMm#WxVGU7nla^ixR*BT7jW~c|#53U$TK!H*A0i2s^l%Te% zyuk~loNYBPPB&qK7rP!IUgs|%ojCawMC+t=T5#mrGS7ZwqBJ_{Ld$)9)9h$A>E9iZ z_efw1W<>_`vPU!(nn$`5gbl-i<>@k&GKZDbwU~rM8RN387)GfXG&JYG$D!UJ)xc9o z=U!ar3N<98lV8mv#e$f|Gy4R*edm4d4$naAgYL}PNzluSk-}I1y1Uv&wh$?6x*Mw8 zjTsHaNK5L{Ag$8fAu1tC^Im+OUp(*s zegFHpA7$^}d(NCWb7sD0?%bJtSxNcttyyHR5+<)@1qb^WTWRCji2}F~sZQaq(Vv?d zb6v01XvMt${N4t|lhv|&;6?&#M$V62 z!^p3xX%Xyxusov}0nnWjG(0x9u+WEY(c`~xLx>y-swLe)SH=lS!SLPUVV)Q{>!l#t z#8v37mEUCA^|XI3S;g?>$M*QAD>bi}gHd{|8qP;gR(E7ibym1+!jk6(m~EU=JensB zNlrIeSA*}@E*{oYyI4yyjb@GWi<=a&d@%l*K!FTyOu0i!)oqh=IvoF{J?+IeNLyW) zH=o4YI)j;?>lY_i5-G^ky%l=$6^@z+{7)FE`}A~@pIvS;Ra`M&KoKYtP4I_w3yHO| z!OcuCwsF}AGsgA48Fy0^vIp7DG!PPhXF`uLazP^;D3qfOg$1~=TaVo>S%t_=`3q0_ z4Mn3bo3^yYd{0$)a|ID1-iFlF#i6P-g8+eL1^AOjD?G;Yzu@0rT%@e{V`5RPlUvK# zu&Zao*G*ajps5uMdraV6FhDybs4!_xs3{(E>sL6Mobp*_X0%2YP>7ajQxPIEQ$~f7 z6kfW*p?NQFgjQ_{2@ridw?hv(!q^UZ-+%e-F(Oj&GxG>P*|0c-0f63(Zr|W@Jf5&b zQUOqL0zFLts7A1DAb>(q)KsJ$Jd|*T?Ku@U5fXq{957U$3gjp5cGcKafK{qM=RcG| zHX{Np4{mzeY`&QS1pXq(!c$13u zV05Bll+6pqP$q@iUg9v=5e_THn__Q%Vc3!PNV{wGwz=}-?~Sy&ewia$g`xX|!I#gI zLVx;2qEHq{J2Zmj zzRUXLJpDy-Jouf#G`$B27%*8ZT9UHhqW_FH?8&~;wq4m0xew9Di(EA5HQX8>%*#VjF5+f0 z9Is7she#FHM9rTum$yJZcQak{&*k)>8$ZrxercEYX%b$>tk!KTD=B6Rlk~L`A}>RM zboBRkp~j$&W(NZRa4ee>I~A&o_F3$w z0loDeJr+E3zQ5i2ApjI0U~_)%5hb*l{G@QNpaQrm?j8sKB*UkX-b`;pzx=ZEbe=H! zn=Af#`#sRb_W2^qQ~bk-V0jx?O)Tn7C)b2>8u$9W{9qj zO!~ZgKDz>7)$Z=Pv*FM&l6HxkJXP#nhJXnY5j!aUCbITa!PhWJ!pl(@JVX>T17}R{ z;W*IQcXUWE3?w0xb{PPaLJs)j6GDf@d1)O?7+{e;d%dTSO#ss; z^>n@4JNY{L4L)mZC!NSgDC7w?bToBP(`WJnb@7Q&DQodgDFWiLb9vjOX&0rG6)6R7 z^t0P0g-x0n{{rbo}<@PjHH$WU?745q~dZQi#H206Kd9po`mrgf4)O*Nj@z0J{q{e%-c*_JBnD3v2E4Z&ubr zSjOI-#`fp=x63q4c`Uy#cG9*h!sHYDV{qMY?d7klH{m=cE?4FK7kt?Jm*Lz$CwR-e zSN`q{HdTrgNdkO>B^%!B8D6EzcHVtXam_%!f7m|xvChOm^B}sx-%E^0)0%IZtGoU+WOpZ(-j-)LUiVH2uHjoD?UiZtmPL`Tk3#j&O2|-NMF#ET zhlGpTrtMXaDMehN-}i;r?N)y{a6Eh}!55^!jTeSCPI{%g#e})MwF4s_e^aHUhe564 z`i^WW@E2OzgD2&$f;?d4##V?_rLxuE7l9&zhz+&ZIE1a*;{d8eM?lEd5&AsY+2|qa zy+iJT@n1#&WTrih-fB;<@=;)``%Ky8Duo5=CvJ$VHX!avky?-5kel2;Lhp1Nm;*71)`#K_R> z21G5;_GoC@-sTxr(^&jTa0@Mv&B;*@$P1xOy#fB(GK14EOA5?Wbe~irijYgnE;{`4 zZ#sL5>^*xUPVFUEcGGnRJ`V3aU?XSQ4Nekmh_@o0oYo?G zM!FMCU*oOs`u+A@mWdtV5wJ*hC~2w!rSx|!n{M({2_%%#`&Us_cMdSOEoeU!WN^PkEx4`{e69Jplj&bb?4!43bmA{SPEMt`-T#k2Yg+vhaP9(t7!`#)3&569Z#F zGVSnYx8Mkpr*4=*SHwg??tS<3l0a&f`!}&XzTzI2_=ur&r{gOwt%3QYAp(HTjD+Dn zO=dBBSTF=WPX82L(#T`sDeZxz-d?f$!j8o@_xeRzLX!pu`c)_S)g^IC^C^QxD@8Qb z9GwpjiRfjPD_TKh(7h{}Gf_gVF#@u+{W6D}8lp}@V;RejeDt(OTAAYC`A)de+J+Nf z3p|~y^vzjQuzC(d-0KwjR`~p?F4=KJzbRfOyX|=wx*n7wL!NgSol{mt#A!52O1GG$^c0M`()?6=gEQ0d--Ej(=IUDwjF$_Q8HO~^jduc^Lgx5b< zjR=zp2&nElyeyefM8b;kTokb^i1gz6WJYP)Kl-HP2DsoRejJYER@b{y8nB`@>|W1S zw{qx5(8IN#p)A2hm+M<2m&c2zNnd%5HdSp~t^_YKG&{Vd@Qz?-*!83-4UfTQNFX>~ zF=hE7m$|_j9tNP)x=(ziz|0%`e2p-DBIu9ht%byXm1dKu=NV!JN=XtZL9MbGrHcQu zfTsVkfd9z~dmAMH%G-b2KN#?O&D5{w_GIrE#z)V`X4-~Kj9_i5ennKn_=EimK9t6y zJyx9Pd-GG{n81%mKc9IZDU|SOa#Fv+stFSH{y-rJiB1TBLX6t6xn28d$S-8b3oh9S zG1>UycJ$`UBLm0PgQ^Zk>lxK^8yneGqq3%@yILOvQJUee4#w7n<~WMKEUPnZekr9l z-sPf~K;o|+#dJQ5{k?rHilVGTAJCNbG*g1aj;PL@smfckH)iRj;Z|SXYZ0C?+1c&A zZ|bz3D#gsi&(tO6Lxks7-KXm`#8i9@#*pzq0fi^phGZRyI{OaT!lf*5RCZvXmq_;A+ozy9d zkbqB&I?=V#=W&2^zVSHrnRY%Q&)Nw;B9>W=|HE!_Xm;~1-WHMKrrYnk742_Hg6iJu z1(;4zQs-wR`#Hbge%qITz|(&51?PPu9*L2_I1P_lIX-bJW0sVz5ocFl<)SgFJ}Xu~ z4ppYKxJW%@8gJ{R`pVarpLIk`U=uTEhG$=O#N8jbnTo&GAjEo;4rzRwmTr{x@Ml#Y zFP@op0&8PdYpIR5(_5}OYGnu6g)gf;M@Jud0-U#ntNNnS64FcUG+^oy&AyK+`M!M$ z$3Lw$pnMT4d)eZ=bhRN9F~&WgV3D3tLZ68>x!%aKA#UgMMQ$mnXZL9RZZ8Dop$q5e zCR%P8gofaKID@v2=;Ly+oD9TCNB+H|49zsH-WqRI*$~%D{61_H;t`@B4WbwyI#sV< z-Wg=I%Q_-4U_WDTE(UOV5h&k*IQe_wfi9_!(5>ba@6!y-_Ff?JRmnVlu(5^RkBu+( zY~sD+w*Ap#WC`voQd!5f&%JYA#Z><;33OlIMgTHFa+)gtq5ns+@0lL}gh)aKNscyB zn}RUr!vk4ATmYEURRN%ls(#I)YZ6C!Rd)p9ve)M|*~v~yc=!QDXNAP7fjtA?YZI4U z9Tqv=fIM@C5WKu7jj#7s=u=sXES0gpVzj2COdaGa>R@-e3Vz3JO4EAyeX#aju={lX zqe^1QuiA^D@~cVY94%Pd}p2QLNfo% zgX)=Bx)K%ogtXbBDgE*Mu%^BhBujCQE);$-HDOMlEehoN3N`O zXPK^P9(+>*bCf;wiObuh=Zq4~qm8K{nAAnR)(V3=HcaF3iCK`D4biqH`Cn>HVB&2M zNkblhTpIodmxk2YjcWW`(^d1V?a?b>;v5HC1GLH2>L$W)d^>el(rSdrS2YgW8Hdsj z1Y)12SPgOA7fN2G`X?U&xz03Qb#Wx$Dau2wFJV=dF*foF>EH4MFlcs$ghRw==-eyy zG=!OU)onV8DrG5ciUaIN7S}4cw+QLc3sMUR#maYS*z{9!-%+LO2QU@f$EZoLUs1#M z^ww>sZBI?46TIZ^+P2ceqSPe6*KKX%*{Z-YDRCj6YCUa7*!i{@e#;1 z%y~2|J&m=31F_Jc#)Yd-Eh=T`MP6my5A0h(b^6Ao*dk$hY!M8^bWP zv;q|hJ-7#myDtEO=%6j2Uj?~J3dwng^A7_$kVW>K08&Q<+yv8m(U=K|sFb zV-?ymTiAuR3ljD_ymyd!z%i|?cn_k7Zi<_Pph@qQ%$e-&OZa#q25r*tY6yN~k5?!B zP1{R`c13wB8*SRiTC^e0p-*E}nMrm0!|p}wk&%+xtme}R=4(PEZ_nBUmYrkh=^^g` zB~!sC95W`bDtq*xqIzXB{9{a)_o0!iZ2yOdMcA6K5r^g9Wr)bZ-tWJ$vh z4E7&<5R=!mDzT{TwpZ=S7s>navF|DEz{kqQI_<;Y*ab1LL-1J7|z;pKceBO zv5(CaAAggx17ir}gyKg7TY7&uH-dv0j8hb102xCDGKTvfj2X9e70kngsBmVxZHWp= z%0G_F`*uL6O|xbSRswiW&D|~tQK(P%%?$g*!@unW5Yg_I9UgnfYUrwkd@wU}Ayr~Q z+aT1@qEkJ|N2T1Urjb*~a_YDbIsW^zZPXR-3ShRtBB36WZ# zlGYM_)w#0Qytklzhr>i4(!1dmJwB4z~t>Mf- zjybxc*I>;RdrM-TfU9G*xtFXm^CR|;8A_cTWr95Hx?gL+nm6Ef8}e2*^ko3QbIi@laISdOLRicVf6|jf}*_q;n)m=Hp1Tk?q0BAEq7((dpeY@=?&NfHyxecg_1>-&<=?77|tb;x{ znkvX%5ERCL2HMdm4$|^hnC2hLt!DfJ%Yfzq^qk{4t_3AgaLuYRfO|3+tymto!YW~g zS!`H>D2JKCsc{V;2~C3zXFT`SrYABdNb|9JT|TQHc<;q!lz-SIFK+0D4^ zh9UTxLP#43KwrSuy$7pb1nW0J#FONq?j&&91O$L}bDxUj>8KHet}4JbS_s6p8lbox z%VspA2SZb)Za-hr)o&ZZSpKgvO8VO`bWOho{w*^=s@%@sQn!x)U}qeqnj?My+Iq4( zi;@^|b~UmXCv}I9e8Dv zEOm(c*fO>0$L~xkErDt9y|;2k+8=WH3#3mQ&5LOHhn=gT zo;6~+woKitgFfiboRK3&+Zx6o+h$DI&UthJkKIdoNqt|Tdg%K(o} zfB9v_sYOiZQ84l$v;%%x?xah%2bYc z1+)6`z{x@ANEM6KCjQ&Y9H{)?{DeG9f@9bK+H(v0m$dN<ha#$YissdnDPwGo#Cwvr zI{;R@GkKktk<&8_*r!h{a@L~`(2V>r7nA(a=O_|){eM?8w5-1`l&>-s4R>Vl{rT{z zl^^zAv#S6n4f}#41IZwsN!C@(2}CN`DfJ9nw4zWmWkQol@pbClR_K1nG)Z|fo4|%$ zA1MtxiU3Ukr4==!*!{%UC?*8(jEo9yq^L1gX+SUT&-UM!+Zsv^C_c>iI`_ky9Y*V5 zWC$k&bZP?gYxqy;hT8bsQEW2s6QQ7j)pk)@hxC7edX_Z$G$exajK4Kx6+()@ui?W_`?%)h0{BsUzX0oRU;Y@1LW>qQ-Re(?M9`O z7J-WfCeB50I9N&t>=u7q47U*L0RY<{o`!Q%gzWq(WQ&*9@!0veu%*9YL7(T%y^q7a zbn`=-#8_w5u8TkFgM%m2etnX zi~HB0{(7KvyBI~aJ3+h*5*}k6$uag2fQ0IU6|gOUJ@8dRx^aLG&0rRezR=ac_8Qz) z@p#sufsTS2=uZGZ$>IU;gHWOuM*U$pkcNOUu7bbnE|qJ7ZH$Zs-L}gNA|fb-Y{o!e z9^9n3@%HogURvxQg+M`t!~JJ8IQ)P9`$H!Q0|2BPW!f_NamLY~yUY81z%4+A&W)bk z0P$7dj^Fkj@e-m@9Km;cvVPyl=YQsQ&0`sw-r!*{r>emc4oeGbQ53$KaPgZqkqtN* zH(wcQu+EudFvuL{)iuyXZJ(EW$e2VMW|QxBE%kS&sC;F33d8iBI86QXDStxm7BSBntUXMzjObNCHgkBnstmLCTF6Ug(8+%^)qrO@5A9U zw7uV7RuX)g+}SW18MYIS?L)jQhOXrmCbw}Pn)CiT8qK<+VRkP2>Ae)3+7RynCEr0U z@rWn&i(gXZb~(!rG0s9#cBlNwxY(n3t-J4kZau>L&J&WK_mn3|6N&l*Dk4(hWBRYz`w`l24O7VsE}oVKpIcz3d?4xjVpp+mB?hgal>Q)U{p>7x zf*N&|*=TcMZ@97VmX$?sC`K z+|{C1OmL@{_63A2;rCqD9BIzV4y_&O%zSp1_#F=*#?)m!TlQMMHFpLM)Rz32%@5-i zg}&+xyVc|z=EbH<%-9|rw%rw)cL)%?Q8 z_EvNzxt$uwh*#6-OCmR|NA8U#oi1{u)(g3WTQQw{1>YX~lp;hF<)kr9x)FIcZ6yje z@ae7j5{-{q(dV``Xo~eZNf#v)--CA^a&Di*aLWy%x^;pjGP4w5b4&8PPkx!F^t5zW zMZqzcBr9>bMg3elK2B^E)xTcT64GEirF0E(R~`>cimQ-Yo6W~&}F*rD^_^%(58N^=y8tnvjdBXBWBCYVKJtsmXHv)JiuqS zc?WX3*i|c>hZ6@ZuPgUyRraw}Wi%V6;s9JO1YuqU@q1v|rMohIhV{KgUSi6E8SioK zo?RH+??Q{Q{w$XV2VhB$eu(ym$0INdd5?%#$#rOM`J;+JfJH#>oNjyN0YLI~-0|lJ zlxdK6I@)At0#wTH)GiOW&9>ssg*Jd2P^J-=CO^WJ-j5s7@RHO<@j! zGQGGMH``VmH=02ckCU%e|L#=4r581el^p|7PE_v|Q(~@LJwnIT@15EtM8QqHr_Pz- zI7OQEEYw9okK#}wE6Bj{=4>UBqMWtUU0>z!3MyJUBQ+Ezue7^jtMNX$^W}F9O|suu zEz_^wt6t^G$y)mE>p1AjG051vsF-(c%ia5eqp02A<7IQ7%AzB40TqLPVZLg@N$>KN zTMRdTJ>5i?Wqi_(mVv>2U-2C@%>VS_uBnIe>x*vwDW7NFT~zKsV!LhC1!!^7P;vjG1AQV~e_S74FsRvF6DNqd0loGs^$#qt71D##3 zfUDv;or*11DUH=`g)tImx&n)2gG4D+--ewlNw2q~Qfi;*0~Oy0D~)Edh4K*XV?1)J zRHaiGdheUWeUX`D_6T1qOi8_JZn$r}_Y@fe&* zow9BLI&8F?e#KvL6<=R{-d&Qz&0Qr4b*{q$kXk2MFQH^41J75TMBH{OAiJw{-ye%A3*g112_gQ|1=7A z<&pmp3_2df2HqhcM_JCt;FY&IWPnkSz?lDO;BKh{4{=KxGKfgRLj!lcoFtk+4vRG=ILKRc90S45O8*6; zTN^0;Se5c!>X0mzv@%@nNNetFhQ{s<&^wr|H7y-aMpN*=@5|u%?uDu9#+rgs2!QhC% zl7=&t|8qqDiUH9>QOi`eb#;fdm>c;6z_tTSRIu}`0+2H!9Ty%z+7l7r#w7oqe^aP& zf)GrmS)g3$`aZG6kV2dx8*ci8rx}4A;>mD*^x%*eZ(&jK_4s{WFrQ}G+=EdhNDzM| zxVdp6fr_&DvSICj;NrA_9?M=ng^bOqoR!DPueZb%F!xM{gA2lcenX3C-nExS}5&|~w zvmTLmQ1l4e!indRqq-Hz)JkN_#0~&~@`7S_0VOqQ?F6M`maizj>jzV%fyQV~|pGC_`WlKhqduYWG{#6es(wpi;(za z)JpQ#tclDQ1M-{vWokQSxfHW)8+f`Z+0`XqYCm`{n=c_qQ#&mB$T-Igx>ky$Y}Mu` z7thzWj9%bVG#0(%VT^UlU))!kIQ1~qm~C!F)u@wrfxRue1DjzmX@`9OaDj3Ek`et0 zfFpBw_Z#`#I=*9!*W;Zl4C2Oc^KvDLfKRhxSO9E*6;oVfhWKGpaXn6tCs@GJZ92g) z(%_dS0@L=b&MY7tmi%2MFucq_RFDAx^gj(_ClG+Coi2U20!DL0gEe2kL0rZiP-z$? zb2LtE?VKDBaR78XvbYkERzJM8A3xdovQYc5)gE^-wb~#YCMn3uDlzyt8K5ZLhoO!y zWT9N(Lh(B>8hr*>H#5%12ZkY< zeljH93Lcr`_DU>kp2P(v=XT8oPG&h?*||4T`OcGFWhA8FS9Xr+>mK~$BOGC*1RSO3 zB_JY<;8!0LeZED=Db24=y297h3F&kAM44dA@|0+oX027|UB2Ls?1WTPOenH+ui}y(z}j#sGU=o1m-?bh8}G~f^Tw0US3)- zt13eE%&5ax&*x<$8XyZdoYZYN7~*8@XG?nES98fWzM_ zor`cI`rC#+xs&WsTjv}DNg?QGutlJtu(V}f@66R?1^b7-9$fO2j6plT(*f{mWzDEj zzV2rv4QURR0j3I;S)hwkuFkEAP6)|Bblv)AzD5)XiIoZ-MJV+SFBcwf3=(e;KKpXP z^tQi7@E-`R=@+atFxdVa39#cMED)f~l9#cyrh3HapO!mEe6$2J{)vN>4?}WxasEyD zzxC3;_Ig1o)&U$ug&~z$bX2BH!LM3^43WvPdFYY|FoPhd$2buM9R($?;K2QKxHErj zcK?K;9NQZ}2VpVoN%X`?FQf2l`mtLjHjWhJhjcfVU*`e>*kDn$cK|rj8+$vp&(Nb+Qv|>Uas%@!GL~~_W1=k$lIExyZ;1s|E+B$UkiqqcF;9cBN!O|(2s5dP*^}w zZXT7Zk!}~)7I-m@+ubv_JT*EiV!&MqoLDZ>h&d0)Ux7qM zgG4(2Ps8>%_r)!#)fNfGB5%Mp{t%B10KWa#%^VibrtE^5o~@s*K(Gg`;GMlf9EG)@OR!rWB&t=?m%3w0UsptD`AZ z4Kj5%PGT7e01pX?|rQl<}3E8zg;JGa(~)WbptC?2dw z$DHx_mKs!Wq5c`f@V`aj&r35ffVvsZBZj!W24A~iV`n<!>E%x~f{QM_C;2$A! zQsCA9y%s@-Z6E?DNf^q~(A%thzUmY{`;}9=t~Qj1fY^RBh4Y<>;y1%=hlyQpc{gPQ z8~NqeG(rwmwnp+J0(Zug6U)}Q8JjPNboS=|G|R8gEso{V!PYzk_%ZmhNXJVL#(sa{ zw*tSKjYxc73K1xx)r%jHu+d!0)>@-HGR~ZiA1*O&pdPmC)@vW8@0(Mqz~v~!;1gbq zDC0h!3rN(&%A3#U_^K8qvouf`lUP3i33OcO-BkH?QZt`I8L^pm>ubZq&BTAP_slCjKQMPW|6)qQ zhQ>l_dKRQNBC4Db@P*;Ccu21=?>IDX|KYv*wnX%gJ$oY%7ho*uZ643lh&tf%F z5&#tY4x9#TkIPsN+HVSymC$=Ze_{g1$6 z_#li70Shz|4_lrnNj` zGu|84Q{!xJd1$c1r2IZN+Ah{4p*)PCDfzP96GhoCp#bn}mmeOhb z=a(0;#|9-IPHkWh9DUs=y!pl!o&>bgM2G{}Lbz1y-p)=v3M)#1O)2U-nuyY__goD3j@QX%Jc99-z0@(CB=l!F>UVhmLM>MB>X0tD}X+q1}0q z!sHEg%^`cQgHCj&v<~C*Q=TyjmEL?A7FQ@>99Pf|TI~*e9>$4-cHf{pW#!Wu+s*uB1cc>q-&aDrCZx5uyX zFb=W@wOAy~<`rewBy)PHg^4-(qV&PaNTK)3v4HBk=`q34LubDY+c1D$NeBl2oi#Ia z1P~xXKU(yr;VvicCm)H3>p@x)kv(;^$4{@yXcn+l@}M*f_>p zp6!BUr2tPQZeqlmxY${3OQc>5h!n<-13Zk8e%NK4D0*P8P-?1DnxBA&eKyLj(`XE8}e>0ByfArwO#vTDl96V;m{n68$n595#q3 z&(;4YF8f=9iXo{ZUI*jv-i3II}PP zzIvqlbhJ_<6IPj89U7%+P6reTG5xd&wJAt zG&UV}&I zg?8e>Ek9U)UF-^*yo+7IcCNwr<}~h-YStBm32kE~mBZgVf*$*&bVwGd#nrm}bMskXKcC-kmg77Vv@o1-L6_ljYS{* zb(qB-Rc|?WePG>KzSkh-YMR!lnEN}LYdm{GVV7Uos=iI5mEy*&4RkrqUh#@QyNsaH3$-4S5juN^o~w-_iXLDNpUbp zJd)q)czIq_i1Tg3C&-OTTj~tA%GacXsP)rOcB5xxQlxJm1}nYY7UdK;x;hrI#TScw zu`m{f$CZxF{U$)!n83X=*q9f9bg{em?3a}vc+oHg#M8p&*Z~G4!!7%uq}N@CH|W7F z7y#q40f6(Hn3P4F8-U3H0Ps^b7l!lKyD)!EHMpK@1wg}aOz<5LpoHJv4>K1&gnvU8 z#XubFn^uq2;G++BlK_k#aGV5T-#1|$TCt)?2#wd%(1*Ob&TH7R6v-7=j=dU(-pWTI zP1i!3lBpKbXY2U|D;9d#3iT_xzw=*CYGQa^_l~Du!bC+51>T6x8C+SXRWv?Sg?xSb znCuC!HH&{2ItN1So}NM8x0R+V0|3%=^<0~5;oTPngZyKD4Nl-8s)snAFOmq^62~^5 z>HD)^009s%<*%yZ0QceCI+!F0XrN|C*(Z(^dj%(|l1(!&zE<|VwRvISxFaFC*xcY2 zfQaB<0`^DHQ4)~<`i@m@=KiXJ61=5*FuoOtgBA5ux9N$ZnW-Uyhc1Cn_WBth}GViul(!3Dwyr zx}-X5%Q8qqtqRFr?OeQpbJG2!>YMs*Gqw{-*W9}olt95#%6q;4ZR!_RpuIT-b4s{b z?0jiZQzu71GeU}%m9KIOC-Ph%^a(m6L9QrY$yjOy_BtQC!pBEEm|@X^4XHT+lsG{+ zR5rRk1S6hdzFMy&bpp4D_zf9zFY{#bXgh1>rpC-tot>94=RfMzfoZLESM^aaeYy5BHGqN@5)+_i)R`Q0kf*-flO}hC9Dg;WhO9 zC1-u+@!TNfXm|%Mm#-TBArug7GTUE`;_1|8>qe}&ymU80hj7=L(PPQcqrNpsKt)B5 z#17FgFki<7$SrN0N$?EE`{?D~|2k{X8;IteLtK~RyJvYY>T+|Qm*fwcwDrv3%H-0= zSgYCA56-%ZsSODSJt4ulPuRXo z^ojX8Ap;9r?FtB2;jlAC6uBfPJ$eGFoRHFK?)aGb6DFJz7h{7sf>nvS5&a})Kf!5X zY6}|q11Yw5NCDwM>VfKP0CjFs-NBU5TgHTq*|l0=+ZhNg8&{6R17%sI6P(xkvbn^S ze?Qa2|DyKyOve#H1kJM@*6;*h6mUOED$J%ib1uoDQlFiPq99j~eq{97KDexK5nI+h zYeBe7-;=Qf<&H#lv-!Hmyp);kQy0mf0#td>mv?u`sUHfxN)Ez^-J75il@jXV2yxEx zzc$<}A1L%Y>k}{?p;nA+#NIb%doPE zqcR4B{g^!8H?)X`KE$%+;G+GE^TVERWv)cSR*cpMZL47 z=XPzSM-?NsCxqC-!bGM&3mm~;vB*6L^oe6anm&GC z`||#9ffn=rQ4Sq!y8k}G`!n`KW;y=d1aHM=OwZyGoCjuizv_R9ni*3w_z7pxKz}RB ztc+}Mt%W`-N2uM^`lg8)Ky!FzEdALKZWOPU03%;NdyetFoZQ*sF1*|pxUuKov$(UP zBU84_f0`kSmfj}{Rl8Tbs9mxM*mr{Z6+?A3M&( zcRppdFck74AJN0+R!RJI_GXKbijF_U8=BRbOG-BUq*+7xzR#`)XOG$QDDb&?W|9)I zNXR?qtF3lV`^riI#(d+mUok~#kiN;uIGQ_TjjxNEY~<&Nk6D|zseRLW)J;iEg4gO& zhnx1;CW|u8Xx}L8kyG85aMV5vWz-`4*+*diNDs-pXUbhY5uonsIty0@y`9FuZFF)j zwevrA10&h+-+sR6dIVfGUAkSbO3q&1y~e4x0B`|b#G@^nx@~-UWiaW=ZuYv#^N$sc zf<;~WuemYtL+h}Ir2yctBMye{%(uv;%_yLId77P7|DDTZsjqOC3w!N>3MV@k6^@jS zOL&W9kS4h+VD|+zb`{Cok^SRB9Q=r*hDIsXEwtqbDCH zEy(IOq(}R`eS)j;)aLC9@%3g(Rce9^rtu25OY5|Jbj@bqbPz?qwp!l{(&dB}h=#sz ztHUXI-$VTn{xm8&o9I4H$IOO3Nk2`+h4}EW94~=c6sI~T$KwiT<&b2y0@!LptLrH&tk+9m~A6C4!`F9 zfM~u(YvPyo%wPBXOE*E-L9WL9gR4X8cd`Iz$QOAO?)OkEwlI<@S6CSUO9MoZC}R|y zGh(L-7=*JW!&Isac_=p2?8qVJn6$X_{3e$n91Yx)qj-`{3hRQyne=CQ%8I3rs>c8buh@8ci z_$Rxb@91&upo#02dhZ54GbTW~xC>)!XMKRmNVr1Utq8|tQkV^%O3HkD);#;Rr&;8c zHnZ-|J(?D)k2|K>2}B!;HXXkwUTG66_D(RN6QONEzG4NaJ}d^G+rD~^tIB>30FKYv z+?eecYbJF(b6KE*wG@NOhuhpI+YcZ7M7u)D-#;12_8{OX191Tih6PF>709dq>^N@m z*=;_90RWR_r?KIBCNgaJXV<{E7XY}!(Z+$$>4RyOYDM808TqL-(*is|GMJmE?5lYY z4k?)Lw%?LfIE4p-%ZOV&L9O&%6RzOaGhsR%v}U}s<>Bh_Ti}!W(bGfb^I+*H6#~(x zS)JQlna#@Y)3Mc^C|}0yFJqA_eB5>4HH)#!si?MK>rG$r+72^c0P}6 zImn(tX%jjYe=WdDZg*J${n^xBOVcx4OZ9T(0-b&AncpzC}@XpN@kVF9lwU99O4v_7}i z40LP*exTngS9iWyP9{MpcMPF8xyHeT^1ZMQ z&~ z6z8X&0o19d^>DI{1-r zGS3rf;mZuY7-k7g(VLU?+|v5!SL@VEc^`^}7^O)Q!_W&(o)VsB^TI?$7pM{kpD>Io zWaL{{w{pMpcs@e4Rqu8b%_2^SpMT9%l{}1V?rNjnYz2h2{fy|?baz>RFr4qaa@%sz zw1iVWa_fB)`f^Yrc;`}dHZdY{EnpxqzS_1oO=<`wYfFiE zHwl&fh(+Va$b(LUbv)^!2khR&x*HnPrfG&1aI1GS3=nJnsdbVJYEz{&t&v*qcHmcn zLGV!1=$bYv@q{Zgx>#v2+9C_xq30TlVcINP- zZZ5Qq^X2m7iRfQLX58;dl_pWCZx~K2KD4h%OjB}R-Kdpw6xCAHDE_#ZC_ep=#-hs1 z!CgMRhs21N7_1w!QT&8D$xu-gXv0MNIfmxs>$ZxP?e%@g@~MRuFF`u#jNs$=yZ25x z;M?+9L%gQmn)*ehOwn<@=X2l6O(Lp=SgLkEeu=Fn$iNs7+lUNC?hPA8^yJBUJ|M~q zZ^rKXY8;c;X_%Z5?PDS8IBez7=g?ufe`0`Zp6?eDdA+D6q#$Y|b%y^sZt^%P!XgxUO~JaPvyw>6beLPOJ*78;px@Q`j&@Md2GHGrv7YCHoYE$}mn7Y=_+_N!6Vk z3uYxd4W52`eWEL~zQCQ^MLfju_WXc>yGA%D11}*j?wahoc8xFTSQ|OQwsOyr-cHI@ zJ@=9NnqfI*CH}WZqA%s`K0SCSiI#F&fG{{n>gO(;sIAm~zIZ ze)S3AUx_2<@8nPaqMWn88L^^VP$fxFWkdvo%Svlka@l+c{fX6=8{+&ENlaVg)0El{%E%&s2eMzvz%(*GX8urDdmnf5jTsh&cD5q*X%5i(EnAu_>K{B(6(JOF$>q|ZIOVTQtV2;b|qk~|r?+p8j5cvcFtum8a zB#GAEr4yBY3GXAx-HvH~yfIp1gzg~A!HiBu@5k<>jN-S}122;ewGL%B%%t7Qofj0J z=onP=d=^fCEGO6ws+jAK+y+#n30))dr;vintm4&mGXqLgNs24I9@{!Vm^|R3i2J=W z94ms;&1S*Z(Tvq`Lh$fR;MTr^!X4ey)Ngo{G=xmted86dyo@`(mpHs&Nh2oi8a&uV zWI_pWm*FHMDmOot&t8^jbx8Zp;J+jWOobk*-u_EQ? zrbF_cf!giHEXK_@DO>c14z)4<1dCJ&0>{XsFn%537hEZ2LJ#ZdUYAz;C2WpdBE^1T zZXY)*GpD=Va({2=j9|BM0bI`SjJJ38pi}J$^+o+Ue{Vg)^=|8Y;XKPOHd`o3@p?9H zxgn-=D2#gZ8esE%Dp!f3VD`32dWrozolWtLKpc5itK+xAYlwLX(l*Y zp{4W+iAfH!h_pxS{97XDXeb69Y3JE<^7ce*{BmQpTHtBt@o1<12Nj}?Ha*rffRmyo zJxoS*yd%RbAW^Qz{QN6a1wd}er!M(fU>(iSRvY)8fx5tPg@f{SWCGvtq#~gaUGBm( zpB<^-6z&gQ&8vy&5wjKEZ%)pT=H*E8)dT+^lQCUw68`39+3dWvRecC%@$$$`r&6*y zMKnS_<4CeFYe?jq*CxT&g5YHM+a;zV4};7>8W^P!5|dykwyiSdwu^{*{S4gM_LJl* z7+27`P9#JVcO%qP(`|Z6{%+e_+h0D#X?W$fNawJx?j%!}2wvP^ zq^Tf=(f#MthZi{o9B;-`6zxc}UdW_Dw+uqQKg$#$& z@T`t;6gdE3-*BgIR$NMxR0?LF;pkjpSy&ybrc8Uc+ibJR<=xi`Ljqv$6Y;)s{4x7gzNAcmKes@)+>&stRbnE|?yRD2JW`+=h6>Mg@pkIcdSfd|e} z+dl8L^B9r_a@}qh9{Ui-YrWVpb!w$P!ra6XC7cc+v}q2aV~;mM1Da+4z!PXqlm5lh z{KH84(^LY|uK*j3`Gj15b8WY%Ww7KQ7Ah1*-KU2ayMW%*=Wt{)Pe5*cj{?qm2aQ#y z^2e|yP7Q`1ru$SX*V$u8Y=h`sii!$ZdZ#+>;GDaqZV4)$!oDR}J7hk6$_V8iY0aNB zZa=_&2sK`j)o_|N0d8k_WxgsJs|WW}8a-5qsvYsI$mu!P4$4% z5XkK|$(Jw3C)@N`-&)*GDNj=&XB`e4FH@2c+TiO&(p2%7j5YYQbAFHpzimuo*lEhk zQik)=EiiVBd6N<7NBJFgpt<&3-}MA*)Qd$AKPD~;v{_fPCvKNxBWM_i21I#cGNk35qmw5g%V*e*7ki^Twl0WqWxN7!Xt;9AY zfvjUq>#Gr)ox4`xkxF9ZUH1mxZsO^?(`|hm;v@bJ9ZZNw`zzn*oJ3-$X@R05IcD=Y zcAX0o$0{1_L=MVoZVY-rxoqaBTn%%1HGU=mZehO?1kH(%?ZoZzf4 z)&8a=QzUh^Rk}&c!x7&pGV8oI_^D9i+0I?dIXZa_W~Uf3`B2-JNHgVMW92Q&=0A{l z+W~FN-O(qp*u80U-x^Rn7IwBAoyBC2+218`JH2bEAG$`omT95J1+(l=_JqL<&n{UC zhHfw@Hw!ZaPqz;KY%`C@>lt6Cs><|nUuallXTNcB*T%!jWaM0nk4(Fx1I2efqmWS2 z82Ce(I?8O@^YW-r;BHnAk_lJ5g{}3Ad}5S6?^Gme|A6h2HR8WH|47Dxih*y zcJsenv5)Dlx;_sqRwO4cB_^v)e3Z=9$t;>sTveNzDKn@%jAQg@ z0&a_m!+52iNl~>0{y`0dw+@yvqQ{tRny-^n%p;r;Bvxvbd&APi=1mzpf%N_pc-n8S zpQ68V<@SBHg=J73RU}@DeI)V`N3f9XMDO&{*AMwvPLW?b4O|^RIK3CH--trZD&~cA zm^7WyE=#%M_2$2=k~>|AbE1BTco{gfC07s5{PIqaLZ?%R_xvfQ`@^*_J4TikUzc zLzdr&=RO!Wx4)mVqOMz?nZ~nK8p~M<8ErWk~BB^q*{f z-l?n=X|s8A`OZmLKbe7hi#?f@e)LXx(7gg~di9~gR^tIiksB-q>r}YucW3VXzM9H= ztb%^meZShodzx3>IeSU?EUG#yK@>w<)sgz~+{FtyuncLoK2)&;gsBn1()-u> z{v%a|rJXvig_}b8Q0luar+>tPj`uu#x(ev4yt6~sqhB5ndDp`WB}pE-}r>(I;1MqI%I`5{>FSheaUtvznzxB_A`6eoLIMqoGUlo?ff}L zWkuUKQ|}m=w7hMVse?s)nO+LCVf!#I!A5fHc?9)A!Ig-0hG@xtUR!RwGmiMpjoQ>i zXUbu$%W<5jxiic!CicRl`UJmBLLX}-mh@wUukzA0^qU|xu72qO#ZOb*y_F+=&t=xv zj4I>`XgFu1HD{O24ivnv4L*?SDQbID`0G<%5j*SWnK&9{#`i)uTd$RK@9b0d?hk3uKH-`W^a&`V?MZ@p*#Y6`9d8FZMjzge{QuXA~U=j<(*at2KH zJ9lTACt$t`EA|_Jx1>*ma1q)>0a&pj@xLge0kjQERH*^u)&{Slh~SGXf_=+l2(p?u zsG}-EqKS3(_SF}fOZhRX!JbCIUpM~an#ME3G@#)2_`Zeot3(FhqU=z_7v^N>vg|9w zas_+iMc;4p&7t-}+P)>02dN2aO!d^VrYAhIy_@Th)VCv~WA|k3VC5l+*8N(gml0}% z*v7Z-?+?2!6Z|S>k7msM+O=>u!^JmaXviWjzA`ooNgEJ-4`I25aAc2^rs?i{X}7Yi z*wv5LEJ!(u_m!?Xwby{t(l-k}O%WBnGWae*aYNTnTk$K#Vgeu}x`j|Yr8kVz=>0g} z_B<&81P9T>Hqn#umsH4;*KUW@*JMtE{Pp#)O)sgHi8k@}%U9~Z*QMtyL_Ir3 z^aNBNC_FRDsa5wzamm#t96?GP3kVvC$z%h#+6e=4nx<*{vaJ=ZD*??L*LRB>++KOG zOkBo^5JdX6`&@)Lhu&z^K_m%M@HabGW7kdRo#N5!hi~w`{23)$lLXQ@H3%Hcm!1;9 zicLO<*5gx?Dl!U@^1iO9%S2{53l$WbS*uD9qZnlCjeRU%>UY1_+HG;M zCksDeva`?7xQV8PIZwIGf33AtW>yNkA2nGM?yr|~gUQ;rYYM;TD_O)1Wx?lzdEBF4?BT=7H`hn}Rf|-vVX_-K85OTxeUfh2=Pb)H z79czxEUw)vRW0{fJVD{X;11=cBXYbY^1wG!>Pu-Vm++;!s)9j}*i@po*d2|=b4W1W zs*@NZA=0UIVm_-FxUj;yn$3sHTBknC5>ZcA`zV*V*%JAE#N+ zlS`or07kXw5tHG9rXn@0r@O*Ia+@;1FlwPm0Cl4>J)u-#XKV`G-r~AA+;@$Ai@TbR~*LP@DxIspooAjn5 zh5Y7jaodXFyTrx@`Csp0QVj9k=C??0#((Z~|JZAdxNSDAXtOoL z$4{w624H({-NpA*%Ay%>tDoid)kD1QL#JdNcPrnI*R>Mt@V>oP@EQ=sHJHqE#=CMk zVA+PKR@hStA-K%t=~J{4+$)jj*em0+*~xM*mrV2WK#wESMN zA0;A4`E~B}?bRQu&VL`eC_{js(6Z#FO`)*~?+iOd=6JyZc2cKJF1<)v? zE!jrVkNWL3R%|8ZXco=mdo2{}SW0B=f_E5_ZV}Xwy6A)n8Wxbs>qp*gK<&=i?E~?Q z!0p%iKh^*^bkz4dMZlOXEk9G~A+J6g=vxH}*-VrN8CPG-K-CO<{C7=)-OES2Xy`bI~ZS zbZ)yTBJ)pCp}+$siuke8;X5Qx{L_^%ZI^|PoS+fy&P+wVs?n@Gw++ z7(jA+6{?PbBH?4X?}><)AVqYhciuTIAvOdU5F8}X0wW>s89act=fC($7qfs~G66hf zWqpsP(BA&{p=0#N!zHMZkI_tPnT06^w+CNfLB`%JAbm9Y`-eZ-KQ?$SA>f}AI5?x#MMiiKm#j01=?9Om`K`#?WJG*PZDZw0pf-jbBE~2 zRiLh-O???E5@&$udkN9^@?X^FA4EXD9M(q+)NP=IB@vlJC$0LuzO&Uo*kaP~yx`m3 z1*OEIeL{m7PnCe!z3N+PogQqV1jjq=3#7*g$C71YeEc6MWBTeE`;^7LgD9_aST&^Jm{A4# z|8(j82A&D~H=x&xN;DA+uze%r!EW-`!UO(Q>OD!Z{<2ve3HP#wuwu>2rx3+Mf{1MxF>jU_nmkkzR!lm}}}R?|jc6d8FJBt6+ru zcu+!EEcKCFxA9p{fbx`RhUbmsRI70TH?!5Tpn=t`zRtU+z?#Ewrcc2?oQwYG`#lwJ ziI*dNR2e7ZkNAy`+Hr@=b{K|uQqm;?Dz2~huqDmh!43@{Qi&wDy87;!(fYMY1bkjo zKRICCGDd8!+IsK14b}G3AUO|J8HJ=)N(aEkH_HDhR8Cgo6Z5tN!Sqsd#812+SyyUO zE^WPD!+Oo;uZ1$qY%L85A4 zCU(S^qMs~zp#ts$DI-Y&NUr>f3NF@Dhv%#5Wi2sip?&}MT*>o ze{4Hck0v+^P9_1VAOb>9gK@n3G9u#{{ru#lM(K(lwuL85i~K3R4-t$g6Hko%5f@MEbDMI^h>2{xDq3f{ff*P0vQEoBM3SxWCrGzLQ@4(v0YO zl55w{tif9bot4NWB~^fP?`38}wxKi$B6u0{aICY?u8 zZrYBKX#zYat_nwoFQFtkLO5pzk0vZjd2-1wxf%iiJBa5mp$g1C{yX|j@4uzuAm+O` z*)UC2^j{OlKHsk-2kH&-yqs0>m^4a)k4j`1#ZPLxR>B@77BbG&t&al@`X&d+4(`Xi zk5DC(j#c;ZrOJ~Ejb;xm=cAafcE+(ZEg>Ay#sE@cx%hS!XkbS}r6JR}{r)uX*-w!H zA#2ZQs`*7gOvI;st-WsV=OOy%T;_TbEz6$^l@df*ZowO3qMoV}bzh~{@eADKiXNC{ zO~n<8e!CW>-#8qRpo@L?OTekZdxg0GUfq)K!Sy|<);rZs@D!a-6z>N{(ZB&O^&tbg-734v2cWU zS!4o{hlaKI!d-JKR}`%AL5%=Rd0anG=SfCAi;f4uhk`3hs@VG3&xHhn^0-5U-}OTA zjFNtxM@dPdMqd3b$~p0Ug#-uF-_D9M^+_M;J5y>eAL2ci_$a!ikAKkEN9dr5b4A3g zTRdz_J8zfR+JI6m2fPA zPilL)ScoPV3wq_f-CX?EcSu5Gqm{2<@OSO7f~c0zMw$#H4S8Zs5vjS(Q2y_e){3Hk6^#qt)ic4v_ z$@5h-xG|*L9Ykb!yptjnESwmIBy3MYR~p}QdzrF~kuq~+kb%a+@ycAL9r3t_k8iaz z^V5i8Ms342NsE_}u-7RZ0-KEyfOl%p?Ec2sgnSxouSTM%g=2QoZ(xlF=)5MQ^K^!n zQ4F1YT6!)$3Sb18?pmJNkru)TIN^70xdh3_wejYJk;eW#GZHyM7Wn`uc6bPUlu#R< zT4h=<&ONIeRq^b*(xv$aU@zE&6+8bgyNtvO0SJdBd#J0`R=mnEp$|?h+W9CF`q*!! zK^uxiPj=m|og!Bg7;X?UYDf@}rMA-#N=ZcVQEv<>jiQ|#*Y{o!uE#w7nel7mgFhEu z)LB_^w(gWU_VowPLuk%&pS+S)soWb>5SM5QKZ%vG8ZgA!U&{W-y?@#b#L0~aIoMGx zC(u2Th&%i^*B|BruB?cgS*;tMPabr6E0Wh^VErsJ_H2FF2s27rDd$Z7-?x!ax1-zK z>STzuXch>zA_{Mq!3V=*epoXAfF5Y3|A(!{t2eAZPjVuY8@z(R{2_YqxBw3VP|tr; zKGNtX#zV61E@VoC8->N3Q`#+bC$%2oyO?iWnbyYbF?{!^RmA#uIlHr*MA2Wt8!GuH z^?Z_70+==grB1z;`vom*kU+nIsI8WYD^Os62MJ*A@UhkCZm4p7^Jn&L^@0aTK%AEU zkctZe64RWoQ2_kHXhc(WzLS{8G#Y>$=pT3p&ES6ENrQ}S-my|F9+JVRL&w~URLhv%0hS7~5QT6$o)1N-)*- z%cg%G_wyK2WGZdAkt^&}*FKWe@`1cM*d6=OE-sSA8tvQI-l;$sgvAj#gmb<_++tWj z`Pi-yx;j{8To?gpyy5qBJJB%yRwf-y=~W0miF&OQCYc3uENQ-&1_qP zgcs=fIWrZ4H(e)g^Su6M97Y$^8I=6;!>EUsLVwq?1D{bc;dMs)=@%kJ*X+KMr5il( zcui?FZ;bzTV;TAC^}z$3NoB{gy+YPVehGdNw@9XUM1{yWk4i1v?~OX_W_Wxng?4-4 zdw!M-J9?2kcej5@O+LKZ|J=3&q6UVQ0lmZJ;+43@`|v{v&vffw@Vw}ujc>QQzn27i zZ>k$qkJQHb{p;Rt$t+U*d+nh~OQJk{zQUev&qsLyC*G1}=Q2EQp zslD{BmK&ojUYms7ta6>U1JmP`%@bEhR~J$15vbBd1jDcmUgA@h8kcbOUp#FcO>TKz zJy$qFg$I-dPc%I!ct?}Fy5&r(>VG(+1$XG*;uY})$DDCE@bbVlzW; zlpAPw7Lqf}-wG2}DN~iOV8v7zMey@D;azPb9*%rl@`jlzuFUPd^omk{{ouD?(bblS zkrLCQ5pI@=4D0z84h6oIl4}2NFSf-b2@dOY;!}C=xwt#CMv%Wg4!Xq_-)7zBkVW3x zPb=KV>IaCZ?7)aR@5)UI=!jr}DKy~WK;!f85A{Y*;CzQ}0O^CY*Hu*UZK40Fy{NCN z$=YF=#@?%fN83RKYzvpvWu?RnN<*vYR)Uo4ryj^eU0vce8jzz%^J#jEA>r?yc_yr! zpJiIKXronawch69PGES4iI5%8UB#%^re3~=h53O&!vzN`VJJDQWfcmKNBA0k{re7& zE9@Bv|>A@jR{j0OL&esM7UtsMJcXb6& zNBwfuc>F2>F}~9h^U9mkq-l;EiS*LAv|_Q!RU+3#WHhF*$Qbk*?N7LOpH--UNyql) zZ(-uMRk>o+s$xH?s1}-40r-B%MwH8BYVtL=)xJQ(s~QmJzb50f&U)nj*ber_ZJNpH zr4dl6x3_WF36HNAdWdX5!xlVP2&>b-Apnp@ITK_kiYesq!R#}$3R!DF~zGv7h%V{5%7e!!h8iemYFU*7UbI4AcE9(hWI$FeETJ46V;oUn-g*#`?nJ2~cn&SCn z=SjnYZZd%1o;L79EhNO#18_V5NmpXP#eoCN2qcoUghYu+tx0eniYZmR(i#znGsGr1 z4tdUIteK7m)D!@KENBM0|LMzK$Pau?K=dFiBJomPTJ{#X?|oiFUF5~cTnO+0>f;J9 z<&qQ_NIx8|@II){Mzvk5GH3F{?Wkmm_v~(A zDz&HsgZ^s^!7IuiE};^fM3ZPC5^0xsEmYrDAZg6SGeXc~Xg9Cp?dp(qPn8Du>B)W-c&zR`7QmtTYo)_FS)J*t$I{>~*eOKiGKdO*~qc1&!} z+tbLs=zgK%RN>mwsvyyok7Hr{{;_KX-w}ac?;TP?>*RAhTT<8YS8FBSJyj4b+w$|h zOnP+lj^P>XG=Gn~`+W=jc^02iWaCiIXn@6ocH!A;^S{&Z$BOxT?m3o>J7h~&aQyzF zDV^X)giBn*zWA|taqM<4{KYqMzXCPmOTxIr(!o;}cU%hUQh!T3CL=5Kw}}>gI@M-& zMdH;}_KFhU9gCILKhxCYAQXjy+JwiN*FRUe;CjV+?@dL899nRUG#6zliQXu<_`+x6m(H00j}m_7m9!ZHw@w z@}kPlmrV-pSaxUFONLP6V*jzK8XE(5g*Ii9TuPn0<#oXu<1F-WcG0F4%Ow904{ZE(f?kvXuuJTWpMN^dz0@U;4eRfY z$|`z%hPiiK!}+~Un1mxcUi_C*53)z8Ms#*-qo>{Y9(&hP(_6(~<~5!78AwzDNjz7D(gUo!?c5 zM;eBkCybhfCHGDY<}IGKZ(XMBCGv*hf?wI8Eth5?9Ki6Pq?B~ELR3}H0gB* z^9y-M_|5ntWuR4Ig|W~wQsO+k10rLLrxuqCYg&L*Z#t6M3qYWRu;SRd{~^DjkSQ;< zbM;F-Je>%ucw?PM`;gQFLl7<|O!XdMrDP`&r|SQ}$?wP9-mN6(<$W{d*U=oKmC@Gd zW?R{9TcQA51JUA{un+l`3bhPE{(`LWZ>FB$H}&WPyi~EXjjRLDHV9;MCkBlMl&qxA zkeg{;PA_#tZb(V)RRh_Cl8ur*6ls9B@x`DOBpF2@a#ta8cmAtTyg1v~Zt_$Q=}*1I z6}K|ZqN<6$XLXCUn{sOA747i~5`TX|H~A(M(gawrkS4lLq^$fZxDIakQzM|3e+LaM z+Q7v7zhikTm#b)u<=1**ZL7vPJfD)W?UhSrD?QTp3Ad^l&|awWAWOA!ZFY+Y`N%$; ze93vWVq0U9;@tYu4;m4)am?K!ax?^c>SXl|YCD!gJK`!}E-0&YDgiJj4iVtp!(G&U zJr#Ne#|vB1jZZWtg0fZ;HeqEKzXp2`$x8)PLHLEd{C7l+f9=Ejr@ad+OyytpeQTcT;quQqtg+T7B z2NByRucMs28V%8WGcJAoY9tcv>D-ML0~#gJxG>V^kjI7}SNWLI)O0_#>CVP`+yb5N zruWPe1--HI6L+MS?oRrc7D-T#c&kJ@3eSXAa&jX_r0;C-6j??%{-&FOFjpuUQv|xX zeA74Vjo*GY;hUq6(q-#jAj?L6Nu|Dm1B z??(Zl;=UWigbFdg-TU4&Or2@x3d?7Ij&zX}qf-oib{O&SfZdn~QOZG^+RGa_MIu6L z6sKnx;SfO)`o^cqxzA_TYr|1Vx9IoR7v4)fm;`(mC!_if5%WxAJ^ymUuIa_yY?@nM zwX^NR0s^fl>}8H6x4ZI;6N%EJO|0S}d<@+O^0waMsFK4vg7Y|4-Apv+Z13-G>5tLm zuuxix`*=Ir{niPNBbk%xw@uLcf^Vmz=vLcrczWPCIC|emj=qfwF?XY$?0BxeeqTb- zYWHP><;Fu;g*C`msU5{ZmN;lZYfQ^sy}047<~6ID3Fl1~L1Vnl4=jf>n3E=(SrEz- zG9s@%#44H0cFmZ8gIKTG>qnoSc5*BYggnZDQ&`CRiEw`)0&gHA;sGQsMN!3Zf5d4n z5W!CFHvqsBGKEbEHGootVex*ZkEvFBp>KD&@C1uH6aoM(J#Gm8L~F2-!@;t?lk|b( z4V?s*XF)M7jJb)Z=l#RAeI#ByhAkHR;QE@(XFOlJdjk<`Z_r7vL&K#Oj;%5lZS}YP z8}jRu&c-mo1k1l~8-aQT%{WBV#^Ny;r7c+l5C zR0de{dFt2nd>{XNYGy;`+hRFMBGSP9%*@YPp?EG47&#HAP(hN*Y%8h5aDnGz6{c+U zwJm~SQ(h1+V!>lwE_Y@{wZ{OsI(1h3g2-}0fou~@mdZO@Q{TYEnAVHsQ*;D@1ZOME z4p4_%Ny|xZKT*UQO;kOCgKMdJJcj2g*S8Wt)G{q_flla!lbj~>PdNy|X9z)0aeDHv zVz8aSMUDgu2*F92A^6EVnGrubVfT7p1?^eCspI-f_&oa zxoy*Cr;tQJ{&>9a+^QW!MKxzW;h8!J=ZgoLRndt!jn2L7>uWGFGDCwlw;u$DOUBud zq%OAuu-AYYvk*Q89k|L8Tr_UmWol_NtE2nFQvl|m5;-vC_}0*0Cqm_gq>#<_L!6{q zz*h>L~V0#gAvA`1W^ErQ1&N&Eqel{C521rz0H7^o+%%myi z0!e8D4Q~vPK$S?qYVhdZhez5~i z-#T0@d&tl{9yz`YpC;>dIX?iXA1qxE;I@JJ;|s*?M0;t_>EVEW1UNe-=1{?cA>kIF z!q_wc@GKmn0LpZx)%~Z&_=^IW$^7^T%_`oF>09?gTf@gYb6_Jea=W+1XL2Ine3OOr z(;tErj*kEmEO0T8t*UE%F}RFD6TRn@FObAt(Gib*H8N-&Mgk+GLuLAPzcCqydEu!A zxh87biljJ)ejW;FTd`7bCo6g_+o<%sc(oe)uOY!Y1uk7IjST?h;7uLp*2QDV$A$oC z9;ZB4*R~sm)`R8f0!o1=Z#EH9R1nkK?>7E<#=&=JRxkf^R{tobbZg-btK+f1({tyR zIK1`Nfyj-sgmG((-5|?-gIwl)+F*GfW66(=WxLHPnc7th2G{h}_nnkW0G_>}!7ylB z5rMJ8G8}$n3@i>%iG;6_&}!Kgs!tvV(YTC;4(>7&%!gZ4aRq79j)YZQi8VW`$EP*C zbwiisF0adS_O-4*)NF-xey1DK_-X*O&ms`3fL>_o zf13ahY8D&o#oCx>qA@#~zzz)!CO1p96MpIDIS#?`jVs2#X@!8GJvy0>iq@)xeH$d zD>e>9K7nr$B*H1(6#W=jBBbGIPzC8jf7H|b3+}}qx5_&^dBt3e`EM_{4Cw^v<64V| z0_Bk#FG5}&;cXP#eRyAzY)q?piT|AWTXW= zH_u4V5qqrv9t}+}p@D2vG}6sQ;8jQ3LLF6{)0gK?+#e%jY?f%B@jZC4kInn6w0HmI zUiNnKj3rT~m%|v%9h!k1b@^DQVlTDR*=Wwn0K$CQY}qFFPa0t(s?ujxy~~uXue}Fi zUywh`&GV4M4^d*}ef2}2HZidv%m3CG8sPQcBxa$#m+|~CGy#xQAlc#kGcF4X!qWDAc9#L}E@u_TAa_$0 zb@@-o$-#m_xkgw#syNT%zj!)-rdYTStt4TO+JK-G8i*(A$G0+3zk1tN%2H^IlM{Gj zTbJwIrTz5NWU8+3pU=-;ev4DUSTQGsR?)J;U2}qMR&D`lALm1S_(h@D z#aFgR&|QU2NN}kM9sr0$Xn%xCc}ha5IaN>k^a*wfK9xO+?Gndoh&#AE57E!xF0VXtckHeRAd*A8(#jlPs(1lWE&|T zQTQQCAcEakfAxi)BG&e*C<|7#y9#zzGlt zZ@@3Xwpy>;{wC@?c0CCTa7Pm%#Y!MS(+Mjs{o5q?>pW^B;V=I>oBIrxr{7X-`~;l! zyUBYr)oTp2{yV;L>luxN<-vL#3wLDL|K&LWnv(AWZ6l9o?9FsuV;tX0gq8U_IGJnsu0`G7X6 zV-`WYx^643KxGH%f@Uq;{bP$WSo-V_MdroSRU#ZecqT-9DMb7KHV5$TJ;augF%q>8 z%FkG3*9b@uxtJ3CnLrd89tF9b+T^b96U;q2E^FUV`X$jPWO+>@Fr;7_u)JGTPR{y# zZ{W_e+Vy9-uw6c=o4PT9&=ImR8D*iw0ZHjj=?0{^us~%YV=o$hzxT1ThyI1m#-g?_ zm5c)<>PXZ3od7_=HwZrvA~NYemDpb^E#q$__a?JvS9?Pbv2g!lOz72thQlvLE1^w| zISAgsLpr9Q-4y`BLYOc}Oji>5o>0i*p>&yk5RuJ;56ltFM9C_|FJdt7RbCJ zddbBFU?z=qdRNKp6%Yq1sMpy&(evh6Pdi9|nXD zH*8@QnC?MJI=I%0BfMCjr)*wEufHzt)OeWq+JHh^M?yTozzkcbO)2L+)Y!48(9i_g z&{EOyewRtmjJG+!VoM!tfw602V7lS}JBy-F>)m%_m%|3p>uSfN<7VtN@eBU^FN?(_ zVARI!niw4+7IN$J3S~U=n@?Z&7ZQh$QeQD#Dh9I_F?+vt^kft#BM+WO`gfCG{dT-Tvu}4cyBXq zAKH_kQ9os&pJ4)S=vx8($Jxd}JjWd9^+7sI6;)8i^Jfj{-{>&V2@>c*<@pdrY^F+HOSf{_!qU#Ow-H6<^IQL<@Xwc zm!OMq+!ng|s)w9zG1K&GUk*>>z^+QHSQ==^G$JXRHd7fiahGY?+SOiuMIJdds4HUd z{q@vqDPq+uBxJBRPhI@cEv+Lx#4Qc=wb+iwyDK^J?fSj0bD3gZ>>;9!(FB$SRBoK1 z9k{TUNlZP9>^HlU69xP`<+`t3adBHHNM@m}rFkk}DU7h>yeVTGcBJ+Sr4d_YlwT7g z6GT;J(EjV-CX;Hi_4a*4#O*pEy%^3MrOU(3j~o5WH9QWdOBB>`jvo}MF=z`#Pf6g} zQ051OP-yQ7mZ}D4W*kl=aXJv5TI<22;DTlL_pIr&E-*Ib5*DA=aPkl47jvS2**_bt zc^hBbcZt8IV?=RY{q*)3J(IeQl$9`~$oPohPVDf1 zCm6(;k75yL|H1tGqX-S#Y+}%0qQPCewW8+fvscL7>w*5SZrYy!{2MLaL=h}v{(8%4 zV5?hKOPyq+1Pj5yDwSm=%!S5tf3fB|c)OQ>I>AT$+lnKWAweAm>nlG0%UJ-^>CH~~ zGA-1SkremJ_M&kLm<`1qzPwd?hwQ9IMC_wC&Ad%g_u;a!xTgR3Y;l~E9nkI!)$nrB zmPj?RgY{se2EB#|@ia?-si16GzYV*qqgtT`AAlLihg&vK@*M0&bb+)gR$^W8gkkNL`d))a)=ketpPLNTt-k}nf-!yfHwLz_#i$2xU2w>eik1*q zt^Wyne`CnWupl(CBX0QXs9DY$`Bt!AcA{~l$7wfq$!=8QqZyqwrw^<1Aqfl7`io1G z^zU1RE4oSGSzUL3)j=3rj6EKzthq330FyX5Nob)9N!NU&uI-x!Hv#x1+-b}qCn#2(h@}%tv^`=EQfwBo;3Dg)wXxvucCT%Fl>W|MwlI~M+Roq>0km@E+n5lj2*IwbS8d8~MEIH>x4>TxH zenGARGxLE^8PP&a4e8ESM7>I)Dvx38&#@?O^xui!$}_uHS$a#!f#(4S&&V>v!;qf# z*Q9ihnF`(!yVTNUoR1IX`hSR|s1p+RHac6_10rGsJj%D~aRqA3o~Pa|2>fc7nZ=z| zVdZ_ByE2;z|nli($ah{%W%Hq`_6IJfZfLDP`AOLUCg%M}ryl{R?L?(ue6b@uq_S`6zNo^4X_bP&(Ejzf;6Fw3lS>^ZyoD<8O` zp1J768#}&!zi@ex1PWhRUKm=uT2@TDe)dYOWVTOu6jw38dyN4nVCMb_(j&0gI!t3^ zgC;RKx7m)xI$NQp)6D11*nGc2VCniQ%Oi_}+>!p7IA5B1q#9A%&}QOgQwbNE)0~Va zEWvXzVmjVSq--dq%Ibs&QYhqg$CFYTj{8LlC%U&UF@XH5kl&Kb0Fm7&2Ef=L8z2@{ z{G{$eX#EdRTe)UdR5Kx(+0qbj-MJ!HxG>>Mi91rh^OHWr|HQ~J?oiC=)n$2YV#$~W zDQpMYBf~-xE~=xp#qT}K$BlOQVms9YH3x#y#qrY7H_1ei_POBe?4=)hKS~C61YsNS zjn6g<&ih;VD>(%%n9PD>M+e#H$OEfS$GnUmupR0|X?R}{b`gJFBXBxwjBU8}hE4s9 zt$%s#bv_-Q4YpLI9@TR=6FPLBDg#6 zj433u*%P0qFXj4qb>*P{V;wC|1VU)?5@9VPu7xa;S9YkbhHAs=v2A@-+Qcn+jb4r) zJ8-5rjFpO0Scleh$T!T9((Cy4_DVw_CL1g#R(VXPhJI^hBALFBmcRk~eyz*H29J@Fa&0|WSwU>-6^p*rl zyTfqEQ@x1i^#5(y{1OSNcvq`K!O@eBuSfR6ICFHl)rw>;S9-3k>?W0Jx|QnH>Uh z7uPT_oG7DS@}yQq zND9j0^cO}qap0A|Dcd>^U+yGZDVkvWw1`96YbL%pP2*wHVNT=w$W6|e^GDLrd^QcU z^Y&N2MElA}Cl$S%U%042l)q`tb=A`y%_C-(&OGLNWLMou<2#e1Ro8{_JZoC&;WpD zXgibsj{xDe*7P}61QMr(Udminr^tL#j5_Lq0mm_k^rXPX)66UF`wRxK5zoIT``x6P^+C7 z0EDhW)S7lS00e-gerZO7b2GXL@mqEPAdy^xX0%|-t;O3MN(^AZNg=x5Ky>f?C*A*u z8rrV~QN(4SgtEjw3Q)b@zIk-7rZ$oji?L~3btLR*S)4UDzw+lpKF*{aci6V1&B3OKax-QWv#$HSAI!HcGc41 zv1iF~wczIx8*V--tnMeCZ%vTkvUSbVmIp7K%ZzhL41p!DS9v3Vp`tYW(0wdO0ORa+ zQiG2oe8%}r=MVtAjUL|g_64ALu{;hYx(dJ@i2K1fta#wU+PXM0Sm3`#1`U|aL$3L4 z_4*5tNsc3Aj0KRnFke8GhAR%0stiIU(}qm%Vro5gc>NBJoA)SJla=bn;IMAV1`E^RlI*K1Vm#$++aGX<-z~}fV_g|{&+7R^#$oH(*{rW^=2ME6u z@#Uf#wJUItfP|GuFbW|0I{8rb%Y2Z<7%|P%M`LJ=xGvRy0)XYMFb}h`7l0@T8H0pf zaXP-JoPaH$3I?42^tqsH;Gc+`IAlZr=5(c{Fzx&`=Raru=R16DxbbD0MTdjP&-=PM zjPQlS)VTVq1?}oH%k=UQA`V(}oYf6t{8{HJzD|tlUxjF!kn(sI_ueU&#e5k1ZD?81 z^(2+zQjzhzIe)XyzC+?JiP50LmcRRTdv^l0(#^yPm0mkYmZR)p;_3i9+KV{t!;6ni zh@?&BpE|-d*1j2Os3nm{N0Dwm)7ZMV+CEtSq(Iu)X=#0te8j^!2MP6`W91@GeL>EW zLZfIH;zpVIyK&wf^_|4C9mz2ktK3Ubi)P|o(%lNC$$q#z)r!QDZ6WUUB43K@2QxTD zv~BK+@6Ll) zBUj&F{R9Xut;Seh{7#w{k}X9=i&Etja=S$#W}Sc)kLg0p`p=dEti*Ew=nht&Kajz@ zWeDmZt|sZf?00iC2!|=uGQ|Sxozsp8^%a45APrs&W2YE7xQ3tc!#Z6e^D+Dp5~_kc zX}{JiZaM{@I9PJ$s-ie2S|<#TM%dkJSl(UpQq^_QK~T7fc}!f5C)En_ zTtdUhYlwkN#n)&#W`O(baiS*RD7iU$9gHw~-hJ=x{`ev$ zI;y98su)7|W3g|NdhzB7rY===Q~{rsTS_&y*%M9Cv$}ZwrjpI?`~9`SSDShiz;W zP)@6GYzF~7M+9ltA$#l?5q^V;fSB~~S{Eu-xsj27>ViE9H#EHJG15pPl8?*qEpfZ# zQYJk_+u{aE!AZ(`lJ3#y8PH$JFxvNK;4J{T4;I6v0Xi(?Ah7DeV&jz4SHR8!8GB27 z9I+&oI!>Q6=jIc29magin_GaL#Hgf+=m=*dAf2SLu_K4lpTGFvwuL=cdxiNcv;cgu zbpDr`zGF^BuQt|Tnv}b}J{qIw>CXm1IQc$)Px^%H6zajGPcUW_ajqJW;R3J%S&05% z$5HIGha()-`&DwzAcx8mIpZ1w*=~sUt6Ef3Ai>T>+XO5Z7$e>`tG}Fe&nHG3)~X~D z$IQ4-s&VOV^RFmkcoZO@0ohrpvlQY83xeKs!2no4x!j}`p35<3gok>J@|uT6-U!s8 zPJAfn<)O*xFg?9xpW4EaE{$f5iSinu4fz@4p|iPxb{q#Tz>Uct(*dq4HCO^RBgP-J zTC_p40l}^`JpAYYJhUu5t}k1FEOTnM>B_KKO!qYj63RuoAN>aE~zn6*1|_$;!)J%vS`Y90qD= z`3NxhUB?X-61_xI3PHV4gH?yZ2}JjT$`TD3>;Q!_eaBL2AQs(ngUWvlm(4owuhkMh4CJXxdxZ%fuw-6D+MaqaG|Qm zm}pvrDzu+U;&@rwP&4Ql@J-^=s>ohapsI5Ra;svs;8{o93K8QRMt zFSQju%YAKxODlPjHuZwV`o^4Gd-`?T>Qi1XQJrLFr&pEC*YxCI=nPi3It^sc+I7Cb zftO@j=8HR@{guRQ3C5jYvTBK%usT2If=N1R16>f?Y9^u@(@0+gCZ*XvDls8|!Apr8 z_Q#D&JCq`Now}l>KjW{#VkgYS%rN_ukOF_rC1{mnyO4+!l9VDOOl94qe8T=Qvav8o zeUg!|y#<%E&OKy+KdrkHev`*OMlz%Gs<hg zzE|XuE4O?0)>FINOM%QJeimf9+0w5lNMr%;2`09U8W&c^3kYpr=Bqf0S)_@q$Sn+wWjEtwwBS@Jjp{L^k!-*Q# zT$|0;t815SoC!iX*A5q;Gn5tP>^|Pp!=8%NhL<+2o{50M9XAJOdQe`O0!DaLoH@C7 zEEFw%L1COHDZG?fXLdYUMU#5l2Vxm>jboO_uhPv^R;_!dw-XB1Sx|Tq>PIHnAevykOK7Pl&Fkw10ca`0MH<&2JLg~+p%ck(BP*NG@}=RHg%TV z^Iyezt94$zV)SmyYV_l1 zM_sl2@@g{TB{qm9QJObqh7tt7*Cbx#ZjAu+d&~FF3K3{!$p@5-P6r+8S*GoWeAKH9 zTQG{Q4%T6Ngse{uIMFSGex|Er7cXb`Q+6B~EsQg5rQPxso>F-$1oIDjKSKxX=aXd$ z0LQSf$6Cj53gR4N7jN1uTLN+KACa5lJaD({I1b>?4?PdKnlyb#a!H*FshaPje}ECO zfYW#%m;yyznL)$;$GR5JQwXaTAGBi&zrg3@{RxM)z?P#N$!%_+DXuw5#}>F0fCw}& z0+vA98~+dOfrBXlZUA3EHU!$J0j(mXjN%c2mQMp})x~u9_h^m%0X^MdUvGf{5F@C$ znqA+6B2j<1p%l5XcP`RJXV*1LLSu~D%^gSdcs>O2l5$&~TU@stFbe{^4M~bE8%TBc zsQ44UuqVSE+m1=SiD(yoKy{Ed#>rX9@(q6mAFV zvi7p2qwS$M{{cU3TJ$M0aKSfB9|Est-ls!daxcYl<0KXgv|--;*&n#Y}u3JVpcXQ8fEsi9|^KSc(G3eZJ8H=yafaQ^&eukSCD( zp&)%GotVv_!l0ewXDmH$23&r`5RIu6hDMNcGFeo|%wvz>?z9}m%uN#W-E5kOh(cbk z@)f^5q*uksLlIKKEl3)j_PjOH!ha%`Qh*ov zTRFsqC9*{P(8=!AE|x!jz1C`#hSI|kLWgg}z%@iYj|Gl>anP(Q{d8kUg!lt)%ftxE z*X_|nv4kXlDz?4j$<^dy+nW9w^}s0qDN`;G|4F+@G+Y=teUIf`&Nz8{{abAB!Y$Vp z4VTH)8yn_lJyak)<}I`CJv(Cyy&JXY3WJAGtBkUYhE8~%N7VRAFu@k7*)R5Ga8vNu zv5NhlKk4uxOgDS-cdAHh*%&`6P38TVL#D~%2DqK{n^j9vE+Suq)Id7q@WRo#gIRiZ z_25Hox8^_{+iKZ)7sf|)y@G;G_m_s_^8F$QMB4IhI}PwOFSOkez4dqVBLqpJyMq;B zpcMgLAbkKKK&tyQqyD3`e=q+K6-Rj5gt?Ufc!D55O7|in=4;1Vow9LPGqjafZ&d0} zEixy4z%?XxL?A0slTOICLhz|r(5646vWT+&BsOI9Ezz}52vNJL00N54uEr)n+fcd+ z-F}ryBiQ;xzdl-QH_}3gYYpEiC%JiW?!Yz&DKcr)D>-tIV@z#rKAeXG>bOIEP|koi ziwzM$Zf}HniDMXtmOcY!68H?e!=7!SwNs`fzup*EK!6s5vT@9t%!D}|2jRCt`C;!F z>%31zYzRACO{(gFh7%Mm(<8lY7(^6^S2zucMC1ZvcHNF8;*$r@vmNVH0m$to0rv(q z9mM0XHuQhwOZ^8U8~d!MBEV9mxN~y0O%MGuY{t}f}R71T#H=sq_w5pZyqUq!es&}Iw^xgSsBh0hQ52_e}8Wh+Ixk}hg7*~!l#$^5k1-&O#{Qr==_F#q(tE2}@dA=(*C;W!nI@C_`|oT*K^MxlH}>k;N>G z*ouDUi`D@3GE0DVw=Q)=L2GxYiBAFo?oCpyIoSDA9fKK)S^>ucn?G$ZNQ`@sgM|W`py`bz;aX5@fou@4Jh!1 zD>&LPu-aXAJ9A5bB(LAf!Qdz=RZRkrfIL@Wp+_gKPT&@jGOCWa+Vb|sYNU&aSLeba zZ{isJ8v;S~58fejXTPXqS|9@bEkzORI|dzu`DDj-If@M;iybRj%UXpiKt4~D``M;| zJ7m+vu;?=qIYlFoVu28evDEvC5F+@8DJ>%QUV;{tON{5lt2uq9%8Mo4$MNewJrZ57 zp0haY=Nwk1)DUFHN&{oMW{Qx7!v!?949Z+E`P4kFzH2ZS9af`I+ud7pi{}9}QGo+7 zh@T&Rr)b8HiCqoK3M!H@5k@2N5+la|5Tkh9EH_wd+!P8M)#}F% zkC>+T*Et9VIJxs8cup=vP8EL(%O=9bz2)gT;Y?4=RRBLhkfM2k)((JKk=(tQe{Wd= z+5cDx7YG{)C`3801PpLg2O#YB000+ETgh4<9P!a-p>YJf=fBT(~RTU~r_9H=QA zexk^){U}?QhfY^w>qtW^NDhi`^yuCs66-1U`EU;u-2<0(x^@G_pxs8gXwS?25$rVt z8KY;;iUiS)l?3Fe+|bT1+RQHvR6$-=uqdaY0`Nm10sI3&t*Qg&o>u&;y9935%LtS9 zfCg!hZU5~(r@@i8{uWPEh0`}e$^?AG$j+T5J)8~AB()mC&DpA0>89 zjp_kyILZuxcKmk1wsFvUP%tWtazK-5aIn5*xogw__$_HVC(>IVdB8=$AI@6JIFZaV z36M+dKaz?5cQR;SabU2*^wXtX+{_@+)Z~NV-qh*vxSW>u&Jr^!bh(JOJcy4bf-Tw6 zm^VF(J#UNzFv49MylkT3 zNog+VHR^>0559dEzkCA`xG@pemXZAOt$;&geB& zM;Jy_J}5gnD4w3Y$w-jx&G1-X!xgR=ROQd|+m5R3Sp%R|Y!iHXiN)fjCsL8B;-^!e z$W>V!FA)HNKo7fwoCA%Wc%C||AD$93E)lprO^beo^iOC;uoFBpy)b%`*yuWh{q+% zyjg>SlDSJdmZa6)Rlm|kGjY5&@ErtOgjk0XaV=NdQD+sEI!KU%gp2{x`c za{b>p4-hYO__`Su)nZocW2Bq9(ufB{VXJ<#Z5j!XoJRL>kAlGOkmIY0cza&#yHUtr z=#M%e#RF$q3e11@Ok&uzQ849|TkwBpA@PRuSZdB4&?VC~p$H(U_??Q@}=( z3DpluUKU$F871b}7O8Susy!%vp)8o_zSHIV7C7;$VwPcK_8PgAQy?8C;UR+sG)&hq zDxb(eXcwBl(iM4lwhB4D<3gSYm>;%it$qzGg_ww*OdJB1gc#Gj(Q$<$Gfhl+sx%at zVo#n^8;Gz$LtbXq>eQ9evj6--o}M^PU3Eg34qj+qubf*40DDTalkNGwtza1-z&66k z*_ngbTsO&|QvqXr2qml%Ttp4z&`W@gKZZc-UWFaeo~LPA)7~h-SKewaSt7?}s%^pf zIXI@F06pIBHl)9;B3SeBhUa%E%dyf(%Y&RzVBo zv2{ndJ14Ja0LtxhYd)38d8qz$7wk+cs+>1Y!8Vfz6>@pV0qXpPV&=Y$M&#_NhK4u} z*sL&fw_yN$s~$s2+$z;ILrOmpy16Q+yv;ym8z&R;e`a!ct>qeI0r+`FPWN;xtv#OAnp z5DZ`=gs&KiYro=DfAy`2*6oI-(p0E+V>f;yr=Q+6b5?v9#Ja>oQ#N-eNYl`%A-8Yx z{)NM%DB_#n3HH{p>9KwHxIjB8zb7Pu(QlsGkN8Mia_uDsVb0sg&)Hvd@{?KCJP3Za z3Hp;X>EJi&6M1~eq$91}N1~{Co4U?uih$&1F)zr?o9i{&c}7*QO=keM^xX{M)IE4$ zsR-( z>#z%bG5C4rBjRovfk%7hqKzz9zBYBD8(W04vf>wP*?)lD_eIX3+aQ42O#Y`|g5heb zf7Tiz7};KnxQ)A%Vja@{@~lK@DV~fT=^BL!Ejq*dZ<7gz*NU|x6YFB(4UDGM-bIZ$ z{IX!B4WExaW?G*i$Z%!_lHUaILl5&vTM1WwPiXAMTbU#IU{Q)jIVPLxG+2MwaYLqf zSXj#4-ts+P#IfPdao)fh9L$h=YhGCIo}c%?d>>JeQiu2I>TI3MX)0`uU`IROH5Cs# z(6R_|XN(B;TGfg;bh?|2zJlUc{W^7lF2C4ql!NATZo1$1Ky1v;uo|363fCpq_3}x= z?iXwYb_vH>ELPRx3s_S<%FdAG?D05cV{lG5>TamIqeY`oVQk0!V;wq0viSo_j2{v@ zwW=@~-_c+-?%*~?MWST}1=;Jgv+4+3k4EA+;!Nq>*i?1SieZXPS+L>Wb?%#3vso8_ zy(+bme%XQ&4DC2^6a5*zEh6TEK%8pQFJYY_@s++~0ML9jzMh{)b;dSmoTz&@Q-kf8 zCw2T>Yc;zH3v6v4N&|eCW+}=>&-_YCAeSYv{aNBYdvVQEfII%3OtZ;`#3x6-ChR39 zw+~_KjY-F}%XISLlzlI8tzbrg5)Tk~S@LmnLB-ZLx5NsYNt=Ms#!XRb9CkYxrATK% zSTlHX+3Ao$|KYep-T?+a zR%3d%=&q&AfC@T&uXZ(Eb!qQ=D$cE9ofQ@ihBf!LPOUDsUwb7)RTiA<}~>Za|`lAwYA{7#S7&>OHe;9;74&I zT$963-rcIv_@{fNOe@M{oAJW4cv>0?hro{Ton{9>2TvmWJhx91+s4S_aB3iwnl2|> zuHk@mod&`Lcg1HTHj|@jzelX4Ld`kl!e9;f?51i*w-!uhX%vI)7k_JzzYt<1o!%mC zl$%~Uu3EF!QCcdMg__M8P)Rg^{{)N14QcgQjPkBH_!OOQZnb_RA!}4OJO5EY z$!j2zIPQKyRaPe^aINPPG?+_`+II2n_=2@OgA zy)3r_GSPm0<>K9N2IhXeqobVR;Crh_D>U$JV%8q=mYDo!%j8Ri#%=ypXB0QT<~H$k z$t3Y&nn&ZVMxS2@7k97|KWtKwNy0FdOXBBA=*$vbDo|D=8s6qZ7 zR_nt&_nX$ctTy9yZT2-pc%FPBb(OOBEioRv-NM5_ud%+I8mye0f(S2dODqTecZu4b z)YL`c$G2f^^aC#RArDpsOM0poi!qXT7lS?brpzu|ECIiXY=(kdyKdC;xdT4ErfQ0E ze4XFO(bi~l$~JYluQoGhs!9~|;Cj_nly+-D7xPFjEv-Krx+Ma!3$2Te1ERf92=%tm zk&w4Z2tKph7%Jp3qrK-TmeV2&t&0wEDNFf$OFuXh?^vsRx8>|wCP&ZKobMz39a7@Y zEn5x=Q{MXOq49B!2@D2>qO?;oKHlil0j@7(7MkoD6oqKzdxLv7Lt2yHCY?0Q&HD4A zGL{2O_>y2)mkHk~RK|R4;DAdeyj|gu1qRcFx!zYEE~+WGp9tT;+-L6Wlsm57cBVBi z-MgKt0Fr8-^S9Q{-onwsD9dQ2fYK-*O$33H#gYLSw=6k@d>AJtANcDnmo3Fny^ZJv zWw~}qi+(ZsNk71SX%lH4<_3>i89Iuj>99{$jGx8Z>g9v3XH5r#ciU?gFe(y+lJx3c zx=xOVLxmbz7pzCmOvA0iDL_BeLjFp@6VaaQV40)|R&AQ%=#=won9`7*zx!I&z72QB zLbEZTf}YcuZ0Us0(OgVx+b~g0vs{oigqtNjC0pTkoD>;~xC_9-Cm+SemVBzC8C~kz z2hIN?60Y%3eS1e(7|rk7NoB0DvZqpLyA?|180sANga0;gu^a62@s4E<>HZ2qQih8I zD*#c&z5|ar7UbaAo2>IhZ4@aU&35<_T>HvNzfJ2-_v}O0B$$}6XyBLmHZCEwr z=mXt4j(hhNLMN-&x;~%n%KF;N+iD=&*WWl}>fp{idpYWFbQ%pBjA#rY)54owDw_A6 z?aGUWhh!$5xIMlZa!VAk!zEV7X9(XlD;w*b!eo#jdKv^F%as%@d|5ZdkNASQ9}}2p zZWS(8^dTH?9*0K73}RvCDm*BRdBIsZ?7ofCs;n&MI9{VrLCI^*FBsLzc*$g-+4}2t ze&dr+Pc_aT{3JOk!1B9n)2il;YFDCi5kv0t`3y}RfK&>B?DXv#wT;_no#4LnhF`AE z!9;7QuOMv>>P2*<&7G;>?)AvwZuRVoC`r=IAORCqB1toPN&Lk1swCMud!3@-jP7-V zrNrmFkCsT^&+b)=j?D`6xmwIg>k|duc;$Ncgv)eZM_>@Gz34IBdVG2&uudR%x==)G z$8@zqVLD^uaqFD#=X5f%vLp)d`1fz0kwK1gA zM)1~GSC_W-GAm~+*OW_al9d`xLt|!@Udxd~10rHknD{NDRB5}?zDLKgamSl>s@vm5 zHHr#J+3i}cJwTaV(eQ43pQ16ps{ifHW4&)`;o{<4xTX~z`{CDJRgU@lP*8!R@UB1h z8GDfy=1ym*A8E|HN>%+?K3&JB!*C>Jm2NJ|v0#}|{MUBRa(VfI%#Kmc)-b{nnK$`1 z>aN1BZuEFj?6E$SAIRKEv(q(3L5`-lxubmC!rdiN1xvcCij!DDJ;0Gxln}~qDe1+IhJ?Jx?R+|9sui=gQQRjIew#>{sq*OxEK53^(Ug4JQ#<_7M!+S=Xugest^yw@5k{r^q$c zp zq3O!~#t^4@W-)#nlARj+AH?-dG*{9aCChVVsvwZH*xC zwYa+f9M{cK~6 zHpm~s%2_?E65}j*Fuz2BBTY`__8Dc}j!fXwhkQ_yt@n{| zt-7OHWCD_B(3j5{*+ZNj)rMIJQ}A_f{)A(id3KP)qPJ+qRvNfojHYRW-OS+3^P#>* z%7N%)o!2)3L@-w^p=P_Iu_4L=8y_M}Em@kAP5p^H#?xw9He$%Hu++aAve!jnZd0Xy z<>!dxdU8`hIVD_B2gz2TF@>$YWSc;#+V?|r{#q}gkaTRn&WvUuiqH2I_TjwXvK21~ zzfQ=swPC>Wu9C@YZCEh-{Y@d-eWaHG?e8`7OcitY1B(e+~{Y#uIYhFViEDncQu>|t-ORkdoT_6pNy8LcOQMfWv`mPe~? z2F%*By%XNH%Q*?rE{lmYNb~SBYQgcUeXU=oLa$V*ZJEQt6}BYp)3(Z9bF3)Ix-}X7 zcisS(ZO=Lc7Q~?9XAEmIeekl;UhW|$hFku5q+{qCl|wDQ^Iu5cN-oR1Ty#sQ$SdM? z{Q8Fv&eY^PM6p-sA~~c29kLtRy{p+8ON&g8EZWONmjMnq=43XjDZC|uVBEwU1a6s@ zj`jT7_KtIXBjAb@m$wr#)vm1Mez=X5SQQk*8MNb*VvL&Xv^#p7vfekDBEy&>UjmoM z!5mOX!ISw6qAA=bt-6`0TfS27+Oy_Pq1tDv@z07pNl z|C+b2$>ZPSn>zoF#RQG6%GVQ%F{l}&uL|7I&o7O|^P$whncGX&h02ky7U43B+ zuL5g#F)wSGprYVKqT>j<@$h12?vl6=bN2@gk8UR!HwFeXo9}|;EK+uzBN2nI~nN0dZ)EF^-p2bcod9E-frd2|Eu9_~V3scRkD>1VB)#7c4 z6}j)V)6QNZ`p>)T!gd#AV-Q*__~wGh(gq4XC0{Ol6AMZho}KftzP3Ol*2SpxH)PW3 z^PB1Enm7<38Mns8()O<+ZVBN{7eBFcE%rh1Y+Dr^uX5t!tBspJZ^UYEj00`cR}}S8$>T zNRni#B$x-6eynX(-{n2m529R)9fXbumy8GwW)}>`_W~196`{l6B&liRK-8Ki^1crI zStvAHY(DWJdOgg~HZARO92~SBS?~|}hViuF{;`P&n%wbw;o2$1@av#4lpGC>s!Bo*nrK7maZ>e|oKe{86gjziZ3S-r`p= z7b+%eUyMl-=fKg4fvrAyjUFFam`ANYE~Bs9Q>mD;#KQwFMFM8^P7DUSHY3{EKIw?= zRuuy_M{lYof8{mzn%Roi3>05D!`b((aF7pU%&iwv)!P9W+tm{q30@mvPV}RSochz* z)Zq8sshC+&PD#!kUheM}&K3Q8?33YXY#$F<&;xKk>MFvxOc^Sa7hy<^+%m73-q5do zgQIJNKolIIr1V*)v>Jc2g=LR4`{xJ}?O=l1QTcK~mu+g|ubOZa zZCWL?iq*yV-N4XmuwzIroINW{|M~${+G=->u86di6kZ%7{P!ca+1TUA-(}&D{`xF) z&>f|^S3)vNT8ZC+GPX`F2|8O%O_X~FM!WDlD82|Ht5%ja;eY-?(-^k-(3yIg zhY%dmHsJfF82H&lASDt<6l)*3#gMDV~TLEokzjU#56{$J>kPT%cS|N@J zHO!vYQFjIducy%wg!PlIfR(7qi}MSh)Y&o@Dy?Srr#4LV5D2h6n-_b&U84a%W#Pna z6B(=p^WpQ(p$Q}eK30$QM{3ngzm{r&?4$ev+`7unbH|n*+|V$Cd%AD5W%g7JtNKD_ zp&k3lvA9*)MrjkP1Q?{>qR}1Q z;5|kJ{SRaLUM#;dTvCHl_p8WXfd_cb(~Kv|;%o2ORV?=jO$@IkuqbQ!PusAlOHdSL z#QEFoKHrt218${wLbx_l)%+n=5zNUxlmzgwE3f)0e`g$QaGKr4@Af-ZkKT~K4bIHQ zAaZ=DeVuxt>}?o!FVvHrq43{v&_>S>Q;dNA&B&B_Zh|h|wrla3aK57SxMe!q%70kF zhICl5&Orrj-8g4L_vUC&{_x&+1m1xsrbU=5n@&6E2Vu!tT8|ICo>>gv2>M%>lgdM1 zoYgPZ(aUx50gAONF?khN9q|LnaJISpNJd1XRhad!HBH56fj8IRQpSV68RNGnPC?@e zzS?nq^2Rfg%f&0PL^MuLskO?_e`0=ms_foPNEmpS<`fyU47iCcaU0T8ex%dgTjSZy_(1Q!cbLjza3IH?Ud5c78@`j`Qh8Br~tTWy?6e$SWw_6t9T zSvc3Vde0~I_RfYYg_C`6bgBnhDdIz@4hz?PHh!f&int^G2?AL#@_~8KC0k-$w zzuC;u4s4+8Jhh#!?8MWxu+0tu@KU6dz!BhGMe?low%o=&?nFU{-eY5h%?6s8(G%GE_4pKkKG7=7MKHFr=yj}^u ze6hVjH0$8>S|r*}=c5>|rLus_%ge`sp1w@tlQ|Lp@$;f6JMgn#?quU~usCx=;7zHr z6=QoGCAIYL*8+)iZI;9kIc&%o84UBXQ7gHvz7=;$eI_KOWm~cIZSoiHuG#Q!N4#p? zURi4TpVrBaPfWfv^)h{~6SW1)!l8MM!2U@oh0wJdigeNC_);0f6icH#rsBXY8|ip14D$-;x|5OE=g3%iEH|6}H{`b6Q#xp~Lzi{sz_3yK93F zG8+{3ValFm`xIcs`6~)4LK`+4v_F}YjTTf1iJ_I}qPo{g9U{=31-4hWgrB+}Pety{ zGVBS4La%5`+*|=_eI!$Qz3VFDY5dj(x^^X`^O_w3;U?2UW|=Ft(Hv^SG_K`@{nI$_ z{w5V2(-sD5siQ*bmF$m#M+bLI3HIQ2joV6e1cbYr2867>-rv%IQJ!Oes&eOG2Cw%@ z$_KTsVC1Sm8?ILUMWKk@tM{KQf&TK&>4D|D$fuLCCCbUt59EDD}5$- z>iGu!HAh#cug5496@>ga=W*KPaUq>ny(@WIKKQq8DxKL>jh_XxpRk9{1q}Hp+t;}sm|a9^W&S3&5v&Od=}^u*iIICxq>xz zMWjJ=tY~C`hv1V5Z$O2TCvyc3SnBBvIv4#gDQtfVWkZ6ZBGNCmP`r$TctAy>BdJrR z%A@p-cgXJ&&$oUyQ#VG0B;tBRv77Bw-_}Bra%1#?X1-t>B$fn6m>V+Qkq?rr1 z+dYp<5^ZNPxRH9KbYe*m^JA?f*i=_SYoqDn4WFghP9+D*RgaD)yzTWozT~h6WyTF+ zx_|yAMuB5m?8SxrW%;`~sye2z=pg)O!@!8j+f=$STNDY#d)MSSb?0&SgW+G*?)|@l zHrE7nW@;MO(4Tj*OYBK&XTYnVE!5PLbD#7gN+uf0>&&&_+Y6&Iz&-HC{wGW?kF{WVw!n)G`EZ+W}!siScJXz*`remsp-<3tt@Od0eCL7Hzsr$ zxSmBSLBNsIjeWLJIBAyYRQEQ`zALX63HoD@qa4_8+*fj^Z7nHdK!C z5k7^-GO!~Lspw+{M--nv^jFCG5uay)7)F7*qI0!(gDNOS=RL>tilMC6<9cgox6{?{ z9pj9lpBWPAxEGDv!#j5ZP4BMp?EBj~71IY+v$C>xrS%q?A{s2;>6!Bg{$srm6X88y ze%7(&1fo#}-T0zYeJ*LC(-lg8ylE19ie#S29?@9q90$*je%n z%+HZ}22BfE%Wv}KeK-v3g;bdx7iF4*4Yd~*%WqX!mGD|IxspbHd8SsWLsa9xMku@= zxcX%4MnG{Lm;+DM^am<_*|p!_;kuS~lx-=~DA%670Mc(xvTozzbyv#QYMQ(Lq?vsH7RPc0no_}oyG`Wi zboa7L`o_?z7+WDOhUSvTn=MudNaRV$ACy+jI1VCEsjt%sB7PM=XC%*(%HVV3bMyf8oMK88;?|% z&T?6>#EO}j^g;veG5MwCK%W>1{?jsWL;h)k(MUs+Ca9N>FqqLw&P5Ait!y1qXq<#U zNYS1S+v&&!&5<2iz>RC9)o7rO2+>BtT0E|L6Cbh&Qjxid&$N$&xr~{zWiW}~hAF*zA7^8=ZDm*D1_F=5f@VL|f=tu0kwf@z^(o5Z=9^_dy7?G&}kf=CGp zhvrQ*qMy-M+ouXm<+p1;x&ZvW?_mwE@~S)ny_rAq1v)S- zrj-&3IYurjbi$iQk846lTjfw9M#^?qo=6+9;5n-KgM?n*lM>G-r|PJaDaH@Qal0^< z*sevnqFy)?G$D9+3J4o3n5{{@+B4(D=-{7B1i2?n)b~Z0o2?E$v`0a71SLP;+7u)F z#&3_vPZ8}r6{={y9BAG@ESr}Df}%w!&cLy4%DWpXhToD_rfErfr7lXtoj%yAW5o6N z6)E|dhi!6Oz9;g|R<_0lxu?Fs3QaN&!6Hq6XNl|I7q$LfD=phiH%0Sl%7C?Z{4?4X zr7vzGK6xo;g}2D()H}K#QXlMNlez|?TRH?ox9^G|9RrL#zDTmgwYyQ+_b(2Pk9;_p ze6rPJuq|bZJwJEat55NQShpp!@k~kJj2FwAUn$t%bvYZpKc~`5tVxIdJo>RpTHy;% zCGD({gYFN>pIxUmb>5Zs&KFL@L#9p(h6`8 zU$W2(%E=t-VV0)JShK&nIJDGOfaqrB@5+>H zt=1glwWX^*CVvi9UrGK*wzfe0<3gh|f_WUVAo*aw;=wF`Pc(^-y^8&)-|SQSmoB8A zBD*4J`S~vcJFmR}9;~g5p3&h|`D|+&6=NLfbe&1z?g$?j6EEm|Y-JcquK)&qmB^ z2Xz3bW8{`zDK%gF!R4t`n-a7V_-6n{2(ELoKV|Q;F%Oh9)af0}{0{-2@EO-wOCp(p z(BVQoX5>pTY%5AO3?@T2+*LDOi16h#*c}~M1*dz`(mG1R!D+~Z2k={RI;jn!vG04N z7M+SejT^XvbvuP?<~K7OS?O5Fa#EN-Ix2^|+&21WAG2pwV1bEe?mJeKdP)pW5M(Q| zTSEoTxtrB0HSm~kX3m7hR`uVoZP`zcmI>NIW9B!IZ9W-b>T&ZjaAN|SH-YA`d^MmPM0NZ<{)qedjtSF#8Sq4IX3O8k ztXnCahw+(bsu6FRD7ynHv(9GSkXGeIkuddo26Jlehbc_3+Lq0=byFb;oQDIX)=sHr z6fc$L#1wV%7LcqI2xPwnz;z3P2(XJ>=s>~}e#*A^M?&DAEXqG01do3efRjw1G(-@q zQ~(qNNXi~y?%UsJf5aa|)}pe0U^<3T&3PCk%PK@3gbQc@KBH7^2@+gkz(WW*I&Q5- z000Yf92VYYxnd8`=yLH-)Tyc{D79!q2^a(b5lmdB?6KfX-hzwV&))IlY%Rc2+_6Xi zObqvVs{*tqBW&geb+SxgJ}yP&IT`ipjL<8+lFeaoO46EwGXenY0Ps+dn7lz~{|Nmr z(f@t?uSQ`9TY&PE|9ox(K$&$Qa?m$WxcPs=6@!4G3RdN`8?dpzG(4#ugez;G_-1P= zB(3`!FS(_WK*;jd-;7j1dWVyg%67^sgo7t)mgGPPw2{N);obF;C!v;@A6BR%gVQ=| z?PQ*H{BChCx>)*||9t4OM!;-|R4_XFoMbYT>lWXXJ>R}=FtRP6J7s}Pg*#MPjZ(MvtD`sd`Eg~|!IjE(|IaeJhc zYY3J#I^ujXtIy9CG^){t+PmuZhs47T$c@)BiFRuopcf*&WDm0CaS#_aR+jK2VBqR-h+1d*+Q%RFf%`MA@C_(p7X3qW4-d!}LedmOH zNHR7%;1=KAVuxYK!Hq@~w>cu@2{;WLSsV+F z#0~Q10hz57nsO>Y=mtIH&Di{?Nc7=m{Y40q}`PzDC(bBW&n zGB0Kef@#8bfQ2wUy1}1|fuQ(gAiGEovF`VUN<7Ta#*7M@72Kml_~d;% zJmLmo3D(}kD$>igoCkdq06aip%j>(@kbWf0(vz1SNl3tWphSic+*<;C7$qAR!nlr3 zY7}t#V5UBJnoU%#7m>LhcLTWT03sYI0*ob!)p2(wfc$>SM;eN*GGqtg-qve*M0i zilUhB88NvAV~HA=gM?(aY$|mL@E$`f9dNZdLHOq+0SjR_{VGXoX)Mh@2pB)%xx%Y} z@D+GVD4|M`s?U1>)`J1#B2HMa6iNU%vOq`~)oD;}_)lRV!#}!%p8u!thA&LuSQVK7 z02Dvw{lTjPyaIC&ZT|FpWNxyH8B*X+Uo%0|^v3E#9Fi79k&&&=HfVC9ZC1?T&0ipT z^DmnC7d80^>!VL}Lx#1c(Fea*H`BzB~O zJixN+dqTJdfF%Iiy)dp)3Lx^CE~S{Ng+lU|T=y>qoSoo0+`Ld`>X0KzpF``lz|pPT zuI^G$!ir&357@__XVr?vux00BAZlCX0GxUUBoCdq*mVl)BrG+?Cl>NfYc1S2PiI*gC+Z4uu1UV z_mPg{LU;|qmh^`oQmr;cXuCa`Mx^s<`bwys9RvdAY>2cE@OzA?_+rrGlRw==Lu$SF zp7%8Ya8A<^Ut2wmY>gj5G9MeQiu0;WFb-_reLUKBv zhbzPh3o|km=y}|6E+gG0+uF(uv+RCBuX-W-Vw0Q47#V7GJJBZr1Hdhg`;r0%HVFdy zz;}lsi{|-9cOVl1;I55!fqF)L0MqBcJtGvqyf7eGWLyydW4$z%egao~AfJ|Tx5yGFo3DG7Gqpp$o&ov@pSvNIGVE{brWw1T2 zX235Hz&o-ct%XbvDCsN!sC^4EHZd4iE>kkBg#dUV(<#j0V@eBvu+ki=-LY8Qz{?CJ zE45ZXaP+I0Yyg9H0GC-3D0J!vm z#0v(ANB>8>|9ZQjOD90dOnW<}fCo+x)TgV2Fo0?Czc0g1FfTXECkCLSFhx6sp|ryS zL?u@H6Ex2(+90m-ko_g8EC3ia;tv1)i+|Vrp9P@kKezlzBnLQy#IX5yBICdB+nVFE_^5yJ!lsP{q|m1huvxwFF$s~%^a$d}`_W>7Ix|oxMJD|D{MaQX{GXwM|IfPo=k9{_ z|I@)m6%L?_)9C}mX4S*|tR*_LP$og>e?^7shhp1b zU73D%={h__U_#lxbY+~TO)QmF)*^qY#Qh9~NLZ{Do<<={NE}WB1pZ$J0%-1aJ=6kM z;)8F)&r00}1;j0c+U+`zg#QGz(_MMc3;OETYUQM5ag z>)NY50C5aGp`JfSNtB@dMHdL+Xq7VQ=;&|pd}mj8Svg0vn&AZ{-@C(Y&f0+A^{Va0 z4ZQXKqpdPc|I&2|wAoadPN!%#MwV=YW?VcvVN^hFN((Y@avtkRtlshXCm*gyAF+o1 zs>aQTDZedm#;Q=?fZUzcrcFHm3(kK+Br z-#31sOH&XZrgJj{(Pk-#jbA#LJ<65(zdsJH?(Wu+RzH;Fb=hh`SkXRHI~Nb9)Mvn? z^c+~amh}O!f`E`PJPb!HaO-^f^nN9v+f?+;{Yy;OT%>!blTn1#g4mmDG?P1fLDvXJxA%so z_ve}})gO7qK=t}Pk~{By(qblF5NK?-B0brUqbpy;<~S?h{s>e{PxPj%VBpJA%3)$v z`!$syg&O^%ejp!_lE@N8MTL7Oq%?Wmw=u6#IJr$v`fr^NusW>+ld;@0l5Fv#@~3H0 zC+eeasJ2sjgz7LT;Cc3GAA;WR5QC)?m{q`&bATv9{cx*!Si62lvlX3_E2NaG!E0*! z@c|+15gJddW+5bF-+iK@d!7?t*HKQZ@~>7768SA8voUx5SD@Hj2)E-K46?arLNEhP z((!ruG!2+qKZUHNfbF{Jms#0WSVCP+3Am zO=DnzzfGIq^17GIZXNUvO;~E1VH#{*P=H7`vj9^sXo-3JD7nF}(5o~*RI_;JEDUxd zd&8BI-?!A80lL{OYi^c92oH5uCZw=fRK-Q=MZEJh9eZ69{6~D}E7z>7S^g8cd*9^r{2athk)lk z<2m%V4%Y2Vdh{RUb21Sl7g{t7Xl#x?;+E}0UJVqd^qRym7UR{dPfRu;v zU2#zWq;$x-r)kEA^#aU>^*6XclrK#bLJoc*0*-?lkq?)~D48*du#z>GjlPrnA`iJR zuFC^&_RulLP^rU>%mAws!1EA5S`>U?f@>PykzR3%vbEMybbVTQn;kp*tfaI`@#;X66K~e2H#l|_+(F2MQ+Z)~hKR#+^2)+{>o2DV zryWR8D9L}NsN*Gt41j4?nR?6EFm?4J510}xY#L1p>^vXmW;1H{RHBD28c=p?)%u9|#ha$2{v~^Duvb$cJWTmp*d>m@Fh}c6Q0`m3U zrEx~Yi-w=*mP@_W_QQPF+2PWWCZ_o)oVGNz8h$p4)JF!0r{vp4&33h*60QNwyX`km zsC94+*!HxTnaH5^9nDPOWis!2<#AERofN6V{AHIq?Rw!fCB{?2`sA|m%69aFn9Hb$ z^oJ5~$PTiKDm~ew?m8l{0_DmgYm*8C!Qa|oW?@8~v9M#nTdh&Iw}_}_)idZtj?I_l zxtnUE4vj`Ax9ZH_T_y!tGizwP|Ft?K7(fbeEb()8O>z~f@oAje6K|;-fZX1s43TZ?J z4m=7pLWK8=@u_ggIN|8o$tReQ`Cw1t2}l408{T3rE%xA*w{(yMq5FXv_>+pQW7q3u zF+yUYjUd!p!1=+#QcfH?i6AFyT`(qhS9lGY_3yLgbb>C#S(~MOza3j`I^6nv&>WXY zSK1CnupcvYgcolO#7om!t%+y6n0nu3`;R zaFR9E87pzMjsbo}hKiG>Ff6CIr7gpycm|VJZFCR)a|I`L*>eBPFCW+2Q>p``g?p(ZhrbeV zwxe6LMTEC`w#$nurdNITxUw`d;tK`eQ}Qox`JtnuuULVvfH{dJ)ZoJNP?XYhl_$2C zRpr#;2I=@vSp5L-oQKIFJlVFFyaHsp+2hV)!GoV`y?an%Bt)< zPCNGeoI26J!)Z*wc;HvH`XgHj;($LMNa)y}8nR{OsUGInro&Eq^5BL;=CtWn%f^q-05A~>B4B3^M+vtbSpXGhbydmiL_zR;sRz)azx538uO~&8+oX1 zc6ZH5H`k2Wje#2`OUsRSUfh(>E)%Dj(Gfx{50`f-W$03oleoZ?cM+!0tRk0uH#D-L z*C6HZELcKcCBgZ<{I}hO3nw^17s}aLlz2zvBIEvbu%Djt^WMigJ=9{E1MI!c*EqAj zT*MEY;A!^dp3Xu{lo*Hbqfb0w_K2X5RPMdh;otrW)5exB+^W@OF@;v*vBRh$2?`4z zoVX6DH(P$Cd@<`=E(d`OE!jQ$eP!~CL&SI&^n;Q?!U-mP^!1OnS=4lnHd9Xv6fSum z|0)C1iske|e4$ROnGbP0WR+PSZq=bM;h<11Fx%n+;n)2orGiZ-cSLjb{2r-WJcxw} z9t>?;bbnrEQWf!!v$oFN{CvQRC-ylr62;&+$O`w!uC(aFEdK_hU_?kFMfmEM^ns(B z!OhbvZ3IGHfb{i?rVih8|IluCeorjQp|uyU_3nC;Z>bbfFmxrM3$X`1airO-R+nXU z6&Pn4#}GSGt*+y@>poRaXMRS@l?g>1>2+qex%+>-gzpJCbAuDfO_3 z>M7LdPAE@Zhe3UR5FF2;3i$V#bVicShV$B8U!2-Q)8}5G2M@$LzGN&}X;TR&>s8Hf zY5`i2U=Rha6;POz8ejWU!gZ7@%*}eH)bJU%X36tD#m^k3FYS`flh6-Og>6E?b>E(* z;ue9EHrkU#oWGwTSxGl6A?2>VE6H=O>8fokZ8^M;0&t#JJ%dN^U`-fe8fX9zy|=|#@`P~n|6?6S^41D@?h7Ze>-o87*j)pw9GR@y|^qdn(I>d z?|}^XRHtIiD>)Q|3x;@QlCKq)lHYzw_uz;-X=Fz{>0gFVQcsX-#u(K@&&Q=Bq;!I3 zh~K#^6fVu-x{%ng?9f(nYAKV8U10HDSaBEa~TYO-`1d$${XN0i_e; z|3~bpZP#08Q^=Mb|H_^z;(P~i0||M&KUYzH=)Y>GyF~y- zG*?KP*F|=j^-o|;kB#gT&U2&Rn*!m$Q95$bOi1##2lKQYP3_;i({2jhF%-{|Xn5DH(2 zJ@IsUveN78W*=-CTh_+-O~_J)6kq7vv!X z1>lB3>Bfe<7vQdYGm5e8VkJ~%;z>9rd-C^a`6Wpts|w`>zkd}J;x4N*bgz-)%^rBG z+AmqY^kDsIx^;vr7PAagqc4&qz0YYpu7$ge2nzKbhL{XfNQA@3+(_Pi-_O8&+D2N# z>4L&0_Kj&$;&1j9jQ{6f?hHuF&w+9ofUKs8Da`OeIwdk{Pg~DCaWbGLGP^ao;L)=_ z7WtRbz0XEC@h}m$`^Q^RS$Vvi2|Saqwli@&l=AXjqDlqhcyq1&kkV?!Cz9g25iUZ8 zwT9p7?Y%Fcx&`GenI_~(bVxz6QalSYkOcauFV4i_W?E?sM@%E3u4b}<$n*Jz^8{;h z&iWZs&sG>4~XPTB=6(D%W^yr z*EhyYk61qIRtBtKa`#nX=dEvFxKv86zPeV0)On!mG_>H&F(ygVkV)n5{72D;#?UZ? zFGve^bh;%N6J{Afl652GQr7pPn7VoecNAi-<~F#UM1!p@womMA9g6TnP)kQ4jXM_E z2k}blqoWs=%2{?@Q6olJ#}96vL^yO(7`=qq&*-?LcO{el%>KwHme*9HE3II6Ja&=) z%flnq2vByjo_Og}*3Z5TXVV_=J`!(_Z3~}Qb4MXz&z|0W6H9TZo4Ov0Ny+v|gp17J zq}Nvf5f?rT#7Bnbs2z^*F0z{uWV&^RC)NJj&euSX^R~v2qY(`Ixm_yJ<#f}rwJd+b zlm_LGK@I8tLfU9GLH@_+erSl05b10OdDLgnoGBa64H6PZY45OLitp%L(ju zkIkV%a{^`VKJJHE*Tps2j{AuzH<=!A&MFo-_|JUNLLIrkj!V)6mOV?LPvi-f3^|@3GPf#e{^H(qAWBkGyo9w7(~rV2`;G0@<(zM1P0vh zBJh%>^qt_5wiC$g6I0a}Pa$p<6N8NLLyaz9}vtV$fWbz(1ngwB(>1KkK zFhpt)tBq1+=|pD^c}d;`lw@0fj5`zlTD`SZ&>h8M=s@SOZ4)G`Ir=WWv+&h?cQr$Y zO@zX)0&QW!q_hg;VkHv|yKeiKCBv1=_zv#&WEwj*xiyrs{RoRK2M1kzTxe4AVz;Nz z*)816veaQ1uR<19h5GJM@TSJ;QS@Bb*V!e!#|{s*=-7N?tZJ(BEd20=$L>ER#))qk zFO^w}=M46K-HbZ32{+Wmd(T-?5J*<&MTIM+D*CXRS#YXHNo+R=r++&l1mUVvgz+)I(gl{`-O@YOEetH9 zqGKB=|2NK{;k8i(_7zlW_M^!c^3G-=4J#7o@ALjX8VXQ+FX$+)S6WvHt?_$6?CyF_W) z)T+SQsa~?5s%-}Izg!LK{1Wo$tc2E}@P#IeDu|JGhgBu`OkYc`YE6Tvr8RPFOik!K z!hjiI<-A(CfK;ruhBLD=f4Z~Rx;XmM1LWbLmzLKh1FNp3MA368oFpN^AF z`t*K~czh7Nn*KVB+M~{xO)KFJ5A-iaX^sFMY1b*2NquZxkA?kn({)GjnE`cesU=nD zU6k7c^gX(SrM!$ET0}t&E7YaKQumQy0TGfVzF@#bTZRYdCRNKp>$eQ`Ka{OgC}J3? z{9u*RocW^=GML`=hea}F-l5VTFTo1U3*b56nb%51$-RH2mu#&-LHBrko$+lZr9D!o z1W}*Z#TwN7fK(o6i6K|&vaGUSLWFS+o@!a$orK=79+9X#QfmkNQSIN_;2hA#w%c(+ zDc8MIC)I4iMw`ysM1tx}P2eE2_D66xGOy|aEJoIt%Rd}O>+rr-#a~6Io{g43RWI<( zT)ci2jus5sMFHY|F%ork@iM+WZVoz1bqxh0F_fMo5mzM1QC^NAP-P0gW5YSTUO~a&hQU$ul44?iY_K96(()Z$N z2xl2^X=+I=td0O6ijT($t(=O=pa>V{2&D58A$;VVY~Q{AxEvfPj*QD`qi#O7fc6_B zDt|O03igRqARt~&8zo>%u;ulcyV<|Ko9<{ODNdUEQ97;Fc+*pFcuEBpvC*?w_>&3->erc2#tc!-ePliUpUf}_V9)J;8^({j|J(Y>9RC~$1fQ!a2LIcI z{_6+I+Y`#Ap#5K#6M${4Zkhlh@oNU#09FNmeOJ2+P-X!0-W31`|MpBSl~p~kpxJ+p zyKRw|a$lrWn?upU2s9&R=tpx}F8OcR;W~sb!drA*3L9~~Hd5s1)mWj^SZ0HaeUmtI z6#N-RAL;LFD9;eeK^`cd1HP4}I2iw1QAYuHB%rx{7sxZ_0~ax+G$;Z@EA3U6(;pUz zg8{~&;7qC`+vkPKc1lx}f>98VmA zZ!3u;;?jSb!8oOvBD57PCji|-n_g=h3IXb2(R<@xE){s7nrWiDqIL0Z^2w4$TM`pk~)+Y2AuRQNeEXc4n`DJ&NE*<0d!=7Y59c8!%WrnmrpC`HR%f6 zo7)1SC5E|C5Xcb;WoK>J*L5%UshzBFg_+G4)0AJg7w~PiqfeIO%jpDL@U#BPl@QuI zReAOsle?7Qu%!b4C)Qa3I}TLri(C-gN&-m)ocLtHx<*c*w*4XQoD3=tBm>_Bmgf{e z0POb+^jT@g8USZc2;_{5uZb1G{nsBRCmoFTf5T|b^S_N)K)C;Zny9~)0H6#ORfvFy z}HBnPa4ij4*cjlA&qjG&j^&2mFe}FN(AiU(f4bBC)(LB%+H-dVzgf{J; zQ0Ap=*1C}w@NAY|n1w<2v@f`y3iCHmsQoV2o+Wu$h1ai(6bB~W*LIKX{G*`-oZYY( zXW{PXJy3@vm8!uo|8XS-8vL23?0*m(?$B*Jg=~keqe0P*21t~jU|p~ z27?lZFqKOw1-q8sWk!JgcS?z4PNH=4q>*9nSlVW(3(&D@ja~)01ByJh`ICk#vK4z1 ze1OX}iW|8(D=ZEpu$=uNlXSeKq=xQMp=__Sz0Bv229#Po;CM&X~1@->42U7sHXW%nbK8&Jx17s}NMsxfPzS%E` z)*-)JfN%LamW3aUF=gG~aCrAsMCy-3FMcmjovEk(n^g2>~^&*e_Q@i2X_iZmYT*_guUU1*H!N+P*mH?3!x7SC|h|>UY!SPw;?#r~W@E z%i8EF($aTkoJ% zykpY>j=hVg%jX9S1>yfdJ``>c3cTx&9TnuwD*|iob$|u~`w6ntnrhWvm2`GJsmxrj zCC3rfyO34x3jKI;C5#S7A=HBVE`>wH{zgj*pOWi_Or1HEi2GHwLTijkcE7v&1hst= z*BqR(TBdxvmcA0#KM8wv9&d!oY8i1D2lPs>j;vU#CriFd_(iqPBthvdSo|*BM3(%L zK@G`*X#lF*EfBv|6B{_za2D&lh=$pRiV>ey4=8Li&qvm-&y|z5ILUg5lH(F2=?9?v zBE-+XjvJ>i|;58V-3P48kuggE+&N z&hi0~Q$7!LND1Wt;yo)x!eoyLOH=Q9!>TrHL6|ZcUNGDW=N|)<`(Ur17t2qmY5vbg z7nKl6@IQUPsmy%@h65FQ=a0s8r`TuCUxzTD2`RnKm*G?)p^C+R&3SAV!sLY1?% z3)1iMohN$qU9}}R3AA>_*1s_-aqwjn6s9fq#Z$wK)VKvV&?x9oy}+$`SlFUOo~dpQ zhF+Y+($DeFdRy~_q7HNs>VJw3 zc@8i3_+adEr|`5K$e>bNTddE9vb1~Xqimx!le$xhS5HOg#Jy4WaK|`DZw3Wvn8`a?6Q7`&iRDv*<`hoKUW8JbEUJQ2pBHn zBh0LgWJDS`ob40 z8{rB^M%kwVQ*VnBPE~Izrya_yqmxaC!BQx4N3p?(tkT$=ev->eKk!aybvlSvvbteF zB%nbIN*~+HkB{HTWy7G1GKwKxgOykAwcROX4DJggK6usDDS&qZH79f=+i*;?w7n&; z`^x5_nbldFe}0y-&|>-Cf+q9tkkb%h_av>1w1k~ZC(nPl#^?oVdn1#nc+C&~*_E?6 z>)*1B6|897iJFDSv$`s(h*RL-FTNP_@hFq+Px_~}dz@?o1{}VFrSj0$58L7N%x9@X z7>+?``B#u7YDPS=jRgZ_`1xPwm8kR+Ima&Fg!(1U>|x3Zhu6vD)SL5Uv>aIdZfZqE zsiz}ae}1*zK{{`4HtvyNtcjk+Y(glVr`I%wyTMk<$01|{I4uSCEqA2C!AnOZ4_!T$fg4pGSBU+!3`@8?DxoB4e_%2 z%*;4RX18Rk+}vmQ`y`S~{4~;9C{aOQ?HLZ;pFri+RfWA)Y_lXn%jE;sFr{Qx^yu)C zRb}B%QXyJEjw|2xvB=m!DasK8lNXsNTAu}&uIuM_?n$wQ(Cvc=l_>1S?M3n$Aeq^A z@&5A*^Ob3XJt0_?=(Y%vuTGx!qU5tZsAf*qB-%a&YQRHEeuT#zJ6cbzwH_?&t(txp@Rk*&8L=#s_np&5+P5Y6r(@6@BpL{}f|DPXU0zIASh|R$X6dDISr*zmj{U z8Wk5hS3{R7ytdAa)Oh5Wos3sJ)4c>7S^oEH11;(8nIU(H@t!CNFpC)&kYIKO+J8oq zL>m0$w6^bjWb=mh14+76`hli!>@b*-6XYm?T?G1KG5&s5J3`+x3%;`ig04AZhPLs& zNC;Ln@)vg)W+uMqmPEsCpEb&|22>|HkmYQNzVDP#fYQl_LB%jjb7Iz~L_HnuYae zr{v%~R`VBgf2?;QsOy^v3#y<_9-MgC%K+|S2aMMYMJ`m24wD4jrbhg#n6O{rbAAAj z=>c75zHvIu+Ls-|?)wqr&J^<+STG$Pba;Rp>CIrmEEPWw&i6Y6?D^fSJ zWKjMBcG7MWPiMAmh{zxW)M4ojRB;Rj2wd4O4c97lB;UV|Gl%QBwVfnIG>pR!jNfz^ z0}Z^CFTk5Cyuw1xalkIx!k>NVL1I3rL8lhPW!@5a+6Xipp#B%!E_+ZWqF=|4WNDIh zTJe)ee(@dB+rsx&Hks)*f8vRW=|(((wbz07bUz&8C+8K#Ljlncltz%EPJywOD{F;t}m!)*hx+xWaO+MUdl*QI%BG4-5(AhI_ z`4ljs7f@XP-3)g46bL#4D9#JYf-AFK_`! zrMU+m@SjcJ>E?XW-nG|f-8qfs+T$-P=+!mK zTE78KZ6kRJ{r7OHCS<<<-9-(|OC&ViXgY_4TjSn(x_1k+WO$`A_Hj>_T~g9#I@#^? z@KFdG+%i`t?qPzQ+NaKq&s}G`Qx5xLN;&Z0S>{txkY8{tLTg?#-)dCTV(Er3&e*6? z99Y-<`A1h(Gja->Af=)#k0AP149vJao8!Y#MQfW%cXHl{z8|+Dsm7KKd}hu23;yk| zf1R4negI0BmW9hcau?Pq`Kel}>2f@=XNtBxIYPJlL`VkG;6cjt3h9A&2RuJ~)JDbV zSEt;8nfAlhD1F*?B(*U#tR;Km`A@S@gsm^Vznr#1iF!btZ@yt=~Ax-2W-bb6BT;yQ$l%sP?z5i742vEV_(@bez!SZ ztKyYjJi%iG9&v-$@SmJ%>?kQ4xaYBV{6v$Ws6s?EQrm}yUWRW?2kIzNgJFsaN6580 zx@tXVjuR-f5W^Xg2)L$d30Y81f`1L!ph3U4cy17>BXQu?jNQoat??gU9L1U*PZPST z6@U9>#63WKi8k`>2PqsaL{}Q4>Isrg6W3p9wcff&uP{kC4A8)&=l*4o_+4JARm?-J zUnfVWP*L+j{s7{TFg1|EU z%S+i_8A%ZLK*8izNwWQl29IlVG|{=KvF^!8fR0P-U~)|&VbpcjlwRi;xgQQ$19W`N zbNINkse^$1oS-PRiQWCSu~c~_ZQL{^Jg<&?<4Y5odTQ3_C?{!C0&%>GeEjGfl8u3) zv7w?2%0G8?t4839n0;zSZY|#YPtWp8Y+}LmLpv_9#I&F%hlCRYq;1Y#rl)nYM7~d>B;G5=B5VBvdw@k7MZR;Ty|1i?y|gr%+?7P3< zC!{E-Zq>tj_Tp_e&R*lcqQCXa{L=aI64{_3sop06Wb@3-Z?P*f4_th8j?kSUSL7Q8 znrjy`NE8m{$bJ~0Qf-@2Hn65x-xcNLeOhgUB}PCm+I2P#$abcch`KmWs$}NtDj{l& z*mnNao88VILtoCu1_cU2Dpbwf_KPJ$fE=QulzD2u8AZcc{d6@eWy*7f1PWjK2Vkm| z&*Jz>G*3xuF)#+TPuyvIP;Y(iMyk6R5DyMbh;<7d5P#o5Sp35NE^>IVz`qO;pP;@Z z0LJ3xZhz#1FL(@WP(Iz^(dk{@ZRvy;y4<)v&aU2d&$oCLCGumxh=yxjBD!tI@|;mx zJ(7t=Eb=+EB#Zq{7<*8(bpT%xu31yPT=^|#XSqF9vEq2;7=9PG_QxOc-}LxyE&fU^ z(4DqO3Pwp{Qd05*c$c#?k$K9gA4H-62NgUzGQ(Vv$ztnN(e!Q8YENzv$;edmbHX2lO+04^|&S(&}UeK z&!y8`n{!N*CLi|cS3L!&9y+J)Aw*pRpg*V?5GZ6AHgzaqjAh_^E?GH@U+a(;1_~UX z*B7m30~%zDUYSF`8MSLH(n(#ug#RMd7xKX^g^Tw2UWN|bb|sk5kbh|7ZRnkj8|_OK z^Xw`qFzAZ}Cc$kU;s8bhdJ2aaBL({?HDBEtL){%KZ>VdfQo-p9SOQ`g^fP>2#0%M_ zQl~)8MbCXbx9ptNd#hJE1;E{Yr)D&#((VwoO4ay~>d{xf^+k-Qy{+t#OBw0@@qZ84 zBCWPat<9|w#Rl|E= zl-#kXJP5X@-1W*I$c>27=CZD09aypc%@*$)rw6g+Zby~8kq7E@&`{bKNCinig7eIA zq}ofjhF?**d<}#p*HS*8kfd6iB0P8bP9KBr@!j)#5zfFC41&6X!Yt2uNH>EkqUU-k zr-&_y!RJ74`{6d_ z5uxH8pY@LTgzmW9bJXWu(g*XJ$14R3TlB%=eQ{1i(I6<&Eu9D378x$Jyz^vo=f|pB zJHRfeYO1kUG#Bt!i zhZZcEp^NM?QFCrbgQ$x_uQF0CO6g{1cL=KeMLZscnBCc+?0=JPyR*iV&(Zw%+l0b1 zO+|bc!2PlZ-n`4z-K_2rGrENW@obIF0P6XfXVksQW`rFC>(=Gq_ABG`z0$8=8cndh zHS>$;=<(t~Lg8E?w?~?ca~qRG<1g|9G><2J+3v6nhAJ;QcG6l88nnkxPBsn-j2s3)8Gcpe%cRY>{48sGFbLpfdY`Rvc zUNxN%g&q>VzCx2x7={00fA>)KF(lVKRbHzmHvpTXtzpCc3b9Zryi*IlWO$OPGYM=c z-FWx+FcmscxIPvpzSCAgiS-f`dJ>TocEV3wW>cMyPNP3AwJPM0?B1xUE444)$xzkc z0~K-)ndA)c4qSs#OAOkh6Wh`G!|U&-_de9d&zl@=m%j?;9Ej?cMi#0cv)r;RMOM<= znq6@1)9xI8P#En!0fp{@7^8FxW+z=y+Sa-;u`N6DIIgjF0MFX;k7FatD^q=Tr?A5p z6xmfO{BNNlobmeLbESqPCXHkiJvSjOZO))8sKMXj25SAkI%PP((p$dX=r&B8Chw*{?5JPI}rLLeGFxxBRq(|ZJ4_xhS7metXRfC4F|Qdk-#-Wg!cuAtmcXX;50 zJMEa=D-A3*QzRkTjk&-)=v1DGkxaOchzd#!*j3-BjwCB$SQFD*i`K~n!RP*S)SU~8 zRn~aS;bmX)Rias^FWB)8n-5gj&dA(FEEf?&oTJNtA*MF!Uzg2 zG7^TuW3kc27+D(&G9<_Mv8HZJyvV~(vV9X}`x@+_BcCw_WWpGG=@e9CYOLUF|Lxu6 z?-AdltduUHEd8oVtPr$M3fsbpry?{T{~Wf#p6&L2*k|m{s^63!P}c9^IoD^YUSUS` z@3NUSF^zu3D#DoF90sZCeTb{-rhy-o)OO}4W^|ncOpKiPD>YgWyiKb$n>&r;(fOs+ z6!==6NF@>UMj;v4P^I?#*sOt%3HCwQ!2M}BfeSYP-`c#dTW8I_2yYs+?~sOQTxR5H zAX($sXO)RtLIb>?{6@{5m^<1)UpB-SmsH%Im@gY!@*|sAB|rnjjKTE&fpLO@P)+_^ zPRY0}vQ}Zr2@kk(v>)VeeQ-gpoyobm^9GM!ZQzIvB2kfB>9SH62Ga=8ZKX_0k?c{V6gj8jG=KrM~w zlM&EqO1Wc3*dG@@=qFZ}bj3$sY9paZs1lt-94sOlhtg@tYvMZ$H z4W|Osh_gKT>z-4EtMh&>kE}rukFDZefN3yO2=gdjOk2%_`Ndr_s-TyI`n#^f6+M@a>{XY)wM z$XzT-aMpS4er=;WR;0A}A_ctIY}$3haFvC6sNB)}N3YRG?mJFF5FNs_K{(KYXJH=& zn+p3gjZOI8Z^XBWg|jWAbDOx^GX1w_gr;M-K%gBl>W^jAcVCQy4Cf zk}t;=ylS(hwrI0m=tXsg$|hH(BxKIGK53TXNGM@GWZq;AEV1!-vtkY|WM9WAHxe1I z*5n_H7hGXmNuUQeM~UhzihWJge$xeQZhE#Vpw%o&2Ow<}5DVIr6Z%MjdQ>jeL;u1i zL@2FD*#a|$L;4oAebtU<92x!!{0W2USebU|1+IiZ-i#_O8qf)k1>4t9-kV#fcd!wH z&cGOzABmq2h!u`Xa=VeNr?_hTJ3o0tVajYPAMeMokj1fo>;$%^DexaZdRYc&YA0Jo z3Nr2-iAe1;hrmP8{vdaZGakGybVd8A8=Mh37DE#zOCdg;j7lL0!wfUVI4#I86uhy| zblRd9FxMLHa{8-fT5Yw*sykRxAKg6}_V1BW8^rh85&~vHqHXWvk|R#UM{0$d?e$PQ z(*cIn!f!(XFwTuc2zeKbF1}CYiMZQzuX?+r>SA!tKDnxUw zVyw+P>BtcLW9@lb&2j#lMO^0>NgG?*{^;MUwuS0+zY>;a*sbCkK+3=hMo=g&L7WuN|L#8 zhr>>w4>mcz=CNp+VU?qVnVZrieWU#0{Z~o+<0Kkq2UUY1xL4K-Qt=P5;p$TFE@5(pIonh-51D z+ITH6m)daOi#86=XJqP^$LKu-fIi*!HlXek9hWH0Us<%D+XZ>hJJXKl5{_yMT;*ci z%LH*bDJmn)*W`a|im`pvtq6y&_MHZc3s|N$GL!$riz(8fE9edJ`OjSqEYN>Xav6 ziQq>V5#XcF5fcl8pI|K6{zLan+R~%G*NLvfUQl}0xq7)doy8SaC|xI*vgO!sgcd(g zBTTna*Vb1P;YCWVfj1DaGJHi1YaEMUr$?)hfqv%y!NFYU==*75o5UDuWkaUdnBx<) z9!nA5o|5A*MD*Pk$~?W6{Z75mJ%b+@X!Fm<4PS=Oqthdrxkp}d zNJvAHKWb;vUE-hFbEcSJ-|!mI+&k?efC6din-Mq_yV%Mf&6$!ok{*_?(nmZ8hIY>) z%N>=Zqeg1^=|Wx0;767-%)ph2&DMC18W?PtAOJdNTaKEHc0qUmr#$ogX-WJp97R&} z73<1H_^i$-fTQ%iw@^aX{XqYGUCIMLP5}kwMmeM%PHejierKxxJf<`z_%y5V@TwR* z(25Nb=7QZDg*cT;*H(^J!)O!%!CugVSP8}YQ`+dXOBNf$*YO{Fn1o9gBbmyT2cl8; znqZG)Dnea>?uA6_>5{lf!rURE#kn+50+@~vI{x{WT&MtIwaCy|F zu!H&tZwvIGvdzM+s>P8CsfBu%Q5>JBcgb(LIiNp@BH*X@8@XqbiDoSTyf;^|rQSTY zwj}r+CTB0Z24;?zg$_7)iE01(d04rBNfgHlhukdG_2P@D%H=O$E28eeLlCjew+G#8 z*=F_p>w=;HT7}vVXhOqaQTte%K_sm15ccp3tv6;=>U4M^61Z7!( z^TmrfkECOZ!Fp|A4buI(f`4V8ci`)w6;Hh|qgWm)wTdn{4)dlcmi69$N*pn*pOkb~ zzLj$3ndf~r_$15wPaC?|BN9`Ni0y-qCg}vbibY{h( z_jPl48p-rK|5*f3ICr$)LRoUU59K5YspM~w| zX4BD|T%7tw?ZPEv*-w;+%8J!A*S3ZCZ zTUE-YGYihu6J@t5J3BSX7gw(O%pJEOm#Tz%PEn!iFTvtzIYZuC!SAN0Mt44a=w-Z( zrLKJ;ssK@`$!HJY zLWc?Ax#(ubopt+0u)~gBMZuuum-y`QNUiKI07_1p86c>ZBgs28PVEFvBVh4vP zkF$J9M>J0F>y4Q72rWw!wm0C0193xbFaYw-Y(lM)n zlTMJ7hljv4Oa`25IX@sfhpqD~vsI&vPsB*cypUR*zr^y(iQ z%mACNJ$-1>f-tK<>uWJs&VI2gec@DE-YI;41moIE@)QQ(z`Nl3fp%%vLQf$Kv@iP- z!lE;e%IWf4+@*5EC({FCtknP2 z=!BE)cnbbj6)>jzD_9POtPye0sBvY1P%im|&c6WJ)I3IjLsjQk%!7{83zoWw15zM* z2sVVo(wyt9#3`mcl8QkCua*DQmuw6S6B(#jl94tZI0uihC)X%{Q(Eg|J)MB=3#~$5 zs+rQ?R6dMYqOmh&Cl*AMQ_GiPfU4<9xuM>9@V8JcO^I%D0u%ELB?z2}$)Lizp7>ww z52C1Q*$&&rg>SRY(L0T6?>*rAi^~BeEs#!5iscOE;XN37y+GL16ElB6 zd{vw}_r+QXyRZ|?>1j_uu!fO_iB0OszUa0Bs60HkW@1Vj|KO}(kGgo4B%>fuCYF?O zWV7yThDtdcju>1XWd035EnkUmLw5L+7g)j0Q3xw`ku!wDHt>e@~#K7PB zM(7q0OVhlyBuR#^%tuTVv~q451SxR|-#U|*#FQU%4{Bxb-B6R_71mlK!3YT&>4uPl z))IPgvcT)3m0#2@Vnu?@Lpg&qC8fC3J@V(n<2C7Vzwh+jN+8O?IJ?C>-CXJh#4GxOGCK?I#7{TS0}JwwnS-D2QCB49jAtbj4)SWd<0*qRlj=ppC2r;bdyAz)5K z+T=;yJ<&eawb80wIW5AaJNMxt4f&&7s)?V3#Io zjD$6VKYWnARpsTNWLBOXaEecLG*?o-|Es;XfU~mN{{NrnoSC7!dytTp7Ep1Jlu|(i z1eETQQhI2lOFD*5=>}owMoPK_2`Ncw_`g4U=6La3zwYa6uHXB+|KD%!{kZmCd+oJX z?ft|#%yh23_^JC@fk*8M#=TSP#mVDqGSsN`bDYVayuNh9y(!NZ_q~xR;gAR0t5us> z@z+$}J;?RUi8kQEg@9`DXDx1C+i@ySuO2=u8^4{#&EdS~I~O933MW%AzhH-UK>P-w z&h_PvcUd3!JK;>Pbje|6)e zOCOfI>aFnQ%DFXK#;7uTY^iDau54*C{AJO^r4oF1bXoh7bI$Lb;H;Q3`DwdGaV29rK%h+c?v~Ywdn1_hR;f zd{-JL{;cC5?-y$(R;zg6c%d~lH;+g+WL@53Ib*hXIH=|I7ROtZEb~sx2l1w?o}6d@ zu0}uRh+BR9w*3!phmUuI6K<<=xA2zQg?2VN^ID0e+rG**f5KPs-fmN5!TB`@Hh#Hw z>pM3xcFf+OVZSMZ%QtzPbDHP$g@R?LzkYk@v}3O?t`=?ShHWXcr#ad^%zO9lYwzx_ zl_Icr$pNE&et9HWmz=$>r^fMxLUr_$5$TpF8b->N1cMh_9f5WY48`<-srP? zdfDh{-WgEAdoSCjILofQTcA?zoAaLw_MA*y{I*F`GRaQ zbH|*X%t_OD(_!zFw^j}vobbfm9C(o6n}yXppGTYd&CB(#<&9o_+_&*7E-h2{;IKrW zO*#~~a9aG&TjXh6Z{wivhP7BT__IiMOZ?{-zG;)X;4Kre#2=jhqrkFH_Qyyv;cnzuU<;ypqS)k+ z@?FAurkTQbU^8v{#VxX--e=3ZbbPw)N6l;C>^U3iYH*TztGhFcGo|2`&%E4t8 zrMebjR5)yqv!3t$EXCrHr|AK=Dz5&FW2Gy5j7?YTa_&_%_*>YwEkxDkm86V~-UT z_wEhMl)aL-%GEwI+ocWmPA&OEj}2$W9a~$u!-y%-KhF|3)~RyI&OW%=KmCLWQ&X>B zva862iF4CWi(PZ~r`_)M2{_xceWesLC*JHjJw-^$6Wixh`0;t*;7?93o>1pj;Mdu9 zkN&cLm6lt&2W=f!Kk15DPg2%iH}2NPv*+Va&v5(tk#(_Jwp>)IX07+&noS2M3|Tm3_W2hpXCz-RHt`q3zkh2`l2P6EjXibXz3)#CbAm&^UU}9NG;V0K zVli6JoI0&cuOac?y1IR5@0Xh=jA`35L){sTn|haDF3MLG=ezx#0<8+qyqa;y2ceF4 z$wviiH7-8ZafiRW8C*8x_vtMbLMquv$?tva#4Z@@l)F+pU_HsL>P{|WzQmn<+AwEU zpS5B0w>i$#z43ER?o%jJ<#jjucfB$3-M8~SSrVyKN~ud{^VWTLE*<^-RCKSonlrvzI>pDCv<3ALV(2@{phpLV(sd8 zCwY~!L-wR!oayb^&8sIk(lq_uAAfi@aa)|4SrXTnGj3_(LT}Vu^V6B^bIbpHv`Mzn z^*>2cuX@PN*gfh5+-$uw>yYz1PhXEYvu53}4P&aDx;3s<+N+5?`}W@M(cX!%bbFKK z2@@_RcHT|rv$1D#ho$n{IcdWp4xzYD-cyJJ57ct>t6rV&2(9`3P}#$r#^-AXJD)hM zx)t1%H`=-(0}8qO>usBOd4AkjRcfF6K3z%A$4}xVn%u2Uk+H3posIv_xPDmzW|XeE zZExc=p9F0SF1Ti3>?v_NwL02!-;>ns`(GaS!G+WBzO^NJQ1gU60(Zw6?CF&^zMJji zthHu1&E{vm8SZqbH#)}Q2e~R;Xg#Uq`i%3i#_Pn28Dc8npHI_QI7y8t->?1w2d3eG z`NnjPjE)1t>*Tq6bXozvMqj4XzMLDIwjJ6#PvKoo_N8-nwaIpd-?*M|;I{`flDTo$I}R{>G?B9}gZhzIKNvPOg;U z_j?SBbvyc1yLBpH{vYsDr082yvGNF34$}9!b7b^vjxl50#n3C+dtJ=4>hj#RPM(>g zYTntkC;HIqxtr$sp}?rr-G;o3IX(I7Z;rXL=tlBXzm6XFu>XPL6SD3+|8Pdz+|T2^ zDEp!FT9^7CUTv7Fa~4rrIMMKHZJKU~8&-BruQ!5{#EI@WgF@q&n~+~Z z|H#P#A%+`wT3yk=^Uk+D*qIseYr$`R&CJ_o>3JvN$c8b!_e*?LG{f4i72R+8&vD}> zxc78uw5k>6XW8E5&8!1kJz8Drz%SpQD3`QJ(7m+-vfP>;cgVhi2gB+*UnKv&``$-C zW_nm5u-|73PF+}cyTq*KXJ$IF8@J1{e1FcNAsX-ko47zg;lA<&xn+-{vi!`P<$@GJiJi zQE;K%x!h)77tJ~|rQ@uBx~|~#I0WMTu)qTfL+#LaBEs@pb%ultGvUi!W~T&_U5f3A z>o`tWvGMQwzUEz{M&w1G-%vGhOV~JP;PlZc(;i$T90ggMVU zPQu48`c_*N>U8eSFSBK-wlp7n7HdIZmDY~;*ZtnchU@h-8eUtifNF!voinL)0>f8F zjQ!Jp>pqActzDr=cGh5WIl9>7kGO;m&?Pk9C!LR_?ouWCud6D1Mh^I3__0vOo1(yx zf&1$<=vgz~;2Uw@yK%Pqs*7Kg%fF-O;;;|a#SKoLb40~b30KwZxhzM&fn_@9Xxd`L z@eZGsNnU8n4F0z0@>5@A9P{)>qLG)LZLg9!WLNtUm-EHD-6>&N=a)H&iw^ws(4(MV zZoi(T>x*-P=d}4aZ>b9H?^I6vcGv4y@9ipnbmGy|ONV4jQmf;x#nY}0s9tqj$nFx+ zpUghH==)uj&z2v2F;@CDjRRBFbjybabSSv?{DrM=%w8B=b@|Az@5Pz*^_&(-+{~$7 z7GHQGPRo>6-8<3aeSZD!<6nF4@Axd?>%E*4%~Fqh@afUF-L;30)hXHR(wGDB+XY#ygKRkMW zC*XtR(M^RYpAr9$Q6}yqwY?+040qRFDYMvl*z7=zj$|gWJGt5o{Sv?IVF4eeeO4m= z#<5Odrw^aT4-d%L^v2Q@dFFN7JgZ3Uge5{JCAeQHN4~QM-d?kM^sL%hm#%y>Ywb$U z`aVy;D`&332hXeyKKLReX|oNjQ(QlMGIi66-c);XoX#}y+>?XH-!0Vm+ma9NH-Aw6 zgE0@vgqB-bcF&OA>E6$}drRg6AI85?dRX&oTLz4({$rZd8M^)igWGy8_D zn>##a$Ib`mR7zVjU+a813a%(VJ4?}qN8-9W<22fFykq6tvquFyi1qdtpY$DBX3?V4 zYx-B1+UBEX(WWd-QFv&Mv{e(82z~SDTrPC$jyN-WbqOyV<9zfgAweOjlCLbcX8(~7M=qM@I9Wp6YXyP>XCyy1 ztiQ+Oymnx0=(m+tx`~oDk5#3#H-FIilJ9K}E;y`Iu~vU*!yhu;agprT>R`_o*kdlS z*b*z85sz^vQ?2;U%1Tb32?s)h)ABsYd2vI=7eRBkr1~!W z%iYDBwocfr=;iupzg?HV^UYy(y%pQPzq4_oVV)GNnj8*wj^3ZvGHiJHzFkUp+8tV{ zN6%`RJI$>hf6bxt^J8_((kWbKm%yUPoc)gt_gv&q5yk8VG5g1bamM%-N1VX7-D`2n zE}EJ=M{TFz>g3zm}!P)OCrF;8_49kk|pH?X7qdY$}j8|vU$gpP94mCUB z{Up|td5hkP-)vIS-mUf@Yf<{%`eD^F??3f4c6j#L(biNg+`q&5RZ|LvW{qApVd%{0 zA5{&1f8N9sr{x{+ow}tlJlDeBL#uTt@^j06{f?$=H#BFPWo0&}X*Rjh({wePN2p zhxHc!lme=Do$nsVHm0RwluQR=Lj$9cZcil7gaq8ZI8IGi!7%kwPx!KD;-w<=d z*x1h=RNVGrb?jNW>JFN{YH@h<)o(0+V{X~C&9l}?x3uEVbL*7vT-)RAf9Xt?(xbB+ z?RaKT_3l4?GCFIFns280Xh-Edr*5u(bf$UghqXO>8w|Ub_hgf-duxX!I-Tg$w(#4@ z0|NHBT^@H`wsK;~lF+P$Z(fe?J}f!9-IlXtxN-MPbt~U)5b6}(>MS&w{ztqI=(m=W zudbDbIW>|FbiD6ob@H7j_;K9HP5*Jhinx#m)%q}aa<4f~j7pO`$6b7_b-#C(g~$Hk z^HT}Z#VFakY{l1S?)V{EK;yITj$d6p{7#vn57VAW-)YV#rB0`Occ)vqz*{BfJe%>+ z&ROx_yIP{zu1m#+2LF^j#n#5_CNyoG;I(VdlizrlYVeOGjwjeU>QbGNjngIXIbmqM zc9Tc#>XV}2{C0e&Y4m_PaZc7cxUs0`=%x2Jr&#AX{cL(Xx9XM}lNyCyi~V);+^xRr z5<4XIrH=|%NN_84_BIpuB|g@@YKlXPXEzJ&d~GFv{$*cdr*N|lanB#;eN4*qb?)@% zA3~N6uNLzAqHN(DFpLrvf<@D>9Ob@r9OobbiM-V53Vy$glcKg$qEYaJW^0^G<%56N z)_eD}M%iLD{CUt@C+?Tq*doZ#lDtK!fCTwZCJA?3*WpCu0(|ZF-uU)n#7^fI zK4&!E#R_+;;1s`exoP=`+cn>`=(Y2enXz(WXw26e2OUUO?Wa&FeaDGi=PM^e=s2&Z z3%7*r2M+5|Z_dE^+1EO5Pw%YP)9*@hW^vZqmwY;Wi~gg|{5funNZHi!F{3$Vm@DY- z#JtCYB@|eMI}J17*6?}pKP$GGkdX7qS<8B_T=ICv_2%F)IQC+vZ^|Bp+qKAWY;VEN zbf;D9qhDc zM995#kB2qc@b%sVYnoSUmNj$otNUUvFOuu{@(zuc#9Em1?%kE!YBx+VIw0`#{8|6ypi%SlSak1@Pww9Kbp)NdX< zBGd^QeYm!?T}CAG_C^iGLYVX-2im)7~kQU~RJWH;cqr@{OriphCV9A19hL`_b+V$$E|*Uc6_>*4$MSdXqeQzu|y4 zIvqb&ylS`F+_a2XdU5H1b0@Zxc@+QK*WQfXy2QyYg{}>JElKY|?sq2=Ob9F2inpld zr3f}BZPBV#2ZycGqC?~Q&{uxER~@(cPRAvHuW*0gVc>UzjuY~#>_4|XjN>nOT#<{Ou<~o7VOJ@muGQ){V)Wz%c&fI2jw%Z`T%@xhj8oiicbcL^O zQNKwY#)4ba_xJs6$4PS0sj}6~%-OhpbAlW3)1gUy{=LFKem2RBzSXf*NN8nYVlqpb}oMYi05`brK#7dd7GB?nt#Q5`X4{>Ti0pZ z8mf+vxNf^P5%CWi;5q^?yW6%ixuGc;0v$28H7+Y>`biEX`xNqkKTz}wX8g?KC9;8M z94F`)e}?8DzcOSGcW|$R%8nDW0>?sWqFIbTO~9R9TwaOBdjpfQ@<~qy-YKQQ;$)bV zfHh+|PQy9%ezPMsdqL|_8-{XOF*HEbSD#Rsr2h~VL(PzxME{j>Rifm6H=mAg{{I{Q zd*c%=GXB5Ik8k6XguuvgU%u5RkG@rkPafA@UfzP7FNcjw8r zepJV8_D41EQMK>CeZDQe{`)Md{@T`ys{a4zd^V+TU;ek9C$_l#x981fzb|jLIQ*YJ z{{Q#$(Dt6*mS_L-%$IlDy#I9GZT8vjm;TfC|KGm8ZC~2*``;cvoBuZdeEZZU_jix~ zZ(rAKbzzIEFK$siA8dBm&Sl%U%|6@uK0j^mHU0DVug1@|zHMFGxW8StI=0yp)p*+S zWwXz=zW;UDCjWPj+v>nSKel}O`{%3AzpBR;=cta`;u_UD^Y_=LFRK3h>3ov#Kjpy| z2mgH9c{5aU$y_Q>hsrc>;K*Hu;u6P z9=G{t+Yi2T&}OHt?rrmJb@g}ax7C?#-2b}Zi`$>pACvwiIj%GQdi>Y(AGg^X)qMQb z^=$dI)uGMasQPQ$C$@2$eZPwrN&lbn?&JIC*QVcQpKbhi_EB%P^=#v|eE6?t+uycv zn}4?YvyI!<_s^FvkG443>fS$2Hb4FCu;syKpKU!`Tx|Z?^!xj7(`U=0ZM}b2-fVI4 z&yy_={&BF$+t#`mK+4R}w`>$uqS5(Js_SmiqHh*pV z%BKJC9=F+Vi;t~7ZR0lm{^x=%-?sH^@r-J|Z0q~ix6OZ>y}onOmPeZ&o87j!+w|M) zv&G$JpKZQ>+->&S#%=!C=G(??{@U{4@2{=S{N-)>ZTf8SiR!p*eVhGJUEikv-yKie zdNzM-@v_yUO~1dtzH`a{{Pvf#)w#cXRPD6I!FG=P)i~JfwfS$e$EM#l?jK*9U~%cpJJcTV}&ku7dfwab4! zo1Ia$$A3MW{kHMHs?X-1Z9Ut*w$-t1zHR-ej@#cM8OEzh>~ZSk_{x6SvjGn+nJ9oW{3 z>U>+gZTYgx+ZH$f=PjGOZ9SX4Hvet&eR=S= z+cwWOZu8qV-?qP^>UUJ*ZaeS%<7tz(`D3%!rr#D%|9xUx&z3)%KmPHt>9g5mTQ92d zvBl3;@3#5=@$k=wZNAMvTl{SEZTX4ne4Bm#@vz0)Kb|)IHveq#x6SvRv$ie!YKn||B4|30y;=kK3Q-nPDN+?G#UzHIhI zb-qo%%|HKm+T?BP{oVCsi&s?b|Euw^t!K0MPvgm)7IMJ2!0O{`=JCm(AX& zj{j-g{)K;EW1Ii4#@(jJmKXnev&Ge>&oN+<4QH`6;Pg{N2?6c{Qs{OY4 zw(+RiXVY&Rx7CL&{!!I$o9};K{i*z4IA{I$>!0fV7rqZ~i=+Q~QO&#UoVVr8wr`>u z58L`S|NrjssKzg<@v+s5Eq+m5-*^3p>N>VK+WfTDp>4kZzOuYpTB=Ld4K&je{AEn`mn{*-yYk3vaR>0O?#8M}K=KEq@Qk`5Aou z3I@<_ABiuZhrpMh8|V!5cY3}8Ex{zv1L*Jk2pSV#e+Ni^6G`Cj+&Zg(bn5R-Nsd3y z>PWXwW(sZovgU7kBqJTK>KR2}_G_LX9X|N<41p&-KABhLWScM)`25g3pAOMi^+@K= z^nAm3S0G#c_4w8r$e8qKT)O0sZ#~~yqv82ve0n4+y+U^&8O2|Eee-;4_k<_8#XvIZ zD+ZF)deRkXPYe~S>cOYG5A7Y4N-pSBpd2ZN2Z3@dA0;at%8~TQe)Y#hQrWI~%DbR( z)r98z{PFqhqnh9M6&dvf-?*syp+L3gKjxDYU-7ZY^g>4Vyc&Pa^+9%y1M)@wM#js? zYYvFE7OL2&FFEa#QD6jrAoU&SA)s1c4HVbG{Ou_nCj6Z$lbfN?VW2BYrU#Raz6O82|_t{VnYvsk-%32I^z!m$zz)farOe$wfyz@sCpg` zLXio8?uuv|8DFf{!;?&JWa2<~ydooAlG_Aib0{)#q4HPfg>PIk62A^D9}C^be8$zE!*1x`SJ?S`<(taK;zP*b3(Q#SDbA|pX?N0dt7U%cIAt7 z3Cd*`ApJfceN;Nt9s;zteKJ0(G3_hql`hGPitn4Nwqo&We8ls|ze`4WlfPQu2miHH z7dCtTT{5rQ;ISxDsT^uQ+J)+u{4ca$T!7To6(tgo7A^pQ5 zp}Dd{=O;P8_yl?&vadZMAAR~YPkUT`$mdu0ljLNhZ;t9`C{Ug><{Ouc=HXM|GU#eB z14woZ(7B*hrK8@6Ae3OjqlMM$z7*O0K(-!Fdb~KQT zeA*1g0-ucHExyKOmrq9Z<&%-0;>#|d%m&)hqxigP&v5$Gc)(KVVxYAZZ=LmXfO16J zjRl<#rUT_r^(%SFD7Qy|Y>-`{Kz>L@dgXH{I0O_&@s)4IOf?}LiksHm0;ETEEg9uk zGMXo-23702cF8xbOn4WBV((9e3G2vB7MrQ^sE4*z(62*t#d~{PXn4G z-D|-n#ueMRv~K{#W+Xzf z`(!%Oe^o~7eGg>2){-8@a2W9E*+zRS(E9Q>6iAQaIRW5XyzKbXhBmqK#-~jj%-M|3 zf%$n?)Bqm3&9nYP=%+xuUi_V8{0L%APY8hTi3J~j-R-nCR2aC_p z0eLq1zkw$ANqb1+U7;S7d^es|R2R2nEtXZJ8V?e#?Mjyavdx zi9j(}0FZNwK&kQHY*Or{Te8YyC^8A4(}C=eeVu^TSOJu~P-KFjk{JnnGGEh{Zq*C- zdFI+Ld7q48D;e>$4^{8cq5gWbmh_A#huM&cNn81n9>ra;V$Ap@KNY`wKzfG*pFPr} z9BD1q)!s6BRt_Y?9yYo(Pcw_yoLhhnYCOOsRS6@B2cYvkL+tbLHP&+(v42fUFZ)$x$(tT^)nwxk8*byDCU}@`SMG(tZ~)5 z1YkK|0SciZvfu`+1wj+0MgY7_uElcY*3t>u9_ckc{#ozU;mo*;Y-XN-w{i}Zfu%tHKLZEAaG)H??k->1-u%lZWY7!KsL_-QvoqFdZg25i`F7{ zX75Pm4mb-Ifqpp=pa+3!Kspo~#dsEwu8qi~fU1s01NotSuN-SV#dt9? z2_xI`Uu&rzl-Chp8Ib-{K>J0po9{UJ;hVktKJyEL58;mm;ot!n27Yqfj~g=BRTP;`znx6 zvgcJ9=@IWsYWD+dRxHN>)rjWb1GnL~1Zik1r{jTamfTA)4ai5$RqZL(s#(>N;(s%; zuQBOmEh94$D!)X}0rrF$m)~uH(C6H-E-gY<1ItoS+Q+F+g>)8Bp`)Osh!y3h?Dn`nm(zF%hf- zm%tXF^|X#`(LU9j;b0SZ0G0#gK{CpTbj<_wA5r-*7NFaW4`qE*LyCudk)4wwaTb{*v?Zh5`eZuNRtywdVrt&! z&!(-~Q!IRX6c1!_r@-Gvw4a0HU<`Az1Nbg+b*lo!T(MJKFm7^1tW537cg6i1pc)hu zSLHGkjAL8eN5=`;nnPWfm?`g}U@eeM%EJvH8RcI7C`Yon3s4OTD}n4$Y_*QhC&kbw zbBK1I$T9IHqcQ1>lyN)L);j2T{RuIkX>>1x{sL5=TfukW0OR@bp#|-y;3!Z$O0W*~8c+pZX~sT*#sE4)3Sk>_lPzZ)AHBoiv*&`!fpN5p zI!U^m?bFBLVX&Ma<1jO(nvFxE#LDJ z&y*Wj>nrdUJmuwG<|?+AL3a89&~)gS0gVME-|l0Om-cng7jyQak`ktiRE6=6Bk-qHv+;LJNlbBotbY(n?}OqfI{m#+VIn}*A#Ubu%0yrGk(UqP z#oCQN?DAlXrx<$Q1lZvH7&L>I1gKv3fFX|a9(Kf-g^lP4_>eL7o);fg=Ky2=Cn0i=h23PjHFPJnk1B!%}3yHn8KOZy3P zK0;Sq`qF{_=5zc7jA@_6kCZtOGJ-|5MUtpE^H+UuZ*gE_p{YPjyU=+>Zfv z>pYU*=6Ce*w~>)oVA@G*eCdm(bZ>NFQn-tT~(jMLV2Lf31(Lsji~ zs1>bmuJO#(nHCMdyu{kv-&KId1NlK2P@l1Hm`6VR;N8IVMGCdda0BcnK6 zqFo!5MScT)#g{Qt4X-t+LW(c}W27hl}{ASOVE_ebcjfErNl12Q2m-(%A!w@it! zpV*oAFLLY}ZPwH~ZPifVW@LKNt`6i!G9bVEP#QlF+Yz+CWGn~B#+n~O+o0zFSPhoK zlV43}?~LdNa6afdVeYREL%#zn(X$Qy#}P8-vxgm?ee?sO(eFT?yqYr$8}uw3 z)Ei3v%{}o1=+^+d%y~74c~j8ek-6zW7VtV_clw@h@tkkcPx~6>-pZ)9X^=n7W^}N z{Ven;ASR}M-e5d8ef%)G@g-mtx>?)wPeSK{E#L}sIwQXVWTelU-srU1m!|#`!J{V4 z^#B>=#!Ky(&q4#5*>21Q0jR zc7VJ)4HN_9&FurI(Lid#6Gpo(NQ}M2$swQaTR^trPlH*=B&UrX0gBU}2pPTq_dcf& zbs5*SJAgIKS}N}l!1%g}A$1PEu1$x!+E4eip%u}{o>%}OZoH}6WQbteq4 zmhOXepX8xF&3hHuL{7~82e~tHlNhHKOg%n;H-Ywb(4Mwxi&&d8U;4?bspI*K-(X%v zXiRvD!+m^dPJcaZ#>{61$}zR4>z{{ucdyZ=&YYjX-Uw>yG6wBaj8kvs{#`Lc*0g2s z2oMGo*9GLD3HtyWf?h+0T69Z-GVl+w4*r^JPyuLq@IKJFSPx)d^is%eM6M?NB+y3G zCOJ3HQo-=pgDx^|L(mMLG5~zkb=cgqUgfOmLq8q-vdsIKws0IhouFNi!~Pft7$fKU z?AJYytqJIpZ}(@Y+8|&I6q`*AQk$MIkQcCbbYH4-&y|nL-)4CII0uiQAKm5}R2P0# z`okS3aS*)h^kuhvs~<7uwuKVg0PHr`tlP+6Ms^4KL*OL`?7!dgO#aM%BBwf^wa1)C z;3RzZwyA4umH*l=Zdk;a&P($i=Oy$9#>kJZ>*mZ9Zv|KaP6Kr5vlq`?;6+C^`uJq( zY!Ott*vEQa)!A##H|bkVpLy=Vwc(Eg*s1S~nfusl5pDC#6Ha>#z&_2@ zdueli)nE>}_nd=ww}L2JlB`hPMGSb7=1dYr)J2 zzV0zp7kbWe`_fjPr7s0-*)f5!{`A#W{C#$hqK(Z?IP&ak-NTyqgPafE%JiuL)rFV* zxbky9(A=qD5+JAMK4~X1==G=ucYrIAe6^9+{h<8R^RT%d5qon6uZPM{d^6YnOUTqk zrW5_2f$YF{y`M4PVdhLQ>kfmDUFM#*9OLoevyY5j;ZW9H-4ecXf=*L!Uv9?YM#_>`t!M7v z-h#gkz%tig?WYrrQ7fJ@P}KwRGkWmBJUiZ_Pb|Fe(C-20>Wqqe$Z?Y7fzLXMqqiqG z$E{Ijt^w>1cQFVCiu<=ukDQtF1s&dA z@b=Ot4mwlJGf`qFu`u^4it8q@9jFHI&kdzbTq-o8pN4(~&=B5zDDe&Wj5wp)ycZ&F z?uQ^7vTfntp{+HEgWkXC{=i%}k?}TWoVqdBWQNRr!t3b6J`Z^}_YAPjb*wJ(GvW89 z9~~zC%4WT<31H8;YZ=QAZ3;w@cfSDS-t!F<8}xaZp1sX;Hohs=0VNoZMVokfFVMcl zIR3cIG5ZHObB~b-niCm(Ht$rvrXQ2}sy*yA_X%m4bDDNbFcK7HyaD6SXv-ez!F(pG z+zkPW0X1))RjSkP3b4oQtw7p27$;`#HFz%oIrU~mp0UStt1(^!q=bJP zXx>6Fk1-WFdGZi1&%5-Mr{?hR$<)we=q1K_g9VIXySYY62X&$E5t{o6$^i$=c-rYt$PAC~F0g3lBPVJykvE-JN-F{5dog za=XA2u!fJJ$zMRXh`x6`RpGbMD1w9Q^@};3*g6+W4^t%AWCD zgby|QX$iC+z%G*))-?B#$?2~K)94ci4^4B8+)raR(EJtfsYy4Sw(LCtlvirX+&@su zg&yI*d_!;inGtRC-s?+vh-n{X3q;Sav{2FO!sN#I!EkH9EqJ17Qxs3fhQb3wPW@tYpI^h+W2hVYe&PkB*?`@CILKT z&Hd5<=pLYWoM&7)MW4C%l^+`K2Xsx*n)i@-fy{ffH9nqpB6!G|`wQ6}4tfFP&9#$# zqx%DMFVr477U;UCHJ>BXj=9oB+>K0k=nz1Sn(s$kMFv0I^YBz#n?YMZ9`wwi_jlf| z$b3$lT$}Soevbq@0dqVJ;Lii{y${$A?;ic#wC@A$2kbC9bHLAoP7ibjyme64@sJ0d z>*l&Qo96e($i`&w!f30ulxwYt&F21(9O_+!s~F1X9bg661m=K!%zK-0a$|CTjdebb z9LFb9hs4(D0$MYM?Rs`I_frd@8l!GJqv6Yb?Uk>Ae4GFjE9%@62;B&J(4LPhF*7k1 zFD!y@;>9|imW(feHwa7zOMr9{Go3Ly4@@m|psoG#CH-+=Dwqc3>o9=7(V1`lUEEyy zV~}T#iN#9#%YgK2oq+&(bB3g&-93^&1$q)3AWlV?D?WKQdj(xaPHQd)CmbgO`t*!u zo<+64iJ3Y3(WB=OPdWOCn&(dPXP$qy!i&S$YydU)gxR5r-Er_EARc;0WbRoe)5jNQ zD3EQ`u-5i;Vmz4kJkS~JfmZ@v4%+0(Q;N3oto(%1KT2OQRUNDX%9-M#+PT1Z8t7>- z95Bc1lZ~|H|6(u`Xq}!wwvu~2GwPnj=vxbwjZ49Ha0KA1hd7&i8GQQfxf^|Ym!bPL z^UT{D`VAP2e0|`hEq$tA%^M9af=fVaKS72V>)zkgw)89lqas26bl!NfAR`^vVBYa5 z2i?GWa0aM;Zvy!S--EsSoY2@$96TrK=cYdd^a6_Y18|+Oyo@Pd(jy&;=_Vk1=QI9{ z@le|2O8d@yo;CxDF0&u*(w-L4H#JHA*u!pp>OHU!GR5f2=bq?duX%!K%P;w(`W^^~ zqj`UV|K|JY;vXZnsi3k;<6Xck=F4yVQw@8GoB8Z%5dDMnYeHowF*P|JhP>>10eS$* z$@X>dm2dW?`D~DS@U%r2u`<4}j(OHrohW9C*Esgc`^W_#r@SgxtQjC1-lMHGmFrOY zv7pNFHf&l*e*o>hK(+J`NLINV3^t&%4>HO@IFL;m4+DygY`qLsTtm@^4d(MS*{HK% zBKQ(a1=2Yl`CZ7|rhNs-&ZR(giLEKVVr)6c1mb}f@PB|Nh9d7JN9KH24Pd{C{e9>G z^in(KIZOFe9D4)SGIc0B*E6m>Z3Wn2o~iTGR!zyqEr5OMS&rO~v~K{}C|?A{8NN40 z3 zL*_#Ffv1dJ;9j;QayjTf1F9XxZ$~6lM?tN5W&@d8lXeEKJO_-}TPZRqb2>io5u%p=U-tTj^Xgah6`$@*H{T-AMZ|HHbf+ zBJ|_ZKM9n#`GB}7UY-Sv6{4*glJ5fm_2z}Tvhx@;4RYx7$QDloOg-<8?B{~wtGTy0 z&m8F*&M`fk`}`8{iEl09>)Am249Ld*SNjRj+Qi-a6XU1pR|L)AF{b+n^IZB7{aBDK8Frr?0v@8 z(&nr%wbl{(9w4<)}whw4uGIK{fugozj90r+ETqe7(I z9%QI56O-zUk#oHd2~Zr#m5IYcC}Min4@eFlTTM3eqH7$R~Nx!^x>}uzm0$2!NX?V!+NPvlRFi~ zIe6p5cMk3W#<0OVk9DaVUGww|W8O85hqh-7pUr1= z%+;Cu`X>6*0kvVyYhvLgjxKhZGkGDjKez&K2_UYDLqI*~bwIv7H$h?ADM2)34?;7b zCmH-!wDG|uPUg(s%(!eOb{^@tL;oW9l|E}4J*nyc5IN^4JnGLom41DI4|->%>$Rr| za`zZxE%RA%0DWpAfVwo#K&PND0d;BKzn-NH^gTQCd^7?|otkUA>R5S5ME_?Xn|?xf zTX>5idDx`;I&<#G{z)PVMaxxb^9J=kvU%Vh`kYjiG$PupD2Wczo3_04x< zYtUwIn|s>cJgSj{pf&W*f+CEOcXO|_!Ep+lMo&-rifv-(GU!r(&GIR*6XU&T=LRVl zKO6zI^-k8Dg{6=|m+ITRcTql1(2ftvf)9Y|<`?Y4ZkM&p{Qx$bYa{#H^BQgTw#lLP zcXG!`odfxpwBL;An|H@0;K^oc-{@ukne&F&d9KiY7u||2b>g`SkTsuecZaG*@&kOy zL_O*L&g}zQf{Exww|Rffelz!Ezn%x*~nU| zH+>fAsRf-(e>)%-rk?TNthw~-p8&oXU9UqgBCB|jd-Klu zd-~1jPo;kzV1x83cE*RxjJKt~6%>X?4apAObDL)e#cdN%?VNF(v~?L{ubVTxIz057 zXW7T_vDGC;CaxQyAHq`&l|ybEP<-3dm(9qV=Uc^5>rp>C8+7)Wd!PIC&(R-@uku}a zk-pkMZQ^R~J@e2X28faQUL5@l)SP+WI|Lm&n9thYc#KyBm)I9?GroX!Yan|RbK;=S zG0eTJ)`9OyNWThWiVeivZzyjMz*+iZf$CC&C&79^Zq?O&w3$BwnwDQ@y{fQ(MG?XEj`3rwwm`O(`mDgd9Lmc)jawA5af%L{g(Dq(19^($ed%#==Y{g{>-^8 zJ;c}C(=>+0r!U@jv?Ws_Le}g>d{8}^+^vK^6|k;Zvn1^>ARFf+$JymQ%vcZ53t)rp zqs-^2Ru8#6w26=IhfJMdyG#DfIgLKu1G~4-c_~7-&dlHy@V3!cUCaeT0d-@Z zZRzX2LHG6^U~HsT^o(cf(o1_Im`HyY^br^XuvzcY&3$h+`idCV&2@&jnRU@&&SUALu2t_QNBq0xPmVFK4s&wCQ(mc0)t{c# zJRwlk&rl#=Hvz?aGGh~%(~`DylV^jO(8Uq$^w*I|g-mlG{xxt1oJM~v&>6mJRJm*c z3gZ72<`6?ybxI6;&*eI&1C)E}*$siudggmI#8-8sXEx6)#@+(azy|sZDJJIMd!&FO z<1T}_9;&>gq5T8shpb}S461l3&xZhhnRBTJZT5h9o|hkr#VW8Z0v_s6ewb^Q?2)YM zKy(i}VnQDQ>caC8ewRZ26OaR>ji3P=p|^qT{}@^9S1!CS>9dZ$PvEHr?F3)@OL+1%c?uM3 z#cwceVrOc17JcGu?kjG>drbR#cmru`9(}XNRzuH$gN&Vq5?9^JoBNnJ@QT8NZ{i@| zqvJC%GCEc|=HH2#_Y|zBYo3WgA>`jt4w5fBGi!;y~$ZP^y>p1-^&>7J2AUW-0U>Il*&}*Kp*t1&Gd_N!o?Z|r4 zXG$iArQ#3kxbn3RR->wey(-sX3rRk(^ zT)%l6HT2V>ev>wJTDNW<(Tn(R&L+* Add new panel` in the top left corner of RViz. + +- Then in the pop up window please select `RealTimeFactorSliderPanel` and double click on it. + +![Panel](../../image/realtime_factor/panel.png) + +- Slider controlling the speed of simulation time should be visible on the left side of the screen. + +![Slider](../../image/realtime_factor/slider.png) + +- The process of adding the panel is also visible in the video: + + \ No newline at end of file From 6e359a10a71a5ced017a0d18d0ac9b1b6f1ac773 Mon Sep 17 00:00:00 2001 From: Dawid Moszynski Date: Tue, 30 Jul 2024 15:11:53 +0200 Subject: [PATCH 059/304] doc(scenario_test_runnrer): fix spell and link --- .github/workflows/custom_spell.json | 1 + docs/user_guide/scenario_test_runner/RealtimeFactor.md | 2 +- 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/.github/workflows/custom_spell.json b/.github/workflows/custom_spell.json index cecc85a3aab..b9638744476 100644 --- a/.github/workflows/custom_spell.json +++ b/.github/workflows/custom_spell.json @@ -41,6 +41,7 @@ "TESTRANDOMIZER", "travelling", "Tschirnhaus", + "walltime", "xerces", "xercesc", "yamacir-kit" diff --git a/docs/user_guide/scenario_test_runner/RealtimeFactor.md b/docs/user_guide/scenario_test_runner/RealtimeFactor.md index 3cce38d5c06..25b20964ac7 100644 --- a/docs/user_guide/scenario_test_runner/RealtimeFactor.md +++ b/docs/user_guide/scenario_test_runner/RealtimeFactor.md @@ -46,5 +46,5 @@ It is possible to modify the speed of simulation (the speed of time published on - The process of adding the panel is also visible in the video: \ No newline at end of file From 69bc2a36c740fd2d1befb7a803b515f0637b865b Mon Sep 17 00:00:00 2001 From: Dawid Moszynski Date: Tue, 30 Jul 2024 15:31:05 +0200 Subject: [PATCH 060/304] doc(simulator_test_runner): add EOF to RealtimeFactor --- docs/user_guide/scenario_test_runner/RealtimeFactor.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/user_guide/scenario_test_runner/RealtimeFactor.md b/docs/user_guide/scenario_test_runner/RealtimeFactor.md index 25b20964ac7..ad7d2847b8b 100644 --- a/docs/user_guide/scenario_test_runner/RealtimeFactor.md +++ b/docs/user_guide/scenario_test_runner/RealtimeFactor.md @@ -47,4 +47,4 @@ It is possible to modify the speed of simulation (the speed of time published on \ No newline at end of file + From da85edf4956083563715daa3d60f0da1f94a423d Mon Sep 17 00:00:00 2001 From: Dawid Moszynski Date: Tue, 30 Jul 2024 15:37:11 +0200 Subject: [PATCH 061/304] feat(params): set use_sim_time default as True --- .../simple_sensor_simulator/src/simple_sensor_simulator.cpp | 2 +- .../scenario_test_runner/launch/scenario_test_runner.launch.py | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/simulation/simple_sensor_simulator/src/simple_sensor_simulator.cpp b/simulation/simple_sensor_simulator/src/simple_sensor_simulator.cpp index 4f3c1130989..143d836768d 100644 --- a/simulation/simple_sensor_simulator/src/simple_sensor_simulator.cpp +++ b/simulation/simple_sensor_simulator/src/simple_sensor_simulator.cpp @@ -230,7 +230,7 @@ auto ScenarioSimulator::spawnVehicleEntity( simulation_interface::toMsg(req.pose(), initial_status.pose); ego_entity_simulation_ = std::make_shared( initial_status, parameters, step_time_, hdmap_utils_, - get_parameter_or("use_sim_time", rclcpp::Parameter("use_sim_time", false)), + get_parameter_or("use_sim_time", rclcpp::Parameter("use_sim_time", true)), get_consider_acceleration_by_road_slope()); } else { vehicles_.emplace_back(req.parameters()); diff --git a/test_runner/scenario_test_runner/launch/scenario_test_runner.launch.py b/test_runner/scenario_test_runner/launch/scenario_test_runner.launch.py index 4d0b80e55f3..961cd9a5f5d 100755 --- a/test_runner/scenario_test_runner/launch/scenario_test_runner.launch.py +++ b/test_runner/scenario_test_runner/launch/scenario_test_runner.launch.py @@ -81,7 +81,7 @@ def launch_setup(context, *args, **kwargs): scenario = LaunchConfiguration("scenario", default=Path("/dev/null")) sensor_model = LaunchConfiguration("sensor_model", default="") sigterm_timeout = LaunchConfiguration("sigterm_timeout", default=8) - use_sim_time = LaunchConfiguration("use_sim_time", default=False) + use_sim_time = LaunchConfiguration("use_sim_time", default=True) vehicle_model = LaunchConfiguration("vehicle_model", default="") # fmt: on From 4b1a8d916d345c65c68336ed2da508bd5d7a44f7 Mon Sep 17 00:00:00 2001 From: Dawid Moszynski Date: Tue, 30 Jul 2024 16:07:14 +0200 Subject: [PATCH 062/304] doc(scenario_test_runner): adapt doc to changes in use_sim_time --- .../scenario_test_runner/RealtimeFactor.md | 48 +++++++++++++++---- 1 file changed, 38 insertions(+), 10 deletions(-) diff --git a/docs/user_guide/scenario_test_runner/RealtimeFactor.md b/docs/user_guide/scenario_test_runner/RealtimeFactor.md index ad7d2847b8b..c0da846dd97 100644 --- a/docs/user_guide/scenario_test_runner/RealtimeFactor.md +++ b/docs/user_guide/scenario_test_runner/RealtimeFactor.md @@ -5,16 +5,6 @@ It is possible to modify the speed of simulation (the speed of time published on - from the start of the simulation (using parameter), - during the simulation (using the GUI slider). - -!!! Warning - Parameter `use_sim_time` of `openscenario_interpreter` is false by default and should not be modified. - - | use_sim_time launch parameter | /clock time published by SS2 | AWF Autoware Time | - |-------------------------------|------------------------------|---------------------| - | false (default) | walltime | walltime | - | true (not supported) | - | - | - - ## Use parameter - When you run simulations on the command line, add an `global_real_time_factor` parameter with a custom value (the default is 1.0). @@ -48,3 +38,41 @@ It is possible to modify the speed of simulation (the speed of time published on + + +## Configure `use_sim_time` parameter + +Parameter `use_sim_time` of `openscenario_interpreter` is true by default and can be modified by passing it using command line. + + + ```bash + ros2 launch scenario_test_runner scenario_test_runner.launch.py \ + architecture_type:=awf/universe \ + record:=false \ + scenario:='$(find-pkg-share scenario_test_runner)/scenario/sample.yaml' \ + sensor_model:=sample_sensor_kit \ + vehicle_model:=sample_vehicle \ + global_real_time_factor:="0.5" \ + use_sim_time:=False + ``` + +However, this impacts the time published on the `/clock` topic and the time used by `Autoware`. +Details are shown in the table below: + +| use_sim_time launch parameter | /clock time published by SS2 | AWF Autoware Time | +| ----------------------------- | ---------------------------- | ---------------------- | +| false | walltime | walltime from /clock | +| true (default) | simulation | simulation from /clock | + +Below are also some bullet points explaining the impact of the `use_sim_time` parameter on `SS2` and `Autoware`: + + - **`use_sim_time:=True` passed using command line (default value)** + - Both Autoware and SS2 are launched with `use_sim_time=true`. + - Time published on `/clock` is the **simulation time** (starting from 0). + - Time published on `/clock` **can be** controlled by RViz plugin. + - Simulation time **can be** controlled by RViz plugin. + - **`use_sim_time:=False` passed using command line** + - Both Autoware and SS2 are launched with `use_sim_time=false`. + - Time published on `/clock` is the **walltime**. + - Time published on `/clock` **cannot be** controlled by RViz plugin. + - Simulation time **can be** controlled by RViz plugin. \ No newline at end of file From f7a1d7c54ed8f63078ba3e7030467f62ed3289a5 Mon Sep 17 00:00:00 2001 From: Dawid Moszynski Date: Tue, 30 Jul 2024 16:09:28 +0200 Subject: [PATCH 063/304] doc(scenario_test_runner): add EOF to RealtimeFactor --- docs/user_guide/scenario_test_runner/RealtimeFactor.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/user_guide/scenario_test_runner/RealtimeFactor.md b/docs/user_guide/scenario_test_runner/RealtimeFactor.md index c0da846dd97..08c70f3249d 100644 --- a/docs/user_guide/scenario_test_runner/RealtimeFactor.md +++ b/docs/user_guide/scenario_test_runner/RealtimeFactor.md @@ -75,4 +75,4 @@ Below are also some bullet points explaining the impact of the `use_sim_time` pa - Both Autoware and SS2 are launched with `use_sim_time=false`. - Time published on `/clock` is the **walltime**. - Time published on `/clock` **cannot be** controlled by RViz plugin. - - Simulation time **can be** controlled by RViz plugin. \ No newline at end of file + - Simulation time **can be** controlled by RViz plugin. From 8ebd1673c275e4c315fa6a8c1b809abf2ed95c96 Mon Sep 17 00:00:00 2001 From: SzymonParapura Date: Tue, 30 Jul 2024 17:21:03 +0200 Subject: [PATCH 064/304] feat: Enhance IMU sensor configuration and initialization - Added frame_id to ImuSensorConfiguration - Separated noise standard deviations for orientation, twist, and acceleration - Updated ImuSensorBase and ImuSensor classes for new noise distributions --- .../simulator_core.hpp | 6 ++- .../sensor_simulation/imu/imu_sensor.hpp | 36 ++++++++++++--- .../src/sensor_simulation/imu/imu_sensor.cpp | 44 +++++++++++-------- .../proto/simulation_api_schema.proto | 14 +++--- 4 files changed, 66 insertions(+), 34 deletions(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/simulator_core.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/simulator_core.hpp index 27ddf6fab82..e025642f819 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/simulator_core.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/simulator_core.hpp @@ -337,11 +337,13 @@ class SimulatorCore core->attachImuSensor(entity_ref, [&]() { simulation_api_schema::ImuSensorConfiguration configuration; configuration.set_entity(entity_ref); + configuration.set_frame_id("tamagawa/imu_link"); configuration.set_add_gravity(true); - configuration.set_add_noise(false); configuration.set_use_seed(true); configuration.set_seed(0); - configuration.set_noise_standard_deviation(0.01); + configuration.set_noise_standard_deviation_orientation(0.01); + configuration.set_noise_standard_deviation_twist(0.01); + configuration.set_noise_standard_deviation_acceleration(0.01); return configuration; }()); diff --git a/simulation/simple_sensor_simulator/include/simple_sensor_simulator/sensor_simulation/imu/imu_sensor.hpp b/simulation/simple_sensor_simulator/include/simple_sensor_simulator/sensor_simulation/imu/imu_sensor.hpp index 9ec044b3801..03a1c7313a7 100644 --- a/simulation/simple_sensor_simulator/include/simple_sensor_simulator/sensor_simulation/imu/imu_sensor.hpp +++ b/simulation/simple_sensor_simulator/include/simple_sensor_simulator/sensor_simulation/imu/imu_sensor.hpp @@ -17,6 +17,7 @@ #include +#include #include #include #include @@ -32,10 +33,16 @@ class ImuSensorBase public: explicit ImuSensorBase(const simulation_api_schema::ImuSensorConfiguration & configuration) : add_gravity_(configuration.add_gravity()), - add_noise_(configuration.add_noise()), - noise_standard_deviation_(add_noise_ ? configuration.noise_standard_deviation() : 0.0), + noise_standard_deviation_orientation_(configuration.noise_standard_deviation_orientation()), + noise_standard_deviation_twist_(configuration.noise_standard_deviation_twist()), + noise_standard_deviation_acceleration_(configuration.noise_standard_deviation_acceleration()), random_generator_(configuration.use_seed() ? configuration.seed() : std::random_device{}()), - noise_distribution_(0.0, noise_standard_deviation_) + noise_distribution_orientation_(0.0, noise_standard_deviation_orientation_), + noise_distribution_twist_(0.0, noise_standard_deviation_twist_), + noise_distribution_acceleration_(0.0, noise_standard_deviation_acceleration_), + orientation_covariance_(calculateCovariance(noise_standard_deviation_orientation_)), + angular_velocity_covariance_(calculateCovariance(noise_standard_deviation_twist_)), + linear_acceleration_covariance_(calculateCovariance(noise_standard_deviation_acceleration_)) { } @@ -47,10 +54,21 @@ class ImuSensorBase protected: const bool add_gravity_; - const bool add_noise_; - const double noise_standard_deviation_; + const double noise_standard_deviation_orientation_; + const double noise_standard_deviation_twist_; + const double noise_standard_deviation_acceleration_; mutable std::mt19937 random_generator_; - mutable std::normal_distribution<> noise_distribution_; + mutable std::normal_distribution<> noise_distribution_orientation_; + mutable std::normal_distribution<> noise_distribution_twist_; + mutable std::normal_distribution<> noise_distribution_acceleration_; + const std::array orientation_covariance_; + const std::array angular_velocity_covariance_; + const std::array linear_acceleration_covariance_; + + auto calculateCovariance(const double stddev) const -> std::array + { + return {std::pow(stddev, 2), 0, 0, 0, std::pow(stddev, 2), 0, 0, 0, std::pow(stddev, 2)}; + }; }; template @@ -60,7 +78,10 @@ class ImuSensor : public ImuSensorBase explicit ImuSensor( const simulation_api_schema::ImuSensorConfiguration & configuration, const typename rclcpp::Publisher::SharedPtr & publisher) - : ImuSensorBase(configuration), entity_name_(configuration.entity()), publisher_(publisher) + : ImuSensorBase(configuration), + entity_name_(configuration.entity()), + frame_id_(configuration.frame_id()), + publisher_(publisher) { } @@ -85,6 +106,7 @@ class ImuSensor : public ImuSensorBase const traffic_simulator_msgs::msg::EntityStatus & status) const -> const MessageType; const std::string entity_name_; + const std::string frame_id_; const typename rclcpp::Publisher::SharedPtr publisher_; }; } // namespace simple_sensor_simulator diff --git a/simulation/simple_sensor_simulator/src/sensor_simulation/imu/imu_sensor.cpp b/simulation/simple_sensor_simulator/src/sensor_simulation/imu/imu_sensor.cpp index 25967c51f7e..9a86e1a3731 100644 --- a/simulation/simple_sensor_simulator/src/sensor_simulation/imu/imu_sensor.cpp +++ b/simulation/simple_sensor_simulator/src/sensor_simulation/imu/imu_sensor.cpp @@ -16,6 +16,7 @@ #include #include +#include #include #include #include @@ -27,25 +28,30 @@ auto ImuSensor::generateMessage( const rclcpp::Time & current_ros_time, const traffic_simulator_msgs::msg::EntityStatus & status) const -> const sensor_msgs::msg::Imu { - const auto applyNoise = [&](geometry_msgs::msg::Vector3 & v) { - v.x += noise_distribution_(random_generator_); - v.y += noise_distribution_(random_generator_); - v.z += noise_distribution_(random_generator_); - }; + const auto applyNoise = + [&](geometry_msgs::msg::Vector3 & v, std::normal_distribution<> & distribution) { + v.x += distribution(random_generator_); + v.y += distribution(random_generator_); + v.z += distribution(random_generator_); + }; auto imu_msg = sensor_msgs::msg::Imu(); imu_msg.header.stamp = current_ros_time; - imu_msg.header.frame_id = "tamagawa/imu_link"; + imu_msg.header.frame_id = frame_id_; auto orientation_rpy = math::geometry::convertQuaternionToEulerAngle(status.pose.orientation); auto twist = status.action_status.twist; auto accel = status.action_status.accel; // Apply noise - if (add_noise_) { - applyNoise(orientation_rpy); - applyNoise(twist.angular); - applyNoise(accel.linear); + if (noise_standard_deviation_orientation_ > 0.0) { + applyNoise(orientation_rpy, noise_distribution_orientation_); + } + if (noise_standard_deviation_twist_ > 0.0) { + applyNoise(twist.angular, noise_distribution_twist_); + } + if (noise_standard_deviation_acceleration_ > 0.0) { + applyNoise(accel.linear, noise_distribution_acceleration_); } // Apply gravity @@ -70,15 +76,15 @@ auto ImuSensor::generateMessage( imu_msg.linear_acceleration.z = accel.linear.z; // Set covariance - imu_msg.orientation_covariance = {std::pow(noise_standard_deviation_, 2), 0, 0, 0, - std::pow(noise_standard_deviation_, 2), 0, 0, 0, - std::pow(noise_standard_deviation_, 2)}; - imu_msg.angular_velocity_covariance = {std::pow(noise_standard_deviation_, 2), 0, 0, 0, - std::pow(noise_standard_deviation_, 2), 0, 0, 0, - std::pow(noise_standard_deviation_, 2)}; - imu_msg.linear_acceleration_covariance = {std::pow(noise_standard_deviation_, 2), 0, 0, 0, - std::pow(noise_standard_deviation_, 2), 0, 0, 0, - std::pow(noise_standard_deviation_, 2)}; + std::copy( + orientation_covariance_.begin(), orientation_covariance_.end(), + imu_msg.orientation_covariance.data()); + std::copy( + angular_velocity_covariance_.begin(), angular_velocity_covariance_.end(), + imu_msg.angular_velocity_covariance.data()); + std::copy( + linear_acceleration_covariance_.begin(), linear_acceleration_covariance_.end(), + imu_msg.linear_acceleration_covariance.data()); return imu_msg; } } // namespace simple_sensor_simulator diff --git a/simulation/simulation_interface/proto/simulation_api_schema.proto b/simulation/simulation_interface/proto/simulation_api_schema.proto index a76df569687..03d1e0e6252 100644 --- a/simulation/simulation_interface/proto/simulation_api_schema.proto +++ b/simulation/simulation_interface/proto/simulation_api_schema.proto @@ -37,12 +37,14 @@ message PseudoTrafficLightDetectorConfiguration { * Parameter configuration of the imu sensor **/ message ImuSensorConfiguration { - string entity = 1; // Name of the entity which you want to attach imu. - bool add_gravity = 2; // If true, gravity will be added to the acceleration vector - bool add_noise = 3; // If true, noise will be added to every vector published - bool use_seed = 4; // If true, as seed will be used the passed value, if not it will be random - int32 seed = 5; // Seed for random number generator - double noise_standard_deviation = 6; // Standard deviation for noise (normal distribution, mean equal to 0.0) + string entity = 1; // Name of the entity which you want to attach imu. + string frame_id = 2; // Frame ID for the IMU sensor + bool add_gravity = 3; // If true, gravity will be added to the acceleration vector + bool use_seed = 4; // If true, as seed will be used the passed value, if not it will be random + int32 seed = 5; // Seed for random number generator + double noise_standard_deviation_orientation = 6; // The standard deviation for orientation noise (normal distribution, mean = 0.0) + double noise_standard_deviation_twist = 7; // The standard deviation for angular velocity noise (normal distribution, mean = 0.0) + double noise_standard_deviation_acceleration = 8; // The standard deviation for linear acceleration noise (normal distribution, mean = 0.0) } /** From 2b40fcb7e792dc5389bd67b85867b052b29b03af Mon Sep 17 00:00:00 2001 From: SzymonParapura Date: Tue, 30 Jul 2024 17:21:43 +0200 Subject: [PATCH 065/304] docs: Update the communication document for this IMU topic --- docs/developer_guide/Communication.md | 1 + 1 file changed, 1 insertion(+) diff --git a/docs/developer_guide/Communication.md b/docs/developer_guide/Communication.md index 1157fd965c9..b4bc8293b5f 100644 --- a/docs/developer_guide/Communication.md +++ b/docs/developer_guide/Communication.md @@ -36,6 +36,7 @@ | `/perception/object_recognition/ground_truth/objects` | [`autoware_auto_perception_msgs/msg/TrackedObjects`](https://github.com/tier4/autoware_auto_msgs/blob/tier4/main/autoware_auto_perception_msgs/msg/TrackedObjects.idl) | [Simulated by simple_sensor_simulator](https://tier4.github.io/scenario_simulator_v2-docs/developer_guide/SimpleSensorSimulator/#object-detection-results-simulation) | | `/perception/obstacle_segmentation/pointcloud` | [`sensor_msgs/msg/PointCloud2`](https://github.com/ros2/common_interfaces/blob/master/sensor_msgs/msg/PointCloud2.msg) | [Simulated by simple_sensor_simulator](https://tier4.github.io/scenario_simulator_v2-docs/developer_guide/SimpleSensorSimulator/#lidar-simulation) | | `/perception/occupancy_grid_map/map` | [`nav_msgs/msg/OccupancyGrid`](https://github.com/ros2/common_interfaces/blob/master/nav_msgs/msg/OccupancyGrid.msg) | [Simulated by simple_sensor_simulator](https://tier4.github.io/scenario_simulator_v2-docs/developer_guide/SimpleSensorSimulator/#occupancy-grid-sensor-simulation) | +| `/sensing/imu/imu_data` | [`sensor_msgs/msg/Imu`](https://github.com/ros2/common_interfaces/blob/master/sensor_msgs/msg/Imu.msg) | | | `/perception/traffic_light_recognition/traffic_signals` | [`autoware_auto_perception_msgs/msg/TrafficSignalArray`](https://github.com/tier4/autoware_auto_msgs/blob/tier4/main/autoware_auto_perception_msgs/msg/TrafficSignalArray.idl) | for `architecture_type` equal to `awf/universe` | | `/perception/traffic_light_recognition/internal/traffic_signals` | [`autoware_perception_msgs/msg/TrafficSignalArray`](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_perception_msgs/msg/TrafficSignalArray.msg) | for `architecture_type` greater or equal to `awf/universe/20230906` | | `/perception/traffic_light_recognition/external/traffic_signals` | [`autoware_perception_msgs/msg/TrafficSignalArray`](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_perception_msgs/msg/TrafficSignalArray.msg) | | From 1904b2a68943bbe5e01d3f811c9bb01c2b7e2f01 Mon Sep 17 00:00:00 2001 From: koki suzuki Date: Wed, 31 Jul 2024 10:28:33 +0900 Subject: [PATCH 066/304] chore: Update Longitudinal_control.md with additional details for requestSpeedChange API --- docs/developer_guide/Longitudinal_control.md | 4 +++- .../requestSpeedChange.png | Bin 333205 -> 361360 bytes 2 files changed, 3 insertions(+), 1 deletion(-) diff --git a/docs/developer_guide/Longitudinal_control.md b/docs/developer_guide/Longitudinal_control.md index f886d60ef48..aad9f112204 100644 --- a/docs/developer_guide/Longitudinal_control.md +++ b/docs/developer_guide/Longitudinal_control.md @@ -50,12 +50,14 @@ If `continuous` is set to `false`, job to accelerate to target speed will be del When `constraint` is set to `LONGITUDINAL_ACCELERATION`, the entity will accelerate to the target speed with acceleration rate you set. - If `transition` is set to `LINEAR`, the entity will accelerate to the target speed linearly. - If `transition` is set to `AUTO`, it will change the maximum acceleration speed of the entity and append the job to change the target speed of the npc to the job queue. After the npc reaches the target speed, it will change the maximum acceleration speed back to the original value. -- If `transition` is set to `STEP`, it +- If `transition` is set to `STEP`, it will When `constraint` is set to `TIME`, the entity will accelerate to the target speed by the time you set. When `constraint` is set to `NONE`, is will append the job to change the target_speed of the npc to the job queue. +`change target speed` block in the below figure is the highest priority compared to other blocks. +If target speed is set somewhere else, the entity will try to change the speed to the target speed under acceleration/deceleration constraints set by the user or if not by the default value. ![requestSpeedChange](../images/Longitudinal_control/requestSpeedChange.png) diff --git a/docs/developer_guide/images/Longitudinal_control/requestSpeedChange.png b/docs/developer_guide/images/Longitudinal_control/requestSpeedChange.png index 66a7e96bb5a6108d4b012c37b141f73613d364e6..6b81cf53ba364aac6352bebf871640444bde123a 100644 GIT binary patch literal 361360 zcmb?@c_7ql-**^ADoUuVC1eRDAro4VUCF*iB5TOLjL~Ve71@_jD%rE|h6-7Sgsdam zSh9^}3}fcKess?JKF_(|`^j^kzjDg?UDx&9zn|~&R9jPd|K4MJckSA>U*+1>8@qNf z!glT2eU)xE_!~W>?i~1o%I${o#98Ktxu3Vg5U<-}!`-^Q8*UTsfcc{IF$s zt?}XD5j~`9)k;ON`t~W%VNLE91`TKMivQz_{_AN-8Tzbf>)scJ(Wmp*Gc7E@#ZP@h zB5oV5#)&k)4h2V@N4nO8V`-7;G}D0>QVzVQnN}z}u&;kjG2q|P?Z2L~O=NK!QP>%`DG2M!I$PPbu7g6wB&e9f>f@dLfsjE zr__Nk1zzNv>M%?~`pNBsYfNZ`$cTPhksn9?2U+>sn;)53jEgjjrpJmT<(5xp5DzMI zybv=fy_e(m!Bjc0hK@nR;DbfRego?$-3W{3%f2qRqOCg~eW%-J#FL)NOX_R9uzg}X zAM#_Y`<+Db$;D?I%)cSE|L;vwc#%s&{HnNluLfDX?|fB>nob_ymB5-)3a%BP^F#2kOC9n7?-|18DpI8_ZX=Y^u2j@2l5ksYhzT3(bS%L4y9xDCuh#hY$ z@yzkd{e*l?f&G#8^!It5e^bsC`Xx>&=k!AJfnl9U=iitT@^h}Y@a7yO#Rj+BXHQ|=!)Q; zUsw1&qk*J9SX64lfb+9dh;W!#UWWnbubbRzg=BPQu$=`-st;l3sTlubf-Q=${`q=Lm07^{fE zb4aUHcgvbpXc4Dl0qx^f1{PTVa@-VVN z;t~Ik^aA^AeTw@J@rWOwMr{n>A{1Ignw{pAuS{^kRH;=iay<4_JGyNOk!`SNlzA2= zlVdW(sGac>`HIcU!{x>@zF7<#5RVA!3*uVC?-mi4sJOR<8Mvnt}?nHY}sZtdL- z8a(L_m^W_-!M86f&ZkX6gIBt+uM0B%dH>%!9=XW2b{m`ul*2AV8vL&pSYxG}%?^dc zS@$Y8pk;JF9%sHbZP5^A^h+aZzAzl7%nS2)eNl4Czp_J$>L3e(BVVJ}>cqlGC!J|| z6f72~8@LgETgMUNiqd&2ERbVA*UqrcR|} z35Vfc=5QnkC|K-+iB|l~KY2s~cynKDVi^tcDxjp*f{`HgHrd)=DJ)W|se>Y2BF%T` z-HuQpjlt`jt5&)Xq#0Bs0{VLgeA+K{vNqN*dQhBt_LWFjjKYmQRWZMwfgGXu)55}g zYP9a|>?rl1ng`%rjB;x!h9lr(lLi()K0e%%4+eo(mvrl29s1WidtdK(cBedJpr(GO z6kt?A&2&VQii+)YVU6b0+d#6Tbi(ek6I)6~!z?a0JKnC=w^Q~QDb#$cd6!yo2D!+} zbgyG(!gyT+w(LAQ`1us)7CUT>Yt{-ICmV0=&>TMkU%uJj`NdQrP(hfQTJ%x*Eb5Pz zDXfwA^`!0h^Ixl3yMO3WVAHi7iLiwqElgdb9pdbaTilo`jFRwfx%7Zd)mnKlUSv^AJ1*Jp5K0j zYP6HQ|MS4p9e#O^fi8CX#~*Gg%(1t@od=yiy!{>xI2ggsV=b`7K^E%zG{?}liRwEd zMqtfzdb-$**i%kyRMbffbfrh~y94m~sfZbpWc0Q^9T5h1Ze(W?I`h{vUQN z)vVFem9}H{87NTB2edvrbPx)wkYTV8tv&DyZoWGdxeMUNT^%o7*_e5>wG?U;l^qL$ zW!c)%UA{82+eBs-vheF8?o!+P?=Seb;BKELP?JA2AL%<#R{=FSQ~GEyDGjJeRY2og ztu2Nrsn@K1JN06RVsRa!gk|J+>zJDN5RJ!kZi(P?5bRO)m*uvIs(=EtXs`@PW7^q` z`SpPIq4-f1`;jWl;KF&EO&<=MP|n{C4Z|PWA~HXaw@+u)BN=x{7v-_Ab4aTYK7y>>OIJGS>pS-- z9enwNMqtHO6oY&P%$&v^wE*5NmHBOwSQNrw>iY-JxgR|t&IN3dQl`X_PXp7~`c%Q| zd$$!^5-7Umiv5r2lb%i6$;MM^L>ISy$ z-fwFm2+`}wMJti9M>qRR&xi)_e@9Fdmjh04LOO218b)^x z(m^@Sx+l?BDcx%yrZc^!x>*ZubDxZV2gx5|LJ zD*iu&n@s1hK3$Z(bU8KLKTH|rN%zQO0`g_=a6&6;Cd+sFRxEU8^%ZWs%r~a0J#&3?xl?PNE=TA? z%Jrb6-JkW;bF`+rTNahPZ9RS_`_47Sn0oX!-AAldHx=%ACJzyDDEY2CN)^2#r6qO)LqFr^#$53? z1Vhwp`r^45Lr-qIo8JyrYu+=6#8~&5c1FI~!+8WQanNTPC#^|858nUXU4q9eRI>XE z?=|-vV_l0&sf9i)OvcIgv8NbY!#D%heyI4Lepl7+R3W+b@ECbL*~G${u#u%WGJM*x zgd_!gtE9tSCBm?-zNutCxn6ZL+hKDW!6s@V-DR#M%S8cs(>K-CM2R=lOB1aL+4kcB zW2K{E>|ag7^^0LJPn>r(J}NgcyIBC`=h}JIrtd=>Dws{o$tRS#kL^^6aO>mqZ99{1 z5Nt+sYR8B8xkOv{Gw!O?!VGygMf1SC3y-F@nQBTog|itRtKG7Vf_O*(smx@5pr?dxMDQ{h#<1jpjuCogXo76|f`%3_>ni+Yl? z(b*8Ga&Fw^*LKhWk&(FSeYKq_0k05K<|*=9%ge54ng=!l8Omn$F6`rh!^#(@uM_Lo z%;9MbUqb_jt-@sPXcFe?6mf}enm6=4`|hUsVf_gjtDHWQuiUELv+DH%xN%10iur0; z`Sr=vrG|@hE|PbZ{1acYV4IS8`}CSUHh^-=lwAGf`-2_3R^Pj-uCTBmmv$Y~i`>H{ zZH#%%NNll@lUPw?uOp9vG@EH@URK zaQNz8zZA>M_?EH7;CvC^TiiGA%t@^j7&B)-7EHRnmo7}#*>ljnXDrSkzmcCv!w7Fb zKUGQ#LyxfJUNbrIVFaLY8mrj=xAM+936IH6psJN1gtG)&Nq)ln1~dt#wIrVHmTw-P zyW%^+`iVCM!Cp`zt0#~0P6J6~??kL5-Q48NO^zgiO*7dB5pARCJ z=0T*dhyCjn@wXDHRJDsOyld8Pqx4jhn``%Q51gNpriEc$8aRom+?$hzk#A$nE}#iR zzG-@W{-jZE`3iYb06r2`=*Yshe1b>%YZZBYX309n^nBxJv)O9C%s3F_4BP%k<(Hz% za`u9RX!fDwbF3}5Ro!}=r;)-v8j;5nA`79;epba{il+Up&8O48mgAd*BR8AH(0=3| zG}*n4;Bw0i1Tn3l@kxtqp4AfRCDcI)PgmyG)XnwQdb_BefBtQow(VGtI3p>d>PnjY zVKJ-977GkM3NHo<5IT7qo@v(^=&EtazIY(e{NAE@t_$-B%0_W}y&%sTAb{;iUbARL zi&5pQqqADrW&?uM@H5XtZdr&&8qee{RE-hNDYcX}WbbtgwoWDwJm6Q4xFV8*NC@zq z2a-=J?9^=?8f6N+OnM+n{-I<(nU2 z&=Z3qFQ;h@+N8gYZqhe(@A69xJ>O)GkBAvVZT_@bvd^t5p1L^F%px@OqkLl(i=f1x z+vuXm;bbr>c=yi-mA{Sgc_jL;_BMKp`A?}uE}i(Y{600T$@BZI$9~yG-A$?Up@4d+#J@T%1|^`eMy88p3}OU75gbE(V*o z%%dq}nZcZ%Ddl&fXc9iXoJhjS%ZC@AB&E*ffC~~?jU8UhmtX^QtW64SuQyvyp5u|O z9^fB(o8-|ah-lJDKC3(b`t-Bn`MX-aM&$UON`CqAmpXXBn2K@u%4>2RTN?-90x{Ek zbK0*{L#kCDSZu+H_cV(SB`{v~68MV%1S5k5v)1-htIjo99d`dKK3 zyK_KllURb@bj(2Yf;}4gbjTyOtGdB za%aAkU5r&Clv|HEqsPu9+rx@OHuSR4ov6pzn^CBtz3P4xR!5?Z+)^Bznpb$}arwpx zaXheicgvnWStT>0)~+@a3@xAX;UOg;I+hIT5x7Q=F!@crjp3g-s32326tF%;6w1ts z;K=p4bI{gs-_4}5>JE$<9F?)5=pRhx4+_Y{n-z&sb7NO>JjY)&+%aBms5|!>9eR3I zdDv#rz|Tnl2*vW7(!K65F}4R$&6~C`XOD7!LIpNy?@KXU#WdkPyFlW-%f`siDouH6 zi4qXQ93y0q8ma{@PN@*}LDUibec~7s2i20ZPiMlrpvyDksipEkF{5hcWHJE_q(*86 zTSXX>W%+!}y)+i3gc_~7u=tsoeZq~2s+JMHP;*nBxwa(~Zw_az9f9CewH0EWSb$5! zoEC@_1s~8&40+>{BCYCt56dfy<4>0id~MG`?FsfyAP@9+JpZ=StV$M1Bh1e)m0-as zyxSQ|`*cihGcjZ^*EfpB$x64<%yE#8u6nVaJuROt^Qw}9dY;o~A@^*j(L>;gl8O)L zyq*j{9$^(OWx)_Zh;0ZT_=+>z4O3>ieg?59Lyd0m7mg`on2kEAq-9~bQSz9}$JUOe z`xznS-NpA81oRG}7d|p1oM%4xk|nc7?`?;Jc~+pIv*L)$KDz3WXTpcl=xzkhGMKMj zJ`~c|aypFLt>ugcN+Yp76Q@({y&Rl3;v(#w3%;}JXw5Q!FFhG_j(4(3sMUiyi1$=k ztP<=PYYE)}(LK&efdrEhMi4PKZayP8Efd{AgmrV*{eq3v3!4U}B_xq!;}u>adTyb^ zi%R__)Im55N`6IAy3V&~U8e5?-B-ursAhP~I@{<^1HOu`$|#I)fB%r4RKn%~;P+db zh3#XO`X>nn>1FVDqHH-FKPgr7{?5~eQTnq^_fgWTfHE@Sx*?BmWqz5N49yvf-C+WU z+*?@j%+lr12CZSVW6!0z;Jf=jam?o6ZhfN;3eLPt?m=wo!uEY7r~9|-jWP%CFMQz*f2n1^<|{@MB)^&$&PNPZ_(L(6Rk8&m&2ji%$E9Yt zT#TjzWi?&PKVzZ_vWF3f$t&DVR#8jAqUER1Kl7XM1sFMBq0)0fGFIb5Bfd*eJgP(W zcBStDu+3uF+mRX(_9N?S5r5Eq4e^D1m=59Tu8$zedCR}xJ|3mtmRm9R-Wyl@XD>i` zyz$lN-?>5IHXV@{ar=yUUinx{UK~mnX$E3_-q@m8G;f&n>v!-x-XK&kPEo-a7S#qj znp5~yl?d`DnWDXuaW=_uh@}K<3**J*cE8N*V%41BbJ505Wh4xO>^AOy$72;wY#Fec zz=1-jab$x4{0BX;0=qd!YBndkl1I5I(&14T(TkzZW87;sd+=V56oc0)!E-Pt^$EDW z!dcHvJaI{$6W6tZ@7A$-e)i(i>vFUXUR3qg9bG&79A7+>Q^8Mos+)t$hvFTruTLu* zHb;AvQwaLN;-_~7^4=@9>zah@`F`jAnPsgDQ*Yu)4XPO5*&=;%wzI!51>^~Fl+_Y+ zlFvlPP*zd5kt7asQ~R6SofHe|otF7MENIC|1J0FYL_>oGTJcn{GRyD zhQ0pDb*VPAcv9+F&mSF74A<)q$UXjT?@C&dhfzScp^e7HdE0Qy72JsXBJtw9w^pk0 z%B+Em`KZL$jYB)jE@10|3$LCvHcB$5vnNXQ)C`Yt`6oObY+zpz<`I1MEtDmQGEX5p z>j~)11P^zQxFKfk&1HQnJ054$1S#PNXL*V{{Mk7xK!w(hdhEoPx0Q;!>d!WdL`p02 zT$MEzYo>f;s}^rGhIgubf41VW?k3-VlW>d+`E&-$<+o4^r*;gUuK_(EVec|s>-QGV zWEE(-4sKv6u#Ldh=$r?padeLiIm(_rI#U0pX1g}+=>;dz!*Ev!@>*$xM@%+%dh zy7V!;-}5T#n%>kcoj4`CKIc(P7kxVS94SM;Dr0WC@I^pZQ!|ifvvEh?qyX4_%md3& zHL4ttl{Aq)w;f@up3-nu{rT|>_2(JKSr|7l|F=0XM~n>6^f?3^<6B zTZ;1XT~o6=*F8Z2^&~N5Ly70!8SxT7N`h0lV7QoDY@-#)#I02_&7>K}iV!nrMs|c2 zXSn#L5*DEtG9v9uk1=+=8$LAaW1RI7?mSc(KXc+s$&lWG&nWucVV-h9fisSaw94Za z%WL?+JHm&0)N&Ixf-$b^OA8^fV}I<>fWA2RME5Y8p1O8UT;bqY;!=S~e{tvyfhkY7 z{FM)Hx^e^GoN|_;4r->#J*a&>V4^ihkLG|hkKjfDh^fod z<^hu%%MMO{YwOO$Q$T?8-tdKlUSh%@*(T2YwlRqp%&3`r(5CllX;pj+>yO!wLCC{Y zQFzKQT}z@j;)HFHU4lG<{8L5(2PH>Y7mDs+$79URm=7P#WbNq(_FH4LUG$iD_vX%gUyy- zj|di^e3Qs+vh#^!yzsg5nVjAYsdepY4-o5S`})XI)j|nHB>XghBXoqRdNeBU4KI9R z)XE7hKb(o{?!SR8Q@mYG-z3Oua`R;`JYcBQn{$cMD80+F5#t&C5x^_^ET6f6 z4-yy;iyEAEgh1CwH;~LK<3O~pT-9m6N;tu@Hj&`m#v7YUY9p`rpmWM7(sQR`Dx6QJ zv+qx>xw_(rmW#XTSb#QGtaC zDYQ(PoZhAEl2A8=ds(80=F=tLgnjZU!w(oWTTZlB40U60O906e$NJ1=NetC< z4nNmCK0UFw_A#f2K}3vg1BATj1xKLVyA2yx7D=K&bed)|se`QeM)Zn7^r0ccHq)@! zz>RHsd+}mgENTk#N!lqwV255pNx@=VH2aWA;+X$+0M4B|<-0hLtXa)$q#bh zFxGX|_=nrqAzk?_qp23C<%sPh}Xu&9?0 zoFPfTa5=BO0$9xpj6u-{Qp-n>POsWUN9DOC$&G8d-+n5`n>U=W!-qI6c!#nOa@u|>F~fWbh|{Isx&DOMiD_- z={C;IC$lWwB$MzlXt>JgtTV!w_%a=9yq~Tb1muy+Bi;jEqoGlEyZevM+vgoPZ&X&= zzml8e`Ia;e_x+itTy;WYcHUay-nY8fhVUMb; zL{GTi7;mWNd~@FG!DZYT?jS*~ziM2+_e0g;HG{g7d)VBW>zXH=vO&@qX|M0Dsg<{{+l!A=DF_+Hkvb~ zl-iBDn&J!C4$Ix7g*jKu7VBWnCEFJu0J32Y;=~Hv!B|$|BHgMqm!IH2g$LX#<@Js% z=g+=eU0_gGr?6%^Mb97#e+>3*^_y&NMF9{DQydYlP&%3Vj7S2G+dQsbdJhaiY&Opk zaqDU`&?uf{K|z6DS7P5hPA3w1-UFBg?6s!l*arB!A6?@-AMa3Ah8|+5V9_@@Q-&ze zy~$fOTih>NHUZKV)71VJE?)q2B%1V03#Ap%pCh)C9ZsuTNGTKodz+%>4qg?odi?+YuZKmg2oMAt_zqDGX~^ ztFHX&23swur~;_DdK0tNP)0Tf6Nm8Sk^)eT5>uPg5nCutIwyOvWQ`+Do{>VQdSIt{ zrV-LC>$O4R6Vn6xM7d_}2drqDnI9+(eL7p!=W~>aqtSXF&=GXg0H}l$-J#6selud#$Ua*#?OZce$cmmWH!g5^(%EP* zWBncI9?YD;2gsx1_Z8-i_G8H&H)8Y*ZasXYA478%0t+PJ=#E;DQ!F)B@g6CQ5^H_J zGiOQ32U*cXUXXJ^b|S$`b8x^XiJXy{6aR7pLB=8a+Qh4D!u5|X)DIdU1wwD+=a_`5m<4aAZL?B!WVhli#ob9S%MI&1t>nfAFLaFgH6Il zP{x+6{u;0Z`FYl1yk?Xxi)&dg%f1t}ahA@Nc_;P~*-dN5->Roh?XDSpCRXHuTblkp z&E$;~0b9Zd8A|KV=RNEDswS2MFW?P_=SO6-Q`P3Zc7%O!AH@o$CEkd`WF$F*^f%%x z6q4ws>CW{7JSW1Qm#HKwTc4^H<3H!NB+(|F8YL1kD6?*~IUP7%qrL15vJR)}Z#UHV zW;;R}fLDuA*1id|8Ui?&BYI=r4<{RWKQ$CSU%AvrF6q>i<(vA(Fu@KO1R8w{tSP{> zcs|vKV?bjgV3I49CEuu)|FjO#-h87EUM+o+ni;k5hrrlDbwe`SrBaENvjN5IOdOZ0 z+y>7N-tQcPj`37esav}P(ooHuiz82XkC|0i)CP@_PR)3Nko!?jq1%U^DauMNBD;|y zAh-Cm7)x{p>5t@;2?*jP6&)pcyb4;+t9=a~#*`H*0zcppp;={tb5*z}up&nNYE;eY z003{`_0JNVtG&50vGq+;*DykSS0ajKY&9j?^L*2s@NzhYE9 z4?$~VeS9${XVJj+#G7Gf13^$CCrts7T>EnMsNdzqqw51V6clfG#<}-6FwGmmIHGCT znlX}kl86ZjR2*XA0e6cSKwzWuiI1czUkSLsH4E$qmQbIzrpuQOC;?%E*fK@{MI0rl zD&~Gus&7ACSoxWl(|UoY(F~v{YS^q&wUX_ukrU1WqFIpMy151nYycqnZmL?}h3=VU z=klp{@uZl|iFIGt^OzDnVB?qH2&|kmhvE(yH63&eO%Uz|g$s1C!u770I~H|aX!5OE zb>$zeGCIEY2ean;M$axGj0EvLp`h}D*EdwZGrDSG*;Qe|cW5a&-tE{dD1#5?wU}U+ zxXgP-P~(Y8J17>}nx@?O>JTn)wcLCUReEx(g}{EP`1Xq#4fUsaygFVhN>a&#nq{Up zJQd)CnIBpDk#v()qhYdkP5REtFrSwX;3uR@di7YC2J94;0jR9wh5<=eUhnA!ve%-_ zI{bTa65{*^!f9$+tEd(H^xR5vJupw_4`lCI-AnXdaX& zP$Ju;hm#gQLFh?u)P)WJFqr7~hIYLVUU7@mIG>*7yW-J?l9w-&`&vF6#4w$dYz}Ov zB(8)x&_wFT6b*VB zc1cr}bImN;+Bh2fFy3(3>Vwq)kogy%Gd#v^*o0|VORfXyiaOhDJ+n*zVW@z4rI*W# zv5Y&BF5lFfjIj^I2v1mdrvM{w1H{o;Xlv@_fm0t9qKVgsvLQ_;j46O*Lqe{*y zmSq8e3P3Nqy|*iYpLFo?m#NYV2v;b}&`?;A*EQNtH%C~K84jeeoBjlq!~8%i!xxP7 zXb6dbrubI_b5m)@(t#IxHM<)Ig~YnL?|xJRUI~Zu)ay;(mc>;9)F9gzn-MsuCR+Ap zjyTIT>Av2eLR;GKY2ry87&LwBwe{6V0>hO@xhf0`OL(V>V@W@YSa>n zG$!Dk_1O=!Q{!Bmy!#Q9%}Dz_EI`%-*ig=Xy`N2r0gxxFBJj0xBHrFE;t-RAh+dYn zyIjedjZE5BqulQr9JW(h9*&!;HistBHBDf~Buk>V*dzvr-yjr-`0BkfP&p=9P}5-1 zAiW#bVCDUZedsy7LbAt1f-+-Hxv=rslJAG>#rTT`i?2EZzdt+KKeV!hqEzx@#?Q8_ z5bj*!O^T+xQ08hZ0ac%ql!K*skX4pBK6WWf88Kvu=i(O71}!X`t_^JG6G8f@bIBF} zQP$Od&$v$@Mo zVPQAB!}GBjU?1m}yZ7hLpX6B^i`3G@A6o$)(c{ZJfZQGt5@n=CsA|pEKC;<0U1#|z zA35(Mj|SGQ>&;SwJUMS-nVz05x#qZ`vZ82DQrIE4o%B+ssMh>ZC&aSxNOySHwdQh6 z0OgV(lh->^&+vvuj-Hw?X;eL45}XB9U_1RHR@EB6I0u!?W}} zp9QE#r;vMb2oBm9a?7S6%-eMcl-aJkX-aw0(UH^c0Q0cvC%1>o%i;#xiBb{>MV*L? zD389ojVo1V$EB;`R+}q5T62aS`Yl9IQQ|f;TwVM467T=o%+r3xeI1lH%{9nSe&l40 z=1+p`{7RM$AJGTYV@xCUq&)8*Vlp9rjeh?a$UWA$%`7A@*xgoJ7={9cAQib2P{jmg zB-+sOR3Pd84UG%BT+~4VZZ+L+zKxf6j@<{1hQHqfGRqMA;d^zQ@NVAr;4Wr_fdC-% zAB`JlBvkwo1Hu5I;i*sowQ-R^ zOt3j=1Riu_0-wuK^IVl&Vf+smg#Hs@j8-$3|;LO2+^m=J3fkig6C~-ZZW} z*t=D=iSWA`Ct5!F+SMb0Ohz*L@u=Vy!x4VtlH-fZkbiAjnw}j1)w_s|p8)4x(VXok zTV9MM!@X1U+f)Lkl%uU`^C)&^F%av2Dl)1cbNA%D+RRiSf znCaIAgO@fSp;G%wT6ipPLWp;YlGj@_wn=i2*x0Hj2hlQ25BZuf9-c`K3}!VNU6fO# zbdLm++pjQ=&t#XFeSO3M66MA&sJ$(6bTMEMR)ejg7U8FqELOSjF}mOw zRb9Aui&ezA-M}+gk)Y0`#^y5(9G$L)cQgm?rX@w3n~qXeSny(On=mMUGuLuvf6PvN z!?C?UU!FJA9zSSsra2#dSfC5DxYT=kH#O$4thf9f{-@!c7#9G(rSwAWAl_k687PhG zR@SO+mU3vaeF-(dT~j;qz^s*YqdiQ}y}WA9Jy-3kiG6kvzAl(epTEBqkC-vWs?M=v zEP!mMSI$e%i*#50vQvEGd7H+t3s8l}c0&>ij9ldTHymR}FMS#xF8stOUpc!`=z|O# zMyM7YV;aEV3P4kdfcrR9Ys?InM6XY0F7ZVhoG7b~p{fO~55}!R+1wl78;shVyPhtF zfm*MYYSY5BKDvDR8!6?%0o68RD7*%cmTt0fQ33qjdXs*2L?Vb)n=@sU@BIY*K+nfs z8KVo2G5LW9^S$fn0VPJXaqoK-8^9V6bm!XRy+Kn}_ZxF(2oW=P^RL>~7kAFGXnI6? z61bIQnVUq3^=Bi*MItCI>5i9;N7Y)bjCd5kCya~j&mf5IrAyADG7f%wx~Gd(%M zKb@Cb%AumaoNj}qB-+&(z2Ood(XQJ z8j4Vsad93En8rh~@5!^E!rw>$$_b|~jy4Y0!H%=99&;H*t;G8uEUW~0m_U!x1vRm%`>kbloNoKSgq)Kj{a_Rz z_%5e%Ct*RyOWhc5S%&&(@b2r6pr$>^yLAE(< zLI{9T%_PhAtg{Kfk3spvJN1ff*_#QWg_eqw5Dd5mT!&?9XIeGhUvjmJI|8T7p&7kY(u{w{P5r8$oDKyz7RBKPpLH%>p5 zkF(-gP(Kq%NR>A9Gm#^J%3J0C1>Kqq+RR}hMHPw)4V}rWg=0hgjwPnmb*#oGH;%pS zpAG!3L=fT*4lJ~^xRUizU+mgjKgR;BRPXJ`le00^%WnZ7RY5vF-{YaeAknd$N`n(oT`ZvV^!h0M`mb^bgSy2xWLTp=`xfOwx;U}n^og3 z&Zo=d4uz$L%Ux*10f{m!8QcUgdt4$rvJGm$ta@WZh}kHi6Pc+y9|EEhA352dAFkjX z;%NmRA>b7yRkMydJ=uBn#~N2U^u!E4q|8|f?NLewQMx^ zYauRylcJvS)xGP%VtJ zxQsU6k9S-YZON)P4$waj3cinGAW&YbiA5ML)z@cuTpG_JY{E7}0$yU^Mui`6@)P4? zhn{%68RF;ha^3CV`0`x3ucHa><_@qTg=T7gkz)1n&s6jr28r#1BRIEwk^XlKM2(?v zpU7HeZv>h;;-f9d@?7RY!g4a4rTW>5fL^08d1z9`Ll#tDtDZH?RW7ypf#x(-yf+vm zJ*+h~>6Ufa@SFkY;|aEpy8dS`fY1XQpX+3NQ|pUxkSuL-M%la+6)o37%w3M;dwP&L z_6yk&>S^dpg8FQ99Pbwpr1a_&!7!t%BWzkp+`6k604XPN^}ejahm!t9M`*f zn!pClbWWQ_C@Z)U{Q;nlFd>lQXaE@h_zaKqzV$`F13(VqZI+Ve{cI)PJ;=}S*!6LSI+exj0ovShX#3bGCoFN${94fMb*B5%)%0c zo5)C2YmWmIFr(!P%q&{}XP7Gqv}-G6f-cOh>z5g1LdV5lv3tV=vG>7P`|v;%vj6CetNnv`wZ&5)KzNqMWHQJfs1Or<*7@J<}O$;eq)KGmbz>%`aX2n|#q16G{6N;d0!#5cV^KhmSY zIN{azB(op={m2csL+n8Ds1=7iw4c!|s=bLa8O_~4nJPk7>>;GxVDRsoecvfS#tW<}!}N@MT33QXfZ zuR0$zIg&XUjYVdc3|*jnQI?B022i=(b>UXQOCYFX^x$8q9m2f_f8D|9Ms-fuMJ(HZrE@;qs zb~Zd^g)SuwZhF5%QK!1Y?C{Kp`cQm!ALPHh;lKkjKPbhGauG`5Ll1;=E4Ls;JY@q- zX@=S%HM5Q2%+g%uIn0i>FJ1Ui67sxXq=RZeg{?1rCO8aQXkgbC&hq9HZ?alp$H7zb z1w{bU71oczW`5C!eFAYWH_E5FgYBVjAq9eJ?e$c`mVmAQ5+`z#e3%J-eY9AQ!8oTs z+YAT)Us*jmzk7FXct@h-XI+5{ybfHTEC1S)d67LQC0#V((@DP5>1lcy`!4WE>j?#S zotzo3INRANn@Mds^R}~*Om`xo_r#I+9Eru7tNj>`xjqbqgrTUbf1CuNhw9f{Aw(K5 zoDVXhBul0%(eM zTXm@dF=no>KMc-VQU<%Nq~I!(0;guJD68{2LH#4x+J9Ww+>pR}ki#5a(uK+OpS7RK z`EFWinA=IgQZ}*apq||7xmdZD9|TPx)cx%CbCTkbJ`@YqZ&ZUGhn7Z3JR4PhYjN2( zv}L@r*C+PACUcl36wjbkPf*{plAL&Lz32v8XDtDCEo-h!qNmPoR>HUf&|nY?8eQU} z!fn1ftx5!awu<_3Cjo>nM?Mr8Hn|QuExD%cWGO~Gl&BAUIr`w>lP>0Yr?a;<5=EMm zdp`Z-n^!JS`H|{XX-=hbOJWk(m@6>RZ<#uw$>zEW4psLr^qTLZBZE4zeq>KvO|X); zBf%i+qhXtyi*E6?+zb-vgbXY61SF5&;CB6Te3sQ}tW7L|@PRXOc>&DwzSD0F3G9F7 z`RYe?D=5)UH^Yqlr+ASS%HNUQq7S@9>+Vqlx zdP=KX&NiRR(qF9P0*S_ii<3*Rjd78YeIgbNP=Mlfl}fcG?WpWrX=?1l96!0W;Rlf$ zSH(efd&p2~7LtFR%;Rh`E>#$i%};-``|i%1DGf@5&?Hdh;3^;W2IR=}$IcH*#sm&u zJDzNxb(I}cnr!V&0pVvn1*Ey^656;DO`0HX(EOB6idxcM*?7e66l?CcSf`>1bu@LI z)|cUt7R@r^EA`3+zc|XZNGo;lJ9{Q4TPNtMgu0&b3}Thyg2q+mFc>3tmpz^9%^dqH z&-n~@;x06RyKwP+J*tz;crG@}|9ZF{Omqftuc~o4wG#0az`KTuyR>u%?Up%!vSogq zyl;Mnr!)~mryXn&YUThHhL|HcJ-#0=)6gYWfb^D11y~ ztbvJxy!<<6OjN-O=t1qrJDyvUGYcLs+_37 z2ObK@{Nm@!aLGhy)F+)~G{($lD&1G{!*{4d2#UVic(u<2-RvK90;P)d87sbSx?&S3 zLxdn`#195@gR*iP^g8yI+3`}_ff<||C_UpKn_Uf(5iMG0W$imzH#jrnq3DU2*T9va z%#~3LJt8AOsm2=KZ!jepq`|u@zqE+`d6{j;>q@^?P>a5yo^OwW>e=a@8Q%$4Q~Xj- z*K}3h9-H=j!HN7s5SK?|4`oas0s?N#G$Dm2p5CTUh#Qw0(p7d)#^TXF zZt>BQ_L(US3uH*+lSBMKca7K)3#SNz)gL&IX0W~J3O|@k4m`av?39gQ&nIYmZ0DIs ziU4#d&zb+^P%ranYc?Ch)sM)D5tNkHP&h?Ow-0I!x(^*nXS7DPxkTyiwI8+HcJ3*U z!Q43~|0>nLz~SFB0X?Ix6Q%B?1}J++!6%mFUC10T zyuVGU?k*`K%Pl5bEYpT)$#Ny}jb{EYHHuE1;pBY7q}HMyH8t#!;$M`yb$8#`gDpz! zdm6ZSw;{FQwqMtO#PA63zWhspHAlckhF=WdJ^SRu*6Wc@&~AhOoZ(KI#nG%()RCwE zWJdpOsY|Ncv%Pj;<->nYDdpCXyRv}a;>uu@d_9f|3?@&k&6RJlrDE|A=aIjKJ-nqHRigU?9V0OCasCvj+Btz_v^^9sF1T)k&>Jycj=iX-~M$(m0#^!jjc~9Y5yaX z3K>pxG6V+q+FuN3|5|*hc*~#Er2Hdt+mOP4r$P)kN`b#rV@*<6_3G9$F8ni;;%v?F zfGW6q|6(}HkTUnSZAHS5va5&d?tz;eE$ffjubi{%><(7)>_Y>y{)rMYcJCfAh_@o3 zbzbFsJUm|a_E*Sif&8O<<*eHFhK-PIYxVg*wN{bdL(hPvsVCru4o7y46pjm@!MQrj`!Cow48niM%| z?*6}vd=xE=c)aBwA@-JVfJJyhe+h4>s?~ASwzblNqO0(>h(+E1Wf%#2M>{91`K)@r zdSm?@OTQ!Fx((7+?U|!mv^7IfIc#0z`L|k^0PM?Os}gNBQqIYN&579;kwB1#-nQ*z zt4kq2h+XY9+v3%c@`nW!v0z+2yY-C+aE!2HbS8++mGNpqd8316lusbF3a5j%Dd+aK zGZ_EXlr;o)3PZz@5i*t?x!83rT44uUsKA~-@mnsF+%NVW&>sFe@@5j6nP5K4VsZvD zpEY13g2|k(*f9%PTz8}(c&}Nv=iNWoC?4Nl^Cz>P2^^bv+h=0IS!=Mi06F088o~uRnYNJRkJ&6tV3M ze94^)Kzv#SY1wvCzooYTb1py1zqDP*lRK=|oEJ+^R_!NDx?aMj1X!doLY)}lpj;4|8S z3pF&1V^BG-Y<}?mU&jjzXC`eEwB{=P_L@V@Pavd|Ogn6{?F4@B4z?$NY%%jZ7BCxL z9r-*Nsd?e2RlNq`^JpLY=u)ylhxqumH*+}V-=#U8-;3xvp!rVCtykMHY7g0y%t#W zeQyisSu_Vjh)w=ET}byc55R)Nk?+-Bdw&tWP=tr4boADLkmo3`?)4vu z8@)P1-_@SxUrdxSq&Se%Nw zm9|ZuLi%&tufXHXyO9a>hp$arFZKQ0_v-=!v|!mUv-H*J_g_F7nEKLW2T>2xdtRVy zoJT6?Z_&{JOTA6AM#$kQHFW9m5=g$6r#+G0R$(UqGWjf%83 zEaW>+{Q%tO4ntR;;4kHmWq3(J$$mjLJsFZcY94BPbSG=Qj<|xr_%Vs9aj2a>E77|5 zElcFvB`~Ec1FfxC0!uE!h&Ns8cokAqLAxjI)-nS>ur5W2kS&2WkFf5wdYq#h`AX$* zYcy>*l93>WR}ZWKeXTKAP>d#mF_RYvfciI%COLoO2m6HOLlX`w(=Y4t zq~|g(GztA$DBONE#Zsidr?&CP0Pql@m%I-nw{`k=Al)OEA#yFe`ttP)U8Qhy{$pW& z%^0jO+U6+D?nt9OtTsSl9){M4)2mN!ydPLU@z-MYl?&qPRx#JVsFgW|UQQn0!TQ4^ zXTXulKaq`d?ey@A&H2H!v6Y=-Xt8M`$4Kf-VJDvy8>tI z%M0QTqcOKIT4iSYd;`YAcksqb(18oD8u8kDE6+9OqjX`gXzUp@1CREedh~&-#!QYu zp*0`&+CHvFbK*lTT5UfPsX0^gA3tlblZP8}t0Hwlr>%9g zwSdMRIto~0FHe8C*eC0Pc(nU)n@Dp`TtJUjVgNy(t0`LL9o-x1@kJDtHuS&jdViC; z2QA4w+@t=*Wm{o?CqqoJ0&kY(-(HWml@a_Iqtw6{);9WJ@_vfji!p!4$88=G&wJS$ z^Jg!>tvvIubAR7tD;`Eou09{8r5pEKrVF|i*kKy`LHai1)nCBmpO=J~tE5_k?NOR` zX#|e@cP7}y9zxOBB+@k}}z6ak^_B(2^{X15t0UHhE%^v=J>EvWyAUb#D zhyngLZw5Z75FPj7J?nqr#kLH`R)BA{4z@+@;9J2^=Lg;Rxqm?!7Qh8P0Ac<%)xg$g zK(>k*LCL>;4cT~Tfl$=wGo-5aJ5smxJG(*nHKOo+@b9u`p$;SYJF0WNvHTZQ_}6Sf z-eLvudMqle^6%=m52D-t4dw{>zuo))_jd8!fNo*6S8hTzfd6_4B$6HoNX_Kn?=SyQ z4+G9Oaw#k7?@vwH09@$y*Ad(S`pgHopvDvMFNz)QkHAZdkmEaO4zh3pFKugW)&1}9 z1f;nP6zkis4d1`R))XB0)@tJS{r`<*;8XPm;9K=;KZJh2pYaGQc<1ABl`ntaeqVEH zFW|u`IZ5x|&n0<5COPutqImD$=>|5EBFxz{8jef+3nKjeEzsXsz-iSDI57W*wYLt4 za&6*<1r`KEK~xl}RY^%n>9t4!m0nVTr9-;QIv9X7qJSbO-5?DHAxn32q+3810fBe+ z#B<<09N*`>-}jHQb>H`OU31Mf^PAtyOr)s&_fIwt!(P}rUvl7|r0c)nb3oUR(6Fs9 za{f^%e#aM35AXtVD!%@IHzWMUVHt!)>`DH(|M0fag4A$gQtN{t$}+uYYQz@|)s4fi z5Fb8pk7|D;JpGpa^g|>=P}f4(P&hV>6+JwvoZl>WNzIf8P7N7uiS{Q2#Fp2%HeX=SM- zdNdW1sJq9*_<2%+PA?q)zVj>0T4| z`+KMs{8GKT{oIUYj|o6IlYiYrJ2M_f-`nG!Ke?(h8Az2fgR-)6 zvFAem<5h!$2qm(jf@EJvo!R3%cUdY|EpN)-IJCzwe)jCHFY z|H&2pdx(Cs)Uf)qVvKovNqD>&8LWPbn0_A3Pp(R?9q-IcJ;fAonK9_{X(%-PwCAbZ zXp9_l4hwZaRE6tJh9lMcjC{{ko-m}~BRN6zn4lVk3nW;h*j_1b`nJ@wl`Y5I%1a&4 z&Nb?BC`A?-NsP6;#j_e-zNd6h6~H#X$F1P@*Bi1O6*oK+9M{$_f zuLmmG}GZHOD`zSM07oDRH5d2(JLML_?^(zR&tzXww#rIflR0|Ev@hh(%W|Dh+ z`lo=rz8>$!OdYM9C9AyOBdUVSNYcaf>qxhq)o%m;{SnyH&hZIR2hc}XZyb6kgN#F9 zm(RzoD;w-3EmWjuK?E-l*Zpi;i?Z2WhMS_0e14UGA1Fb!uQkPESQ#bz`S}NjP6cZd zFlu4bMDq8V-q8q{-LcNa*CPKlsef$&s%yi-eMH;iyf3vH#ZQvfn!2uWZ3DafvUDFM{rPJQK-S4v-B&H?-!G7b^hH?^j*CX1 zIY#$7+fYbpP;T7PLE>dHyVUH?d+Z~)WLP1`%-`YKERA~SY0VbSV<3Pu-O{~ksEhi&ODVf8Hx2*M^MRe8OCY`I0O^!E%jWW zy>gjde{y>Hl^#3KPaWX7uoPS&1|dm<_NS$-ES!G& zOTQw_gs%_5%#UpS%?akc6f%rLYbaGa^OygaJ$o&b8%uKoH`RBj!+HaEqJwN_k(N(fG zpQR3%6=a%T=qt?ZEpf3Ojwc}BsRaG{4+nePjg|CxMyXR*+^xO_Qa6C{z&>>R{j0{Pot!N&>rUpf8s35M@0FpERP4dFgW)hR|9QU|5|HmS!2J4;yaSXG`yj*E zOPiURV>s{t0pbgJ)P!>X$Jw1<-0`SNa6Skg(%3EByOch%i})cZICBi2U8a7SJ+Fcv zP0{X)#>FbPVG4AfXkz?cZdlP{lwViYRO|dd#_$4{-*tE-S>BHlfTWjC?{}E zNNhS%!h6d+TzUzK*-z|vYJ|Ot;Y8z$>F*;!B248WEBc}yB3EjtNO=rn1*#NZBX$ko z&t1GEi$4n|wAxhn{P?#iSkjLN<)&>!Nh&oNf2Y0r37rG4*xv_CJgWcd!X1)vBCR11 zf)F>KRpNbw^MvDTUt%Ao|7{$9yc}i)nX)-+b?MKC`R@sbWA$A-BL&xjX;bVA9FpMd zZb?2Cb1BnTU;ED#A${<6zfYi$nHeQfs3}mQQhMOACqErcWLt^h01BSgzeP-cto5oA85c zI&^;ECxbH}mgy$)Zvw!-|A|bz>CR;dzU?Q_B+=$cW$9Wz=-Fb6_(B>rA^-gK?4IWV z=z5SF3M!4gh55IUB1MS3v-TtK#l&eTsp2p0oTXYlKMvKTD9T&u4GlV+?)Okg(0pWS zC!+VfUabIL^W_pLyX^V#Z;M?k>z9Nx9OgIq{C1$kWx|G;P;#eS`8_^hHB_!wS9X7M z@C=w6bv1N+>yJ@T<(EDnG)!;jO#G$R3`xIkJ|lR4cBc^hO+AjrRw6ept>HPe0*v&i zdpj=_yg|qy=E%oXU3_YCPJKSL<%1`6)=gas*O^C)NczzwPqm$uAf}aAy32 z)&c)Pt78{M-ctMJk^TQN%I{S$%GDvCxPk{U9J|!(lIAevxC${x2Y-O$@&1d3}g_uUo5g%zq|9R_qej$ zmNCmW(;6<=7LXSyss*9m65>1@2>tKqGt};7kOn^>9CvAUlS4)R^HxE@>6K^j%iVQB zfqOeot$l>Tepy6})>oEk{7&;y;ntqc7+{*E_ZS%gf`VXf?YI$B>Rzk+=X=l#%&dZn zV@c&&+b$hgi^kt3w;(}~!tW^Jy_B^57rFyteme*L=Ow@vgZpgv$OY{6>7VZ%WgwV4 zewsrf_bSbPEKH>kCZS$-3kxMwz@#$&rfu&(JWAG z{E+J_Bn2+>9`^>|<72sP|Eivjb3us4ZZZAak``gQFM~QC@i9mspqm)e6 zKhcc@()b0r==Ci6{ch=q!9PI3s|4FfE^X?PiktThRoON=@zqee7f&O#K5d0P3=&RZij5mtVIonCVBbX;v?b!>5YpCP0f zBi2)>pQ@3Lzj>7JFzPrF|6Vu_k}3dZ-uS-Z{axPD-yU)_#TR$r>8!`)=QKMP2bDqk zS{(WP)gzvV14C3)&j%8q?rM1e11Ifq1mXzQ^HhW4X5L+!^pEr9F`3zrC?-wg>_6BW zzyF4xJ$~~da|sje8>gK@a4n3u^)Qv^r(>FCtAadEA8{&iQj*p9k_4X$6k~x$Bv@eE zn`b@^RTwnXQ#I5-Jv^q`k)r-+&cS0Dx?80}>F4WC3xj$>*1c-@gxM6wsn!&$o}3it zx!x4`!E~=>raF}Ta;Ts0#({%vVLb!hRfJ4$SAs01)7Pr~sY_$^sW%c8lAj4#ri=th z>mQ`$znrd9sH_-gX3~>mG7SZXAK{Ah%iL3LeR`O3Ie6|CI6(qp3V5`#Wus9K z4Z1S)I*fuOlR7i>EHO@cK9EqBC-s<4geStLCXitonnr2r6+2!B)AdQ?4Q``&>I#x}4|cjjzXa(YSt&OXA8JHMX0GY` zTW%uaXn6G{G%$rW1Fx(@kr*;Ap?blt`f$!SkOQ=RdHLhU!kakn8&C_$`TbJb63cmX ztD<3M7d5Y)NGL&7iSyizOAijIhjVJ;I;5kouR|L54V?n3#c8zTMw)hR-cl^22v6d` z;+7!_|d zIWFmAw4_$rRr8n9i;W-4=~3^qvd*n|nBDEl&3}J(iUsKjd!}gw^(Vs5OcbuuGP1PSfr3D+@!?#riKV z5(}9%BlE$qG?V0?nGa!6YzIbC;;b99ZG8l{Wa>L8tZOu;h$cIP?`G2upj(2mv!1rF zP5)ct@jgiFyu@HvNq}C5dLUi-Ruz6FHzGTv-SB6gUVX0cI=5!4B42iy6&WETpP?@r zI@o-Br)8pGz!G2TxweE}$IbQW$kS&+e}I4pjs6&6>yrZ-nfj6|kkEaZ=&p!$?`!C~ z_Q32~fzI&vN9ms%A=*ciZ#mf6sLubM<;hNQVf7N zvJj*#($qP8Ymu$_9J$Yo?5)son7k=+Qhc8xBkQoO`g8aU#|DhW4D~nNB6|~Vd@-Om ziP;+CO>votp*`M-v0#3raO)Ik)zN2y0!@ujAxvwy^7-7BxyVA=Q8$9+?>Y1I%Tb2! z|3bibVbK7HM;XP}`nTx(D*RJc!nGri0@L<3WVZ#1}ana9$) zH?O5v*m+hz|o_(cI@M` zAC==a$i+1Dhg>nm6fk+X8B}vznnX*IeoT{oacoLw5#Ac1?$$qi4;f=w0Lc%T)XAFVstNvkFA6^kb~Yt__L2 zN)Wm49ZKX9rq3VhKSJ6!=IP4}UW0Pol5LBD;(XIJ4C?D>U8rPRuS+dOjk76PvruG_ z!-R!7I^QA@H``;xs%T!uN96y2k||?l26Vhi3MCA`ZAlswci;~U$}WJKB@DYYV>$&^ ziN=oe`0?`X5<3=%px$hK-Q%;XL3MgvxP0el8^A9fEZwlY zH&3;9TcsC|+L8GlaFjL@<~BoRAv}^C)^L5c`5T!L+&b0UJ-1CHd2 zK@oZCjrmEBXrV&)m1%S_k6tmmxj}Ox4AEnCK7C~h>If>Qi1VxFcs<6=bTvI4q9C>D z%}YM>r0f1nW`#bd&un)#`i95A#^8Q2>DuQ`guRPR#hopC5eR;E>;O$5?RYbzTt}=7 z2JqP(11G(XciwW%FA({I;x(q3vfKpFOilHTvigVn2URyWRyB|7yS@~IZQGIjCN^c$ zvMb|-^Y)ks^4-;F{_@^a0miI1OB~{)ymXhPpf?m+tWFgQ5Oow-_nAq9ee=9Et?C{v zl_#{`F!OpQXdYrYR3;1+l48(Xa14ltfb_$eXa9P!m(Ok(mHy+LQMH-;T#fb6M%wm8 zKN41!c!urQ_946Ai5-u>OTq6P7ksenXEbMSyc^s0qawy`1jV};W7_-?2(}}RmK_^l zikyuOFNlw?r1-X+KMx}VY19ZOGuR|SC|j`!y0C+m<*P>mG@e)xP$7+|G|yU%X0pt-{3opuU=Zf+d>C8M(pAhsS4rphn}{R zf7?(0!%I{(ao+wLMnnc{r5-1-Zii39aEa|~Zs8O!|8clfc7 z=~KmH79*UIVloE*<8<$sef~4?lEKriz0n7EX%UnhXvti^d3P*^IQrE2Xl>VuwQ)N2 z>|0mn^i$xtYw5ZDMkOu-tozggn}HPE{6MPEB6v0(OU9Q_Ssj&7u`U^QytH-b4owVJlZ|FYR?!+nS0fYvMt5(5Jv46(tA&Jjg+58_s4x>BLc zg8a%=cE+;FK=>T_>y%hlhu{)ksrI|#4O;k2wK``?W2~z`yCz-nCo!Pbbb!cVN-rS z$zBZF3wlE_r$4c+*epo!S`;pY5`^e2@U}!lVrst5<~BL+-p?PTr2Csr7SO!%b^dW6 zn?dc#KRy57PTRj;Ub~DJ|NK4F@o#oBnw8KWjvJym#%bssCK&T;5l`-X@4<%(AT}?z zHa9Hiq@kN@nqGF-dkRwFJ`t<#EUl6sr9}`%%ioeWz~1v6KE2)`>nx~4XVBBajNTKW z`{_ep3q!yIHavKtExXHmd{3RV|HHfo)8t^Cl_oqT6sbN2PYFkx2t4IrzNIF&Ei~#J z%rSX%_WG;KX_U}*?rlOQ?9U%CkJY`bBQuW$8tw9U2k*D3NbA+xHV$*T0mAM0dE5hI z?Kvh+vbp<)|I2Qb(+4pT8vM{QyEAY=fbb_By@mP;iC?piM)8)0zxk(ES%m)J47uR< z+zQO?Tktp6Eh@s_f`gy!QA=|0q*jd4Z;uP@T9UtfdQ{V^dF@&}gyrcibxK7-GQi@` zF1^tRHX*$>DXH?7;(q&&h+89^kEMU1;tc;;?EkOT-}RTETm6LmUCe!w1;${Bu>jRa$*MbMmrR_q2!JWYk7Cus7WF@Pl-H6 z!YxMw5EZXHF^zO|;>YUg4**bP%mo#mzL0D3IV@mI63#e=Iyf0(a@P*g@_)P@;dN)o zUfgN=sAb%@+mp>NaknIf6vgT<>#InvsCDHb5EBh9EK`$jg{xby6PWCYzU>;`-}m`w zfiDh~GIONKYIg|tB30IY$j@V%w5hiWL3H=dXyutbjlQg-!ZPU$PF#vw@{MeF=6B9p zKi1GixNyKkILMxdJA-CYiMgkNc^z(evydgcKwdO}(4VCN8ZI$dR$%XnyMHq)WIbPi zFM6Ks*&63DUsUt7+IDyzT*|cY4iHyaZQMcc`fy)skIG#7R9XQ{_apmKn6cus0KKG1 zh8TRltwZ{|e2#aYI54svxe)d5m2RypUgs9>kL}qVCBA#gkh1gO8DyiCY9x=aF;88=HCDiU3D>r@Y=3)LsW1Kl z(F%N$jQ6YSJ-YNItq zjAoqbf>LU?gmu;q_UpZ~d#MqNU{&;8#IsS#zkfLZ*8bhMk?MX!_AHx_w(>GuFUMHk z3Cf|R;#;Jhvy7HR`+KlhgCU#ujfjLIE5)gln(BFwLCoDwQ|ssVG|m$5L>Ygobp9ha zqfhWcGGcD}U%o9KqMUjY*Ew&CU1tvNDt~>_k&~c0{H(ftJBz?pXR4-3IESiCpJqB* zDBrj)#H?eStE5$i!?I!%_lSgBXHGHS+MCcnG4SQ32Nu?X>9e`B&o;=($=k8f0_jN> znchS$EJy&bif{KJ{i-^@6zau~2<^Cwt8qT$Z- zp!axjlNg~`#@}bRGTk9LlQV5SSXzVzb0aO8pC}X2j^3Ed1PA^}qM{2bOO07zo0a@? zexb@>p?RAOxY%5s%F9apekFiM7MmJow1-=uvhvKEVkM`co3t8WrB3<68}J{ukmq;1 zT=76BLVuzcIcu>!^pDo&FKq7u#{MUxBjhNU=uQ%ISdu?YkKc|GBr|~ksX(2_aasF9 z47knm_=egkH$U80z}yM1L`UZr!XPZLQRmPRYIkhXF9Mh#;sj-#QjVxdT(9G*WKoQG z-06Y`QW+)P-;y0+eOuchvoXWsT8jb zT#I(dCl&v+ZKz?1KPZx+R4$8#Ud|YrRs=AlShsOnCqMz;;+u7xL|S#Uy_P?+g6}la zavQ&m(Ar*K;I4U9p2Y)hLiB# zSqS}AMKWr$#d~dsIHf0C_`CMqDSCTvMQvWNb0_nb#CW3|L?beheBP$52n=P3z{R}c@8b)G_AIR6=-@3QjiQ=Q^r8{ z@rjq!K}?zDKb92p!MF5$9e`WI!^e0J06e-P}@SbTs$ z73x!kxIeK!Mp{R4NTX)wgVPdkdlNqVj&S<%n+K#Wmi1q?B9cLge@ZAP4sc_O;fWOw&JF>LT+0h5w zyzo3H@VN0HDo0`aY(;w)z~^E0x%_y%rG?Vc;A|%Ks0S3qP6jYt{PPOG1>mrPO@Kc= zR|s#BfP$tG3FW-y-``&!1Ua6Uo9M`h@2iJU;aeX(ptXLS8$Bu)`I&@FuCTBt-P;37 zwc>t^dvIieg^~g@kphVRZxI-3<99X#VjkHXWiFPF`WADK&qus*UHsA#FY8gPHi#!R z=9WUKMpX`(`sIFyCUcXAnRzY^&xFv$Y8u#?OE>kHRLwntB|LDm*AJc)w0j4>wuoFd z*|LJ&&}2(O2b4@tI;-|}`0bE{i?LoW#{~BMy#q%g;;#DRck22B_CWFZ^XfUqb$6{f zG}59hpcBkDO2JyDd^yY-M2)B;7CKjr3*GYT(!I&vE7yE+_L47P3TTaUY?Y5yqC{6b zz6S$J1^_(;oSf9EJNr|CXJ9ZlP|}s#h!oez&`mbBiuPg@v3b65E3pi-<(S^|LcFVm zM`Zc3^aJ{P-NI=G6;kdtj6OdW@rF$Kx-)cte+#6mWaLWm3$`!pKJQp3`Q4U`)0q~l z?V5{Amr5Q7w9ntdjV+}-m?J%U#V@NV2*q|hy6sfF-krApC&TM5ubmMPU6;4FohT|M zUn{mV$|Tavgw8Vn^4%W7l5H~yfHJBnI^uWnxLwgWv)3J!`)M?M zJ{iVNM&|VYTK7S8_%jgg3~-XOI^BL%y+p}V-h{R)S zC9j5vK&H_bml7-mK8muf9?%5Ka9i9P_oaVHYpxWEfXvE=dNVnrzJm4`cMEJ!R+W{H zHxK?)DmAKz%EC5VGB_-+06Io~ak{p|eZ|5Fn%uc}ns&yS>G|Jgavdg+mGlak*`90m24iCvQD5=)?2G6g`$Owz1rF3RJqhk<-sFM#?>H3AEmnIGWk)5sbUN6Z zU`DsFY>7d^hAc|j(jnF5+g_ymU7qUS9mm?6etrcHJjY%(2W@Rv9J<$R04I>6^cUR| z1hx<#E1O8G#P>FU?i+c)N?1(u;=UAeGz@8u>kvR>h! zNUzQJ2YA)skb9z8R?w8rZBx?}TgM&Lao>LIb28XUy`gL?QnS9pW`qbyG^VRih zf|%meHn1PZS57ez`gf&iC(MpC3tD%kMc0KbtwVH8!jw3oau6cy$q<4!fSSRU7M*F@ zEe>dJn#T;{8hTLUWf~eGwgeV#c2l0do32@~)j7zv!s4`Xix?kX=?Xx7M|(&r#DVMjrsHPpBmU6*xJ20?#&Rz@ zL9_S{jxNuN`4GJO=O|d$Akorv%HtHY2n-Hsl5#ehDMN_I!ES1CP|aAy!$b#;^Qci9 z;+;r*5B2IY<>zkW(d9l#ptCi^N7bc56N`Z}m7wZFv1|6WrxM<|4Momnvd(&>p4%{KcsU_V{cpM(zs(OQ%*-6!QvV_#yyc9Q>uA z@Way7U|GpJm_*nVi7pnc2Fr0JGOOiW#KFndZ|}lcQIbZ`hHY}; zRk9%I)`gG^{{^+dd;J79OIb698+l~>XHsiYR zQU8%n{LNxQ`+?rzy7hq!Uhm8x8*3G3ov0NM$F7!2N7~%+bCIZaNXuk<9v?1l-uimd zlqD5feAbyh;XA(8V-(JtNqv{z@wUJ!9hC(5K$KrtF<{#u}>5iV4WTeWqDo}Y$z0x}aNTTB|RAK7h3CEiryth5f{l8$c zyEWHWZob+vKZ6;97DxwrUA7Q%L&dD)xR=suTT}EQS8?#<^R@yCv0sJ39tta72OzDe zF^SU;D$f6Kc+Wq#85wQB!uL^%1mY8~oM*eAX3+~=NFk`=CrT^xcH_O!1kO~f_PtCe zGJ9Hn<6jc4PR(c;Y)QAwJzqx^+D{lT zy~gT-RK<7VOYV=ec|}wX^x2ds^|1=&-V~agcZCaLw zXlE+Ig7q1PE~b=+o!xFU++h|BFqL9%YN|<`gEHZXGQzb1!h^63&jvL~me*O0Sjs=<#ldlf1?0Bf%QpWb#E2 z0t~`+-HCC?l_8MB1S`qiM$0YdTa)s#Vyp)*y^wV0B$OqnYlmSWNeBJt*y>X6>#+7}rr!!ZSp0j+P1tmq%u0lo_Hq5>J zPQF?0)u-7CL(fM<;kjV@U$cG>ihIEG9$EbclOwYpl z={}R_0gVVCbm;Z5`8Zbgnp!^0EQC|O3wlT9TfXU$T%Sxh$F{uw4fY;H`JzSa(}hh( zxz$s`*1?7j;iwi$*PX!b8E2r7(pKE zKAoIl66JS4+&F&6YZ$|uTr@yn-{9N@G~kYWyw z1l`v<*bw1sxa<(+`nia^@g^6zksX2IVLrX)Z$5GNN~i=ulOZ$rwIbwNx(`0U&|B{1 z(Vv5TF`hs9I#iiI^tIQ3Ma7&@Gq-Xt-Bn^z<7<`9`dSn2@ymCx+H8glnlnN(C*^(` zFW(#B`f{KaI3h(7-z_DP7UkY2>z>%iq9m44B^rd8H@lzjU9X zWr-CH0nevY8;99-2{u;DhBm$rv1S#%B{P$ze25+~=ly^2zeq}838mOAGU^{!F-wv^>i`p7T!^JLJDdBqI%ckAb{m+bbk?ERYBqw~xZ8ZdeHofl z5=OoQ_8MC6#=?)aWv{NtjJvRS2t;H+{TzlyrZO7)nB6ZBcaCF3$3Lu;rm%on%p1c< z8`Eh&Uo>H{f-m&1P+dI4^4Qlf+O6X`ch7S@9PqF@dpZ2#lDS}4LL=S%6er@NUw{j8 zG8(ZTHX3e`O+b^aM9`*Rixcmk;vK6xnj`1Sek|_y*q8S$6*iY&y;9;nf#z$y;5(fS z30RKm63IR^vd$&sGSjI<*QZfw_C;fgBT#IbJ^lFuCT}gpuV4&XY=ATK3Lm9Tly_o* z=zat3@Yo4G=%kqJTqiJ;npvJAsvvoXkg9+R(N$or@-F!{;Z?!6vP6&Cy(!E7Bl?M6E!l>mr6PAak zNK2)U5ZFS~st+vNu;0&; za>f7z_sIy(5~CJ@xMqj<~Y%W?8^Ia&Y z11h;qMGwwy18eb?IW!|u>42zKdg=T?Ne!;XBlIdNODFg_LK*Yn3ynlLdwjb}2^lFa zVf5;mT)h|p&DH6S`e?hM2(`etXo!tBwtS9s=<*J%OUuSB%P3lak)*^5Ptx8O5c9idFhqLWlVz)d#O0J!M}Fp(dMYT2?XJ$s$VshOeMPn(kN2?l6p zUr<1)4;UnA1GHX%{S_u~(+OMEn$e|w#-c9WUOd^Q5zA*Fpk3kS^|bu{vEZ2+X1x_y zRXz2$*DlbhE@m|7TbF(R@+hCbG(%LR-|kKXPg+lU?kVJV$ouSCXYERGGu(cT(Eh^VM1YoFQ&k;M=^9Ii+=I9XeVj zJc&FLc>cWu*K2#&HyG42#26#gM@7>a4>Vo<1xQ*A@yW2>DL`x~#tl*EM#S?+YYRjJ z5*0;L7Z%=N4j5lDgGw~Rfb~;ap_%sNghVee$_GMXMS;M#=L&l$HnNuQ^DElQX(cp0bvZFRE)i&)vmOmJ?apSpgiy zu6)rYhi(ONJAScf&ufvW`q4CtHbe?Qz2TG}zD$vvhD6nYj095otyMYHp>ejL;xBCjzh(Ruxi^ zuo|l0@QXDiG~|S!c)GHvNLd7+VgrYDS0RJKjm2faMxUvlOILvAWOlwN`DobE;s*RA^sPVaxUC?Xw5l=AQn8A;JdKCG+D1Ro*Khil+KQ zAA9E}y!jLHw9z^ywydBxU{7#H3!RVt^n>eKp^aWXScy%ivC>$iG@U=scvB<UL%?O_UyO`ZW=@7tjaP#nljplD zc`XT~;-+)e^-cf^-gdAF%)7x!G(dOw?u^!J7YemcLjMB8mc)%F|EdqpY+- z$VTOp%BU}!trl5yRu~9dV&8_!BdJDJLgF_6uZEn_rnUwl8 z`fHEg zeeeWd(oS%Yl#sQVrJbYz-Sr}R+rRZdo%l9X4U3nJZTL|1%GcOBB zIx8+d!o3PXkoM_NqXNq=o-VP5Ee~RnC-kB>ICFtxaGOXul#H|-P|*AwmTsOG0_-Ih zU9B7s#4bJSX-XjNYCs@La=!Pn`?-%h)pAmagpZhxFOvI*pBn@UeLA++7k1I}y4_uJlU6deMrOyG_K8AJuxTNF27%aiG6o;JTOYD6rlCpa zB1Aa1w-mN&<-zKw_gn0|tzeQg2=P=Ex={OcG#Kdy2VLCQM&3cz6IzOl`cTeM2pE8u zkiYfI6vW)_IC9twLYm6?>1Fbd!cD4~zJ|$J5U52L@wesB^JW4CjjL!RfflM$m`&ul z@Z*kNhZQ<3X(vdxw{P{&7|K^_xf-r2+ymu?O2ZAQ%x=Ht0@KsO4HTsKMqHOHD|9aK z8^s-qGAf(z&i=ri%)ha4jEc+e0fc;CY1n|W3d0Ic6(Gn+dGt$N-=k!68}Ugu*1791 zCRgy@;-l8i0slA9e7>L7KMq3qHQ8Grc=;ok^xqDxMSnwJan767-z7VeHqDTk3@lpI zHo<=S_zq|p=py>rr4QLfx8Y`ok1w$}3}Ez`zG%Or2_B=vv%Y)e>~5CE3#E$lZzK=o z0YVE#o(Pfu*faErM>;^betx|37Rkw8>kqC#)iIFmEG@tHt7Z5pA9iDikNK!ad@R8e zGR5&Ka)NUedR)F56CaN<@*G=M2zx?M1@`~4h0X9BxRtFxMzs!|6s*nHU6y!qoC+9u z(y4fNkaGiCT03xS3Ihef=|HtJB1Z-#9+#V>F39}39Bm+16RQ_OD6u87%shN60(2I8l%|IV z(`wCG%bRF)W%b&SoKz@5gDnEsIPK>Oppc)kQ5~3$jIM3Vj_Nu-1@RiaOH*%LfhfRh zlRGe77<5N%P!XA>%O(x27~eU0%>4k?5`=ye^A;yXNCCqxLQ9$Z1jl(nPDtskPvo*b zTbm0$9xcR!lR0$v-8t~O_{Cpt`q_~^4E9ZPwRm4u=!^`W zomogfUwFO{YF_!hk|6ow8D@C=pH^!hVe)~aW4uk~;uSw`Qgm1Qp0PlV9*ib+E!p1M zV5o5%`y761bu{w}Rto%@>C6|^;sVyMDqqj_6{cP~Bzk$K33wBju#{I-65~W{ftNRg zOYw;eZXvc1&DF2dE9BMAVHQhxjXg`dU;x<@`NhW7jjmuys=e}Ubsf{*FveUf3Bt~v zFpfTd&WF&yNo(?2OspdwstSrjcH=`dmZ1m^Xt+MqlA%WE58d54YpgP$Sbj>v ztSj9peST0OP*Qc6YPC7LU!ilHa z?!dS@A)-?3{H#W!^MEDZLH@;e_#6E}ynh_vJ+H&PHhhONZ;{gt?~GfzC}b|x&;#`S zCY-YhSI32q^+i;`nHHOy$9A?5Ob?b{3Lv2u?c@G!^6A?ijs+JwO2`&*!rL83fNpnc z$t@W)7}{slHTnQSl|;PNc2Dib>2r)Xwvz&%LoSxyo7`+DVe!XO^79yaOBoK}HqOp# zKl~_pz$oHe{covjtLTCn?dT>j57}6`bRoXVhLwz%zhjrR}p&Q@C0eG~!iE zx3=LNU#ZHxr=#7IHwRhJ*MVP5Hh|}D-7Z;cS5*<64l~?(uLU*hJ=3|VKbD)fCA~L$ z$WL_8d$Bz+8RF z+cPyvx~x5;ZLQ7P{m;THw-MN;{b|c3s2vsVu;-{I5)dW-Y>&w4`SQM2Ej+_Un1l+4 zT79BVC`~Jl1YCaBcebO^fcqBmASdiWoeJ+Vqx($|m4E$GM4^ayMu94=>lSXv*032E z>1hmaAOvQx36@5-1*9A~U_Uyagw%Z$8CUij>0j?2d93zp+PDSktH(mwo3((kZ&PiT zE|h$0Rm{&B)2h+&CwcyfQ>Xfk*Yny9R{^!+d=@>3yct@OL`y*f4zvq2ZO5cH z6BjTjaOuTTzj5_Z2p%>19q6?yVO`%W;yqSB5e>=p7DlpLS@*G4F`w-}bG$J#`6ONu z(&GZzpl@2~!w(WvY3jQrelP~lgky#6dJ;HhmQEd+215dm++x=OjcK}rhwe3k=v_9T z_RmpkpI6eIx0>iWJt7xPN`!vpCUoPCf05vp`P5?{{ZPMn(l^rI_82~sZQ@SWd(we_5O2B}!1-_Gr%Mp^Fv!03slC`~MuN6sYvUkANPHn^5lgS>p$eb0SOD8BHeN3* z;?Eb+R$d_2>PLj(#$dg`e4+OS%G@ml8B7uc$1P0iXYVaW#1oh4!iYdgF5>ZzeGGk68{u0k&6jDo3ffYMN(lwPx(M6yh~X@ywiyU@h_p z1N3a2fmdQ|$?bZ;)lHv2tDeFh-6M&;;x7zMX1A-kZ{T8#iKgKT7;IZH< zC_9Pl_SGW2Bb!_Og%%7@a?ohDw!kb&AnKW-Nh_lj`^h>Zfj&|}$->*yK5SQuvOdaQlef2z*pbA1FrZ@Z~c^*_cg(93a0i_cc zmh`|mDp^`noEgTRt=~F3QUWv?w9XbV-TOk%50>P!ydbC&cb>h5XEAhELxAs7uL%hS z8#yVywwp!-HpdnCDM{ZJep8Mi4zth%UM0=i#uj)GJP3r!3$c!0n+t7+!mf^K3EB?o za;gMgFC7CLr>nL8Ha@oU#YEoS0Lc9bRW5*H2BHB)Hr)aP*B4ZZ*}v*GqPay zCv*iv)bj#9`#9qY1ln$acyOu@Ke6fhXzV?&NCe5J33z+;$qS&|BrjBKOC{rgIVs1P z06qvu+yi@_P6+#QWlrH<#MnSADlL>g-*f~rpL!mYj$(H~oONv3jZV7`2{Xu0k|>_0Mwjl-e3z)YG2?UM^oPqlx3=>X&MkEIeR zD2_@$ldyqyo7z%BL#P$cj#1Ch6-~G07Z?Q${Nl_lz##IL#=4cF_)giZVYWjLQcO3$ zyrc03VWvP8#f3qdm)@82y^c3(aumYY42Wex{TCFCGVUI>!$fe*MC#fHB!HE${8*>8Tez^`wE$A<>=qz}3<9SDp@v5< z>oO(L#{;Ahl~HFU$xh-8t4yqF&lXDTXBXt!$yX~A7VBEj}v-|0)zTXgVB7+ihTkEZGok9|39wd~EY2m!m zL?#+H9KaMxO;W0<;;waM{R<+Z6hyPXaaeOg7eUmx^?}u@{%mWd$dNH)=Og&kCJV$W{(xRE=xez zOG|2h%!R(CniIy_K!om$xGWv>MOg6D3+G2(3ts&>!3e)nydEf>a@ukX8;Oywc^3OS z-+fpUwc#23#hRw)Pd)Ge@qMd(p@zNnA9F+y$C|xwGUV|soe6$JNDS3+MIsHpMonnG zT1l27^5e#&mpX1|aD@`s+7K{8G65NV9)}E2_3n?e*33m21kY3*zfk*X1omPq`{2naTuw%8qlo86{Ay`U+s*DF*UuE#7a2L%9GYMGS2~<5udc5v4(R{_1|C_mYzH< z-N*8ENWY*oPSE^D|Eq>&!5&DL@Wf|#m$kBq&euosb``L#ThSE0Dv9g2UY@8445nwsdN};cO z)Da?2$9R2PRhU?m!~m1@t$lva9Wsj)d*%Tsb)bJ_nNh@g^Y{Sv2Cb&X75)-)@b~Gh zqk$qC{&Be@ojU+xQ*7Z#EwZh2_0)*Y@xd|=asQXln#)8(F?yiYn+NaC#%_KqxkQL+ zK;}XnURR7rCS|ggD~&#>_{TmQI1c3T87&B#0K~DrdT!u8qruEHEgJG#ePQIRT*up$ z0Ht}|#vc`4$|&OR%PwPB+Jd-RK%`O`AR~biAu9gQ5%IljinRD3ad7f&f3Q#4@wX z1s~iK_4tKXqG`iMLohSzjq}av2c>_d4R};>EqYFQG-`lBRZpX1k=$^#PM%yE4Aj>v` z+DOt~)rheCn;$4uLXZ_dCuq8+hd@kgG)OkQqmv zkYaKLLMMIo$K`KZFs$zbOP{5)gljQE=;pN2*^n(}XgJbq6j%6ijK{kS@&k>&bk{oH z3LTNM>H;_nrGZnJVc1UGh+*TsWOd*bIlKG zU18NKl9vp4UCs=IV>16Um#?Mkl=sq4>|Bv_UjY93TZ1my@bjM<%-wa_oqR*<2wd907CT9YR{&Ut24$1oJ0_|kNaZyufP1?> znUTrGacE}3vnFV2(CDihF&5Oslr2xT*WUl!1EtgRke(5L-tjZ(!YV@ui7fyCux`a8J0fSAEJJLojqxo)s+K}U7G^;+0kc6E~_j zl*42j{lhXp;q3?Zb<|#0jbd`A3U%lY)L2u+Y0kYI8V-LDEu)Ib>R`md=y-g(Lsi{% zhd$S>;Yc#L;i*8Hx{?=yIUkPOHalX(ps(hc)4#p+V}SoG-VlI8B-YN-ee?lM*6dk% z-M=n638EPQ32v<|j0su}z-?JHcs8|bI!WQp=E8>51-UvSg9CHB4( zwlg&pnj@<3O0f8J0SkzIp{5mduU?}08kes3+Coj00&2ep<1fr>mE;5sGi#R0$xJS~ z1jemW340AJ=-jQwB}>=!ENK2%Rw1Elc*v=6`A`o7XI%-4)zaa$Vm5ncQ2I%2fB(yc zxgpGc<2?h1Pu^NB1#$DmnJ)haeO4d~NoQG5mo|!8$u)qMPM#xVb5j6#!EP$tcAFW% z-y~VwUY%#ersm|C($hOhN`(;M*W21->qCeN0|RqJZLKr@%E&P)uM701xh9EEe@!$b zgYufs%dXa)9ia&8#kHvL#b{pR7GAsYvX*b3zgaBy#Kg8XIgdB342bJ=r)#R7zxPQ* zYMT~^H?z?O0Ep9@k+e7V%W;B*)3@e|jUUrJK-j}d)5M(c_H{3=6ic{s zi|!Q8I?pLFj=eIRN(I%sSp{IjZ!z+zSogKaduc{OT>q-Kp;AQk9-Wrx^lhLba`AY@ z%46T;A~jff!j>wFCO(q~!Up>40v&tie2$t!#4;V3y2A7xEjo^e*2n%0$MWZh7 zL6?H64}+M{u#I3`2PbIqG;Q_Ah1gS9S!DUKT)I8YvBJ7o=+bCt7z?@TO1lrb?QH1k z8a}lA`9DBYu7yXfU^zzBjJl*-hQ_a}HH8r%Zf3d#XXb?Ms}kXMP~I@oBiWVm>ng0jDt=x44o8m(*JsT^SnQKSRj zncfwiZ!0{558kNALM-b9Ht%<)A!ziaf=pIx*Eo>E)p<<#PQZZ)a1~j-l$!V4fV&gg zAdL7QR+K92&XG+M-y(-^fcGA*8<`pEy8MosM8yXZan{z+fknWBhU-rI=non#}hr zejMpDVBM6Qa5FLi!8G3bLLqxWB_~b(m1p1q;cT+C%InD|2=)oUmb%!-i0W5u z8EsIbp9)KL*DGbsIlF|k?PP_w?$NujdI%I~0+MsmLko&PB}7UJHhTo8nv6ql3zvo$ zKR-NStVo)y1oVIo#>A-CRwa`RO900AsV8jB{E8B$5G8a})Ex*{p<@pcvgo{7X00N2 z>~f;iMUUGpLSMi`AV|fR%l~)_w%sLq+Fg&=s_u(z*9x!-q;3Q)--jw#jyyBkP*TtG zlULeZK9G~!gHn$k^%wnWCIE|1%fN&y9ssKZM4xOA>WUP^ME1=VxAK62vZDG&B^1#| znPs_+FVq_|p!i6Gv&7b!Yux%l>PtLUQ^yc!IkJ`Py3juy{sGxX`FD<=qYc!(hYA_WXfAW)QbY-)xXc6!#iQoZIy= zI?g?M?;Yy6=HndY%d~&r9To0teXh(#0$l$x3r}D?o~xNYJAp#4!C{@vFrU zLuhAbmGo|Ft`^pr;Oy^yiYix)tzYm86*~18Gm4uxy;#>BLU0J4Ub@iI$wl|+FK^*%Sd`%FH8 z`$J&d7qqWARq^Ss;HlJyJOP$+@e%{-r?m`UpwV9TNA%kLitxpP>Fd2dzodTks7=?i zBQic|`#))ae*&#YV8WB8WK|!EM@5Co;hTGA$zx}v9@5F{&)mBm>D>5K?vKCfaTmS% zs6aqxP2nCjo=Nw_WBJ=tXC&OWkAC=Av-h)4J%)$Cn@I7|`t=v%0&rKi@-B|MbN$m` zIpkry|8jSD&qvJtnix-1Q!l_!J(s0%irB-1`}E0Y{#*nRNZe; zH=uf#9A7d?4YU!*xwYS+J@M;GISudOb4A1(hu`mk5P1(v{r)xo2KK!mM&3h;(XB%s zCIsYXUYVJ0ShHH)Q8=`J3!F+k;P&bCD<+W?;u|>Fb%AFjZ)M5wKUI>=zu0rt^H3u& zS$s57CiS-S*EbKJ8eVBvYgscnwf}?mrRqeIIM^rlbmkKA01!xH`rM*h%|6 z6=j~IcE~(03Ln0fJm?F2XZEz>FS-S$1_`Q7=4=bUT(CXfAz$h{p=$8o!C0lYv7ARE zsogPL=)A2$c55F6^WD?L=Fyp|no7c?GCBk4b!1t}yNSKuV$w~~w_U_?R`o^)%EJUN zY(s*}>;}s_So!yXbd-B1afB95Vv)h${z`aweyyVZA^U#sACII!imZBhP6y0s;KH%o z89RLrStd*wy5!#E>+=)Z+W}M^yFGX|jK(g%jwr>w(NUuG>er*F8?1UQjnATJ9hwu} z^tRir#;wzzWp@=a=U4aB^?LO`l(OLL*4_kulaUAj*I|^q|{XPyPtK9 zWcYZmqE6&IJ?wd2^6Zmw|MsKlQAl&MAQRe9C8PX02I6{i!_^Uv{uF{aN<_toJGp6> zevL1qL@?w4=GcHCB2s2G`2frMytYl(i22QDNB;A4|K(54pe}CNkf|}kqawnA_tpIK z5Xt197dPAg)#23XR&e$^fC|TlUl^{-mkjbrah7r}G&*tO^w=#}vgu;V=l`~3H1x=l z-D*xcg2H>r5QnW)s93u(u>VoxvT)%|wXwFYR@5PZlBUpGe{pi?>hdMaUx^4Oj-{*o z7geW@LFr)-=XI>BXZS$zlnSK^emcj?$BTE z!^1`ja@Dhm;WslR{yeGs_Br_Nl!kv5Cex&G$DrYa@l5elB~k7V0;e*NXyU4vxtMd`Idz)sqXy& z`&YptV#&B56vcj<=!@Gpj8lz9Z;+|BSc3E~_FkG6G)wG)-gck7AS*+jJ62Q<8Nl0F z!li>70$(5aEg5+KYh1(|m8;sc5pv^xWq^jEcCgrwAL{!)+^;Uj{KO@9t25H|LYKSV zc0!LZ>&=ob+eP(h_*&*}bh@&N9qj!*tf9nRkWE5BeCHYKAh#B9$tB%DPjvNV4PsJF z?-)Mot9DH zuJxS$w5+@M1X2;tb{4xUblWyb6IH-Ejt&>XkCQ=yfOT5fjMvROVz9Y zqSo_rKonhOB*Ffx4WWcMW+PiL`iKO?LdTO3EHL+bzx-+FibplP`F_GObJ2lXv>H!T z9#bmhueX(?XasqJk?Y&Ni4;_R$dyqQPZDV)G7NN0wn=}G5UFPBq^AHCAkY}*19kwz zTW3Kh<7uh=bjah7fOtj>CX11H)8)&C_}tl3Is_=s+&*J}fdy{|0eY&de(iLT_%KunaU>*|0st%vF_rtiW@(zKOe_A zuy?K{kSg(`bNZRb1+)3xI`ms7#4vNv6;lq3)glA|j&!L-)yBa&_Xxj%Beea{T{R6K!+a6xDZ_c^$c zz>{)|r?haq?vIhW&(z)Bhc9XqD2C!87s81&O63L__wD8;|Bhc5f&yF!rxx??RPW)(DAy3#OELByteyylgFLYum~OI zyc|BU?hY;#mE$BXKHrC4Q=$&+{q_Jl*vbTJ8VV{EE`auRBCsvu;tqNF8}JW$4PfA5 zWstNXI630Yl5)3fIrFJ!C@{^kOhtLE2IIMK~8-AW3$i?rBFz|5orK9u0a{l-OjAr?>qQs%f2z^baWp)e5|9U8YaX^wK*g9 zE8vQw3{-O&Uu&|+mRad5_sYJMIp%_YSHf9#J@={pVmq4j8K-5TFM#6MgDDZ+R0)tJ z#HCh3!+%hM;c?gQw2u`}0U>RO!6joMnjK&enI6GoodMd7;H&_bWW&ag6rid-%?6fS ztkY<~<~;DC^7!g6H>?r8PmFmewKUVinY~lDV(a{Z1Cbn^IS2|)4^GL3?qVQ+fQfV$ zYi72h#s)$vv0rTFVd7QsF7!Q5Hes7q4)#R1QVJ@Ux-_4DtNeKrAdX=2`v@@2XFv58 zu^LMT;NWduAX_(R#PhG$l=~jspx(G+T5CG7GNPMw+?cUj^&Ed~k1zdRM?r7ZT|sAjPN#H(i;YrpU)~^mko0GNHZA8TSB5+J0t! z4>T`AOosX_3z4BHW|lU^%k34R?jNZKny4B1xw8{#5 z#Q2R{^mAz*DmBl3`mEl@&zqZB?~f?~rQ7Z_c1=U&i98t`8U7pG>Tpd3D#_PsY@x(QB3C)7S1%p z{e)QYcihR1b}Lx#?#YV7sm@VMOY@$p{oJ1bPSsPuez!S2yRM;f$37ug`H3M(CupwB zWBd9Z;G&0MVn;?_-=v}-jALzy@mPaHH3?j%2rfp`AxUMoiTfNehQYmU6t?{~2|=CB zV7)!NA$%^Yy&*d@PyEzD&w<_@5Ld2lx1!%}>DT(*ftYY);q1 zMdEOlRJf2A9sB31?Z3wYvfbCNyVZ~d!hJC+17%v_kl6^y{&bFt2+8L{a;F6dF3BLf zoIMhgt^`mgFbSRGwJ93LfA&^MK>3Km<9cKEO`mY{K} zt>rRZCVi1JVB=E|qLqQelD!UXqz)i9gsO!X0|Tsgxh)n9d|&1gNM-_(l^#!a^==%; z3Zpt>5%h(hl01S2P5hDE7%+sAP4jaBIzckr0Ld^ZMF|mmZovSbTZmO>FXB$6x=Wnf z;usKyua}Dv;GJBhs`XKl<-H*YkNC9HkQBi4s~P=3T}6znBrRWHHlZm&pZ{^qgZy}u zk*@RnV?COg(U)(L~*uIZi30Rd3T_%92U{y!%a_ zyPl*mrGNaO(IEKV=+v*|Xs6iusGfhlP~1~M6HWWs;$IInIRw?Bi8xSn9`Fc2a*s9K zb)iL1U=A5D@?0h7qFr3B8q^WBasl%F*_ZB!9LFWFjcN2i;zV-pz2C1ZkQ@%Qc0VWdW|FpmK)#%c8To1 zq7K5E0b6ycnl#^3z~W6E>xE3LtydC#%i*##?F+Z2WB)QZ=vo03iKgbfm4v6UTeK2D zQjL+W%GaiJM69c6KIx`<&x@g=o9CICx*Dd&bdK|{cCt=`;92fvDI^X_FyP|>y)?S+ z2gH1h^Kw_eqFb?JJ{Q4{8XMYK|M6PQDy-CxUW!8Hq*h1|L`w)rE+qkZr0)3v%)+d~wkg(XC#a&9JJI+A4jChTV6fPIF9((Cc$AT8VBJxI-4JrK z{GT~y+1<3!?&5`II$))qE~EZ+31W*~-z|ie)LW24oQ8H>cd2X0OlXA(o>DirKV3gg zAMXUC!UEe2`FFIIGl$&u)ET>v$Y5cwG#t2h&I)87;IbzcVF_L#Gnqj#hTO`=JJ{lh zn5Qc_4fZMS_xaxdKVMy%&9UCB-<2XqqcGP3zgK2S!gvRdn5e(f%`IIhXBJ2b?8?DX z6^LI_US1n(a%T5+75e)H+B%K%(_kDiC#AShd>(C{mA<+vR+#P1M294F7uQ@ZivmipNRa!ofj16PRqw zE^FQ_`vt1~dNc1x?ru^?x||3KpdTSC(D5aDAT$dt^z4at8noWBq3~FZPG+Ib zW|`&7iaBSq(GL?eaQnimp}QR)%)&IZ4P?%in|a-nGnB3eJwMhSQ7oUyY0O)Yc7j~{ zT)H6QaA-`N%WSiv@wKbz!=^tG9TwbOt*lfQD&%4A0L1V>KBw}cg$5>WebdsS4M&Np zd<*NHQkX8F9Rwym(H{$J1vX;Uv*=M|1kMhz@vB}q`{vUm*I=Hs9}WDYviyLSa;+L# zesk|binu-0{Ewmjw5sgaVUz;NC%^Z|1<%97iIG>~ zIl4$K;t3a9mov1c&LnvwGleGUza!4f4$bc^`R-UAjEJw9o(}06{L-z8J9@$nJE>a z05tIP!bQ!3v_N;KLN78R=2X7YEibf{DPq7FOlzf+Iv}-v4G#|#2VkZaBoxVh`<}g%dsNU?0{i&HV^{cY^_GtdbKS3Q)N(|g(oAr6e7#yV;>L_eZLV$ zy6sAI_3yPv&mXrLy?vLJrqSW{3(mL?t7Gv@0rW*il0tQBiiywgm%?x ziDfgmp=+!TrF%{#!5A;ZuM#&zd3Evv27qTR0`W_Iq!BKK04hxeQYV7Olz^f?XUB>B z+>eIAuijB7@R;MCcVFw{)OFjkR|fl}^rOqJaLPI9MRXBs^L3y%pm?y9JF8wHnds&g z;APHLo|L^R(m0Wp+hUt8&4=UP;)}S>r$-?;8{Duh$Xi0n8B_Y1H1V+%?jvwN5tSg>F%+V3kxGAJ}56L?~OwT)z zwlf`G*IFjDEHuu?r>_ywaX9Owx8^EF zC=dNDRlfM+vR=#awrJykKPFJVW{lhNrfj~X2v^4(5umTw!iWcd8Wa7+gtY3kg6A)z z-0%SrjQb!9ozY6^`+3aM=R@s$0;vwGlOP6?$5%wftiUOr2$l2hHTgkeodYGTg4!Oea|7VP}>F=+?%=#%o__s`N@EdY)+!bCEIAz5O_epn-!=}X55 z!&Mh>!mBMk9R|#SG}Lt3`|MhZX$`+VFSt{$w@oF)<1)e!C{3nWP>I}chFP5(r-zTY87kg(jch*_XBnAzcH&{el8XN;s2^D^Q-(pk?jUM5VMl zhNaFUZVnke;JOKlv)9uOI+QgmRI5Pvo<~+5?hrp$O6WlZ_f|wVRz%IN5sZ<(a3`C) zen8FUu>0qopTfV6N8K6riNiOzxL+s#CoJJX2if6G!bJ@k+7qy)|K+}hCa@4`U>+S4 z(gaqKqH1?0_*D6Iy7eA!W)f3I5lwn9-h07sFQB6+Dl!Zij57F#a{E^6!&nZGs_hVsDYn8)F;TVL6#)Wes!d z2t;JZ!WrZ~3_qNP@ysGzAr36H)7S0n?eOPhmXK*DT(ML*b;%3)m5mPD#XoexkQ%^; zPMPu=dA?Zd!LptN7DphCwX2Vv4R4ixVbpC;-2nyXs!hX;d4^2ztyKnrUoom1kfk(f(k$YjD=q3)f zMuaO>A{`pc*8#a$boKHf`1=ZgRmWIBx9p04DucGL2k z4R@4sXr_Q=uFZrvCRq8 z089}yv|Q=8ZDf<3Qs@SjOf%BjlWJ17x1`3?Dnq@+-U8FUx#$=tpRnd#-nAlL#$F zv_E8zZ&D379-7>jt6-=ifHD$dqVht6+TGm?wx!sND{1F`6`{u&d;r=gR1KYdt8|e* z?M0+d`+mC3b$m@!<*XJ=3G;0U0#yx$Jd1hK>m6;*QLJK|@ulWpD5I+5B6?_#%ZI>WV9yo; z!tArV&qRavHQc=O-5r9cyIA6F@IJ^P+x6jnpLhHIJBF$YwJD;x$$HULAqhG9NxVVo zr_kSr?mm2#Y^WX?J#iAB4xwqKwZ?Km{C;<06|Cq_R(rMR*A?hXy}x@*Vbl|&2mN27 z772eNR=^)5(kRNnF2Kw(WNRMcqg={QWmWBX%WmjeytRA>8^L`Tu`5hXv~jNgUK)LW zP<;!a`i$nyTH)~f-!|0MrF*xzDtLK+-00CCd$u14lfFg~;osj^L zU1oHtP{A979!OpZ7=iF8cM4X*D5V!6t$?6mOVY`Rq%m_$8M5PEh^pTC<$BeqZp)q7oozPLzN^|NBaV3(lfrFw5QlTvi;CT|>hBeH+Ks+bDN0DV4YQCjsEDTJrKZ`dvZi9-4sasT&z zxku<&Q?fPZAS=vWpT9Pz#-QZ(HRlFzw-gTBVmh= z?oE)r-QP+Eo{$O8vDfN1%pe7zKmk>1gLNAFtaYuDDPdd-EJM9 z@&_QC4S7)Lj1ECI^`t=%>d_GTSl@E zy*)|PpD0I}?g~?dnn=mw zkv|lx7%tqrNaoLJH2DBj9sidV{fA45bGB{AE=C-jJ&1Nr?yhATe!t7gz_`tt+uu9z zYE!TKao%rG8E9!kQH0E+Nb?QMstV=r zEl6@J5jR_bAgE-Kq4NDI6>7Og&w*hO(e(tJ+qewR3hOqwIna1~Y~hvL+1}C)0@K6E zUIzqjKH|y6`MoPWGNb_NxN!#P)$M^*k>BEA(K2v)B-Q+m8+`188b<@s+q;1GgP--! z&~T^+-FR!gev9+XkYrz()C}imVmsTD$+*OJT`7cc^e}%bHL){Y^+7lb2R!cK(j|S;(r(X5yQ0qP z`GOHOh*~bAnveSNpvArfF;hsrkIdDDsjV)m*Hu0PD5IS(F!vsdF`mFRX^P!411Y zxyJRB;Ldamo%AA-b8&_&3FaGw1X~Z$J_~~*4ILo8aMlZqxe{%tLAeoZfqPS;hYN;nW z^PD%KJn@9{Bh2bQ2c>th9s#ubU=X}frK-(p!C3oO(2&7H7-c6)hi(8^_@B5$C59v& zSw7qatS}mTz3jUN<<6n@%J8LmmKM7@7}Q1nCYSc6$N>*${Cl&50|Hn4>t^I{n4wXG zCi?8U8`t>85Q9OD0T8jiR!nC%3(W?#iQx|?;-u*%N*66~JJ#UkpbQ{+I)F03a?pKW z0VTW?!NcI->T(L=fSD-sI%H5nr@3AJkn4tNAG9A@?E2z#i*Oru?aX?j9*jKI5PUn> z<^Y~d&^`lT+|-os-uK~%Lgz4m2|E#(Fus|X%iIrFeSQT2(eDMa0X3tTuCHi+7)rAM8vJGY#637eFzmVUSzpe({M?(wVbPZ^ zs-c$S&qG_Lv#oyWTQVT+wX{@fDo;YHY$n29T&4*1%GK`EIUJ)Gfb8HVcS_GHJe2-_ zhR0V$QNHDGrP_~5;faFCI$JP8`K=1DnW*7)*c2;>@&EBU9>VL0tW_qXq@4?eOX8T+ z3}k>!CHG1e$rnIbDmqIi{+tLCH;jf!Zq^i$x($E7jjRBN*D!5|N&QB*qiaYvvDU-) zM|tQxFM)gIE08?0EWuV{>KQ`Jg6NroB24KHv`4OsA*WE@1p|DYx=NF(7JF(4kt$Yli=w0~C%fiszBZ z&UD{5;K(Wf!BKj~jaJN8o;b^Tr5x=j&5ngxOBxH|&Z=+|aodc1_+U1KkV{l%sW!Z# z*`cTQ_612YhzT+~B~e1qasK&XUeq&Acy06~J(E^rN|n`kTMIJENBOQxi!tWz*7{QL zPX&gZw_D@ax38m0-2mSUyFAW74-%_NK=tW|;vZfH`}p)D^|iBaU}&61ZzF4I6L<2a z`0*Bpx@iE&i>#O^BX%x7B7YAzum%0j+WRlr`pVEx>Oe+Dg$p(4hW&peyHWd+UF(d19K`D!rVRGBJyQTJ zh;+|seA$;?=qTRCkT?x|i=&G+(C#)hlyD^e3%eZPJ_toDgXL`6n?7^=mJrNT8wI?3 z(yen`aG=zFfWwTQQlGkKTPU-7VBnQ@cRjM>#CcYslM`zYDV1{0W(puK!>xINnQL>U zZeJ#$MJ~;UFKfTye`qt$5)eUEc#(xZE6!IA-hoE=jaJKnihy9B=%sK_*7q4bZG9`- z0&bAl0*wdRhtNCFcxUcZ^;{vG|H`5A|C;3KZGWL?)DA%aTVY{Amd0Ysl>P z2#9-u)nk*OF8|45@B19)->QZt7lRF+vS*JDY(=WGxy}lBIm2_W2_`G>q3}Lj8wSz& z75`>kBxyr3PD7UcwNog^4V zx_W5>ydmWQHp?~M26k9=>aHfM7|~>nQ5w(|yCMmqN(;=J{Tlue6jw>CMZ+k1`=8(3 z5V{)zcybCa`dCcFVz-Z;C9){o0sKb=rqs_FUi!gt#bBu&aHKx<2SUbR=t3rqDNN(j z)QAlQazp*9IyekVx`265K;FBQXn#;_#%{f#vx_HAweMT2&rN$aJuwfTmI8q5tBxx@ zj*YGyU^KJ@wt^e=I?(+JGSaMLLL-#dDQF;c_3HZ*Zh+fz)gm!5m0mcGFxuk;x@On% zZMXb$=M~m#_=A)=Pt5LS;;%YwauhXxdbOc~k)c)BWhprGT!O_P{~sRugj&hHmwz{I#6r!DonwhXJO`+0puo3h;a`LsfTpl3@RD~{W!@q2c~iPW+2QrEtEpBAhjQi z@DJ71;VuuHJ3uD z^UT1z)a>W?&l<7ymkq#GO2lVAe+%(04W?&W=R3$Zz_AALy%T7F34S2c&fiU2%hh_R zt3P{@+j{R(2t9EL`vce4nSmdc>ehY~@AN5kmIu9gre*+GJ)Ni5zpheqS`}Y@2;x!4 z(9ZUK7*mX1g1IVdwlAN*!@~=4HjwcJ7oKc4$-7x-`bHrIc{S9VLtj=)z$o(HJ;{W~*_tD)I!9`AA*3S*VuNT26&{8AMb+feL& z7{z-M!3$Bec>e`2%zcXg$CzY{EIRL8ATQ&KYtSrZ_TX)al!8*f{=Fs3v;6>pM-gFD zj9}j;R?k6=lza3MMh4yFLdVejnye4GiJy3mldjk?U_nvQkAKze+|V*#?i-Ti6L<_& zYb^Im`RVtlR)Bvu$vwK6@P$w7pOK5NEkboi_p>4v5H(=SeZz~CIA|2Uz(iRxm*c{y zXVD2U`u!kLTo&5kF~dZ@m!Wzqy2SRjK6->r?+5L?wT(@Fz;<(5C3odJzJrRI&@;(# zzbqWAfAl!omJyz<;V|CRo^k|3fewoux4k5$p74)|z(Kq1DyRQ)i-45pHqYZ;TKRjZ zm8;g5knzHfMd>$Q?8COHi0*s9tl99&^ZnZQRCT$|cyyq~g#sU%SFms)hl`?pbHugf ztqbr%_;DtzzxC-DJLJJ_Q;oh_Ic9Y~k#6rR39h-XnP%0W()9Wl^s>L_aPfXV8>Rv` z?_Aef#*s0&$*4ShqIrUk@s0-k)5;-M(2IqS2vOR_S(j1sr0gp%Rtt-YG$eM6x`rZj zZ%5-KvjD2DUbWVD6{kAdb2`HTMe>>$NTm_Ov^UzVNW6qt|P`jt%!v0fH6vJi;uCJpyRcodD zUvB^G@=NdCPr|U0|SPNY$g_~)g&7U2+Zbbomz3a#VY=U?zC9EHXi+ub5Zebe!# z@D~*)#K!g~^>OTI9hW8LMV^C>L)AND1e!F+YpvM-T2;>&W6a0bvFJ0+8{`0O zk{`HHl~1jmqI*6gPk3^8Gh|~RhIlVPdFLHiY}X57EI9Tr5KmF=aoazTMrT4$XfA4# zH2}jm4_y+@6KX)uMzR0+Ao!b7g3M(%wt$uBwvs#4Cw7l*=>B6{GC{wK93{A~MLsa{ zx}*qQdiTZ1Vx#U1EJMUXLA_?(fV7;gS5X9xi_JF%wnnaOW{uF9_Tk+I$*4JXlsVx`} zZE<|c1;5KZ(tUAdZvWZncaRaMUt{!nyyLTnN3E3j-HA{gBgGSy8FAOb`(Y(r*KQ%j5G ztsCdGbu-&{$ER52U9#c8Q#Kt_ek(?mbzp)gGdies?-gHE#2HWYm{6j_Q}|~T&s*tu z&VFK<2Ob{0Vp@616gd5pgq!VU_4i;J59uWKO2i)$vq`)x9J{bW;;c#2T~ zA?8g5t`hIFk`SGHB6RsC7}}5+VufP0>uT~-frkr&hbufE)Vg=rF5ZEMt7cHLIG^#4 z_u8Yo#+0MK#gn@$xON(3niHiQFZ~ao$Oy|!2Te-A(#vPH;M~pq;u4%n6o}n<+-L(< zG7X)BuN}hspj*{{e`IK6#Ecs9c{g)c*H%djgb4AHL2vumzVq8F+px0tvQCA=>8M&{ zB>wB-KX>ImBp+7)BjSR(?p)W2q~pqfku{;sG((nz7meD1nHvwYXm1%5_M5Qo4@Rpe zfdBg_(EQLM-@BYNYnH}9^CNJU0yL`n-4v~x3m-E8&7w;`A~trBxDQ!KSG3l6M)>)3 zNNd?~TC80iZWZkH{NlVJLHPgPiGR_2>di@eK7KS2;dOz(N4&RH@#kCn&&Z5pcNU*&gfixB!WX56gs}lQm0>c2ESP6S)`twr|4s zUe{h9IY0`Nadh--HMX}pC$0T`F&8x{`q{Ore*b5?%t**;TDmqBqeE8_J_R1lFo#$3 zj0vD)p7?iN33J}(KsJGV&<(1pO|CBn&(h!T_O}1GT$Sj@%%lGOHwM)ZBI0*eeX@WE zo;+xo8`qo1YJw03NheTNpAEwf-Ji7LC}A>ip*Lu{O`%sAYVLjPl}>m78HCEL70M0X zZ5Gyy)4f|}!lbIxoYv{skOx;k7aEZXz$(x~ zd0vm@iGU~j{R=QQcxf8>moA6K0>2KK)^x{j2nGsU{+P9~oO@=d-kD>2<66RQu&CW1 zEI!&?NeG6MNr)55YiT6T1Q(VJEIzBly@owxHqQP3d;rx{v>S6+VU=YYb7BgZ&B5V8 znx#==n&WbptHd`a!sCPomk;i86a#9`1lXme5nr6p;$88}XP&;(nB#DCgHFyBTAb{t z@v9-k5 z(?hXErnt(ngcQ(1+Tet4jQ%IIoDde17u*W~wk-dLqfj&Rrr1#Z5liF4?wquA){}bJ z!<-ctzC8c?VR*?7+RD1t=A?;)7-A`E@MEEg5T}Q3TDxC;E9x1jk~L6c1zWXRJNkaX zLA)W3zGE))hk8G){1n_rTvIrAu(5DU+{5;H75L|JfUC=FlP#@%2U6la6kTjwqBKyV z0AxnBYHS7j_hnPKN}*#yw)g%`@geYB3BNOa7m|wDJI7I_)8it&&gIRnPRVz8UTvWd zaUgU64?X>1?`6w8yZWS8p``uAAEGD?I5w`<<)n3MF_fJp9$GwH|93yu`@@+qEA=jq z@TgTufFE#a^;&8P6Gm>qPy-I)i`MF0^C5h{KLCzzmjLU$}t z3=}L@C6fss7QxT66I8vO(2ni^k|M3z;_9vXF`oUaKrUid;6*6#1x>O$iU#=YI<>@2GJ@*iz0H*)r&?bOPUS}?A3sJHHKd| z0^Wz~5Uu_)GAmA%G8j)pqo=Da;2#uL9#+mzPV8<}3Bg0)FqQU|^`sW|aP~5`FO~ZG zlZ$J*9EfGs5)jf;VVIa8MXr;^UP!`xK#!6$P4vQCVuqG-kZ7tPz>kB~^40r|ywM=B z`JhxKaOgvBaNZxO|L<$ZV+L<-L&HJqO`tjT@~kxY#$+>_-$fH~S9%XzVfr#vH`G-$ z&WJ~l z?BENFIs#L}Ve4Qyd7kc2-kUwaT-;O^r{9iyLQ$G&UO^QCKL?bwknzoVwd z4Tygk>R>E(uYfNf4W{dwKtJDgZ~zalOK=lik^Q`|XM`t~wRqdSOj8ggO-Pq@uRGd2 z^k-j=qtf?6)MVks^FGhGsa7$KIU%Jo7Rs$Lf}Nl`I~iHefAp6pogd0JL)OM_L$fhw zRI3#t;0Ud}?blMvW0bKWpNaRUYJay1bJ(h8&3kxSjPW1$RxZSr@l99s<}j-lGjty} zK0oq6lV!pZ>56w89!0xt*!{m1{V)hO9F>^3#Oc|UyoVS3h71`xrx&vy( z?@Z}0ZD9E0Lk-Zp_S-2BBg|XKZIfW5C&8#Gn)z5(H>gXefV``MG)?Z%>m_RftQ|OY z!9Gpl&65ZrmlES1=dW^AS8JYf`;QQvvG}=V(U{}caJ@Z$t8XaD@ON3~o$G#C{I+X^ z7rsW!Gv5!JFWvP7!-CxP256;l93HEMZtMt_jjsE{n8h=i(i1YQlbpQ5CyBJqY@N>k zcKz}pbnI7-SIUTKBM^f876oDo_A+%Mew<=cmWjKCcBO{ui4&8DPd&Qb zo$q`YeK>g);n+JgZX?_l-1>L+ebBmAMl3iPt?|)9-~!fxOn8fE*_;D#UmnI=-U0=* zOaqK!k}?Cnvk~#&VWNw}-|Wg-BYLc()7}-d#qZdiKa+;-#(BaT`Fq>R;A)Lu=!qp$ zxONInb6J?4O6|A<^gUO+H3GC>bxv%y%P|*k(^3_&*L2a|A5?2IwsmEIe_LlUt9^2Z z5YGxODKWciPB5oA8J4T&-nwk=-Y@qqbdP%Pv@{ie)3-2sdMwJ#|W_05H)-m1QHnFV8dx#(KsW zU8+ug?`5ryXK%JUYgAk+Bu=SU{}) zO~)i@f=9z2eIvUeDn5L+cCCq=FqgS;D)3Q?*;tO;uXQBY^MjuE-rKcF-wW+LmFX*e150oLEzMYz76*IzR`}uCj0Ua_b*XL#DsE0RL&) z@BS%n6}{@hGU%dHx1|Z$Q2O|g&6(L;c%f?_heOnLBH2yb=$dn(EBkbvStCzkqYMZx zz=T#d?acoI?tPDM>r+aiZzJ=FSmgLWgWsnzs1pMhLP)$E-(JvLRw|Rbk=H_$WTf83 z#;RXc>~F}={zYBo;iIryzupfK6HaLH)60*)TKeKH2>rQLs5_0vj5(FV!6Y(c2j;-} zX4_W@u}H1Uw6wx1iB;afevxO!spf{lrX#8japcX8NNPW`w=&PP^`J@6i+1cQ-Z=>o z>hMvhW95q=kI^n-c{RR&d;GmyMs*-Q+giso5)+oY>2mLcyhnD*@j6u6xa!PGFNdYu zL`yVxE5Z(=YXtqg_{I;2R;+8Rbv}2F;pqS|)$CK8$2bi7Q(ppFjZyi;I-gb)$E|e0Gl9CST z?iPdYZs|@zx|EjgR;0VTQ#zDdGzds{*ZHmeZufb=@4VkV_l|MLU^vzvYY%b%YCiLs z&z!!U*LsQHKWsqx3mn#*l3VrZy&Kj8nkcdvDR;-H-%R$WynkI}%6M*;IV^np>U6yltIA{1ZBMtjWZb0HxX)Q{#FK0+9xGf(x_Y{~yg;WghYm#F z88Gb38+>r;kGoxZsh;5<%3vJlCr zRNe@;R_VNQ!d!I+nIqx?p_{C4i82FjSK+HKhH{nGjcdLF6mRaNaj>;YwW;TNBRf&- z7}$juyI7m`e0YDT>DMhkvp{6thVONiywity+GX9!H=ItRcf~&^64DD>5^uF7?kaA> z)K16xTUY#kRPWFC+j()>Zgq7{3*1Cb7HF(KDsZbV2tKUVy5%c4ZDE`+ZgwxA#j;iN zW=e@+Ta;NGn%Gj%%-C%`Pp3V0oE!r$@A-a{Yvh*e%9vzNe)ImobaAy|SeI!o@uJ4O z;E_f3&Bp}KxW%k@p2a$jIRfg@Hl5u2)Mp=+!nae)3Ki=WGh4T&=3hVeSXu}^JUJwk zi?`aZeLlR~u|;Bbkg z^h~b_@7cgb{DUK@5q_DWbdT0}Z&r}bUd=$i`A88Yte_Yi$^7Y7ktVhQtLkDIrdpZg zT#a}tM|jvFPK00g(n&1-GWnkm@mp|+k5Yh>ntt9y9@{phuw$ z=Zwbwi|0xo5m0Q=_;)q(fA+QXRjkt^_g zR|4kX64$c*l%#daid-V372wtgGaF3KdtCxK;uB{4<+Fs7F(~ipek&tkmo?xOdy)j< z@j6}z)f|n-M>PTR2GT;SO5;oStt;PWG=A%n^iqBw785yyjCqG0ysuB5IQ7-%UiHs1 zX~FC4-=Ev*8Hd@)>8k&p-Tz2^ToLKd&pLfApNl*V2C-|(P4F6tsXAnR54a3_`=8tUo2b^2b*hw$C1A8gq zbLX!*x7o{22wB|BW^b$Q-#wOIaI+TPb!=n+A*JQQ^;$Gj9L}1q@ed@Ch8Hh(=U!z< zKFB@3{;HO`Us$^6e)(=QV%cfvo1BG*nM+=h`dc-8dH#X3N1~ z%+D<HDK+Rn|96wCg_ljtC}~Vl6=OIEk+H#Tv|Z+7>ed7oabbMH*Ny z(79BTmupx_I>-f#<3#qzx{d4BEnc4>xeM zHlW0Hx1M4Tk{CFctgVP zA)OTk@GxWY|Kk3D!e=zHc;3||g)FKIAvD?Jvi3a4_Ifd62XrfTc z!U3NX-k?iV}EeS7y0-#RI?y)mk`G{vtlurt4_ zXsCqX^8dK>WE4HeoVJaR0(%yTW4_S!M-`OZ+Ge3hL4ve-hT4_+y8g%dCQ>c6pRcjM z&BjJ{b9`L>ZHah#*qyy)N>M7~t%m0Od`rUN@%J=t>ad5k4qkT`)t@T0gmg1@>)lto zkbmiXzNH6avHW0sHx276n6%si&I6$*pHlubQ$17M$Fo(Y`Hr7}}-g%5y0H_{s zq{L?`b^j3o`}landFdV7ssw5EeD(fV0&d01BD^`_kKvB%aWhW}$Yqx;lX%-XB zj1ko2_XG@hL7C2wdI}8~I zPuLB47QHzw*xIgVu6y(;35=An{b~)+QBa(;Io-~K^Bk6h#5Ny{w#LPtMuZM4pKk4F zSA^*-fEU`1u@g-oM&&*Fbna`#hTHQ6_OWo&z3W`J+fDaaNRs4(+1I9NMFlFw(N&)2 z^a#uzyGV>fLX02ODlE#LtJ4x=rqW(YC%H66JKVckw|>f<$Gxt1$PSUb+2yJe)bre| z2kD-wei+Q#^GbaMwV3L3g|Q2+$D|V$BPLX{{UOyKBAOb0HD~c(9XQhtXr5fflu%a? zoQN5g$i-FyxG_=GcV5WKjV6v99m|%Lk;Oa*#XMo}d+TSkws_&K`>pzQPxx)xZ4=0! ziSCb6NwK!Q)|jJuaoaK*kZ&$Gm%ZTO{4%pND+9Vyt2Tayseijs!7Jg)KTF|T?|gT} z;Q8b9`x(@fjf=8Py(a`8qX}>-aS&zxT^ zKy9z|EB6S)sw#>=?c|D@?j7k<8|cDQZ*{?6j8dml|>EX_RZ6 zDb3Jy=K%DhQ+rM~vXf$8i>ey-p)le5H|Zp{;Fgx#fIDE8ey_?b=UQ@N6ICxl z;T-R*hMe*c(FE>8>b&Yl1;5e}buq1=IUWk^69SN2RxMQO-?36_RCO^Jw>-T)d zm%yR~Bs;^-qG6sO{A+ssy^+@_qMiS)$N8ry6Bh&6Wn6^*3#I+$;?z*Qyv^sU_Fs+LUY|Kcs>^sLbtmQ zQbXdEC&6@ny0cez^5`0#sz@$w0YPS)6O$pCIf+!cOoMN`CVqDV$+!&!SwkNv4Kfmjy|7pVd|pt}sC@4~i~YbPb$H5#9A%e>@BZQOn`m9Fs7hP2gis9PncHZN!w{l&0|gaCSay z3gX%PKGOqPsLG19ekK88sGRr{ymo3v7z8_PUZ8VPoTQ7WK-OPl4@^9C5F zpnK1I=rbsRGpenI;N79e;(Qwq-xOTT` zrl$RU2=G&`^s4m!`Kk9kyJBGq#4tYId9~J2%8$!B&?JoTg@y#5iY5|jO>J$)J{~KJ zF#(cuZEc(>l6uvm)PuZA>GJpn-fdFRt+TVU%3qtfzZfhnoDU*3mwCruawD&80c6m?;NsyLgI1 zwreE$xclF2bFEE1jYN&9#?$R>m`k^lj^}O!;`5YslS$5?G?C93^yp`oDY<$(ICLwy z<*Ir9O`ta|>vA!$H18w&oR(z_Pm%c3Il;{ZZ;M$eUXTF0S2&Z7Cb!@yC2{}V;zYJn zd6hq=Ja(vR{iZElPK8D7u@DgPgu0Q-t^VE6=ko1DpJJwD7%+&_chBi!hxe!YqEm&f zIssEc{fGC+_1V&Sb<+n?ReFqsyEqlUp_;5?UHFgpPerupzfJFD`%f&ujCjL=sK45B z5;JT3i|9k^S)fY&;iOfH9tvnl5Q6z*&dB=`OvN@OvfVWSJg(^q!as+3Mhphp))H}- zM!RxYF(Xx`y*}WhgQ(fnYi{5v!{!qj?_Iv@UG>bD2ayOQltaDdnp_=$43tkrg zcP-U7oagu&!BtgF#?|WVX+>@3IiO(P<(SfS^%}1+f!c1gX3?n@eTj42uD%uckpyRf z*=D-FdA5K`9n05pbdi>BZd@(h_#CjK!yF$4hK?xp)l|FQ=fuRx4DIfmtLeG~)D%O! zyw1+p(}C?9<%0>0fLlHlFw$;gVM{Z@RvI1Wvn!w^I6zl4T!m>w+x{hg9CAC1s(pfm zadTvNbtAXMbKCmix?sv)2W5;}7>^U1=8QSIRpeMOwO%K@zdx_@ zqd#PJnC(|Jg!p>qEv5dnw0nK;R==X!4<4;sibCC#_WlZji}_p*0(YD3v)4fNeZHMr+ClEE zO#?SM_sjI?S2 zp4GmyxsysaPc=?z4+We=AG;1GMsSf_ykF+WL_s2Sex_AIv&b;DA^wxsH& z^qty8K_PpFa_JACxW#!BVYWy;)>`4WDO+ukqsAX`C2X4#@UD<3sg-*(Hnnbt$+7R z_PJ&~zZzWodVe=J`rdYpRm+ZFokmBwd3+@Nt_aFlcp({CKI3H`?s1RtNb-Z$HsF8w6>dn1kG@?8Fk8AAHO<6hCm4v&ZpQhP|A zNq6VJ_>b4!Qw(t3A-;c!TZoZ+XT5X79}%fr3i_3{$lgQDyM&6bQ%ALZOMnRiEho(B z7&bdr5Be?q#snJ)-2@nOmANe;GC^h(zwycEE zYuB!c0b0-sXr5?IWV_E*hBsjMnKFFT+*Ubw1|;YYBuBGnYiu$kMs)&ft_$~iiApHt zPlr<;Q)N4W4Alw$`6I_`tI_NYi;YX!K;mEg#ad-)TKGpZ_%u!v{k-Q@tAYdeD2PJa zu{PBjEa9H1vPiFN5a*Xc;>MtF10PNN>^)w-D;C25Hq zq|%~aF};P?9}>DUT33?Tbes`R@4Vh-x>`)$xslhvi_BL zKAUSxX}zHm?rIfv)YMa}Myzl#mr63NRB_J>2l^_f9qIl`e>BkIQu;t75B=0vQMA9? z2M_XmV5$i(Z5Eu|%>VR6BEAv

    _5SNu%iH+|{}D#-iJ&3%BgI`eo}0lS6srvQ;KS z1S-XvoI?j+1BvNWvS4{}$&SOkxj#A19)Vrs(Sbx`2IlNJD`aEC=8N|HMCE>%XZ3TN%yVv= zRA-_*5cvXz$i)K4AH>;zIpQ#^&<%EX~L zJy6sgXV%;S^x3%4~%Mdvev)!ojYv10j^5_LruwzxHn9|k?!%ajA zA<)K&zU|6u8^U;HwNf7m$80FzBpKy36d$veQQcRPn%SO8&e^Y9kc^QSjTqy8YrRB~n7nwC zT_sM)h>XOj970a@nvU=O-qLG`b7L^c-E@!bgZt3xq3hsWQf1S~F~hmXuwbd{syo=q zGBxkt`z?Vk<#fm4Bcw=?EubalxWj6}9%!Gs%%{7MsCq!Fe0T8Ma+mov^0O1lapbs~ zOKBWP0;5ic67jv~j&5JiaiPi~_F@&qoa+H&bCySm#n?0}NgC-zVZ?$RYUz4dnd)9$ zz=iS??wet)EIU&*22+%8Jqp5V3~HK^oe~&xmy(zM&bk7`DXtyYHhXhN#Ahn|Ex%_> z*ac5_YDq5+rUs~-^Js$VRT>9J3P|gQ5hjQ_lkEqOjh{_K9r^WIA19?84_EI?9=?)Xq+f%<%s`|%} zsS3v2O+`TZ`0INg@i_~MCb&Y^YZc)P<|K+4_{IZFxQTST3=%@;lvr7mCkZ)WTN3X^ z)jF~*J<$#wKtnf+BNbZ9sav5_c>HiMJ3xc53z!roT~*q}`#{A1^+Rd^4+gj*sRevR z^z#-&nV%Al1W`u%K>#=TQ-~;#A(0X(^1*-p$zp_a@(jz^CD&x@6QB+pc0rBb5<*D$ zg=KLB{PkWOZi8Bq-aVW|m=WdBH6!8` zZ+>b}MQDGfd`|s4?Wl{T?@g_reh}8PCN>2Dm$xKiop__xUVEkU0t#~f`fwD_yvO)8Ig zuMNaUj|ac9vVfMP8Um;`QbiM#6Z(wN$`Y%91&Pe<)aoC0`a`Vm~WQ|Ff2Q=xshVC#J5GVmFtHdo<7`Z zPVY$o`QQwTs-@TZV`KXvOe({4%>MO-_tiBl%NO}O?|1pN34*;!hS3k`cehntY`i(d zBR2V@MByn#{`&cXiN|j8nZq0z0$+KvFqsYQ8lj9F{{OIT*yV2e`95fDY&JQQY*zsM z(?3}PqYI~IP=T&8L=T{4HG6ij|A8@Tuv(4POc(It(P0gxln1``**7oHj%3FgK7>t$ zuRO?4i&DDbakXv#41T@H7w|9gFWl=j&3R=B$`3Mmw z6-2Zv!D+3>oe3~4ME1gD6hV#?Zi>|0uIlS{5)7?+nH^yY&a>{&vB2803WkTll;+|0 z=2`-HIm?+QU3VM^$^2dUwnIG*f7MGBl@(i6KvBzoomW#%G`78FZCbgzZn{N9Km}wG|}A zXc9k>LS=XJv% z9lmTtKL7t-;|K7-JOOnWWq9x@?p1SfD5ofV(koK5TdCbn`|o}d(f`A}5Gex1l%JZq zn5oEUYpC^^y5Fn(u8f;h6;EQV0T?VzbB25%%*mw$Dc>);-==7l8@!(8U{k@k`4!{L zOaZ*DPzUJ8AAqHb-pU2MaTIl2`5~JVk#T*@aU+KzKRJplJgvAsm?<9rz|u2OZ8_z} z)Ylh7W4$SzE-(`xPKQ_moER8UZNa^j^%!pWN3>&lJnd=b->dAMP@^Wk_|-aDXGJ3m zht5;rSPA21TTSYTTwA%BWgjV`&Fqb0zE{cST#w`J+<8U{xI`iC1s`VASzZxD1yQF# zm9zYoHhP6fD@;eI?Sra3_{Iv&ZKn!<-9gaj)+_Bcnp_>E&f3@Q?0;@Nn`)GYt>=wL z9}%r|7Sa2|_!ib~lgdRueHM+|R`Y-hEz@s%#GhLBTW_j{oa0LA5GM~+R`W6@I2x)g znbx*VZ$;jhtUe8O_r5>KS7xgA6h3St-K_7IIL9Y$F0Ogqp_fpSasKlX&MW(NPBRa5 zsB(LyQ?p6oF#q)v6x0SR<+G9GfGN@bc}+gG@EclsaIOGWTX8;318rTU|P^^Ww6qO99R?mDw%>j{0HQN}dB$`oH_Rw)7Vx>}D%Bbyr8GQi3t0EGB| z9cM5m`_FOCJAUZ3PBf9rr4PIFBQgvqN?r5)mf~fYju^&~6LR(Zmb}kOuo5^T^)CF~ zn6>kKd|sS&PTkQjc^*fk6+$`+oY7md6F4%&ABnPbHBQ#J>rB;fHBLC>Wsu;_X~EEd zcBcAM+EmU(vy$c@1C`l{ktjsJjgjQMQ#|+AtB(w>E}j}32bP9>)QU%RiB~=5zd3av z!~&|se|cK-T1FJKpt8#@)c8qgSSne#P7#>ua*RLD)NpC-9MW%bUshbLty7z2_b zP*a?2>4IXbzTsg_D8Fkvb;Rb&$Guu;8n++wG)QxTb!#iUIP2!7DC1tp*>(=v5oIeJ z-H%W@sJhTllYgWt{EhgVjF`-i{gJJk2d(3KmADq5^S;T7WlH<^tM3CLCqKA7UzEa1 zzi(|{b#JY8dTqo*5hW6W86=Y!=aAQi}_he-tc|HH$K>7mMNC-aLAN?v;^B$1hhEjok`h=JZ zq`p;DUy=;fbI_UwMc`Y8VH;%8kAnGfey;N4$#dlPl!ObLjw>p}bk=uS%DA5&Vzd%N z8wOR9q7^WTkZYEGC!aW4Cc<&QkE`QB@+(Z&5k)>99lc9Gu2?6Guq^dkQgRo1YEe(x zl*VseR9JCIi^!yz71>2{+e6>Er7{vdJ{rt)Zlg`=FAB`4&Rs`b>#G@~{PYXM4v6o1 ze$u?U-)@|SesUU?Z&iJA2x1U4i3>+qjKttAX20G&cTB3_3s)_ZZ1IWRV?D1MNUrZ zP@)em!_x5Rpu+w+Mefle@)SPheRdUl4MoKg46LFN@sOVCeSQLlNE$YxJ%D{>&3jx1 zb^ZUc{FaHwkJ5p6W$Ce!%E4;F=!R;KnM0RmyW1Y>$8|><|#=7rhyV#*ZfbmkZcewFNkMOugABw#>Q%LI4w;hws z_SHkFcW%Ey`&wAfD3pX5y&b1NKKdx+)lQz9>twdQRj(v12}=^UW0NJd?lzMKcvt2R zh*1?RqB;<)1yZ{T3P^b{_ooU(o*R};a0zd3+$Lny#ND1-(^I+^)x37p$@jpgEft@R z1BgLVY^vp3`B+39IO9re`SO6`GHw6ocxz+HZ#?!YU9RJbg_9tCg4p%dTjKbdCu@XK z;?Mp5&v*a+K$?bR=gF96$=%$Ki@x91`hwV3#Q?1CN2;s3XYaDZWXkrKemOUkGwKw8}icqbu zKDz*?mbaGmLR0o;>U?RZh0ID z!%-BC7uSJuhIEL>Vi>3q=^(W}rk~C0XIgsySk4TU;*AjoM2y4q`G`fT){IipDARDU zA~;?W%5#NEmb64oSZ|>vD>x%yS*O3GWV4B~xB~z`dR{hQzkMf71Sx0n35m7*{KPSQNgf+dM|}`XNv9~QxSKE;^N-#=$NjSBKz^z z*jS(#<`nXGUNZ?OYh9nzMV;CAmtI{uugyj?mTiY-m%7r$l%zJeKiU5NxjCG<)$=%N zNHzDYctBWV4|b}@v;4Am2U8I!{=D*bG9qat7tKYhQ29rcz8s_&fp=6x`>T;cF_eG4 z@(&{T`-AU$>bBGB_a*ZubhB(j`@9y{PS^M^mxP!O#5c3sF+Jx(NAs0vf;B*3RG0Am z4VHZiz=E;kVub1~9`%N9t#?<2)?$`GLO|5n=*a@yH&dPiYiS2U9YUr_KmAxiV0s*# z=8y6W7sP6et&{W(rP#)E2V@F?agk>diufdN+0*OsqVXtYkUsycdYsSf?s6weicvR> zKtp@`c|Q^&0#Ey931EeUD?6am5=>YEWH!oFz7nynwn zLA7*!ql|My8Hyoc+Pifx6VoC#_JPa$qQFvgT5qxRDaK8b_d#C4`f4Dl%Lep=_1eWn z+B2(~yqcs8vKLH|!Wpq|*bx141z4pkXl>KyG{0tQpq<`y23&&WE{!3@gSXh8Mv6$c za0|ZMQNbv3Q*X(%e<){6;5kx^iFFX1KzadtlABVu`ts3C1h31mNox3zsQIfb$o-qk z-}1|8r&^89%Q=g(SS^&V>qJpW;Rg3j;@CnH^ZfK(t|#JVHW&6z_oZCFgyRl-^~4A0 zoj&w+Sbm8>nPMW1XI|NxFQB{kEli^~0i{6gFm_~|J4gIbtlE~@`SQ7H8j1b_6%K>3 z=>kBie-5(=ED|8q)KD{!%MvD#1)Zx?m@CSCyh-sr8brX%T-q&3^Xg!mE1 zx#Nbc7Edj=^ZtVMafth2_p`>ZJv`VRF?tUKCgR3#Gknc{1L=RbbDbwhLUU%u19Q?p zLjvb=lKPf8R+D)54pKEBM*x6!CZFkV54`JOaG-^7ZAxyMI_MeANRZ+np%PM~=q#~b zfRUv1kj&u(Si)GCoM;&?ify!rCg$iM=b-Duk)+q8WPe@#wM*Znyf8Wni0Mh1ZNFH4 zo&43iAG5x)p&vXLIUK_O0$4{0A*Otzq(3P3lhXPWXR zX`I4clrSqe4rsI=qc1sjFd!Vb)7_jKdsmCIdwmnELa!G6I{d{qaG!9gmeRF$?KPBG>#P~a?@yJ+hoFoU(mk3R zRT)gjJSoJ~8KC1Yo>!gj&?(!7{a_RzjnI)4RI_{5&GNftu@ zpv)RO3xQ+Dgc^tIJdIT%Yi;4}x4TM9foDe0opk{Vabe#>hn<7=m18Q$Dtm6mbjHKi zgx#Tdb6NM-H8@aKXufBo1iQjJP_gD1VJ80nxHD@YnTKdMg>NI;=w9V}o5gRqZln5w zKvJz(dK%m09dN@)U)%tLPOh_G)Mm0{mB0zSoijzd5xeIFw9apzbbp6y$@Z(F4&)#@)c)YuleD`{a1Nk5P7CYd`TZ z{=3)ET@@R(?D8LwFl_!UUo$P&)u&sob@+Cs~Xx<lxU-H(!ap|ic<$dD3;|7r2ykHckA<8v{ zYd;J4bietWW}9{?MUS9^h+TE_&{8bOv+o%rINXTFAcc!=?HCkaH3HHpw*@3s8H!ZD z%F)-lP!OcGUZyRxYMrv(cPlm~5}4=dCLZD&EXr@L&RBDwN7g0n(kfr0C75KU!|3qw ztd8s<=~M)=KL{x((T7j?z+HpJpc9|f0v@E3VuDTy=XxN3o#A}Vuc&;uTez*E92Zl- z$@W!}!LQIEYLiws5IsPp1=w;w*R(!%Gz}Js|M?o#g4foQnk|q?@e@7Cs`+7;K?Z5z zd<4nz$m+K7ibNa)-pvO7d|GvOU$Lo^(F^Rd!7L8h>w1i1TzYETVLurv$yf|n>g;s0 zd+j7qkWtIU3JR;sfqoRTo{&~je>@{S$T=ts+dee`0JY2zke*ymIr}5RdIjB1SOkbx zYpLep9)ZzI%m|^Yyca43v0-rI^&m&=y@D$k@Uv6CGhi`d4aTN8_%i?%PHokvvQA;5$O&LLHvQ+mL((*Rg3hU3Cwk1~N-s^Wbw4~Ns1axV`ygg3wRqHP0J&z?nvwQQ&!o}*`2bZe3{T@}eRxk!A} zgqC?B`YB8nYI4M{BfJj9#$5C~5-yfOME6anwfICckB{|6^3d_u_r2fClX9Xgki4x# zXF$BHfG$k6u~?cQOWg++G)UXz#aBo>#^Xu8du>{QuBcLJg5se8D?<#=0t0my0)I7m zc4>y;fdvoQiYIHDH&E~A$3E&~V61f!bO?G64jkO?cbh-HJkK}Wt96wL*wD|d$U|*% zL41>3CR6?FlJ``s3hsv#_otPEY0EGYNtSxUp+<7=mit*tn;zc6ml|*;vTL25Rkr}C zMIGgdsvsT0puvlz3iC#|U6K-pwQy0-b{-D;edV2!21Y86-&HE$)(L+}ik2->ARqrzUi{mC_OHz?2l2CXHJy|cd~KqS8N?1( zy5Ni6Eskh~E44*(g=4>f0OzvE>22GNue${cc1>(g0tqy+LPzQqMiSpo$YN;~UoFh# zKwUuJI&?UVKNQHpkb=xYa2YKIdOts8Jpjru95y*-^i^8KfafshZPlMv@sD*sfy57i zRpUx9b^R1H3@~AXSIGH8JO_hc@Ag)+2T`w?;bQXFtit&POdo+?YAU`5{8Hm_Jq_Mk z)TIC!D+agy9{ZNv@_8TI<+?jm25KrVUYP(!gZ8Jckfyv9xU;kOl~85iaO{( ziemZHYC-a`?nwuqj*u6U-?O14qe>LNW_yZ#>;v`s53BIy#+TbG6MYc`=~gmP2B1&Z z1wA*xd-=9n8w0=7{dbLuW7vhs>HlL z5CZ|~>^XG!O`664jwHtCCV4KE7amH60}d#5}n_c(nPbilq59Ryw9<{o#2)Q^M) z?h})e25}C+MF}*a7m_au)H?|^Ir|oH5+l&~vT7c5F%{?R{3KK$5jSP3kA#@R32mwve{w>n0s6+$&vdKzxAVHx zQldgry{jt$$fA$w=dzQ|Y=}g}0>x6CoBV!Z_Y~S{AV4XmIvV6UQp5QmMgB7^0j|p=Ng8YcU)sy`*Cq`kXQf-N_;AI=B zHSy%pWs?BEf|zIwy1D2*tc%EQXTokhw+Egtr&%(Z7nZL24e=cH6$*YxP~ z|Am}?Ff}z^WAP(XKXkBqon=EEUrOR^I8l1g7m?zA>`VErP zrWwE>6#p2IThi(#)?__FX+H*1HEb?nX1Enb!~n(@-l4dRRmMmCUxA9>0EkO;L%x@h zA(~yJtfGx1i7t7`5RRTs7_;KS*te#a94bQO;7xFVM;APa{F$K>&iE!3Bs-|4^4OCb zA^q>OW7dQ2xX|Wkf+7AJR-<=`DPu=)ko_*!f2wbO6?Nv`VD}Y1;LBtmHE4u?*Q2pO zQ9(m|w3vAHiA?|F#Sc0}l~qwx%lI){Q5JzTx8fAs1WxSUR;^tPjL&Q@e`_`vv08f; zYQG2Rw<9v5s??S0X)+OY4IcLBFKsP#F{H$PZDQ+wxUUG^3R;wjmzzsbsY( zKm9C(cl@umOo(lU(HF*g%Q_25@h(MwM|dq!lW>va*>wd1kS!vl|guH7p@xj#W~D^SDaMg@sU6hM?j1;TBO zse2t!5zVH1?OzyISg#6*NJg?^i#Y%&58}fC&apx8)57 zfp-;Ej$FoGzY(&Z&N~BAOmP(WWP6HmrKi+sMi5LPVHE`7K5B7f%afm38{mFh~5Jb~H90$Z|a!XZ!e=%X&2J{>m%NOr7S0&x8T&e8O~}LN&nwC5@%> zy5qPZ)Y1{Y>mm07QoQuQLsa4%v1aMEUyqkrn%pv=$HDYACM}00B=2ebO-{Y4Hu)6Qf|kNQR~4|;k_bCG^adGe1a_NU7!zGHia{@=Hp__k}h z0UHZaS3=w4FI1(^e8zzr$-y_3dp0?(S^uGcZkw1@pqiU;%<5C2U5`pBO*hZ%@j61_94j^9`KZ z4hn+jN*GoIS74ilCb64_fEcz=KpCLi$f}m zW0Sm2K0lk-56XQrN2bZytgg&k*yOVz?edgSqbaYhZoxlb>HUwDnUXGbu!Dz=ylQ^q zupZ>>t@v%JK!CP`Qj^qM2u?1B`+ciq)9nggCq)kaf?L3sGW$*_fS*m|Y9*=g>CEo$ z&1ff?J$Ti1S01X2{m}xn3PQAYwGR4UjWwD+wqM{i4JG$SA@I{d6eBAm^x9xtxt7~N z*nQO$C3Yoo&+KG2@yg9cM(abf`|b5gYs5S~Uv>Q)hUUx9DCq}iS|!pFVp$%5hUfwm zg46D)azaFcd*fs?%@SjkLH+of##cJ+AK4(~vJ1gvN3VHFjr@7=UcN!(SVqEsxec&{ zzM(1fz1;w&*h!GUD0*9?S24jOEq2u5@&gR3oX76VX?2F%IhhXG4gm><(^@&o_F_N7 zys|@BQn;cKR#)HNX6R2yv(MpoC?S3?HJc-y-XCiDXuni|8`f>uX@jNbeG{L{^~nPi zjD7N4{PtX+Pha$anPZ{>r3SUZJ(HFV~AaP&9F zvkeZG+Tm>%m~;s4gVrzr&Ca!;zW}ma%8mLkbMwgdOM!}L4kSjv+j90sJh<>B5r!)Mu)&Jr=l_2`qZ}U5`jN! z;s67Pr?C_m2hIlJP8;UC2It+a*k*fg!04|4J|FWr-+K(;4fMo@r!PaeRRJ9a>Ro;a zcGU9%*$%^uDscO^uDU$lkXkkwNq>&|VWkUc^~ohj`(d~G9!H-5$hF!RVB4F4oG^tR zKsB=CEx3K1tuipq)-DaPCyD9DUabO0_3W%eS{hl#tzlbvhn&vm-KJ)9U2^jLhxGdR} z5-i8~&_6wuHo?EZ`%1{fI6zA3pf`CR^R-+qd4%)^I9wI=O_wa=PoC%&<^*1V^MHdf zRxkqGil||Z09tO7gy1ls_I&Ksa*6WKeaFd|JA%>NVOjpeeyI(vGqgm>WBT_=5m40x zs81w2gJ`fPhxF+htL+0Y&01C~ATs&!PC?>Nbcb9rhs0nCw_Jm1PA(SY9yqjRg8CVH z5R|)Wn==IhOYDz+^?hO7^4AhQNanQ6y6KG|VTO6ee*-yE9ccrxv=nH>0xyz$Ze*Mf zOsr+Ty$Z%`H$}ukgqZZ!MMzwB^H@{=&wz4M7Ki{gbvyIbgbF__QTU21l|XPsw@Ai2 zc!Xi+OavQJ)S8`EFS{h)TjWXpVBfMeHGe-2d=EL}Xu`O2zxKry^S3_-h7WV;Mw#1K z^4eX39kx*U)asedn-p&R&9==i^lD;H?#GKvNy3vvqOGZ1q5a_b6hHmE-%i3cXsV-x zG026{$%V0-mjxZOf&JJ%~992EO{!(J)Ke>SVb>?*ZBy>4}L{XBXRxpR4aM?Nv+=!DEX8t;G7hIMcb+_s13V8j*DegHPBh( z?IOJdx>|QBd-=y;E~+%CdiQe!>+Hi}u-)shse$mXpBZhF{r`dCG=(vo8&H{{ist+K zW;iiK0S=_WgsZ@+=^=F3iN`>I+qN|~Es4?p{td~V+U^68rQsk#l6!ecxciQ;8AI*{ z^8UUVBEum(!cOe|l8r3?+8blYL3qNhuM&duLa9pSaK#>J)9``*YJr-dRF&;SS9O~$ zpbxU|<5;-%)Q?NHFM?m#Qg85D&)LCHRA#sFlh@r2+1*&^s17=66oDr(TLdo;q)qT6 zDt?IBnM8D#n<;@BjGZ-qHD@&|)fiN^|DwGP-u%^De{ZNcoB0~WJlz4fw1xi2l}m}p zX76gu!JDYM2N4939ZL^ari!)HB%cvGh`FY`P8IUJ61NAUc}(oZf+Tf8^aMJU{)6`@ z_Oy^%*3Bye~t~g7W8BJpL>2mAwE@S&r~EoOT(9wjk0s~ zby4Evd-D{B9t*+VQx_`zI}X^c(U*6CjL|@dYZ%0iqY1sO z174OPpyZHz_nw3luS7XN8XL%n7AFvJ4j@)gA9gEP7A{xO={lIUX6kldi&HC#2-^mU z78384#wLf}xpfQyG{OUviQO{nAGgRAn_|JXz-#>`Ifggt& zvk{1=h?Dw4vhK(j1CAfU*5;LH+f~YH(l!LmX^`(B(!u|EtcKd~-(lit;M~Y#8$Wv; z73@xp@d=k%Q~fIA@yoGO6g_8b58^ww`eg<6=O`Ppgxh$5PAe_4E8P~S_c;=$pRX*T zdFdDC$B)BL&xU$!gB|JAVprCN)1-E;t-czjy3AzkZ7O1V7!;eBds zrSw0K{=&a{(0uyVAlxX6w|_8+T?Z!<_^-9QxWr6o*)~&kHv$L7k0T1hFuP1Q;;l|# z7noHC%C^ZzY6$JHxpl5ox8ta{#8KlUtOlP5UctI2$Y5{@PYW-X5Fl11aRnzp@f|^}p_(dVc@!c%Jh;_cvg>@kPeW~H+-k(x%y)o zqGw`kYXY9Uc=BY7&ryE;lFl|W zwLgt72BGj{t#3ilpiGVi_4;EYJB5CGwKni-+d?U(>q*3F5brpRGmamTHFhOk)i_9R zr<&C>7*tcH62D!`d(2kyBZAGe`|I^qC=J3gF-SNs`ex3R*>NtCbN=uB{OA5P;#o}2;V1{b~jK78yh> zKO?@#{jdYm8AqA5f}9o!H2IHN9IUIjZp!Zuty0I&6uP@q4`oo7W;;tP8Zq zx6cH6l|7ri4Xo(v0P1s z+=H=CjkmDp3!kLv-j zUjCEA#fQKCm(R(6%;(Tp-omH3g`PJRVw&sQs%B0^9ad#T#n_#vrgd<7op%B=o$QK+ zf*A7Dw?)!xNS%p-CB{l@_hp(lyISgWzIDcTg7YlJUK?(+Z>)wp<PzxpD9U6!?FL2kig8>prmp<4RVOb?;D|_N;nXE~t1ns)DW>zS;gGe-oX9 zjSnE@Hz*SWjLFiTN&jU6|NaG?2e!fz@`D*E2fcq59o;tJN`{aFDi4;zfQP-GJO)i2T?y*=ZFD$STNGn~$cw$&6-fm=_KKn8vPQt~9%$^Nc-mZNlxxR*eT zpsKw(06R|V<9ID;$Av^&mN(Dm>=szwX@675hOM$%!aZ@!O}YS`b7j-&=TEv%V~TBm z`7{LD&$=kD{b+yd<-Q_pkYHqeDBgkc;x9+DZ&G?azv}i>!0z%(H2s0*%h;S+`AG-E z8)f>^SBX*bhVpQHO#1oTT3HH2y)SQ&aYGlm#9>mRU95mG;{t{kQQy;j(C9U!GXyFS zRi`OOq9?VDG>R2?v#;qH8#rn6f2b>`@X%ZeJ|`+C&|PEI|-)6X5m^pZ)#Os3AbrhfeSs z*iO@mQ-8gNso0xPAqDb?i-9ykRvVRMt^C*tQ9A0mgP~w?~5n5I?Qu zZ)R?+fV+D$?4h7y1DIBnWBr+RVbsG^Lz=c@Dg0oV8BG!*QJ0iPrwrdpm<#{y<;_-uFFKW%#&fdA2;K#A3G;6P8uq7B74fKAPQxj^hvC~C|df_YR! zDoNy6_~o=r)Di0dpLB`%`mh#gYi_iVsG>s0W9UGHk+7&J>`Vvhg`CH*@yhAYq741% zq5i{_{dwEUVJ;!NwJC+k7y<6gjwl^95vV{XgK}q2&Ai)4rv4o&a6~@c*lG?!hgkgc zoFD(kIV)?yITxNr6dU|Dclw{^zSsu4(z5my0jg$Xe?(;m=cb-B3Zx>o2*BeylCkNJ zNHO#YP+Ak17y~fgKy=~q?Py#6r2$3kl|(vnnMr`oZd5jIZNg4x6OP9_kj!eoQ#W0@ zeD+Mt-<&d>Xc9c4MeI~E#`4dY_x`V#w=bIg&6d{RJp^M0BoZBne&}EOMQs79uW@qX z)2*PrF1aKg99E3mjf9v6uQ;Ymk4sK|8?|ZgSrjLWa87POC}-fOJ(|Blz80AgJt za5}Aqp>%7c2B30o!67&m-uw62#zD0!=#h!9LFP3AHUjrD%_uqC08M?^Ow9q{5#yKe z1D~~byZz6bxTM!-TEm#Vl;T;ZmGJQcQRQsw%MfEbw|H`E+4W0*8|S0_NC2f1j+yo$ zo;o2Ob+}RsLw*R#pGSHIjx>7Cx5Rot`FDI$pnC$u@c-#hJ5HTGx&FEhp=W*_>I>PB ztbH7eN&rYB-)3Q*ql*6A1<*kbAFLjvje&T=MlhU5^MMIlz>X3$&&=Jb?8iS|Z!ClH zBA8WEtQ_;0Pm`u>y7Oag(&+IG>EcQ^rSNik_qe|e!U_$Kpp~2Yeq92`(O0oLoqG>R zyuVEL*Ygnxm|gqpI20JsQ`0Suj;_A=4OZ1hmN&rb6BD$oNSS^vO_E#bPH^d8iv zKAiw1>5J{|4TLxBT|K)ZrJurc_i-2Lcm!P3P$;34oY=4jcT^t52w?n^yAmRrI(SNQ zae@VHm8l3oTOI=KVg;0%DNIEV`N-DGdp}9_iM?}>3 zoIJwL@7IT}Vie`3%pc9xw%srV-oTad*gV19wvF;(xknVe2y+|76MuaMa~GU=8@_8mFHMzHQN<>|Rc$ z;b^7j{#@}5bR;pjC?@Jer(e%b7x8Bu-PrR6XRE^zm2#mM_LDl6oap%4p84}rVs!?P zi$3ND8TV5A-0izF{&FAHOh5a_M*hj^-kXp3uCv|FjoyO-RwiKzcrY2x3!fX^f#=ao zD5>BCk^z+7k@rbC^lnR;Q?5#p2UV2ng66S+9+1gkRcqRNINnde{%5f6Z4HfMq(HWT zIco@;(JPHXObJ`!x-jf_HpMf0=fA1%;k+_305Sdm#4BQFpp5p3H0i>E#DE0A{KOgh zHMBEllcck@pqcQp81T*5XDPG{9A{=^!)-ZE^L5KUn!ntFO{J_41B=HzQKKvSt@J+s zFqyQVi~=PMYS{J5!7G~FS(@Yj`CetA5FSllvTDE52HY2j@}xJhEDU~K2?bfWNS?_` z+_w2RxdG`qp`l4c zg`oX1>x8(|Ob}{q`+1slm+LU=_|j3^(Bq|)cg~p}lq+m~1BxuE0b#%fk1>J9VSp=Y zh^rQM$3(j7(2gMwR~p@OC$H1`^dAgYPt^O?pU(z^L&1ZUj&l(Tt>wVYh}~oZcu?s6 z*U;qr6?`Z6{mpL?LT(ctIp@jjs-xw zz_;GLzf!h5jjeDjtG7Idg?c-o0a6*h>E{IZHatd9G4uR!qWW)OhZ^Nxced)YIG_K0 z%3vOhr?;?|j@>EuilI37Xzj?>=? z3*%b>OQ2?V$N~+3a1c_Z`}P246vCiRU{4ZgqC3{NeiOKyqWkaoOFehQKTM7{!tcAQ@mI$5?_WgYpoS=M zDn9aDQ<7SwoqHmwG!o?jr%hrka|i43r$_bZ*}|o(!7X4!NJ}E#~AH>xpBD+R=r&vlR*~y9Hf`mRpE$Z`9tGiY|5-)6}I( z5Bvr_jr=*KA;cdk3*WmDMk&|f)wTFSI4IwT=KSq=SobT%XVV4c*nu=x6D$~re@0Iw z*S&6Kiwc_nxYP&IL>AoDD12SBLd)6o%G*HB1o7)m{t3DM%b)(d@SfVTrO>-kSG(}T zmNLqudWqGLg3UV3ffz?j|K%0+_q-zC(tvACi(9Rs-_Uwsc3eVG{PWY2@iTj;g{;ov zG^qGDFaz)11^Jv)sO7Ni-YIN+X@TOB0RR#KiXM8ZTQM1=tOp_*%`#w84@ z_h;XIcM*6=n*sAi?l)X#p4a%ID2)foklj)84wm36um=EL*_s?01=rqW*O`bKQ z2VMNq+*fDbZM0F22)()g4L5-$8KdzkF1nTGSKEZOkI4a3?u6{h>3^Ft0J<thKpeS>jlN_17=DZc$R<|d^a%=+KGkle?v*Ye<;x zM!<^cLX?y&eGgBqs>30=+wl5kCmQIwqLz-N&auy zR>@KjhmzGg+0C;4)mTw@V9dG4;fVsMAY{j4;r%-Z@j?*F?h@l-#sh%@)+r@BG_s|r z?e<^y84)G`5&Y_h=>V;#$0SWNzfr96pS`Wu480>gdrZ+v7{EWz+V`RQZ21pE+ubOC z(_PV7Dt`m~&8u=!RekX3u_-85AL;67eiY9FH|Z-4gBA6!c(JGAx78P)KKara?RKLo zyPTYIpebJ^+OLm)zdb7Nh@&21tv6?F@2C3X6SNy;szD^%MwpmN?ka^ zjlhvpl3HOw7DdY46P%5ax{R7LkFDdK`Cn!f?<8>Oft@R~@_UTH?T=2yAU-~HE)Qg! z%@G5*gn9mx)N3BUhIhLYSGMaTsYOK+4uHDwqzS$pKBagg$-@2n`P2=q!f1hZ@Q7@zi-A=aZQy~sz z@fY{n!Dc_JoFZ^j3|58A03c1IDz*{iK9_9S0vfJN5+{3R8?Yd|wGShk`a1ezH5s1t zI*gmNf*WmtJ$)^=RK=OW!*YO>EMvBEG6O2omE7$lMRjpQZ^%nKwtOe&mO;NKx#8u) zBvW=V0z)HKis~SduRcol;Gg6hl2HuNH?F#sRyYdBjLc-;tWi2T8pJ4D>^&D5p1ujT zm=Mo+CZYoa9Y*mdPwa35X8T6iup!YJ*lrOyMu zdy(WGZ3(gv1n{d@Do0xqjgSjT0<=uDXg1U{A{x@`g9ZAnAiv27YE`RwU0*w%+$gv1 zyQZ8bqDdv{`jLbjH$Z&abc!6IcKB%WH6u4GdK{g9JUtAyzC?1h{!e4->^k_6(=gs8 zov~(x2mefhdT?%X+GM$VsGR0=6!8a>DO3hpnQ^fuYyP(jgU#lZR%6vA)!!2ITe1}6 zFm_Tm_9Wp2S!UDirMXSS9N->ki0w>iAU?)i0%i!eM1`ejxx`ECzYjLb_F2C98OcXH zoWLe)fL=!{bo?SD*=s$7p%u)$I8?;7eWt>wdfyv38DW41dwh6mLLw(spbF9g(CNMA z{QZ+O5OSDjTyKGd*apDHVITot|;T5m;GrS{7k{}CK^o9KTzJFe=SGIyzw7~ zy+N@jSL4b_SLw|eU|twE(qXErSrn~{eD$t`cAq>lDIm zttR)GqWdvwcL>R*2iDlg)X9VXHYh7h;X^K6!WQkv>z@WM6sXoUS%$tjP7ps|N&n$> zDc|e{9b$M@41WU$r{$qv|Jhra^Pf6&5GZDL@hYJCL;@c`5~0h9(2Il~U&3S4eE6u3 z`;V5Ase306J*PjuOf;m(=US%}b+!FWxAE3@fW62Al}*KEvm?o808#4JQ*IMF1sP}L zc`i;5l*+^9P7o@*z>|J@vRmJHav%0+1><*yc%sh<*$KDbC2o>al)5ejUBHGXBj}ui zv`bOHD{9i8Y2-Pg)E~1?v2d~|(6&R+fI0xcmXh7%GM;IU8>3u-Lx{(N^qgi*Hg#f|MDqmV2)X-5SyZ*nYji_ywdm!)$~ zHDn-p8wLI(xUpPQ5(-?3GUm|x4!yDaO znG_oE&|VQ-s=f8;k4fx!7_8FS1v(TZG_ekTEMy)p^=5`xeJOpJ3;U$r$FZnhlYdb zvl#*{w*|N)bFcPL$SR5#5P$BVH%?VzfsOj?PNJX4>Kh^q!izjDT0IImK**kf)kKb( ze&AV9d=aaMjQ~X=+*h5U$0irNJ1Y;7S-n6-4k2v#&Gao(bT|gXcZTVV+)3T(rmdei z@~^z(-(bmxdPpgDxbO^P{FJ7smmCye4Yy+3UAGaa`l3xSp84$PZrAMIbXlLaL`@03 zBFNSu%XmXX3>g+}mS@y$L^$`yE;PahM@}?{hQ&Jh2S`k=G9#buCn;Zfc$7ucXz#fAI zQW})5jM#%5thJDO6J4MV3xwP?)|M6W$F3SjxktPj2H3f?hCo zHe3(zf|*fd@4v-8E>V7Nku0_5GK-O#!R|-NNjBSKG%hlHd^7)yQWFiun)>30fxf_}Ej_uTL3frqWbi?Id06k~G zghDKJk_|s>$p)s*2!7kvMf4Asu_Mh-?`3OW#%$cMLqpXfe1&QVs*4Uwr*)QvvtraH zn@sCm5TRtzwC~|n>-gqN{?3JU%29VVIgoE7%64RlV-PqXEZ?ksY}i}epfZUPTC3fX zgAPH2AU^;|W26o0E1wDC$%Fg*2F>$_qg!m;pXAB{l^HB-BlKROE@ zwY1fZF`U0|H*gXr;ZZ*0lIQL!2do@3b{_z-up$6;Q#LAVI-Xn!gRP38AvB%}K-m1k z*X0^qaQU@by3Ih|-5Z(Ew$Y$~QmORe#{Jp7joA$FBr}CItHcN_U)V=B1N^X0m$)Cy zDYLDCFIAkbJ6ODe)>B4y$2o>xPM)%P^p75(6{8WB!t^dNiuixNy)&dagpktO0K~Cp z0`NGmF4A9*q{@H=(CAH8wH_`aP+cWELiR8YXsXB)oR_@NlI80d?!g}nD1QQ{M9Y!&Z1o#~pkPJeE+ z9Rcgla>n^rK<-4HCbS89Og7#{K>Fm$t6OQM5i}|ICjQ`f?Oq_Ew!N)6Ik5s6%I|zm zx)Aas`5*K;c~Nxd2P>tvC3M9-2cpDC+Ii@uNTJ6NHyC0pCBbA4GQ3r)l~1985$zTA zwUKAM95g#5;#(hiGeBIrP2%eE%a#e6<{Yu2xXPwLeSfp|v~raO6t<;3N#%%Vyj8R6|8%W@L!s#isOLE8!wJ z)P|Pn6(EeR2vYNENto;D<(;8d+wZLVF1>z3UsO^=KAAq;9O^STTpxlAc^3e5 zWNwUaC`LQDOQ-kF{UOH26*ef2Tr{xI9|0&$?uD5-p8h?N&V9P+p+<7CZ`nb%5pz|p z0I{Z*J}uHOxgUxh!$wNl@2-;0RkO?^TfFd+Pp2VZs*mmFk`K0+@5#O;qsP%1Tc7O5 zd&-o=P|XR}!#`dZ+wQ;BCRwIMI$c;)J%hW^B{-QB8Zd7~b~{=Pg;skuHf0&Lqi7G` z2%PxNVe4ZNP%xF6e_#+Fa+2{fdh7g(C9Wj;2drdxTNnZuJ#Otq_E=2aP`<+-3ud7j zE<3Mx=_0)$w6_BBb>WpVLRUs7KRX8*EJVs+v$fK{_<#kbqZ(zB`Nc@hkjLBFs;8Z@!6iV zP50T6Z-nVgE89YJ2F2($+nQc)zgeY_WI`3-7Uduf)CC=zkeg&6pyw!C--3o#%zp}b zvZSpcw%@~ENQV@i3KnvQEYn;PdPxnKY38N!>|(fX%8~MRx0-D-Mc>9?SYoC(do`=_ zzQJ4JZ^0fWI#d%YD3Dg6;o6k&(wc%hTH$_*o(4x$+vBC^u6__$ zTtAD`lJ3`kF0O8iX;^AGr3uNf+^%s@G;6sm{uXLYnbio5unSSgmU++lQjbxC@T)*j z{5;1&-K4TyomvuOiQPu&UEGKbdousD;CZx!V>|;LY9rl2}c(@pK~!BI~Bsz zy{kqMw-MebUikt>%aE3r>>WYd;ZNHVx1RI?>VS{oxHIFr#+T{@ue}}T&N`9@Hz2Kp zkXx8)C1@txG8FZ)usTCe@M7$%PXacGxKyy+APh#TEvMToikGnp3F#SI@+}1xCIX{K^v-)GUv@1C$8GE;2V7hREEOz z*)^~t@1?u@R>G=65Zy2#Qs+qRVYrscbm8>0uFoyqa=gn^ggxbhwbLbi=ff5kSrT?9 zd{2GY*1!*tJ3M)CWsz^CP3Di!_a7Lm&p|^WVUxcP$E}U>tBi-O*48An8dk9=wLO}z z{h$=Y604ozu$f-2lE5-^|DZ{x3o4&F>=kY8+r=i$V@YINSMNy%u$UAFTsIzQQ%k28 zB48F1AZSne`b{41-m}yF9^a2yR6Udew$Zlj0d$ezwO_M0gl)Z2>)wf1NIC8-I&Xz~A+ zX2V~lW>Dq&hKm#);B^r&f--WT{}~vO49AL(Hy~@|Nos)X{}pongc=(o@6s+pVd-$PPR?l zURJH03cwTl7UpVtp>2`;QYM{_Hqw2q^+fj$W$$=kCh=Co4TQ5v>S|-JT5e##l$!I* zmhvraYY_s|lGvDkXlI;bJnkb(w=PLtL}{6dO;>Ef!^W&m)80E`#O!&Y0(mEw=E`*{ zcYA|c_mYh{KK64!#vO9!)kSrh*4JAWf2h_BfL`J4E&p8G<>8WGoeQV7s2M3xjMdd? zc3tdOoa&))gI$q>S%E_!!FkxY29r^V9fYJXKujLtYurfSQg7AEfF^AOSqUa7UH-?Z zmfyOwJ zzxa~e@IF8o_66uG{EMOwqz}?=!$ST%sm#zB^>Yy^K2NvY+uYS{Ecei`I%7|Z zp$q3^9Mf3qOj{qL&rC4iNC<_g3kF$ie<{Sx@*HtGD(G-^450-J~b5H3;vC{8+kfr`Mdw#UXJk5}atiXMQ5t-(@#A z|F#7h?H36^sq=03C=7G-*u*LC{mqN@6|Kiu>=samLj?c(=ljuMM7|2^`q0b}}`-*}OpU%vqC#3>ulPxb|baW~VGXP0#YdM~`$wiW>~y z2=>t!UfLTri&8ways0&O=B&xf)lfisyr^S}tj}~0lROd#_Xz`n&9f3!{6pRxo*n;vJB{I|sW|5vZl9(KtJW8R>N5%akoAn(p>m$tJXBtXK@w z7>$rg5=5E^jyVR#BSG;ipyy-dA+%r@@`88SG5SR|9rT(~73dIG0?OCqDU~c0Pz18g~7`9Tdrh5m~ zdWd&fKNzO%se<$mOs5xp8?fqfWD{m6!vIE=OwAxi7ryl=`-Cx4o^X7+3Kev6Ww8|t zTzp{8BjhOOg6$OlZJ(5j7#?rWoTlpawe#x)i_$ILmVXiI1p@+jM`lz#XJ#y4cj+Lw zTMO1@7W*sL39GvqU4iQ>`}B34I08=}8Uk|fJ^jcWw!18J!Zpc+3ogpa;l`9y*y`L4 z{6nPQACteVKFJ9Rpo^Cu`>B1#w|NFLTWjQ4c23_vy|_jNYb}l-I;~ULWk+qnr2O}! z>$SAG0aK95T&x7%{iu$bO9!p#8j4W%P09DlP+fnk?uh%J@=xj^$|E5b`h8GrklTA4(_Mv2axvsAS$LD&+oV}y{FQ}U>#09R)kD60;# zWowrk78(M01jKc=ns>*bsRA!86|N#al2P^=VtJTKHgg8AoAX0 z|3(Z3=4XZI|pgZ+Ifs`npQP2yM3ki)mz&7;pSP#KWgd$G4_^I+nzP zFQYdT$|B@V(PZblG`rAb1T^!p3A0{IM4D&&%U`Tj{Ghig9e6f5%Fc2ikgc{{1V^AC zh6Sp&Zzgl|ObnoWzDy=ryU@Wd*qu8MBPgSfKWtEB7{5-`!^U*E&V+Z_LImVppPQ#! z+q}|viE%>IK8ibD&c-WVW$CWTzg7ASrr)SF93TBKiDJ{>o1Nh>1H#-Vizvaor_&$H z;#lw8{KFwU5b-%Ygtt~ilp66>uepiSo!0fi6i3WpwGPI$@x^mLOa?e>2fDjncpmX@ z_2UHio*uh>xD?bXqnL3HQWUS^Vi54FJ`=WPq1(kP_CS<+afWBYd45if>?CHW=^-9< zCK7t?0yPLMyRice>^tZ>tfGL3X6?BLX7-`2wOM>|k^l&%Ir5v1_d_f%8?mhsYxe6W z2#S_v!qzC=*) zcW~okHbz>_>@?()bqaT7OR}r*pz7AY^UIwIr=hKO7PgARiWsD;1O^twc{$f>-z~M% z`ts3+h}XkFk4Ex_YD%~Mr3r;sn;xrg=9{vk{y^9_F=kOrD$30PI>&`{uSu^sLhO48 z2NTkAu7^}5o2W~(bVry=x0a*Lm~R&tYI!*k5VpIUk%>jg&`~WG+_iW+-7O-0H7E^I zGd!{Z_sECD11j!c2B;yfCN!Z|;dH8#k?lh6$kOTnqv8Ur6LL9q>gOh&kJE$}ah94o z-E>2#MaJGlM22kE-n)4wjCVcv^=2PVK$YzmQ@nXs?yjen`GqccD(msfbAIlmTz85S zMy=Up>-|_SaLG1wk`%M-$eQK8POFe6RZLC1J2*wB^;anVddUS&j*vtVv=4bG%RFm;3QY zQcgH^ly2Jv!&oT>Y=y1*uZzMT%x*$ghDimbDrYlGm)jyy4*k8`AD@Zqqc{?k)yP#z z*||l-3iEZu5d==9aBeN&;!m`76dk9(-+O9P7-M^Hs4%UIW}KjE`y!z?t_ULmI< zMi-vb4L?#oT1`3bzOT|k_0YqD^&i@Ze2NDl49HuvzPAP+HQXD_-*@o4s;zC{^w7Ml zk8(CO)?cU)h<6$kB0V{XQ{8a^|4TaXcev*-iC`cH%765@Rgp zh1UcK$(aJZygz#M)&^~kGLc{ICgOxrC2|>YeoCmNfn_nUURjL!7SsWc3he2ns@?|( zmUsvQ-pceXu!?h$^fHPhz($qi;j_g{s+ymlCYHJLy;l|&E2b>*47!7jMD-v}Kq7~} z1s;}a%_EV1Ou_K$C`P8u0|0XAo?w~kRbi1@jne=^8@q|Koh>@<)(AwvC4np44ijQ* zT-Z)7l@f=`Wg0^6NfMqva+kb|qYEl8=9C;kBPO9qtI$B#=2q^<0Rf7RFrQrK44>=- zVc8)~9a~}rP4v$?@p%uQkN+(+A5Djv`9-)}q{L#B0{!j6;+oRlor^R6(0b$_NzW$- z9uo+V8y8&&@>}ez=n1F3f$slD8!>dY6i`l);O!lQ$A9!>46b?qSkj>Zg9{u7#_^!X z?86Y9?RA?|mY__>RpSD;WgHhTDLy1j{e%MS76w6AR}7%Z%3M(Be4YG#C+?L=emXrv zWr7FfCWGytU6>BF$8iG)sYRHs7FCYSTzh_xUv2#KQF-yaid*g>3DICd9A%a^R5~99 z)h6s+81$Bz!?#Nur)54|!p=xLS8+6Kmb>+-pbgbheJR#JVEsn;b_naur+iM~pg_&| zv|7A)=N<3Rqtw?|*YFvi|2=(2Joe<`qtTDUvBfGFJAm!$$p{(AG$ccF@xvUbD>MrS zG?QrFc87FwRAvIzrjl^4Nl28PH|Ynbm`FFQid?_Xgs(`6GZRV5|A}2%YwZ#<9}g)%zZY3Sl>NUi*O+BDn^!jU|QmtFcVa>Yx5~6 z@o_w2dFC#In_1RQs`#eFWl0M-?XOAf@@TByxief#aNkO;IOkMAf&m%9VWp$}yQC}f zVIQu$G=8{ZrrGZaHDhZFCqI!pN9AT~Kw;mDLr!;?H%ko|U7aOJ8mx7U5PX~$auA3? z`t%(Y)B*t=aB{P{31F2 zC;Z{p1C7QxUPp_>O$=O6g64lZnSg;*ZFiV{JLyBRaY(iWjOq zPt&#Gdu7-paZCSLkZQ1vYx^?!ELP;rt8Vqpxvnd80^tMGkT(veh6fmr8|H!M(v(@A zKj{I=qJqzvE%7v7q7PD0v_}XGFFwUoz)&^bv`0|RC&~S3SS8x(X=bwCi`%TgLW_@# zQ_~(#*QvOtsjB;GB3yPwRT&c`D!c8^EokYq_L7%UQ47 z$^>r`cy(;bfT-G<$c+2#>eMoKbPWHtAw(QZW!$+eDfbLfh6Il5i%)Nmq#pv5a$8VM ziw$5*;kb`+0JLvjQ$gc01f0F|A|?4x(^U|)_rEFe>%8xA_j)#Pww#xJN0*TOvQ9H} zIJyspxA|+y^!ubI7JJ`3uw)A-<0`Vyv*OC5^8$|UoY}1R=2u1i^nhJ$u8>u`SbNOI z8;P9Tv6{-wd3g3i1`i@~e!%`0&H}M!=-DRh8He4CLN47OFw_=mJ%Z zlmV*1Tx9g9UK%>#?aP9?*^D+{#5J$`!qM0%PE?(iS8+Pe;B`P>q07en#0!9_$X4h; z=D}p#PLA$AbQ-R^Z@c0*PrD30RcSwMpYZX!aqCIQ8KdY+pI zceDeo+$hVN=j3<#_D%=I5}As5yM-9p9O5NouL2(^!~bL^vSr1EODVy7h9o`d;{y;W zI5A>A@FuN~9jHsQS2Ukh!lubFLdc`vm0)}Otpt4J-I#cCvRy#auBT@#*p@A*DGq%) z9)M=v=c5bFW|6|#u!NdLY#Qf7o$UbQDY+ZP>XTaSc!Zc$j#V8aU56tS_bg954o4@S z#qTPrdVZE_S6E8wnAELg{j$5D>g!or@O{jhL-PGBq&Ug>Ea}P@sXIN^czeWnU+pS$ z*}q-Lj&wQCjB)+V*66{acD+d7;`JSmy5|?S6-ijrX)``qI`yy;KwK~oK^; z?fv%QDssZzq;|1OuXeMD19qYDltuL}R^DqRvD)L>A#%*NtP9t&CrUMZg^-7UN1_B5 zrxAXI&W0 z8l><;(YWc(wn$N&>7`QQWDOpnSS>Bh2%1t@UbYm0HNSD2bDff-LmM_O`_@l1wG=D2 z>vrF9Np^-8Ws+pQQ`u?Yhk;%iBf1J_)LZc13-VeBCN{-+Bi>_h{UwhEwb`@T%RU zp;(lWo?W`(cAmD&$2cPkfub;CvBR4QG|pc8-Q`9{Gi1~*k6Xs2vuoDsYRstRaT?{R z^I1|Io9I#~7Hjv1llY&Tk`@7DuKJ-W9D%Z>)0R93jJCrRP= z*W%sY{{IZnen~N9O@s2G9*SY zq)XA>mLEMD5T4V}V)i!*{al zKrv5iX$JUrv~Hm;y?({c;l?1z?9}6Ir%2U&85zeGi~3s<_NE5rl5s&($oNZws>u3; zf{hHZZPMuV_)B6NQ}k#5^j6P#&t~w)8!Sg;E*QjPkScl}E62Ql!nIXwI3LH8XmJ07 zxxPG(G4B&$&Zg1MAv@|n9aBx$n(yhMEu`dKr24icEt%ul#~x#8`@HG<%BXy=vM76Y z-&W+dh!#($;LN!ur}_SZ%8|Tc6(DGMPCwnkX@p@X_i68U6CaBhmysu1=`3Lo)M*}m zyXW?-Ys*sd@XH6+8TpgdS7o{my*wMQV^(e*-Pc3bL2td*C*fjxyVEnH>*_M=Ku`U` zZR8wz^B#p|i2j(J$f?;`k20iDB0as3FX!plyoBJo{YTn)IQ`d!Z}S)}4qTpE*Hw=m zROcjjeBCNPZV9~p!R+~j`15<$|J{esNf}q8@1LAZ7mkl$D@QeOMqHacWL}f(ppn!v|U^x^YLg6RMutl;%gp{^ozDy1x9V-(p(00#b1jQ zZdew`#B_ zq{Haik|Hz48i?sD?z@dx=jg_?-}D?=q7WQnecC200dHY)*AFhD0(+0wN_*GQ{9U_t zR&4@ICUKWb;@l<-zfPJi!ruy=napd}N{NgaW7kXjy;+pF0GmVI(F2b(Ri*Az9vyY` zVP!)&PkD_A`z3O1nRTJ#$F?U&^OBZ;Xn2#R$wv7sn~|hs_>fUMK=SC)oA-3>CJ%kJ zW-ipwe4>E!h%OQz)>(D1Yy~$z?*q=tWXZc~{d7H#^&XXPc3g=v z*N4SQ#-*1oK`2R0^@#w85|K+lWE2A!ZDSLt5|k#t)t};B&}01q(MGl{n!v`c7gJ2jIz;@Hte{`fjCb*HmQwctZSN{DD&( z${#R`Ck9OcSD&BF!I|m8op{1b8dMlBE!cgx=5waV6}Yu3gX-~eq*thaT8c%}<8x2& zIIEv0n+rKi)E1@%Y%KZqdg$;yp$7{ogdJ%7Uxx5F%GF#)?W!sy4A+xXu_MhKKaod% zZ8$2Sq}E;OTQb~zYyNCcvrYXbcuFMvsQS}m#xJ*f-^`9qp6p1C9`vQ3#K-ef)i7UJ z1Ml~tHp=6pS*gOk^cKFtb5&g4(|C$$%`C_}>ye_X-(Qd1RmSc<9hvRDPCKrBXT);E zIFNuiG2?*;Rp9>Yrs(9p%Hh4s+hRtEO54G#>}crwTSP?vl12Oq0taND>Idte2;=<9 zFI*4`Bfd{4#?&*KCV+`ewJxibF)Ukg5(*6`UOusJp_O@5ZR9Uyk6*dRH($mev z`tYpbrTj9L(t@LLrNb}ZA#BFyXRjJ+cFT7o%!ui3#C^9L*qjIQt(lP` z_oO|7x0#SG>;70Y-`~7-a;dhfS*d)~Lz2GN(xkFy|8U%){y6qqr(?)e#h~65wp&$O zj#VP9hx=b>e;d5cf6Rzb1&N zqxGl9{cc3bkgZAd>!2^wMVFr{i6>>sJPf1sYa!5?v7p=MW|bGTxCpnE)Z`0sKo4w? zKbO3oJN(^C7NSQ?@ zV6~u+!x}6VTN~DbI3aX=!0Bz@22J{_os;90qsV7AGLFlc(reu*S5^ZO=Am}^*|9j@@p3ms5sfSP~jxzycZ;5H!I6NTuQ+&PdjQg zH=uI9!Ei-MD6BgLnbU*ZDO1!ngEX#j_Qz7yviz1f1nMt^nsz8vQ+;)BTQsaG(`}3G)v3!Ey8C#koM@gnI`-b48c*p-cb?3I2y?mEi6G-;I?AtF+1w(lL%CyhnjZ&&efZ4Hw753UnObAoOk-9X8j zWhW!hmva~V z+mI7UD5^?PjA<7>VHYsS4w@ntO`^@&0{<$uVf~IA+yVSf<(USjhxMnUmpj6vK!U-S zbXHW~m)n(Bk^r2;R{E*8#+-s_H%t0_=ckhcugOEhQt#zNup4k0t<-lH1bfRhbI8+^ zXdT82Bv2-E87_VO4Fzm_c{yR)t@&>;gZBBfz=VK96-#RD#?*m>* ztym(t856}M;AHt(5~y1~4p)d*H_0%@W8b3+q)3n1fVxSx^dQpFm4qW<&U&pcnX)fO z@2Ki;ofn^rGlcHQ`^Yb6Z(`TMvYgWIU#%y(n%}0_jp3C0yxS1#NKAiB9ALEZSo^Ex z(*D6CRd2`&sx$8+A7?Fk-=AxT3jfGf*5i(I$f80tO>224XAP5!@8Yd=kxv%S_CH!) z>TE|YLdKGov|lsV#xuFsCU|zlzV{<4c!+j*wTj^dYoN=&i_o<5pYYnBD}h;lmiBh_>(m44&+Hvq2#oa(MQPH1 zWU+uA;d0QFs?XxB4+4-eZ%5kgc$$GukWxYvM8D?|+xQ|#{)9(nx#P^wj6g()y7e)4 zD-qtxR@-p7bhc3UNMh7{%nt*;2s3X}n;HlaoRCaiAo}M0kyi9f6({@uJ&|z>xQ9uh zrvndeVs{&1aFo7h5Eqqtyy)CQblqHZxmb3~^f>Qz;pL~ySCk^df~t_&3SxIGlJ63a zRttSkkRz=h+o^6B=S-F)Rz6IgQE8IL2^%L4XrJEgG&y%QKHok0(#>RDY+0!#AH$V2U)FpftxVLb=H=fYm3BL*%+cHVz3}tlbJI zkldN)IGBR2L=VFoHxQ@o%#Z*lrQK`$g++4zgSlu-?&Rw;Y55qF1<0 zKL5qO&!8U9w7#mc&+`a=)&7z1>ti&d3#4&iaMy6p^_oGt1}&Q10uT zIdTF~FUyT)1W*U2=)wr?CK9YiXG2pMwN(8Y5SW|u@8}Ch^8QP`(Qhbqs<+}+f=m1> z0YSMN!E%2xe!X7d`P8@-z(Kl7?r>{u<(G9+RJ*<|sMMP=aL(z2Ko!&i*-Y%Dja`KDvJ(?9A+@IL3tKz>gJuB4aTPcvL8hr;Cz;7cRY&iNn zQK~(0Z{_j7<(RNw_)g;)DO6rGyMK7oII23bB-GCA<_+75*8}PX8ZiZygp@_bv=SA}GkCA}XLrNtZMzNEk?$bfa{O zl;k*=v^0n?DAFZ0bf|Yai4V}f;oBVc$sG7WWPoa;vKCRXm0;F2QnuA^txb9g@Uq9h zGYSR-QEGHA#s3&&F$W7RH{>Hb*=e3#^8}W|d`R*A+Iom@r?J$Tg1UTLWPS35LD_>` z0G2em>2-8LMNH#Gjz0lS8JkGT;cgr^IlJ*5kaKiX^M+^L9AuQcvUjcKN{YG9*(0LU zIqHA1yOaXucMLYIJ=o(&K1($sr1y>A(?83MMcP7iBJPEc3A;N7tb2GOayIDVvV%PSb>g8&G~fuu-kDz4u%z8Khr+rOPJNe(3>-?zz9Z*8=j^B9qO?Bkd zWk*ZwwBwCI;1LLRp;Z$6gG4YB562H9J+$pNYVU~l&hRU^T^SQaIJi}#35X{2sc!|Y zR74(HM1N^qM6IGXP92=FGUK}~SbpzKA9GL9n$G-!5W{P#bbM%`?S(g@vf=uVz3Fqv zs3H+Hd^>E&5}>}&8BdKjr+t^k4|v&3cK(upmbtV4IHbUs$`(@8uD5iRGZ$a@4z!7` z&BAHJK3p1vj<&2kL>MD|`g!*#g7- zkW3>V0UL6Clmm8)*_pR=SUwc8#9MHxVL~WIQ@9rA+svx5ny!PMkvYq?3>29k}D0)T8%4&E=t%!LpwK=RtsXSbllkVgWUrX zf;b+zpdr$_VAhPhhqcAA%OA!aw(0ZT?=C!)VGk2VX9rqm4g(#|pnLTCt*z~O7_1gK zupGO#!e-HDSD;$aW!O=no@7P0?KyOkYGNW(Xe`pO*oIZ`>hQUO4C^XGhk;nvsTAD^ z@AH2&>YW*?Ii$dv!*nAsNwCc%BcbdJ*hU1b?mDGU;!U+bTSUv%b~(Ti#@NsjN_1`7 zk8bVlZ}et&c@tYLP3wdZ;BI0mP6C`CPqY8^3K7lalKFO?-O{J`cun$7Q?n|AN8EX&?W^JP9zsE2dxIbW zvoEQRB6`gp9HO)Xh};iOy} zFVHN=)(U|JPCx2Tes|?6>lNVReFv zBf$ZN{C_f;E>x%%*!hEKgB1Qw$!0RKmm!( zEw*5F+K)nWrR3f(W|irzAB@X2+yoJ{e*-{z({0EBLn2iWbiV}T1_;d0y;oSV(H9AR z>_(pm1TZb?i}01(Q_F3Ep1i*Lb%fs~>HIzP92h6o`HG|FB|mpS#H}9kvHx~w(q~!h&OA0YqiF1XUCuULs>D{6 zr@znuGJ+3#Tkz6%q2Pw$+LPCVcwycBXyZRN)9`KB_>yE|EVELnej2K=JJqt+ko~GK%N+x0+@C`8?mr z|H!FDu&=krapOo~Z21k@5+6l<%I4%k(${>eD*RMPAmL~4oy`du7dZ+b%-YnlG)x1; zPnMnk@KqRzAx>{i6)&Q;-^I{R+i%p{&XG$m*MkK}9;5bd5O37QKHhrNr$JvcHCoWU zBZ%|><+ORWHZ|k%lvostm|v8(ahR%LeFcc_@z<)vKKVw_WS192r^8!g2Ye-U*SSi~ zt~vqA8wSykIVMZLIzKK0E>Cu16evaWnE?szO^>np=zDz&G&Pac8aZ8V8MPXwe(b)B z_OOix{oqt!7aW-7DA0>(Kq>KU)E8TSH{V*a+H18&J9CX(NRFDf==U{zB3$)~fX9k* z6B#3B_356DC)qdOVzl#Je9@oizD>)IiP5tA>FT$vA=(b8e7LWZMP{1okC2VxWv+{X zJpQnmq%B88l5sa$BkHxk*CEJd--!KOpprNVX=fSSH5`88UMAXxZgIdKA@hC(WQ_v} zLFEgpaVU69;%yDEK_;h9mQ+dH`T1;qza+I~Kb$X^rguCh#b$WH*QouI&?jU>Zujy; zlD%w<&cFxbU?XFC!!#TW0CMu^coDWhM?=o}O4+m36*tV?7Pr zYtj-pqq4nkM}{Joq;`Tr2j(5H+iRwFq*LyutFpZ}Hg9`!#trH_Hag$*pE~#Tw_=B; zj>=A#TU!x8{=}P^#r;yZ#scM+yLh|jz3u@17#%dD6Dm27D$zC!+Whsf+3c);nAD*p ztUmwXrCgh@n#d%SIb%Q1uU+R_`9{d`A-i~(4CVy#ep@u=B%fGA2Ke}&3k@|* z27gQh`sa|n<=b1!c79kZYaU|PZY|4*bG%P<4cYdUK$gqaH$bWL)tRVbrg51X|rocWUbcra{>o1dhAb-BuZpnR>~+y zmee_Eh7rX%*K>uSAcHyhU2j3>e3q<#4@Z5Fvl)kJ!MGA)y}B|gQL?q~u`hdY@p!jp zC{dr5?baXdKJlA^*OnVrmj#Lch14fDK>|$F60ksjkt;i_RAq&(PRUw?G0s_Bb$&%@ z%2}iOMLq$t6C79j%^Kf<;bs?T|Tl`0IN>mADr zQG%!p8(QD3s6;q$WXfH4sY0i_e1`6#*U8&+(v%hQD80l_<83rf;0_FqUlO^%&-ZG$ zo9?tQb{5!~9@`q#Uf=vDq~N|L7f;}HUig6+PgQ&xTRlDk<*#r8OjE?7~bxqbejnR!5K#np(tcWZcWx1=Z&7X&@-}~L~ z<6B=0oJJ;^NJgr`Yg-zjfKTbLHDyKY75{{bVZ++iO?yzF>Md7@-N`Tz*C~+d zFNS<)_n{aS;f7r}xoxRkL4SyK(P+4otmje)Vn)!`eW5eUGk-jrg{F{EfBCzYedWzw z2IP?w&)@-kM!N7?u+3frWQaMg;;?a zuSWTszhBODY1_uA(qGpUASQzR>ZYKZ)1zh5&`>`69~^UPJ2Su-+D8I zVmEJm8@}-w=xEkR&>@|l;}7kkgFj!_kL#KXqOXc%JX3hrlviy@#Xuu2Cz1?dAearLbydZ*PO#Of*dGVh6D~!W4kw9 z96*MnpkUi@aj)qQU>I%oCKXPb_t6Uww+=UV1YM)#LXR+t-trY9LI6#KkXXAnVtQ=@ zv@GpsbFNy1^rGslUU94H^0#!$oW2@6J>BJ9vJdB+%fy$rL06rY0Achmwz-$&6kj1j zqn&%s^J@0BS_!(T8oP_N-ByW(7uSGF7di`~AWiyT30pXQt*wCt-}DR^4fA0Ab=ky; zxiOz!%mJTr_$_o`&8T1}#@!^_6_vg$YYN4=jr}UT7hzm_EHy(_kp*O|Xvpu5`Bf_t zzCGt$5$)*sKzN7EhU`lde=l$C{c4SNGJ6t3xm{fqb}<;$2T}-5zmoG~_O+AZQkw(J z!7@Pg1E2I)uVFGQs%HkILihG%WzQS-Df_)RQ$nVF#gKAvquCklksAV%3nVlRZ$I{X z9P&L{#(qrSyaju1I`s%Qf;f%H)+&41d{%^<<5zii41P(uIaEA$E zF)ddP-^QA)<{Kr*MQh@UvZGDtB5N-^@xYJE1GteQ#dFL&8;vYCY(QoMf{A8*-tAE+ zFl%2Gwlx5=r|Wi>_)INXD;f6Mu#4f==ahoyiy_}FOf=6Qgy$-gaUIN7ZQ5HV+ueyZ zfoW&oll)4C{T&Dv3pKvSCt@lP+X013tu%@EELECrOw)6cz(0G4hO_tJ9}MxA!M2G% zp`X@Lu5$6fViN@tHmi?TBQ#*|EwVRY0o%ME8}A)5PpK0WTC}Cy?}%>S?eodhy8A@j z`NLy{e6cNVBe&BnQKqq)Zh`2{W|&AF(#QHDHD{#Q)8?yIO7<6zB;WzxjdTT!SeXjv zpFIT@&U_I>j`OLAK6&k-N2MQ5je@+UrK00O?CSER){lIKxt?eqN&MI{UEPRKBAssG zG(E@5g`iSAWWH`yc;U^*aY*zLK zU?GUOwMP$x3IpF!OP8M8>vLH>;nb06H`<*rMe z+NuYeJERg^{D1F(z#QkLj2HWdrAPs}-$%14>*e4Aw%b~mBDW1xA7gXjw!w~N(8}!gQBPBKv51s>T=ZcIyXk}uw8y%Vfmz>`oe(D%` z=S^20KVfGH15TYw8iV7*v&RtcFmY=I{|)nAntcF<-lI0hc0Ou+Be)MM`-_~OIoJGo z6Aq7h;zry(OB?H*SQ#1oxjLRODrx-K`u@zH7fA|%_akJ!cp}|B8TYDX%fUhD(eG9~WOMN5{aPjCM<77c-sy;HT0wE@8Q`=xcKSxZXargTIyr%Q9%BSZS<3}sbs=qVkDJg~;6|eH&yRcsHDL(^ zvKrK|o%c`dtYQ!5Ia;k)0zfuZ3uk7KO|g5}2F;L0t5x$VnQ`x%R$Z{lTLoF*^3a1< zs=z9X3&zK{yk8F8y4Ym{vQ#V!WK@%{qOq<<_3_I4};#HONzwf zr?m;t5I%u(@6r!M!|OtewChK(Iv85f4NzbHU^UADJS8F2fATp6n2v{e}ssr0z&4z51)-Peh|B;IPbsmkDIP6Q~=Xc0g@eAKS21q>hcfZRG1 zQe#n2;GG?~c~Dm^(}N%#3I&oXB0Ye&x}Fk5Y_vMd2J0tUQ>9oH_!3pA%?A}&y_$Cfp3D5v&&R2X9+8$qt?&|4)K=iokYO&8)iIUR*l(=>8FzvAoCOG(5%#Z1? zl!jmy+M&sJoPd)7F#AH6ad2>oXCZ#=MMLg$KrI^Ja4dNLga+?#hqDPVLI(FXgXP`z z##w=niACngb9^A*Y>h8DkmYYs?c)Ji64;HMMK8%d4j3#!3XavVK0r{N0uFXFpkQ?vjd%g7Z(=oO!WqtRc=VWB*D^$6+UIRq2>ti6;<2fpu0 zGeFe(DW~n3uI;_eNdlOuMDKcz(*aSyiwGxLuQnvW{dX4*pTeJLeeZU%;VQnYBE)yT zT;o5W`h!CUFUI)*N=+^74vjj1iyH*Fm>>#i>3w9929QGuq_asK5CbPA*h75r)h~K` zTT+5{X#Ns)27Upk-Ja&v94VB>(5r-Ti4Q0psb)C`uC9CkXf^824&nlMJ!dXXgng1`%`^5)8$&w%TKF~Z^2X3MmwfUEBp)#r2 zeLdI{mkw9q4x!@ZX|{KH^V2#?j)xrT2opGQfcT~r%a`8ACoyllrCHIec3dXP+k46D zV*iE~(!`tX@8$$fJM%l41%JBmqVx(6R@sHa0({D?;#?#NF9Q0lV} z)(4uEA_?3b(_-mud$64zo%+dIvxq%p{Gcu6E2!^pFVhiiyKNocp+kON4aT)^umrke+?~-^Q23 zzhT4c5+NoIVVQV+dgL*`tG^DgjLq%ttz$rW2ved7BFUYPD23p6F8fFBN+^jxXU5_3 zLM#j#JnT$n`Z0q`Q-i^Ah3;JVZwF^00fTG)7x3%!nJwLb`#=Zn6ROE|h59476xd6wk1^lp;=H1r4Tm&7>^8Qai{RB~8o8HnXI15A~ESGhTu>7xy z#K1%ZPF~lK;Bkc32cno-kqsJrU{da&^k9XSnx?R@ZA2I6@&&;0FEi&pK8F67d;$IC z%nq-+6Vt1d|#n+YKvRnrQ&HB)!`T)!S0)Zk4AZTOM#riu3eEVp~qi+Dt zFP(4l41Reap*ys};1X_i1(;j4Kf^q6@>`%JW=Td}4mo5ThYw`52_EPPWgfm%Rj(&H@ei+z*MfFXna_kruc(n0}8w;!GmqU>G znm8$!x^IoH&@SX>d9Z^GfyBKFA~a%gFL5>u3tx(>&>gergv&tA^ytPL9J7kU<>0#` zg=yB`(gsX0svpWRIlOZq3wg^R$&fb!pC~z0YzN#x{rmEPX8#v?RlWp?nsU!h|2jz2 zJpP#a@dkdy5|x5@QYUYjRQ}%VAYX$Y5)QDS)~KC!nB@SE{oWi`KXfm)Fn z!iAJ?tOw4Jzg7+>Ae_*TUO4x~z5Z?qP{>v{u{8{bd5uk0n^IWVB%=NU+C+X%fb4f#bZbym4@59-Td(bEZ#aVg6 z%+Em9}Pq?_CaI_KsPRazoV&WvFF!H)EEM>jD{`{^xgU=X_?O->?&Ps=UJwe_@xhr zn>l=_#D#YCPd~$dyDKssgJoz}!Qmh9+D2bS&;-W}n_KX9V;CnC(xz%`61whW=~cR>kf zCV4x*zP08V-*!_v;zyU(Xx>F50D& zky=^9LY~t!Nb+=_f8ce5c>(iX!y_`EagT;N+(s&G>y)~su-fs;!e1x_e-OX;@4~x(FcK9+2msV!JG?$AcBpGko(8+!b(y zHP=pg>%*y!9{hkP>M`@kh&iO%V;HY>A|SXj0=Py34f<7=14}aBApL?}~W==9g}kt6yIL5$*68po^iPf{PhYt?U8H3AWjJfbvHL zznKUF3I4`_9f~{EGbb69%oSViV0f{c6Xv&-QtfZyElKI2*wu}8$o4vRJSU5sBLj}~ zdX$e+>QzFzZiUsNrw5U110)U}7M5bCEZKR)CS(y}KWT1ybgCO3!zS&aU?!sop~AO*X{lX@fXI4F2cRf zK;3Pg%Q@pjZrft_5K*j3tlWdMt;WY+Azp0yeaeQ$?}oeL`yBi=o#KLMq`4Js3eVA* z^_-!j@XF6f@Hs{~CG!W$Xp}in`{V&IvEtN`wZv2P*3ud|;d{k-f!pSpxyuI=X?wOtQ z%F(X_eg2Y{t!7|NVn={H`Y$pl)FGy068jV$vh+eRT+<|K2ISveYsM$F1lEum4wQgR zGX8eUB_61km{5d_D(oB1#!D(GgW$>oujE_cKs5N)bU7L!0v{<(Q6qiLvajhjO2@@1 zIBsf5TF4$UjJO&csW%4x(batsLf6Zzh3RF>iY)Qk6q4n|4ZaCCh(E>=7O0do%@>D1pPZKtdUnBwBtz9 zh=FL`xvzq1iZRE)$4?P}2j32aKX9f2|9;bZI*tvBIog6yt=_PzJ5WvFiIujV%h7Dj zS7yiGZH$NJTiA!I1WE69N`gz_9C5m(*%#7$HkXj+aOzfrWu*2|SS*u+ujdTIUkGhM z_s#*oD_Jk~ARhCVEHbzTWKqpWD{@uRn+YBZb>MEp_qyPU<_9C-NaJkbGB=9oeC;JL zMWB&`d-fEg#AsHcn8#D~`;|F`Q$02cwJUh%- z{|amoB?keL(};IXImp>OJVvl{J4jHy$+1?^9AX9}7li)G2(&&k>(i)YvJ*J*7oP!s z5QA;@w{JM5DsqR#jSp{$Ks30L4(`3rm=Ztn7oLnjhqd)a?;vpS_nEaS12t8Fl8V^uTDQo85l}^%!Ob$|seVyP@;JEC zbWcD|wkeeAx#PA*Hm->?O!9+qOA;pp_lRkZ^qwBJLHru%0PIMLzSvLs(jI6G?&8d1 zBZ7!-uUd=$bGRJ7OOk@PmKvg}hoRb|qvDhXtTVnNe@+m8>!Zg|9RcG9&X2!2_+_4p zQQ!vL8jIXon`?5ssg!yzANM$@)Xx4z91|A;F1_V;1I>EI`F*N?;^NEZSAu3w2q-^q zV}7715u=iZ{vW_1sqE2~ytFrim@+se9*|{Go`HXe7;`aV0IB>mSi4mi#OW}Ivb2Q~sXchlMf$nd*E!o zyk1qNKRT|%HG;Tz1;4cJbY^j-LeJ@#El{!*yFy0R%P1Ci3I{ayciAafJFP0J$pZWD zapY>ssR)nM0~}G>JCpwvjyy30I0B`k2HewN14=!d4Jt+o!Om?rIUp=LJ^PO3wSBV} zd!s?w*ws2m+I>Oz|9}^#dr!yQULSh#;5R@TkWd49J1YP{#HJ$H!YZ_mTR@yv26;jT z96FD2-y5v^=fT3UcOHCZvnfXoTlfdS&>}I7GRK?;t}F0TP0tRuPm)Lm1l9+}DS_Qc z(;A5NI>3r#i_yo4y`Qs}dl7;swmA}tv{d&pBo)t{*iKUJrc`-!Fb9+fCy1MrK9_o2 zszxT@>0>Nr8-j#%wGy{pe`Ufuf#XQT8JE$lPcfRMeGL0%g84omuw;nCCY&QJ-e(T4 znc}c{CKeHr)?4I-w!U@rsVszY@LxwCH1u1F9j_SGxyWd9%Xl{GR zP*A_q(5*>*OJwQf!%~nHQE7$uuUXo%y2QqGxWal6E(3w=eowdOyXxWKC#7%i2_|4s zv(*WsyZl~E4sQj~m7bp@ct}dP{~5W1SuF%J9{_)8xc~ceO|;1K2l0E(hbK<>;D3+9sRBk1ya|Yy(f~F&?o2Vk`i~Rl8``|m8a#kW7?(X$y|GId zoHPK!e3r8*=MGWlKW9w@{%+ZtIJg!}{~2rIE1gr_lRuoK|NC>T)j5@=0YxlkaZcrR zZluL;IW`;v;ZfT*rbkVHa`N;!UHAM#_;l7UHat@JEO(Os+U+FC4}r}j?R&F_q3^$Pmut2+8T>2j&og?B96=wp5`R+n;XdleS{H(|zTp z_gEm`g;tmr28}puH-Il&1o5U(l2nBwMtI=DF;D~y@r6$m>^*Mqa6H4X8MwIvctrt2 zl+&jlO|v|PAu{O`KJd1<0oX8ZcglVsww?~K;js+S&cpaaB*M@r0UudsYBwM=21Zv8fUjJ4gcQmm`Z#{r<*5|gLpT9TLDPf0TZsJO9|0H6 z@W3eG9fC4Z2jWam2|JH-HYPvc8Rw*0JIDpdzf;{PDhG*yl?&`@lFutU&iqHaHnzwD zY52SFy96!3Wm;kNaBqov&;ne~9%;)*y!zBdAO#{LijrgiKlXW(@GJrh@&b}Qy7~;p zY1YSqS{ozoV!;uIHC||tmf3|QTBJsRZ1F)#*#H`?@PQK%iDhn_E zJ|BcsU91nu_YQQF6d=`d7h>wryq7J5kZSene$x9PIYSTs2OfvQ-ue*}Q!8GEIMj5* zXRG|CW9Y}&vVuur7H_3OW%RMyUdMsTNQf_%Zzp*j!ch4JFcRg9UQHd!-6QNGQvpa7 z_jnA!0Fa8T{U&KNjhMk1-2ZH+c->!9_ne@oAoBU&?et%6jp|ac)(LuuL3u=lW+0Cf zcUH5cqbX%T-06|N6WIf=GNi?zXGJd`dZQvimfpQ5_3SE$14=!j-O4ziI-R=AgXJXv z((Y0~k&-bE?gKh7DX&LZXjbONON6-sj?m_ddFk?bfnJC2Ry}eZ`j6uvmz=>DvR`wW z(e#7#SoA=F%3KNEpvXQ!zq@viw)o#%Eu4E7c1_r-X<$c+gsy54!0+H8Q6|xJB%+&b zf#-^S>YHHAx5nul^?(h|s(u=84)otLZ_Y(t$ES%A;bQf){&fySXGNij}Z z=ynLxBXc7>ki*_Y1+=7FTEq#VF_xl|2uGjj5s zLX*63HuYH?#fAD`g%REE$5hDXM-cV>pu>$|zWzp^WE)(F)W*zxh{f;|xWM8*5zfPU z_|;zz{;zlVloa{lP0}iH0M~Zjg->b^d#v?G#5nwvLNyD`e}GI&Z`-f`AjZZ)W0@!X zpjF}wC^u}h0S^2tZ95wXY*E&#Q||!vJhr!D8`S-mgJR1-cMNEns9Wo#ZQJOCftn~H z8@U^dK-)eiFM{T>X;}p(+<7wqlr9`_qRt^JZ|53_c~n zbgSAXsM);b{bE9WYt|Mfl($--<^UB~WY3`^-TJ5Xx;LM(1rmFKp27634241HVauIm zr2_x-zYrA8b%u_#)37g7?vPC!(I?2F+{qW5sdnxBtqXZ7vDkup1gT-ys4iZ^JoJ^5 zxV``?pkpIR{+*iK*dUf+3n~M>T|ig4Zy<*G^}C#;o_Ru84(PYc2Fe9?y8QbvxkOBF zw~0S2U3yf7ld$0#LiB;b5r9CLZo8>zxGfqMO0ki-o%8*?>pgVcS_SR!ErAxhjhL+z z+V>bXbZ< zCiXI=d+&1v^eRC(uCPC-==zdG8*uZJp%4@f`y$Y8?*ZPB$M*!6kwuGgUl|XEirR#Q zJv2lhXQ9eja0BO|kt}Awjk7^GT^IUI?NERn3KD!3$gRV-rX3@*{R@OZk~UrlGsKX6 zxJETfPOR)tEWR{HKCtk*id!_&G)SDJ4z%Mbnpq5lxg()gbA69!MX`i>3tlszgqZ~w z6gl<1917olO>PsZ3$7D>H8yZfCvLO{tuek_T)eFt$2(|C?A3l>fZ%J2gs8Xe*rbiq zYPG&*>zJl#Qzu=x8eO(SSeTl|7f?9&f@ikCXQqHV#+MG)a!yqxj(4^lIsIvDb!o(p2NIss zLP=1%&}oC7MZwnKCScpv&PJCVb6Na=ouRI5(m)UhS68T=Xt46AtrFo;m5Ixr@1bPv z8F^^6t55C$(+8JC=S!3A3Te}@@Lyja0@DXr2bW8pIp^Ta+mMf3;Bu|QV%>IdeL}BM zbzZ%p9Q(5zG@O;XW;h5gqyC11nk>$UVwXj80p%eL6$e1eu~u0T;km-$9QJ~~9K#Kb zTF?+wU84@v!hS~qCOOcp|8G}AwH6Yf=Ssen)iAg;XP)VMcf~-|yAmkdqO94o-tz~| z8waa`)dy|p@0%d~#=4~fYC(^Jq6^}G<_#&ABhN)V(X!6(gepDD^O*zfiGI}f<2Kv! z-?{>SxJTZ%=mB{fOMgjwtSP^>{)n*r9w=U+MP`=F_~BvL$`Rm`VMW;N7B$T??z61g z6h30iJxLqW@wap=H1im6K+ibc&21gfulqewck$JvSXT>TQM-T*i1PCU5um#X#kA<; z=aARP9Zz*$e}b>uJ$Yk7i&Ym%XIKfovWHFG9_u}Q&wNAUpf3X?loBpzJo(CBv8eyv zi}|>`=rd4tUZwo|Z`W&dE#}zB7P#iBhDO$tn-!y$LRUbyvMI?Mx*+2!7wQ&9k^Bzg z^2m;dGV~b3kFQAT%K;lWpBKB;2vzQeI6i3HMh4zV+*r-4xFP*x8`a|3CDI^?IB$r7 zy5>6p!ZU^Xu)k>mjWmLUHz(q0Grsetmkw?5ze?InNq@>*J_uN3oei;p6Su&jHcGzrju}bl!+4il~HeQ{JsfM<2 z4$np3$u)Z_4^V)6@5y{HChuPys0kqQr!*@)*Co+Pf%M604o|zBIjDmp2DH`?Oz&JP zqa^ssqYPEPYJSP0!)=*SMcxAb@nYWcj=xe4;T42zg$B`s>*L3`!k>#_f$-lf;2wX5 zckTw+LYq(bJcz-;$nM!`^;(LATZ_qFt`DK|yCPMVTlReh)DA_66F+g&*%}5tu0D{_ z;jWEgK=?Wos&toY{En^InXYi8uw=Ik|^7= z4kd{umy1y2`jB6K%iW;Rl4pFi*#wW+%Pp-RoTSvhAh~*0wMJoi_QfXO*N(S`s$r!A z;Rwf<|G}yZR3Cchb%$yr(!V>1taKaSC)_H{@5SSKy~IM=Cm502zh7P)QyBr>pRf0V z4q>~ZR%kY_JqPj=qwbv--UZBDpbga65It;2h4}@QUC!7(vcG&LkBW2|5jb?oB#fRU za$-%Jg4inyyK@D_7;uxbce1FZzDwUZ!zwC)DuNyP>k}%KH7n9uc-|Z(v<4G*>cqo_ zt%h)hE8q_-MMcv!h(8^Abh}2+Am{8IGRz>?P|f7lT(l$16l5Liwip z=8=!f2X%J*O?34Nzvt#A-L{LddNmr+M55~uWWr{(70PJhhHaNe)gc70W0qSu$jr*N z!+*o%h4`6aUpIs|wyd*yOH6N3mM@-0iR%l|xYd&D$68m+mReb6(2UhB5x+AvMyjE+s=3(RH7ky9am8dVdwDI>0 zV!js0+tiHNBVA391A>;I^met-#66>EGZn>yD87RpQ?K9^S{_j_TEn7qVy8VOUN?k1 zZOm(lMJ|T8WoDK6ZHojNVtJ_C)zLruoqk-G*RJ)fnp7_FUT@vs?J2i?r=w-}puU9%H#$oAtqZ(a%46aV6Ilfi&3h zoNf~t{DM}%2>Qm>?qIr@5zW^TbM9w28)6l}W~|Kyr&cngA{WR;K zIg9hdE>Oi=7SEO;5WAXgO1}(>j76e^6!3~YSY%ojHpxsxxur@iA zeHH9j!^Piz$vXvV%!_Oh!5BqbqAuVNGl+TQH0h&5NO z8;80a4~qm~3qzLFw5`L0e-kK}QIlclL%5GX@$V; zCb`0EeLTIOhZ<1j=YCyV4g3WI?W+(m9%z(Dj4$ZxIp1y^q07(QgWYPu(jf|3v{!C7 zldJ1Gs@8Jb%`};8f)*Ep*_q&;33vXq9NBP34RmiZ7u8=TUMCT7)1@g{Bph1gN0uxU z>98FAbzWMDjmSBrDA(+Ze8gJ0&q|NEg7@=`(LY?oOxnHJrA2I)>`g0d>4Xa%18nNY3lg?&t@2(&x@(kM zUFvJ9Ns@{?!>Z$a-P?l*h50X+3HtkyZ9ATHY!y!P{g{APl9a+rx)@_vjPa5a2HA@^ z&qK2wja{rW`Qy;GGlACAKu2>HHLbu7nDq|+eWeZG0pDd8I+lVg!^H8R^s?T77AZF0 zE{gf;MdxXS7TZiwPuY(iAPXpr*%@*8Ol2Nj~ z{WbyWs7Dyi;mYmva_E=*HPcz+$*>81mCPX~osO7l*1Ggj0?eWR%HR{wU>WLdhduDGX>l&lQWb1;+tm(@uVv3gnMidB`Es!; zS4e_;7d)`laY$}CVlPZDxoND6Ne-1EqNe}7TrTM@@gOGMN0v7UWM?q!hy|Viy7)&{ zv~y>!Im6g)db*aAI`?kv2voH4aj_zZwzf=d+deoCMwEXUcU>NR`?-v@SvX^-&x_E4q*8bu7$1Ps~WeFRs@DCP4Dyx~#w_nDmbR2#4`d*Ib#C*d{ z4plink2%7~YI?c}wp9KsvOP*k4yHiqhUbOFH21X*7f6hwrEA_cI%Raz@SI{?jzGoG zYouq9u4KQQqyJ^w9h4#V1y^p(DqCCHBS@sctf!Dp(soTMwqabSAc||T>lvAb$wZgF z0$Rf)@th#73j;Dxeb8vk3Kd(|Gq+mqhme>nAK*JzI<-;ZtnVY_7B;-rGuQOK%9L94 z+ot;k{2Qew3$9Npbp}?)wu0DowODFG z+hm|K;{0ZzO@Hwe5Os?zUC)}%$ubh+HdwWD(>`f+`qhwc-p=quV*}(Tc(=G)MFh(;^+iVG!&n@hRy7}C``_vB^DAsO z$neA8b=_EX=H5yCF+MSL5*^U8DLC5vd#cUNMo~cD-p-w02g9S5VPU*l_tRAPrT(MTdX}3HIcuXp%=?_N9ue40%uV+he z9(?wy$8s%^zMQ!Z(i+{MWBmee5GpQdfbY6q3x?1%S-eG7%~@CU z*X7_)K_j6$=>J8tunT6#EL6&Y^dRgnW!1Y?4u4P{o*nQy49N*N6A;nZ-e&4?}N z>z5|bDP}~_1dH1&Wwwv_n+#QIN(C8*Q|7!B~I3S29^J;g5>nH zSA?WBEwyYKU&Q2M1XWjOd)4dG5yfRQ95Gj{wpnsd2IZ8$Bz<#^B2~|QQG69hveeOr zh&0VylN8`uS5!?kqHL&Hs}tc#1xg)ObxEOFU}847mKX;>$&Em}rvTi$e05q1%VQT3 z^>7tU|6Zy?goEFHOtv##A~1NhH{X&JaYxN$B@E?c-1}A=T<<9pZZ~z6+eq@~oY7Ov zL|8+5p?t{)jL&7(8qSD@iwTFRZ zjR_ zQuqT}B3XIP!WO=sUThfw2KQ&94?j%5XNS5)sjh)`W=kyPBl%z8LtkH<|?MmRB{BuPoBI+wJLB@mmp9#M+mWXh4{P!1X4j;C))3B4k2xbW();Dn_u#b;+uj%RBHY{%WFr#9EBy5{ zHJkjvJfP?V+%JXW+weP_;&EiHxRcof=L<*7i^=N5u#Czh=db~qBUX3x^v>x-b5=r3 zC=L%bXW#Ij^KLT?uCW%JznFMNR$16GLzm9l^>*TQF`)iGTe+Ult$F0V{S zy?!OzL?y$v))#9`?}!9~8x~YmbXk75-bR~W`Q`Y~h!WpubY5HJlox$oBFrXLJ&pK$ zE9%jW@giJjdc~A1+OI<69@_)waAkfJenUEPR4m92MsdT|pM3mz@{znQF+)c~H#C%MH~qVN zyzD+5A~HQ)Z%FWc()uS=mdEfFdKx(oil`HsdfgHBlnpcK>SiY%6O2zyOPjU*e{_9$ zJk;&?el$V}sq9-DiU^UNHi}aAean`;?AwqfDr?!2HL@>*$!;vkIx@*_FtRhoZY*Q? z-BX{%^Lu?i|JC$7#`}Js`<&}s=Q`);4b&&B;>LZ-Z^S1YD}Y$xEVt&)IwD%nd$S9F zG5O}UxfLXr>W6u(h`t=2Xg`LLH_~Sqab^D`Zj)}ovv3cqd}By&yqe3WIXW2oU}#KF zd-+PqyiCHeT;m*F74)X~g9l^a-xEX-ce=|`AvP&`Z!J$aP-jbHJD?ej(@HRT4!Srj zQsv{Qli@??dZNU3U#cQU*#ZAy9cDgsoR@lk(XHKl?6yh8%_z%;^ubH;5en+uPCAaE zG@*tyL4qKHmX}6=Y(>XfcEXO^A?8IGgvB{#nsW(Q#86#EnZ))vuZ6#}T!qT(+2c#NGj6X`q z3xlCx&7*cXSV@hVnQ3VWV`^*O@|K?2NSxod`KVB`&-{u*DxUZqY{Fhf^CX&ieSdRC z(c}vhY-W7BBDLNMvfU|trHYi;Ik%V>UxQz7)ejcx^}2Ay3(yxPIQjEfjPlfME%dfM z59*rcn04>D&%}a7`Xw4HKsJR-aWAbR{rJuw#TjK6O?}^XDxbzITr;UpRznpH(ykhzXmcOFLJ9U_ zt2uaL#SgG+wa~%1VUZNS`E7>ouXj`3p$tQDEW%q`7FHTQl5@L_8>(XQaT9a-gI0Tj zD}}sdnh4stml+BrU5<+ayxR==v5BuzM9z*O1q%0S7|LRAJkN0ZR&Pzo6a)#JlM(NJ zp78bM_@>YC@&dw{!y5y#&l?7)2c-{kBU{&NolboUdmLTg`Dmc#bK#*&V9A%*s~3!5 zED>4B_W~YD*9pK6c}}`4;wlFn;MOjfgZt;H;#p$dq^Z9yI;d_Aac)Dsxu&X%yQ%;V zkGhh}FfDp9z|3b%#n(zFzG9>`aYRl8Th5^!KipX9SKrmE;IZ%5AGovB@7-`Bxfkt$ zIF27i-WbZ)KFi5@XmcuoqW86T`5Kuj!x}#=F<<&L$xk z-4J+?3)fg7p^JGrhDb@FU}{LE1A5@OP8j3$K5*?P&c&_Pn>6^f)~w5R2|W-Xobw66 znl*=95il7yEVqrjW-`971_Pt^JIalDjyExMR#c{RePW;HF`M(=S_F5(%i1yPY)Pe3 z)m_$j#UrRYz>w)i{k<7)a~rOIWAy(9F7PKwp2ppBb~N|RHk}FYs8b3{YiyfdKTS*2 zj28q=u8x<3ss48TbzUybzsBR8&E~t zAa4>mg-c@_cfDSaup$#*QfS2u10j7y&nmSI<9Vl+4c|~~@W6x8`ZG2fy zMS43}`EzW4cI%sGQEwa$ts4kb8I(yc#%TjApMe6Lv8Z=39WiMr(_1M-{VnWe4i zYG$0>4_84fA;JkJ;yfcp*hy!m{WhNoQzP=~P2A-sgiyo2$O|zL6GR6RhUKq(Uv%T&1kU6l>okwtd4BDi zqstA4ekiTXQ8^L#8dzVFeOZ$qE{p7Hxs95V1+1l_|706X{%~oS*QGcakCAX*r zuv0pmDm$X{I9w&hy+|HxVMq0&BBv*3%c`SG#C2JfAGZpL6TpDRMt-4%V6( zEtX|Oe5?5tO38V{|GA>ygNZo^dT60?lvKf0lqT)KA>wwX9-RoxB4-(_(fWzPf-#vE zg*pY=MZu!pwNkC8Qpxu!hVVn%6R&Um+wYTN0rw#!Tu6O)&{seFKiTS$o1magA<+=8 z<#&zl!qZES;Sj93pPB%pU0V9-y|PrMtkq{X0#@n?s>ARuZ^NG&lh>IZbAVZdwwv=k zwlke^P1hcp<>it$z1?HQBNlpdc$XG>pU4|c&c_k~s^>9mTX~$=q9kbO+WB%hK|pV^ z@+6G%+zWwn0;Klh__Y@S?T4h`VMu+^t9&XUimBFWBJO9_V3{%O;rw#6J0aJ+hCTms zuJ?9?PSwEHNeFW3oAHbn!oB6bH4C95@=$_%wZ_;?8YVSet`UW`?Q_wFan^5n0_P_G zn-4RC1NHBD)l5NZYwz;@g4A?4S~5h=oz{0BOF~gB$Mks&ZUse% zF#KS*OM-Z%DsvAB4kCw*TfOSNdo&dNzpun(q4qw3pB!|;0f&0q1wkxi4*Fu9N9IRW zqD=@%O#VwuAM1XL`2CnJ&%I;B1Vip4c3u2 zImz6*@Q6)8gz zmV=x8FkQcMt zd=a|0NnNJjA>zNkrX(Yg?_}4I_yn;B2gJySvVBe(c8Q-uX(~^}&Q^j&%bmG7)~M9_ zeoqR0fJdfk>xdz;{J8e_mvHwdQQ#K19}f%(utfA1=&-qqaLVmYpRH~GFlX!sxB79- zOMd>iO(xO&wOMOP@SUwv^p}TcQPD7+HwISTv@Y=GHil0J4Tl7I)WyIPft06NExwv` z*LH?im^q4cyB%jqGOh#(QlDQ z1XKZ`JqP#XjngZ!V1%;hKrN`7Y*uwY@E=E;%3_NKnW4t2~l88(JF`8w72a1E;> zp;l3GTR7nNDr&rN843r!#m9A zDQbc!5}}Vt(8|}njUY}=r8=yOKEl^pfdZuQecq#uBcTPl@Y#!H>nLS!e2UA z6b;aV@@W@rPiAPT5hWexlD_OBZpv2S4U@Rz=<`h_IRY|4X#08-Ed<%sN6OfZ7nTC=3hE875#HT9-Qmiu`)$w?885cS z4S&X4Lj)O+@|^+ihO-gadzNddSJRUmeb^UGLtY=r!WFnHDS!*F9@Eqh{XboJH}wm@ z>vQ7Nr6zOzRyk-;gp#*&KDQF6ifjJm#0f#Q>JDPB(QMiBk?9!fR z0TtvTkzhsXSH_{Btl7{tUjS9r{K49P=k-^HI9#1IWuQl1gGR1YE5^Q?ejwix{uC>X zd*Cj=TBmV3j57sI7??Uw<>&vK1~}*%OT9585G?zQmuqg%3OuM4bDYp`HE#18ueuG* z6l_pfT~l(q8GlN2s#GJVtKQ&qpx0>WPGZMr^ir%fMu~&!z^|XY`Cdg#a5c_d5`|NE zfgZRHO>i4{xh&1zH;}7hHR?Wo%K32ZgLU{;R*_%8L+Y}{sVCpQ-(LKgQ0o6kp`x~n zu|VijROU&D)6VuOW%3R0hRaJ*&JX0bX3#E1xH2@$bTtQ+Tt;)i=gv4(Xz=$f@lN|j z_c1kxG{6M1IlOo8h@u+8J;d+N+6jtxE-d|a9%>@6A=|C5=vD6#7>osVx@jVJBAlQI zLmzwKt((@Ej2;QlFRbO&ue=A|`c%6>az$n^1xe-bQ#4?t9Hv|PO$!eevs(zoZ|?rM zg|UzAt#+|Sxt)}xA1%-k0;O049}K+@a%&m+v^8Yx8@jpcLa4n$0YTOxvU=FJI z4fVY7%i;EEL3JQ{e_-4OVq7+d_>y_B%W|fAyz1ptxFy@o=M&Y2WlS?|=eBTuU=D|O zF~ep0rSrcKK;R^URN0&as;g&TACB)E|(NJ z!NeU#E*qxa3OY4kjOOH(^ZspglmTxCq$yI^6lWAP%(ZYoow)nO9XAqE+xA*s+3NGh8)kPt+R7wET%#X_TR(9F zJF9YL(z?Vy%;PtEmxmb8F{$3ctyc}w?e zm)mK35aB_EX2+XMias()OjLB5SE#@gRwZ-T?KTk_1or^!i;A}#n_H(KE9jamH656_ z6p1YkIT(DwtDKng} z5+$n9#th6Du{vM%)BHBR)H{uJ$#8H!rs^iT{Bvp7#6eDN{KHvmv{%H6g{1`nO4w2G zm=bQwU|~O=?EkPgVTwf3h}l{!x252C=JZshaW}=>7B$QLh zrMXs)YRZnJ9E*Rqybq%mOQsolliBfpcY`PLMAv4~2aQ#CLup&3M0(3HxH6=mXuLyD z#{FE>n~g*%pcIU7{xW7<$sJ%yEhJ4KpEK?b4M9MG9=+H()&IaN^COs>K2Y8jC4cZ- zKx2eg4HAfxnx?#V%YJAAy$QyvAm_J1?P#G^z$y6bi`GK-G~%IJ7R5iXg*eH$N0hU; zkDB~{7}R%n8|4~WUA~oslcfpMFFT))SJj$;H5{mO`K|_dgGoY@q9U3FRv}7XPrd4! z?ugMS;;A>*4442#+)7Ox4cxircoRruG|k&0wG1j9PxsQqKfahAWzKoFZ7| zg498tWc`b14RX0Shz0<$MHTkLlNuxV1TLV*`C^$}_Jd!ixDLU9Q@cPJ7)ryEv2}B| znLA(tc+g(kM2-q@#98uwr-kp9bOjrILQl4Y8JTOLGn%amxjz8Wit{+1O%#0h`0mv`1-j zV?&&eKi%xX;GqHz@lR{(Ii^De5Tqd)Ngu=|knvYFLbx65{{VJ zxwi@(33(2b#QVP-YTo{z7(gGgv|%T+O&w&*#9^xWMe(X}7H2 za455ucjx;7Bbn-a8WQ;9R6oB~{uhgoRN!0lKr*TMuxba~ga^Y3=ZO?crClyA0+a9c z=%iO;aL3d$_MXg-cMNTNU_BqqM{8%S&mj1YH(}}zoqc>*KE4sURNmlU%KMN!*U( z=Soz6!bheb1d2f1uw}0qpXC>ZPn&ESc_#w7s)+hp*odqi|o_W5&c*a)G#$AQPPW*a8sfxD%|I3DO?ZHvR@%S3!|W=}t1s9^(-d^# z^hjjPWTv=7m-(-IaB-8DE$0=vw!sFu;Brp?x?OXnw|gA3vWZzkBs;3J9~Q}^Q(yUT zMWybY%Ff72!{PF^Ij|E$bf6kYJt8cxY37>NrA3l_R94C*#qb+@7vZu#V@oVGKKP}D za%NZ--^7~aL!|#Zb*iI;*L29MwHE$cpYHJ=B?bPI2eq^PiN0Ysmlj{Xye}N}dbm`# zFva1+q#J)>JWl|LP%Jj8t!V`_D2x-GPq%4!5hJD6M2 zt7k2T`0S0`xpzS6_9VwIWo>KV$coa0G(x|k+qOIk6}R%0@01G33LAGUCCU5O>2{R4 z*HWf>5x$NWHQ zzVlkC&8wRkod=Z`Bh|c960-9^?G$EVWm8+fqI3O4B48QmswZf465TnvH`Zs6EN+iE zU5qB&Qbd+Y@^nnsiLXV&y_Mk(IJdMEsn-5kdq^NhlvtQ`i}fjaP~bobn^qnI+Kz8{ zwtEkcz)4HJep-NtS{#FishPy0t@nTESlSEhS9yQ#5lW2H+s3mdRa6oUE6i<>CCKo- zYN&7ec4!-mq@ZZ)qcdzS2UqT5URw@ylIoizcBDT~gLlC*hD9*Vd+{o2Ae>8HZecGk z@;C4vJzBg06S&K_$(z)i(wK}rn>L2BG;&mJJ7cesR19ihC}zamQm-+*D})*nnquZv zJB?SW&?&d=kKJef42?NvkMQ0KFO_#+()AIZ@`4#7!e=yyhC|qLK)U9(c>#bYQ19+V zD%on>oA60|JSsQ`Qjl8%mB*V%S;_d5wirNG02xM}U9yn=*Y^I`8mf{lFW$epQMpMy zWG?7*Fc=qd6vruWlTDq{N*B|m`cFdrALIHP2D!N?Y`;G%eay)eI5hWG1A1^rfKgf@ zNVxMMCQBeTHvg4jx=w>1)V%hqOYcoC3S zKHftC6KC%3c?sqW+Q~Zt`1jj?+@_7?Pf)A%i0z4QAmW@BVM5~~Bj%Oz{d46-YqGwp zyPvT({bh+g#;~;%TSA6DN=}aN+mvvP{mFaYzWFQIY2nJvlO%e<76c;_@0Jg;(EMjD z?^@-MYZ$;u_Jy;E8pg@vhs;~o*P!br{?+j+gQp;Yl`1EwAxhQIgPkcl5|eE%6DwpQ z$0>&yw>?yJJ?9hO zBb;YCuRzCba#CU;9o1P+8g~g_#*&oyW$qp^kbpWyzTG?JxO91#^xdhWN$-*Whz#OO zQ9LMkP=Y$0FuTjnPqlQjkxvwwQ1(>a24bOT3T2PAs-Pxs${J=UG+-rz(rg?WbPHDI zu3Y+)r)HdF%~D5M&ZSu`Z5W8#F-U!hD;x(_j-wkLoL7MxvF)88)Q#9vTDzEqOo%>N zblmI^>caMO&6R`7C#_}(UAa{0s^;E$~ zz=Wn%L&fpMGP(gY;|xBL*siOC0j;X}J)8)KEU(cozq=KU@`n10G?0AFcD@PO5o(2Y zAcfp|&yvCv@F42RR>Ru*M*}MgKjN0o7U)na0G(^!hCJRvBUr^^A%~mjrD3=c@?oxs z#x3$Dv?VBl0S<3t4&@Q?8fXU`onCxU0+shTJ7TUiRXmS!i3Vnc-MRfjal8k1;D>Iu z6Q;h{a*0W>Vc*$21?ZAd#+Qpw;D?ZEBbkqXt?;J#invOXSU?>~m)S1i&iBJF-E_PJ z(&m6Q&_K|05q5*c4iLW?%5$3sw5&JzQjD?$vS=_41MFEx1qBLZ)I*d+iaxQL!2b)| zkUlGU%zYN#yN~3hT1sb|ORGM~>lOeaa&~=LdA8y6Tod~%QI@k4nvVF_M(P7KZdmoJ z`4$}2xdVO&{W>B$Y>9%~JFO2dL)n z=qXwhP{IeQGnsQh@B4foTIDjG{**XButslA1TaVCxhf_NSMJmM6#C(1sSlh-k;U)x zB#C|&;Dw*fkt!A`HwL&{?D!rl^h4tkz~AKCb_+|P;aipl7T4(QQS3fyX~qHQtK%m1 zvV;BF4UN;?TZ_!d@sw}&-)~pGEItvKg7-(P-|u(CXoo1J=!^9Ypc1P00k;8?(dzh@ zom({t!yc9)wnR}`t6(4b^Zj@|#QfFF>%WTQgyhfUKQSh5dIKMr{c?ziq~j8FE$?^o z_32OJhYhz;-uKc}%;5-V2et!^l9^>pX#`nET-Q#4QxG^P^z%l5SR=Nl2-9)=5thGp zgB4cYe*lmS(nQd^VjfPBc*YF~OVDh|(>=ekR3f%41uQSo?}O#pwIdfIyKz8%?Fto) zziu#Fhx2htgU24T;c)`dOysU-x$SIJS2(NKHCOoT50^vc9!f4>(^&YkmXitC0$9E6 zp9Jhgpk;*#%hcY18r|(Qu$#Bl=a;|Z!ug-LN?G?vttzD>P9cDt{zkp#c?JJ@@}qd? zuN?2yu?)uJ{QuShkpBIZfoX6X1vh^8cRFgW^;u~{ZNUq~v)F`jq~6Keo7E+b^FKf5 z19Qz+O_9n6p34?&ceh#C{3vW5j#Dpv))I@nLZ2+c!5^>QXzo8dLbi6Nhw9$JA4*r5 zzN3HxCQnE&MJ1rRrG*}!Vy7ZFjIk+`gPb){t-qM}ox*CH%BbiS1b*|fj=@reByCPge+xwTKA$b3=;1=Tx-^nvXZk<1(;oi|iKBfk7 zPedv}AAD*04`L4qApU5E6jI@01n_Dayl)1vP22k@H(+__f~DM2g#MTlDjk?pQ6pHh zXS39%Dz|HqNyfkzn;5i(y9w9;^F&v<3-onHq7S$wI&tPvap0I8oa|pIG2H8KdoRsRi=MaFKlNqWlWSF2y3a|t~&NzPCj{Qx9-(#(;P8HuNK$R$2NpLuxgggy$rX+Vx?Zx zoC@aEA>;EHv#20BkJ{d4om(ABlO%8~hpBM$`(u_GpY#P}-q?CbKag6wo?RexlD)5H zCB7h{LFxJ@arYv&`=EB%g`e~LF{xKvu`@g>KSDFEtOvrn@eP-Z0+Yj30*Fiz4ZGI{ z_xx^az=mHWpnL>g82ME!_{swGQ{_1OdN+pybNz+C-=S-s?Pz*EQb^+ueqnLbf@xpr zvmZl5F4z|enGXrk`(n$Fhg;eW7INCoPTxS^TvS+vrPXm>yScJyS=oA;<}8fsT*>jK zX9Dty6S41?#`(Vzch@D0w?MSPcg?rCO7``qS`bgJA2>7%iuqo7Mf~BjaePp$>TscT z?`^9`G~U9F1ypgXXglVMct{F|-O>3&a>q-HFT2>$=&~hQS0&FPfunrFb%TyhF%wuFem|9P@Mnr7QxTFF3bMVL(Q58E- zq~dK#>A?H=ljgc{1|_J6g?>mcG%nsRG0S#zmj-)`-BI~Vi7A$?rqa)`)fxDVC8kY3 zj+fuhjMSpJ+~t-@X}(=ajbLO&aT6EnK7uK+mTv~FmI zzN7{cIslwIv{(6_BXV>_V>-J^3=_g-kl(7+NEGpQgjpAE@OjxsvWjn|>% zTfgCzR{YfWMhFp?=w#bHh#n?h-^%y1ql`C<#>W{8jFT4h{WFy$mgl0F3QnG{K)t){ zQ0Ms5D`4^ca8i=E@ZHF=dJ}Hlkt(GPqX_qum(R8p+$4zvJTXBlNj9nARJWAc5ARj? zt>(~EcZ*hHr#ze}1KDuuLT0=8!Y?Am#LfznhRF;#%_(c&_QDZ-S@*_SpN~vyq-+jj znc|l017mqQBQ{68w=I$i`kRz=d`N!sPI*F_%xn$#D%{6gMC00NeV1Qb_Ir#Y&D0m_TYRif&m*TF%Gd}^qg{s&o5`wK5!Xkh3roHs>0%Y!L(_C#l ze9$E|?dKRfm(NQ7HriM^Td|?7ztVzcDR9OBP8_q|qHZF-Bw3ga_^k>Q5U)6F&gEuCuH$Nnt)Oq$tPopO zcd&=WXIw$4V0F}^+k!}xM?a9DJ?{llBAB@SQ2KP+?PRU z9NSZ<2lsr{=VP;?i*H_`JT)Ox1^gkllnzB111zBSgSivt$(`^`f=`js@E(_ z7UdUY9Dhzdz@6OpOCLQTgLXOi6mpcU(jQGU*TM2XhL0;LpNU84vVUWMzqlYo!Nw}b z>uL*kN$;_#eV2Bu);qs7(5#1CjR|wN;E4uaILqRanQ8S4l?M6;-!1~#uCek=hcYBk zBip=1{p9@A$5SK8MvgsW*0}%PC*#}Sxj$=AlPxkiBdve%H!|PCo-I{Yg!uLM=mK zwMs34?L^tW3*A`aSHV0N>>RT1p%Rx_p%9r~j_g8Jnq)`aD+Ca2lhVlbqPyfl=z|mA zSAevLT94Nb8MBRH;6jV#>$p*rk(dn+;xFJGX$A|`emr-Yqow3oO542qjnK_JK)4ol zmVzfrK0i|}A$SrLBgQM8Y7!w0mf|lEa=Xb`q(qb@qb^j^O8~AWy^=F^@cZQ;o7)md zYCj|f2E`-nBPH!JgI90CjHdN5{PY0K%qTcA#Kx6`IKCv#5RKd<93pKA?K^puG1V(E zew}nDB^(~Q3W-{w;axD_VUFy0ktMy4Gu6S+vvEQzMx)yn%|C=6-K>v^ODx*PO$B90 zi)1!mj4uBxc1u{tYWEb?gLX_7LI#NW7h`XO!a>AVC>__bzCQq@`9S{M>dc@R%N2ae zIY!SEnQ+VhffW#_q!##rE$E7}B7&sGit56HXTp?$nIm$Qqt0Qa4wnVkEVLIv8nf=- z1{1T*J$e2bv!x7S3BG4_lhay+Uf}$nnY0Fq;mn`Gwr16-axjQKS53XzmLGAW!1w^!C7`oQ34~_yTNUXmD+Fujv%q zZ{Gd}7x8h1jM_hzR?ltN{GIGBz?~bnat5w zgLx%G;sKy|XvE>W+7$BHUL{fOj@3CYPz>w?TJ5vm9ryJ?m0U-pHl(YpGie|y$NI-} z+-xzb&<5K8Ym7ybk@RZv2e-?|3Snt{^a8&dq53#S0ioaRZOa@pdI_Sfmp5%f%`CIk z63_SP@o;Rz_Is00tL$w}o}GeXqf0WzJ-lRcF*fx`q(J3eA=#YE^KxqypNsWkEN4v{ z>W5C4Sy9D{WI4F|WXUz4K8KT8$2(HLLxv;v_TG}m*kL>swek!*bo~YuYx#sXuxWLI z<_%k%KfTU*mEtfxiVSZ6 zfxz<42;eHKt)4wTmmV{bj$PUK`I#CUeJf0oUVs?&jPRfYJ&f-rrr!?ot&B)!W0!KB z$4?EuJ=@Revt$-~L6nj(CIU+H09Z#w~$0BY=N05 zd&NB3nTiqDN}YX4ZWrVB4X6?J^JS5+E?+_mlgUoJklD%xN*>eCl&B@sE%er1MBEDAI!~;@~JbaKC*vNTqFkxkubPfT|YmJlD%);@hKTRmNlyGH=`8#iit2 z5jBcRm6g^zQ%t--W0yzL)c#L-XsQgjVaBs@YF=eW1OgAIy5lvA|RLSW!X8 z00%6)u*A@@3PcAgCf@j^!~y?XU@Sj*TvX_~TF?gVC3D=d_*x=H07z#jRY0 z+~-fl&74GK=58~}Wck|ZLGslFeS&&Pg?HEz-U@MzKoeCv= z!v~E}BPcrSK-G3^Y+$aU2mj@h)O;H%(NnR;ZrP|#(_cj!afnvufZo) zxS$a=K$^OSpP%vik&1?6&DQ+d!>h34zN!c*ESX#Lc_u#U?^49*=(;XB`%qtgZ9W*N z5vo5lbpid8;lfTrY~sKyWAwsP#3i;x49a~Yjs5Yrw?LK~js{2#^>JA14qC}o;-~H{ zJ=0&bO)5~4vk5zoKtaIQzM~>u*d23ShhMnIdhx@|6^RDZ*?Y~mw-ee(uikLHPJ`5&ifB|0&e?31AD6-YB+T{aJhJD? zgFjg@r=eVk`D!4CVPK9&)h?X^nswDNZ``Y$0|k$mHqbg&P;b1O;nZ;X#mYWa5a`ty z7FzIe-ggS`dLT&T^c>I2|1F5N?vNn{XHJ?cnh2dGFptTfjUok9DUnS0#pwQjw_%)( zj{eM1cCKyqM^YQARA%$%UEA?Guf={HlL(Cbdi$j{7L_D%hsBWwW6$5OsrgrWbE520 zu4(0eM@>E8b^|qb+u<@x+wNpZ<-ktdNV&^(O#1EPTY#qKEwlz#S$rVu5GprCbLDqC zsXK}6_z4n{Ww8Xb!>(ENuhg)$ljg>5{aT9XFSHE?Hphz)KHK7pH9M1G#Qb*+oGtjZ zy)}8^kJ28+`VD>v{Ypn8-@>sM&8Ka_yrb(jhox7H`1{h@9B) ztBIw9#SMT~rw$^52>gqVnjP)dUahyg)Nbt#YNpCo67ddK=bp2P*-q;pR82*yC|{I6 z<~3v%T0Ia~(=EGg=!TNr&IOX4n{sR$VC*)mGyXbO-+kn(P3jh?MIpUx2DjmzaZ`i_ z0Ip5Iyex+`XoB_qfiU9UmP@&sfaMA6-Io-OiDydM_(ScF`ktq{ps%#(+ad?z_7U#u zsLy(*W18D`p9?Q(=5?U_DX1~BN=?T~(C+HK`Ynf%FWpjDfo72j_bo#u!E>=U?8_1z z1KUB}MDVdcaR3Ljan?-K5TCN?(J)SQ|M1ES6LxaFKcurd+nN5;wWE4>~4ebtSD9YCNpIZ{_P4$D~&pCj@6*nO>-@8^m(Z z+7|ffZ`jtc!=7ftBV!8&wMG<5Vy`s0Q|C#$L8`gjhpX4zgHJGECvKL(+V8u#i6iR~a0qvikT=^V`mc zo2g%4ZY}ncVyIFSXUbPvYA)<8Y5L?`j@y`+)eIPsU4&(K>r`NO7$tb6UDjJ8-uh)o^OuwT)Tp%{ym-B2S5FeM9hB_l>-icsBT06 zW89Pcy$kBdcTbdV){q-#e|zRfF0%2u>*8-Q?A;GIb_^{jSgI2V+d6FG_NxUKH?few zyD_DAK0#z!eNT8;o=Y(&7a{0t{}qRyx_reJrNcj)=kf%{LZ{{J8yVh!UiYhv4CSLP z;JGFW!c~{T@JjeuL)_+KSeIt?(8&v`4J$ktH#iFwqe)`<=IUMiwnJL4QsSDXmD_lk z-$UQp_QLLNALlgt5L0V|&cdE&HmLOc1WWn&;kSodJ7d&sK^lJfAegvhD0~KLI&X^; z&lA;#9brVnJ@19;oLmz*W5ZvRFTYw>xeXxi0n9Ib*g=Tx>c;g=c?iLKJMCK{EkT!s zo{m*Q{IO~iS!0;W4WF%y9OXs#kqNg$bj_{400)CB0`eRIrg;Wd;)qZH~JZQl0eCNG>^PhPHHULKT_Y{@~pn~`q?vSiK(R0DE&RFiWpv{C7|r~%hB z{A*}?7_H`S{P_;W6*wBy7NY|4qfOTXD0vPDPq>HDM0(LmRuyAlR?7#+LlS{OQkD?c zkwRA@;uP{^kAD@_E;~bY08CvAI6oukFsKibhnlEJS<6Nb*E&_tFp~5ZI=iZAI0C5S z8ICNWV;Yt90nQ0>Fcb1 zumaH-2WBq_bW3m;Pid2{kBab``pb#Rsu}UlA>@FYe_5w&EX_{GY#a6UhfX z4Of3B(;3HpW(mLiz!_?dn?-)DO{|9%*wvS3+EqQ52M8_++O z532QgUrc;6((g=7 z?7{q2PCrMpkcJU0q1Lv-?(P*)>rR0T0Ql5_BIdEoi#@P6envn@`TS5sBn#&s%NeUd5Aq1)=4Mo)@9lR{#*8Tjn|C+hQ+XOsca?W}B7F9XEa z{RW5LU%oV`q38=Mox07Z`hbS90B>KKl&_bmFH^$b^ptwY=+?YU`SOoB<&mq{2U&|0i=3~dXFXJ|eD1gNN*y4|KO%8_$N|( zZ+84tTVqW0_OM{G0{(qBfq~tBGnFkCnB{r?*r=%UEOwM!B_5+%cZl8Vd85{#>m2uf zIB-t2R_Wm}or);m?&O1ZIVF4n!pB|htP@*4z;(}*p&wX=t>r~3EKGRPuCmyzS6ZcM z*Zv_*NtL6_CD23FK9q18;Lx@D@lZo3Nl(1|nOSy&zI|^kk4WU3-@X>V!ML;He^>yz z)xKDWqrgSONX)4NNxNsXhLt@6v`X}WCj031UB<)+?e0MuP8kW#aR<;`yFVHU`Ecdf zaE+T?f33%g=gRqAs{d1^;xa86f23WqjRlMg7<4<%LbwCH+}6B-Z!aP7WUzYT=F>OVo3?^JzR)CXeB5@l9{ zNYEMp#W;fmVk=m1WfmS2L@U*996V>kSQ14i6KUp2{U2um5ZbzK7m%zuhR6I1=V0`8u{4_bHUZknL(yrklO`W>+Ml~f)MnsN67l6U?Hmc>5at362Z zFe}rn7$%7r*qu_K>pk~-Rx}IOp(#*uo-I8rP%X^K->878noXXJyfaYuHgT9cX5kHaf zM!kh)jY#Lwy6e%WrEjll)Ea2vgta^?jbwrK8wI>PsD2@s^_iE7JKBNFj*FMT>ezB2 z`Yb7XrTbktdfNJYbH)2a=oU1iYfq1cDA+33xm2`Q;kW!*dU)W_KYqzI0#tPt;Ex8y zJ1U)*rh+CVZe}Kw>I(2i0<{C(`bW0E3|IAKZaBM6zGmJu;Srec(4YM{$vN*W#V{jb z=hdZKN1ZvJK)?qfJv8mXsRED96aV<_|0C0-=MyALOtG4(*g%9mE7i>raK}g-8b<5% z|GWyJZ+~};>8s^SR4O9hW%dsNT-nHgyPo_LO_~nEx~vY|qBpqvzZjz}3a7hucYzC! zzzO(Mk}A0sVgaVD3ao7kHrrm{i1DkiwRQA8Q zKn!=detY#rM+^THG@6$(LV!H}>iTdCrZj_z9$@)KDq5`+zPw`Op@C_7& zkL78OyT=0BDXP-1hvM;})ZPEq0&Mn(U9tW{R=Nhi;mh<4dQLa$SM;*(D;V^fYw5zN z%8K8gf@j$R0rkxR*_~I2nBq2F4&yffu{HX!b$=2 z1zTFw>|jUU^t+DP#8C*`yqde0Z96j*y8qm~i-&=Vum1uMPb!jHVv*}`Cv?py8+1N% zs;sN?K!BwSaEhvl9ev#v3XMBuaRKXB8UEJ;r%OS zYozd;IzOBMvs1Ld80ar++j*c-8_WT(@657dbTwFVIdR`b z^PbX?nkXLwkPzy;-%LC@Q0X5olgh%l5nRZhI)gtYA@pxFfhCJH9M3u7PX^Sk)!CT#tdK zcFXNPAFSX90|}%6WD)~puq_D+)h%r2lkD6g2}oI5%j*OZ3OUE=Q!?mtF490jE5KOx{n_ZThSc?^QYJo(6L`)0c|^ayC<@tt_GLV1P{f&B$htUGTjPZu)&JFRTCzHe&Z?llI>(=J2FN zOWs8%D!i~I2;z6qW5D*<?{IZx9OmAJ*aG?1{&na2W{K_Qkkd$n zB9mtryAQ7ZMpWSZQO|V$nyEiEzxs)q|0Rszjp+3pTs!{8<=-X^tHZf?k*DkK5a8HOKEAKW}^zK1&P zl+OmMd8$>UF1aA?elU&$YE9DYBl|fTM{6JgMEhG#!aq1!g5e_vN(^;D3W|{MhO1}% z#4@k_bt#kNpi2^{f(t-ykr7KlHb?m4p7uV7{^Zg2(10Z>W?l%q7h-$#(|=qIV0x1ytvD0b}k}4_cj^&7}BCh&ebfY6ZH#j6IC^YWTaGyTP+6mSQ;nbg{l!wU7K^l95d)P%4%=+ zyR|2^8+VP*H3&RUURnH?vz2 z8#xp{qe^W@4Drn=a45q6i;4n2_AxmCGvDg#Lcqizg;+4OEIu1?v*pWW@QQz(xtKu{ z_&l7f^_cl9;YQ~66=72@t}m|9P0CbX1RHk~_!^?snf^LJFYd`? z8>&>ZcY|y$9rcn&i@gfQRLpZ}8xyQ7p8$2?b+M7c!E5bSx+$9tu&@_19mYatm76ZyeS!Hn2+Wh2)Z_QLapa(hYnAxE z^6y*bQv_e1P4o;SKjNUhYK@Ge?)>kkKi77-FW?mz0+NtS7*G!S z`}FO_$L5}tU%JA1B${8`s}nEQ`NW9ds@ zy}WZ{vIZ>II&vUKE~G;G3lapdsS0_05qum_1-|_JGFPPUd?Lrrg~m7xnP3GMItpAj z(yRX^d;&OoUy1C`5foP%cbV$>Fa15oR~Nv23zQnj6g_grRgmzrfyEwPWdG~Cj|KFR z!cuELpA5+*C|>~Qo`;LoEtj-w!O7UO6lV09cMt7|dxTl?Da zKaGBkou#Lj{mjI^ihKPhb^gDOM3NsoJ-eiGCd-khw|LMfapB`wRf%E z_mvRL`IXqsM?Smd9CF(+tT8*O!nW^s3#ZFOg$c8{Yhlm*JlO?#ASm5&>!`6UE81>+ zBZp7d3+pbgIDuiUSBT^T>WPjSf9z%cm@{tFP zKfum~^J%YE8Jub;qNlU-9{|bknZM@i_5*Kd0B^o7H&WMaX=sS@N8VmGuwwL=Z;#S=5MFX&Dcz}RD4aw4-OXqc$7m5lHr382@}mAFIY>UP z^nt9caQeUG&AZ589aTzvvaKe?@zmP$z?A7h`{7a%`Hzdzli7^8QV+JpG*47 zCpTE3bA9C%juy}uw^LwsZqrQ1o!5{!>TkUqowJXno^1qpx!BXCt4%DwKTZ}lLqCG% zQ={RQ$Dg z<<1pB1aTy3JfwM0G$8u)60X_bV_)2DioW$%RitDbTkuXA`yFgYDb#)$W4upAZ2mJx z*$X__ybxmZll8@)4RUu1qw{73$|@GM)_yoz?72#Cv(n>L67$05fVMGHV<#AYf0{H2 z7@gPpJ}G2vU){f zE81`KKp8C4=}wIwpnb`gsIC0tE?A5OF59531E0GfV{K#AqHYLld9*{pX?NadCqv;M zKIm!{;(^>JmLG5GK=+)t|FFi2-Vb}g#9YAQOGAu&GM&mU?%euhI!8n@^M@tGw(iF^ zFMNf4`XQ_bjxaWv9wE8{O-JcOtm;LdH%n8lTq#M5T_Yue6U#{2eg8Do58FJwYt|mI zPEy(k>0_u$o0!}9`m6XKGQl3H+J$!ISKM-?Zqzh-{Ql;fvEKxL?TsInHQUkMd-GtA z>LZB5F#gJYzyhY@O~xYIKbOns&g}h+qeZE%9P7KimcH>vM0V^uMD@@!+C?xD3<$`+ zDz%jP!{H3VXg6mrv}>m21DLq_6Nc|dBc@tzck-8vL{uI+wVC7GNPDJkkH+OoyCFhe zLx~=<^51Y)X*<-G8qlMo0x`#=2pKi7(UYQ$uH;yCvT?xtOZo|;U@W5f&eE?62O!}g3TaKA%6 z2#Tk1yeWYYhu`zdJ?hKbgL_QqId#=`J-{dK4;_Avp2vs&MsjrK*^zDW3l522Tvrpe zwb^XdtEhYEl8+qcL(XW6KWEo{K?#|Z2yPGAiO=}71?`#f>m&N9m|tp5zIoS00e6wI z<%pY}y@yA*e(X>%Y878Yf?FU4;b z+G_7@fVJXwprDg4338-}4ZQM_juWrQK1}ehO{+F~cf@Z`%?JkUWnIz~SpP^D2w}cv zDKW0klhy;qG5-|OGbE>?PYd6QL|c3@nEYNP%``>U#UQ7d4{#o3@475?0r=$*5=ue4 ztPN*nXE@IC)vah}tV#ZQ@I z_)rRhK6;10@oib?&n3erY#iEC$rX;&C(9=*KGRTW_^1r{lUN3MwH&leOyHYuTlYy$ zWS`=F@#~1>!EUmmC)iccCUK>WS&^Y1Pk2g(f+Cr7*_9_-9y#cXs8SG>h{{&=*#?Mv zFGlIGlCQ~>?udoUC+-4e!Ebhp*b5}sMXm^KB#AfTy*Kbm!WFkU+jC7X(U~Lk(cfn$ zvpWwlvsx1jtjQWXzm2x~u?`Y9mrXopEs5&*BlmgQKjT6OUm;v_`+Q;b!Jpc;4H>~v zS>ebgh@{~rQ5%HlJelhFVn6KH4T5&jEWO4zo29I_P7bY0ce$hV5I%<>b$!2S`o?Fc zAKCI#ZzNYfG=V#KtRc{4Cj69C>E@qq`)ahy2A;G1+|?KATO2vbdrxG;xa6dne}1<-EH(KZ2Yi9)%vnYi(yw`-6kzKmOWwP6w`Qv0H$;p^6~X^u>kdo-FQxLV|C} z&M%y(b~xPgi{R=H4r5^Lrnkeyp9$2{D+E3kDOYTtUXK6ip-4{NL^8S;*1k?Zk!HK} zF@s@cQHrcNp9bC>S}QvH{Z^opt(?=ktmJ-#^m)HMy@5hU)RvLa-1|-;AyiJ8;4bsgKDWw4_gx$}XdCW7ihljZ z{l@~_wTTbC+5IU0l3B?xEUVr$zYh(Gpa`!as@3K(WA z9bdwsnk`!MZ&vUtxA*;@JtZVSl`CQ6fhGUHtm@By>$(?)V=z~k|7(%`uYY^zf(zF4 zAJzNsEae~7`-=nnkAD0|_5M4p`wln%o$965m@53y3-D_=`Ue634_N*GALl!b|6E9R z&;DzHS)bOvc3OkL>IU{T*#`_N7jItuAUi7ck|gobo4K3f?S~^SKR&MHck#CXwfU!P zDx@D;eVi6o*1{(98*01whwJl~A{I)97YfoW>T7LEYV37NEb5mc8deVe96^Y6`E&N` z&ks0u3r7uyoiS$2t_#d0Hp?27Zd$Y9{x9Lk0OHa zDRfD_`hPVHIYKmAA;8!B=Mw*`H^fq)(P$e2wP*iV!${nV!K5-X9{aCW@$)7A0id6I z@wZ#~4*>mZP5lRe{sxt|fcifG^f#!y1=Rlmpnm{pi#q%*25*UXwpiAWfAtRl{R2S% zQbGQw%53{T{{YZG0Q3(4{f!R%lY;%trfl_3|D<65IyLx*1Nt|f`5zAGUjpwx0Q3(4 z{YwSe3dVmI0{#O){~rSoHi)oQ%6ISqgIKDB?_er}7>$H)%x8*wb?^8;;)k)Son~Hm zAu(SqUk0VL8b_c0?Ntxppa&E-gxPNye&9?t-%nYZ*uf&+W`L5bH_@NJUr#XXVo}E5 zchq!0-|n!TTYj8x=Kp9gz%hDho3iXfyVLSeGh{yBffJ%o`3aF^eeSgv%-@|5&nPyV!XWn2 z=k<0u;f(iEmOk&&I#ii(6fZLDGLvMySX)hVEvnJhpjfEx@AlyPmf)NOcZ*OTNDtq> zlFL!c<(Z<1u~cY`q)SNFO^26^p-rAXlzS2gY@G9$q{mHrW`b4;Hgl!WtTs!=n)!hTcOs`M`sBrRoFpbW@ z5j#()?ReRjp^ZW8pyOk=?OT_1qik6&em9}NXp|J%QzJWbEMN&uG+3#)HhA#HwZGOO z%3fnXELEMjw|v=pTQv2N9oHqC+$s0iVGqf-;IcG{U3Z&`mwE({LE8^^Tb%z5t2w*( zJd7wFflC=>itue38tv&l;up4k$!R4*PmOCmxAw3xNsE;&f4WmFI4@T?Ht;IDN}MU@ z^0vPPnhr;E@Z?H_zQ(@#1lFyacOnxzN!#joK!L1%UyT8Z&|E7q;JVI} z?Z^NE7G#iKFBw65hr)FcTlc1e_37FptI!%>K?2kS={*BqhO|4o^}fP2`SZBlG~Zr) zp_c=lS0IEz)0^C@o`$q%TH;w-BiJQUw=L)N9$3x7Xqk&0>9?J*8o%k(#ZfU*1z9hU(4MrIWpz6RM^$$MF9`gJ7Ef! z7R5E%+*$Kw5WC)Bb5?zO1ro zbMr+SmD(+STgBt2PPcSmOe~GS1&iO~z$9>*3%@=W-yn>4Fz%})0u8-Midb|rT;G|y zT++9^IY#~|ct?dCG9O5Yjwm{~O+S%;W+zFvR(yk? z+|NErVr+|d`zDN7^IF>KT}jO*qIEWb(-uu)Obef1KN|(>kwQT`vBQjGIlW&=5aISs z9snVHlDfZhR6ME*RKzP+A_tG&Ggv8Ozn&o@h}am&K)*R|Xp(*gzX|g}v#ajDI)`4B z=o7}z30t&%TI*RV*}RLTZI#z(eYE>p0IW)yP3$zqjRrcD2uHe>QDU4(=)UNkLCx<;NNj?+s0C^Q9 z+_;StA$sZS4u9pXiW&6`Q75m1N>VOZsl5(t0w*);csl3D`<}Uz(tQ+0sTk*L&lH#6 z5^Ud@cxbD6f}VlUHjf;XzJYS2*IZAeEx_Z_w2Xsbb5BopMS{z#tFMxQ73T27ja}#=hK&a z`h0PdVrRD(l{?^?hPwy7+4RoftPx|>&1IW%N9A+2SVzvyG9fEY-*bMs@BWBF$!tJJ zFU(KSI7LQK9uUmHj5%srMv%X>YhlVP8IH8L`K#whV6oHh-bYw>=)c|g3SHsd+@PM< zYz?8I0;_>(>CL=D!?NGws>n7Wc9WmnFK$yPRLz8qDkx(MDG#3i8fr4>fnx|@z((Z~ z!e!P4{r30Al58YE&RZ207Y5tiL$eD`N;|@PFt;_>H6FutQQp;1zsd|IjuWGUu`f)- zOKk#EMHaE-Hpl7sm=EHt+e;PHZDVCO7)AwgaIr6Exbx=9qlWBp8@~P(xN5E4K7gi- zY7ZtN_N?C|rL_IXsx$=x8q2~s#z4i}d8One>(1;E*OJQ$#!>|wA}W@6+4Bc| zEn$W#tvYYR`MDSvxEcES;td4z+qp%v3tICP2ov>M}*Xh=}n_mov zyf`4W1@q{zQ9*>}_ic++WvuA2nh&s(s}qH!jE7HPqjU+0m%YE4q-A&iZS!Dc^oR-svkqN!!9GHpx0$3JpnFA2fZCwfEX%!AoOgT6 z3h7QS!@^c|`LNga%m;wn%S&_%dnmr9n3N1ln&g!EW62u26W5Mx+vOP`LFg1cQOwM{LW zt1HgU@dPk-fqig%V$@} z#d@b7^2TJ=o{=b+enS*bZTR|v-TU7j#rT|`y=ojOuP!+_qc3k9W-=UMZ(IN)1Y)P| zRS7(7$UUMPmTt|?3fioH)Ps-W_Tq424O}@MHfN7t>lH2-5 z77BY^?w4SpO4L4=?8LSXgDfPXC)i*#IUZ_X`Q zNErch3#EZ@XvD;Mtut^`qiC}i_AfgNW@z+k6b9yezU^Tdq8<1u+@_J@N^kC)y(}>T z61?iqX;8=Rj2g z%{H`c0l?5)2%v$ShX@Q(AYrFe#}yasFyO^vg&>x3E4+L>0Lp$2pRWD{eZmct-6@Zd z*z#C+?};l?(a+E);<0E_r!kdYar)CKgHD~M-EdQ3aF11+T0rCRr{hT)8+V7y<6sab zx6aDOmM%c6-bxq7~5yg>caKe8Vez6lOnSeD$>`~P1ID!`iV=6;immWwt}@qO@js)Pe=9v`PNA3=0cjx*x?JM z?dOkwJ{zb=i>qoknkiDknxgNDk{Aribfq1reyXj_dbkS*PwuzeC)=6jRu)AxnA(dwYSnZSg)TV$^vJiAC9eBDk#_;c zwg7CFXw+tY#^UFI1NnOyv6^(?0!GzYVL+^-v7nBq|M3X5=_>?y{NJt!-ukj9r9ly#Jh!Oc7!gY!mOu+;x1qK$! z?$m)BtmA+Ll3JAmjicRq_O;2#=q`%Px?=ATZ01_kcxJjkp_WL2Jjzu;#VA{~htuB7 zdSyh)`FSS|u1L=HYNl;VWR(-AiggZ~TtpTB!ORcdIavaDjEk3ME3*}Q+>?+%xZ8QY z@%dBoG(0$Z-d+a_qg{QsL*&#&X~{1XM6*?dynK7y$?`?ArwBng#4=b3TuVif@LWiP zzkDV&K{=c)6fFP@2*@c_oa!H2zV(<{*jT!#gahELBi&u;n};or{V`#x=?3S`%$9m_ z*hpe`teCK(t>)#6TX&V@TPoJr)IFNu;MdfXOt#=$^ zg#DFjJ+qntvjzxhW;L z$L?~U0a_m5vY6gI7$_GiuF}e07&hMR_3%g&hTA7ZBWV}9%Iawyz0Ntd zj!MtMXC^$|ui_(=l^b+eG{EY)b$IH(k~JVuI+@$+G$O_n?jHdw8sV%u>SqjZ8_V^+ z(za1g-)2+BxOP%4+4-}>h=fMsv0(&_^wGm2BvxUdt~@I2j%c1L&(C#%@;hB&zS$zT z)4M3eG)$5Az@aKWSA}S)bE65-O_)lKI5oJ8zZqj_l2bI}Wl}qV%&CrTl+u}djyST+ zJ5`>&6^yeQ+5vLrBU-)Rl5WTK^W|__7}q{LhHFOrn?&a)y|_L*XG)s(a}{&c#(BTB znUJq7%CBbVwOu+Oc=KG6En4BxjGTg+9G8#Miw6GTFiYTsPK96Lt6$NP=;F;V+7mtQ z*=>-TuVeIZH8_10W~-$ho8p^#dEosdMZ*A9CWKm=PYK;O)R}hO^uMqr4kkd6(Mun# zeIBfeL_tgt1x?W%5YndxLhkVCzRoA?sz@P%mK(uy;F3JKVXeS#d`n{z=*tR9$E7*#Q@HmY<)FEbX)(5X(zj-)G;`i{Nh_{BgAp}KugF&@ zg?=uyG2g8H!JvGjJ&P1>W+iYM4Pf(m05B%&~-vH@5o|}9tWhL z(V|a{)-e}yx=B@?+qHwv)(Z2yGpt$ATwg8GSgBTcK1sIH+FYqMZ!<%Ap@Fk=0s+>@K*K6 zE!*l-@!TxOy-IF>U<|6Apulz2jpjh|KG@WDANTgWs|z)oO}CXo!TaMLgNt5$6OFDV z)I++!rlD6aM15Xbn#Fn+Y^4HRu{(0N z7E!E<0v+K@OqjrkDAm!DXO78*{GmznWD3~f^m1?4*_ri^8*HQ90_ozNh zZE|lUy~z)o+EO65Xcq0o zQ%#r=$X^5qHzF&+7SQPo*2yBFtkU*jz@m&`_u%N^%ml>!?;DfvB_ViAO8GpSZ@O&f zSg7cE@|}qTMcztSddfV$&XLFA)XDdN#Ud3ORW=q%r&_%uDYv)Q@|44%%gmqQow#cYw>(jwvvff+!V6}=jnpG z(zdmep=`Vn`1N676U94)J6(bNc|*FeQg2hz{934e9}MZ~eQdzKx-24r{zlPBli99e zR&m(N`iMF$S2M+uSNlug^hqdh;%-OsMrrXqzp}-sakxV#_utufhyJX4naf_pFCDwr z#EwFr1HWX0ouWei7`I8nS71upVdt9Io$A1pU$i_$;HJbHoAnqVZ8ohuqC2>ngW)sM<_D^zdD)|#hW=Y3Yv0rWE&g7rr<}Y}EVo*; zx$wd(si8%fx?V@kcx^X79Un@N7H+kEXw+cL2P0D~bVx}$^+pC~R+@rJ{8KaQ&t-=Q zYwh|3?y5j0TO_#`@;Y-PyDEVm&g0h{uSC0yYHZF1EikYN)4=S7{8_l&pfPUPEQ@Qc z2bmy}tojvh^9k$Zbu|dBdl^=@OcuF(*|;~DG&c{T2V`uJ!XrK#TF3du+h?gtgvOFH z%^_MeLLUiYlLK9g>*)8)rL;juI09Mz6$$pts)Un>ccS2X_l+O*omu()-2T{s(L54?)K0 zW|hNPB#^936JJwh5n$@uOG;}x3JLr;RPv8e7wHWtx5HF-bE9sUj6gN`yj6$4J|bRD6=;^g8sWt! zP6c`Ik~{8ztLxfMdfmkpMnAg)vC{NM%)9 z;_OBDr7^zP_zm&m+;Ct)*Qn5-vEE(`8=sup-OiVPEhw0TrKn zP5^Jb$r91~I4@cAM2g@FDqQ-4NecpE`9fz()+RfvC!2u$j7mdiY>a-KyY8KG(qk*T zgs%MUDK#s#sE{=yHfj!)KbD&&;&(G}2QGpff|iy2YEKZ#vW(-=YB_~nqP$=HnMg6; z!Nl6$f@{x9u78bKa62(_`v%L3w{Jk*@8J!W2u#Gz4vihc%%@?$W@3vY^j_ZL(6Qd*?~NeJzK+C(cnQ8r-KwJ&lI&Ag$d&F$@*8D* zIFawLxmJoVm<^4uU$9U2tDw63Q9rNH)MxY?gq*{=Cr|Uq0k@hL|VNyjS z@D*iIdk;;08lYi&MzAf{w3MXd{nnZ;dl>Zj^7o`@i}N{Npl1uDY&@!&No;mpS{Mlb zr33xLTuaG~C|CQ^vv+@|`FA08-eKWZmS<%#B<~%_6CkN=_qZ#Uwzs9Buwx)5?;E!- z(8IrxWJZ3E8-!Aw8q{t-VQj*LJV6t0@yIoO z^bK;nd*(zA6-k#k)+#6Bi+Yg|!u#m>af6V1@lNl|@)lZEsN;P0k>;tEZjSoEOjpBZ zN9FdNeNc2OzS3DxzBsB7wEA^;#VT^ zr-nFop^*vhu_KAe4hY+Y@L&7!$wX zV{WJ(7_dje)CI@O&lQ0t^qy5w$^kc|$`71!qaT=v6WRM7tw#|{qkNur+k?Lgbi9w{ zK7VB-Kozqg!JiRU%n{&C4T8Vo?v*4s4`*~(@l^Bfy%=Mbg$H*wn`>u)b^k5q%upy+Zbwt{eu53A8mFo+<>->_~-E z)L3l_Y62fo^7PV54Ga#A)sLt+lUQPWsE_A8LHUjN>ujRzN-AgR@|vsS)jt6T`kfZ7 zvNF!1B00+S!dv@EdqU>0wki`)>PcarU}jEar*jrv1;UBu&&w!X}s)OaulVgVR) zeR(6(Nz1Y4+dYMS7^fPQo~A%Mgl&o)1Q>#uh=ts0nE@On%eSe9k@$r-wSae&BYNDr zo}>t_x*r@Zo-7#SF))5>RB^;-;1OeW;BD+Qu$Kyf$zRS9l<(6wgluaEq4;FgwTBlC zxBCrsC<7KO$X2wtA=NR+wsv^)>mMXQsU1AsCvX?f0=9IY<+W(sfkPx+YgH@h$QHu~ ziG2t?r)iG3^d?>Vii4DvxLRGDoiG=_y;90#AaIUpP@?8FezRTuQ^1rZW0L8SGbT6>1XAz ziOfb$8Y9Q(9gQT*5ZCeb7g59XXPI8$cFqU2LDn_WWRccbjWDeFS|SJWfAj)uXvGca zly{q5(}s|>`1)Yec99P}QG&(Xh2ZbnY^p#I8eZcy~vn`y1_))awl>8xp7Euai zr3i=F4;_+a17|%p3J;SMt$Ym~u0^P7dCbG+N+0Pv$H;+MMZgW^nn@J_Z7@;!*c^>x zc0DO(C&i)qmW0y1vxE-hzj$Uq9Cc>^>Vqe%V%4Wc~3{@YU zC`vBafMG1gH}9~$7Yc2V~qJ)y`0yU2774--CLu<6{AC2vtXOLq@OzL-c9Lm57@ z>8&&|rUZrrN;C(gcw*;)6VbiwsAWBhWacBlyGIBig-^KLP~)7vrI|>#F(Fzszum&t z?;6i3gUN)klI04Hud_;!&519OlBibS2An{P6J~78{jVIfWlJT(qV zM>*Vp#Ahu=R)eEqM zqq;E|_IlIjDQov4(x7^>uXFuA?K++Ap&@_5tGu4!vrXOJ$Y0sZ z(E_xPF-Y}{LK+ZKmg8>npDoT4l!K$ao0@92|J`_jl;FZmH{a$g1(d7s>@%Oiju}W~ zGi5hCo-6|Is46r=e@NTIrSHt)F?eNZcIjE6I6p0x>h0iYh8f&dQ~AtC4ZKbf1l4S` zIq8A0DJevh(-RJlQZECw%6z)jrB7+^hBo?hWyY8^iRogoa;8h4BWOUuQw8hZ{y9u) z%0Y+KyC)hlAC8h=s3lcYuFYIt1-Xu&&XUS}L5jC}p@hR&Ok;p9TzP=0H zuxuwicLB8PM!F+uk-ecWgNb3w>lX`S6tinBA6E}QLV1tLd(qHJ`ra9mseT>uJszF+ z#ZE@Ft}@-U2Y8NBjhZeww@O8XyS_KCG(h8dD-=JUpd%p3>liNw*tJZR^0c2{9ZM6w z*pE>hQh1KnT}~wd^sPhC_q@>VW0umBs*kaaiRERDiL@KvMDsT~1usqSJaGQw z=^Z75g8He(ayh-0&DUb%Hwh_JPajVMw!tJ;zbYf6dquC z@I3M^v#mwhASIyt{JJW3`m`Gpk`&3&b*AnAMWR}su_aLzJy!k<;S>%-jmf&?lEQKD zbB7;CH3YAm-Bhoi$B`B(YiKyD7D_i?z2PinZS2cH#3Xj+Y-VaniVSx86r=vw+MT)7 zv?Srm@$_gy!Ybmo3-c8F>salzbkrPGqN^|`)pI}gjMotQGUVrqIdNVxjV{7>F`Udp zYBJnyK38hP!s_r-Ax6(m=&01Q*Ui?&c?@&Don>@eAJeYjKd60WhpD65BB$ruxWmjb?5sAY?ZT@U4S@5!*@vU0i)E^ zKb~P0i44rLKr@9~%BD_v(&byTqg?SRNc7@Yr3;i%eK--6KIA0g-+XyQ8_`+XO;E0} z-cMmMRClI^RUaMcytIt`WTby-+Z#`61gIezUz|kylQA3MU^4MvlM5-#N z1GQkJ`AGj2+q1mSHiqz!SX%%F?R4b2i&#`;+c|#!7}l)?49R4y@kgWEnSnqK8RSV##!2|z`N|*`cpd&iB$748C&V?BjkCsNW20YN%-6x@ z+k!>f@LG1;PW3iQW+t6(wNqlg_W|7}$=1}{VqCbmRzy26`+Fu9c%%Tmb=thNBN)VP zf9*_T5SzXF+Xnw7efI-$J8hzq?biBdh$=kyrX_u)F1&KujAsgi5;`O1EBDY_LU2sa z0PQcVan<>X;DrwZ%5GU-oH{=iJo05&sg-t_4g*i3fAVA@tLgf*Z&Awcz*T(mX>q*w z7qUdP-%;(J#<4%5gldj!2GF_?gW`aB-39LsN(`=6PB{z<@Oy!AG3E+R4sp)iEhHx> z#|NfBTJd2Z6G~D;^==SgCdW4S2~OEc8RH=*D+QN5f+Avl$}*)zyQV0yz;;3i*iDO- zI-pJT+iUYlPxAwt^|grxxUGtDsuCyAu%=)czBLMh^#!0*L{}hOwn^PYz`A&Ok8?6a z%onoT8xEQ{&4n@*v9}XfQIP-(iRV{nNSH%tmb!wGIn2ojEpL8vTT2$Y<;0}a>QD3? zvsJ>I>G~TU)B_G|5mKT@%`S7om`0aAS#lO6tY>~&%=8OXsJM`8c1IhbuUH|kkPtOW z2Fj|85}``+comL9zQOPjD4s0I$dx1zTx$m=Z=>v_m%C=~?lWtZYXuu3?YghpcHWO< z8=vz&v3BSFON)%vY_$YsJ`6Zh zEPCuPAo`xwe%p=9YuJbP`a=J^jG3QKs632Vx)hn}49sRqDU-($w}BN=W`8QK zy4EF+sw%F`QJzjgft_aKHi~}l+6%691P@tfpBNbnby7>{6dj{J<1@t`^F+xwiFKjf zjQ;)NWZTXMxhLCSbrO`9vSk_Jea{7^tlqg*s#0@sUtMjO;Nr}BIfK|&y{9E5c8hKI zE91$l6=O;o>3^5uEnJtQNxx8j^^+aA5A4$SOpg9xr6=r}Vm8pbB>SN4PJ9XYGE1$*s1CgPxL*t!rt(QyEZlDx-#Za*bHL=f;x#I(cWGVBd<=+}r3`NVOTNR&iPxqCWhoX|)Zj@V+JKH;ZJviL@sxzT3NPqL@C8Bp_5KxT(CB>~HvaG%wZ~B9 zW*w?p3kWk?P6@Nj*nkq&)d|B*3AXH;RGFLdkgRJ5b#0p1)~GZs6L@4?!J3A+TY;B6 zN%4NM?oxvQf6mKoZiIyL5!SfO@aW3tfE~Dcq5@(nVL2ksO_> zGk*2i7qjVL@5`V9{&EC*4=rlEdU`@VRpu($@U^g=a)C8OYa*IC zzaKO}`oxl2g#$b9@4)SaNWAjTNc@cz^B$x#Z2IG+14FCX!DeT5I8zGFgUWmd=b8Zp zXy_@=}2D{NAbL@{%nK8SFZdl&Kvpx+Glp7ZAO<33r6Dd zwVGM4raRTDLoF%GNs>ZY??u<qGn)|ab&DbPn#`&1wLosy=ukGP^E2-r8_f3IKR}Z%0ew<46%@@#e5io8DVYloaK`ij zODy@lvb6}DWv6Hsy*yI6s^zR2oF(oB0xE&Kx4#;5apU77A^*9ZZjL&F<=Tij=1og2nE$Tvb8f%p5;QPvqV zqgv>E%ilm+XLysJyYxNe=0SLj2iQfy%3r08r?>FBHt!yL9S$I@-Xv8#(-$yDGq$+= zNUnXhy}^km$a!7MFe`TXz=&Nqd+GXYqqUL#8q(B|q*5H#xT*9h!D(TGsec9`|0Il_ z%(v)&h< z_ZADO%*dbmVCERh_gRN2}AZy&CwC;=}BykqQ7r!{xJuotm zf5hBbU0EIo<5;;-B$b(-xf`5hpCQ!?s7zKzkeq7x4V3+F2<#ttr64?|V!nStx-FjB z=pZyn4tvOVL&9W>!vxp$XlN}~AiZkQtpYlgK)SP8tcgS!M~BdAiPRbL&z#p`@Lme? z3dF2#q~TZ7EI|WnChXT|s(3pXH=rjiOhN!?>=@3ZVLb_^p5CD1ph>qQu5aVW0IclT zB6cEum~StU;oL(_N^FfHLv)^>D(-h@5gErLH3>_6#uUNL@LRS(N!JH(0S^*`P8s;{{HTEEt=>)WbVcqK$NYn7hg+7}z3 z`*{Qz-TT^`^S*g)5%n4?(sT(;BF{U8QzJz(kBIIt=lr%Pp|L9aHskgs7DuI+UTDcQ zUwATm9U95wv{k_tN1$sdveN|W>XHMGPExT|Xth)ykh&ZJvl$&ziv*XtGG%015e90C zFk>m?#jp`o(=)bhJh)^Q)|kZLC07u%Vi_HVaM@A#O-sct{|)-rcgk3X1zRV=F&Jn7 z6+VCK`OJaFevXFLPIj2R5p2&My~{5_$nZ85Kb za6EslNr%@+=H!5L2KA$es^omBLrrR73}P)NMH0L_U8PQC=|_@NlW{TX_Hsqs%y8zU zTh8(2_L6r@dWsjNX3YAY*qkWFcKJE2t@c(5(mgBYUF;g}eUczOBk>Lzy^cX&FA zP^vCj?qn^U+4YXRXZKKj(s+)J6{V31`tiG4I2m9@uH z;)0P32O9Q*;t*1871*`&;h-R*6og}qE4w`)ti2q(euCuUPV$i{7#zW# zsdJ(OT>9QK)O+>YQmV^Xqf?OXNBvsqqgDdY)M8*&7vW*m*{CydObR>A;WXnxx}WqY zb=!qn|8)S&vm3q8|IO`ff|h98X$PnEzIJ5awB8hbYNjaKcW*pWO&7L5szlAM25di^L~PrpTnpgbi^dm|ucFgUkV^ah+NMB80LtjEGT{YWOGSO#Q= zk#LB%P|PRh56`z4A zSd{Y(z2-Hltm4K|qrGbyGQO`VNgR~Ko{J>y=NK&2ihh8=flFBoMey0Vfn(kKiR(+! zzNHXYF>;95+5;acjDX%p>h zqtCYnA*jA5VG|l#d5`0RUs)ax z!q~Cz5{N)*R97yCLq2GspJNREERE12Q0KW)`{cS-<+R}9=jfr;woY>4y{2F}x_8gd z>L)?$`xbJNuu9zlJN^`*N*_wk98V@XzFBsnIAi$+3`Q6l4DWujLz39#-yVpJ&`t%a$y{e&CEeTAYZ` zA#`F8x^{_wH0rkd0?Dj=$16rhlehM!CyXE)a&93?o`&K%U&bns6Y4cB@ruLoz6|^v zV!l#vVmWTFwy3Z1E;K&dAvV~y#F1HPn1e5pB$>i$n+s@MgCyb)^v|mS9H6`3m zqNP{^pqWpGMqO&Km^yG`lgx0*g4MfWUIJ?xMjN@>5?@KI2mygkNC4rx%JEAT=@By} z#`2GJI{Q7EfRLP@UZD~mr5LbS7(1!++bWo6535I9XLSedh0~nT3IV0TUWQ21OAv4t zUz8$8t$>Q7sAFnYR4VQcsoHO4;69S!vZm79Qz-&w>#0H4BXzmV=qruN$O>~(vM7fDs;OtKOPv?*Qd&NuJpl8qjMid3>17jkOW zIMS}r!>5M5(9p=bQ)K0E8v>dfD7hdgeTy&nEWSJNVhRe6v0O|PW5R)ejsvic6h|I! zr9_X1Ug~Li{q7?`oX*`oEUw|hOScRMf)YQa$*5(FAywoo$~-4<1iXd{;7Q#m)UUPy zG5T;MI(cRndbe!tL7HBlCk^fGtGsqJxCw-|ZH88rsFu7uS*)qdI|JAsZt{~O_J!xi zqwj6QxCCbDqpC>-k#M1}r3R$ZJTwLA+Aj&^6>qtPIj*B-?gc%;V7#5DTXv7i18+DZ zf2w$@WX-%({3w@K%bZUY=wj!J+h;Rg`Ca_DaWfjbo(&qQeP9S5kKksYTX5QdrDhf3 zwVQ^&PUc1%PFZ73vz7#*K*A?37=4Y?ei~sumQG%Ubjc~CY+L`=vqWpXYLe5d zo((8h3F%~n@51F^-m$t%QA}PllbW>DG@UHIHu-kgrRdu*=xQGXaHMAht-k6e|qHwA8BMNKVIQaQXxUd)I~`P*4pYu=AON;>2@e2{C+Y zVExTFL8M9P2)n5foQGpVPeO+fcMl#;(eUV_FICohk{0p5CFY7DjXHwob(pg64HY5j z@#5{_`+81zZ9H>CNjE$I%Co8P$L!Eimra*`lBH+rvS|ksbSlrof5fP!E~u#WZy2w? zu7=`nkVsiCk&IE)aWf41q8TwhyOBVC{ zNF|Rsip<*}eauMrXAE+(rvSgX7O$XYB`1+Hun&{kHU%`l7!-1)+Pux?wPbQJ?mnBg z-~+^w2>M|pA=0;C2|Y;Hpiyj5S(t{4y=vt~tBo*{^FqkxTWNFqIGw;|e}{VspN{P& z9Q065lTDFgUv&1;5uoikHODaPZg9SqUb@JMy=vox(`y!?AX@0%%brTPV@c z->y^$lOpWafl_aCG}^}_H{PZ`LiAFDed^Aezk#u3iD^Q)Dy8;~0953h$yYm__tkk* zb1ktwXApDvU|VoepjY;DJO#>iOimU40uR?ow94r0^Ijs0hk}HJW7Qii2mokVms1rJ zI`uf(n8)$)zQ@q$peV)feV0aL%eTMu_;0AZyFWbVRpie5B!xR*EX8W>mQF zW1b#be~&14%(wRu6f;9#g7+kT`hSGI1ymH;+CL09zyJb6gVX>99V)GKsFZ-fFd(4< zQo@kZFr-q7NUI29(b7nFr*tzk(%t_(>N)Sd=iK#uOO^{8cRcZnXPb55p+k-7BPL$} zU&vJpVY8O#n2P;3!f%?uPF4s#M77n$-h8`p49Ma1D+~*b55A9##Wz=ef{acO94_^X z{Z|kHi$n!Ldv~ic6*F-4|JJH?MagWmvh%I*f{_jPv0ca;dWcp-CB8clZ~@y?%Nr`J zh&7H}|M-FZ@dZ1tNl**!rh@RbzKjrnKW!_!S^4m!*n;Kz@DNuLNIJ~a3&7nh9xo-b znoSNyG*nll@|82ek}{8u0aCxe!%VaP{Vy#*)!Z7$Y4-0kclM~}&0L#qteMNK+Xj|a zaA;?9YdqY=060FE*Tg`^p60eC_KP-2ftYJVUG&bs=;6aHW#?*QpH=quOy))q@vb&V zXe4_RK0XqlKA4MW1w$={9a;&w;QQDZ-u_vqQui070ouH;?OFN2$U2jOMFnCq9|XIA zAXot^5M$ehkM3ib4KENi;+6*OB+W){Y`|?4JeP2A5M_%uy+U_)QHjWstqawwfMd~XD*NUSOxD*@Xti*p@!>%~Has>8I|dqS3Z@7$(Cd8_X8cZ1$~*RdF32 zoBY03@jWeuTuWvhV4pEtgTO`@%qIoxGc$!=3-YWN#`{}dxd3qhbBcPrwfGxg%rf|b zocP#Y=(cd6uw$^fNDkD(73J3nBjH? z*2o$to6@Wmj9tuy_rbpgbGRD)0={}pxjG1r0lxL|mz2v6xB6kqO6VKlU$d#qegJN{ zaWXJ#uW@hZ73Ftj#5s$4NUwsr+nuV?;PY9@4rzQND6Qz0_YPFczuw^UX1h78We9=L zDVANvCN~$7y2zI|?iUkUOlVNQGrm^sS6y;^G%b$`ef_ftBskJNpsG^CVk`3z?F5WA zU0SV#m*D$=L%U4}zMiCdtXb0rg$Wm(D{RNkhQJzA%gUEt0TPE5h>J=j8g`_dmwtTJ zSsrn^bb|bTqcNczYG5+TY=Cj{DPPxT%bVmhPt$}#R zPT)MHT8zXt;7$O&8*Aj)E?lzp0MG@t2RS#e$q=ZNC6Y8eWv|BoSAfma`{$uRyA@w( z=K@rcV;%PwLB*kiU9%CI!y(p!u4xkDqg?};bw*GRTNCu4t2b_9D%lJDaY(yVHhbncNB)`wLys>uX8nC-L^VraRC!Tw;~SDDT} zKq=RQMW|gpu>ea8A8WMlB#A(opoJiiSEXTvRvo5kuXS6}4u%IRVn&Q+6(s?H0XlZW zlj($rsx?{TJBL|B3*R1fTi~tQ`Fp>&{%?C5D0M`@(ee_Z{8;)QiwJ9iQde?D4b5=< zu``T_Y;s^I@X9a1JhA>L^QZccUMdE4h6DSpl-K@LuyX$Uq35qOq}-mK(eF!wv})Zf z3VcYT?x0VlKJrM!onToz(TN0Sh1iJ$zW?JnDY6iz%D6WRv@)HqFE)cJ%M++kE^+r) zzWw>W&1>%Tu%!)~Ip{#s*{6E)@$zlTJarv?_OY#aFOGNhcU-7phUf>tZ2=DN{p3D< z>b!Sn*&z9hVLqFRWS^eqj3)1%097dPTagyc_?{zcVt$7`X4notxJcCFDkpArJ!{nn z$k0mHkASncS-gBF^Xy&uHNQ%$j;(S~0yB=_$- z(C05uQ+Dg2(->L?qGt80`9zBOs-YVP9%B=Gj$Tslj>PBRI(C-Kk9({xZ$0&t9I^27 z?%!Ih=VdLeUvrP{ivK^8UH3N;J-Vk;1k) zEgEvm_g^2$Fi3HwZi?iCHW8v1IREvr9vETk3%Qfvd;DH|2@#_9-a#!7fnN>G1Eyc^ z1d%d+EC{FIP=b8@iiJ{`u@*JjbiHi#Kq3(@+Z4n~KZO$KZD;Wm@ z&(WE$DgQRZM%Qi2*N76~Sp;LqnmOJuGdKF#(;i%~K)erBM1};~^2e63y|qD`?7Jy9 zOY=^>HE;Eu9e;C2EP9?hl(n*EOiIa6!(dv=?jW2FZL6~$Rw|(y-sIq2j1fzWK8D|z z&J`y{+unN``Rf$H$?*0C8sb4nm2-dy z+GEI&5>gFp0)e`_9d9JR(|*@@CzUXPiIg7i%U+SKfK+eIchbG)*6G=F0dn`jZ!d~H zVm5fIx)idB*sBisQ00mE?7#LCZ0Ub~g!tp^4N&IGH>CXI>_#)=t^~82>ABO!L5?XF z*2KuX?`henFIS>$@Pxw8IPU&Lo6Kw``;+wyHv%*FT>7Evat(Iuiv$yXwI%g4>8T*Q zT++QZaLJali{P}sAOjx8B?6Q0!1T!iUm!kU;_1}c6OL8B%1ZLlIWcv{K;aB!`B9R} z$_uAlUBQ`ogjB4>C+LtwplX(O=o2Y&VES0Ik+r(Z$D1@4## z=q;fq)e=RX5s+SZJj){bB+2@vvG;*lyItQ`?2ETNh9`;Sn{3ciFbSouLvk%+mc;82 z+-}iV8Z!lE$IopA&Eyo7eYXtQJ;X^A@h-~z>*Iw6-l#E8=}ms~kbj06Pbxtl-f2nr z%_tcL3i=tbjwND0Ss^0-g44v#cGiYWDo%Xa^_k{Z1-sqZ#?s}mm~oXBrg?u2k+wDIY>uAnBS5oK3nz@*dRHR zn>|2BR-$IYs_%rm_kTLuNWd{@xj_~yG8()*`vyel=@2VwC zMdLLw3wp&Qva3D3ZoYyDiOP){X-IoyX&q^3wFxQiH+_CX>11e%+3?a!w8?9N&foWb z`m%3isDkMw#G7;T2&sgW7?mBy6A~MWx;TjJddq7b#goIGg3=2TPM@!gaYCy3m$~>@ zy-$)rar*W^m{khYq(}*2>waqBLdaX>^E$zX_7FSe2&Q=Nw<{O#$O>+{f$U@Ug8_l9 z^oG7g#m&bQzK^(hLqGs8X@ashPapPQSL4q$@hgVf`(&1hbRm%c{mXujD7w72qcT!* zuU~{Q;37l}G;?vaRBKE!&l(CS>YM_=b_iw^WBdI@5v^1u(p>ZQ3!O_IST^&td)$-{ z;YT z9^}DyVGGY&oQbJ$F-A72E59SVs2`(ehpofvu16hH)mw zIaP#byP!wO1wI1ngBM;GI{PyX=C4RTTjyxaWNP0C9+*|c-T-$I64`$pe{dmSbhu{5 zYOA6#15YSbRQ~xpE~&~?G&MgYq6^f&;#WplTs4T}_qs5hsgdhLy~&WBc4M&!I!@gZ ziq_Nse(bD%rPcC1qt2z}-cONpXFwA?aI6i>n7XwcC^Y{5e%DKouw}$42EhS0U~beu zK5{4TH(|>N>>HRnr-h>|q&j4IeWG4D`yS#pfpkd5ge#Lp6h>@>>luEy9zo`sSjSLhXdJ66 z(|jngUykbh!$#C)z5LLGt1>Yh_|^J28$!RM*ErEk?emn1plN zUfO^$AcpwaX}nNS2SygSJo9=1UZS_KeWwz`O95Vd@2`;p^Um~ZtNqnrHbXw$(`1`v zdf7(PvBusTuVX(v{kGnGgwq0fo&c(#4^B^FK+61go`%z6!`4zczj?$zfB6PcoV4J^ zc3UtuzI=FXQZOM?j7y=+7Eo;^^E+WBQfWIn+giSug2k8{J$v z10-DA`UPFs`E;(FLdyCH(4)k^lpYU>@HMLy9TVAaVx;jk4?W=BI9!^1%4K(Iu%se@PKm_UK=EBvl75%9u(x(z`1 z)Hm1eo(+lyBm#;$DfT2n?~T|=3)v1|m)5_P#2Qhn-)Ned8Kw8Ati{}0Wi+`O4||sW z_3;=|Y)n1m{c<#zXX~9_-u^!#K8o^%0Q)Ar#jt89)2Lu@J_Ow27+jOb~YGg9(>Ws_)7 zbL@kMg}DFv=BH5PH|nr;{o^{{t%2mTW=GqL$2n7mgjQ|xCX%C&=lc)st`@y{ zo_FtK6Rqy8no>X#-AeCdb{S-|j-De|w|y|tovLiTVFU!i{ZA!bSCe-2(slVZS_LW} z?SlY!?)C$_M-1~lwt=VnwJQHwh~G=&2e*Yk6X=;cRh5zsiOD|UC@=zVigN-!Qgmgk z(xUV2*VrF!Ux?9X2c14vX8y^pAh|QlI)2Z!?7f@|d~22{nWV(_AxO11emAJuJ8o@# zPK{`Zc{Kfwkilai)={ToL}pr&iR9Kl;}`Y-yb!}X7#HBG-Nzh~Uh8H1?}`lW7siSU zBO-d?E9w{O_2gb1+xdR)r!mFMpV;~DauK1yh)563Ok{zRK{Yw8sNHx*H`YSY)7f1y z2I-)NSPxQqO*tm@4wKeC%J|Y095eRst1(E>QbMZg%Jk{gK~`K{?BWL^w5Bq4?vBz3 zwjV24;?a?{4<=*2+G1YVn>+yO9U3qwF1?|#49WpjGJJJet)*!X$mbtj*47=6U4C|2 z;!2~*$eDPMnL$8J8}rWq0M13r3mFBEOAJRbW=z?80+9#N|NK4d7fmX{6zPRi+5HqK zKTnBukmHK*P3{plqO9ipg8F@0?KQrdDDq#D6@)YU9B&{E+<@Qsx{G`;S>M~vBynvI zegRHs%*805{4kUoeGUDkKX)l1{ndvu^GHRh6cr1O&kXzGwD=RKEKiY7Xm^7MlY zv)_5Figz9d@SOpb)a6pA#gy4IAVGUo)riyDr@wTE!Tl*R2;0~!n^ZZx`d3^4kzz){ z_sIIaYghisa96Gn-hUStxRg*CUxACbCfz(l_h7|!-xwb3UfQ})Gug^POJHp|lb>D- z@)oDC?0Oi(wfw@KROLvg64P>s^g^_4soT~Zp0r^8uU;d{O{0)-wu$KPkPUw&<4&q0 z1Zw6<=0E=?rxe}*&zk$3A?@6un>>_PC96KZu4v%{FIk z4x>}KH;C-LRUCpX{&$r4)#P<0J{~r*T^OXt{bwMBz^mw@aB>!2L%5-k0?LftJWf7> z^bMtosaoh5QFH>FK4qdIobl5LiMLn?D_f1)JE@yqtcji+N@4bVV))frk16+j87q?3 z{)8ydIodMM@<49>iP(3IPK2sy3rEH z-abT$gV~DPq2KI9V%dyK$cdsC-t7s(1;;FIGcTush0H+R=Sq@2npO|AVs%lMR1CMM zbPm8x`kEGcGs&j^+5Kxe)8xfImxA?Km>Z{#b*E3_hkjRM|Jjs*&qLmUzD#Z{J>H|> zJ;x)+Khnm<$yglYTgOo;(v)39=W}gB;!c{EC5S_-k;fZ$M6d0hr(K3BsbNi)NDu7z z+pl;>du#71B3Yfiu_izo71H)?>2{ z3-4@WCngJNR{Z{Hl~EF>8qgGFgMBtkm;V`BEg@(KqEWtu(GKHlcs~zmw#CDSu^&Sb&%Al#n*1f=;#|F=qD(R#otW#wQ!bG_3xqs1tz%63}2=vf~CVi!1dXA_b! zJysFv-s8o@Gr2zH{ne$6_3DfLy;kZ4s~xD{I+)tYhAg!CGPd`1f)hX2XmRju`RU;@QmUKoqxu`GtqTj|N#c%I zr@eqOE(4`-|5O?zVC3*VY%)VXFT?W6&POxVR~WL$Umb*&qiC^0%8U|}>(&^Gd|fOKR-4VN|y%1buMCO{#pm z9`TnhuxCnPT{#)31ZlAoFe~9^Z3ZY3v3)I4;@invYy)n(0bsR^5K4?}A<67xhSR5^ ze_}|>Ti=o_ZVx!*H_~x8ACjdzzSefox^hUaM%g%RNS0=`TFSKW&E;a?3waov7 z`pH@{`*d}*1W)&IUtvBNWnnq+#1tiM1#%8@DG#(P&#n5tS{{@Ez2-fE_Z?vL1{vQf zKnOy!D^DdjIy|E%@<+o;OMrU)T95h?X#t;ZlCt0I90H5DEKCO)lo-i1;ZHu_nU16wRModH{{N)hjtcLe0o_q!3eF|=SW ze($82e3hZzYqe_qyT2~CUlcp+hx>Fo1(DySi?$VQ8^Q&j{o~P-oV(KI9Z8maj%@hV zO-W{D`oOjYJ8{GJft?D52k%z!F_5W4M z-aQY{Z(4U&wUI9qGv*G65 z7W5>jRxDQt7(Fr#igtCJP4TN^)at^@W~MDpj}Iy~H8f6%5KFS4oce2tF5Z=`GHivN z|Ld}G_@(o%J)L6;S{`7h#Z#e0B2On&RT@8WL3f)CFb{&<0Qr`IL(B&?$}8aCCo-lm+EFB7j2G#_L53+CI3|nNCMI~PHudC1tx#$sGJKcv>8fKwBzwX$O=+E z1q5?`eziSN5j5X2ZdH}z=Uq{Zkh~E?=vUWi7i;AHrN0s+`-B(ctq(xZiI(siF!s66 z_^uFGU7|R9-kok=;hVq?DY-q97=ID>brleN8fP*;R4X&7#_LmAaNK>}1!Vx$j|>`$ z9W2`0FounPMBMj*D;x-Qy5c}ADiXVP!88lotN@T@!l?w?o0+%8QJ501YNCAjwl5<~ z$GH(f5ikA~_k4}<=17RLxq{3XIaft+OxG=Gm<`i;_A(izo+Zd|k)W$n?tgbdjxY#Y zMGGiULyl^qp&Fy>JKw|pq(Q%{SCTWov?Sq&YWzA2catC{H&L%=nKjH!9zAwWSsv=7TYOwSmFrktL0)XqA9NA4iKc4hw=rb&0O&rLp zg`3K3P$hPN@U`AL1K4SQkH&OhTKf!&^WhIgCHThH$o>YVz#ACDlu0~id?O%to>hVJ z3gX=+jha>vGH;_7a+ta0cd!WDFO;vYXwc?abkc%h5w=`3&)hQMF9c-Qzv`rGu}YQz z=}0}W7+-!;JVoGlR$I0=?okh5bbhJB1&&;B6qAlL;&Nf}kRS~5VLu@aopmC1Cpw~xK7tbHlb#nS-B z3h!7=kioH$0zfG}*4(Fr#_>fE+IQGs`#iQvu=VIoQsvxCGkeZ$`H!&@mjQx33aS1q zkC4wT;LAQNAbMbn3Ml_XjBfW7dE5n$4yjA`1ShIL&S`D@{?-#7pL^&@Y4FD*7zQoRbrRmBxd_Nvc%^`>_kjTWmYyv9j_f)XgaL{MhwiUBJel{43m6d`QeXmM zT`>w%2Z}?yJ|g^TKl@AlTLDB=SBHmzrXn^yuAzSBHX;?(y+_C)6(G1w)C1JU6E_(? zNcXYMqbB&98fxqXo4f=69xzJ93su|)a}C8C2h#Nf_@q2dra-h(Ym5zr?}JAdZiTPW zV>aHW*kpBirNJ=rB9}c^)lKHw;um)dK(um=B=Vtj;hPO2WNpuB4+U257Y4BL$T%GQ z>TVp;t8}mP;Pm+*9lK{vU8SA*E0)1G~~xbrzFYOy|e)DY!b zu_nWS$nwuyOj1cY>SVK`(uLP8dp?x02{y)T4kDlDN6(2dTh4@q{r5)rLdu})fpwu| z?_SEd;8F20a+p^VyOa8D)Pf4MEvk&xZrsJ29)Qj=Llik-*7`vlQopHUxZk&n$(fC< zQ8*-Ozk^f;$PXLA&t1QZM_`zcRbf_JW<%vBc~xM~u&rD=Uc}Ep6^ZVx5iC309uHb+ zsvNvq%6KSPoS>;(=?OjsB(eYd%wQRii9QEfK5ZabBxG3G2S@weKA1jG5A0;zCM(1- zIc8#RK>K(TUqR5R{x)0>5HDBAE?nnKtuQN3UBP-U@Mve=`kcCL08%algn6R;JOCn+ zAk;IB%1ebkv4GE~ciu}x886tCJHs|ie?m;S^a>^248J|PJ?Y77SS-lFQWuO`31;<% zGO_Yzwj4KMK&8MW#v+VUw|SMHDO3k$xUeB>*05y)Nw{tq_2l6!FSNs%Z&uL*>!T=K zsEoVPcZ!Xt9{BTlA=v!E@`&G2bN`--Bmu%uZ{pQbUwUlsa1A-Wv*8ypfzd1t%a0l1 z?P>auxqsf2d)S+D&pP6Op8!wOfG`NQFWZQ6+0YluJUbk!d(Vn39oOXn;31`K>dx^i zGI6@%4ZD|(n&uq;zAuW3CZ924c485Z2#T3Ii2^5OuX+Ggi$k=}2KI%WehSkm_h4QW zfn(MCF1c}w8e}q%AEu9mUV#P{zlF;CX9X~Lee8|J z9Pt&6QgX7mM?}hGp(okogC703w)7pG@oAuO-q!JD^*PqWdXscb?Ew;i|Mok8s>Yh4 zCr&`xlT77{V3n2<3<155Ssh2CAoKuTYFZm)xgiV92X%jP_v2Gm&vjY8jt4XlI(N^m zipYNoyNj_`_%ti8Rtd5Ga0 z`?Uy%vek*oN)dwdOk#op^fSYX;tiD}+QVE{JNJeaO;>+Mk-wXOJK+Fuxs%xtH}Qbo zz7mVZrNIXbm>Ojby+PaW7o%k4;ziE|?u0&NPM9qKyk7owsV2$6${$CL-1xl_a6dHF z;P*-KeU5X(p87EYL%i3)pE82lpDjiD6^3+}6gFNh60xA;{L`y0MARzOfj7f|U zoDiem0ZFeDz4&E~Hxk01c;)Zr1C#yZjcQ`r%t!M9*VgL_SnK$MFzoG;hq852E-Xi zt~4ZW95&$+GQqAtKYs=U&K0y4Ld57$Q_m)xM#c(goU>jBdeX38%jktrXLAXqa*5RP za6!5YtDH*dF=aAb?8b!QT*~^F81M5~o(a4;<6PRQ_eD$56Clhl=~S7mxjR}PCvrul zd|VDWW}j-l_4iu;{^b9WA$Yo4WB91l60SEt76o&YKhpTd2LmdyV<}R!)xQd; z$KDsbu`L`@vKcQMa-AB;y3Yd`sdOi%a|GvMp!dIJEN{;=gJGHQIV%^TO^qA{^HD0c zFmosX(BGLSLeVC|ixCZkqTXd|YLh@8(m$+MLX392uj1Ct49M38TGlS#@8BNhA7NGd zde=Q^adC;!weoFd{KW69u09YP;3nma$vz92L0$NCzFz%{xAZs#%JSX1EcDtOj8eVn-o*ni6XeU z^FWHk_oVW~1w>b4dN%+29SOoJGBY{geUA?rT%f_z!7^I;b`wTewE*4&`95sngVZM^ zz3@Rw{hj>Ghi`S_yq$;6*p5NzsdNn&gAdcOZU*8dC3<^x%pl)(M5LZvH}$T@4*0jn zB&PzX>Ok+s2aj=b1Y@92D#N}d{QR+uH8XL11;ZwkLNS1n=~$DR?z+7UkePhfKYB88Ul#ewbM(KcZ~KZ91V-XS3aqJ}qO3(5Wppq5Ys@6c(*)W8D* zg*CU+fS69?p4$rz1h@2b2nSY=!uwS(`|V*Zy~7Vp<+R~ZEXQ#`!VRqeNJ{>p+=v92 z=h(XuD4siOHq-R7pHoeC9jF^$>=N?SM@pX-F8~t#@zA%l&j8^6YHSNiey$Fn3x59; zNRoR`{ohvgaBTL0&g91j5 z4J4s64`@Vu`53x|PeS|Q#1>4)#*{1?mt)@{={23bo#d4Uu9d#a4m1m9_Ryy8*v~sO zmjxpSAQ7z-hUFA62T_%D&aDCvfSKNc1fR)RpZoRQZ`+~|T{ryrOh|el7rFt4P^IH- z9bi2LhjDmwREWg7rvt^PhbU0Ce0qy53g5h%9637Xe>n_QFV!ox5#F z0V!mU^uqO9ndEG~wWHy?YXe}?vI0nC3i~l6Pk#m6Cbe=t<`^ToK7e(C^GYmuApE&883wdZ+?!KcC zO3SB(83RT>9`nw(%om4$xZi0X0J@yaKp)V{)dAc}`viZDh5q5o%j0zG-lt%E2qAKw z&7n=vDuJF+h)iMe$39PoylqUhsYzx;OU^Ox)jt9L52h=Fi!FtG*W;aph`U}Zol?7ejbPoP=4$ zi-S*tL>B(-fE0bM;3g)x**oc=b{jm^Aw+Y2TI`_KPS{95RK>TT zXmAYt*$l-guv{kaGzZcMZuGnrz`$xM-@&ZNFCR?Dwt(x=I_R|;;}vKoJc4){eja#s z^0cH^i|Q@M{RfHhs!16|Ah$2i(&70(87sA%y^hh#W}A5fXrDcV`x>rc-njx5u?b$rh5OA#^7+ zWQ%eEi?3rm2~6XSQ9rjAd$rN#4E>!H)4~CHC7&VHFun)j!8_02-KZuH_(FAAHOGtx z!_uHBY~+cMmk7yXTi1Oz(jinC&TvhMpf^G@BP}2LI&=fmXzf<3>~wDrOcT=gh$zsY z4+fY<(O8U-@krbx3uI%zD$+Q1ZU1E?$T7T^Qe0c}+$yaHvc5!i?sNGcjN_kr8&=E- ze6TH)_AJIBlhX`&*S_gagx<>4<%)*y17m`U7jGkzg&NC}^L)n}uS%*o>r&u%<*R3A z9oRT}8%q9(SO42ZnvON;{hZK*c`zrV+U~CL>5pQb4wBqPtrknG9qkr;)A7F#_3xtT zP9(NW&F+Z9)KE3mORUp3qAn;WIfK4nxc>c>Uwwfr=nE(!`@??gbl_jGZL=0hv%_Ch z=qt70zTM+$Le~AIb2-<)1o;>6ge00+ zYLyFgjzOyTH#R{ZYC+0TTgq%|c^k>o8eAur#|AiEtGFoN!EX$y6jW<)OHV^6*c|MX3^9zr+&(L4T}ak&b4*d zxDlb*x`Z(PIwNvo+OYFHPd@8u=h(~*lm*fENBTQUA}(F8Jt_&>XGIs-km2zQOF`|Y zR8e1+8ePby!dR^fVHado?Luo;SOT|X3ACb3unCMJM zU9dQ}bQ}AYBY5+!$>uwYX*J@I+&!SnZF`}c0R@23h6KI^M9SP5nuNcpDb@`GCRBH~ zkWsKO)fI9kUNA1)0?%}@nr}0p+iXyS{aOq!bw_=L9}7$UNL>PhNN=x*HzXTMNuk9k z_(O1v=19()`Uxktx*j7u5?INj+}d2~kR+^1&2yl6nD;oXDb9!??~j}U!?x*HDz-6~ zp&bLrG#J_hnz$iEsy_!;E_?O;*;(JN>1MqLq<OPH${i_@L%||BZK=$Rd5T~l;+t4bB^)uc?Hgn^e9fC#_95T+P zQUBw=qj&5l)3EM8beqg=s;+*_rTdgvJ^Zh~ZBtn$QK0q6HZct_=^;@#d)b?!_Sejf zA?)!Jpq@ytKW7?X>|cmdvZ z8jLui+}Aw9j_5y+iw}W%^G;WDCnks{rIv9v{v67~_pS=xu2R?uy}t1&$T=^Bx(F`D z@2$-29Ifk}<7;MlEa(ZOWe)&*#bu4H8Ejg5^0?Svp7s?MfNC}xUnm5)AJ?S#PA{t^ ze0Vn{erh9)XpEfebFVH@6Z`OyvF`x9$nZI>9H=XwfiNNIl?{5|X;9~@>*srcVS3s% zcc9G%`Hx@ja%>p^c5nm8w4R!i%6Vy51+K%oux}K8kzyYaJiMTweAU}+6p%Ui#TJfO z%?^|#_j1Nfc^pXhW!{(A$*g#0R)BR5I;-|4v`|q3Pp|PXoG?6qBC4?O2iKwTNwj<( zKa4eWxIO$_FyO2Cm_|3&jk$Fx}hT|EUmJhbZJLA3t)L3fI zVv3#2#q-M@uuL#Df&;JSG9o(0R+~lAX<_p9y*ukxN4^Sq=IxNW^2gdFbo{EXmw||l z0ucB2B}ftDftM`eX(M{Rl^dj>w(%1Yl&q#rb3oYWn92LK>(0vA{(`UV@pVkF;C(ZH z$9#&!R-lle7k7F1^C~8={>}lDvgcrp6Kd!6gA1%xlRyR3u@JlvnAv9?XrI}cQ&I%g=*u6?Hbqd-cZ z?{t?Ix~UvS&xW118C{?r)(x|M3vA*2;$n$uCZ739wr8-Pe$S342^t$b%HTD2( z{TH`$ju`N;(4&I6^G}}ePi%0E;hrOSG{b6R63AkGDI;F6Aw|0Sn+E{qgwGyhhNP+} z?!lNEj{_s2pLc@9M{Oh#d4AZQBS1o<`LJaVsThG<(xwRGPM=LTD9UOp+zBZtYhM!W z=R>%fmeuaxv>U%6@>zcC34I!nO&<`?EF+%_n$v6bDI(yOa23k-qZlGxE?@wjC;^Z3-BUTY(iC~lAd#jXKsz5Z9vwd8 z(31wE529i$j+?x(3YIbd;>Ju{+tK1~E5$6kiHa!Q^KmBc_w(!x1 zSU92}<+n6j?U|DbE{C6>=XlOomkaAJ77q!5e|@&*@gMPA z_t5Kgt+F4|=9a;53N?@ zg&Fv>DzsEF=NiNuz4Cwq^drP2Ds%EX*f!p zwi=n1SSyw`M?$OM1JEAPwJ%4YkXQ9`QXnOieUpf_NEBQ@4$)#O*2Xl72UHnZHv>uo z8D}|#VO=19LdME@x3?NG0bu;cPEt3k zE_ecQu=&e^W$?D#^;#`)DV&*|Q$Qbqy1Z$FaalCPcWe~k0x=sDtZfC}QnVK_He;m) zF@^08CEJYKpTDJx?TwzFsy&Z~9D8(Qmh|ry>CY!k9Jm!PW+?bm)tUTk`uzsPBOI;I z%b5`AE?3HmIxYNSB1fV2wR&WEH~tdHTmg8{>f$T%KecMIC(+}rv=I-^HS9H%xeKs3 z?ulnTNwn+Dpht+`+@N#PrekxS^NhD67%#qoT!EqP_j1XQLzboAd|+A z_Y8b3PzdmQQKgm>Pj)fDd_zaARZW5R6E+{`lzxd}W+w!HO}M`f*X;vtF{VI82~lZFto=Ua5N@j*<{*;t@z#G`oMh6i$}1_b9(WGmCbIx%Dv11x zhabvbP2v|jI5dGIDWeZkAw_%a7In9>~ z<%(^l9Y5f|FNxRiq^@bNcK_6Zv!z~`%k28L$Z`X=0PWw+L5x#Q!gS_MOkW-DE8pZIg&hY zrhYpsMAE}2&W?q-(CLTL{a@5_KaU_FY{>_vFht`vMzCMh>c=e}DoBZl#dD_{~1UY-WX63c`UIIr? z7S9Q2uSW<$c8G*>+Bd)J7m5vV1J8>zn68GrpJLP)!E8-CiS0$<-;CJU63)ctL6X>>QaazQ=8{z3M)+>t|+i2gJ&~hjH?MX#wE4?*I+? z2B`D?=70D7eG6I6Fe075i&OADHMXJJDu^D({tTSw|Imf)<6R)du|y@S31H>)Be5(t z?1INo&z+^dp3wOXP(c0YnE(ZW=ZUY8k~?@;)oN<2P6hTN?qmmGfv>usval6`_Ul?% zVhFFgti9o}YHK!!a>Vwdk5YByCz={COV#+Rid9i@?ST}zRp=y3uGWlfK#6*luhlJp0!`;pKSm*v7lnAX|BX;`1r8MV*PX1YdJKmSWv5%p{D>6zj}N~^Ehr%31v$)RgErT zwXnXHvuo}M8^gX#frp1gc4GMUOh~)C*%n6LXevus z?%iD(X;of)Sb-7E>`#4i60&4QpvETM;2nl9GOq_?nm;zPo}gDT0(L?JimR*jCA!T; za0GJk^>Vb!%COrmBUJ<7?(-||7CpJ2Yg$XtYp^tY8On0~@r%A}H>wqt`>gOv?}<=~ zSj+o2M-FRLCzg@lv?BrsA9BrJFA%x+|BV*F2Ja8;zc?`meoPX?|uR$6KIA@jXJGN2^I z)7?i)B*OQbI3mwelk$Rig~hb5)pWkSX|Q$f?6HMx64xp!Z&dO@9h5H<_=7D9Tx{mf z)mRs(KIvao4Rr?!)m(bA5yS+^2 zV%oQQ@c=h(Ly`18b0!!?x+RwL*^a6xY{$nE_r0BYZw$c@KqNAl$st5IB%TbC0sD67 z48~H1#gMhk|32A1h#hS=j3?+9vlOoZT?@s>+NU2H4uEAj(Wqx&&K+l}0=yow?YQ*; zhMx4?#`Y&R&c4p-FpG#CSar63Uc-ezaavjWWmn#B`nqq$9nF;_L~xB@xsQ|r_(jpc zZrlxF;Lwmdc$8_kvo+S*zK2GpL z4d+|-a~=cTO;V-J%E;xmLfR&W-b`DAvX4*j_0tC%Qf-zk5ofydn)$Yg{yMg0!C$?F zSO`&b9(>bsXGP+P@WD00XRrw%k4>GWS-a~!h86DQG+DeTh|`ncu6*wJw7kA_=emd;N!uIPRbhY4+IDC`@mO5eSoI&ckAzoRb>=zhX%t=1C*50RzMgf$jV6*s{V$EEE?MNX~0{BH-!h1yMcnu2M`YI15 zfl9Tn2Yt7Gt}T+PirWlE`10GZx&10QqkVLbPJzvccU_ZA*vE*y3=pNNTStKLZ~ok) zj8M?S)F!RXb&=^*4$U>oLD5^?de1FAi@`L?e2K?DKEE_@E*TFlP%B_TJ)v4+$8+SB z07vdVrr;(Zkz!(EY0pByh)tep7v(Olr6sev8 zox#tg2~RodU&(g4^K$<)pwxLh1*hzoTSt-i z^@z934cu`qEZ(>gvERP?M&%Uv`7(3;b!-xWd?CW|^jm>lc1f#lmf#*bLuZo<+EA*+ zOl7~iLqS$_HIcOyMYWWGo&*xAQbo&hJLI*7VEto>kqayV-E{$jAX0AW32Ad3B=0`>r!Nu*P2_kOh%-e?4E^oC5d+4Bz*PcftiVqT-bMOToIM!3CxiGBG9$#iQVe~>V}&8h^& za!=I+Sw+GQ4VwINw}W~r94I~R>VjvzJi^DoSIWX!X50y2lut2a3g4e}B$2#mgs+0k z+}(q&YMe9aGq4r4NJ0g*CobO%8UC>@=E~TLSt7AASM$>VHDO=luy}@N>$hV4@-v{q z?D3u~QjTOnGA#ik3g7k0oVTm9SR_{2IF|@bA}oc~Jf@#BBy^^?1{~kldW?Bm4^wCt zxxZND!zsX}85Dz`JBhwq;R zw1GO%R%F`b_%1if-sNw+$dnt?0{TtjDO!HRIKH^G`GW{nH=Wk7E%3D*biCVs3TE3_ zZZLsoL^of$Z2xr_5t5OuAW+U|!@>#zhH0&Se4esu9tjP%>@EdrOx?9Pcia<^kZVWc zQVy`Xc)3#`E8xFnuUE-k`+RG9$c-yJ>G4X=^>1y4e_F4YdHiHZM%vwFh1=30HT zKW+aKf@eXBeP$m*KE`@dLT^@9vwt0qFug4rLc)Rf9n7^Y$j3g{i~G`~tMV5g-gr6Y zdZ0Q?j?g)$?8CReb2?(ozLpeuaES!kZGyWC;Jn*?W5CDdpQ3gUDOWcgBgjipld=J* z_BY?~z+hZSgI4y|i;+3kZHV>zuG^p|lkqGOMA3`Q7@(c%dsGKTkEb0}NACOYQtjLI ze0WA1$+a68f}E3Ou>;QxR9Rx5D`eP+!;8nhDpnhrST9c+m1);u-x@tK8V#V z6{~8hgsl%YJWjkTG15r-`*dPU*b}7)O)&zR$ITMTmAV*)tB*oFKQOoFHkq3tNlXm) znM1pb0HynN_VygPo7gO-m!U-b`asQ8UUgroCg(C=pVWwU$OTdS+omD2teVvTpE`WqN(} zA`U61ltTQXgE4Bz|6}j1qpI4v|6w_T96;gF2q*`G5D7(6goC7#1|cG)qEZqnA$34P zT2Vx4m5^3KxwbzC znR^$p$$P#woC!-XUG6D@P2Yd9^0c9^4qFJRI&f~`V0o=LiH)6#-; zTvDe=%%UXo)BY;9J+1>;gvA!$12OItEIbD^k`padA9peD*{LbWbj&W@`Av07RV=n8 zh#36S0@Rq`U{q%0 z^wmuIof3Zi+FfjVr%K}n9EpniHOUnQC3lI7M+LR7n3oL;Qa;3#sZS(4vy^6_nEt9G zU~LTTPUs@J-6x$;;xDqO7#_Sx*|a~+_cD@neYTQx^?Lnb8p}J4np%*Eo zlMtYI>(kcSJ`w3W#n7|YV>(Vp_HXWLSRzSLGkk-Jz%`3Nhl?0CQ{+iJiI$=4q|%hNvx zfa_qYA8{5fwQ$TN*gDS=1`!~91IF1f$uV{+5g?^Pl18G=ePupd7Z5~WP3*M~4VOZP zGd^|F^Jrh?c1oT|=+<$VR!dTRChPn0ql>0M+-+!IkS^Rdy9~IBClbA6F5btpg=K8U z@+SS9v(6-WYu9;8Vodz{zEt{CX!{yUysjYzot3sFH7mJ^GBNf^EzRy?#^@0KB#Y0| zQciPKy02ocRYcH8nji9|F#MUBp_I1Uq?wr6+*v&Ws@O7Z70wl?eby2uY&I%k5;Vcg zV!cJS#oMaZ9h!;C&pB7B_N7(^lLrBa2mAE|YP9PDvFHk|xN~WSP;vrZte42Ji1@Z= zhZCWSVw_3>0aQO()^0-SJcbzQEQgy`2S=SL%jNOCXusP_uSi^6wQT*2lkTfXn)~lQ zmY(@O|F(5X%;5Y8H2L}1Q|zG%$aNPzEAE?c(tdiib2dDhg0_!Mk@Ct(V+om16+_?6 zx(16!Y__74m+!rEcW!dpI`)-s<@C$~Epz=-_1=T4;Ub(cxV>W9XSe_IKkn|2ta-$f z5|y{|0iMKs`M}Fb*%veirxvzNB)0k?Cl7A1h=!2(C8;f7x367Gm_u8cQST24I%Gxp z>BhIVb5$wlnJq|MzVu!(rqQ*Zka-usJL^&!qtCn;6d)4b(J)I6aM63rt{LYhBb&Au z(PQ8UcZPf4&wpLml)>tpUJJptX0+%HtV5Ob_~}@dguR0XuE_Lb2rwqeIj;qy0!A`uQXMxslc` zv*zTmpkA<>%aG(>w8-UmG&TOCdpM!MGzl@@a7e$sWMUR*vKkv`T5UFeZ-7q%5~ROI~c}s#UnG8>9LCMMi|d zTbjwg5Z9>gM)KLar>jr11%mKwvhkJrpBJBA^(>{8!N%XK;!OD~myLpu$^On9BruLW z00EPeMcYrc%78ufn9jv@DOkt{J3EqA*Yw?=g>IngF)A;zPr9Hr(=?&48P21^mGh`d zoj3KB5Ry}a{L@{SbED7(i&t=(KyjyOG6P}pVclc5e>A*PeQ|pK1k89<<=`_;wCp+4 zl6N<@RFT|ybzpC(6myhl;2;946Zaco9(-c^Sio5Q(nJE~faJbFAyShe@zFG5ItSiF&i<%&m8aO2baSHw5AAQZ4$c?9_rBdZ-DU0f@jzMMp3Vv2R4LV3 zn!txf4&xprp1=N+lCbialN&8z<%(p?J~*TNp%o=Ae&0J6y5D5j@MV6|j)G&>gWbjP zY_&RDTbj?I==}54PT!Q=CkC83|6+DO;D%($1JlN|E)s0ywC-zPrVgaoA0LTW+Ri&& zWLC>1J&};H|6a+MUsAPS9xNBvf{2e2h~<)nu2X$4^{G^ebCc5f2r~W3 zuB>AwO^J``>Y)3p*)(IN<|U<;FKn%iP{X;O{OAZ@()O?Ejyqz_o&7|BOSL^ zmSbvJP&dwf~4hb?eC+UkRYr1-l83yr$fkt zbyq^JcoZchtBKxi4P1$@f*2XF!_i|l7PV^eO2W|--{P@cHoyx<4?ein&(%w%1np7@ zycp3t^iLKrJ1QmxO~ScA@qi|Ae|$FtWbUz^4#C>Iy}!Sp{x$$)4u6DW^-J%-(Mk78 zsJKzSG1PE^i{ehBph7C(K;xdpCB8x+C|cpCIw4ffcar^%5++gWdo@}wo8VM@Yi1_2 zX56l8D6yl}k$=xrR`-7CDKy>eJ*69qfEOe5s!V_Xbw64Ma-4Bm8Sxd2O~S0=-tQ!< z{l%axNm|e3hWAl&$_}Iy=pn7?_Mpp)qEjCL{e8`X#uaM=jd+^ABUMp_GAHNGzcg^8 z>o7j(pTOHfY7YH>ug!@KJ`eoZ;U_+Sb#!M%f=MlN!ddT^sRnU=l5n6|Wqv(f2h@~2 zK@$W`;f*=Y9D;FD`N1X1_F~2TJq+F^gY)@9`XzUKUd8p;2!w-Y2bfBZ#XWuBPA(h0{en1^_7yA7#R-p9oY92|Wq{dp1*N zdrlC^X&wm|y)ycN1zK6~mbCUqxO9P)tYlmT{Pz!MLFKxhz5Xucn(b@rv5qETC{i{9 ze6@N901(el?wpDd<VE11 z@Pqk3zOuL*7*TzmrxJ3kr_aWpJ;7BEX#V?@YOAj2nVaUo+~Wo4(EYT_KqVDUd7Ve7 z!(rwEcVXNZ6lPtPzU(#9MM3A}n#Er$ETv!!eFJOITK~AYQVZ2wgcF1+U^++Qb zhyZj9?!?W}R)HEqlRRKiV|aSv`EJy^5&Iugl#GV;YMbzxd4c|{E zX$ctXw7uhpU>3KS4XrCS3-L<}a;(R`sS^$_A{7Q?{+8L`zE2aKmyH1Y9Crll<%{o_ z?zGNcbv7w zx#%|*AYQ0#(J`M~1f4%?)SS$15(HqF_>0s-2H@`$1j;Tuzd5t`InUNg)V|=0+UTQLh*&%)SYV^d@E6TPc%1Wh&QV{}@ehlhZbPN>j#U z$b++)ltM$iJ;Tr%&M&Qkp{69JH>e1uslk=Nx(QLam;vccXpBlmK-OynK2m#nImtvi zBOP6v{@pYA0~&fhvw>`A9`}i2LvHFXP8cCbTO}#8X5L^b{lehgkcY6f2)e z^_8TOxe46YhA@b8<45OuWNUunKi)dq34Uq#9M%BL_DxUqCS z-nx3Q-AC~F3VSN6_pP0XWe5r@ze8qjr83n8*i6(Gwu+u^6kftXg|gebT@*$=6qA`-KH)8b{!yURU`YnH|M=>jUI8w`GWEPCalm zA8AgBfRJ@QWGZ8a%)5&4sB4gft{AfZ^y>0XQ;Y+br)%7fYOsCSuEgfYHR=my<`gEw&bMalzJRTNPOJJ zpn%eN+Sq8%uu|Ks|x^9^iv zc&J;RojF(Rok&;>06pj3Yf9|*u?xPMJ?mYseP3Advm{p+n~f*kSKuC4G^oJ}iAa8# zHNi&8p%q>cRzr#BinZ4p0b!(VwnEV>Cfzuq1{Wy06pI6KVA->I%?>4`X>nnQu7KD5pYV38d@ql->Qo&z*eN0W5lEIEd%M0f3ta`(%w1;2}YhEql@HEu?)!Gzv3`kB+3e z2K9qG7v4SExxDncpSUmdsI{59#N;+<#luc;G(V%O-2X`1z)nTiBa95P3WLFS` zP?U)cYZ8#XKq}Dal$-Jax#8xW!24YC0DDZIG}=vBe6IJ#&hZJfkbWVR(tN|h7J{Mr zbQ2LEFiT%HVFzYbNDQ4EIBz*~aZWu`W+xkqgADhTLp~JHpw72~bb3T1ku;(A{zEZ? zgXRF-EZ0)#C#r;kkZSIuO+TTO^L+`x2Qt*1z+$RjuszpbCTyS;H#6UbSHw)ZGRsv@ zd{7$kO4TO}M6*a^m~U`jPD}NE$xb>06+a3I)D03%cVf0`q>1a1Fi!XOr5YN)kHiOU zoA)35zDuH?-bx4Qp6%e&brtFdUSuS+s&zor1qpn@Q+EW%}+MIc4wS&bdLT7=#YXCn8f4}XN;neE2Cs;xF15b1O z=8N6K2JVVTVccOXvKts69#1=QwdSh}mFFc#ewiJqH~N}Er?c+TJSgz<{jc zb$suua!Y^S1k9xm_8$}A7Lw#c4TN+e2E+HQQSKoEh8Y3iE}wH3o_Zdrd^-Pm9Rl+3 z<$bpdq;RnjxnYq>af!XQ2u~Lz1-P-}@A|Q~+!(F`_d}KEFfg85X4GCLb%AOhZb;DG z^STJ7lF8jza-hf@=KqM)HeE;~Ehb5Fah zZcEM;gb9@l)~BA3()JZAx*wNlypvAO^9eMNy!rUT@FA!QsgOT&WCtsgbf_75PZH$A zpJ(B0jQqG6LfTf(1cpJWH}QunMatSzlZ~t-7N-J*=f6HXqyN5g0>4cluUT`qhHh#f z6T~UYygD5Kr>rCVZpugr*v`upH<=yE71Q5; z*(!eaX%qhtv4IrtDZYvW==5reOOY(MvxR4m2XlR9@C$woWe=Bj={Dv)l?a*K*JQxr zFm-Q;+rckeODR_25l{HFqF3=lPH+^_>adjI8`bAtl1<6fzq*!T)Tm7~4_k#p4rPmz_i3O8ImFirv=17bea&=_3&Hu*}^j}M}^vK6^>iTR(! zBlmrF&(8D*W61Gf0t77&pO5k%%F?#jeZ%Q_+oJJByX;cExxbWS_3Q`UN*h~#0jNtU z61{n*!uZUAsc#erO%?|eib0{_Ww}LY#wl`bpI>}wRMHS4q&|Cu?iUH;9)u_3)u&T> zk|(g@5F+$4@iCOnrheZ+Y-PIGPw|Ks_}My7AsdI)6ZJX$+Ovm5w@Wcp$FU?_ahQ@K zuZHw%^<_x=GS(pcGPM2rcxHh>GMdIJ?sgrf4A(|%94$|FoL19D&F#!=_av0P&~y9i z>^bat5}R|jzIYBC_k&nF=Pg^VA-2_a20pCm&K<|MqXm=>y@wLs3&Z=!9b?9cF5_pT zA;0tDJI;oTa^D>eFp+(-pfmHCI>l`mg`9^(C2F1yXAQ^wS+Yuxk3q3V8MK8CD<(M3 z(P$LIxO)I|7h$&PBQBv&=k)Zf0~_nXO^q{WgL8l9zE$AB-CxbV7l?8srsdd-+2g< zP>PhD#Y`7Mwz>z7uoLI=rERf6vQ9@Tt;M85Q#nY6-QwMD)?ZgOo`Cb^&3QPF`QN$E zON*-#zu7xq3`vjJb7s+pIq2Z7u>t{aYG&Yd`q2y3bfzjLRIo1_5)~CG0IE&W9AJW1)rf{zJx1i4Bxi z^!*N=W;KWPJ8oIUq|)l=-Wq-Kgz1o+{`@M4 zNUr<1?fJrTxzm7)J^I?f6YHWUO;x!-o9O_7T!O$zt5d+wAUz1x=22goW``}+%!(I2js#d;t zs8r&>fNKUuEf^JSGB^Tt)u%&Ov^fpZoJ=1!5Hcwb4czJQAj(dN|EMT$qqj zpvC2s`8~K!|1Q-Yc3$=*n@z&| zY4jq2k>(^b%W>ymI`STeGtZySYjDegEeD6pJt5CImmk(X`sRkq)q+8L6}25$A4>MI zpxM;=hvtA)Bzktr+Dk;%SL&GDEs&o>+@!c^?0f9 zflq`YJs0WXv1%39c7N&dwq~1@VwZfkwGdMnrQF6mFO?~L9cbaWvy_SkX^H!#>?2X+ z!{kB=lb%~y1_O8!^$vSt8LrJ=Q0V@$+t613#gUV*uYP#yV@t>ql`4{$Q8V$WI%1S@ z_=>$I7OAgHHQMnZhuh!rTa^E$^JBzdnw=;ZNJ$+%TAM*?Lm1`_!HIj@9Qg;Qi&;~C zY%%Tw=7id&P%;2fL+{SO4;4rk$i%tn;o=gu@ogs_6Y~wnR$HY0Cxtw)d4{GxrX!J7 z=u*0QW}9x=b0p}8PbC~@Q66gP5v~or>cInjO;_daE~{ScjnpD4LhfAahx%#x;)^%Xz6bq!yfIm4_7r_7b{7 z8jHr!?N$typ+rZxp&ZBq_@((W^NQj*6OR*Hr0Up$Sj`)qKU@RtdZlm;n1*7P#7{pi zhnmTG-g|XdtHC}prARBBWr9h%`Am%B2_g@@&()=X0B($P2$Raf&wqclWE|saoL>3N zPxK@qt!nxH5~*&4)-FND=)A2S-WDKpjQr*==gRYs!^*t{G`P&jt16!4xxhL1tZnM@ z(fmYLK2=!mpQ{k31l1Y!D)c1Yx@4?6>T6^ z^Ofgq`+&h7w1xOVAqDYIe!;F-`x$5eR{QcRq}&wGo!l{hkHmfpfx5tA;-rbXi<%)! zz$8)s=|=z0P-%40Z`xmcKF+uWhP0R*EqZGtuCEaI1B@oUNAk|UHq#PKeLvJMXxjR~ zj($AXuk=X+vrt=4#iD(s{}C*ski^KBreyO%#4&`>ntIh+!*fstyw}ejB8R{%s;g~G z`<(U$&pR26&yDdV8>Gd@k`2k7(b#aic;~Jrf362^dYY#+KBs9o{WwEj@6TvmZkzmb zUmv4#LWHH;e-NM3xI;vUv^4C+eH;y8_-UcbE{?~V+Pb<05Rbswc~0tZrNwT4gCc_! zge2lr;1H#$7yU|pRe0}#(xiRO1P(dE7@qK^(nyve)cJ=vL(IJp)Qj#?kDp$(BgDHz zZ;aE{R@H+YaS)ifDS@Q?3VPuU105G@LmM;!B)XG^p$UVEN{B><%aict_gLQEMzAN* za*r?6w2`4Ju-{y_5R{xKld$SnrUvRn)UCx+6+~jv= z75uZr%RosOomk(LeBt~N=qzzrpf=^^c~5)n^W6R?#;57hRbx}*y|Yy71dJLmn84R2 zpH3s7#qB!}?`!M__RPS0EGbMN4igFF>Wcwa(C>?heBM_eJq!rQ${+<-b)td2eirC7 z2@j4Ii*g4`Df)hw)b#%0CI~gP@6S3!)p%H70&$8rfgv>}F+7S{o(y$FQ_|ID2^zgp zaabjj8#Dk5*Igh%7giggFz6MqCEEW8n!7GNiKtD&o9Y^H6bz9A~wry?(*~ z8+fUcZ}-AZDnyd0guxnkoJln~+_MhT)5oGI=A_!Cs{I8$mPot#TlYvu1EBmQiF%v( z?2ZqdiGzSl78Ka_%=cN6BuAo_H2G0_!VJv8?CZe2jFdG$1p{;NRg{um2d-1LfR8Pn zd{n`d9~i@O=Y@xDnH?kzQ5SbsXb2PvSI$03;Fl1_&stJW5kfDV!r`VQ1qY6;qa=$= zPG2>GoAuAtryDU@>rNOjHqYu+l|q1k*9=U30{#8-d=<9LzrWZ@tnFGaZcW^36p&@Sm2nW6Sp zd*8noVm<{(E^60pJ5J7(2J;RGqAvjx`CO?C0y)P#1sV6;5-**5VbWLA} z>F6yJqa^aEER!mmnX;c-#OKX{duevw{62)rk3+i?$fPGpgs^C-P6k(Hi|`P2?&kc7 z(OP_PYzOLhh94;@|! zixE)ClM`6gDk{I#q+0vH(+{flOA6xn#Q>wf4JxE$gyi{SLJ?zVr|*%X9cb#tMNRZ! z;Nqpiy7%4|khuiejkoM)3icl%D#mDi1b79F5WyJ?ndG5eYoRtI;O2akz&`YNJ8u!O zCXhLG@5Xwt8!gZdh+Kd0;2IA2WF8QB|AO(Xs+WDLSj4Ks*sv*}C^0SP+aDA=-TLC~ zaRd2t02dwCEcsZX(l8}-r8vE^S$y54v7D8a7cO|M@@(1cn6B48alwR1Wu;Fm% zQT36F&}t>UvO2m$RKidImoZ%r9AcEVLqqe4Jz|xn_h0RZX*~7mv|jOFoKMo@kXI%u zu9ZH4J&dYq^nDD~Niqc!tAuGDMIe{P$z+&%29@)x&kwgi1n`Qgw@tRxhQBuT62Sqnu!9(4gXk|q;S#=Dl%U-Fsp7PKT z2vFA_`;`_7^x@!q`MgGYJ&YPjLjr{die~{4nC~8cI@$~I=JxV>&F7v0DzjFulg*TK zeP#am^>3`iUXLTh>1w1;$Ru{~z zDSfP}e`VWgxZu?eHrXH6{k76p5xmV(CQ3mbh47`TMR{1oq+r0WF1_Wf>$Io_q+jaZ zRsf9Ef2O2pL+V0(=HWfsJ1$*sR1fc=8duVTGFyZ9k&-#uL5>bCZb_9Wq^8K@Lk)f7`jO;aL|PH4V_~X%Y|e%lcV00|KudPb0->Ho?XeMMM z?u{toj17HSa|Vt%Iwa@Obm!5*b9;swUOaQ#h19K@Pr;t}^2>edEiYa+&mMyuRa#^Fl0>}BhA9yl0M;4bw(9(LH=8VgdzCY_~ruo(@(n9`tl*}y|+#yCO8a7WKzW2EU zhTmqx!mAd)2@Ry=*72(~jMs!(<@~hm{QSC;zny=jeQYE@0nv#o4|YrI9l<*!#J3*# z>Cz7oOj3kT_&TqvSnw9SB_S~9{Xl3kZH|res;Mxa{)P=|O(D+Arz572G$Zvr!r+r#0jfz#(I&>e-S{4VRrw(>4KD^Fym-NU`F;C%kabRQ@B3Io75*{VaA=bx2 zPN*U>&*k5a?|OJ);Q+pX2+6vRyU^!FP8{Rwc$V5a014*YF&;bdwIUxwpgeE%nTH5lgh#EP<`TgcOY@hrI2#B`3T>9bYUugd5juVBC`$ zRs_JplJgzkgHj=*Bv7D{G(O<_*>U-;ilb!~1iWA04$}R-TC*DXG5dj|P~5QNbCb%n z)^G*W^^veEZUWl7uV4N+*q0e>nxPnb#qRj3P+{PUxCs>L{T?Y3XKJdJ7xD3hUb+n< zu;SehQ|vE~IbGBqyB>K2u3|?aDLdiO^!gIzqoXt_1VeRB=hW1WJ(`tVy;n88XW^sT z!cy8*0R|}zJ3F)cc%%uzSc-kx8(icmiXRiSb2-iV$sfQc2>l?(e@?6(-*vF$$W``T z=-m&_UnEqg$pZGw60oV5k)F2W4`RhG5Aw2hKt`ejS=k%GebDNQG{s@mxRhOD?(H~) zsFG&47s~&79ZU&0m8EIn(}|{ITZR_3BWBCkw?*BZd2Bc?&X&Pr<{h%N_=TIS(|T|A z2fUG3PKgRxVQ&0QHMI+`ORAov0yKO)**c#KVKsKm0uMs)_m3gAD9m6dF6m* z)knic(Gh`jdp=UGi2AyuITtY!skdBwvdk2sFZbR?;)qGT)&@b;8-iteam9J!(E;-b zQeKlxhkRi2o#+N9m`te6TxzyLsNiLV299Sh4oi<`S?D6}{_*)b1(T53c4&@pEv~R% zBZN9WeqQfIV3Y;r%J_B@^^Bz)6YTr2s;=Z=p)74bL`D$WVaAu@-`F~wbTw*lJ!XFw zD(wF<*hmdL?T`CPgYC-n7fth6hI;VfYhr+i)E0aODTjR1fj&{x97$egd_1v+jRmz+ z`%i7P?F@&zUm_4hBhZz2IbB$FcazpwyDgCG2)sXW?OFvPTB)NUjk@}y*O z-55{8a4ogQ4058Q<6OkOMWiC;N@{A;%-zJR7pGoC4Gr$HvZ7!4)f2Yst5ZBW8gmEP zgREc|+f+=6(Bk`;r_<(6{@rMtnK||opSB&luOQKrHSqEJ;=c6-j@$yOgh28LA<7st z+ZZ38tlN##6C<7-A&O?^kRTq)jtr;%rFUCN%7$ZZsaOfEj;d=>ZEkE|&vam&!IHTM zsKhan7i41E-{x;lKG`@K>oXHzO#XZcM1HB?7;x;osvltbH3R4Bc=$wq>m?d&Ss z+GJLK?FSjZT&kT{`#rlYbbQIE!{_VF8CpKxhevtuCbhi#&-E%gYlUr`;d}9et2XfL z&lkF@+G0gd(s005V_|4GYache2+ z=v7r_loS8UxRCv@`lovo`&c~C#ddZ{=!NSSJ+v&-|MNJgqnH=N>u8-{6a-SCXRy(3lxUim)RUGfzLv2u%G zKWCRqqAvwcZyX@zt1|9bdssC4`gQBC`TKq02fQ}n2>qM=r{_=n9(5!RwgFyJVBh8& zUVs}OeYx#_ePv5{<$d&2yY~Ek4BsvSqPI5;OrLLhyZ2$vb~#5CRMxNi{e{gxWTRVn z0~DT51^!-B93FNE%GF4I^9^(1hSml<{&wPiza6}CFTAom&py$0G1e1>8xEGW%9CvT za^z8h=^NHT;p^9JxXZ@nv!qPb#XgcBWdHpk9z{g6k7!$Cz^3Vnw1yjwl`;PPQvCih z0qQLYyt20Z4bR`NTyz8Mw)(pn_ts?{?t-%hW%%vjvCZPX>6xoT?%ktTh~v5UQDuEi ziQohv-5$@nNkVXAaKnzf0-IN0(=@OC={_~Qa(2L1%klKPQ4OGBI4iYDLhv0#4fXld#{Xq0*57>}JG`j&2LSFWd24Nzonl0CWU%k3m_vAJneo5lTamMFj*v_rP^Nr`nK`J)im*7}b^T$i$S z0bUVC+#iJqLh?r;u8GATg}Cu}_)DXCq>)4|e&3R+0{aHLH`pDg?W1(DL3TYr zy&|5i5ViX}mmLCYl8r8#%&(K^Xe)7X`}<_eUvg5Gb7y!rgyeCNXlNtJWuUrkV~Pw6 z3OhQ;8*Cq$05Oo4#)gkMWWGG{_erG<`L30h(i0@6n!Cu|zCqXOk)qPd?PtllQ-pKIq z>%FA#;RCE*0WYgp#eet1H;fvI+z^^v<-&TpZ@%6YvOdJ@%~*JhEG1v3e@XJGO%L33 zkIiH8Br>_`Eo0BN`G%XOp?YS&^aq9wV(>rQ4y)?yyu*};@B?Pk^?K$6(^Fl&jF8|f z;z0HPJk=twIqv&=0sixcmvFV;_>EHu7*5UoscCF zJmn;Yuk#T`=Hh=H(x$m`#u1enPbx%{11aH zgBzCb5noBP|Nahs4$=#AvdQoi90{xm)zhonH^10lERyvHaNvsEGf^&A(VMOZu#KIa zxg~UB0PGOKqFW!R|F^`bjy2n9A?Mn>$kz0P$(x$!ee~)=oPTIU3j+X4K{CrO@G3WwY;bEo>kmD zC;hPT2AHy4U{w2IO%yzz9{R6C+H^Zyr0( z4OUO;{7N={<6AIj!}L2@msmuIF8U9g*f8vJ_p!yR({Qo+BSb4XHS6ywoBR;-BQ?0R6 zLv7k$O|AUp_~X0GZ=mKSWpv(nVLm>7DGmxz7_PkgZ~$LUXttzByHL5F($VB5raONj z>j}=7VA^77`Xz%`)N1}>Dr{>KJ@f7jF;1K)%7WmYa^2LO%?|E!uE=m@AwfG?SY#fe z>X{2h$xDf@3Gt$x-MYjPyOzT3$s0WG46l~p1UxS?@^D%RFV$bKG78&zg2&)S{3ZPC z;=?-fhi`uuwpfrq$fG+fxE|&Wq)zRM(0;RHwf66qY8Aym(TVd{N>DU!a7Ff=P616Y z7s>JQf=AJ!bFPsS%^`L59qG4p)zrpdF2eUNU;`dFyXuhJtv_ng68oauyH-&Wwma}ujs*n&P8FrL43#tzYLS&eQPwR!#ow7K zPpimjm(r~p;<)m1MJ^IynqNtNj|lmpcW-2PExWoMq)G6C5Sw#wCb_)=o&c2Zor}C44O5XxsiNf2{oaJLw49ZyX zUfP2EL$m()wUOel4dC*`8O$y}-H%d0`Od!xefL3rb#(Y$w3^*@x(7ox43R8Uw~XkJW2e+Qv}m7B@R^524o zMxv&z=|_l1VB`~RxeIen8c^iM>WE=b!-|i8+0v3u;e5AnwrWLiaA8{~=JguNy((fk zQnmTH7eg)1#SO167ETVuwXn0ArdhsXJv1MwiLW3lHjulf_m>qt4<#S3!^07|J_~Z) zF4u3xWg<;V3ELlTuts^Q~z*zZ77i_0E@ zX<2u-;IEP?|;1xEI-zkuai=NM?1l#-L9- zIH0oodKNU|R{xyRGXn!o-DeJc0^IFtgTtgUYdQUg4ZXh8pu9=`Zdl$)JlaZ;8MtRU zr%(P$U_7;cF|Achv975INvW>pVGdr^cHdAAjI8ZE4J4*t41WSygRN}esdP~MaPHit z<_p$4;Qz2)BJc;zv?Aa@V;ai7c#G#n{7`AT;;HcC|J%ZyH0DXyUMtq6;lkw0B{h?7 zOjxT1;J&!&Nq#v@vtg9TTE&9mQn^qEIbG23{Xc)av^lM&Mp0`fZd=OKp*q6Gv~@2o zQUVVolw9F~!`XdrM`Jlvu&Kc~`>sk>K98c`8E?Fe!!JE{#3*_x{;%X2T`?%pm5fu}agPm6kd96{-PNCe1UgxdkXpr#hJhu&@ zq6~kB5VQgfqAzT8994c^dq<64-E`<`*1z3!zM`B_hm|$f#PuGb;j(rGzN^WYn_}HB z2?#}I$uhs5b@MC*#5miD)?|I9g(b|PlIvQpRfL;#16Xgb_;OK=UzDYjSZ*w5d|boOv;R$;WuM&maCLlj zd5Z2AjYQN4W7_PJ`ZlcCeQFSD#boOZ^>-_p;Ufrj>`wZ8DEGoOgACnzS}2h_*b6kY zuV_6$>XV38jutcVlz%i3qYF1|*YsdO{=XbZ#N+lGmcZ|Ix$thq7Rc7?b}f!MIf)55 zJ^e>RVJtMN-?}OadM5Z!5+N4YtZA*P4JYzGc0`D^$2L^_t&IISCkQb=j~&$V;*;U{ z7?oZ&yjA}e&SAbEyBS8Q0sBxyUpQNCW43fU_r<$*LONkzJlCADvC|C@q&-X!ygc0fN1 z*6}JwVqXF{CVT)sGRk(v`t{!~Mr)E_o06VB!I zcNCJ(yt1JoKvB~JyrsQ&`DBE1^9nC1{*0a1gO(;3a|*RO10n2*b$rQuj)JfylGZQQ3xG9fMc8^0qfAP(JJgOu$eCaud7UJJ`A$wP6H=Zz1i$^L8%NBs4L0> zZst~CTJGn+HEc%JnPA(cI?wP1zHr~MiX=%?D*9RP)_lfn!x8xqIU?1MHJ@A6i@$6` zzHk8ah~4G}qh3!QtkR>S?wzffFS5KqS4;wK%veYyH#h9>tcLey8Qo?mGBTUx!-YOK z5DXNc-X8p`6+SVVc}NprfVBT`rc-F+JXV=S76|{%O!vLMEbC8#kyrbNGyQ@tWqy_I zL6&NK=|=bT1Ey8`1et_O`;ntXt?p*fnz~)v>OR0>u)9vD3Z{wSG}w^Jx!pn^3+QX8 zkOH)SroTuNZ?7>eq*MNz=QbNodfi6!85baQa^HSxA0_PBDnX7HA!H-|Wf+zXyWUFJ z0mq7F(a%SpTs|zXAURQE?|x z9T7Zv;g;**Lwq7~Sf&kS*Zy)PR+k??0mb)UJ{co0K`G>QuL&)jZr%Qj7kqv0e>l~7 z3flRrDm#qK#wlmq?%j?RCAP9*Um^ZUb^L&+!ms_iDqI!7;NgEID{;Qc*aPs!qO@#%zf`7J)EjbORSGhH|@B24a$n{7Eo+qq0 zJ=8z6LLTFGnRu?qk{;#1IuN~0)GfGSqpMT@Gd*2pMD)CKb*8Cl{*B%eDn2IUuIP+Y z+4#o%(^7h4j#ZC+$7bqg2ltjVDEV|22On5@&CqWpAWc~HeE=TJXz zV6x{P`a0hFw^B-)_s>kYjO%I^eOd@(AC+0bT)%lat;QV+`>w6sVPp1JY$iiGnU}gK zmaus<`C~hvGl%W$_eX`yNF*(>R-@mJJpsytytpA@8lPrbBZE3*TkP-{2ow7U8>Y z8B<$Rdk#NK^g0?A7V5mUIFQWt)z(|sEK+hp_K@(f8wYh*G!JdyAyEy&U6fKkC&kaW zq5yu|rtd=_${?ggfkYWjqeN3E$KKSD6CTBg$v^dNc{9@7+_bE6ktmveT_>Y&?0L@-f7JG=$GR`E;yHZ>&#AAn z1q}zSDp{{^r_Q=n98CdN~U^ai*Ol8WREjY$lh@+ZA+S08eG zF@;Q`je^)E_gFw4a3PvQ1NS=+{Tl0jvp7$VP7L@-qG+4*KCS4nnwmrR^770=_~*wz zZIHRhLFPhus=4+{l+&!G@L09R9if76>E^{Dj_l(m10oMP_m7EMa~j@k`<63j)$?Oi ztVi&yV`B6!VwV9P3GILw+~MK+Eb&%6RTVc8skY_Y{oTIT?Z13<0v^QXHcC;9*rTgd z^ldlll|JX6PwX_lx%dT0;o6hKfSL1Fdv$!B71m}6-v!;@t`71(P8_%obi{gUDus{3 zAp|XNB@(T%Vdh5SaN3$X)I*tML9%ImiVK~yh5&FRLFyDADsSjkCpT6m~c&11|>+=%m9Fe*Qc0l`X zv`(f3beSvBD4cJkty%2pK~*L5OQ_7}(T*+Am zx#IQT&`lmCIR*2}=jR84K!>}vr9s@8?1(hb4hgybBf+yUr^ULJPLDT(4q556m- z^`P!d6otdp^NGx89rd>Z12zutyXPyPt-Askd7R$);>?>95x7S;)}7B4S>Fc*LdxRO zqDUElGNEPI*p=mnU7rqZci^+h9JRmoZeK$^)Ac-y+|pdqRlm7K`vyP1z>k zsD|rp9K_t7yl2p$pB?v*Xj@pybGH_dS|lq@m}wh}!KOl6RfOMFmb}r4KvzS;akSYn zX=3E&aFZL$(zwTkV~#a-7FZkcMg`sZkESmzu{H%7MjB^&;gLx-wZ+q&i#M=Yw(=kFT`_WI#O7y)$0#LiTfR42nPY|h+e8=l z*KFOj`SF9a40}3a{WlG{;WN+n7oAx%3bz1Cza}alEKR)AvWO%f}*rbUH2f zgl!-1CaM*itd=Do1!BwY&z(y@N;^|4I_F}Y=3~bp|MzNQM0BQNwi`EYKMj=k28c9< zk3DRqotTdtm=361bK8)q<4Y~dbTJ+7aq8+9_>0DU1+m~OI|aj#U{eW7q;AF^4yq_x zL5FI;7h|r)X{OPcENtFO)n+;I7i~c+WDLy!XKt(KTZHUbzW9YWJ>ycR)zmjTZ{uPum5I6yS?@Zo-lCC(rr}~et zUy7`gvV`nwVUQ$yb_S!6eaT+7DP)bY?@LmMkag^1ZERy3GnO&@UhdEL`#kske188L z`@G(->s;rY>pDlg!u$Jo;4J8;kN3J&Xk;i$nodZ6k`T2fbj_5u42imO^drE@Z^hVH z!Wjh4NVt?|G#?|Z;oiyEGxz8l>c+q>-=U5ZX95g&R5v~6h;QEhb04PF+3%-3o@D(O z1d0I=h|N$F&^7mMscL(7P^K0G$}&0ou71M1o`|nb6^XMs?+3|xM-gAkMZgN-^TzJp zb8S&GfJQ%uOLNtzIoRrIHEh~S1o?P$tH=K(ILjnhX5Ak;m&Ha|d<9}$(fAjJMYn{> z?xn;dpZDKnL@nNw8+N>D!;B7N(R8QT28j1m@6jI+SI`&yz1Hkn&u8oqW;R+`nMhN1 zG2jfWU1N3qdN?zxeE9g@+%{7P%h6U@NzzHn%{S9o$hG_^@^b4NTmxxAt=F^}TUXL0 zC=KqA5x*rff7#7b${|OGSftPdnP|td^X2p8eu~o(USDkoO!-7=h+#KbvdC4&lRTOi8gCNA59Jvl9-$^P_whv+{}H@m)dKzHU4Vj zjhchpvUdI3K(=x@nf1|L8XUkP8+87Jr8Zf+8v_CuQ|77teZye0d&}0XpIB(0B1o+D zFe#b64HV7smGi3m3X^yS+0cLgjgr}l2)eRpzs|UM*ILbTZ>RU@?M60_jNEGVx|{`2 z;huE9MIrhxeTz73J^u}W9Ek&h;i1bXTyZ7c5n*dbd>^)MN4_iM-&a5xacNKfhC6J3 zJL8EYOSFpg%8JUYy=&)R*g3|m+pZ4#UCJ=NhMDFDeqUk=>4kT;>@z!{*h5wsrJi+bY^`DL$Eh;g68q3hrC8_d#$8Cc}q+ z0b@z${dl)FS5~rNxf;oFu*cYec8#t=-9Vgn|XkT?V{b5b|z(?`F(X5G_ zk9m*|bJxIZqH$;hTyFLE#hKb(-~E2C_vJyj*l`;|-SO0V@@x+$lVY?X} z2EO;Hjc|iz4N*Dk%|R1cCl`gAy%KS&x#q!AxM?yBIjwOOBH}3sEWM24sKQ*u%`IV7Paip7f0Czx(5zx6ScM=tG58; zJQjeQ0jsJ|brAocKUwdox&I9WhM)>=VPrS?Ch4X?qDRAb1;z3P=xWO9tEb)5 zR?(Z^vIjxw=_xYaWy_QG)nnec^mspRNa_#dCItlDD0inxiv2d?q!jPifHcymoW|YR zh&DgjB1~x{3rMtaUx>99ig%d#_O`f;QQ&EUiuSyA=MPaj0!Km6U)1b>ouIk@7Zv^M zzo=avea+a$mGFiK|LeoYpOJ9k#P9&uK;l&@@Y(EKZ=SKO2P&K$b~w1%_07D|Uhdn^ z*ROpiKKt9>eevu41=XLXjMObHBOr!vcu{%jIIBm-=!K3q!*5iCdi(7&u8v99PlSCV zHHNU&WK^o#z`JvVYu=w~vBRcj^}r}2^C4UEyJ26Qhi0uW_9Y3NEV!}CrZs�)wEBE>U`>LB;$a08W|lR5v<(CGs$9t{B|50Y7I9iDJdl z?n?m{lP@g%2S1t05bk+f2~nv+a7UY?na@$-uXUSYyR%{^iNx6tba{eDBLf|U$(C#p z!lYOq#|;5#RKTPxmG^kf@=~1QQo{U*)w!cD6LGsPaC$&v4+vc;i z44QH7{12`{>WYuNkevuOvv+g$J29qB$itCF2`+!?Z-o>%=D7^hr!u%woh8I>XSE5{ z(qCv_%iW8`tT(*lH$y&_*YqSzM?4rxEjHDjsK%Y)k|2Nk=tjLI1sg)KNxtYx`x?nC zrUx=|BSn7xu|q}d>TSIpomU=vT6O1$G_tUaOPBUE01=wOPFFtj(o~(w7ivCmiE9B# z8CeL@Dsvu+1RB}j>*i&XFyxIL(3OuIO;_(1OWfM8y-B+3( zb>>FrQb5uW-(;GkYoye-v|lI~R(}da1Fso>M>ii9aPpRh8Z;V>V4ll)fP`o3U&@(G zXGVh}Xk798l%9nUY6Y5RuveY^NAl-bwo47b*OCxALFpVuM+h~7E%sJ>jkGQ|X_650 zk^|#$s*CGGg1E8cWZ?vmrNn|`BwwIe^ebDsH|ZNpK7JPd&tq{P0ug4^QXF(lIro1a zl>dFPg9khnd)b=MK62Z!b9Pt>%F^KGz@tccxc2B1!j#$TrG9ZqADm%Qb zxJg4h%yOKd*%#BF%TV+|z?Ev>wRGv;`G<^(mzm$(WJOLRhQHil5UDZt##fwzX@^FZ zX@@ABN?MFzjIY2kIJnM~$NRp0QpH|ljBAXu(S#jtR9LMzK>DVdt!3wpV_NS+Y1Q;B zWu4y7MeJWkRngjnz;hJr6ZhBaiM*9R7>%#)Y`ekRzqQ-cW8u_E%B(K;^IVMWvG;C2 z_cPzFRFZ=r_lM?8%tXmE&#BGPq?~%v4sHD{$a86{L{F4}{08wz20Q((hnCW$kWASa z%C~V~zz!3-y?r0+{901b8(9BYn#{i2?9_V>-yGt;lKowobF2~`qHsZ@-7Hf&qQt0| zY1>F)2fA9l(vi$=6qMue6#p((;F)XTAN8)F?J9K_!QR@QKVitf`h7D9st~BlT271C*woalEhdXN#Dn0OpUDNSW#q#IWTPKTf=jC5{ zTl3BLUV78et%q*L zWN`49-9z6SX7ZDJ%!+7QzCDCKTX9!Q7<(+?jm}TzibX1JFIR>w8bjBYmjYRx8i~Wp z_-ZVPcev)o`J92X0bFAh3e>b?w9=D;^{Wg~-nZ+f6z91oO!kVOM3ovZ#M7L_9e(%X!tF{1s3qHo^%p`Ji^p zr^+p}&;$fRcEadd#ay<@=lQ9{Q3~vy!YE#(g=5Pw25yYbC1m>D|IYO(t3VZ5nXLGca!@-DFB08uF?S zwwJi?^4crc-7RNUElnED#@h6~V4?fytrr5-{syG&H{ ziK~8ZgbKr@tiw~J-P7t2Uq^qsq*WN2xCJjy7S_k^wDAc(8ijigrycY(fqbT)FKZc| z?8D004Az?t-Xms8eFpEI?A4B{njA}n`)XNFUzeubJe*I!uX4>6xtfu%4HE6;7jnOR zBtNWMT`5q@?2NuHbzkLiTw!^ze$Ta1kEB%;i zI+l+aDR*?byrl2zydFx< zFF}DaINIg4q)NH@qG^MF>Gj% zCYZP_x%WmAqTsRkyCtznF@kX!IF|<^+;6OW$!4{112-6p75DbInTA_E3^6OffU=PH$W&+!LuLX#T8p$yd0LOTbhp!eMXHe zB76ZdH}U9Y*1Z0yaTPBj(hEZ=!^e2`mIc+9T(ufkk&6J^zE=9E*G5j3kvlALP;<}77aqAKHowEm zX{hRb*3k|Gy&rtlmZR<3`7_i6Vy==3pTK9I?6Hd%2rv<`Afu(NoV|C>(9G{jq6*iO znD+NM7bmZ`g?_!u+BA)r(#ih$=&DI%fH|aS>AEeZAolX_(Px4jgN#qL&mF6BjBVh~{EbfPAr)!b4-+~|Lua|O4%>8|{JPlN`jze9V52;ndLRP5FjeaDeF10@8cB;0%$BzR(_4^)#Eofkhg z-6kyV1+r=~yJq!?Lo9Q;$nDkHk2i*g8{y<9W;|)kq zBex#KzX~w7zkGH;uqb4&WqXoza*{iqY=ylW4pZfaR4Be*n~(S7ZJAd_s~dVeH-^NM z_YwzrdcQy6A&D-(L%nE1hd9ghz>F%Hc2U7a;v>C!b}Ie7PbbNHTLe$z z-|L}o6sIYj6=YxLN8<`6h1Hth&#!m;O-N|!Q8<3#ajIk96Oc(?ipG}jCJHwMudlvq z&p>OZ8(M$lj-}yf9OQtK%;cU-cY$loiFbu9ObIRacmcbx`Pt-8CGLz!N{mH;3cC4%zUi4Rk&n(LKA}siX)HExdT#! z@)}8FU3m|`r-DY3sG8Bh{Xlk{C!nG5wu1bIw(OV7#mvCo$_HN9;68sy7_T_Gp{#Oj=HvBt+9pZ&5(_ff$F$-)_{8_O6qNtVFi3s z9&%oK@3~N4MXRG_Tck+myS<45{X&@tNzhA2RX|BMmDiq4I5hn2{S-H4n7jFZJInt8%zY4Z*&8?PYy-gOz0;)nEIOr@U_PGoxJU7-uSzJb z$nq^Lj&HMjvewl)Fl!*$VZ2IR>4#C1ulLk6I}L5{;fQ6--F>ahqwIZl5u^M~jRl!A zV{+erEA%r!*|kTI{RdyYh98)qk{@x>(sce{Jeb!pNr)=r5-sR{0FBMzGtT@mw#P}8 zo8HSvE$v;r?4QF|l)h6gVVwuMZf4?z<^q(Hobg9)D!KZ{XjkLMw;X&AW2OBFsuhph zY5jy|9~;lxV0Z#d!$R|M@f|rHQn-erQJ!lyio3O|L-|ch>AukWLo2VMbpf8M%a7L} zL7yf(`l|6EpTzK1zn2fH1_{jRyhO?nFu4Gw$=KU?nPuAFHmbWuJ6Ozm=CHM+euovW z^GAC5x1iGg4T-beZ`J9Ix#B8&w6>1Y9`N6`3V(#*%PdWZR~5F2Naosi;uXoALQ1a- zIy~JUV@hN6CG#j=3fTS-CK9@p5xQ&(0o^dhbB zFg6cUW%MNTjgwLNNc@|gO|q41d|#n^{eJrBxCAz%e$8HZB!7W)+uy4tUkzHc;(o6^ z|6u&5@k<{cB)uD4zAldAUGiQ&Vf7x_3(eSSEChWNhFIQ+rvUndE$<@=xvv6v3=bu^ zP;8chOQPoq#EoMWQ}s>Oz+Vt<2?yIAAug9vtbuC4v}Lqpn>qKv{5k>jeh0sV>IGvh z-KSg{K>l_ad0#$(A_k&*4eMX@W)w-Z?~E`OuLH5X$z~x~AaBaK{U|jiIBLQ+8C2%f z1R`Q`!ZJqoLcQVyzEUN~z8>pXx5SOkF19;vRr#K-#cRqfsp3p%IA}ol;AE6XrR|U^ z1;jjRXy4xPBa`lKbxQrxe8g`Veq#pF@$TmBuH@9NBmvz-zEs$<`&^Vn-PVE*J%6Ts z{W_6+nrFBa zrH<*BAL<_y+I%3=qon5uR=unC31&^bhO?<;5GQN^n7lhiV}7^Uf-{i&OST8Qn?GX= zvKUgKG#cy4DBrEH6-$LBzT=;ddNX^d`*5X8W%?rB4lf#fe==bvGfbP{cK~M&!6}$ z1qGhW@|>tD6(wN}roN&4ha}LhnGd@DP_*_M=CEm`Zh@K{9&|G|d2iR*Z_bJvV|KbR z&!q`jI60o}ZS_LT%?CQt=vUj9sL$Xv8)+$k$Bs>MVs>%@YBtC5`6~dkqocA9L9~02_ zReWwgE+oEm$lVT_n6|{89vJN4Ht-XB8g(RoS zE6o#yhG_9Nk+9%vFOD0`As~F^fFyHPBH%{6l@=22AYfsy)&a=5VA2inmhF72kPF z=*dw3TK`+&o}wg&=1lSMPDyMzV37=DwV4LCdZmb{exS4l9Z7iQFHyP@&Fw8=l{ zl?~8@j>TNS9M_5j#y2|G)>FNG|9UpgMDjI-#@>S|CbKMfBNM;kiO~n-Ji$Z;+22JYuq}ODr%*wstY2L9e0Zoj)27@=hvL4Zsu-B zNQ4Iqlc33B^4paYXGb3EMn0V2^`mkxyUb$Q_Z#Tv(!^)-JlR_WjzFec9iIV`hK?7Krt zbEY7b^NjBi>;T$8kLG8`jDQkrmykcel1-x%Oy3bl{Fe=SIW@mPGd5 z3Edd+F%Bv-v_~>71<*7^Ywpv<%G4zuY>g5-&W4A#$hmg8(MqWYnH*&2_)r|Q41-6w zd=n5%ZJY3Y8>`gTurB8{n%IM8^|6oLKR6giM?R==?4>*S12Ks?^`--tyYI@|Za+ig zb@pXzsC(exaAo0ME7Us8S?QgnADbi;cpH+q>x$WYH9Rc zOHGk`3rez$2;x>zo7(TXXFtwiw@DYJdGRF{t*e|r3Af1Yj`y`hO6HB5d}~`Y4rT^4 zVU-d5(mS&fz|vJlmZ!^(BE?(@-n4+cU2Yox@?Wo zPl|dh8W*2x0c9<Jo_x;- zXaE~(<__ZF9ZG*No*s9j@Ir!wYUdeD5rmIHT3x>tW zNk%DEKeJ}SgJ~&y?G@Jg)ywzLQ_*hiOeD!E^P5oXW*PW{$&mG?DTzkYp48q{$aGMc z!tKg|Q7WUbPF|>^bUJoV8C~oD{hKDe%s~M%m?FJCBJ)aCgTmIZC6smHLrf5)Qfgrr z@4(u9&55Nh3TfqIYDS*A-paa^%O%%m$<-`Clk~E11(v~<7ghC9KZpc(*s2#lth!lT zwSSfy|EQ8F&DkWcF8gBD*YY_>2idMrReJuuJYwmWr$fBUMNF)l_VH}3ZWssoSB-U* zL&0|=PGW9S`7}nk9DJ{tDL&99#wY+uraLlxaVW#hBzoQZokj9NXka?-U?Aph|Dyyi zY4rjEomsl=Jd+3VFufqn7h8@yBbh?bvfrc+bwk?5z&R-~I|4E7 z$tR9)^7RM6uLE@(ZD(`pvF73}#Tayg8}@VXC}{hIv&_!WUSI5Fbw8@PMnC&)tkUkH z&-|!a+4C@`vsD1T>7vb=rzHFeSgI#nBD6gLG#R9W9lYaJ+nNI8dM1cxwwxzMMAyIU zgL0&Qk>IRze6Rk!>llD^#&%4?jkV-Az$Iyy;5i${gSe8sm7+k8XhwDL90{v3Q?XJ2#$*cd%yFDP6JIJwI zH={A;Dg6PZtoHP!B_4?DINqhlL4IQm|CF5LzIBh>)2N#Lz&8vtGdT&=FE2%p6{=_Px0EG*REI>2BAMV12s$ z@i%>wzH?5$ScVPCfEmBl_ZnZ9wT$}gnse15*5hXk%?Mt_6FHE`bZxQn#5A&=+SSN-rY(QSB9K#0v+ck zjyGeKLZ)?t`XoT!Jm*pKK@O-(FfX{R40nrZ-aa1?BfWM{GnFE!ifA-jn2c&voP>E$ zEP9R!omSRTe76L4Ti_cbb(c^6V+jby_&R%gBy)UK%^6m&uP@6(6`S{$`Fee`lw-vE z#cc;W#7yfVwk*RD&DdA17c-s&&;&Fp)E&pITYKjVHUYDTQfjszL$?tYRQel+*EW0Y z9cvk>)r=jQr2%QBo5CL8(AexTYL%R@RLh+9y2pLM*`E8^)qiR=Z|(v7q3bMsmF2%X z(kJZZ=v+z9h-?e0OTK@xeLXX~auVwhe${^W{)VRhBj(`O3S;jjoHF7TuQBXp1E1At z&lo!Y1cgsEfB|dOoBJRRfCn1hIJlIH%1HEQaNryg_p6g0%VcUT!6-D`5HCQcok@)u>c$<~=KhzK zT7WdVWGyH2^kVHi|Ii9ZWgQuI3E?i7F(B##plo_%f71?-bB1cxXBcY)2%#QJTr_fo zpp0O=skHkAlaK+Ps^1t*`Ud0rVI|Y{8-42C=~9B*&28f!`l>`BsZtKrJEQc}=%)u? z>d0;W1x>lvi=^* zy5Rvo+2qo!vtzdbq?TVqW=J7}3a<-^*yshATfCycdOa&uR^vOI8Cr~}NwWjZMZU7H zn(x_LIh_yq5wcB|kG8tdPtL=BXp9ogTt($_N8K5N;t^|~`ab!|w;4_5D2+QhjBuJf zwa1P;65E)FH?`^CEFbmW^Q;ry^227ZEl%7cr5Q3KPi93jbK!Eun`_WaVx>nBLQPug zDevcMTJ@*O)7<)1Z2PlS0F2iE6yd*odxy>^^e;!C|9?8X$SnHZ%kkiQ+-H6ox%CFZ zgUxlIuDASBqrdKcG;%sra}soj1y0zepKKrO#;b~K$13t|e}9zUx`En75qhIDdF8Gt z(O);va;PTG$7_mvorYZXT$>o};D{}zRH+Hpet$F$NE)r)P{QNmL~$j_en+%GD7(@3 zt{$W5)djzoBY2P=?wUvdAmZ8&8OruR@tu|7BC-C29nN#|C8i+<_ZI-X_De+qix{&9 z7QmAxn_5Wp>$&nVx$~$;TGao#ptWvMNB+?JbSK>7fAsu+;EZ!=uNyP|$TVe2>}NE! zpV>I!%l?rrh-~t9@B;%_eUY_49Y{9_{@moq4z0qZ+pK+Zf9YJ}e%w)!^1LaJx@8?m zT(x7&+^$upT7WazAWJDqheh0;X5d19&drZxk#^>YGrQy~8|%q<%c^M}ELFB1QSGu$ zBZW-yi}?*L(p%_~HKw2V@D9(0BJsLA$I-OLsto=S7Fs-)fGR13^++t$23;9Niq zsK$LT=$d-_c$0t6Pi1DS-LnDJPG#w_g8V|w+tu(%m|Lm?OB!K|CIE|=febCM`EdXE zgmk#*A{%*(Zv)RORXb|+PQ&*1)gHRq4K?Iz2Pd2BQ1{8N{^E>cO1*WeWtIoH2=t-1 z9t|NOM{1YHV;`Qm74~Iy*RZZpfQIpnbDa#yZ_k3N(czdwxy8|W_(8_@eIH|^>4IcZ z$FHi%Dt|TDs7-(R_-ey}v?=pmlT$BUXX}TCUrt>sCvB2+CrCF->_U<|C3qc`K^U6(Bwsta~REkI&Xf zSFoh(AFt!$Z|H_oX7&EwVX3UkC|yR8>tkFQE;b#18Hg0M>b#r<0~&k|mL!`b9+79d zerE5c8X72)NZtO^JPvQqUD=ga6w+dbyVlr}sg4c;{>c9ex?0dA2;_*X@3+o#3H<8} z9#eko#nh|BJ2+E?_^MXYv-So-b`(fn!!PugAMQPN?!#(S}$OA8~Z+hf)NAO?{ zfnPqe_q736g^uZ9emwttsB7IV4e%<6>Wz&&<7Lr&)8JhD9DqF6BLZu+w{m=>uCg z8Snv%WuxY|te!(twh8%-#+!6>3Kuyw0z(KtGbC zk~*+Zx_;EyDyYN^F1^pLzhX#Y3)6|~pLy2YDFR?d2eg)lul;M1-<cze+ zWfn`5cP@cBdw?r4Awp@UA~{3Z?=2t34*!hV4cicT3CmSw;(oC4`ou}`)}I?MlTCj~ z+7#q^7HcXA&yLTL*XHbx;EOuz-`<{Y3|I5U1D@ek zqS%XHS2=pqJ*RB4^MP*Y3}fNZrV03*{xF30u6^vwUU=$_PxXdqIQ(Z#(#;bwIL>0M zySc(UKgmGdI!{@EY>4JhCFQIQZS1O}#3?}Oaiej2E`le>S(O|PFc1I_sW zzErGr-Jm0hiwf9!xYuXO4+HFGx%!Hm$3$QQdtbtfbulLk2@P;u%%L!cD#@uO}itqs+mrQ2S2H} zZ15gCFtP%N(@mNH#fCyyVea*T)*;7nTJk}`q4l-DucHDp%%fb4amJi*rcphf1iJKT z9P2eavq%+ao^5CGn7nE;Up+s<)OD`d&-nc&GjYrh&PaBz-`=@3ofRvudiV^BpAX)( zm>+sWkg^(irYqDk4{)gP@@-A*m^UipPXEv!Uz&g$tbB}*)s)U-?RKg%{!CJMItK#%MSCxJxWYl=-jKE^VdleXCm_T&U;dE$1YyI zJ;dXHtfvdiKpR*0=<@_jcRvE?ENcyg%kb%OUF)y3Gra3Ot3U+HM+%*q_S(euD-07x zg#)HbAW0JO6TZ(0p!g-lv2j#LK)!;RjNcm+?JT9ypOFM$h3k35wk`Q6*>PvmQ)1a! z1AODRXwyS*g4ZrXyoCC`<6YXKZ`jROpK7_nXK-iDdXAGkqX}%w( z8e|ZTxER88yKKv;TSv(WZ{tL{*x42x%Dcst*sAR?f&;Uc1EwSUVoTGgW!gj?7H5Qm zsh2q!!cZ~?->$BAIv>?4KudF5hZqlrt5b;o>jh8{xOYz140Q={?SjGvBe(y%3P4Ko zOj;;ijXS)&x#G#zaJ?hv!DZ_40Ee*qEJ3vye;Nj&MfOKD=_df%Q>wEQl9g~XMKspl zqvfMHBoGuktJH$32iBVJzH`t%7qBu^jp)%bHFIFww*48$WeXfC1wK1#1ptG!ycb0?{SxV3T_ci7KWao1Agss297yCIXLPZR0wb^Pxvij}UXaS`U ze;=&QhxegWD@d)3mzQV)x&|)I3(%dI4B0ypuAvs~LdTGgnoNG?k)DdJDU&URBXUsZj`fx>jzO2s&A| z2Y5~w8S^ec9xV5^e0A0AsS~>A(CNlzKre&a6bV*;hOIF^eWq%q@N>E8p6ivHH9tLG zxK%v<9_^7}jTRmDm%&;Mh{Ze6{o=I8UI}L(ajaILW7M{tl&Un5Irv^s#eOe-5mR;F zw9UNH0la6&MbG}&&7$P9U6qKdc{1k^RVQju?H-5#W%JN9LtH5qlfib6aGF%gMZa{Q zcf=ypZePo_0iODTrGeZ+FkJTgYJHF&5ML8$j_LscDx#`IEl@r77wt3s6KAmIZ@0 z!_psg(%o7l(Owm1PtDOu(m9P)|6(aE()#Lu9ka)8asu>(Prq5X__Is@taSf*`^SOA zW1V_y;cxVGzxeDtRBGcXAGE|FaC0XP{YsRl!~;L}OUzhu;o(DyB_Dv7Eg$SjA*MRR zK#>%?UBDmXt7lie4$LP4^{ACVUku8Qtoqq^TzR!6gkS{eP~5J>H3og9)dz>g!Cf?WAQCDvw2l| zd*$fH>Bu>%YF#h?y zR6XTV`S709I2aRNLI^Sn!B;0pljH0BiuY5xj@ve95T?NDu;UjIW5!nZq};mRKXNgU zPENSR zSnaqb^$V)YePNODDmlhPfBVyk%R@u^#Fg@A+a0kSQOJDYhi_Ye()3)t!Q7?t)l%lX zFlTJG!r2SNjWd>M=bilxps~9?QW}7e&FcRbTc8Dx~Ys-(-0Gu16wXuB5TdBoIxV_VtX5#teU#-I@qv{U!f1>GF>sF*V znk$Ahg-6TDNTsoX7?{jure<+3Qz19`l8U`K3`)n?zVvO&e4yds!n0@RfpHR@+>OM@ z`3&5kZ0;$qxg|pMk3#R)YT#3XCxI<**)|3xYf&5#voxnxpZ+wc00%((-L2fMbzywC zRFN#~kpyZQsd6dQ7g+!cbos?7@CF#~hpx7RWnErbC!n_yI$97g^^`k5AH{cHqHamG zId0KLVO3~1{Fu9|<;m+|^!hs-l06~pMk#fG6k>6xU8`H^OvGyl`k2Te)*fdH3N(t2#lt&A$R5Vi%n`*;l)|FoZ1%PqIKDWmb<|@Dq_;1^ds_i=aHF=*Wc!A29LaT}O%QPv}lntz@JMdM@l-NL zngWONSNFZr?mxtmfN2go5!f#n==7+@3BbRkH=s0Lv%8>5FXN_VmQ_4fX&V$i><64e zkq5J_$bji%zkdHP+E`j|eqPw`S|$4~M$_y(SBj_o=qDSFz%UHmxe>r(@xzp+6Jj0L zxyIlCRPp&IP%M>|U_c5iCS{lNbx@3hP3$+WoFGZ8cb_%EfEp`)e6rZ_KMk+>Ag6z^ zjI>AJhyTglnpiyQtepsVCjnq1SwW$b*?8T8Rh#$jxEXTQCi>oN=x-u*_iIq*^4SB- zRc`1XUH6`k4Q4xLuToi3|2zsx2jeMsx4K+WLVy$;BRc1r)_YhnjyxFOoNG^>RCC_| zoe;BSp&z%xW^Kv2&DkC{13KxRV^~T{i8jw>=AK@#A@XWTG}9<9e>bef-404m@C5 z82Yr4zu7XZjL%P?$q@J+Y}*2}WX5Nc&5E7IOWw3-W;jbX0;M$R8Mxvzi*IfvX`GmkXaaG!U1;JWSf{4DVxdEf6iEx%KdZeCIK&%do6K z`JcHhW@ht0U|*Wb`vXeKzdg;*8)NL;DMU35j0`4!tCW>P2DZJjI~N=dYn=bYGX~_dS3%{Nz5X^L;w3qv4`#-Ds5fEnsV0-hIu-iRR$6~O<7qjLjSH41@ z8T@X+st<8_!MLepa3I((;DZU41$Lr5G@caIC0PHfW95}Mz7n&VZG~G{ zFf@4A-txC%He6&^u>@2mL*T)HW3pMkTpnjf9em#G+${d!Qk za%ZTOR{F6@_S)G?+<9PTX+k-{07sydmBv|5SwP8Qmv|5_*rYwa z#I8B{lT+jN1MNAKB89ia?S_9P7RdxmbE~J+be?yy!1{IXoYRygCiI``Pvq6t0VJ-& zyUa(I;$E-0rbb&zh_ssj3rvchu!Ily)^%r`GL^F`*fy*|eMN@7p_7QsolTc4+ROp+9RsqUGc1T16s7=g?JRg8PIx;$P z0Z7#%Y!#yqo$PzMF8SeqJO(K8iSb6f(2VwPL}O5>yh1LNY7jP`WZkXy_3B&p-QHfN z{N?W`;GtE zt~XRrU&;c?Rv*U9R`}gE@ZQThnCjqwE<1Egi_J5=`7)4UznU8@0W(J%RECcMFME@F zsQIe_?CW`W=301%l&LW*n~!UM^~zxJ62o(ttWCDlAs~Q%gscqbTUAtpNf@0m9**|^&a=t0uUX@uWa+KNq@Wf&D0`LGOA!cX+J9Re@W zHTTuw;>x&3E%IG(nSsc$ThId{TQ8_H4Aht}+OqT#kj`+Uht|&c&$znfS7YD+h92FS z=)6w;uCXV7B3A(T`$Wd0MUQ&a97QS?~6RqrleVLbJ$n_Im|~wR?Y3qnaS4_V4lrL94ub z)NQshsI6b1C(`K!W~PXaccNWy(x2hd@JH8 z7!rU5KSk;Ac!`TdiW3l`Dn_Fx_@0fkLx%zV&#k!Lv&-+Z*QX58^Kk%*h3-(Hp@cpC z<`)G`jmjd^dIJYA;G)z7#!tr*xd89AtVakb25eBy_l%O%P?S5FOR7xHQ;sxZ*~+N0 z|C-uu4Lk~WMOuyi^(aW4uq@SIZhOY|-;aXY@uP5-^T*#p$NiqOp^HBc>l4>Zg1+Lc zKUpcso@my+Im%51=5|8H0Bdw1xIdXe`vEk(;c$P&7W`9hd;e5^dTi%sFnyRQFw!La zyyIQM-oT^+eOfgAj;rEV(gJ^^;bm=K>R_+kH+E^|{l8Q=8PYrL3Iuk4CU4w&+$dYW zj(g?`L@vW)+nnx~yDNS5CbK{Mq}P@|hy(Fv1YuOI5qy!jJZyjxM2wZI$HA!)(Rtd? zC5<}Eyx3-7ZE1oyW?iO^_-klOcc@ZVnFu80j4BnB>Cn-yG8yP!!-QN0>WF)NF>r{w=ldwl76~xQo!Vl@YY?2iYWB&r$Id)cb-|K6-1Zpa7yhM5W5#$w;~^H zue(|K?Jf_NIe)eA1Q1JxFdAT<+cPYXlD|MeZU5pRcHMifyi%-RUbl~}7ux?5R^XrQ z2Yu~n?@40V-07-*u~((JrE>X|@pnPkx#@OaU^JImiQR1FiwTWeV0IaMe(czWFI@R{ z*9WOJwRd_iBJTdwpWL4E`Bm3STD~Ed5IQ!vIP2Mm5R>rN0_hugFdwCZf!iIvdVBCO z8cT-`%NtnYuoi;&Hv>UA;bpFR>YwoMDXRB*zR6>-xRyZO;hPe3{4|W@tVK46hqT}N z>X{2yr^h9>9A9lrx1{3GV3Hx-W9;XxhtM-*2cSRugSjsy<7@}8Ua8u-d)<4(uG|C$ zB*aM3prOyn@B$=-Xo$7{whX3Dge(^}8o{z5KSB_&Vw3fyJJAYF6kwh6?P4n3k;J9V zl__S1=Z+~wyP+Xqf744M==Qx|7?(bKI|iKDQ2>4r!05q(Dw`5L`0a&Qtj-NE!M$4a zU(}svxLIc)KxmImJB+1(Y0dsCEtCsq7tEDR| z<0W(1qJinFe>a-v67P>Je#Kg;(5!9SJ6ubwEyUIo__}igbOgfup!{F zd#)D^nqHlY*Y9bigK=!tOy!Z-o7)XMC|{ScMTVtmWiA>~@7 z+(ZJ-S9ZWf#Gl&D>`$OLV7!Lp?6)hE%WhJ8(2NJ59?;+XY!^t=Tm@9TyG<(8?P|R+ z{V-vj%va%$jDng;V%)RhkYVqkONs1Wq=b4?JVVP=$ETAC3SW+iPlVIj+;X3Y1UJX1 z6f_igUkcv#YN(#O;ZU#eoWJj(A^-cNU+W`GpV^I;S1T}%g5y==FZkTMzq%%bKF6YV zg7$a5gbd0`m=*(6SH_Q*RUX><<2{^ z-e8dK*B`5znZ4}Z;rx!Ko3{6(4}^A1JD*FmBJ^~7bdAoW==|(+pY5%NOdLtd>nQsM z1H==6(>%b@<`&nl%5Vi3wbMd=s%={s&l^{&THW;?6y^%(<|=0s_np#UF`(xssa&?q zz1RcK)bDcL9vj#xq=WAn#!*V-{h~UGp<{9-1h~?aTY!o&wGdH-Q*cHMs0%9CxF$w6 z7FWU*)%T0Bb)1bfIGn}}>sP<`x}3@B#?1IQIhlp`tjlXGNBNw*?#*I8g;sKNA*M;# z+GK%#@lwUM*FctkT%~IdiKPJch;u#c)#MDn&t|SBquhc`3@~cRy<=m2=gYvg^Xn3V zH|&|fujgMNrF9C+Bt(Xi$xv@O?WCMgs!JbC2glqPBYZDZz2DKhNl}=;w?6W%7#nL* zu-TB1BOi07NeZ*Z6AuIYtYaT|$hR#3pJSx}Ji>e;K&PABd zqEp|G%n)L-jO>9iwUZ9Mevl}Mx%j35*jaGLb`}VI>?eV;%h3R7K5nx70LJE1WPPd- z3yFqtWU%~5n7On9Y|Sa&Bm!ws^T{3&vi(44{+KEz#ELfP`z%LR;^`w zbn$l7wYxgNUFY737^`-2npZpYlUumVHQNEiw?g0v$+zlCVzvVP;+{qAR#U_#gC+df z$2gu%+g#KTFg(@h!{To0HS-p!&xKa*gTY~kJQu(?*Jp#Gr=JaqO+IW_t`yg6I5bm8 zR`~VNa%-JzM=?O#6fm$+cIRT^VdwH#UgloBWMe4AGvs_M3y-~wQQYbgjaLt%&Pj&$13M2LScW^9vzbFw^U87)7_K6?uGh6u+tzRvdwo; zTR9)N#_IaPlDVu5;_-FnV}sfMf*{WCN_eaqxr4@qvt6(^{7VEd3%gfp8>v!T?>V2U zngGq?U2)JnzWwK1^PIZj}TH_@!j|nO$*51;kZdAW>!r*>z0U(Z4;V9OAzmpe2n8wYb5O1w2UE10{X~MFjZrF?9fp11yS*b=||n#*7d5 zF~v2Dk)j5)<@WgW&>D}UdpPL!@Crj|MW{?VS)P=>Gxh(m_m*K*tz8?a;8MV%R8YFX zLPRP(s|A zde(n{Qk3sepssApyCFgYR^mb4U`_n|X7e#){9x`O*0%jv*{x>>ri=G7^BE-=@aSEb zBx^V%vF}Uqe8c;)dC{kp4vohyZHV&F?webRq6lKi*Y-%4JVw`)B)eYavWrt9e>6vP zM(e|)CA-~x9jX4IBQ5e$)=$!)B|ueZeeN2l|kkyoMW zctec5bO>Zobs-?j&*qr#PRYs3`asM1v2*o+A>->oOd86XhPC_+cA;4j{4q zK5!lHlog%s5XQ=*$@^j7G>gQ6puC2)z?qnkX?{v{=)A! zSW+$UKT^xIrvT+DIkh5&tMEkn^Q z*WtB+0XIw|SdS8`a@KE{sa)`uE+f9|;T(fZKGHpzRUFH|?VFZcVFNzFA-KqHLtN9ls(% z-J%Z>+q*0ILQnQ>wz2_WDXyq_Nk&)X@gplb3j0p*zJ!s?@foGGX5E;A?uK(cvAbQ{ zt-)=Jf%=WC&!&253rYsLsmIxLZ-fu95MD?;e>DPQ0=kmfwa`8fWsnNKqv*eWWBKN2 zf^3Xjcoyxq%r)hfR8R^D3Q0n2cfJ;+uZP>K-*xuycq$lr+7vZ9@S0NR>Us3aicbNL za}~a1P@db#>04)ooFyr%ovH zuOFrwhw70V(76L?2;ys{#qivgZr?>DTn)!bVji`d>zK^eh{W8B&qQL_;^kNtP3;h9 zfXvq(x=t3b_mNjG+2Lh;d%Y2o&oN_+kKdTq0>|^NTlwB?qsV1fX@j%e(JSk=@~6`b zVrd_|y@=nIb%AdV8c)#fi89EY6s2U5gS<*v`$mP0f{J0OQFNQsX>WY@KAPS@w&;_t z=gpgqoZmArw0gU{3`I69P%|Rn4(S09{h;s46>2r|jv30i{ux}qCK3}z^;~NNdQ|bg ziqieAizS;b6&I;4@A!&3F&oax>jEzGO}##SkgT?0YNIz#XJO5K#iB{IEG(BxxXt)` z-|#2lL!$dmUvfXm3uRib@25*W^+jTPY!l^1cCSM%>InOrqd!)ka6Q@#XYs|11uL&^ z*8=4G=6Pd(rgoWglR8DMmL%*LOMU1l)obkYbOg!RaR~qfiFl$U;eb5@lZ7vLFBe|B z<#?8{cbw1V`6d^J`LM=!&;(najbY< zI&s+dr9N}fb^K?hW3@@6nWmv+$FQK_S*-10-xJ-YnCrqz&uX*RdzN$?!}Fr=j~o@7 zFH&oClTo1l9)M|Oc zskJP?e=OfJnTw{J$FrowUKT~`zW6MrhOgEFp&_w&>S5DwI?2_yHwMR^-ziKX&lPvw zCBG~Z%34N#%vei#40;h9hm+59b3DviT0R%G!lpXkB_~OQGEK29DW%+NA*(ZwB73bG z!r#ug0xb*9mL}Wi%(IV=upfp4TLOs#xWWGC?Q*K6$Ciw~nj9I*!C8gF9kM-TUh)K$ zDG=N!gFQ2km?3)H^!W|QI5y6sAafO<3_ zC9$L_ND+^p22{^PzY=yn zKJ?lJ@6-`hlRDYb4x?i}v;+^+*v*Mf)Htoo4*48@@!3-PmTcyOzTO!oerxDg`|kbq zs1x}3SZ(J36)a8f-o>1^7y%_aGSe@;^PZWeOeespkMg9~YWX(9FLgr8&D;$~7r{~U zvG0Z+I;yF6zhACPP*ZbNXg$VIGJlL!`yD7fZbhpFD89V*6=E~qR=3@~r^HGxB*{|~ zs~LSfl4sJyp`Sg*UMxKi^M-hE1{CSlt8uSbusa#;Odz>XVQ4--BD}(K?60*DI8bQw zQicY1D+h2XT%Y=R4@aMMeYBQ6SfcfEwux>aSSu%tb8WF$^Oh-n>{GsK{jmy0duqlr zkAn8SUxRZLUdL5M$0AQZ;Yn+mad_8HSL zO8X{-r3;>!Ao&5-bydHrsPhWYE2}r?F(ApDFFZ=+cGS8N%T& zBzE=zVZ*i*y#YvH1LVn~DB90PP&WCwo|Wxh{SBy(yH3THMBAcKjXTY*6rq8JW+)j@ zpN}dA(Qk0QcNF?-IXvBEunDdvjQt1|7^yHV9(I~QE>NBPKJrez@@&M=XrcGXE{YF* zMq1Tsbp+P;$KK|Jg^AK;^~W#)d}&09e@K6L(SRi1>^fU}{416Yi^2GjWcp_%^83o< z`7Q2e)l{E58o$0^Jj-UUZbj+FFVoIa4Ho)ds8H^60>*%)_qqI^zfgNz`LQ^Dl+z(H z-B=xHr!nE<{iTT(c#t}T?kf7B^Jm7Gr9vkMQm-OsP<9mSz@Opgu>rez*p%!;2=PW# zy>!EC?b4-ov*qdwKhe9)pl!PFc6!qA#DoSsmQq7mRlH zFT-kV53FcKx@@*%DE#W7oE@%b;u4*(NWGZbLme~;BckehA! zs`2)In`A2L2=~Q(HRI4ZN;B^R^p1M>k(EO9zoK;ud;bvxA_aa(-^SVXZUqrNx)u*!d{Z^2kk58w>MZD&4 zRWi*gTA><_Fx#*4lS>egEq5uJSKu65SF)b@%22pMD<7+Bxoq<~?9Ik}N0h_zL`#a* z%2=^{RJ2@W(D9|{8}DPGFV#$*`GdOkYs^F!4A;Y+Yb>x>+Nf8Nb2>nvn%MSacjlE6 z-A$onq{W1EP#pJQxPyDXbn3kZIW_A!St_=a$QF%!)=x`%j{DHK*-jLPcz?X;y|?Gk zWEz2Uf>Q+GGUr%}eAy%;B{ybi#~1JQti3&OCQB4&@`BRC-CS&$IF0sU8boJn)>qv+ z>DyRp16a8Oq9<|=mZ9VN!SK%xY13e7n7QAw9iiOF=Dipp@{q`otd8Nx5`c#!z4U>)?HSZtvkQO+zoN`^7e zW}j9)q~%zIrmF1j;553$-?$H2#@7cb!5-WSpN{Fv9hy`eqsIc%!Pu*mTSW!7e*07u*N75C z_0`-{Qxo^j;)1z+_IREuh_$Ns4)JRR>-xtsy~4 zsf~A$I`vki#>EIO0@wbcsEwOzPRQ8{*~;T}-{+HN7WAY1T4Er~7a3;USPj*P95#L3 zicD$eAX{a*x9|vdukYh24!WW@$7FxlKyTD4su0@bAg4g=uaRSOj);NJS&sc=XJyka z%o>8Ts@Rv6*i!#$I-mN1>5LfTKE730iBAB5=KiiABBUSX72mCQyU6+Bs%+~f!xEmV zX)ijOyEfHCJqHaK-)){$8n2hTFPk49t(@r%Vi%#CA#0r~9^@BYjl);hd$qWB*=v9X zukw}P`G)Gx3t#%9UDMTGOAXekjOAz=1L8j|3#syGI4~NG#2s@N?nJ>!EHS=?uXj?X z+&G3tNEg`bJB!FkjMsRzUt2-Ti-jeEc@e1sMIyQdx~u~wU^5UCsg4P_Q5G7F${sm! zLk1CHm^K)69O|)d=31Cwq-T8yDqZ>hX+ZM^_71az2r@H@Chp~DH2L1V;-fg2;Hi1C z)0-OHZV($pMjYDS#{zdn(1M1pIoMmObRm(UdGCmswKV%4rBy!#K!xB$yAnk9_eWLUdZWQ&d# za-2Jl4{uEXE#Le)3i-xUTkI)N${$a6Mr;fUY@VN+ggOgYhRcc-&I%0!%sQf0{PGQy z?xvEufikl_zGUUTt?RdRGZV6kNVeyZ_j((w{;~MqQ!4eWXS-clvzf! zc$QsoU@Hm^?z3OK=xaxO5Ki#H*`{3-jQSLb16bq7Q1X<|u4BT;xV777kN)t1h44Gq z?n(`)9!4wc%^?JK?ayU9kE|5kc*>AMx{*jkpytZvdwgO>mhmn@R`dX@k#Y|P|D7)r zo#YG6_hI;HeD_hq8rxZlAA7=X1(vJCI?r+KIU#Jx(>a>-AG9{2g`r~qSH|dBtU1UI zVwXwv7se?0d&bcB3-$eRK$7t$W{yDRP^%l7hJ9v=2{ZI^(w%-o!w6xXI)LnU4>H`u z*<{xxIz%ruGwa;pggr4t_9WlIvh`m29s%r(r%DBvHfn5taA?yc#!oqd`D%O8b>Cdr zA~moVY)S77%ZZ)p5ip87k^S>}iQB(#$S%8XI%r;Kw&Llx6_I<0a?kf)T3db6Oa+Y% zss9Nvm`Fhj(`n~!YCo5iaK*+Ks= zA^f>S*4m?*4OX{6wiWZtve$a?maKkq!fl*!$f)*D6nFrlT3-Fl_vVjP>=B1mJg+W$ zhqqHGpKn^0o2)PXU|A5Stb2^-=9X;N;3H~l)Su=20Z?1qNTQ~dpNn8oA*9H%v+Cz;%*S z0D2xs{_kbPd*l*h-;W)6>i%Dll2geOx9^+*wN>zsOiAb5Ny#5#*oz3OG510Q+KGVP zkjF6kbRzB*#0 z9bGneT!>OVSKvh^CVEAmj1Xen=(LF5{^X6HTKxgi6z0s(HTF%_>$}fRde%#dAC89$ zEgo`WhwCp%bwW@tZJ?Xt#piHWvX2)E{!Wn?Rp{Qije~!-Ui4C4@9UpU$h7PpuiLT) zd5Yf|c3?tdQs7)XQnXLDun>wGq6c{N1e+>XumUG1-u7X#VOP;9t5P9^O077j6cP(U z-KxEo6x^2Z3E_-x6CVE6y&C7YU?GN8c!o7#p^LnHueh;+Mi~jmk|?&d`t6E?cqmpy zH0wWvpUANGMu+O?U$uO)G!SV15+eZe^r=3)y7i_AeWe9A@{gek>9{tE8Gl(iq?wy4c4_dQ{vTRs zhh?+}zmv@O@X+Q*lvSwsdI9bsD2uDHz32dHKyV$0)MD_}yz=U2PTUWTA>Dp@_sJ4#DUtd1i(NQQP0IIJ9g`7&4eSeM4@=Tui(7`Z;8=nAA{~5?0o>q2B zdqE3}yHO&}AGnR51^uuGH#i(9GiV2FkpST~N8>?MZhv7wN`ckSkG7$NpbQ*2aPX!k z+uXsDkOHD*X9hwBsfup{rw)V1Tk^aBdi>q1F3xvfp>$iT`Fnm65Pnq(`%*7vqCF~Bbh-bXbKZ(sP6Y?LcVO<@?*);Utay9C5Bwr1Zl zj5Oz<`Ah(G!rqHOx?OfimnAkh%^K?5p%N&}Aa~>(Y~`QP-4kB_SNGwO3JiM`RG%Yw zY*Qf+FobX9AF%KA4&J!6V;vw=;1p_BVb1&jKR=hY3-bc_L5Hq9eYp7%o+%~|oQd{W zE@Pk(@jNvpeIJPleA;7&Pjk7^cru^B_2QQd+~h`z|IB1@zHW2Gw|^*bN*QHfGN1nw zlZh9&5GaG^oBD9*TlcbsQ$5_;VZLHq7|JkBQi| zlC%UPv$!&8P1+=>P?cuCc-HAM@Wc~Ib?8A5eZgVx{OU^CMQSR|{Ui_z-FC2lSMn}a z_CimL7}R6^_gOv>8QE3=F7}VtH&`xWd#>ET2mAF?2(CN_jhcA)UCCm@MI2_rI7S0UxNcYH_N~72CTC%Z4@crX zfAqS45-;$*sK4!bl5LJVMUc25@b)l+U?W;@O3qDnb_|vFS9K-?V4e)~sMwD;3BqpG zwROCfuCId3X1P7ZO7s-4$CW1qFi6tZ9e+LpPTT8i+;}3$j|6P~=w?iF$-f#`097mb zCYiqE&^9&BF?3EzvHAJXx}%*ed5=JRzv$A}@d$$QQ(@dBm6-|D&E z`w>DPjp)>4L#}8WxlnEMo0deux@|y)ly~AbWjD9^%@stcL|@h*`m0j;f+&?^j32km zrXF@JJUqeD${lIu1>v*fZ{Q?Dl)JzKDjLwmIjH(Lr6?rl1{wd;mhof3`F^6bx@FoQ zO1|3D{T)LxHo6`-cv2R#Dv&9Yxm}iOD{zD;Dr zTNZ)IAPYUl^@FRq?Oe$zB7N7a`C!yztuNE{T5me>S}3UYi!)GX!~*i-VU9E;$U{-U zwT<L1YFt z*>){J4x(yMB&dB)ciA&spG4uBZ3YIASe`xw`uD8Xk)bD4N6!WN#x zFZ0=$N^fU4LU0r+`WzcE3eZlpZ0?ibUPKOdd7Sz|!(FIhC^PAS3~z}fW>+6z>wAtx z7rj1WUHOKUcZHUKLf@jELC<1-1VzjsifNZaAULVDFSHW_cNbP%lzTR&l$vEy~;6^Gq0Uh%vT*#9ue__e+1#dk5*^ zPoG^BXM=b-cT!@D_9!ZV%-D3_wx9KPH`rE%=(j~aRfMofg<_%TPYtwvD?CVm|@Cwp=z#gefx<56}`p3H1S*=narOPWYa zS3i`NZ)mAbseULgA2J!55L5l~y+O=fZY%<1!1T_E$v+39{_&5q3K&FZapfx3e+^JY zt_zPUv$%N}eQNc8yy;hVxL3Nz%}Z$a`g#eo{=3TgfGnYZvM#~!?|YOBT8C&Nt?PJkfmdpWRIyx!arFF-qunyM{3`(^U#hdt^fI6c*I<=G_T;?Ko~9l>+42W+6C9@-=RBjXB&AHh7MuKy(Z96Hrn;AYv@ zj&ojUum7LkS`Z5-<8h|LUg7I#SB9U3J$Q2L#6h~9um2y{CS!%{f$f1g^!IFLR_AN8 zF=qQ`;?5WctR~Jg%Z<*t!g#O+n4!XGZ;$>wv{(7@6>%`!4Qt@G!H((6a2*~{?IXs2 zd@*z?+$S`|Fm8D#i!RnGwD6Xf9NwQq6AkoV{^2Wb72u5!exYXcQN|&Ra5vZ25t4uS z$)Dcu2SaAvfV-)1CuUtjBgyF_Ani;EMgNd!?~cNYraBFvuOXZTq`fqF6#WtC*PuOp z>#KsZ*cp$_iSdqHK>P9yD55iM&qmJvqfM}T4tp^3sVU|q8oNI|3AwP=r0);VclkeU z!V_deyPPB((C8Ds8x!Mf7byEZua`z!1hEuQt*iFN(SP)w z7?>tt43z!Lg3#$pDGxBf|Knw}NBn1{bd#zRvtRDr2_LjK%2ELx*&?E_@tO4#p-}%d{1r|3+cUmsAZ_%Fo^N0V! zj(=gt|G+Z;!j6Ao$KSHYzp&$9*zxyf@L$;RFYMTfPSEhjzp&$9*zvb^1%>_p7wiyh z*ss;#pt>-7R-JNh$zx)?-5Qi0cJX0&LzI73bnfng^F-4$-}j}W#}e!`aG+B7Ud{)< zogz?7_e=%XB7|OWs*~!+?bS21$v#v4gyZOc9J3o`?qW5t{4Gp_-HWXtJrLfw)7`ft zz(!UsZbi6TL-2qL1`FlhWEL5FrsrqS7qSTw3S{1U`MQMN@eX}D4Z-?}7&`$qG2GdT9kC=Ds zBfD?=XJ@5d&J_BJ5}`T1Km8bWT9mhdg4e~}wZD;MA4Dfq3NC!t+PUrn4uZ+#r>yrL z-nI29wXxC2JUi*bls^P@7Te*eKEJg8PD)q?T`6W|Cu6` z@{~&sCgbGnzdu(Ih#l+Fu=Bo*&cEIF-vw{&=f4#GAz{z{<>8-{`2S4kJlFMKZr1|* z)O7!9jGv_VSH*1^qyLvIA$Sk9J|nQfx)e(WZ4l$$i@vwUbS8Zus*wkMqvvu5$|v{f zWpp{Y&eguZ?woGV{$d^~yXe+j#FC&(o5A(55Lpk$&Z89>hkrA<+jcJ#OlH-yB*shc}jXV-NUO!L^4^Vg&;_f&C@#A*d=Ml`&; z`nm|lP1LkI`DU==6pm3?;S^HErqB}up*ohm!l`B%rc^sKGUFsu^*Py z?j~kA1*`6u7SC_%{JZxxyqMy3gS;IMGoQWv*>}>zz=}o!CL1(fWN%b=&z<_62VV|~r;q2%ROOwEA;><_QtCxP0Zq%;PR%h!<~?@oT;})4;c2WEkr;Q! z3C!J4HSc?IIeIACy4l3J6FTT;R&!ZEo$<&MlTi=<_ORU{H2%sD%JYmzVa)N(MjIWH z(6v0`VXfk+ok(Rz;vn2lu!Fg|W2x_9+?w9+8CdQ83eweSlkPiN&YPLz}Nh5ij&Y_@|=U{3A;l5ZxCng@v7bDkDs( zh?{oi{*`hM?9t4DQ0pERQk+8Q+@V3tsx6`R((P2T=;DyHZSw**{ayp;|K@SNl3)1n zGd$jl1$aesKg5)uCVW2#HshC^kQ|ja&KbR-O-|G%U@aV_uQfOl3p5 zb?v*WT}fr+B=7FFQ$)b-Q(-#cIjzjF%pNtd!6C3$;<*eRPKJ5>OO0b4JI_gm&A!;V zH$NAMauTOpy1im}B$^Z*X@Bj5{E7;HLDtUfquufCB_=SO)hu;CTSjU;>rrM%i%Li; zJ#O9iQ7bhjJ}dg0qnGulX8C+Eu0W3J_Z*G`m<0CDPK{5i%f8;c;r^NqmHsHWUe$7} zSNQ~0MyW)xHu|G~io1*mtj#iHEoU2nZ?j{?(ZtZu`(4L&O8#fsXR%mHLELrC-+Dp} zm@_)<6QQ$<6U>GXIF(v^?biCz0IqQrmyUvA;hy4sCu8xTQBw9~rGX7=D>R3ZfH!?_v#Gl5oLEPYQ)zg3gzSRLJ#i=>uJcazQ_ygo><==KYtQTT7WZB#^&n|jP@R~nTwfhg+qgNj0gok- zyLtD`(=}iq6{BV?AIYK%SY(ICVXUgQ8*bbgTh6ldEFWPpY|oyfKAHKmZ+G_~oPYx5`?E7)8#xne+M&EK>-rXq$9#dx8-8$)&&&0@7vH=>v21GA zs+_xl$v~hawx`%QOH!7f=A#wZu%l3%oHiVNkKfDGDW0Fd)YPgZvOU01c}>+y^<+6K zxiM^%oVQj=S*_(7uy5jJ0oHrin#Bb@PdUbgEqVN~>% zIt!I~o?>;o=_KJXO-m0cyZ=R|3W zS$Zinz2zDbmLj-bxzH2B&=c|y%YqjM65e|4!5*zBmCKFTv_Ml@eOc(_@}-}5ro!jL zLKV-1MAoqhcBQs)vw?bTimCYADXG-DKDKGzc8pm+CH-TG&2s)7(Nl5bjp{(05RD$P zt0YDhNSbQp`1+cV z(0*pwcB#*wV>Jw?WIfER+x10!nHkdTlb~8PEGH~!9L~Gs&<8noHl63PxgAI{baJQO z`^B;!u2QbJt+UI;o!Ch~JW3e_Fg8VpLY#Jnfz(Aol^Z@fA;S_1l4vBhqKWzaL`*CJ zf`OdP%33<0e7vh($>3mvs^xu7FhasPG`c8bWvCL?r6JWZxTr=IDx< ztVXdtpul2kSz+w^iR`f1ecz?L%p50@#308g;N0yioFlO*MbHPG z$dhlrF%ep;Gnia{Z6@;7VlEBD!_y$O4cWf7H!+%w{9fgK&SZ}iGGO#eQP{@nfMFS# zsUs+f4-a(umj=QFngl!tV6?SDo1;xN(wV(CpxlSSc~s{_JCoV_H-6ErES$_#ob}J| z4}iUu&*YhhrnLC+nf-y2K^?2~%FvFhi>G5rO2Hs^Zh0)f`{_w1=u(!ew&JwBM64$? zdD~y5eqt4`nuubhv8)K1N?*^+9tGX1#Fel*C?c>AY|s7typoHn(2p`oO)Z+EWadI@ z6AUjR_5)q{IZdGhj-3!oaSug)ZY*UFu^4{;Vq=lga{TG-5+2qD%ZD05hG`o$C+V-3 zt-DhQR-kk0A0nev=OaLwXult9~pYAZASzKw38{C6em&qc_O zb(?=^=H~Y*tF<`bi%04;!bef|Nasu5+I-7OyVpwHivIgLC#j~;v6g4r#}EBIxJk}8 zOh}1I|HXovPKKQ+xB^cwcQWZ`CNR!CbolR|Kgt2~LlvZObi!f<*sG3jRoZs>y4tjg zLD6?;4|;PZ02)^_usn73W9dp$<+EKZrZ`a^l-pMp#-ca|El%SVr6nH6wA;ebl9)_` zTn-Jgld*|H*W@Iesw{IBawjC`SDG90{L+=$?o(_mmie61h-jCUSCO3wFk|={aQ0?f z!=39RHN(>_Ywmk2R*J`OOu{cIn49NeZ%|z0r#io|1 z=&-(Ex*@im8}(}|KPXeK>|gMce}{>#O}_3yfZFpoV|Dk8ggc?l<_3W(Fx0jmhrT)PrH=+z83M4^7Jx29Y1%6 zzKbOx7D&qdp0&Me4n$U`J-*9XVD(nAK@Opw#I)Wl{={nFTqd|MSiGw+^l03)Rg$Bv zb|M3Gch%JW^HiMeOdLT0S-`{%l7bUYf><;!2LP_o$cFaG3wdo5IyphQbBnnE)8cbH zO*7;DC)<_2GTSbF>0MNi%ONqP@iI#vAI{SJrkyLo8s=3(+p9*=H_ z%v-1u*jVjtY)oiuzv*QrKRujRHZZk1H~U?>fjiQ`(ttp3VhUjKdmg!v0KDLa4Org? zeF78Sbe)aY4yq1jMAH^tO8S{^!c2M7d--Tl)pA2~am!65hl{EHj7$X8)d8AJWAPV} z|8~LSxevr!a5#>zF()c&pf)r#RLRo9Vtis~$o%ba#PFzTVgn!F0pi1Kd%JabY)TD= zhK9J3qM~$C>OboVz3u=vluyG#Ltj;PjoW-3^PB{V9< z9|KC|^WjF|dh435?CKL{D=IF2`U~|I=Y1vvrz8jI`r2p*?hKY%RGRYTkdB z@#=?$GeN<}CrXd|xX+MJRn^pK;)O9M7GMH`RQ=SF+mW{aOa^7ng!RP!n7Fi?E~Ye| zuAy_|_9`j`a6v#V*@V>!Sea}K|6X(0Ke+j8X?8Ia@Z!XWDF#1UjKulR>cAMLcyrOT z_(9c?L+MRI$s71Wyz>BCtHHvT&K4rHdORdcya* zR5_o7(4?N9YD{!kG53-Tv7H5`E!S&?#j+o%9!SZ&BicRJPtd+2Xc2CPX`NqSJK+EA zl&l-tjtj%1Vys(5^T>Q!TS2bnnd2?}z<$yK- z6|lev6!NY}AE_&c?!$hOBl`uD3%`_{Z^wUh){CRVDn;$Vy*Qrh19YeXI&F@dwy(QB1_CzGus~ew!JF2o;nv%j0DP9|EQTFg zdCgkicECKUO7la^{yoEV8)niE0+4Ls=6>L5hVPFO%=(p{3$Mj2XPy#2{b~kXn!=3$ zA(h6BZpE&KaZa^=|86V<=MzS_h-7r~4RZakPwxFpxI1BPcGfB(DvBYLh8O!`px}cu zfg$^9m#X!F$0En3vKK@ImTMB(R>81Iehvd4pa{mv^SqnZwC}wpe)@&4ah+$~pPcf+fH~1!Il(*S=)8XF?w504PF+tSOKr~pFAq$ktuEa#xC0B|G~N8zuU}pI>4?1Y^K7+N z1xLqD7)_R_y%N*mvKGsq|8W4?a+=PaVGGllU{{Ti!YNF_0X@QQUK2Wg^w}U?jrh-; zBr)UOEKBxC(_bY1%iW_xtw_KDFZZZ>J7rE&-lRB*c)mV9io~Vthn$w|?-vYtJdx6Ps3En^<_TKkq=ZE0^Z&&iv z1XjCnox@gp8D3N?K^?Si2QfKCl zT_50)q;zeFux2!Xp!Hdc*}+KM+_3B;atc%>kqK(6-9%jo><-VKf01BC$HYNj*>2Y3 z;jo?#j7ZyOwfsG->b^KDj#u3tl?UZ?VtjD+cAqrw)J0@-D8L~pPh#mZ48NESQyD3_ zv_nkl-z(a%8hprFedJ|8gHs5z(iJt1YjU+;wMaBFEx{L|?W?__T}_WFGotuRV?z}B z;4@R#ezirR%_xawJIwOFRpgim6YQM>P)chCHJ6Aan~7Jrui+FnZ777xB@YU+L$?Eo z28%mWSB*hysYKr$AWiJ-DF35xF|#S zPgmi?Rr!_!q}_T~)FbzJ6QAyOo(27ayPrA7@SE4@z#00o`1E#*E`kafz5RW5((-_hUXhhngHaW#tsq3@1gD(?ugxkj zpvU41zCu99S^pghkru|N0uL^tE6&W;L*kNcu7>k{4G@q0dK!~CXHqEO{M~Dh^4eCG zogRd8&t(;(EP9frQ{IK;f-lZH3OeT&C|Rjxp9Ma$^tg=fr-+r@XOJ^>x$=zd>}!hq z?_zJ7)HdfeX$SSybNM=U!jzLlwR8OtPxMuij`L{B4k|-cTX-RHQrBvAf@dQyT2@qJ zz8EYlvU}rM!O#Wzx2YQMUXG<`R}Q}!TX`vot>1s98mx=gGMx{{_dK%-Q94u^Po-Qs zS367g%QE^PJ#XI>un4_JX{gMSO2mW=^#j}&ONXmVfG72qBe>dtCl{Y%)8p@`9;w33 zGCvb(utQTbK3nYyci*)vu_NLIycq~*YxFTIH&LpLg=FCy?qE9W{l=YS9ji=h0!j~$bi(6-dgb7nTM3B2AE5DBA`i3 zZsrTCZo)9)$;F&=Sj}=LhaLb90}!Du-n?9}8@IQ)#G}cv4W^A zXwO19&yR8>9s$OhT2c954CX6DxwKoH$s*S07d;VoN_`LY%IhrKW zO-QKfJoA%w8@&tyViKCkV-VNo3yu|2gm5!5z^?ep$vEE+rU1urz)ih-O(c#e#1}88 z;@lV7HO|$^;(Kh_0b9^yibt3o)ri5H-0noCzBC-q`W_oA=_h zIv`k=*`FtDu33DLLt^+P;J(W4Jg95e>vce-?Rv-#T#c}3F#|*lt^BS~BTnczQ9$GO@2oM)m_q@gv(UuW zb8t_~2?oJ%VoWdIX;HeR#AVXyDz4j2;{w*hx15nUu7;I&;JrR@apW^CC$k}v99caz zld;r)FKSG7yA~j5;pA+%!=WqlN~UclD`Tv|BoKw=9|$(~exzN+ENo!_-VQEIIJ3~_ z$e(_ZKzq9^`!w#r>unUV9=5R*R&w664@}7UAGG!?pKns&fd*1O(<8ZN{V#Qv$po&M zVyoUyt@BQk2t5B@_4~a%4zO5}!3j2VF_|mcgc@`xwU80tHn5@`^m(8gMI@@?JsS{+ zu<&(};?#`^qA+PtxTYQX5CK}7AA8GotNxYnz}djMH<(S16k_V$1zW5O*w}7#HC#OE z!j8jW;U6G9nc;s_sO%Rv0E=5<6OFm{5w6&#LCBG(pCpgXS} z0wSnFd7`W7K=cRv)<;3~QQis_ZcX|v^Q9yPj-ze2dIqKdr-@}9_aTW9h;k6)7vHBl zc?tA965jh(6%ar&Vc1-e53utr)5&=V>Q+~e6}mEn28@za-vd4Pxh?&r$4@K_mpu#U z|9G3#FV*wd6`{$7y!q6~I0RY+a2adIMK9mahxoitkEWUkq>&*MDB7G{C#N)bZ$gkn zgZggHYvVbtp8SoKd}CZ6yc~t@-b00%x6XBw#Aq&s4A8JiUp2tllZ+$aT|jH+iWKo} zlCEj#0#1}@)-UB49AOG*6&c<1TS%%1$vx8w4v z#{GkEI@xS9{r~6?dG+a-M+;0hCb(}@_mq|-JG-iR?31} zj;7w+PiBPdcY1Nre&*neP>8eDohn|o0%g1D3qI0^n3{ubON|Ic2q{I6P9%Z77x(bH z$kQyDT%I4*$!!6%d7m4e6A?;u>?|y)7ab$fV7ly~GHPpimPhM*$BCe(WNa>QW3sYxVU92s9D$Bcow=cpM-STRhD2n=x! zyO!n?z5d8ikihxUssfUOp=u8?P6VXdNHeqo9Z|fgHNH(^?mzWxbY^YBR-j3TQ|&zL za5eu5?U)jh`-2I2=OVQ~I(82)Nm;G?=dZp|dzp~8tQ(*cYVK|A#nm5R16Tx)FfnFC z5rB!0ijs;=c3Jv!$4+bn715pH8PCw{J{QdF9_Ou#B&^`)XAq-uaZ@RdR43Bp%=&Y!{ZHTJpSG~rUzJ!jOA{P%L8mJLK|8; zG0b0}K6wUapFf@T{>fH?=1{tr>>Jf$aRuErJHhc%K3aY(L|Y2FqSjTdZ_NT~W4P$yvz>03}+3}uM#)}$f?uxDVA zJrFP0!vW&!CpoCHDdg&$AO`^^pPLkFWxB?*C*my_thoV5ajMp_5R|3Vloeu81e3NX zN#&e;7$;JHJG@%t)W9?0Lt?{CkYjk@76#ErVgVbgWP?@Q-N&sB6cE69DOGOk;Ald zRYr*Ym!Y>i7=6Ymo|fWcF9t4f{P~l3KKoKk8%BqQ6cZ#E8`f1+_2`E4+zHFx?5R&y0?67J|=ZDB;!fJp|9*>DpF|) zSJIW|vD7RH;+ur~!(YcV z1;tR1gJ2d*H$g9-#y%hhp#@Q^&D@2ZH#Vt~_0?G9rjA;VE)iNMNIp`4zH@6rM)-ueWsm=tvqD7UJ^yrb?YZK#Ur?jCz#509PmUzxBi+pgI&XRv+VE>| zL6XDMwAIrzBYyn4L`A&+VN$|*O#w(uzaS-=;8&fXqRQYQfSl(m&2BT3iW1@pKM|As zcJp>FR-)5G7Jq_fU*`y^$$qsakU3}9>pw;}l0E**{{l_4%T617t)Lgiq?_RevCigU zw}@&;$m(a-D+yrZ5nr%Fya67fjj(ee3UjG6C~soYLa*ZRm^_G03Fo-!&n*~Rk^6`v zHt5Q=KB(iMuz`kQPHOAZ{!}*Y^AMNDn~(_Pqo-G|wX!B>};Hll*iq~cMnF<)Jr>Vn8Y++7|}X$pg& zgIg0kc*Z_lcMloi+Q$z*?55Ku~8#zBG5epWg!FOBplisnoeeiHY#-Z3A@3VfCuXY^Rfk?IL7w9 zxfMhHbCW@rV{VsyFH;6h(%?uC{EE^(3!(7U)`)!l%WJwq{cNqzN-Qhxx3le#vj$J9 z+jz4hfbYf5DqyJ;v3(&{Ea_?Bxo2WRbmQKmGd4IJQ|Op%fHQXjDsFu z&Q=7s-&~^oscYJ9K8q;1@C<&C|ADBdz+}4{`w4o{DRkk%#ul5 zE{MguLO-cBcd162e@P2JVWb{PwYViZA%$FC^^t<9DO1)|L=|-Bp%s_&wZQ@#OVw2L zt#Y=~9McH=Ig}5@1SHWk-n-Sp(ZhrRL<;J5k)cSGhRqEDy+s4?9K4oBmklUzA_|3i ziNLE)c2As}0$(#6U!Vc4ZTWsc)!4NZ2X zR*=o#$6}*uJy(}EUjfm94l+5*FXiIc`n@wX@{1cQ73@Bc8_%D}TPXqsdsaQnqUE>% zg9xe7MKdVZh>1y9QWl!jaJ~P00&f-ON;@B9Z=@WOHc*~j_r>F#CL}w}82ZPsLHhv_ zw;dFJ2hs6MmbuosJ1gxFrMYU0F>?3$R+@G1QM1 z{OPl^vpKwzL!Zb|PO`8Umo?J~7u-xwdYIlrN)3)9Gi(wEBix)I&K%_(o`qO%S3(B4 z@d8U2n(ZvGKIJ88N=1J&)OLO87AT*0w5*;a9A_#ZG4~=1DQCO#pb?@pWH6)N`wGF7 z`bi5&3kmVs6glGD0$p=!v@z*L_JlrEEOvbr#ytpF#_F8*6zK!#_SXKg59p zt!otoTgEu0UkIf*lAMzTyH8FX(WGfV#*j}#a zlDsJogWhq0uLG}_!y%4h`NbtH29h}RNDTAVlOuA2ZhdCX?RUs0YWa{V7r;HU#5fHckXKQyUfP2qf9{0;Mw*sB*`M-MJ){)o92LSuw zpr6e|vpVtrxW0KL(34@^c8aX~XA&i445x{BmbLxIs0=?HMd= zjg{f(xBmO)*`2|6H{+D-$-lB3KE{i~XZZ&>DtXy#>7spV(&y6<^4oU(D+rkUiX9Xp z+5WA|vW*hV`8mF^dOB>W+<<<+p+}Dk#SH8!Ei`9()SdKyISGFO zBHTi|PUig^Rw@h1(|fC5tp#!GP_70R+75kwvZHw^#2tS19+z$Jre}N5F1f{0JJ1pRE%MI|b`ULDCO`e98v*|% zk9Bo++$I>*gY=|-Jg|cJn}2p8{dczalR_&v%iMZ@KJ4rPH+%5u;dl}HUwT+br`uEw zaL*V2a?eeklD|g_O0xd9+;iHCl8OotneG0JMHEg;4^l3O)+6Jx@meROe53^*!D9#qSA} z^Z%{*yPv3p0N|&8GZBb`OSyXb!gvkS7fwptP9+T_%QpX|c(k^f-v|JH|B6e0#9ug? zyomRAJlg+nxvM3^FR)i2<&%~CA}gY@u-Zksd8F|+?iJ(|YVj8UhPBv}WM`8K;$Y6& z6C+kXb@TLj0ST8s`p>46-X`4Q1v-z96R#+A?o1jJ6ydIf|F{OEI~9i3;K5uaLK^K9C0PIbpwAumsxBAk9tp7|<#KgvkG?V^L z4bS481Gyowof!^KCb@CbKM?3W9S;0XDsCmO#_7aubSLP!>3@*|l2${O!g|W|Xj&10 zx?kTFq{-fpOk`|?u@@2mg{@biXVHB1S3v#?% zmGHpd3+xXeNXmdL9J;<&cI!EOF6ET+gPB1H9rH`@estvtrh|K7#6<8GK@b&`#b!#;Vc%}(aNj|N(sW|{I$h)spi6jf9kcsKsd2;Fe@&L-_T(+}ANe>g z+hznUtCYrX%in+%T)3756n9J2?)M(uT4|jDSapH$4oIcSR*06bqLsVl3fS7g> zr}*8&sksMh#_I=`YzwO`aJPF~X#Uh5#1mdz5S>fRA8D9QIc^pD2bymM2YXY^lD+Y( z!gLYz@(s!e5;o_`-41ocs-O$7(et; zUX!PwvI+gC7U1`8maBk-oF;DIodKlv^h~U=fHSdN&QzNTx9r!KnAr8EC2VdBfw`(2 zSWG9iZCHZ;-KbO+5qwP0myG^%V2q?3AyfEtludH`-)G&w4`l1>6D0$uF=p=s&#=3i zzIqpn+yxA~F8pj>WkXj#Mn7yajlUk~X^bbToI|Y@mBqHdj=8ginl^x?5V%6mAQVIl z-3$zMzON5Jj4yyx#b)c_1c#e|F0M38R=8Jf<^eQpsceG}KV(=^_gUtF>UP>u`82Qr zx7tBCU(hIGiTTJ3qqwnky6A#Gk>!! z#3$b$oc~zF-{*&(djdRV3um4v?q#c2O|!z3%$AKUKaoi{>dc9#Vtx#Lu`NaZ8G%*~Ymc%Hc1z-wPbg(;kTd5g9s$Rl*1EIZ{z?MhU_SX^& zq5IsBwNY-s&IIjc1h!Ud97c=cy7fsK2dRC{mNe9Ilu;tT09i`}nhkZeAY9?+^?=?EdmPy!Po8*%=pHuF=G61S@N%ksm2wg{bVYv5bTNagpyvCwF*xWn(4C#Z zI2S+fmFU=tc5y)+&54aSx?DxS%!6TqMEM0(dRi~uy!x^{;HqviE0$kyLwx^@eM>oc z)TRED4Rjz|<$%E9YJgfCX6fB@+-_st2rII}6v!@LQF954(Ny*4v?Qb!(k19y>G%Xpe~(R4&>)(akp89c-8@I$n8VjO7%}Z8bVP(pZy2 zW5-H=B2({4lzs1W8`fgxsGm2vzWa)ThI*=Ycy%`4aDr2GFIWNF6^-@VdG8y0(D-X# zKW=wt_45=2p+3k~Qoa8O`TBYSH66tbk!&)<4IPWz;&s0QDh$Fj(W$MRE@*_VzS^PM zQQX<~dz62>9c;I**1>bg-tL#@;abKoSYXRNx~T`PLa3v)j!}KH+4JlO$nm#?*|(+* zROvNyiC2ai4@-f%tY$x~>>w(2f0Q%6zqv!a%Dm0tcz+QVF~Y0BMJk}RBo^;+uv5gf zjA$HyKHm`3n^V)bnA#D7YNolHglv(UK8W%Y^=sSNZY7*+$)+yQUr~wZubZQur07@T z$@c2+-I}1A6Jd$*+j7ky@T*$uc(P9xfZ+3gM)Ze!>Lp?dZ(j^|X8Pkba8~cc1E47P zwXP*dU7l+BdnBgZJg1MZjy~RaEzBdd-@wtTK0!PF)gyR(RV20tsN-%a1ec{|C>!@=wE&Ib z-KcWmP}rg;$>}RYa1f=Tk8_jGRf)sRk9D|qWS1Vm9o)bX_4D<6lPnA#lFvj)mbF05 zl)d<3^2N81K9%ryB!?3x26QZ_<1Lc7+pgkrM-^@O9UTshyidlvSOU#~xRB9yVhNVx zKs=pv_)7l!grr;B{G_3wkItl59`b0(xA7`=y~0)6e0P|ZT;K2T=r-VgSnx2nDE->; zyQU7fL{U}pUyRXMz@M3H6RNT7(vEohz%qDdH*K*S15Yzd0=D_w4R!Bgzw-@FtF{HL z>$p94j3(^PIGI|A(TVF3 zJhp0CDd`Y1dy-hs=U;2$b8_;;+j_eE>GLqg_)N3#Qh4U$3J%h+uI*khWF)@SPnDrm zA(Juw`JE>TcCywCOxK=tADtL3jfhTHZzKy_E{eKhc0KFUM|zU06OmriBNMI}u8TW* zNANifLxTV#1c3Hb?Q?D2Y`kSYbV_ zt6@+{zo^he8S2HQ072g^;!J*x91wRK!euMTF=wwUE>M_ELq!dnrSV zS1WkCwN2}+1{h%x8G`#91Oj~A-GM%~!v$M`oKKTklv1orwKHW1(LhOm!6xvFylEBd zqI6QJ6=OGnlbh17=FSo@u$ z5mv8DWr`0sL**)?66)VuvKpdvF(FnPS;;Ei7*n2@h?dx)(LBl*-s&0Y&R7zWHI#h2 z#>z=!mc#dB|9ABfBMqA+cDv(YO{Iv=4r^a8xFv0oVUhCluLtv02)GyH;jh(>2MsTV z=dCUn<-_O^w{>r2%EW-y(NTM?fEnYF-9aJzttX}3Q2vuoRpL+V5Qwy+Lupl>oOsev zs4`{}zgYsx%ja~M4lxm7=3yKwMEO2$pYb?kt}P=7N1+eb!4^Ex8+3xxOs*9XmZFHs zK7~V3{$q$7O%-})$I?+wxE4O=w$^mumUZ*13U?tFJ{ZaK)(Y>hTV@F2U+#Zk`_XO< z?rsMAL;uJ9JuzAMd!lJs=fZVy-*JhN{KmnL@t&xC^LTzwio2vTet_7~veX$-VXqd? zt~snFpRK(!RPXH$>j4@HBZ^S0xZ(L`;Pz@`3%W5En}aNQ4S-}fWH|cQeiwTYQ&#>v zhe2@-ZwwKSx+=c{p_5^Zm=)8%^4&RFJEkQr*aF7~K` z>lmLar3$#cb^P|;A8@pdqLH-x^8GQaww%`8P`Wt9W`3I=Ar_Y(k*tNrl9PP(z{4O@ z(AEis_lO)J)cL*rnXuy2)taoLqA>%YqtNTb~5Km=Z&PJp3r0{%~m4Mz36}w?! z!NGdqh~9bQYt3IyW?&D(~8+w-*rVe&muDKym`TKilF`c zcrdeQ97jzszy18@k%CTtRS5&HH3xJb5ivVya@b4M_o>ODDf4cju8!_&hnpvOZ4NI=Dr~7WbfJ~3bkoBFiDvP%VlUpu+BL+MXcwwgv%FFYm!_&s*j??X zNxisH_izZN#y9@x4Wn$Psn}wLzs+jvfX#v0uB<7tN163n4^hHNDf*|yhDh?9>4qF; z^7vt(nMESUAn!5R#qDT3rh81`KFQxd-G}^a)U&jxUG(nEc37gvGPXAC4%=qBhV^g~ zWsBdcA4X~Ci?|7mJ99D++&h#CrTFt;o$+@fOrrDnVxKnr*UP83JXJq=**{nk8IO7^NSG*n!KgrWck@2bgq9F3Nte6h@!n}o1>CZ7|*U>Q$AkjS(c?& zaBiQC0H+A%hq(BP0(pPQQ)Zua>_(&eFE`Ms$UI@tpz$KP#l`Koy=WA_s&N6y^m3Zy z4wHYi>(YbL6}aulJ&X3~G!gf_57NOGYNDfW@;zdoE;5u*uXLDPE+JPIdgu!z2J*bu zyA>*cOv;@>Eb9S2eat<)0u@uP@$F?ho!>`nAmykg_bGJa^UJ<#uG$;2RqO%s-n67s z+Dj;1H4+ZSxo6(128a#Oe#PWQKYo?5^Try6j4b7qj?;d>(y94VKlag%=oiXZS#w!V z8`kf+4Sha7fn6*Rmx-WZ56lVSg_V}VDjhk8KB^uq^N_weF84{W^!r&>U$_>2qt7AE z*KZ*+S6(Is^C0%Db`+vp8ylO3evtZ7tF;=I%5<-L((_&Z`%Hz+g;qFA8cHFIRNwBCzW> zXv(5OCc$U9-kgaxz<-Yse+3`4sC+21s^MwNZeJ7n?o&E}HLRdD_MvXjiiX%&JDDQ1 zc5~?S=LrLY)_DVG=A%x2XXm0q9lB?Jec{no&{1D9P!ST3Rk{`@a`rUz5MiK9>}7QR zd52l&b`G|~+>>k9e6>uBNIe>{U4CLWL+lv~;Uku*~A+^*C|iDD>V!bNJ+8N`4k>59w6BuYL_b=K-_E(+xXJ@ zj2D@L3>4Lgo@M(p7;Fc;#C%}p5^aC-?{}-cl$<5p^sL#uZ2kNCvS)IVr9bRSB${Gp zj_V#Xx#*oKgJaEWZuRtGpwU7<2_ol!>~CW=Hsra@NFgkqRsvdQt6dZbtQIE{7b7yh9zRI}e z^(xRl?+$rQH~7M9ww;bZR-uOkiWg;e?-~D#kEY#`!%C=ecsKm&MclRLOic&(gEf*~ zxiWJi)zmiQ6rELX*eh5(-${9+_;G7I!LGzYth32_nD2bEMp|lN!&lYef?A8t7wV;E zgs_ZSht&=3{%fB@U-sJ#qU!ImT%)!W<(n!iH0v%uEOwNAXB{Tmdn{ATev=1Gyg&4-Qo9-tjM-HH4&jeNjzOkt?^NDl^zsiyG;otCF+2XLq>AmRx|k z{OQ<`r#1F_cF2oKUMdBV68yMq5AD*Eb~4v-lpyk!%hPizC(oD(5-xW^AdFUU1dZ)< z1eU0ObxlW;*8zcz@g=>5t$rlKZ8u!sb-T87)P`4ic<=GBty%%cSd%+Ucde_b&v_@& zHES#%1w}V5bM$)!3yNr&eye&|pLF8UysE$pLtu+Brfrq#f`b){2k)H}Xl(wzdM^1< z)8S^UHO83uPxCr;gY@LUkRFiBolpJ!UkZN&ELc-&^x*mhkdChT6o}MoaOqYkn%*(p z1*42Ssodrwy)05d+Ub$tCi12zVCMJ;&B3wlltxexhkgL&+rXW#GYA$L;p;7yXzkD~ zxul-itu#s`{=^Woi=V)uojDo2kiHFO{2VNnI?p{)uX$k&iv;&OR}F)#1q*liu37D} z@FQC(Rj=EX1YG`X0DPRQck|6}wQq}5l$uqt31bz#`&J75Sk`~cTB$rttS>a1j8}wX zkoHY&mLjV)gaOP%s6IH|gRXHzB}SIRc4Ka>kX9f0#G5gbd|(U;-wn0kj!GODT9vN2 z$Uk9-T$0e#UmlNs>qd?r?zA7wJSc`7#qzd=W1koO)OMWK;lE#d@NTlLte~ElG&aTU zRaPSX=!VBQws=Fqmv3-eOptifJik6o3mZxhz}&K2Vz2Y4Lz6d2BlkIjMZ1;vNv!ek zEpNt{DCTcsbLAKv&s=uKXWpp>*x2Nesl+u2;dO|in}jEJ>@)XJ!3J~E+k(+;{nYwH zc9n?jp~O)xXM+MQRak@O;`(#KfZm?A7RTi!1YKv-#O}o4P{@hihjdS;ssoQ(II#NLMYWW*^JS>+aSGbi>K^aw`hfNvLC}q*`r~H&Y$dzrh|T4owpoIC5(Gu zQ7#r@o?H=E`FPV5e2exVwzt)yl97QgkvGHswxXNLO@}javx_FT{>Pl{kDLr!V-h*o+cl+m9M`(|lJnxfBiR&1tvER)~Y|*AjzC z$r9+-%z1J&_xP8w5W_1->64Z!RV5y>+zd+41If4 zF<9c9eaw>sYHut(EK)1kREY&T#mYz^fN-0$ODLK0JDTcFk@&JvOKh-X_LGGG!(Pr` zMBa&Czkt|J_th5A(IwqZ-4*9*p2x-Kc(L~m_9J^`;}8TyY()!prKqPkmki$!GPRN- z#<=NLR?FQnf!`dSt+Y8AO<>f^g9}no2e~vE7?h5+fTy_}<|oU|epxfeUF1T?hV$O9 zZ(mQW%+30+_H8tB!bQ-YYT1LGFvlVR-r1^Zaf0H64|o3B@|g4Z<;3FJMqDiaep%@m zd|v-E8998$*NT5frU0@V7JgbRtw+_jPLrw0X!o3{12FwX4Fw29sum!iZ0Dcfn~NS< zeFsK{I3u;rZ>y6`EclfrdS9`;JN+>k#m+hu7Y96J2=eJU2CTi2gO zua!KTzJ{+*F$6G*9rLWaR@Xn&rz#nA+^XHR2!Iup7D=hZdzK2pryKedV#S24gAkAaDpiRhwI+cnlkpJCRiKHAMk-7y{JncmR!rh{GKdg!#P_RG(Tl4-7FD93D?Q$6qF@N__K^u>xX zoBoMx9g@2J?&=gSUS-Bb0aWQ!YQW5*618Und{qmP6>U|BX1-YobA?vqPi5o{QR>#? z$1$40J2FB-kA4|*nI7|#buZrDpgC*ruydC_$2hFXO1yKIweTCQK7rXeGHm5sCUa>7Dfd);k+)e zR@)J%L2Ea&{I!ws%`ivrdPRib$i=h6Jl9_R1zeQA#O10)Yi%-rn#ZZ7NV1S{OQ`IK zZ~Ng=D^)8U>(E z6@e5K)qp%z9J^M=ZvbwON4K#LNKqPid>GC!yFPzC;>>PhU45g~h%(jBmss6mh4}9z zUxn}_j()|N-tq+Pj^_~77QIw*BA~ChCW}^$L=UFJFL(1Q_+-@&>8~KkIz)r6cve4( zD*Q)sv4*+4<{d>*`w%|@12I8?Rm+YHB=n+dunn=uGJIGZLO%UYRC&^;w=EC(q=Rh> z)_jc3qZ-Ql%ofikbgal=`}EOL;;OyAD+5h_ZZ<>T#-GU8*^D_jw2F)mk5dr#oU;p#f}+Y54sOJPlO zhu=-zMS%6kWy_OrTz;)T-ESPX$C{kS99TlI#+-e!4}G)YTr%1<4E)XIv3~4WqVQMo zM@L)_6l`zD&+)nawCbfOK}P0uoR2!6Y>E;GfPntald2y@nsV%X%cWCMyjy$8YZE_3 z45(Mc0TjwRdzQ%VZ$#_M?f1T$ghkpq|NHvt`TJ*gcJ6PG;*+0iJ;Nh;ndF?a3BBO0 z9py+$A_@+t)1CS_P z1$N4}iJJSWm3p+J7K0a&zQ*{?-BVtVX#IZ7sycs8gh8V&l7a}H?$>OE&Wqw|KnCkhmZ0qKiuodtGnnsuKikt;xI$=XO!QLdAZNPPE0z(`{%2_^E>X-jhhQ;y0l|@&us_mFVLQ`#d^U7{F~$1 z_~9{t%iiprH=8eBT=iJ_{z=ETI%*0`pRKZ=&!^v8uT9gwi!h%u2obvK&%spev1Nj~#o_u5AS-mEaR3Mz8R!E8 zALgw(uHg$hPEDx3J_mN(f#mBe{wv~U8&rsY?B&Uziha?fw2F9xy%F&4m<2ty^UbLZ z9;_*ZLJ>$-a{T6;bf>oh;!7_igg1dcDUS#)P>0`a0U6`IAx|9|!cuR-ruuNxPj2#K z*md?i=f^)J1PAiXH*V&vjKrDERP?nW67K5Dm#NrAX?BSEnRQE-3xK28ZK*QQ#njad zn-bv?T`LwI0t83tCY&|%r=uYCWK`%kcYuKj+X?Qc1Q-c6SkUg&kF_VKDStaqTG$I& zo`{sY(E%wudb-mcv4Kk?(gcO8>k}gYpGY>lG3>w=4I*-riuBXJZ!rIAg*P6Y5K(b$ z?sTjEx==k?y6I4~*Bih2AIGh=>BPjyi;2wI+|TF{#&iGnCTQ9G9Lucm`j!e1&M51h zE3DV>FI1)M7hIV|Brs)~RWYwjJB~OrSa13C6XGc(a15+B^AZCP(z-IM4ZJPTh(ZZ)ZV#iJ`_Xb<&?p>eysp9~m0JC2UVVjoz^`1kt&LM-HFD zx(&&v9x$Viq{y#;{qoym9#L((wD2~>WE#5uka~@yY#*G{<7=;Q9FbSL;hKLi zkFp#p%IMdK)gE7S1Qj{0VgNzFMMG#|mQoop(igzxPmxjhn_u zl#U-r)&X$JU|q7=F|u>N5uj0NmAZB*b-la1QLpSc3w8D^}CTyuoLC#Q262b5UDr%I`K=D2>C89`;xm=X)C{!SKuIcFqDGvNu~G zXi^ROgGq~R1C?e?L~}!*Rd2&kAj`gaLbAo;$4-N=uxJsR)E+cn=1yor5yzF7piCz%Wl z-NeMRKHA^rj1QRUif6MrT&N-JDs~R^(xG<9>~>R_{?YZ-ZF`;l%A>#X8f(pc) zu@*y*U-#U`Jaa@$zBE_})r~c;Zm1LKc_szSd)F7vQNsL5d7B$4tjFma%M)e5M~Pe{VXvZ~fe`Y=pCc9L}YV?m<6X`$S~P@COrg z#@`NvPODCVxf06%MHBt&=X}VkCXbs`L$HoiQbyhMDD2WZ-)#|@4iFt-t0N(D-EZ$^!Nsh;(Mza{bqC!gNKj@n%}7IoCN&rs zU`E`3OfKdO#=YAfg^=t6WvXI%bsfx-E?*2gT-PEXfg_I)V`n-TNFthmo)eBOo{+}% zz8OW{`2;jBB61>*4g1+ywD`?enP^^0_K_L+reuVFyJ3*?!q?^!^cnMg`Hva4_r&CC zg9Y*o1&bfE8#IChw$j!&X;I+p`Me6B~j>QpUffw z83OAJk&A#9`lVHDC;x)_If*ECKlpw|Yopvo^+2Ve1ZT#==Zu2O&Di0*59s)i(Se@r zwc+;R_zmkLf;dpI?^%$&SmTu?u^ZcU~eDLkr4@daMsR7xN0 z4)~BYuVIEZuoz_EN?iE?FGVLAermF5QB`rUqsXh>*XDg2B%t!)w|zczNR=TeVA5#% zE;qoa`#3VA;gb&Su*{q)+(i~{J85#!PmN>({n3=xyZ|y;5$mhT`y5fUG9aC{^E|J8 z3At-9Y)4uP$hvAt@#_5*NP(Mcn)A2)h25e>VLNn~W92d5LQ=JONC{;2+Fz+p%q#pJ z;(OZ5cr1SdV}E&CNg6z96!FP57e5OoGGSh2KNlU~SuHaTuMU(rOx9TUtPaESA*k_q zCt}b*{%t&tCt1Y3(9#=ZJuaf(#`86~`nRDfxVhL@MKp>GP?a^d)y3zVe|m#7ieH2s z6h+Xz*^48`;nDjcjMWOD4w~vGIP+4H8xIWYeg|ok zn2X>G;D7(N27vu=fv$M=r5X!q5}F&F*Xd*6_*xl@>n40>`=2$4^PiVUW|VO$Go7_n zvD$rF4H5UmYEK6g`!yJTl-aaAdh$rUEaN#rfM&hK&}_${CY|f3$+$&5= zssGt?`m=c6a*S_!F~LS;6B!F?1a`@veNW!O0o?g@(+xQ++*%cCR#2A8Zt~L$y=pz@ z1XQAka3KuHc#7h=GzyY*;5PAD@21ZIMTfIl8_=EJKGN9bpsb+RdQbyqH1kg{JRlwT z7DX!}irV!4xsaHq&8<`EfMUC~jj#|;bWLt4@C>$xlFl3_^pl@$kfwi#C;fU^in8;@ z;YQ=h1)E+yt~8*5EJTyy*P6`Iui!;FTX79#}07HXM0v_EFQI z>w~f##+(xSQr2p@xGIcq5wj7jLrRaME&EoWrH+2b`aAyPMHum`P;jt`X(u$1`BMA! z=gg7o1N$Jr1F1gG~vxD%ZVUF0;xOczzOx1#7SC4nTG z<0PWV=JwREQhB|@N-7T7q~qiBT8iorS_@rD%-GqT5S5%`$6GU$$UxN=JxoLouXcnv zN?<ltRC*6@J=g+#S$+biuFX+6Cm58Jr+Iz4BaVS!s?Oa2ZWxLh0SLr~ZvLYlOmD$Q zvLXZf)Q+OspFWYb*Xd%_5gfMl5_9*DG7hdZ9P0I#YS7vu6V9qfX)gitE`8pcv-^=P zl9_;lG*A0@YoKy(wY$`G`0d5#-O|L*Kx9$fF@Qb~eL4QXavG3Bfgx5Xdry=?g8oh0 z(0Y@$u)GzO$t9a`OSRe%ZJq7P?1oNj+Q2NSk@7YpEEU3 z`=au*vvjN zy$TrrMsY740Nj6d2e^YG`wSi!(_aoLD$=bi951(4o1ieeG6=WTggLZ@T^BoXCJ30R zdVKec|2qaF-9#N%nd5@4%^!?075_3q2PqkeOf}N8@(FTS^dgIq;wyTO4r02`rRMUs z6?>g84ng7bJhg>5au|{0bsYxX$&M6lvjGWW_YKJE`=Yo!jl$1RU7n6X0o#d5UYjnh zHZuHZkeIYfcB!P^XK^t6zEtQIK7=c%SHmTTOIagO3el4=xMB8-yKwI#vVL(HZmVdO z&Kh<`q(_D5$=9z|cA5oG`xw4Lfy}7?;1wyr#5D7?49a#}vvfOtsT`7QHC%6j7@A8Y z7?oo0cG&uc-hrZjj)?h|@sZC~nw_iMWgV%mkAQP&8=)4=3`@epA9u0Pz#@e>iX1zZk{ZzsXroN}l`BZgOwE}=J+@EC@touUr|B{E2;0fvy!|+G@q5xqh)szE57@vw4Yx5gT15a5~W>bDJ zqWPN_?<@8zRQE&fc3tOjjAuJ&(Kb1kU7?mrG`j=5DezQpjU%%)aiE8-C_Kb6Xx>(lDDCX2+gu)FDKru(&;E@6aW=pf= zI8dzHPUN|8oH;vdb@+WZS|SZU zXbY#@>2XR0XdJ=QUSXJTt%eOi1oVC5cxqQx!!NCdoEbHcNTAnh_3urg`5aH_JU@T& zbv4GkEh$7?iKoDfD!$;oMlyGWtAUS9nbM&bvihPJmZT(e(tV6>beE=oJ9YsBB(K*A zCh6*z9?1=xb<(UYgm=4at3TjZLf7iI-1Na*2G5+3>LU1p>+d z&nA6j;Cop=smqYD{$9z2a3QO$)%Uk_(BF<}L z|EzLj5crqGo7VQ};}BCnY5$L|(EpHupmoI7Z9YTP#pAGoc4l#x-Zb}^Te z(4Zwf=LaYP2Yu!j9LWJjJXT<0N@1o&H(e*A518VY3ucvTq(Ki>@=QCT@?^s)3Z-oF zqs$g>0D?*C_}LRyBObUt43~Y8%p7MMlGOpCi;SMzZj`&DMz-{*OG3aCsB4F|7rKW) zFJvZ|NS^!p^36=lq`RTqKBxuS)^0uo*O|Nnfts`!rU0vEl+ZBuuqJ(s#0hTA0toJ= zUtv7VGZ@;Z4KQ=6tC;qb4|)^(N=@bq;~{?$4{2p+aUU!LP=A(6o=wJy1eiy}w4a$w z7ivB^=JhX$7p41J$=r{FF+bx_&8+e|L5He-$XZDZiD33#79=tV9j-i7_(ZRDU^jBW z9qb6lB?$MAl0?E_2urn%SmHLVL-^z&?=~QhYbyQ zN14c)1si4)C(_6UL9{da#~xycdFh2(Ec4J*@EW%Bo88v0+Uv9LljC)GrNgZ@-_!mBa+)_Hgh?So(IeU-pCB@QDj)sQJ%P1 z*6xkY$M>LyzE8N+bB0fjOH9E)yU_NCdIR3Y8zLuWYpKX{wgX=%{w`pyfC46eV)GK$ z|4RWg^9U==&VyMB;=r%?YCA2l^kZ;};lU1=;`QLxy|)~7#tkxhb<hqQ-1oPL<4(IHb5Jb+J z>x|@N&#>Oi%rq;%8!+W-kH?XS{E8OWFOjPL{C>DQ8`%CQKS5Pp4hb3Vy)Rkrvghp> zkIRXqdc7E5!+jLtKt!B&fi{&q+5uMKTghEaujO;?15$h_zbdM-vki6RS6Ea0GQN$Y z02WU=0y7k5k#h7lWK5uVlcVWbIVVRqpm((2TRQ-mkV)2{wH}$$G(O+_J%Ior`_TbC zYw5kiPbr5YU?WI4mRaT+@y~$vfLjp~pA{)rX_^`>8Kc7Yh6-#OD4TQD#Rp(c+=wgN z2FE4MI5NOG_%6XMZ|wWe#iGj|Y3_@;swLHQ5^6l+Cc$PO*4>+v33u{!b1Zr|IunXq zGDy!l#W)KC5kcnI_yQfxC~^{tGEX-(M<-hAy84os(ze|FE40%S5n9pdlzxLMzWx`| z^fxUB41)D+r}9qz(TD4aM`J)xSZ&?`wj*1>Zj{7?_+;emU5~p4 zbyWvoIO0#tZIhosxsiwKK7iD;#?AQv_~Hj>iKeQImbvs%io|XVjX^ld@tsN4esaid zHC0#b1%7b|RIvq%qpu~KUin&)Q(iF_1yB@&o-|HWa2Wm4?3_5@fN79761|nm73;mw zKY|F!k4GdU#PFMWW}GhJ2|sEw@B6wZd;P-eNA#%EXl@%lVTIY+#4miIl=o=OuYwsqpi~M93Ns(Z2LET$-vB8WreXD0LY0C(nv8++b-$8Z_ zur@1lypjr!%m)p2>h~VZ{45&+^3H2}^fbMfD>drP2m;!s#`+~bGKo|UMUQBd4$4=U zgqt%480E5$eUg=2ABsjelUm@kKj(dQ1*+_Ebga#!C}uawm>}SjV<-Lu(D+F|d$4BF=+*<6+C^hw)|=U;M|@|)GYEp2^LL}@#5db|R|UuBOwqS>_b(Dgu8yF4 zi=OAku6Buw4bd6)@1Ww$szHtC=v?ZkA~t&m-Mv(nWv@_Sj;*G?s5f7$QX9Q80f_w% zFdr*|zkLY7DW6nK@LSsT7oYS$Ajtb-{MVy&T0EF(g=de91}y*zP2)W!a?Kr}$8_qS z!qU%vI;~ag1xg(zA9S3n0R05_!`pls0fY!79^6CKu9i4%LH&c&d1kytGG_VD0Hu;^ zyAPP!Y$`sB2%QoW*`A6^-n{Vu@f!wHcD0pK?mq!@bj|aCpezp*&Urrj+p2}&LSj|W ziSQJ#N>6dkh*W|O?{EN%dc6Ht{0L#CMJj`RX@HM?9U<=pJvj265|VHH&hUC{8V%LB z*}_4^llT3Tg51eGbh^}BVW`p1kKca$J{lk?2ajIUj|#F~lA=cv7K`_0w0#cGu{O*| z3CMU67EOl2B3>2cc{|oWaudZoR&O+*WlrW}4##o1LvJ{VLoX>O)}tf1cr*as)pFh?TlocmG0Wi$t?XF&M98|Ti%&Bd0^WZ7{Mh3TwD>QUlGBkT^bbI zlPFgE;;Dj#sQQd!9v?meiP~Y#sP?SZfF9#7MF3sO8VTbrc$O=5 zKcRo^h184mIFD_cZYYpNb<|5TC8OZK_jBgqTVJ;J<2=|k`=FQAqm0{vj}Us*f9iXY`-FD>#`XEP1Y z8w`R5l-2E>{-;3qr)cZl>R0$}vGkZS?NeGMHYOJf>NE2zEewBq>+n-=JxZ(?{D1b= z{wKGeJ|GLVgLu;KPvR8bml&+4B`lA~r-T4bV0QUz;y&jqHER7&Z-6E$qWTgK{y$H# z2#BWEdJNf>$OtW*xhh^~F&>fAW@S+@>nW`MMT5dN5qUwnh#JX_<56x`ZO0!|+mc?h ztW`-iYXroX<&}OWkrHOtB?u4+Ofi$!|BZbclYbL`8$2n5I_+rt&!1nii*Uk7G(uDY z5RDlw?2M!+tR=SP`x@>q-MM_$)G^VE_McjSsJQCanz(#gBZ(-u=ARCRDe_dZ6;b1n zOp0^+fkN!AZQA?X0uGA`IOCTE|%=c7(-SxsCBXAW7|7S&#FYUHBN3agej^T+=ihU2E~SfO-jz*99Mq;dcy)q$QYXZep*R3f%k=DRL&yVq^gDw4L2F{P)&7>BDH2C z#UAM$&bBiOPnWt@MAwgg$A9mrqJ%R$F9cbl01IGtJ%KJf9th0=0C5~BOENs8CkYmc38qB|Qof56UY>#h-dOezm) z(R}&IhI8JY+pL!kB|J#sf98|n-4FHY@zjE$<2*(xb&i)f_*4axlp%cEy5^^2)pjXp zGq>-I%fJ_vW1UnQqiaG6e6u(|G|AV~cxMCtz(V3O4wOy(dlNs|kwzL1Jjufi5(~(M zM5qkA*4_K8)`z#g1xF!(J(v*u@Y`3NdyuXW<2GmV@mElbYk@(s6sLmCWjb|j`m7&E z6~aLrMje?Gt@z9FmdaMQB&~JtPr&^w{_e{?zVn575%-1eiL6zz^)22LZn)~3#sGHm z98_mdG}#*6G`>m|r!8qM#Lv2Rh)zSkz=~DO`V?sjbv>@%ZtT+1P$HdkXF;bu@*?xz znYbmUS9K7Q$~k&^XTXj?fk$M13b;yobvn*S8=b7-s)Yb;6C(=Sc-`pP zx$zuM=c&IQM#LGGt; zQ}0lNuux;RVZF*SRKA+d9l;3!>Uo{KQt5A$cVhmw4e{>t4}2H=U>nt(rNm3xS)Zn% zx$ISY6lKC%q-~y_`7IKeq|01`Ge-~g!kQy%E*6pX}LExE7^|FS(kYC z^Xej5PDdU&q#Wp6zP_0GtTXPb%Li)`kTe3@ONrOuNF^MTXP3cRkBsTFvI*}hbimh$ z7)iT`3hy-2NKdI^=>jKvHT!&-#;>YvgcD=ZOIJVak0CG&ycZ9h77NYpO-`QD``SQ0 zE4-`pLVT?0+8j;EW?hx}Wuos4CqSfXKar+4WO5lV#3hPFRP>EA$_FXB#ZY%5d-s`) zr5*Rw?I(@+JHl=LY?xhyZKoy!eRoiMr;O9I<0DtZ=C=bYdob{h2k&z6QY^ODEO6}U z53u!Y20e@@1)51baFJIQ6|NrE-Q$2V(aLu6n$y_$`g$6iG7k)--q7o4_}9Yl?=KLd zB5rg@tryugCEuZMc3xWpL=ZhW8TqMF6<(u(Pm?2F|3WgM2&qNs=)`#Yed*&zOV(PJ z&pmXxM5DULp$tXTgrm+5d;dxTntY8CMe5^f_~#$*5NRO_d|km?aZUU4{%~t{?x97P zFS06q{2(yj1x&m%cPF(UJ?Mi4RCw-=`o4e%G@#e^%H8A9Ob6L13GBr@Q|UK%?Ar<8 z9m9copZ!esCOh-Z1AFhN?=W&ZmbVK#Ky+8>&7)K&r{JAhrkIZ*|8zJOV( z{=4Cyhy1Q|am~s1bgsbf_#&dBhdr9UQy#_@`69IU=D;)DsoTbnMQ^G`2%P=&C*t4r zb^<3tS>T{=Gbr^Ncr-ch((*4X<-XlyIwi;H^ZkkG!QiV+DKvfzsE8fF#gMbun?oj8 z>Gz%X-U##MzF8_I{Z#;jXo#B}QgP5BCj6uU&2dZ!{C2MEas`1o47~`vFP_0(clCM9}9;`Pl5=a zrbybpKL}s?LpcAlejbQ7g69RIpO{BF@;t4lzbr504(_)f`X57l$e{pcTRXPhf_ORU z3MCaQtPbA`PSwhtas}Q+2JQ>`XSE2y9q>T%)?W*e|AG2WPJ{^gdFI2pjNm8aLc2;I z_>qUuRv!nK0&5flhDm+ZKAOZp|7t~>CJR1H2p$p;5gF24{4RMkIO)8I>=i6xkNuj3 zfW9DFL;#dxHJElN#hosWCJP2cHm=y*I;?=S643(#xaw?eu=uPiSV$ecMfi;a@glxn zRgMTLgp?SWgXLjtBh85Aio*cqVJN|no13EdmA`s=6GZ$kO)3k)kBX|<4Y_F%Wgq64-Z`|R*G-@w~N)k7vaD!tynWVSk2ks1VVu6 zdR4(c5r6;)ptD>R%LCdUY7h{Y`)tEl!qJ|77nQ7*?t)UUZt7&YJR>n_j7}L|KbVoU_o*5i^H)0C(3j8aK3%} zogMhe&4qk5Gh1-)BBQ1467s$X-34EnP}7niWYTp*nQ4&!*Nxuw0|7Muoa-*OV^zP% z2z>OXM>sHa8;|P{@NegNP(e?%&GRymt6xwxCa;-q$v&>0XeCF8NiBYvdllpR;k_>f z$NLNe`lya9!?02J9;{#{g`jGBog_n~`s{L7QlGE%gDbp znp?BUv=E2SSbH54&*fOtDz31}T}(>&CudY5AyMkAacPj$q0sMs1lhm*h}AcoWpcm1 zas&%w8h6spgp7K}3U@Axh7R#W7d{G`Y=EN|AO(cHJZf@ojvhpLHQ4&6#M(Ij}Nd_*`^%l#&Y(@4{@Q!R_tUNP~RXE{N@Zev#5hBaKB(9n&;O& z2+`DG*HT~oV6eaU`^^g-PYU^>I`kY*+CY9AgZgzWH^NRQFhV7!%p{HzcLp3Yqc_qd z#9+dSxc>f;A{~oyA0NlPPmQ0Vq6m_paIHq;gW|`r+xcYSviBUeQsOw16(BMpmdNP-g1APT9B+#dy zp`+#c^0rjTxBKnBa@`*_{z4X2h|*o#O^7r-{lX3u7}H|ArU{JE?d>Pudy?GJay+>P z6PxyK-Q?gvzDtG;)kb%=vK9@8nh$Us^+&-TeNZ0__me=Gu~=z`6d=SV$EodcN#c-! zUhd~*1JJ3#Wwf1pOQ<}ptaZ(6kx<7Mh7q~U5j()N;`e07TcPSPbsD-l{PcrAreyX) zG`Qzn?oAq~?1u)h1LZ-fTQCDBE;-uQ>z_MPq0Z4L{gbx7$%dbsZ0x`vy=sjGfW8+a~{B~C9WNCnbxFI+m_ zPzJTW*{b!zsBkhJeTOVVGxa7{l1|~@p0uybKG}bnSNsEZuZzbd?i4Sc{1F!UdBVTa z!{fq$O!wQyi9vVjt5el_dI&*MiE?1ib^Te&-W)`x`!O%kL{~&J@paazVd}Rhw^s6B z7f!8Jb5IVzSb?Ey-r88nO8HrB*_lNFj2SSF=0VixeEOBxJuWb2_LLzXAWRWTVVBO4 zAIvI;{@!b-U_2L+m^*cKS%$W+Oo zRm=`n54|vO2=)~Z3-;u{E&0{Pa$?4X-+j2+-R58WbS;&h5Kos?cdwL%Sx5>pB zYvgz`5886{#_A(H`IWxy=<;hQG)#cxNl3Bb5p~IP21osA5!cXk6xSIrd@mkezPZPR zsf+=7g6qP#+Nb<8+tRA25};GS@SsM%yAT`_Aco)0ThW_(SnQi+MO{Sfs>=f`-W{tIx{7Kn>S)0CGua7&^{e*@ zP2&$rY}Q?yNa(MKPmO5ep!!nw-BdL>R6U*#FeKS2$o9)M!|X7wj4@glHl2@m#?;^?&}%|f=k z1!fYqTsjf)f`VNaRdIGelgM<}){WH# z4US>%69iKZjLHSK7&25#G0lUt~VSDFy??ToEx*yvkAAc_DAXvK4==5cp`n(Q+qDRIvI3alYRosxV_##ZP>Y7yt$-c4xN}{DH7u< zL&*U1fK=2p>0cP-7EC$j%YA-93kD#`XNDQ&UE(#SmdLgz$5Kwi&oQYXQC9)#keB>+=4)07}p8v_N&XP*{j1(VO8)3#e}-5T=~ zSkqkurP~!Yo5?)%5o(E7sYr;Vl9db3X?Is2!bYl;kRqhWv^%V6#uqg60S-_qznKoN zFUK?{4+cjcNmI}6?SaO-OdCjhB2Q=GsS7=O!bZM)Nh$B%T*d6{TS7U2uyifF-M)F{ z0JiNav-&(TA~<>b#&(0?Hsh>ZvI^07W!PIyhbNBVsF?>e+*HqI8^YS9DcVoni*U#O z-DP&(#Pfd5uQLDc4(2E!5zjPZ{h#dVWqe9XPf?3*YF{dTn|mu#D$TUuU@u_9EK{Qe zuB3=Z;xB|R>#(15E!ie&RA(JyE;`SB^0xB@#ycvw*qz25sn5PvBFLxS8^4k5NH&nr z4+A-GfG8Lz+iS+t-107j33HTN2&Qwg!!2CP&pqS^b#TeC5)w5}*#o?HV(gF+9Yd-D zy+#6mN|NS~{r2WEf43Ci&ZWP-?54@wt$u`*XbeojjGpB=>{42TJ{Z46GOq=|!8f1+ zCMtn>$u;0XcfBUmj5X=MzSA7rWok>FZSP5v&(hZCo*4xlX4NJOo?sK6LWfyc~SSa4YtL#Xv!>k7js`JmY9f z#i4YlXtztRyj*?*=^6=e+&>TF6kmZ7yLdL?Y8a;^QlFWr+fszDUP=`wQ zv@`okD4YB$w0>AURGvP9%(jk)=3#lI!A3v~(v=;>C!v1@6{zyPFeG#$M8ntg34=;e z0kPW4Zid?~1JH9Qd#QM7j@XgTjm}8fanqc`^0Ok{^GSDV2kxgBa`!Wq=IJDYZU!7_ zo7SrEC{HN#oni)k=tWnZs_zKuy6(D8XS&uBZPym~Y)|kK>KsHj&J@*#aWUISinomc zEP=3+)!>8V+xMxV3N=Y-K{DH@_lCU=h|c5H&?e#1KG z^Vo^!B6+q=X>>UKZ+&ERfmyKN|5IRABKpR0;?=iXPG113A*L-^Y0~cD(_@HUAi$)x zNs!NsU$t$EdL%A7dPo^1j*G!W<>UWxnhKNl?wkJg3w+~&!maxy?>`6Bmd1(taGqx6 z7pf|v1@2TfuViIKBa}ZTJ*55g#5>z!-EIF7y$FlmhvE$Y=H@e}Tn!a5{juWL*ph4t zW3Plh?_@55X?n-Bwc8da+j-agS64vV<|gQEHfql{w5)-}I)8K5XPNQLc4f1TW?UlQ z{K5b_yw9x(!P*%fwik{cndE@!y{~4QsYq#weHMvLUltZj!3}0PE&dgaiz?AeK+98} z6j4{gex0Tap217D3o`*sJVAy5y=|Yp=x`3PCVDs(D#NhAK&Va0lFbHFm;Br=!3VT% z*p}r~2kV41I2}(k-&xptzUm3L1^fbent>wd^$FB`Vqpt&XJshPsxh;ET6}l{FRT6R zS>GB#!hwU~PMbCz8Bx9*d+bL~{Wi2G6?`e@S5MeEoKAI1*FVE|i0s#J$G`4;FMLYK zN3lKt;JfOTN5ZpWsjs0TYlH%Wh!z20*l%g(a{L{cYPjv zNNpBXdXvYr1`@;?F=vEp)&^cFfxE!Vjv`JXqI3_ALgi3^{+x^M#qH$EsCg(D&?(J^ z(Oq*H=Oe^OtaBAi6h-R-JX@5r9k;i3kJTONFE{=4qZXiAK%bdmJwvB~(~GCitE4OO z1o?|PIX3K4XfllxdBLOk4wa$bzKrxMYiE1#zvNGm1E-xfnUhBVCf6#D>Q>1mD~_YI zy{@%PnpcwRaIX;$7Dvqm)#k=V1k`m;27Xh~XEX4|H41y!%=hlC{&08_kn$W~L-mn< zk5T?KXTxbc7yhQ>)Az}n8AE9NFaP#-@>(&hk#q-%0aLY$5T|;^m+D{C{`DG8BZcqH zMja63KH6JOb;Yza6OYn7XA3=6YYna0J)v=CCyjLWV=$e`7=3;@?HRyPr&Zor znH?-*LJ4aD_+G0A(Xke&tB(ic@y>_=Esonpe8_6K|hI?m;pIR;G*9C!)9w?(wDqkXxM!x$7n_=UaB`-%%-^ zVwy7HUoGPZIYgyg`4)~?{wXSDj=l6yly;_z%HP*Pkg0P+lrI(R`Uro7Bse%iZKxH% z5r2MOsG3c;p7fEprp0mMN4fV&u|HfA@~TVB&ADOlO7l>r%3IpmeG43pTXs;0E|LBa z*V@yn!D#rXJLS-Aev;j#Mx9o4B8jVd{Y8bNadMSf8Ig+)fNT{HdzL@U3?T02d8!O$ z*NF~yhh7b3dpTfNaD>PQJbGF4&po#n$D74`s0I73(~-NVW{?n_fTw$Od|rS;Nxp;= z(x{DY#<}Ly5;5H!z7Y@dmB24+SX8&AA+KSL#;Q#p3Wsg6=hpQba zh5YN|iV2ODkwm|XQ@+diNc8#F8#@i0m>}m!!CP*;9p22Z0rloifpypg(PeZ!RgEs5!NNo-Ko%kb?bPh7Bj4 z%Y}idF*@?bx=9O|IN}f=zrD3wEZ=*}o)&NE0ej2&(VQ*g&Jrq!js7mqBfjDVIJOwkPC%BLi>kKSom^C}Ek(G#D{QMuGJfA>Tx7%n&=R-ZsT=?jX0 z2#T|O8N(OC2}=6;mNR`AdfO`3tFaa0Z=Onu*uD2qPS#`3Z$4Ot(va!=NcGcA*-*|w!1?jyZvz{YN;rduepT=DL69&I?z>T9 z`g>BN#5tUuK~V(PxHgY2w-xw_s_t^N^KpjDjVQDvq257Cb1{VP&h@2iKB$8A2{dmA zzEY4RpLqiY7I{5|zVJ10+%S1)Nv>7kBkYQbZM%ZEb51codEsb5&2L z%a*~LX`YHYXC5C@3sc64LYe_(BQaAN?*2*C)@Mxygp#g+M}9jroDrS{g_qn(B*93bPYL&&n9OFViftc) zOVS$QJPbC;c;k?+gyK^z+13A9!R%S4Qh`-kO5Qx-D`;EJlYk8efkbhsP=zL%!RZXPb0=_*^>Z(*@ zeWaEHaGPTLgUPvI@_T4XJWxjMvcgd_#j}QUF8sNYyGkFQv2wxX`;n-}&>JtcPO!STuTlarFs<*&v&^H!!@(F80F>7$H&?q)=+)d1`f+w6G zuOBimFc~~=4&0;Pqu#sVcW&Y&hyB`@5GvXDo7I-KX=`i^m)g{` zFdeSsc^@KhV$A{Kj`AvS)5>dW2PYsgf^b+8`upJ4^C(_1H(lHDx#9;pJOOYqIM$`k zjla0>51m;)^1Kk~w=~2Ro+YO^fnA!c79fYKH0pgtsY+FDKe5o4kpujt*z~`$MhQFx;wU$do=Bu?eHxkfuf%NbL-3?+dbZ1XrkKv@T4^ zHc2+=Dd&E*q=Pv7DL-|o0C`}X45g1SBswUw5aS{rn#z5N7sS%NE$S5B=f-EQ76RT} z)qv`zkX(>%zQZk$;c5BYn}5WJUBB&$MmPxEow$hD&ZaaCG4~{g z{RHG}qWU_(F{VjwG-Sf5`l=&y!ojPpRRJ!vC_MLFE+>>`u?eldXEsq-^<;QDt-=gD zNFx-BYILZrJ`j_N^{0^Xk3_c+4%iTtI*n=RXNvuA?mV^`d_dZw6|58sfy-#tOs{wZ zi)0Z3qr7WulRbcW?#re|^^P4dQ^x{plPqM7$gNLEMJ5JzLO-kGg(S7qiRL)JwqQ-0 z{p*1Q!m}`>Ai9(33Z2AfXa%tgjXDLeJv5Ogw=uAAboq`i^(y1J08T;01p(@ehAP{o zvnKeimv(GtXBf|aFCr3mOOM+9Pz%4adS4&n5Bhc{VU^KgPqSq;mEB}gHsW>NvAb}S zuBt8=@4@s?g0L%2=!Nt4QFmMhUQ5U6ZSD1%8?NHDixjZWi|K(-?D$F2%CEun$r=f9 z`H-TrLolPMT?L6jKkbEh@*Yif2sUS~jlW0rKzy~%7hKwzf z@ba<~&@MhP-6{2f?Y{P(oYH=%N*W#ECD_ zJRok7j`I@zFpCP{%jncSec8!qhg>uI=_M2)87HfMOvz;cam6xXL_LY|=Zu?UecG-< zXRneq4IT`GpdhohYjlw6%AnRbRl2iD>0c)$G=v-_v9a6JKb-duE`=~wB(hH`{iuM^ zHMp$Fz-$5bdO$~MTssWyA{Ir^UfH#p+OHWvV}*DcGqik@&}WuV1CEI-B#v9&Lzc2B z(?E^z3^c({icPJJJeIQKT8BvJD~ML54a|UUyW6r)0ku(1BBjge<S}*v`Y5ud{uU{yMKsN1A9pPe|578(gOo;?{xK^nQ^TBOn^5(sDK)%%-yWo)t zK3&q45Mw|$Vl4Y~_v8CJMH2KKaJTr--1}Hc;5I`)WLO*0AMkudq=4I?o;?Kj$}Arf z@_+G{%?4<9-#j?)nfw`nqz1?{@T_^84?teMZ6Zz@RiIUKh%QZ)l&;UbT`8^BGW_vm zt+L9}g)dV}=VA99OlRg-L#(HBn2&NJMI!$?=6~e(Bp=2CZbVtO_}>3_2M!fdUm3f= zE{avdEpNbOZwuV1o+B-4u~Jc=Wm*=j>Yj3N)Ek9fg)CfRAP>X^_`A(`)8GpC$_I(K z+I$R@Yk{czXIVxYq>oCw(<%iLVfss+x27Nt=_gmWumQ&&4;Lb8u`sSas~DXlJgi#p z4=>&3vcf2X zf$%KkW@b_?2g@F4XZtSGzDkA^-<#x9AE;nJQcQvQ0O%|8FDE*aH3|WWuXn|divOJK z!tSw=JO&uepxyuO(XqYtVZ3-QW@0Ei7{qaB_{{AJ>)j`uXt+h>3`2f@OQONW*HxJs zi+0S}8FoicLm?VQ#IBUmiR7wiz)dwCM1~>`g5L?$4l75Kp%Z8^Fd#A3LQMu1s5t4_ zn0Y%xTmCi?p;RPaXJ&!lK45*D{rTa{HTVTRv0IGw-w)@Q;66umNj4=6!G^rUXG3dx+lUN@a zg5^*&40Z+7I1>+}VJ)luw0J=RNDF=EG1`7B@+4BmTLU@Tbf0_fuLPNmaDxLHFFRpiq?}Eg?P9B3W_npClYWj4mVlJFh1vQo*;m&}Gh)Y!5ofs2kEST3vnY)H z&QRw^q_Aa`4ble<=@9czkd+-$V0*Q&<~Y@hUtn)mD7a-vb!_2)ik&ChiJLcR*~vZx zqb}UVe zL!W+BVS__t)$n>pvwYNGZlCRKzl?(VIDY4i9E-{4BD~)wS$-ch`Oi#m8d7nGv?#|< z96JZv!Mx<1U#&%ne@@9FC8dZ=YT%tIC_jbsaulK_sdb#)_jA<8!H+rwx{4|p63!-& zUUdg$oV#_KVDylP3?z(ItUf(+e_B>?Z2H;xF96k9s)xX1!;a~>$#61vucmJ>39ihIS-I=ZhjII?E0cY z5K`I76AVa>M4Jbz4zF*m_irmt8P$%#Aj)nJ&KMkOc+%2^SCIF7`0MePfUh{kcY1_5X4dZdTvdXP49I~caM;@*^j>reyEiBh3|6)ptt$)_-PM^K$rQ-w6SCN z4HeeLd`NR<^~xzGEyKLiJ6&Q2od+DZ7NU+OXZ0BLY0WTaw%k~}W=N?^kT~YtH6+05 zue`B3L|V+Pt->1KyK;vMMY(JXvxVM5ok!JF9Cv-?!UIxe?jE?U`Fsu&xO$H!hqZ4` z;9}H<&MmA`h!GojRN1rFNOJYEkIkPWIXM@`PAWiu{$FzNeTeHOo&WZY;^K=s?0+WK zCu--BExjPzc{UOc28@)viFnW3mvm3B^0_g9#qFMj{GxUeha543(l(=Gkv)r>u{!MW#~l%4AxB=H#%&PDx5xjDlYuP zz3!D#%i{Ik>%|F}r7`oZg0+77+lpCa_~>=d6;9_7`V!5s@YR1N=l(}8A+v$K5Qa=U zc0S7rG!K-T^q__=7qDK*g=oARnTgL}FPW^O=A#P}&jvvyoC$~F*@I1D)JM3wkYUFr zaA$B|E}XGnfC%6Hfh8JC+{aY&)1$_DI&JL2?Ar}<`yC^D_Uz=wEu zZw+qq+>b$f7i!N+*)BVBlLEX=sb#^<6Rh+GO)vSF5u z=@)N??MkOnMYFntqj0u1n-$TsD%)%AL}u$%f?GsLx#HRqtI3h=3Yp~LG>-)CZP1h9 zX$@Agc#&ylc#B!}+{4~$mb5sf!^=z#%R>)SQ|zbp--1YztKWJPvCF|gg~sacZkJ)! z!tvO!vNi={CBc*m3Qq=$ls6wPFLv?F6f8W{`e^OxBxFLG@`n8adVz}BbDS$ttoMWa zpXG_n2$82t^zRhDeXqnH9}k;wx#C&p&iU})IVw6BvwGj8vPB~EZZAFU;(O8u)25^0Q&A-Jdn$~&5 z&HRGBZqQDf{%^5*EKHMIEFXYBf9Ts2STr#)OCJvsH&CK|E(;k#+)}di>u8Dea}TQL z(Jl9Ua`nB-Kfm+K2j^!8fC_{!oi3q0(x2aq=0L*=*%m}FVD%@Ve*N%CktSEI*V;@T z-HHBus#D2}gW&1xzui}T4~F@|sX7y5I1gO1?bT8L^=UsJ@`)EAZof~x6IvquWQ#^Y zG`#RRYA?sJe@(dm_LdS&QlNs=QuR~ne;?;RYekOp9O9V$d%63Q6Q|G;7X#A}9|Wzt ztGN>GZhmfy>>&@WO7K>JY82TN$wSx%wXDFyUrQnG@G#;|c^ zozt{F(M;E2X) z5mLr_Yx`1j6#XWzy>?O&mwTUJ`e%)X{=|PJKm@pHmZLhx|J&yT?!m+UyPn_h01*5y zeSYP-|1$Mo`uwHOADssD#^5I-{pFv({PUN8eu~4-4}b0ZpXK5&eg4wtf1@}4^3PxX z`O7~)&CSmbfBmsP%f(;%{H4$TMsNJ(pTGR`mw$emo1Y*4KljJ%Pt9h@Ct27e$>wLu zCiJQ#v~DRTw9cD3w_j-~8E6;UFshnaVak-BZjnz~YAfP9Mt%To02xPofUE!2?rpMf z;aw!u9n)H}OR0J_r}^<&FnW}-o|t&0;svkd7Q-`)2mG{Go?i@b8NS; zy8zzPsF^~lje}0SJZ=rGdYL5pneu#MD`+#LyPOa0#xBGz{1F#_<(#G$T~V_q>^IpU z=d9iHEZ4jD0Ti=y(ZP;v*#v$DJVv}koR*T49H<5&>hbQ35NEVMj&8uN+_P&{QT)pH zXt@)`r;HlXx4&7}rQ?ua^4uT$8g&vcoa6E?7K6gYw!!CKXZAoLsLsmfj3YJ7GRqxs z-{o9=3{~8WU}NMA`|_4ST@qPVmtMj~@$%|q%E5Z-NVG{-Cm|ANzLA5GImcG2e#Gxf zOxlGU>>Eee%DR6t=gtq&8qR#E7E@OW8X?GtDJvzkI$S@5qYTabZ=ooMI1)--s~_92 zLs^*oAuA|`nH+O^a7g~-wz1>zqEDtgQ>4fS`uIMwn%QH!ID0Tys`}^TzVd+cEv(f= z;m0+2#^{q_yPSP@Qyh)1)Tr902dOmtgCWX?aQdJJ{cS(A2?n{kavm2_o!_$oHDG(8 z_}+53czt!)oWusFnFlTVt|`(G0;&|g%j>V%420d`{ZT6QWK?Lsk4KOyM1@T;@S5zL z^D|OzEq5L z5mKn}!Y$jwkm#?nx4eBWeCRhxBsPTb*!0-HB!}8@J3qPxqg^OeNa*%n5HqU1W>Lhhj?PF_OG_{Xmv(LRNNCq7Y}vD zAbN)-cwY6_G?Ih;pOR@$GrseV^R`$WphJJ$s83IYsJ6!C-%`*DMW4V- z0EH9mb+icT7S*k8cxzvF5^BfZ&okn`@suV~L3X-2^vVgeG$cczBRSUH+ZrKgzfZ&B zglWB^vnvh?5!~blyw%C9(kc$^h1yQR{6nY~6td;nFU?Z!4@lR0wiSQW0w{AApW!xq z)sRXrg_iLDC%fPHxqC-Abf|Nj8ob2(^b`iB5-Ioeo96jRmnz%4^v&pt@Nh)Y(7V)0 zv5kx#J;9;4fog-iB`+zvtXb3k61`ZH}mNf2BR3gBR zGOOna+>Om~#i?W#FWkKCHtaC)|JDvS;>qxe7V3H3Po(L_V&mPUH-V)6 zn@94>pW~CzTnh!4=;N625p*^d%6-rX0nQh;s#LU#5>f@oQK7+I-tADL6mrVn&XGX^ z2RW=~Pu?*?2?p*x-rxUBg7GQTGXz4C zU(R8x4K4R!okn9WRfU+%2*S`V3L8fV2)4h(YTu(>&Y_sq%h~Cg(QcqX&Otd|=n44- zv_9$IWBGe5J59!4Y56NHzj}~A+?Kye?5}P4|Eq1$=@3y>;awUSacIrcFFHez@431c zCmy-sb|pAx7hCs^6w|4!)K=ksE~Z;uEOk;ICFA_T*E@|Vfs@d@#3BY+%262KD^0Vy zB^yN0V$!fX(q`iIY(~^3qar{O4!(GNbr0aK7_5|$7NM>}Cy5E5a=Pb#&SOCO&iJW= z_q&Thhry_4+gY@coddh)OBzz$i?Cg~_ZIH6Eet8PxsIh5orr_&;w48B`MXd+6SxtB zpTgFj>~fY*$}*xp1+K)P=jkl2X6lUrTu*6&bM??_G?>+Gq@VIEAc+v}X)mS$3o~6a zp{*|uCK{eMm|0A5v=7k=x*cF4Q5LEO{mp~`5@X8GvH@N1S#6i9Wj9AM+T`_pcxKqV zEc(I(>}@<g-so5w^=r?pWmPXUk$TAQpL4y(eu(w+VM zNYc9QhRaJVVn!vqrUyEd*?`=!pWjd9RVYBj!+sl}xuBJU}(;GA>MT^ei-!weXTs!066Mm|{ zJRciR6LT)5QBa0BWYV04dv(kA$lT$2ri*(EDm8LCwZnW4Yx6k|AfTjEsc-jJr|GwR zxOmv`fKkC*Wl$wackarN7t&HG(S2@pZVaZ<)Z*VwLI4DDMbEQ3FR6% zPx2Hm4m^q7ik>5QWhBU`c?b0)2^w%Mmjs(0ffkUD>4wz3XqG zsXog1X~9?3GSYbElUIOQ_pLF}D6~2{niP}7!SNyu_r3yr>^Q1TvNwmHu<|d4jjILS z)($l-{(5Hm)2(u$rnT5ExWgff!#u(?Ii$hY*3c)7oU3Vp3qu(nvk_wQ6LS|FXAgFa z8=52|=zHP9N@p*rYm@57+klmVK)$XZ?TG+;8n6Ogn?{BW&!IUQ*epOmW0TT)E0V2v z=&HcPV>K_Ieo9$+wa(O%gwee~L$O=xX&1^A+7uWl-z>YA^|mWh%H#WdbRO8(mui#V ze=J*xNMOC1e`5Mf-fY5Kzz{h!8fDyvdK=koFt=nfitqlwQQ)3*x)j4^rD0^wWIT+- zG|I5PHEhoCpkoW#F>goJ40)ZQY_r>ZKX{DS=*XFkF4neX9Dp>&gm4O}yPYOR4mg!wZ$<~f75Iwz*Lrq)%YDk;W#^i)jq-Hi(i1cI5k zZ1rzxO*~1RJ-^otdd3Tt_a-EUb1& zYSq;k-{F^4Mthr?`FSaG+UwOG`?T$?Ia4TFSTs!i$;X^ZlFM;Dtc)mXMK@>0P2!>< zL)2TupCPYN65MR_-gKN#N^!F^o)5CwhZy?B>4#Bch869_IUC_?-0ipR15-zayjprm z6;-!pD>Id;1qvJ7-_97VZFw&ZFNsmVk^8W{McvD~T9D{BWShPDX~V{_Xj;-3kKyWV z`U1VJ)rrN$r!Rx?jBjbQrp|~7ppv<_M`kyUart$9_HxYOAg{VrWsuaW%&TWx!J4(k z=dfICGgUf>rC@wWJ%Y1nJd=&`f7) z+0n1>#x_;KHh);l^k{_6=e0R`o9c?PwaG-;lsMbu?RxKNg$Oaze4`^#>S0<9!*lCR z58~Wz38uvk&-sm|SSc&3)Ql1gky-&C+?jto!F_H#d){fX}E6E ztkr*|ixiKlebGMxZP-IdReX0q7=?(QY8Q4T18RHErnE-y2&0{YMlfQiEz3ym+n;md zo6Q@Gv~3eZ&|>Hv=D3v{Hx~`-o<|7Hf>T9Iv5h4ZL*E7{7qcHEm@`|)bPo&8m6NCy zt&U2JW`bGw>k=zoDYwSQ_OrNWyM8<7;$FXDeyJ|>jeEU^LK@f4x>Dk8&Df^wvz^IP z@)&$qHscs3;D=EqX1uLN-1Yvgsx=Ka&h24N=53Iek+`Kq_tDA;1~+%n$LC zI!)cOz3fS&EYG4g-Z~1tqzXU7OI6qB6_kW?kxS7ysXUJ;gl}+mGhq3!J;z>bv30}# zP2Ugp6zi2$WYOM(8>9}7`kNt@yL9Fj8m5YEC92kzsJCscs@#mPEHPz07W6CaFph9A zXwEvphT6zpPfl=LR^WH9$gS|7rJ}Y|v0BUKVvmqctR_=rk}q#Gu-k59Xh^};@`?)N z_gi+>Xk4Tw+_GzNc(_O%Wx2jGGEJ)DI95A6>4^Q@U_)!BV!@i=G-)^4q&0!Qap7t= zaZP&GuK3WZZ%!L3nwZ$sV5NYKob)aQBE@|EV(+J8$$Kc}92r+PXI{-zv~n7+4q8jP-nOP$i7-|wE}BlJ?zr1x zv0z%>*mp!uspCzQo3NrOcd}miO#j5BpW_IY#u8E0bpz()4vO{dwO~R*#66q8ZJM7x z))dFOr0vJ5x>{su*dv=S9qcH{|88w2jw)h`)HSMZ?M{K?SSx9(+^#c+XKu|D-s$By zPoT-wHSr})!Fiy;(PpMxEz$abpkG2wpX2aLjrvn<7N*7e+r!>AA!oN;OMDF9W0pFu zH6(N;_b(Tj#h~<$CtLLD@(NTQbgi2AOW>_iH8m}kjjC$2Cs-P@zj70VLQ*Are$Vhz ziSUK@3}?8GiAOb@D)Q}LcwR@R6LpOctLk8$*NopHU-FgSiH9RHlu_xq6@eMUbCmj1 zT2X+wF#yvkUb&__Y}qt$n2)7fJS|-AdM!P{;BWlYz8KrZ)=}-H7+SlCBBONP2;Oo% zd-oV!BQ@sq*1@$Q%g;JccW~s$m6#6M1}sr1=hMncZ0~?6^u$UFoP}KbNX` zCe4B(ii2u<*;4Ruld)oE?qIK#_h;58TRtRycyjjZ`h#vW5lVuxbKFV!qmvg6sIl4_ z1n(|*WO*%kmiAm+pJSy8W8!o$n^#WsA!G5)48V0!vEB$iiWBc;SUy(6l%dJra~P}A zQpMIZ#9_R1Fe9obrthjow}@boLWf#d-D7({-g{Bks}2|I`)nTeLp&(^%$}U|FDc1I zCwt5`Ez6{e&1_bBoVO1J-PW5U>aL<-q+pNa@)b*ryV&hhl`~{Gys)w|QrI4p)ufxy zT4h-{%yew+VZ!^!dm|@A6zjN>J1C3e=6J~s`%)|8Uv_g%G7ECXQ9Fu<%s+iOVOTDR zjq+Qp7PDtlwCKAu_{O{Nu`;WIm7VY)SE87m?@u{A}vx06Zb zlKSpuWc#k1!N<1T%)8`@HuFWp;)y-4@=ogc>(D)ra<@BEoYp!zIfvu=c*eMa#1-qS z3;_yzz@sRrzwjKUG^-{0T)5n)8K%uF4+uUo?g%*Mi>MaM{$_Ex(`MP+N=}4JuTh5PS5Ji*R>~-^+_k0l%1kO=gYTx30IPeNkyJH7OhXj zZdUM+F8efSkR@}+4lUps7crLmYnw&^rjcE7j?%ETV#MOWc_(f+Gq3f^Ms;$e`b9<2`E>g?SX2g|We5Y7N!2xpO!|UiKF!xwD4I)Wr+a?1x#i zZXdeqyIw(Ks39|y<6=P&%LP6~%x-$>l?uZ1Md^kFkGT>OI#f2U+TDvY3=mKkY$7ZLyk>12?#96;6Q@bI(FBkrwzOFo;3IG3pilkEbl%t$| z`jjH1Lb;|CMd(DXl~r<%l6zb0F30MlDA$xwxsvYxfAr`NZEx?_{d~RN&sXi&vGN$lch@Lj?4-_X^DpL~Ks+z5ELIYidhosSKT~l? zx0$97u$(Besx=P3QDy5yi}Vnh1o#BEiy%ODSmV_97w;&2$p8oGu+2pG8%~vMJ7||@ zVq-l2EiYbWktSf9X{7)rs?Dz9Gj**C%hee=d(i#&K7NG6Cf0Tz(CvCER40w4pFd{r z3+d1J>~~7PJ6a=k1ka4pcoN+n=&Y$n(ax!Q!2ldY3T#DW)zr44rbRASJ68gbZMnC$ zthvu11>lWRWJSV55-#U5_gqw@+T!Nh)7gafy$Z~oCIr7L%Cn8^2y}1BA6NYGB_BL+ zF4XxIVXqeh+@_iO`mWspYywi}rsG8FOn3o^5xoU@F5!_c>q>t2OKtk9OjXaSL%=@m zy?4lhoYC7d+wZ1 zIpLO4cwppfGVKPQyus<&l!ASamNIt9NDSk|ivC#Thhq>EvT_uO@e1}g!Ux}xLL3g} zi1B7s;M%%74NO28KHr`h!R&@FD#cGNf&vLEpHd9)=710KKvfS%o16K){*@JY|4Ow2u5sBV_UG_@RAw z+g|Sw_U)=)ZlIGX*m@BNSN7OvBD30u@~mfHC-AX)>jPvKqcW!m&padW+I{>~!|2Z9 z-BOD7FA?-SvbndDH-5(G-sK3yL`l;~8oO@6?Sa<4=2)jI^~-AsuW#J`F3YbxJt*p{`v4ST|@$uz!7>oJSeugO&D^$Z=4F_Xd#NRCJETGZd5( zR^4(kPOdX~)I#O4EE}K(Zv0q+qqlnjjk-pZC}U3HjocU~>gQZ2`*e6+beUT~9>1i< zJ8!|wG_>I6RKcR}U*0NP5?5pM^8%qi=S3c3S2$y{xndwGU z_3~#6HipJ7KcZr8fbpFC?QDIg(sFxrfB5hqOtPzdnDtTS`C`v7cc8>RN+BDYrMVH^g{T` z+^JUe>N>_yi&tT{d8$N4$>c{hadv=cwx}!h3xxTi<+_w8_(O&P|mDOR0QEq*(TUD`lPf~@wtT+x}4^C5RVi%aO z01#8;^HAEDmK_S&aglGk#y&Om3_haiT!JQ&7ICaJ>FWm6b@z9WKVI*npb*>#lkxL0 zSSL3W5c+uq?lcn2?On7tH`pN*jzk~Ve#~)0wzhPLt~skQ%^GZauVsSm`%^wK9Od+B zY5nkyY%y0XDEs!@82k1ypu4~$HNJ3*xCwv_Vgg}4oB>IceBq>xNd@3Dw3rK;EF{JL z5cnEV{Xci`@`gC)CcDmz3wKI*Q(H#M5E_dV->R!%CXqjkXK=@jNd=0no*lk3T%%EW zHoF1EEf_YLJvpw>;ZQh?h@i@kvv4XbQ#Wa|=B9;R>&9FIx@if%*kWb_*7@ z=6;dGr-tk)S?c=RqQzXP)48Q1@gMj1y%DUpiEqw|F`cGjAbkbBHjokk3t2Q$0STU# zPmxOa7LkqOzQ;~*U_8j~NdGCOj<7bF=#JAV83GG#IkNh(`8XtJ)QN*&9L{x3$$s2% z)koi?L8RJByVSu6k%;7Mt(UiVy6ox1)+gw6P*;RaJe_0q1^Ip}zT>km7uUr>k9mNZfU=l%PvBtIe55MdM`-$P#4f5!aXOVCYjyTO!5W2f z<@vY9wHt$6blsd;2b@BZR^QS`j4%5XD&SRg{&ZD@Ij=v!D7Polro6Om2)`3$_zz4? zlJi_uP@TBrhK$|*A?yT_bBEbb%&clj5t@=W5TKoi{ z%ZnSUOW2r9>ii}@M_=qOLuJb+ejEL0Agn+&9;|=iF`W7SR3HlHyKd@kS z@pwXBj-VoG)hnMF0eguduke6du(W`Voc55|Eh%dIV(<0|FgNYO3IhEFy|S6kTc+4# zw)wY0|7AwOe+K?QaFwR0Rb6*%ux53e`2ZK#YX{%!>nME5f>@M2Z%`}p# zSbjITDzwFD;Qgh@Y_VIg12aUqq%F})A1!M2oGOezmSz{!e7N|qPIgVi?t=aYsF25n z0^U>xu59=w8E$D;zI&Z014r$s@6qqNS{ci}su*K5N(R1tVJ!1cgb%*muy)R>#g|R- zigo?N!`CxofLMDmb)K{#FWK#C=-0bY<5xRoFI+K-E7&L= zeUGIWU+L=qdGAA~^Ct_sa8Zk}6nrpFW8Dc}3s?V7^2bR*9bANArcss#9|V4`d0n|y z)Z(@PCz6IeVn%43Bg#a=s!TfOn3$fPS$~gC0ueY6uQy8}8ZFd=Z-OHi$cX!|qg<7- z4b6tTHd`r@Fj_{1la3E)or8&j()p6j*UMwGxyOqR0${_!dtWTn*WQi-E7bXlrIA+0 zuu;1E425TU&yNYry$(7QHib$#DRTRqh~_2Ey=yUnBDpB;IN0wLvHPz?1xdj6dAi(A zq*@MYG^@Qwu-_uhCy?57#^&Jm%_xo*1?(+KvtGPy3j+XdF!1_O7^4M;Di-Q}Ge0_x znkGc#|GWSDwEX?p6}Co55kC$RXs{QCHCY!*MPKT{$kf zSI8(<{^|nbk?;*sq$JQ`U#1t=80v+?j1{}Rv$88F0Hey4EL4^kG>|v)&p=Qo$-Wx7 zCC;tp=P&FPd*$?k7F@I|pMF{OKu0|&JNGq$-b8A%&OJU=y+}=oRWD_4=lhN1fDwS# zk;HB_z7g-@tyh!2hThK#zBW*=^X#K738xk9L3Q}KkyXK5jwbG+T*)Gpx&WWtPB?-} zhN_$x;)|#MgbnF=&&p>#qN77%w-8~AklpW-ojZ)1*KIfvGzpyX$7bWjo}nIj_-;TN zJh^S8$5V9)w8yNvBPf-?F}NQI>kZu|_B?{ZIKUIQxdN8JUQei&Y}J{;)Gg11U*i_n z%mf&<|39nzM?~LD-F3mJ<_?3K`yKfVRLhQf?kxcn<8!~j+zW#2XfU0oOqJ*0e)rS& zEKylm&FBiK9a;+aBL@{C!Uc);afPOp)vU1(y?Y{kBGvYHWu+4o#ChK#*A^3}!99Jf zXLnr{s7VWbbL>s_{l4LP9n=bDV^XAcbVwFrwuMqKwdJ_NWpsUct`f`Q5z*@jBdB+~ zd$j!ZT#@RpLvnH0Gm^ zQ#6=I21##BQ5nna_IkZz%TE4vG6{MVkn>jmNP%=9_~1#r$A9i#s8rC7T;2)gCHm#g zH@!H}Y`+30r%XQXa6l}8Km*D_N%(nq_7Kk^tKMFF>7A5W9x0qQCuL9J(9HDjmiU-V zi7a&P>M91Z(y4IbxK8e!G~Px?YT1TDEUhS4^Vz>nRJ-WY;rhTjq+v*(%}za)FrFZb zRdEUSq(90_@GfvYusGCmmtQeL9;gT19RJJo3Otx0LEJfRi0-#Vc*jZmj3D;Aw&;=) zk3%U&^n6VQ`RX>wgxFO(807iwS>3iI$k@MMkPAjvi#}K82 zfo1p%`7A8o03v+C-}W5$lfp%SLpW{>zL9MgmL8n?uAv1bnE7y!x4d@7dvMzw?!j9# zVy-AQnR2gm#1ig`q+3BPcZ3Lf=EQ!%>lhPloC9LMJ;ul0(Iah;=n}>Qz20c~MKB}K zUBE@oJQUd^?i>0%ly|7UG}CWvMmX?+*#4#MJMck5rv@&wKSevKE$(pZ&raexbrpe9 zk7;vo?+YuAai9dA$0d=9_h%p_L}}>Bl9fIhBXvF|3j-bxt@2H$Ej4y0cn8fL3M=fj z&!ea(3moH&WbwUlSDj!szq@?nfzo#d(EjaCH-9^>Dy6q#>%@a;DMe{Nn0SPg>7lx3 z5=SnJ$-GLv={mJhe6z6}to#p_VkN{;n!MOCavNJyf6a>BS{BG;c}uv7@9aLGjTIq}9(HcWssso)ZbmThlXW*f@M=;0&wqyj00(MZlRX z#>46rbiV>L=|Ck6V_bBp0kUw)t4^_dnbllF$(6~owFY&ViJito*3-VAlV zJx=UsVU>;~WauTb8K@9152JaQ(^HyPZmHwj+^?P4dvDa8R%jXvJ4NWkz?k!g+GVW> zX8(Jr>)+VVN!iglIF^4gLe=lyy-?})wCbF zzw|mSw)>&NbQpMkBDnWUnb}3^^ZPtnU(W#v6nf*-O>|7r{jqJ|7UAFc87X)Z?Hog8 zq5k0Hb~Nq>*d)F=stD5-%|1d;uKvqP>xpalU|)_{%`#v~S270kc{8o0iPsvpDkTw{ z;eAB`;W8_$rQ&$=kGgoj@9R#}bG-YAQb~(!WxE9pe(gAy8$G^XD!j9r z9oM{TWxjSJzI>8dMvG@!5sA)o>Qade#jr1{7d^rf2e{ubxnA;KnN>rcZRxRn?BP=r z<~>u2_PSEek$inf#A}_P$ zTGH82M2V@NqF^D!(>|3O*T7Pe8`iV8)@fb6%Ku^}sZ_*OX8}%a!*dAkl^8FF+Et&{ z39b9z+%%vDyjeyDEHXqKop#Xm$}TIxb(n)->p z8AmOs7>15aM$MCw#BMQ_VksYbJCu^z{P{~y{yM${gvDuoVfbv>Q`a_oq~9q61#}>? z@Z5!Kn54j+m5U;5T=up&JJ{8Q&~}k(osp0rmoC5DMT#%i_4aYlQt3q|Bwf!WDPzN| z!5;L{`*MiVmr=+jThXU#wvM>{=}cTeKy9#NlC4^=w^FCteh>K5sBj^f@KIR=u&q|`^z@`B1gHFVQXnkt zYnubI(K|@*2g|5Wgu?mfq~&A2M>PsM)n++D)f)#Jp23>DnM~<;f#nC#akb0iIqiPl zKvL3f%_v`PgP|5&-by1OH~Hj-K69sY;-Zvrde?f|4gL*^C%XbSTWYJTNKwDq?XBOl zItTxL66e?z$egzksScasq_?sd#iV8*Y>SEtUM;&2Gy$opS^!Bg32mM@4UMsL$Vu%j zTkJv*TW54S?9lz%ivE7|N)785-@Z22CpCKD!JY?5sJq2W)}XU%VaJy3F<0>55ufON zf6m@pucDqPC)_Qgrhof`Q~9!1)lcWvX{?LYN?hZXG4p=i8hl&2 zwMIxwysm~|$9fvce68r}Nia@v-eAYr6|kL>{=`Cgb0Nn}()g)hKIdMbE$F{Ule7N9 zm`*=vYX`$4rO7fRC5&)`dQ|niM*y$GWQ;tEDM6PFV+hUf1)eE8r9%teRTRK@*=3W; z6&HmBGR~#>e{6Zr;8wGIl4^5DTx0%_dcp5u!-Ild8mOp+RL1@ae(8O<7mF9JrCc%D zdXI|r{XLqE!t^|ebqzgCue4CUX6nTKIMoD@fei-<2aDE<66N*dU2$=9eZ`D!J7^t? zy8wk-=Jo}LE>E*5$$}hW4vQ~IOQl8xIvRsS-af~~r*nbnay-@5sW1u8tH0d`y{0|3 zEwH_r;uOwZ=Ol(>)HW)UK0d-2!ovY(y&v~Q3uBg)JZYQ^gb#1y7 zqe8laqmoK)uAYx)y|xLJ#RizKAk(&V%bvr9*fWnjLv zndb-d&p2z_8qC7zYWl7{bDb&_zf<-4WBZWOW`>h|UR<$WrFro?MqsyM=Hk%!?RUFl zBX0{etnZRc+5LVe9>K$!Zx+=uKUtR7QT)39=8bPrRbGj+#rWPOGL6>w;!OPQz?Idu z5N<%*w6AEicInVx(E(5}Z2i(d8!TV|^0e-#TG_1L2M(@AvPzYzgyl&!D=i zlx?r%6(&e36_2S8hwXCmExOq7-VqOKj{9&ndD4oed!w$N9>iZrjfH89RCYzj>)6+> zx@BuPwJ{Ah$hA*GeSUyA3g)V3adXkdm4yM}qL(6O0;n^sx!9AQsIJSgHrm`!-v*OE z_BcSXdE>r!vMjbVY=?3=Cw**_3&PD**=$-;&+O9CHKG>lZC_Lz_NXxQ#W%gD$cG7Db`n{07!{*Z6o6Gn|9)S@$}WPuun!t-(4 zi(e(*%VazOYQdn5-&O}|A#BwD?|e4pRR6v@>$e+};aTmTWL>@X8I80A7&l_=20Pnc z(5gG%@?0nN67Jh+t7kZ0H7UhO&V)O}3XIBLqj$bSx-OQH(g0GR23omiG+)wMuvpwe zVQ!jcQRgcU1$c0+LhG$n>l~G#{3t;TAhk4hnrM&ZP32M7Jr((P4)>pe`HLA^ryLTq z8c9$O{&pN6HUXR__YRdevyEP-Hs!OWqil+tp?^oNxOZ9CnnK2y`X!G08v5EB+y_;I zC8m$bO@}>Nv@p#T*Cp7L(Gc{}))_0U(jyH@zU*E84S z)*QXmnRSIM!eB5 zsAiOA^Y}eRc-mzZX}c`QVleX41lJJ<2`n|{q~^4teyw%@bbP|j1#3c8 z=KR*b_V`7pI<+=nnM{L^ot7$*pQ=%~8pCc ze0jQ7GK1ch5jXN4mmQ1)BZ28Y#l3n>i3j%y#0Y*Zn{Zm%1goUDZNOI0@y|cen{*R@? z&);MerjCEy5RF~>#6B&$4JOwtzQ$r&pTF7v4*3rUQWh4u>Q*j(De|8G(F=^BRLSFc zu;Ca<=L95@xt&gSSB4bC_(-32_I$g&t=Ar_zbT-xMdL6bFKkqsQ4&77G{{*7`e#y1 zPM?vh%E66&roSn$zxzB**ID(z@}uhw zw_o{lI-I=YZ9p{GRnsrMrIPy@{u+*Cbp})+!_qsq7veC%ea#!1?z)#_q!k;3(xQ`I zZri`qzHx(<8geAnjQSRy+cj0X&%MHb)X2@Ehd5QK-W$pywYo!C1DnvDgGPV+sZuUU z+e*0{oBX&LGXH!Nx=D~Ton^AZ48aT$t4@nhC;y1pnQdTV5rpI?&cTb3@J~DtrK}9g z&9Abv$?!7ABDc{2I+~mm9EJD4-hIYHg8{aww>D$_v@Hnz~vmis;em|5SjAQK> zk0Z!jUjmUlzWD%8<;;X7Vmd1*eYKM_WVXl=(L3Sn=IyWLzrJL)BIZ6}Gwt`S>@(2^ zFO7ytJ8LIWb;jsV%5%L#f$R^As3K=f73Io@nnOv-y8`nzzQFiSNVnaQ5}OP?`EWd^ltjgd`h2Ya&BI?IvvzZ zFNZ^p_T!eeOUx6^pL10fC_$r?=bcZCn%S_`6^7ZR%LR8~p)Gyo6746r{*@(!Z|udv z5S+=Is?d5Vp}y^hliQ1~9fw=4XL2lDHmsDZbqJ2xy}Xc7YN{`i`?YqBTH?uTx!6UU zmDOMECI-X63Pb%K=UjMxFD*vRR=N9pN$KHn`^=%3)wjsTi#8PfpsAh?RouQmzkDnx znF{{%KYsLI|EO|U7fJu#B8fP8O1nGKl%X-c(!mMa!AKZ-y9 z#;1h&psGKpg;#U(re+Ox9{q(=B3>&?>tvYvO$2n)dnQV_dUTcrW8#36B2E4f>74!f zxAbtDRuhgl2MPCkdG2CIHW6sp6)wR`dM<~dQPV0t>pjoAk_+dTX|{oSfBd9j)8Q9& zI$wPe(1Cg$Y!KFlX=zTPy(XFsglvH*@f629{&opp_p`HrS&bD=}vL zh$f9}!ZhKdt2}0SUrp|r_4%qniQ0N4pwcN+v``l3wdUR5u&Ti@DR;3FMtb=^#E{m7 zVLkN!sP#>SRb^;CS-cRRxxU=$nt#p=b;v{VBT6^CacD=yt#}5)<{C! zL_{fLKd8i)zyh!n`B$1O8+NyKp&T9{Ne-~60I*y<13c7AznYUu6hz6O{Wpve*H5+G zz_?TfdkAM)NZlmQ{9Y@0qF)aXm;jeC;r5ohZ@8;Ij^vT&k}bkfG<|r&A6W*@30yF= zx8Z3%r97x%rUQFs;%tb8?BR-~MyivtVJy0TI?Bb0QZQ+!NwiONnh4%fZh+szpL!Yc z&?PB?QAa&yC@Ob-bGiBb%edQ~2qzY^GieFbpCO&0JG)gTVG|uj&MA8&MJ*tCA^{U` z5;6LGgXZ~E)MC!ueTylF;0*)M8GcTRqzF^L$VGxx^NBpeps%)>#LgtWKn<UJ?7O;bP`mI9Ydhgk zLDGUNch8r0Ek%&Pi0*`uA|*m8{XYBh%A+W0#b}pG{#<5Q_ce{>$$8Eu?nfBs)}8ev zr*a>BT3qsD9+Hn}%a`nJT{u{$MQRF+*G?Q$2||o3w6;O;{%R{4BTAk`lJ0M&XKeB6!mG|2zk3T0<`cjq9%rm=sH;sE3_}x@s1orFhoC5DM)618m z^`xAqd0>v=m^~D6BOc&?@j5W`(DqE%XM(3mu?}tz_g}2JvmeYq2ws zHCV9Su-0PUL6CEwvc71$;d73MfA)-UN~d#DKa|6LcdbS0BzwRx_ZZY@jOvl0&$D)f zC+VJ2Ss%Vkf*YOx6q%?#aS8M&xP(*Xc3K8Z~z@s8hf@$Du<=u|n8l3ohojMOkE7dKST zQ_B}>+FG-MCZFiJ^3QpE9+J7YvRqms>Sphg`-+d1%NO6>rAAVtllPSe;Qa(h2m;LB zUujVRFvs#|n#r?;9+tJ)p$2j4J@<(XSnsG_J3pp80%k-f_)}l+2 zTk)5|4u>0Wv|u@ItB1uu7Ih~bIE?dGmcA6_=O?;(Tgqm`trlOF^RXPi+b%lk{3TYD z*-Ijr=vqC%?IwBez2sD(rd*z9=J(Y#Qa?~F`5-mQqqmSG-#vVQP~Khe*6iiflJoG^ zMtvMkQ64h<94~4Yp=S{q+3z9xNr3dMgDlp$tL2E4PnNhW_gq9_1?6nC=gwu9J&c8b z#>6g6YL=oQee-OOeTvNv$(z;_U*89Z4JD2ZNqwmU5#Jbu9$nC zEG2l@_?H`6V{gwn&F6v%f)aCC3Z{Rl*oN=@NUzrOMVgvKyXCj;acDW~vDcmDh(*ju zUK~i*k~=k*%HY`KKW-{8H)8V#!w2IxlG=lsdv+xu1_uOj?c!P5Cc_Us#+r_zMAK8K`z4f|DVs?$WR!dA_-IalGZ_yA}Y$%E($1{uNgKuVb8+ zLth3E-#+V=*NZ_{OMhPaEkMH6-kL^%*Wy~M;+-kW!5(cgLUHu?wPyzfF!o!|J@qA1 zDkXcmu8vGlS5MiOL6^`7ik?<;*nYd)$VS-&ABXsH@lBG;2hVwMLR3qTq-pi2Hivg% zKEOt;?f1G0jetLnD!&nJd--B185}Z!c;U~q1RQm5;ppo%Qlk$|1EV6mq98&c4|y-N z<#))V=6w5l_o(}&50en%sC1QbWb}QeGKMB!Ufj_#e~yNA%i;62x_aM%H#(;k&USP%4ccPum1B|}fS(qCj9x2_7oJXX3|VT{uw*JO z`X-m~SC2TVI;;=K6O)~fkIR+J>itEk@^0&NJ>ZeF00;A0b?;2sjG@+<2%C7o`vx`| z+V`)8iwnE4Z|lyE2!wh5+iy>(nH$R#BT7qV{@T};D2dmf%xl}=kxCzb-5b>Xa`Gmn zDK6Qi%w8Ts#s-m|`KUl-X@<#cBihimwnHjCYLg(>@W|G+vxXiR>@T8?je=zJy3(QP z8Sk!$>&0f%OE}q})b!c;L)_Bc)@#> z`gK8Z5U}mY>!=xpBkby zdIB!Yt_&nCZPodGFYFTcz8&B)`mW!*IeG>LiQ9%qHhIq=ZyE8exs%q)UhLBR?(DkP z*;)zUIs>3kXBz3CG4pkr7fdg zZ{@KNwrJx7&+~8$N!#Ti5cX*+%@^s}6{kVv+}6fpbZ<*Sjp=w)SCCg736qzaoOd67 zu^MheOTKnCl+>8i3i@pc=_g#bYUX_$1n5JojaOEYWoR$Id$-cwF#OzYcv7tE^1So) zUTUeVc+Ns$9tlhIEx>}2_xGY-{}ige-xa><<~niF#Xr}+1%4a6Ugtnp*9uz)?e8t3+=N>j{DtP@O7X`GtOAzIV<+pnHDn z18+8PUO)s)BY13XWX0(4~>15rE*A zZvNnyLe15G=1j!O#efTj%5FChPG$T33*>jMKwl`e7RVhCpPb~&%I_9-nFs+B-b&}& zO8t9LBep+?a?4JM0Nuh^ZFCXJtNX)!N<0A6cebw{Z`p1N$Yo4n@O5UPkjQXX|}RjJ*@$8Vb20`Y2~xca8TKAv#wXV)*!@ zY0}>*?D*=c;C4hy#0;x0^BS=~?k6BsAl+55yYKxX_dBTrlqUJeR$a@RKn!&`3-^Te z>rF2M3P)T0!$-QM%>Q9|-qWf37&IpH{dA;+o#;n$g8mHhjRqe;E4vYV&u3@adSPoS z(T~;)p;cDoRB!Nm0byqR7#!?<1B81rZ#ZH=_)CQEw|o}pOo`g5V<1xnyeDXlimk$a z_~dcmk=ml9p6K2A`p+DyM4-U7EVbMu9tn}x-x_}5#J_F#xhwgGu$XUp7Z4v|ej{C2 zUDAkU{kR{r?>8XaH`AvHUw)CM5sv-q_(taTH+qFdfRiCVJN{?ws}hfYe*6>$(9LTJ ze`g>J(siK(Dqtrjh%Yz2-itVov~Yg-HdB31Rj7)@rw@cZztGL)ogfs)?0jv$MoLP2 ziu%miUYKW-c={91Q*Em0EAcDS(*F1HwMl+S!h|cJ*!{`z`+p}2^@V?@j-k8%ef*hr zC#KNjXZ`H>RayZOKjZlXCj}AXU$^g0@>wq|!tUw+>G7AY5vPA~`=P4uQ%nkqFI3-3 z78L>ZTebB21Fz%U!Zbi_PP#oFw?pXv1)S^u#Ie->9mhmUKj~ckg()YmH9D=*9X9vX zf@tsg6)b@MvJoA^909L(?uUhLZ#y6?Du{~x)UU2^{3#i|K+L9C(W!Tmq7*PVX}o4N z2yW<^?S4e1Ai$tRW(Qce2~SAXwSN*NPO?@-tq^8hfBVKcm;Oh~rqiIUu8TVz(HtwN zloG-8CLk6FL*UEk!mUh3;MIi&y;lwLwZhW^;tOjAr#PXA1F&m1e{e>LZ}U9>0*%<3l|(5VExO;nB2QE!lsysH9F z^B>1LdcHN1;*423&q&-7>Puv#e)e0gw30OwR)_ulTfRxD${jbW1_Q{x_O<9OfL1+x zjern2M1JY*TGvI1heE#&w&N!<+;e4}jFQls`SE>c9s4uq(fxo^dLMTNgHnX9F?YAR zX=*Q;jN-BO`*ar=NrjuI<=zw%x`-NWvhF8A=nHN5;nXj@xY&^kF@WdoG-Brxpqrbr zJaBT`cY$uSIj~hy1n-d9o-X;R@QZLy`bF+%&K7?#@yO4X2nastw&osz zhjGGNO~1>`iBAU4`;M*^Hvsg)Gh6qdcpL!;Y9zs7J7&w0WKqJeEk#f_3TpKA7x({2 zb-^nH7eTVO$>-pobk0405-S|`{vt({l0V-6+Gvvzczqv0OA3ls-#MzfQq;9?WpU3nt4Cf( zkiBo(J+TUOH!54`$>no@X1LTFNkbJv{qzsN)Gg>V(kt`eco5LHkiY060; zE_hVmTIIpxu;_pW%~sAO;MAj*@EI0-W@%n8N25=uNum7(fkRjVU0nj*vqFgZ{gYFV zI`lsV#!r(Sz(1)$bRp@)j#_?OiRVO9Zm2P&TB`D_hzePKF7CJg_;|Q~{sel=58SsAC1gKXJUhIy_yLL~!^roV)tS!OkJF4&`&q63? zKA#tbM=q%8SMCiKK7lCO{kv4K`s(E1>F+z;!6UOT4kA99>J|SDF(9GfDa?FCr60ZW SN6~NK&+(%+M{*8dxb;8FjnHHO diff --git a/docs/developer_guide/images/Longitudinal_control/synchronizedAction.png b/docs/developer_guide/images/Longitudinal_control/synchronizedAction.png new file mode 100644 index 0000000000000000000000000000000000000000..7ebcf6436c0a8a21b42da552d6d14b1ab549d2e4 GIT binary patch literal 74305 zcmeFYRZv|`@GpuaKyU)VonXP;A;E)NaCdii32wn1f&>Z9#$AG2aCdj#8|NucBX6+%u0?{8UsRSuYpVRIsj+Sr#cQ4(&5!DBEvhgwtg>BQ=XR z3!k|+tWCU7w?#|Icr5cXh(}BA46bjD5*#&cv~4I?W{iJPS1p-0HzHEI$P^sbj{e0S zVHIE%Fd4`;aFOKOI+Zagj5{NN9f) zR8esWf&ZU@|0L+$|2gtApS86D)x@LCh*Mr(zO{lJM{vlNbB8RQOpkYF`tMMeRS>}q z;X&|d@rj9l_5>kK7q$@tC>Y_Q<~BAavt=41sVqjV85FOCIZn~cuTe4TwU0dBU8Ql^ zt-5oGZHL@$C&J?5YLCoEUId9QYawQGBOn`Rj> zGXqustc}cP*q&EYGNAC^!o}?yzAw*DTPuVB8`6IM_hnVK{mb*i8Qtr9lG^{Q45qf6 z9BQd*`Q{U3ZEw9R=zqPS|L=wOog-;%8g-T*&e|Z^-LKPM=fAEVPm1+Q^_mq^BM$5dfr0>7(!T85;3X{{C52V_1<~JZ#$UU!H zYH?+F0H5TSmP!ji0M0hxjaCCZZ+dHNV)8mw3=yCBw{J7P9bH>j=kWaKaoYZ1Yt2c3 zCU{F~3i4>ppe85Bj0$X%j0II*-GaVp?-QQF(aPvuFtvhqp9vN|Vc-q@;vCBs?6O!7 zms>A{dmv?~z|1sH>t3<4-F1+lW@A&{5d7lo;-aXfHQe#E)PWH#&Vq})>@+U$IOq3- zGhv=Mm_V(psW}w*7U}g&&vqli2HxcAGfi$yzFicw+}MhdP1CsUmr^$%3!i z?cQmC46XXT_^f(g$&O_U4By`z^|uTH+VO>EJ`y>RHK(n^E0kJhYXu!6tx;xKsNqM~ zmP?@bw*C3Uf-qyWNNI)GhOZ%?<2HiXc(zGT2#WVbq~0;4EV0R8JmuE3CLmIhD*W;vW2*O!Td?@Y@2Q23iYzPhYJvoKXL~d&?EYDnD*!wdS=k$%AU=6aNTb*n1iTPxA3-)$6O@^_j=P2`K8A6L&@6 z1HV^l%JZ`#aU(>xhWL1O7udzJXJWnYyBGROAu!azK~tH~hljzEo2G&yzpUS}0dny2 zLORl8L4m?KOKnEiJF0SgM|jmbIstf`X6j zmr0e#M>kiyqgzaVcSyvsdwrZTfGrLT*^G?J1wCYMU!=%8#nFyvw+0HggpXn4NDOz# zDK3d0<1pG^7!LWDk6nP*aH_$7-lno9^wK4>QnLk*A(3owd#7UB*{ok5fF5t#bg(Qv z{blSSIM}R4OBUKiXj|r5gF|>hdYI0HeHRyEjHcK%wMFUP=U7@D&mUWKaK5GqhEDEb zvpIdzz8&bQ?x8MLKkA;j#I&sEXN|(($ZshMB(dE&(p!r@GDMu(^N#)iGG)F~LMnp2VRLeg&K4jwy2y)OX^Cu`p#^t0gLq(-#aGqO?jjKE(u`BjAf z{*4{ecA!7JOo`l{H11F~)EgX0JEEsOutL#toX={n{+uTkY1^%6LIX%IrGS9X{M(Du z#x2xB`JAx@klEnKNNZO)CPrMiT$iqKS*Bmc<)wOYPREtNs)mON_+)pc^6I94m}mJN zEc|^#+ueJntVSqh91x_9+Ru7c2 z#e1@OKEbJ4ftPwb?sRPfkMq^Q)PfcS)%d5Re7t7KC63mK(`lP}%~16W-Uo$1twU~N zYsvmZSNd*Juf}9{CWHC6*WqMnV&zKo(I(dJ;}(W*jp=NXm(7;J5V2Rfo4obTuLhi} zG0Y1i$dml>COp`Of7jk2K%?xr3r&3zl#obitorTmW^p%$cK2k!;PWyIYJ+okVsDwY zBb%X5RQJ;#z;$T!zPk*o|0*T5IY}wI_#OiTr56XU3>4hZP+|6TU-|->Y*&5?8HST5 z>2bgq@D7Zodq|m1=ReXqepIDGPWSYR>G@XFB#8*#DF}jk~HTla`Y5$MQ@&5Y8?H&=K;L1B%5RJ~FPtKcIMTc7>(uAZ+Fv<-}f?2ug z)#Slvq;GcF&3&1Wi52A(xsKiqZ2fyB&Wg;L7wE+m>ATs(yZIB)y72J6r5=AxppqA& zw(~i7qYL(AoS1J!B8%B&5R=QtSkBaxYFzMver9Hdkk9pamss1=2e4iR<>fZ>kd>kw zUnwmu0?3Nn8j5Wi;Hbdd02c9*g?iQVD7{iDjVI`X)h-w{O<<2#nwr^UmvGaCX0^ke zHf@LGLUGNW#MuRBamaXVx$CA5S_a%SBIS`Xg)`>(`z>PSgcdF9>Zz{wP-cppQ}+#{ z#M12FhNQ8cR!b6!#$>7JwGT1pW{rgNZ!L@{HoW-=u*?w*NCUXPZWiMph8-W?e zq29NoCaPp$?jA$aa*t3*g;m@A11&?H@+t4=!S9~ha_yd^VaMd2P$3vrjpjUiZSftM z3{Di#f{e8EFgKwN)M*<;H*bQ5#QPi?FcK}hNAj86T>#O)U)>Y`z_tN>TG#A{l+n3U z4z|(#tKP@=IAeNH>!*0iTYfA#ERiEv_wWz(NZR{vlnN7gT*9`N1%mKs?VCZ-NH`&W z_~dg|jZQxBOiGMyohJ__vU#Mhj-~-Q_n&V;R8Zy zQ|hEdMSUm%1vCDh#ot2$0>>H@k87W_1L7}Gu`KGh>hg22{xqt}Uj+dvi zyV#doG(;q%uhP;j;pJF>dP@Q7{eyNSoiC+{0v~m0LF+SJFS{sxYG$AXt9|wOIHS%! zah6cpph#gjmJ$^#4qwZjl4Ww6j58IYG*X)5vCde#S7JTKO52o;1kZ8ACq7WE4s6e7eNmX4;kWnSl~Pxpx=7MvBU|>mp_c<&TcnP5B{WV zqLx2dJ$;|T_$59Imfeh27NZtT#Hp$8_;x)?BZ3v;lpwc=6b#rLAru zHQ6k9kqc2dYSoSN()dFsd#6e~OU<~SDP!8blI03P zjm~l%4_l{rZbmSS+U8p@+Im$aGXflGC2Xcp4BCzM0i+`QXt+qRWj~#FGprx>alaMm znVcrNIn;J0_R8C1MsCne%jEJtV@2nb?FO)0pzQpSBw zouII=v6a--!+`k6Oy~g*usEHD)y#IQ{OylBOipt;ZqZi@fMYzG_xqOI=%bS=6>X>3 z9PMUO4zJrWvl%>`S3*`3NXeg5E(c#lh|vG%k&1Oo2`IJnR|KVjjH&Ix`@*Tg1tZkO zF&=k_HMKEguJfsXzb*)|S{|A)b9X*eWI7Wqd#lH(XJ3|NM}WiXRHhInixIwpTh`p` z%3*SfgtXz9x#whxq!s|HARy;oSy+tg+{c}YE{WKMHO4!e1Q2EesNnlQ=RhQt?Qykx z5pCxkWasy=W#wttM5Xz!bp*>@(|8EshIv8EoOXE0Il;Z`Q2OZk%w@_N`o979E( zO#$2&keK(49r1d#&t8SYU*M`p*ef%>a9-~=7#bEj?kLbX$Es9oY;fp zqr4}~8(NF{MMs+ngA-%B^~;E)=ejp>wIHK~dU_3T&k=7Le!jZq>goeR&s#z@J`b+1 z!Bdsfp4@Du-nifMp5Ob{TxD4xeC0pTbB+t(mA_JY&QC@I z(KSb>=?*!7(L`l3wJi*nwkhIqJtj=cXs9YMg#AVWS?i5T;#+X64MU+`-8txIRA_dj zbuvqBbYAVPZdlz_m!?)e9-zpmJg|W0xQY;KDHyehcN9b&N|)D_wZ}QwM(-dzhWhpTf|hYJWf2V1L4x zw|=aIJ)RX#dy5g%6Uy`C04$Z^;j+WA+a=$YBZJwdY`TqaKzUJ3Ugz2yFM{%&>AH4h@FFGb~~+B#IK72-t_b(+ok;WV$1D#3>7 zZ1+6;lWWfYf;q2~s&y36izc+UBiXo(?nntr|Lv{whYv*thY`K4_o5v*EM~n*g=*i< z9foA2?7H#YU`2c!9WPOY3T2Q5+HQUJHqTbuGNz|h5D^h+=;^nwa$X+Yxs*jkE0q5S zce8D+vzlWC%-im02G^==lZ|#WRskkvTj`n(uhatUusdW^hVv!wc?f^@sbTZ637hc^ z+0JRnNUB4F=RxQ}g1n#saErHs7p>;4>o08Ox|bU4NV@cYd@EI5c?{A+>_ZHBYfxkH zDGj1G?!(;db*NMoU0+X{MN4HmlG>$Es*XzQp6#?3B*QtX-?tLP)xPbX4Bw$EWtRgERYTk^+=lFYF!^g$_i=Vs)zQf*O~_AB?|w3+b~`srGEgbDZ6NjCq$`-7!RAMk zG2nz}+{1@q1QUT=sb>YYc7`vn5E79clEN#SLD0RZ3a5#urcQB(9aw zr^4JA&loN}p^>+RmvuAJ9}ag43FaeT0T*RO#egn-QX!!n!0Ck=)LfM!zpCmBZ)mv-~d&;d63?lZ@7`w^e+jPwj1)+#7GMZ%v@|vzMRS`m{$Wi z3`S=d)zI8lR;UnSt(Jfke^#F^~8eGOAAw( z&-*Z0%Dd;Wd}>Z7O8)s%n1@r7lURo)>hTE)v@|q7fBy7;c|LpD1+KZ)n^~>ayWNbD zEWVUiTwn)D@3#A&q=dYh%n(!l3nRI)`TqL3Qu|Cn@gzF%RbmNST8AO!+G1mT6TTUf zU?y(^1*YeQjwc&dR@PMD z82zre{Cc(r@ja=?S>u4fKdQQAuVMq0Vjp+K zA@-l9hoiA7abA+tbOFES7UnfP9oBnhbz5-(&}U`Q?fPG@?x(}kGo)khW=@af%yb$1 zwE2iJ+xPxJ(T)V+&3v5|4t8WPj;{NcTwU8#_qN+mRHD4!zau1wJ-!37!Q!+#a$#E- zHee(13NXQW?B|B=@9*QjPW1e^Cj=l#k0FsbOspnDi5PZkQ_7VJOk7%Px{qi=k3WF( zKR+z3bOhv!8PLVoi`j_PVmlqUl>z>flLztN@8`e%Y^_8s1@>>f>Kp(wM7uA^3*LR7 z)AP%Ez335dSZ#r`O=B}d1vazsdMR-GK5}z#aHy!MUHuh7V*%!NbaYH*f6ab;1Mb6L z9aR8&_HO@Gjpr(Kyic8Swg3!OwK(P7Mz+`K#vpahHh`y+S3s_3zsuni%1H z`#hqN!?G=Cwu6GJVJRVfu8ZYe7q(wFC+ZSd{zHDh&`w82{X)q7oLbx!#^dr)XBR^_ zfV7JlSB8q7VzE9Hr@_q~6Hyr2?^s=&0^8~E91R0;9W7|k&{P45f(&MZ1`d>laf}g$ zj_~H4M3-?5^LEKYx<%U;3QF=^sIK|9;eNJiE3@(v=uuQt%xhN$*=Of5zEhPtAJ?gI zIrQ1nLg&B=P=3s=@~QMakJh5XZ@LXS!zMC$TOkzh$6M@^qDgMgXxNy|T$)CAG!70Om z#d_)KhKOdX4*DWEjvYh7#i7&Px6fU$Y@I~ z%GP`n%BgUQV92oASD*K6L`Lq56N*Zl*FGp+1zAQZFxjp)Utq;HDFoYvG7&Cy6s7OA zE26*=^e)vavLBLRL#JDPDiJ*Go_g6d0x=mb)R5Oa=y;QGWN~IHSW7{qc!RT>(m_c1`n;ROa4Moz> zRh2sZiDvO;EzJ^@_;>#b@u_l0_dso?cZ5^~tt5$iJBH@Cin7l@c#FWiUq%@}c2Z&$ z=@)BF|&T~<`q82NYlqU6zhw~Noe7`5?97WwlLmV7?cb` zjYaBTJ-H=mz(ke^$N#CvWw?&)rMn!-hU)8m~{x9NCaAaq7Ay4RP2w4jXP602B4W|JRksbcAG^8}fq$Eea{jtxO} z43#$fd@sCd(~_y?+}}G&(zhh|MP)5y*wR^UPQj#0!$;<^ffHcnJ04YJ0}@*^Nx`4}Rq#KEo< zAyu*BYM3V|67xGqpo==z8n1CKVd)uESHcVQ-msGmVMo^TR1v}S3~hGynTwF6XtycV zWHa3+$@WDe>ym49j)J%gdony#iV$<$oT50Yh9FqJ^a~r$@)u5Ox0xUS z@x6DyTXoxH*LvD0+1RlVI?@durS*!+pCq|e@`y;wg$qN<><}r`>}rq!c*e_V3Ta3^ zMWZKj-0K40nqIpuX2B=W>qjaH5YJLrZCAFkl-;j;+sJR_D@ zbMYty)=D`a3w8NKAa|VH>4O?K_)OQb1J7IDd%dvib#uxm`%YP!Xo?PhL=xFA;rYwd zRWxOcdQFFp+NQq|lKYv_9zd}xYfZI{_MKJpwwz&BApnQis(#SrFz|H(>1{Rm!K#G& z@8=)vm$SC7TQK{kIg*yeRMU_fKJ-LAc(Nc~u~cwj>ks76{#>KnWN_K37ULXjxH%LX z3Ozvdo;rTBJqr?u+0Svkhl}Fr#ext7W<|Mt!Ry5f>FP)1c3=+(HCuD?~^RmT@bU!RHp{Jue#W{qIpF$b{LDz0w^wG88P@3z0*62_`yVc=tQ|#=^ zn}kl9RR(FOCd+GPwu#{%72CnfxF$0V6EpAe;vEH=V9CJ-GFlSYDd2quWo>?wuRbo> zp&uf&zfcCzj>y91xo5PAZrbF08>v}ZyA%ccr{=`P( zvxDz3uSX`M=V=7CgusbES!r1O7Yg)|?PRPt6R5?k>4xh}^)gpj^?@qX%)TE{b@l?4 zZTAAMmBU9*nRT!tJ6sJ2i#N38b6Fp4vum<6bOVh3?hL*q5PGKY-X%2q)r2R zMVd+hs9_;t-9I5S$r(g@Pt1m#`2IAxok{)BMjq{3E+^I=O%6pt^EEcOhrD6;{I^g@ zg3H2@01*Yg57wG#c^Ftz+YM!#{`FpEf%8QoN=&@ZCPb!@KWcDGd@-n?=>n++*Ts z?J-cf3hbN^0es43ofn(pj#})ab#)w6XB=)etU+eIkRPk z{C0KeKwlvvhr^5D^QKHfH;&C47j%SR!(RA&#k`GD1|+jibJpHFkIQvxC?n5TMk1$9 zZbrBH8!L~SvHyL-J82?8F3{N2p@2eCW&4W?tp`;Fm4=n_VX|@fiX^w(O6a*>j@_J~oeKp%h=EZ1V)qz)Ij>3lUD8NI3BA< zL~WA@*x|i62LRMnhG+25s6AcbN31Qy-6^N9p#Py&v%aL_rw0rS*(p& zt$us9t(qT&oP61Uj^aY60vh@;v7i8}c)~kabd=kDJcX4Uv{<|K@%WZdb2oG_yzM&k zL#ajY!aOwYz$aP)tV3v+=Oae7c^mq1x7G@s#GgWvt!~`!kzM`7M^|zbovc%Rm=^_X zNLM>lo>#}06sFWjKS&p5y-jn)#$w2?tIs4#vTco_VE<6rlWpB)8BSzYTt66{3*ffo ztkt5z-^B&knS^Q3NzoB{E0g&Tsoo+)?bvroepjIRQ|EeMWoxnzT?7lkBS&wHadov5 zsu^vmgoJT6vz)~Z=&M@Ks#oTZpM+m|Tx~ge!rhotn;9FhL2Y2;Yr)yP5j|(`t!Fbf zj&l%@MeY?Qg~Plkl#yN*8D!*u|sg)y@j&8^$Yz88Z2u!+2BR?fR1%ZJA{$C>s3pHiNfa)ea*XKe_w* zQEZ%&D|X#G&Nd?JS1CRYA<^$2K!xAh&k*J9x>Kyi2#Q3YSQyXaD5%t+KXe}Im4CBd z{U%S!5j#`K&_Am*901GF*xI#fkU^z|8kwA=m`K#oPxaR^Q)K3;vZ2eEg8IclD$i}2k<;BRL7HLiyOeSKmua)K<)(3uVN^hs9NlCv-FCz!k1vr$>S-v8|ir~_t9p!GI{fK_U~+2Z^%79*BG z4~to|%DHm=N0UA@rv!&CgzVG!{6nP?+V^z2JGrJHR}tbPw@QNAk^HEbz$csSAT+_B z)hxCaQgPpL!uPA~$gRp(x{`-ZiJ23k%c9tUI4Jub*4pBt`gft?m95MkyNHkGLq9`wzi9(~`ZBJJW7ZaF|o9j#a71=%<}W7n>E8eJ7UNB{r2+ zort)|1^Cfwzl8{*aHD|>rj0d+Yf@@7hDgP$+dr;0iqJY)1>x?ZS-?GW=GgKWG%jd^ z?EK~c;r@b)*!ZP_msh5K{!(W`-79bv?)NYsf{jn~ug7iUfFadfQ;DaOe7|9oPQE;EI@)tdO zcyn04gl_eejvLUKE``j$cP{au#F}d=0XLU;UwCMPwXLZTJhdBJ#Sx`1Ey|q#b|~{F zEez*$A1p`*JwP$F?-w!)!I!c~%`XjH+`}#A!%bcesdFxi8rJA@1ackcnvN4c;)&lTma-pVP~*u;zjYw?X#Vcn2C*fIfWrP$lL`<6u^qsbB z1_)jbv%Kbrfd-m_l)*lN^as6VzOCUz60O`rdVf+n{9BPRLyFPdd<5ixa2gM*Qgfc~ zZEvQUu)!$mA^(iEM>|G~Knijxh6sDq_)^&LK_M(Go>*+c(v(OmD3sW{iC^GLFZypJ+JC)wj;BK}Ex{HwhpZF0s(och*s-sxum zsW>aK-gw_6oq$r@tmcrL$|iVLQPF143jk59c7=f2H96iqxWb*vt>783pnwvYrlqT* z?n$3cQ>cgrAH0AhI<%p{3QLve{J(Y6xJq0ZwPFOb*)ImtKdOCA1ceZ z9IAe2Q`y1Z=rZFL#eHkcuGu8i1grF|FmibDWYjMfSMZCrEe&GGuQ@fusntZ8h{4WA zjML|R9PcFi6Wlj5) zF>hJE{kaaaAs@dXf6q<4aEHFY+2b9!y{96cO{3igGZ{8%x^bENX!%-aWIQ!l%;17m z3UTs*h}vg@sy@w-;vyaY@ElAVYnKUTj!j`Knyai zbch{sj*)uY`{bEDXhFR2W@yg9@5D5_^xB^#w5~-@AM9^86u0}t-_i30zO%OfZgp(( zH2XV3^oMapU6Sv$!PZZ!j&Ocxi1ywOPK5RnEXMr3r#46-7d!NS(z4c!?L@FxldHX! z^1g^rh*SvhcMO01u~BA3vN7V8ZD6OISleCxsH~A$LD>}@TvagVf1Eo@)t9LTF@-G+cJyRcOd z`5y+Ycy?o3;T}VD(*-Sb<~4%jQ89_s$3Oc5ptQ#3s~sUkF{CnD1G96RZ4$mQc7EBg zr!;-7(U0~z6`m(MA>rSJf24cvu+7%waA*;}k-f8CY)EfRuqKE078J@Y4p0HTE#2X5 z#ub6~?qY_^e>d#^+bhl=El220i7CD6u>S)q;CjO4r%g{Rlg25OJ+%?&-95x#OrtGu zs_abtAjuJ8K6Z+Is8e5S@BbW*UMvx>xA+eb3 z1Bk~)z5n3OS^}jcmBB*2?^-s2_%-(s$MQGE$c`t*ssmm5nF@RZhLJG0h+)t&uG)zs z*z=Ni1e0GD@^G^j`zPY4Ih8H(k7nagGsC1-?=5hzgVArA%~2U}uh;dNnQZ0DI_xx6 zRhRE#N_aes39`6D7Xnf<@iRsiCyom!6L}gh>w3rX@-|LNy<&|S7dw$6LwtjK4ZHk9 z&DlRc2Cj=c;%xspaj4Z~@P|klF#SBc$xcqdY*1?aWlzy^qR)=s(qY}OepvCBV>Dan zkC$;*c1jm?Lxw#F39ad(CuzX^`(y1rz(ZN%ox+6l#TU#oh`V7@4+EZq&=l0ijOxNz zMU*fVw%O_12PsZ1ynE)s0#u66Iv8ZzSDQC?EXE^LQ<;lGP!g?;ZBSHYv!$6@zuz9& z&z*jBMO9l`3De$crY=hFetJ*pM$jMh2Qi*)UbJt1}j%}D#Y-?DgBbSyMUxyqU5y4g>`kTCT!~Mb3i2HFp9=OKI%EYw3*Ojy@BFv>d7bjYcWgB=w$&*ZF%uPLAb+^QP$6{LLi ze!=%gvLWgYjby1tk&2KP12-{aX5_=*qki*a#>Nj+{F%hy^Q60`l0lJQwiId>r=)`m zCapEZ;A6M-cb@jM9`>`}TyZ9cd$aWh@&ZRN;3A<$IUY*NEIRp)IWF$mqSgs3w9iU) zQgRzE2p77NDdrYQ{e_Sl)Vt#^5;aCHTg6>@mP(c`2%~|rE=?5CSHPLyS+pxvv0M4B zVNqL;&0{#i;kdYO>KbnRB`7GbgL)Rt1kL`uG{40HQJOAN$GB`ueNt^{jXT9Uprs%>D9k5*Zx3EEe=Ij#*&?32w2?Iu+UhC1gp_uq6 zA*WB`?}EwE-LTDYU)GZ#6$}e9%{~|h;Q8&_AC-7>gPN9y_~v$QmwnmDtXo(|1b@zc z^47Z&<54cns~8h459wdd3*O_N-kdf>SGy5dJ+mf{x4)fA_~@^~ij#QJ9mq;5{1NL! z@ADaUvUQzu^Ozj%AKIVP;dEJ>HZL+5`hP)q2b>nI1f)Pk92@5BY53ijoSa*Yh0uOX zGn*zA03iH~l`|)_4VW@NYxIt;KpXD14IscWvhL`LiMg!|uLX~tbr6@#S|dtvRoUne zQ;{AzY(`um8~xqTN)I3XIsUVXS*{q~TX$_9?!k9%iA%KSv9`YU@8Xqip=NcVjuAmz z#;3IHrH|8S@tMCB{E)uN$x`09KG946>m^~0QL0{;gbMS-KNp4TAfI&1+;WJVHqk#L zZdjSvFW@+RhGpk9>XApmbFB%T0U1z~dJQxJK&m?r-}Lq$f#qq!%MD)Lp03|)$TzoS z9Qj4}zKQ0`)mI{fBl=-N@`BTnvL{ua9-=?PHMPwxeSmm|YCkO0m>@B=HIk?ybcP5l zz4_cy>Kg_@ATOsb;W^EtMBjr2m_{!v7tYql1)7h9B|ICziLV%zZM0>v?0?MJsib z8C^Jk^`b5(*)AuIUupZGF5sz7M#1H6kowwD$Yzr&Mr|i1{#fFxVEs_afU-;^n(=9& zbw#Y1MQSk*hh|i_6DA|b((Xry08@>?xLnA)ZX#lQ9pXR>q=j2yxVrJPUu27NPtQ*U zi=YA8OxgRY%5MF^G|Dos<6EQ33Db2oQxItUBws{b)VnTD_W2|&9LUpt^!$CL(j+M=UprG8uK zxbyL|ySR69M`s3GY3Q;N9A=7GXULdNQ0YpS?&`Y;$P!b#WYbl06qqQgw?@SWUT-9N z9)Xr*k~?aMMS6V?(|OJ994CpFC@gqlK@Kh~DsxWX*S|$R-&8R!4sa@Sz@yD zIdAUDp%WNl#V9H1M^5zKkb;V%y8Cpv7kg@32+aFCd){JnN=@|LyaB7M+qN=a?*QWK!0;PF2~XnApt=a}1olhL;Am z#~2=t7~p`cQTa@W>w<_k_3MJD>@aUme8$!Q8oSA*B9J82Flc}p48^a9z`#Efe{J## z`!4*QMgLTJyX0nF=v+w$-k9D9^6ht@1dO2fGrA&jfhN8B=v)pK1(}ebo<9xT$gDH{ zT+^`RfPARXXBtG@SAR^qE$!8(f>vV5pbyer@)`?Kp;x8b4bWMQLl0oa9W~N3rrm~Y zAbmI7!#JCF&~D1sm#ovTOP`SjWZN<8pG{uw?bbzbGWE>#IEMy&&6t0_=FOvhmd+Oi zpeL&U?ZY@`+|nvgz#{=PhV{4LHB`=i()Hfu(Os+wibx1L>I+RrQ#^`+5wE$d!8)WQ zd%7+X`c+c$?xqN+RgM11115LWx(5o{MwomrkOXhnVKp^1fi6S1NNfiDGt-sqNgTy{ zdw~}GK=!ukw9!-VOD9$UZaH&R(pnRR*B_uMbbj;pT$Cza@99wO@uA~|k18QNFc9Xo zeZ~G?nHT7_ODs3{mfUga7AO_!uJn7d@_oL_`B%tOQBkq_0#vYl@$k5F=K?BDE*vg9 zi9a2+A?x<70HYTIW~kD3JMCH%S}#AkX5h#{1Tv<(4W0uSJd`vj_*A!fC=bT;O~k7ECmV<E-Dqr|luu=BWAXKCHQnWZod0V$8CR1?c>{mfon58d75TllZL3(6JI3{DSN64a?)gUVCFxb5GIR(r?!Mn2$ooYAG`acixpB4t zy{eb*3OZjqIbYQ+gm&jQU><-WiK6^^rM?cO9<2ZAcAsW``#*ix95Ml~?V|rrAAOhx z+FDIhzWleK=^r{^ZLX@7;CaSZ6i$~$OyLZwi9EU~ajUg(WX~wSGH=oO5i#j-sx`<6LI+MPT`Gu7sX~U}IA{C3R$Oq7kwWS8GII zwzagbmDt+7kP<2hb<+-;Ilol9K>5BYpQZ|Dp$0jA5YJS}Kkm=`@#a9tu*v(85!}y2 zO$@g|1PknJY-~{KAcD(xzpn_)EpO>X5*qBGBnaTao_E{*)iXyMsvUB_n!V{|xCKQ} zsmo&+uyL7;UY9dAmK+^nhD}v&<`%W(0t8hn`CVww*C1N?tQ9#M7onlAY%VVG##vcZ zdRs*3gk{+an+3UKNG_-&g`@A~>|b3s`a zh9s*ubV|{S`$z0N9!Vw60;rWZDU5+GII%Kuuz(-O&Dp}9!%T(5X$E`8KfN?!qWja= ze?VMGpQ*;A$=nZ&b&{bIbrX*~^>d`& z+mqg#^IAOKzw0j7X3)?V6cCTaw(AGvW#6wI3lC69GxH=Z9Sb9vwm!s6ln+A6sfj3( z7mtO#11a-G&7fo&eX;=t5J@~i#YO)r18y>{Klu&Huli%%ouft4{uat%e2m-ct{!vxnr z2KbeGaB#z+snGaZmh9t94~Nhxa%q&qjW5()Gi4cSUEZ80Nt-6L4jsW78AEAF<9PX~ zUWOx3h~$eFBAT$un9`$CuO_?lE~XDLUZfKXjPDe)=p|osi#!EI$x#h#{M;IN$EzK= znwY(7Y5v{bIKrJ(gvv~xRjX>AsBu~F@x-@Py4^dl6bBxUj(J3jCoX7|h-Jnk^m7!*8TdhxKFlgmCUMcmi-X@sft^F*?> z&c~*qb7R);rV{dzQA2TKDF?PYt*f`pFQ=+oh$?*?Hl&8rOj-G5XtZxvSeppps76fr zP>TrkwD_PagM!V-hi?@~a^15<9quTazQT=z-vAU zkf6sVi~%rgE1eul?}Y<|-1QIS)o;R`;quSFs1u^%3oyJ{)Uqf$|3X(GeSna1-%|jU z(Gl6E%QmHUkB1w9K8%~{vyyoTR@C#9vA%5qZ`KK49v&e_nLydYfu|;FM;4czzt27N z7(-?Hg5BJ41WU8CH!W#I-TB4&<36UaAy4z)6MH zc-s$Idl&N`>wi>oeY&E0Pk&bPbdJTG3^V#Mxn(gv6FWghMB|;C&jn<5J&#eTZF6$! zlY=26#@jA%-Ct|M%{T7sSViH+;(u4djzb>3BA0jMA6U0f9dr-W9)kkC zZ2^TRgM;UkH4bPikm29S%e%Zwhqg*~yZRQa*M=Bl;$$Uh-jhOW-*&0c=) zf3ymhU~+HyL!Z0bnExwP0&D^vXeD6kB)@J&ubre8aY6L^-*e!^xWl)tb4Inx{K{(| zeCQuA?mi~u8U*%w`7)~A${xpvd)pAb@s9a5XE^vYw!QGxEhF;74XkTAf^Lic;AG9EZKlIm6R;Q{be4wyfjKbR#u+PG`vk9&1xVNntjsOPykYuFl7~X zAAzc2cWVy6$u6|JxNvl!`oE}q>#(Sz_H7hIL8SzwI~)`w2kDRyL`p%rySp0%q+7Z~ zN~Cibx`ttB=^UB?>25fi_q~4C_nq_iIoI`_{ol-9GkZO2Ju9BIpZmTg96_CVHgo<_ zU1gDYCi!Iep=szg$<(zOm;#>cy#wEJ7pb7~5ow!bxg&~RF*~}WBj&#dI+v+Zk8HM` z2t_?(`kk?46LolgWHx(cr*H(5_~MbJeO<0GA_@));&DH7_}x;q20{VIqoVtXPJ?a} zWcc;L88>yJ@K{jGNvIho=kh!h<9uGcS_q3Gf z_lc&3N;jB(0HJ^~E^G8j<>@FEqC5 zm8KmoHROSPZfKUZF4>cJ}Wfu*iHrG?0tL z|3`cuf!yGWjHg`Oq&iHaWi|+%uRPgt3o3TV&3lR9C9<$8 zqnKvul8kz()G!A1?yydbKW?6HsueXh`MA!VZ)OzrB=peb%ppI|@%GWA$qxtq<|Q4} z3Q=&RH8-V=(3>b9+blsP(T*f+^DXS*x9Nr~#mCEZl5>rl0^{GUCzx547zj;-p|j`2 zsab5bQB#tt&Q(+8 zZf1#Y=1wWWSm)X<)p~`G((F#?(jG$kNlX{q60g6B@2aQc`XR!CmwuGKNRk(5!0 z{q)F=VS%cJ$eh6_0eiNn5@+jX3YdE>!qwp|f3P`<-s_CF%=ZDd^0|||_;Wjs;0$668Rqg7c6sxg6#eD2oT?=Q3MKT~%p99q=+=YE?H?jh5%v@x zpD@ad(@f&zOi;k}SJo?8GZY01hv>E?I1dwd&TSO=4`#__XtE+D9r{!;pEK&Eu`jA& zO&F%9e%ZA~$e4*AlE&rz)aCJkz-}rcJ}Q))9EYG^oZT%Ac^sW7u%qo@%##*ToD)S= zyoAOG#sp<#Y)E6BrhfWn)fcvdPi=u?-(F-%T)x`zz_U&%FZ!S&|;Y+69I~|?C zhI+o_{}ic>*yb)kGTta5Q4+qu80y*vYK?9B48<4Ny6l-vI+^j#E&Rj6O(qrph^JnS z`80AdlA2l=e9J_98yoxjQLkP{qPho7R68#ICD~ujcpKI-;x^|5hu_oQ+|XyWKXjtU zQuz5O$1`j^9#Pj`XHJ)%#wifS#&GlS_e90h3p&JzqR1Otw#T)dFsJ=TB-sTe^nbq? zoYQKYUeM`H*V)&RCB5dI^c>aM6+wioyv>5Okc&^m$N^nP_)DlqoHIw)Um~nYPRSI5 z&3T{C_KsN7Ekf@TyCM*;YqunW=&y#zOLw=n-^L#ok%w)d5%I?6oCV+)Eqt3XiIano z<6}MhzPhGNbdt3Vciccza5b=>=@*wt_Na`FPes?TK+ec66Y?&GpX7ekW1qsE!Q1nR=U#SAy&mg30Ss6BnjJgc5qFE%{B%`Bk4qhjDlG`$emhLFvj zOEBQ(={Df}1R`BM+8P_D6;p(-d_lMbV>5HSH18VZ*M78PVcBWNWyrJ|Ec5*-jN9ZF zMy9CwMt4ktT78pE_;_v8qN?joCDZ7@K@f2)mor~(uebPTinbB->-Y9S>LHn1=q=%jB$3Ye3 zBnIrB$&{BzZga;-wapHWjLR`uGUECT|K5fg@1%oU!S*cjXSSCLP?%xlz~HSQvJ}u6 z-TDoOv{BxVTS^q;EJylYh=it!$$wjJ?dW_Picmo1;^~iyMlrvFt(FzL;0&L zD!Z4hy0=}Aj=-d;y&duvVc|nvu)k-5R7f={`9v}n1=~Nqm8Ab^ zRp5$H*U34vZatHN3LCIH>$6kAExigo^kWEOm@M^Q%qW399C?4ck3wI6w6Qs=ZYc;y zqJ{{D$hu{&p4Cwsmv2FBZT-ZJ7_=ISGBOSt)sKfxErXb`*oU5+4pGYpG*-AI>F3^g z`YN2XI>b2i(eXOOf6+%=YMo)njPQ|;+piX@gwE)Vc59WnQAO)D@1=O|bv_ng95V0^ zOMY_7GknnwgZ@O;+&_kY;`rACYM%3LP!g5V=aFF-Y%eHbqbes1uBfFoz^@&7(L8`7 z0QyESI;YJ#?@uUYrc^y6GnX#oB_-j1JUH^CIu(GVhSNyZsaG=-{yBi^Q zw^4uot>x3owjHNduXMNlLMV_4_Mzg%V9H%fEs=F0)Y<>ie3IJM<;oW3pGFVxS9)&5 zCNPBLU|jcO8O?+*cRCrgH4-Lr?)hu5 zD^Nl;X2QCm8WZg|40{V$eQ%k|;d3k5_d|tdZthpfe)=V(i#E*6iF8$)tZVX$K6B}Z z9>NzwKIyl~V{j_qk2EY4_;0`Za?=fhIZQk} zT%`Q2F7977%)ve{WCSz*Qjo!_RQ~oIstNeLQR-hV)(05 zcIs!u6`GZoLZpvRYyMH3kG9M~Pw<@ygG2LRaB7ODRKIzy)ng$g7)pomtY=thS`+R= zU_a9{_jjvvEqOO6{@KlRTLU##@*MBS@C`S0oeo2Lq4wNcEYClvr&&l90o#tkJ&_?BB zNc-%a_*OO7d)wI{9WzfQYk~}T#jb@YS?A?^clK?1a15l#X>>hVV2I`AOU<1HERx5k z1v_Qe8$(3|xPHal5C5E6!*pzGi7CEDX~a1c zz<&^`Hz@BIYxwx36Hi4B{Ece)`W0oh+MZi)s;_PjF$R6Y>;;wZ?c<92uWN1@nR_!l zUt5vy=}<4ny?sFrH@i-K_zGGXMesF=J-TzXP@c|(lJN=K5GMZmReS@vS!(dW=P z6pRojzJrb=Jl_74ZIf=|ovWh-oQWfPAnv)YNxT1djI$Rgtmj#p&d#I@tTYK6@bC%= z%u25&YV4P0Z{}OMWwX&rr_0Rfu-1ClfASDI*(}0ycl(oa@iGRLg{8miq`~D%?KQ7Jjl8| zy|9OO9&_^Ygg<^JG-Sa~>kn?jjBhRfbvUd&>_h56{TJ62tA5TfJyH0d>_?TmOG5rF z6>Ai|L>ZaX9W_gAa~h=lH|WAazRp2t*i7*70Z}dFl6C@}9eN3A4$&_zI%3B3fF5G} zu%7TCGdmvWjM^*4#uAuZ*E+cwOY5(1UaY4t|LL(%yb3Joqzl2Yp9!#hl~Z-Mn^IFy zaHMS2L?jf49%Yj(e5@exmRo@D^U5idm6!PJJ^tb$`FIAKMrln!L$s~vd$)v-hv)8I zQwKX&Z1o+N79Q-5zXwTwR()#H+CN?8Rp2yimv_lziXj%>01sZQ?L<#0$W0t?{e(@m zulIxBe>+6*P~%xwWyW822-?f7-)XJd#rPKCmYNNiZI?0EK5kc(Ywvn*^QbF~;5oB} zezP)OYAfLzy$oKhN0GF7gwPtx9z8X-oWTUeBH5xurbJo7txKfVsja+x!=JOxQvRJ9 zXAJTL#PhL`n4W){k<>#_#fW(M&we9Q!DG6XByVIHxSH_B#8gPRkuQ;2T{~*sxRsYF9BL}y7nwmI8HDjQrLVN3_ zt=|`s*Cv!X_uDM%MQQ0-?ITwa=+I(HLU4~W+1<7ifI@oc%In{dl=CuuL& z3s3wTW#DBVdUqPIQ+p8!{ww`s#3K#5ymg=xU~>4xLQmG7Ifpre%?IUD?I1GM&3;U& zi6Y`6gwY~b9N3+0XB`D2ZIj~-piks--o7Dp4zHu)FX7!)@L;_aA;_6S4z5|{j}B`Y zz_&PuTjPtnS+vq^zIEHo8#{irH>R?qvi2P9Sk8k92(3;JV-KHlySOHFH_Dr{8xQWL zJPED&^umHWNjS#-2NhU>LDXAXL4U7jk(yt-)1k*IqNPMrOL8 zMVXoUX+VL5f4(2*-*}V5klxeq>Arfg0Z`bmo2U)mpWA#iJk-u5&&O_*7(G|g>$@Hh z)t(iqn5L;eaKVZ#5p29$+REz#lM@yd>^n(NmnX^=LEy60F7$Q2idUi=obIo#9#el7 z6C5TF3m-PIGsIWMCec0>3Yah|gil&eKl z-o`UPHaNbPv9lS~Ra~aImJG)hiS-2=zQB%7w9~z~S$26X%on+g{nZ2WU5<(H*ZFGB zY`VHLjut3yvrW4Z-cn3*Ld5XEmC9ZW*R5Xu6sxGMXhj6&!A2{$FQ_US zv}w@R&&SO*uoWg-Hr-6esfu?Ml+JB zYF=huAAuT$LX*gj*Le)f7K7JiP6r=ry$uc`{}}R2(aq_ni+~PdDZI%Rn(xctPV?kU z`9u2QREk}oF>r{TssJlpavdj^T`5i)IG(7{xiMy;zIw-U@>M=kC^d3C?RN%lZS<#- zr}9bHtYoifZGZVeTkUmy5h(H`4818lK_AIXY|>%Xpq#9_xRZjNGX>B93D``fie`L5 zT(CplEV`wC^w?~zxAeE@V5{q?^MEOYizls0V<0sG{MFSJ6X9X?1UwCl&0p%t1Ab-c z6QPS^@b2J10&K2UgEyNmb3ZyZ7UqV$Pt%OLIeFcJx+1mHwBR=8B5iYCb^@iO8kUKz zGK;gTYmtKU0gj*I-sw((XC&aXf5lA&Tww`rqhH(PTgvnN%Hwrhek8adO|)7?N?D;Y zWJ!Aj>uWW~*5Kq8Jas<>4mFg;>I~Sf90!l{Wx4?f%OEaX=|zmv3z{vsiQ|g(ett=w zgkFqksr_}G8uor-Nx2-PZZHR=tW#)bcT&}Psw%f2L1|+mr^aihY^rvqYV>vIIonl$ z>bQNoNw&X&Y}Y&ep*npGNMTH2KwGL5ha^8)L5Zaw^mcv;p+##=bQui1-6MV_<1N6a z+-nd$qwupN5l^4!4CY&bh`d>s>mZi5TSKsq9qM}A|8Y@AsQBs)(24omYe~|nUV)6C z^!KTsd0rNyvw!#`$OIO@l9?khWnQ!z)ybM`Ew02>H8;m%Ll%G)!*fv{W(K&L#|F!# zpM!FW&MvFUPeN>)X3DXs`!`#k10@kI)V!8H?S z68rjMea@a6JYw#}@t?ElA@DoF_rC|;o<)fEj}0MrwM|;Bp2W)(&<}@nbbXSR{-jrv z-kVpR57Vk|X2mIFDR%$cxUZ>oZYnDu1EwK278aD{(MxsZ<#z1EC?coTZ^US?uK#>( z%F?1#?pD>eYjd3Vb`^yB2V zu6!-CDRId&bs1nK8uX5X9G7sIC19GRZq_lV+=mGk}M$z}i>e_&hnGRgqUA`5!*(nlltS zK~;EliH;m~DlE|-r?lV=*L%sxC;mFY)Z1D_J|r@T*{s=iB7q`u9ty;1eRA;d!E$2f z`oC(X-sL93Rh=>fV5Sl?g1$ugAsR%~f>!Q~VowQk;v0oj^;e#1roiT6M%+In?fido z0YaD#|IlJGtvKhHSEtAUGy~Q5!i-=v+?`F)-atuRo(y!xp7;Bo(;jnaOZr(^?di<< z1V)I9n8EaQ19-1W5FCk<&9Z&aKZ9#TFt6W%{gZvQNf(F9Nqv#;n^BYY8LlYdg*qq z$?nm%2j5Iw!?hdK)vEiB(>^h6^f*utT|Szlb}kN(Wgojl6xQ^Ycj~Z~RJ4r9u-I{= z7MdJ%k4hNST@y#l)AJZ}tgmk*=B2$=HETIm!HMlr^Y|PzE#-o6b2wg+0zwiHGci$g z(Jxhqz$dto^KivX=Fq#xXRZw`cJjtwaJc2A3x5_n{hN^D5j^))+#hYRtXaLy#3#`+ z#HRXLQ-x=-{$4#5#V#KgiSM+m42GX4&&hZ=llS=gqL5~!{+6q360=G7wt6LvJKP3v9*En zg4ow=C3yQtbIsjyUF}ffqA|?BFXI?^(=cT&iISpq44ai(oIEV6b<98*-HcJ@a~5ST z?8kpE%bpIZa_^?7pz{Bs8#~hR4X*Kc=&tLhM=6&2l{879%QCNY*SIxDC$TDIm5|5U z23+98u`%iB&iGof*6FjhDQ&>7JvLmza15SNt=C~F%-8dZ(PqtU3~d~icKr#ctLr#b z(4&%nfo0Z7KuArk+Lyqb_R$bHG%lgPZ|{+%+N=m`{D<>sz`4;!yj?F-u< z(qf{N14CyYx>iGo!Dh6!#OxH2rhb$Nsp`%@Y2B|;SifGiMSq!I^bI1T^gPfW4QngN zJ@AiyhKa>o+%WW7NO2K?^1Ryi?^r&L$IV<=OwUAuBAipCg1Xk#X-wf;v}7d--DS`G zSmh#X;6`dnrA}PuInyDJqv6+N2P%G;;O!8>CJm9{%s1t#xhd^ zDU7Xvbe*NN#kJ*hqYa!%B&OX^hADoarycGe7Vet5zp3CCY8)-Q{byl!Ok4q{itjLh zB}HEr(|-wd9dt0l;T_|@j>ys^u~FUet&@MjNkiW!F0FU5j2DDr+QSs zDqnZXYG;)E6Z)`c0xX-&S0JAus1Wb1qzbkm1bB6wTLTM80|n0Kh1Up`hJ&M~dz&og$a zA8Vb28<&;2?75L753Pe59IhDDNy}{enHhBi7vz5PD=)s->~5ngS0WPdk9WXqm;Tvg z{r7cER{fr$uvq}PwAXc7Gxarf#rLMP87i@~12hcmv%SH@Ose&pNDi(zhf%2a+`Mwv zg_O$|nNh7#`mD9S36tgh%gX{ESB0i6AP|%0TuBk|y&_yiz)(I3%Qehf8Lvf4HcwV` zR8h!4IJoJ6uV)1IH$;wPY)q%cB>^=Q(y<7Onc=4+Vr;xBOXTbISxSq<kQmUqqL!lJkZ8?XF(+69lKg*zLLkq<9E~T9llX`?<*{G8drmciODOs(3uoSOnrW6($yJxlGOD;Wxh3`|Enr za&69D5v(XB=iJmH*xHVPIimDt*WwtZHl8+rA>7~MRiL(r8AR=m!lRH!Bky6)%s=lN z|0Uk_c1)e)Xml%nC4zue0hz=+Rd&2*=6)y$Ho|D0_YMisEfd~C&<|x%rp+Y}w^bN_ z`6Y%G$nNjh{z~%VMoy=hTSR}zCmpd|lbP8>BH~h8;nHq$>DT_KoL4K0vuPHLl{$~! zm(Teko`DUP@_gsQ9m44&C>25VH<0wQ#{mP6)ntrZIgQGo6T13zVOQ;2ZokxOJCLU( zNCmSzt-S6ZCptLB zNJ8=OUO3_HLSg?-;qg+8wid<4zs+TX8z$1uH&GsO>N(H;E-tm}*?0DWWCsTJN~}BU zZN-N7taV2I%ImlEURHH}4q+QnFo)I|pYb*dbqSA=!ahC`SlnOz3US|N3MsZXJdYvx zm9k1Eof$u-L{u$MIfasCRxxqHOtrbdr~b7-P0!6QJsu#xNj1zgKb^HpCAicTkp#*i zGIFHrnl4c~zHha9B!3ZmBeI}}#yZy&`$Eh&y}yboZPQdyOyt{)S(l!^jA#Z^Qo27+ z`_9%c^ZS3ps>U+RbDb63$$w8K8Wao;6ipd^-?LNg^&nKMY@Hm#WnNVPZQpwo~6 z536;ktF(c(MqHg{wSJH`e0 zUy_b?&X=>i>la{ql37yv6m-c!av1d_5Y$UBn=pG;m)FV-Zk zZS{9Mk%O-E*C>N{DX7$d-c=mnbdTh0nwfD9dzWSBO^GGg)jUG`O6L1!yPS`4Wu*d; zHcf*qyFM)08bnQ^FdbB%H-+|^D?d^GH5RpjQnIA>oNvg**Z=Ty> zSP&z;H7XiajDDX>qn4>ofF@)cibo*k8M726&f*h@V!WNE!UJ9=+f=*AX<=uV)10Mf z8h)M{|DdG)E#)e2&B^f_X*Tn;`p0C;A9sa?m^TZd8kaqytXo(=oR;uC$aW%!PV0ox z^(XQJ7~BO1r{zAJBJE;MciL43_)SdA!rBdIO|`|ELnfBCd%xZwf2G@~>hdRYzP)}ZFLSdzVIG^avif%9SQ%JP3R93{!)ocWWI91PvL4ZW0z58Grj%E?m!ij@HZQHNSW9n)ObEX@!B;n6pD?dl!fDie>#W>%gfg4#OnS#pvZex2G zJFh`+z}#S|ysBu~KXqC$BsY5r{*cSQJzf1H%vtZ4k%`gInOwv1>ET2-60v6Dd>N zAlyq?BiGC()^}gd{yYC!_&vL%mD%@;fdQS*`VICzp(>#e4qRmlp)KSVJHlG!x3%jj ztjDguPTx%nKWF*EPmD$zA&`ZOrocOYcS|LvVxgZr-ODQ`B+FF}U$)j-4D3>cbUZoR z4dr*edE>@245XV%r zoUowV4}8Z!if;7;G2x?E2?99s8dQoprr;0j2oRXe3>!H4or8Jo>pKW$Vr05x3w)4q zT;a%3e4)gIAUEKibL3T%eVItL0WG=?$0$su@$=|azmZH{bIFtfVQEzIXIX#zUC%vp z!V@k9IG?;3*e#R@j_Es@{9`yF3@%IJSJ}5Hmh&nL5eQR+ikT;lF^yt^5{XOlZmda~ zdE?*U#C^RUc-L1{6wb`OhQp~%#jkT#?aG;>m;j_pYPGEsQk84*B3y*U3q2MDGGmU~ z#Ca9CvCJZqu1@bpFM+2flp6j*TEVNX2Am<9$tNz~qzWrP{Ft%n*wc{fY*uO%o^e?g zHPmw`TZ4L?Z8r;=q1m0??>?LTb2@yiNf^$LkUz{;S)XlAswUa9CdU~_-Nnnq+iuib zytGM>Vvq%;baBe3vXPYHVZ|ire4b$%3+MS>OjFXr8Pu|NpHh7OSw6uO zppD`c%P`0qsu6$Fh;8O=H;B^SGfRo zhDV--dj8)@Wt87z2(>vUx0DaEC-zPjnm;IsnVgQU>HsO^Jn>As(}Uq%Wu_@Ys3Hle zh^C^{%)#xe(wZsojR^ZF>KKAdxeg}}K*-9NUy4f-Xnq7gARMYO*#+@-=$yQQ z$r-z(?vI5%^+Z0EmFcpl-HGV4lZQN7cRU1pz`)|JBQw#C)2ju0Z&9S3&&yc-1fe3q}GQ z0R0#C0pLs?$VwlsVnZNT{lDK@r9J{k#~!YDio*X5lJb90(Hud~qyHVf^532VI*;Mq zPC3B%_quyOWJ18|f8@Xc?X7hXTW^i%s5Kg-Y ze0sR%)t>L{zo=-t69m{NNgt@rTV_5G%)Get$==$sr13cr-)q`$9b}JrDBNqC*M5h0 z2>kpQpe_%D(|Fs|L^4#<-yMtHCjvy^fq-M!xqbPMliRWWccK71=Kob#)&CQB)JwgK zC3b<{Vc<{`3GkUzn?2b4P+6Noccf?Ne+b>noAy>72;9v`0r@+V3E)%^sFizdtk@k{ zK->Lw8ww?Mf4M;-4cx^2pPNm4jgeya$6}}ld5Mdrwre5L(_*E=UdC7(w<^Fwwf~~R zo>p2grC8S)?+zl-I;x9LC&Mr@Kl4E=b* zCb!*(Iz95go$?<9Ae)i@Y2)7N|02-dDpSnIMn~JaIRcOR10>=-G-HpA!+p!XuTlp9 zN3*f~ug9=F(69s2Gh~a`$a6AUpkG%2+kX`NXI9CNm|405(3Q;qKJft)M-cz&f2s%c z>ITp(f3DJXo810RPWHIBUF$wrP`wTSmw=K&vv68}VaS5+J8Ej`$B)qed(VQ_n;>5M z1b|8|-pm2sVn!+nAlm?2`-i57uZ~jM26WvQU;t_2#TlgSL1Ch{qkxEjKrjGBSKkWDHK&dr(w1aa(;}UJ&3lPG>ust+%`O$4f!@b_NK*=;R{6gf)_d2FIX> zrxoSp83Vq?VC?|tKpkWGA7GVu4X3o-nA#zm5f9IsgaEu1_lLChpSS+!*Cy0AllHeH zfP7$vE)D@S`T@#%@X)6KSCb<6!PescPShsRfWl4C;=a0s2m!&&*Z;Pxow%jLz0&=O z(tlbGiUCaI(B1OGJm&LC^I@Xqv;IN$$lgAmlOfifnVL|M;Wk7l;o+29$6_ zUT%_zWm-4?ts$;x8)TdEuAnv;&K42A%)__45A~NAz&r=E&U90j?%M9Q+b#g%ogRGu z3(3~&h5e&0+PgSFngW$Sw&nV|EG*1t6mXmPIrgrvYqrSjE1tINlnh;xc;YM9VE08o z%5tm*$EH}<)v4z5y}4%Wn;G0Cr1s?j&J=_F@!7TZ?$zA9lW8GxeHY@du!`b_+;@qI z0~TYn14=#uJ{Je+g#Q+rJrkFg4et(V?+Lm%In(5Cko&hZZGdnLCr;1U&9{(05;PORq|rcaOh)pvZ)RYb+n^Tjo| ze@*0K%OH%ncmp|1yG-kM^X|fhF=yttv1+54DA7`g{{`37C6B)e6o#KtO>;B5c(4jz z&K~x&1Ik`L7Xs3DGg}7u?oFKg)U54ZHMBXdV%}f--`j(jnLRI-LoID>*8!Ezw}8|E zAFcll7r@)U`k?D0cF}XX{o*cg2Uz~q%B0spu8agL-X^UU!UZSznZ?L^T$ zJAlF}?l*nEb)2VJjYp-~h__wS1)fsa{&6Y&GzDlTA2J7CPi}P;Q1u6)KQg_$uIts7 zLbge-vT=+x)I9V)Fhyq6m=7P7+52KwOf~&Fe*kB%>));G^85*@J4>r^mA{ud+bo*gT?6uqjnr6h%+twMj1w=qhb5iwNK6 zohQ5ahr6=^8_C?h>sWtF@Pv_Wedmg=70Y z+WDfGzpiK7bXTnC#qX=Cvb%U(-p_HSF?gWJ|*M7%wwC)#ge+n4miw>-j2 zsBrafI!#F*uk!d%|!{`GD(WOtU^o@xnw3gZT*RF2WMF{-W`vVXC550B0EKuhU|k?I#$*UfRnuDU}V zJag6t*?5PXgm!1^B4ucOe}K)04odWI|NOJQzs$K$0~WVb;A@u;aKD`@cmptIsx)k< zKLLZFPEqb~eJH^*bXDK?+rCV>^RT(tFtVtvo7NZ8@76C4g7nBZR{9Vof18?1dT+um zHq~<8DKk~!yxR4KUF1@DSY~fkPTxDd!WXmr!?)(c$?ImvYjG+Ay>+X^w(R?uP(P>@F_RldCDcZR&VG@ z;v1v~V<&d3urkPg(Yx94P3P%$&PKfM@zi1+Ewuq^Ip<)XPqd5n){?KuCucpI@?LSR zjPC-WbVo`Z@9ueeBz9olFKT!|0QiuqTee5a_PGz{VvgH!0o1q!p>3aq;y{KUAY(&4 z4wXKAIya2Vj$ytK`%e>+PG6hntb$EEI4(f;_iO%#6CZ=yF1J3o4U$~s;Y?NNqk5t{ z?VX0rX_w_<&BK~6dH40(La#;d`CAu5yhZQ*k1tw8v;DW(7{nU7IhttKl=_&!H|t8s zrQ7YP%YoIVr}N961a7;tA9Qu8|07WQuy)hlEz>6ZE_8Q4W>2w(Jv;PUY zmmis)Zpi*X0z@wWpni{z_HgKs`O~!+(l@xKfo|Vb04SCc;32yeK+E}aDIL3)h6g?YP?o?+goDebsVX)(~9n? zrr6xLtw?vY=5~}$aWI=+`JukX_(t-`o7D0YuQOe()BUD+X-@wa1VJzQO!zS+~X*Y9(+ zo_tUIev7+P>7Te}CtW$QyNbI{S5n{7spNn1m~kK9PNaWZ-z(~N!TwNUfk;EIF5g4* zsb=in%1Pd~$8z7R@|Ft2RX+Xolfq@!9i!_%kvt0)>(P5%!h)^JcDlJ+yOix+HZ^vc z3rv`D-4BanLQ<0J)RJiY$AjfiT1D%Y2dzPe&zN#g>4W3SFN_4jb@FphG2`InM0r8S z`K70IRLDclrGl+fRw8%>UU`q8A@nV;?ObnH`;xahl#6!V??kq=P~Ky)C!>t$dS9<) zy01=LqwY4`bdkG0F8Q2)N}QXIda3(@R8D}zEtNY^+)gKFaPxA!dUAhdyx9JDmuOg# z|GZ{$e+hdVjLxB6G1ScAF)7VDM}vuJQ|qR*b9A?-ZJ!vmy|3f1u5bVI+SkKjE*{#gLxT{QYwIs>~wQ96@yBng`um42555`_2FG9nPt;Wpw5&$Z&U@zzxe~Q9wV6bzfzeU-Zhe@ChuMO%j{l-M^^dHkW!@u;!r=^ zAPxeRxPIT(Z@jyRy(jyRY?tDtCPVzvLnQZO(iI3a9w>00?S#CLKpQ32f6K@h3YL(` z^nnz9pHlICIZ@fZ2#hb3cCw=0>5!t* zj#4en*h^f&RcA-J;BWrUh=Q70HOvn=-#C;ssitMCet;ySBP2I@(crpG5`+=-exnp} z_uG}y6PIJPu5Q$~pL>+r-=)9SHQ)3Kgxp53>Dl`N)iGGje1TMUNO|Nox3kkn$apEhrCc6;y0c$@=(VljwnO2y>(DQ| z4Wo>M5^Tq~T-OPEw&>~ko~r)&^Jlu+v_E+G)Jp`Aj=x!B7F$ltxmnW%uL2}9Z5t2! zyh@F?Cg$eD=2bxRyd@-@jx;qkp<20~YB-s!lWnDvt#6GDpC+x$X)>d1s;^iv8he+H z^hmMK{wRH@uFbLXiYU>wkj-9VAbMcHyKPW=zXhS*R+|&ahe_{D?72M^pHf5*1_R>W z+B$7cL4i;*+8Shp>q7syuACbjqEQ{7?ZT(KhFLjewLausC(a-VNvB+}R}d6NP3n4c z<0K52rpT(PHBN=5S$x;$ng3M2J(Ri)kk_Pk)$5YPxam{%aU8w04%A*y(4h*zf@se0 zS{k*lcWs{@^|4kM)M@Pt?%zzcp1tc_=Da_^zi+R%o$~-TK^{wiSkj{RK!~}yvy%@5 zo=L3gqf=9GU{wPHGF-Yt1oXi#`U4-I8O`)kMF?|GQEyb=W?0Vk?kQ<%WY5RT|2lUg zQpXePD=c-lY}^bPU=xN)X8(jaIcH6sGY4I%YPTw^LW?|H2AUvG?fniJ7Mv3r)i@!^ zfP@ytz4`5icl^=Ny(0V5`dlV2KzyiN6c&F9*|e+UYG-LR$Xb?vEH~ot`5p$GAe4)X zFo73n`5gjs?oNsx)azW_+|PNefxgrLVkc0-xv-`9>64R>AG9@lO9sB->{SLA|( zmqWN=_Zbs;tA<5P|BM~%D=Odnx6obBo|+9t9Q1GB z^tn|Dq8|}V$;ruyHn35kt>~nS;jrq}=(=EHVA0$0r+E#PKGAh9$iZjVF?(s%J2)HW z3h&~1r?YCbts1k2dr)YLM&p;j%#_H?$@{zF_wUqEZeY<^0%)RyV@0oCv!_G?Q=l_I zt20@y8`)v-^Y`ztSl=CEG>x|;fD(vbTaN!_ivKbo@VDtA$ZL-r0OCYV(WCg-0o2|z z`rwAxk4M5)KBW)?uNP#S8!JtgvsDcHhkM>NA8X%LOjaAGgv(=A*3DMFYl%)#wOOpQ zrN?^qw2G5qDzve=!pJqk<9xD7p;j-WtLj!@uF`HG7@g8yh*6Sl48QtsqpeQA3m!-X zk2CCemsLI!{%DD0szPslBY$v9AXUC3K)if*v~=5yk9YsTJ@FMn3li^|)*e7KH}SGx zN92>N9lQS(>bi39kE~dv!X$MmMl)$frLGUr9NL;KL@|@ZfjnLIv)C+L?9TDQGWFIY z;?~nL`$K>cDda&6k5T;A0y8ME!tb=?L7mbEVD3WoC9(cTG8Q-^(rMyFjDUdwAomRz z0GA^g({&;OSqmBdQ|-Yf;}GQPU=i!ZjrrXVxSqHD5UG2@M)6kzaJ~UBwodLu7u-fk3 zoV$ic9J)=}qC&mAn1!Kw#2)u{nUYaoaEIJ!^TAoSgRoOU42PK7r@Nx;Y@SNL@y1Bk zG|uT;ZVr9&Hd+FkQ(PB(iNY<}(ynk`HGA`^dewjwzHNO}3)ftO?6$i$^z80>zHhF( zu?ZDuvf8BaX_NGQUAJg48+WaU<<)nFOb0~fb8&vxSV2kA6!uAf%;g=^Odahfg| zE&YiuoV4>;k-1s@llOI8w`)#o*nLWyE3Ll9l0;+`Xjuc#Wd{3q?>IT1mXx}0l+zmT zvMW-z_OAL*4QlJNt@rS<>Q}Dil1DAM>gCtfWl#o{OuJpQud&T-TMMXq$8)soW9p{|Ul3n>R)^kXKbaPHwX z=x6a;kFK%{{kx--t-ZaC(E>RhKE7k%ytUG_p9ByI*Mut1x&ynK;y7Se!%@Q4d^N@^ z&oO?uFe%sk#XX$wyO=j;Y_wALQg=MFh8ULboO3q+KslsUK4`2T_C1B(nNgrlsX%|} zuepFt-JwfjinaYahiLiwG`uL>9fZ+pqL4>JaUf;dC^slMc}o{u;<+*&dw}#x|1P)C zeCWP_u)gdNuJ=8LXI^c9)E1jzF@;5zM|$~tCF&Ovd8TTCBI&j}m8C0X5KJ;Eu=}lt zW~u)__zh1{cH`AlRm&;&5ahd9zsW=+hr>lLffbv|8+npgnoF)-PZ`hL)+9Mxe|SN> zYMIeOy}5wH3fi1=PZEay6-P069p;Ji?y5o<$xTsAT1ZdlyZt&Ndp@9-Ie)li+R% z?(Xg`!5w<@p7Zq&=pKF37mUG%v3J?3swH!+Y1MZIaMd!qlJ~y&>}Oa2N(3U{nbkim zSQWAtPm+$J_+F$XzP>zn{e@%pGX-$WVj@>){36LnJO2G`wSD{+&Qks341~5{%H3Bn zu%@WJ#CmV?Td4JqBst^idPI&uCEW+=%i$q~`?Q`d==;P;QFZ4E_?#cPrx$1FvR!Nu zM+)y-JJ0XOj_^3e435EB7B~KW{G!{bW2u>wEH=)FfYI_svfzLcEYVY*O{A`1rq*Qd z{Q3lz_*a&l$7U$wE@lL7VWVy67b7wc58Zh(*T(Khz#9_oBgFe5??Aj+=FN^j((z1- z+sV8XgTH|Rskpc}aO;H$J=X~lvUTJF+q+Lp`?T*WwTRr}?8yrywr+B_GDqFHt#Xd1 zQf@`)PC)t@?GlfH1BTq;A4_XyN(g7+N z!|Fp?S?7_f+iT%4Or5Bx3+KjJP`CGfil~@6mjQQmc~g^3yx z4D`ba5b{WI%I?&{3B?Tosp7IU$d&XX%zCu#PN(ZLT+iYy0{-SO$cC(a(8A2CLk;xp z4n7i0uJ4s}uIDy95ejTNlU_kbM~=|zjF1_??&AA2lSfTSX#$F&1GW&L@gX|p#VmG? zOwCv5b}h@@H-N*Ct`0US%&|V-_>01^KrU?TA9^r5ubuSHpY8dn*PP8-E6@B*Fp&`X2!pLk7w zjObZ+w>7S~*dAtRcPmc8d9xQjSF?*~rSIH;LF0Gtnfoy_)RWv1r> zY_HHp^O+8l^yv4&(Rmot;_2y1Q-Xs3RkF(48*rB~biTh{To*C>Sxv#-?)YtE=KYwA ze*f^p7ETSOeb#vxwGb3jPkTXuC+~gz3gJV3?!wcy{HSp9d2m=eZA}+9Ro1?t0jc@dY|(2=LVU z0?WQfN%}Y_imL)gp7!}aBL%Le(hu-u%bMM7>=Dc+q?KcL6%~aQ7gLk?-6(zB=dFNs z@iCD#r&5N@z)b|l61A1zSzGJ81arF+XWth9#6?{ewvSBNX%BQp~C-pvOt@ zxE*6nS-OH^r~!o{vwjir#1rklCSR9H0MMRssefm&GZq$P9LP!Yy9N7Cx`rv(EY| ziYtk>>nsL&moKU`CqjRP)5@cvHsHyv;6yGx@e8YjVrze%b zGcdOEvM(3eOA~Kw7ic8+QBEiNcV{b-XU#bC!V4aY?=L*Mmye&9I+n+~r3@~NS(QDu zQLJikfupv!w$Zo`!Q02j3s^KdIyz8eqdO>u3P*HRA)zAA-_NvL@_3a(wq@s?pzq{n zk~Hwq&Zk3TMT^X%%!38KjE^N6>JIo!sOG%j%RjMozk5AFfJG1pK;(uo#W%-Ta!WD7 zL`#II=di?m+WFdpP5}=cC-H4q9J1p^u0p4YG(m_Z2in~7cqJ-42=32mXB9j38cxP zb{xE=&D`N-{)*r>8|$0sfp>-X!}z(Eo&7UfV_GBKaQT z`NS?13)9D7IfhP7HN~Hg*{RyqvN5PM{dd3layE%*VKBdVL%45DYNiZkD+_Rfzrnbv zlJJI3DNP)?ld`a<5P8Qf2ZO9n?RIocVC@5_w3wq2LdufX+D1TTLbr`@Ps6;&^!+Fb zk+3=Sx|V;>@7R?0fE?nn6b%iP+!7L<__o>SSlKo~hA#1$0yO%B|T&q6&|%YY%Dnw=|DFX7FIp$3Di9Ch5S_wM1c-rB1~Qy z^lBpP>XC3TLx!fy#Pc~rc`|`lHD?R+usW9QBL4Ik=E;nUvM{rhCp-nvJYEgWi%@J1 z>^bh(3yp34Var}M7|r3Pg>>VWpuqWbXkT2hCMlXcMv#g#HfYW4SlOBU233kgNJ}?c z*bCuF6h|aPVrt_as%h+M$W^av0DC(?c-bp#!d^FL`c)Dypb9f$MSdqy|K<6(l*7sh z;a1R&tsIpMoe~`p^B=oY`;x?}rE!IH2nOPo6Ysyrv+Q56XCn<*alE-fBPHDKjS+*2 zUu@|o3sGSIwG!WOXO>-@nJKJ^$hfJ{J_%ItLE|kOtZ2nA>C!%$Gg4#AFa`o7MO`I1 zGeLN;^6`QJJDxz9q4qUN2<&iV9E9r|%R+GPHF@vVoa|fAf26#_i4vsn zp9ptg5G6VgKA}@?x@_GoatE}h{{bbNq-XSa>&gGm&J0Dn2XX)IXB*02*X)}T!(O%e z@+;rk22(P=e&@nAzwbrBJwES>ajUrHbKY?>vr=&vCcA2;{N?EpiLpK5xFd_1HgO-{ zy|U{gp24-auz~23JlfFg5Wnj_>Fzl(GM{o1-#uEt8Pd?~+c(tI0d$zqZn<5`Nb-F#l~UH<^ftm>jn4 zVf^~Q>3+qkQB6@p@J7o35&29I!&HU!Dww=%RXeI;>&vaXP!96vl&|`fu0#iq5~Phdu-H9r>?OCY?NaK#9~T*%(|Z)}k>l4uTgJJ6{*^byKusi|uWu^bYnKBIS+xaD^pF0ge#q}ZQ>I_RDc1ENFa-_7{QaXlTk+}Z>80Eyb7wFTQY!u! znq=oKryH4G&AT=*;AgaVTl4%eTwjH0 z)w7PpQ>o-E{3DxazP$nYTc0A(cvaYc_#V3j3)?af%D+iyjAU%w_M}Hq^?L!dW|(@a z?M{4ngaIk^&7);UcL;aWU@?+%Z=5=YSSxFHjTnuEJo5cyI$=|5yW4RHQW z(|td`*4H@#7IVnZe~;l5=Salf$bk`!F2pzC19M{GIDWtVRh_$Ael6@tv~B}xjwY`+ zq33aP4&3AEXL)@q$om7 ze)nH8mcSqBX(}a$Qny8mir+C2(1SteT|Kiut&T`@N0heal_eYPiBdIw^}h$I;nHGv$}Jwu`)x4&Fd9`9>!H4_erjAQX! z3DT2rf(UAChS6tvTJ9Uz02&K<9%ZHsII3?L@Gw!`>~*IKQ?VyvB1O_bgdK@GJ{=AN zFIq3;&L!KqNZTM-(erRa5stcD6rb)N1W<>Hnon&5ad7f*5)7pI!x2j{0zNc(#PmdY z4m}X11LrWpkqqfDke}X$u~~lQ@WN`>Q-O^@Oi=t$94j-LmVPo}C84EqVNVjU3jW(x z8`4Oh$|0N((eq?`MeXvD=FvC6!YNlC2HlV9F%nj)^ zxD>`MNyr%>23Jh9`;xyvg$8%cRg?ko8UZ~`K_O5;l!EJ+Ir& zsm=DnBvkX2LOl4_a}tt;k&g5+daPr9tLh7y}#By=Q_TV5_nszfrQ|VQF&MzX4 zKm8k8U8{c09$v|&sLeY5+r8&e%1MZZ^4H-z=N`4|U=sSzcKIRZRIv4B3*RFltNUt7 z(3{45DDx{?UO>`Y+%+vpj$F=9ZKG^U_F>Zsq?-uq<7MyVt@a4yD9A=RRGQ$bO}Ez0c5#M zsQCRX?)fo_6|r$7a}7ZyUtN{Zc6uHeR?gQol6566`e!9wH*YfM4UBRsUx;pu*&zWc2FZA?P{eKPs+7jZ%~yv-vuO(|8Vj1i zZM}8`nVPVtDk(K!C)>ZMRK~bG6FO4gq+IwUBK(SJbiuWBxyK|VSubNTF0VAdA6#q$ zvm59XlO&U%0^cmWY$>sXQQhyzUe*Fzr_L2Jp^*ijqq$eE3|~i_nAwEGhytT>Qs<1LYW zNeUb2J^~6n*osK1ou1#f`1N}sx%qS~Pn@?<`}Qvvxs)^Q{tp%)4*Sl1YI-%Ohszru zGVD`=$uCCp?n^${-R6oVRYN(|T*nw)C5x7gW5+$TI?v&+^DM9X zaGPh~@9>^%51KEkIlHEPwtOe3ZlowQ$;ooO1m>Ql!W3!kT|c$SnqpZ^_~Ha%4>C=9 zHADJX$BbBx8Vlz@&`+4){BPWSUWN2Dhr7NZAwOUuh1t1_1PJKsG73)JpTq=twRKZw zan@QIyO{_kcp_zqj1?r_)MaXkUBijkIdlfA@VV@C9*D;S4zP(pwv3Vn1?E57XDaVq z_bUXa2N@W83~l-^tU#B*Quh!vbF5(&$-O~Tn&+Ky;5$kCv z(VX4+3;(t3OwJITQ0^ws;d{-+(e{>`#foJz!qRZjan9rw!#5Kv@mzEYKbY|T^P$jU zmQ=<*^Fv_-%0$>(_6L950um6ji)x7R5Enh@SS@;=axC z$Dp-Ddc;HKWi1eS;wSNqH<#xl=J!8Dn|FGpFiC_<#DjvkaNNIP;5J^uiwm<%fdcPJ zc#A|Gc=Ybh-t7ZPsVdEurYuUanu`~SLYGRC_)><7p;LrP=JH^ROUK{GAiZ}Xq$04Y zBD|NB!nqZ~2K2^{>4}RBU-~+EpSiz);P8g&GL=u!_H)=GyozWb0ITtOXvT*8v}EB8 zAp$Z%CCRx3YDy|pibBHkM$BbayyyCMQ7o{)D6R%AMC{%i*_vjIAlCb{3}fWRMM=pk_NqN8EXtYbD4R)s%mornuW~Jm{h(M?xZ|G~KpS&k zj~i)-z`ai&zf#g$HJJTTZbN&S+kftGFz6yUYK|$T;Z5;K7>eQ~H zA>;ym&tWUUz&aAP_+8A;JVq!Khth%Y!a{0iF^qn1I)x@;C(lqaQ8(hpWjB|CK4c6`V;CG}CmyT!4$4M^U3sm|N?scb}TxMv@{n9Gbl9%4s6 z=;^uxo|zEaYk7Lfxug0M0pc^?IZ1-2U#Dfx&h1kXJE;e7+%jKq@h8##UP#-s1xI%u zmk)(ZK$r1hKZeoU4&)6u(Dj*4=J&pE^V&93=2y~zhFQyv;gg&Lm@;8RkJ zIIR^i!1>+zPz<0{CFt*MiH9OU92!PeeDWn#8I%((UoxV<9IMer;emG{mh_0hL7VjL zczD;0nsqR-VJtFZ0uX=?`1j52?dK22Dpvyk66J%_70unnVdfonXTCn9P za5q`%7O(C8G+-~4AIEm!6Pe%r@F0kyc~LLZ_sm-=v>rLIAuU!Hm2Qm?eq5PQ%r+FN z8EteDnlH5K6ZG^X{~~Z;bx8l?AB6~`vo>afn6`3OzoxQ?o10ej z3 zO61RD*`!Bs#rZ=UGID1R`nLGHTBuH{8-tJLup~e^&6UCR+G0nB`5d($5*{tXgC-Vh zXts!NZW^c7_U*NrxS9?FyW$3NrY1PBm>F$Du|T=>bUX)&b9lvzbS z-cs1XNfm9Kxa%d2LwFub7gZ%iUO|w2aHR3}Tgkj6+)S zlc^L5$A(XGW)xw8=f(XOHCVX5B$rH^xuN8?(mPVGI`{3&8#7q1F(PWTC{QW;VLhEp zN+dO=W;sHMCu&B&d%d`(fp6TfW1#RC1nbYducf;nKvXxL!RNN{O6#dSBo+FGxXPMO zaM&iZ+?^-uF}IZp;GrA5A4E}iqLD3xG~_gub97|JVv1(JhCl^x?bd1&Kh@)l%q;kL zw`eMK0N}Rr{SrZ0pMb$E9~Hl(piWO3*ccBC(q(f|rNTM0!f$n`&<#~Z{OOzeb8EEG zY3)}X+4LK7+-OvIu)ow3LT^%BZ7bcJik2YrSeRuv~#W8C%S>g3O8@| zX82FWz56EJJBbu&M$WF|nYWCpZJnFxm&pH%x+ z;&J-I?UP)^I*)}@Y}+uah4QZ!UX^}s64HYxuP0d+%#!hM_I`)>@1@?%J3#wk$_5|Q zvAr&cDjQNPoT)hQYZebz7fJ#5jh@xMId({22ywv#=7f{J&5g-HobJCc4#fWltW9ah0_s6I?=Z|RGFUK=YNwQkmj(Mm7w6fgU zvia#!RDXonZ~y4g2WSs45s)oiZra}#h;x~zlD`D)uArtSksaO^=iV`bBr1dhD87=R z(YW0Ske_!{U-Mh=K8p;M6ciX*-+zb3?eRM2wh(|<1&Rog5aqN{L^rkITOdthDH-cF zD){XtzGX*M}eX7Y347N+Uz>Gl;hY#vtO&YV?+D%P0I<)QIxX2%|F*{H+ zIB#BwXMi!ys`)9GAtZk)@9yO$(Q2kzT3oY&56#iuj5?lOw-xi?==$X7%8Bx6nxR|O z7}U=0kolS1$a`gcYH>a!VAy3lj^mdJZcLnPM|!7ze+;z`A{dJYrQ~X|pO6S6QHVH( zVALo22NYawZ#bBaW&v`HQrcC$k!|Vs{61a1s54JC!F#RTXC1;YXqft5I8Qy#Clg`L zPaJAT78vNFt1kaz{1w?=eWpfA?(>xSTi>?1#`cs1Ai>Cq8uiPs5C+NOpKD|As*5Xa zwRajLB=X`%zp~@H784vJFdVt?Rr6&xd;8r;Qr!5Q*87~gHfAijI5GoP4M{;W0g8$P zDmeYTEiGtNH&CQRq=;4+<{^{YzcT{A|AlV!_e$7sHMmQs{WSfYf;R;M%S3@-wmU4j z@X+{xvYOcKEYs+-goHhG#PLmief^f><6+Hn5-BYKQW#F7y1EiC4L)KRnv3{!^TCIQA%4iXWT$SMqrnt*= z5=@{hSf4G!({xpMT8ei!A1w265B5-&d3_EqJRI+06Wd#_h6c!B?bvA!#(Ol?20#d} zy~+}-=J?SGh0|ZM%^7%Zk5z*qIJ7y?Ao>*L$Hs$O7!%R1DLrU5dD zvrk@wv6_r@!QNz>sH1jsQO?`DZSR6)&!p*t1ys&JxT*gAg}!T{?#w zMUgO~?t(_@=P6&Fxku+fzgt{t(;@F^FvL^MK@i1*;$Pv$xEoP&>?CT9Ks6bme} zkQY&t+UJgqcuGC!uRce|&9N2C*?0U{Ky)vS^*?{?s3OxI_9LxuuYdeCU1oG)2QIfu zF+k9uFmswwIOtEcV2i{hVk(G8;Ta;5cfaV~p-DLRdqPWSoT7A{9Pn0vk zWnY+4D zER5sBpAFwwlMb&^40;(Gn=f(p@eAqy`B>9OH*@W371={Nqg#{c8HopuPEohGUy1y} z#IX)lsk(vq4hhB6z>@Xh&kheW@TNg+>{2^cb|8Hpgd* zp>=3AwZh>F35P)#g~-sh#GZld-Es`mbkbgJMTv~R5_LkN6B!3Q=A1^e!i>8;dpGDq z>%&1I61=%SVYy$0?pzKOv##jsv6A^>ILIei#AIG$1(d%8xS9{?fJZxVS4jqLu3Porlmz{f?{F~xc-9^$;1%)9mg{br4g!I2 zMvbfV2cp3k$2H|#DC&1%;yx#hU_yv|g2}GRC%(L-XnMe@S)4*|Co^kaUQYBtxb~Go z(3>dGs5bkSSEihFKxreM8K-*&6XH`|f$B!x?#!u6vLUkhh^zBfLQ>+uIPN`&J-cv* zxM1TfpA;hFVR7r7de< zdo%&#@0rCXlN%rJLrEhsE22piCqvRLHsnQqa{fDcey~zali&N3=gwENPO55;4+H{V z`8hNFz*YB`pzpqmS885q#*Lub6=a5+yS(_tx>4C{S>P5*1T&5BB^-WN5KTinE6|-t{{tR6vLyGS&SY z^K)D_^HF1t48JTH8dWBk_*B8nNt${R>qoa>{wHb}-si(}zv^U5jvY49-uri3Tp%J3 zSYPrqcJbI%60;e#kLyEhp^-?!x+_4X zaA;c74<(<;a?9bcz=DG z^l{?e*95Zz`x_BOtD9YH?ELf}`lE%|4C?u`2vJ{y0sLJZfDHKnY6Ho(5;{7BEiEm! z>+KnFgj@y6WjL+Pz;xpLH=UZ(9|XBhd&AhL?tK1T0lODHO`WQ125}OU(FLn@tO(?3 z35v8|xruVWjBPo77qZ*VoX#=F_(g-~c4UY70r9Ewdb>`;>0{FuZY!fRR z8*X#`$FLCbO_)P9Igwx>0bmhOrr-tn{m$XNe{UomAh*KDw-A!8RY4@*9|7jG+3%UN z$zfwZ2$p2C2UUoQh9&~|Ty#v#lqEZ&-q()>{{G(rTL8V~zZ#_c_~|uf`5$21_D2pl zZmT6A0Kk9+Hvu`})@igg0zhk(`W@Z?5(k)&#N^)(z#ys6;0&8qmOB0TNM8>naa*|o zsXR1zzcqLqloae<29obvX+K09?SF%hKp-hnT(~MW0^r7h{fb}D3l=kq7-jMoB)@?2*>LhT6t4SH-)!o-~(j?G28G@xFw{%%4uqD={&O;Zrz>1oU(N2%KNfC;C9vUZPLwj~35A zF*IIRhK!Sx770J-;7<>vXXj*JwYa`doL_WFEg5^lT{bwju8YKS@cVCL&98#GB(t-t z9C{PF!~KLzyR66&>EM>FxYr{UhAi$!pbu&E$b=U%ym`g)YlyZRGJ{*_24p8)Eee1 zF09fGTCh&6lN?Qfx~s#WA&3u>iSgF zNVM?@xc9t9l$lpxnaRy%&cnV%t|FE&9~V{BB;rIQNKw2lq@4OPs&S}dpA^}L{UC=w zwJ59#>tU|PWZ>zwX)xKSD*JYS38@01sF-k};*!31{*4zg!e0?0kk#Tf#GB`R)#Bn7tg7^Y(TI9PbRi&`4m!XKENjqAbFdF?D1wbZi0gK?0-WMc&1e*J*Gb;xChnuZ58DQwBEH`DV1M83^^~J`+AU9jlJ}QHM&hQN;}HuRkL9qQ z76H%~Upn=5bN!9UQFE$@`bo=ngj=BQMMpz{IYGO9h6688$urNFzjl8+A6ZM7z8Hyx z_C-RDz?s?ZIf?-%K#*-w(We&^ApM2t!NYv+?R&80i&2;MMs&Gzxlxp1Mgnj~Vx3)` zrO_#C{k%th{1t+9i*c0WdGE9J@-oh3?xY)c5FY$wJ32vRs*pMV;JL|a(dm+wtB9oF z0@+x=JB;f+8jcn-nKT+rnlNC|22)&%kT)0ez}t)q(#Rc%j>Q(&w!{fCKsib6hfX#}CU?8(#1?bO1S@G=)W`_k~_ zkwxD-BieD|3I@FAuy{p>bM#XT)6>^rjfqh2JWRS_LB@G;!7^M;2Y9Gv-0IxdHmP!1 z3$V4k%YrSD$*SJYw(cG)??&e^zy*EvB4_~wPMXjQnu!#(QvmSl8dAgTG+)5_Gog%k!Bi=Einw>g0?hbOCbPbqiR8-T5Qj%-B z)Itz^GcKppXxwI3sat0FgxURC&e0l%rtyv(RLn}q^Kt`c>coXq3_-9*#+aLswNu{2 z5=6o3Vf+?dK;+^yt4pVdL#AUk2LsWC#ZanU)B3>w!2(e2#hEdlQzJMO&R%k{Z493uwE_K(#{urIFX&+t|PB zbaeyyY@RslA$`Rm7Ppk+NyNE4M&FS6b!(FbAq;}qpv(9?6IH27W{|^j#Et%nLDL`780h#S6X&GZaLg``hx|A8$M`&ie%Crfi{Z0B)7BJwGrqKHo-OQ~ zVVS{TQ^9`5<}(&P%9;oL|K`jmDL3;x6(uS*WjSa;Wcy9^{VGwTP5}Fy2Dj(tLf8wU)cNHV5WqMm3QZ^8 zGq_TA0t5~g1#L!UP5+*(#T(PV9eptxrOs3~lfy0~*DQk_wm2?WRQPdp=Dxqzg<^jN z*cbX|?zZJX#MuiAhK<1d@(u}SOiC9=@H0c}Pu>t@E#N4Vsofd`BCi};>1Xb#@3*UR zHW#r3YPFAepgwSPblhyBT=F^LA71euaDS02-v<*w{7XHIVa|{&=@O%6j!!+K%uHy= zaza;it#;#eq>ID4cR_1BVQQ0#1jq!nf>uh5ox5izEfp=S>~og)yjS9hYp+x-nc;>F zCQUY_dan)QW%b=zW8%d=u%aW?0>Q*BS79B$AWh{KK<*;qN*q{^v4wfVkynIom)#3& z@yh}LnTnNBmTU_pYW}S)2jMq~H6xsMtxkcY#2GpiNUo-p#tF8ctY+45o@oa9yr8DT zxOE4nD7r=$aS1?%O`&?Vu6&VSh^ir{c$M4aVg{F=)Ib+~cszr-prOg`uQbK1y17PdN6|8nC!Soum}?Zm;J8q3-_b9pAj`>z;#&0iUX zu12PKX}dG0;#qE)Gt9S%IR<%=rn!20$svK`^8?#X1B%5Adt3E~+K#@UpHqVu$p#41 zgvsm*DpaUcs!;q>=~QVJac$c=sxbfy9g*{A1^T0dofRHlah<*#d&LXiMhOZ*1&{4! zy*>6EQyLmdQoH1I)RnO`PbQln2172+1Zgoxm!;ju29Ld#JKc3{f`?M$%8ep-6%fdZ~FsEGW5! zLK=L-muZu#DtAu!Vo$KHruTlFbh@y7&uxk48yAeT79Cb8pDp9HCI1j?Plfah5#V@EvK82OKk zr69Yhu>D``YzqPI37L+sft>ugh#KGUY31Y}m z-9`QwalLUj#%lljJmAITzbTwHcuIol&9^}rf_r+gR|*c?zh7;=OZPkL_pFrVaKAaM zW3oYn&iAnl{Sp|CmhloA;>0+c{Pwogpdm+}*R;r+G)3T58)gRKBA~p?lqio6{*!Ig zK);G*WsPUL*t>P0B!|C2B52JOFQEJTCCJq%>v|$@k;ewi{beMIfwxMJxh7A>nQVTL zCfU>9bL7usoxdzagzK(ip?8wFvcOmMv`Ei0xW(4jr7d-@mcOB`9;<@*>3nWmXE)1B z9j=HM%R-S8gq`Lm*{Ab3_|oEZrc(1+QjKtg4jOPRjKW#oP6-!H*R$*yt4dLydT{5w z$oO1IHQPg9AS}#~e`T9L*Tp?to$-yG|MVZV*Y4}67V)JsU2NpMRSq}3f|IuUu3!fD zj&`wx&$-2Illz@L*xQJ{TiZCS$*FeWPCqF8hq=#$pIuF<+^0Gls9Se)bxvtU zeR)|f2CbwaBrC7>KmHWd4II=7Ni=@_oo-KIe$u3jTMyI~3ylbTzA?78hZgSj+VQeA zbN4*ax&sYYnP0g|VXHTDb!hgv{8i}IHZr!rHG`G9<-t<7of10@R_K#(Z$GoHTY3&w z9?Bs|n)&sw<9}MmoQ2fXC0FOt_*Ynf?ERH=ITa%bX4Asz>?w_l@O+Y<(8h?Lgqb9h z_LbBnSv{=1bi#9mlA+SzL}TTK|8fsskDMcVcLG+RG<+5zdC}Jie-@G(qFpmS|Cxxj z=z2Y^ldLTu90HEb#`d=XOpABU{F3G!1z7oyy@!I5)%0Nf@w(9y4FMqUqHpZxB*?1PiEp(PcV(MYaB_Vu`|HMUyXpZq;$L->R zN&_M4t$*k-%v;ctrU-pQl0WUt2dV z{_30yJ`mJki04b+@MnKAF3DV2bvW&L5b1^%`uhMauefBxfLf7vQ<=FD1swe3JJblH}bz374kh^=iOf+ut#st2-%war1D8-5X zb}c&N6>%C+cVjEbQo?@rUVK^}UHN;E%y=WhXv) zcI=9P5rp|&b@(e+3>xVhsMZPUv|xP5BMav?In-_cUEfBElWpA4&MrLc-P3Rb!WZnV z$3VzjoDGU=5-{wVFMk}D#Cj=Si~kaPuFAg}sF^+dakcdwJt2*u-lt`Ecq`CiBqKmk zV`tx;^{Wt_8r-!;4S#mH^a#yBjn8asVnfa^K(ZtnunkTi-MHozI6*t{A*6FP=FnOvE#*!8I`&4XpWtCOT^i`|+wE;r%gHxt6>S5dzvj+X8bMj-=p zGqc2Vy1-oLw}UBgl(LY2#!?FLx(v$Acn?c{i7^MIfgEVNZ$QZwbpQ1LwVtyqPFw3_ zZ_k7{z2l8=CR7p=>{9)X2rZZqq{Q!U!bO_-(~>F2Vf+|@n>5pF z1s(}cCFzY)pr3@EHkOHlf!O34RM7_ahP2q;5Q)H^kR<|nQIeG_4XQms5g%Yh=j4b^ z1r5Z6cW+aC=^8#!5W3#U;=nO4uC_*S-U`fd=-RIESd!dveNcZ-4tRY+6nbxF$ww7{ ziv5+YT{lc7jq?(7BiCeni4MOZu*He3PqtV!wq``pS|(DK^8NV*>hFYT*A7$iFzp}L z*xp)P@Kk5sJ}b;p(xm0|$!gX*3=98kIq7jUL_Z8}?lxYe_NhU+HDjk4p1ESqDtQd8 zV5hgdfY)JWp?Bf-3+|@POTxIa`Lcvf+SwSdwcH&u7M#O?`av9Ha$C(dWswDOG1f#P z1ObM~b8%x2x)_lw*2o&Si=Mloo^2!hb&tBZ);BmfwwO?dn^fe4l`p_Sdn zCP*IW!9+P_t|G3HhqYfiKIyli#gfB$u4-+2^@O!#%$oaRul>w5WO{MVEtV({vl&!z>oO-Y>gw<&Xz&z<=-$CP#NuQauNi05qQbv#7eFpn6b z2ZF0MutHUvy*tGDVbFv*zwMfs1fq+n3M0tveM4BsxFHxjBWs$uH{|MPPqRgOw2y6;P&@+3|tVePH>`<^q^a+?wvOi zYWNTIbBeLsavy}Pj-}RI^Ly(GiF>}KL1|GM{l)%aaeGVS|8|LNqr|K(oXY1GK&5HR zO%(FGtCnn$w^5vsc38g3V>3gwX~GVwLT$G**sKrt2Z`cxSP7e0vFh^%|0c?$Myecb z;o1Omzt*LW$mitsv8zuF2|t5gmk2IfE}>K$eV*mvv@3%_J*UkAuiCTA4Y1l9Z`Fn_ z+%WbBIF;!u^ARO+x-8WE+4?XU^k52qOe(()OBLFywxaUf_*~@vAf;js5wewC^U->H zd)^JIX}!F`R1`TJ&Rba!a%nHxLDD-afvpw0kL?o}d3q*&d?XDp;(0=Wedmj`t@HIW5!hP-v<%56?U{-wQEQd@G!t@YfX z!&W!f|Hau`2FKAX+oD2?$+9GinPoAfEoNqBW@ct)u+Tz_8Ar^_%*@Qv2;O{q-+j+{ z@7#DlZbnbcM08AbbwO6u%3PV(h=DMl>1O9wQ6nJDXS92gQ)|aj>gL#>%zt;ep&ym+ z;`^7iw7JL4#u`p_EzkS<4HWs6yI0tZIoyoq_J#>7iqGu!x5({aYWeir__f(!vaF~F zZEQdSGbf&FG%sb}PGnt^_WV=|$KAx_2zQ&+aZt0S?Gnf zoS&k&)OFu#kUii1ZEalB3NMyna!}eUwX^#!+`fH*SFX2G&RpO|T#Ir+tNpS~%zDCX zB~YPSAr$^FiJ0!?rdPYfwUQ8yp|IAf+d$DRaI9qw_m zX{+F)HE@}V7 zHPEw`nYrz2&M`%eN0>u$7}cM@3RWzg zluBD$idu;E;LQhP%dNUF&ShWeNkAhgttBI_TK>&6>{cTb63i?8!Toc5QpliwtE+4w*8U?-$X%e8W4H?-eZa zy0%7m8*2x|uloTfvWa?qj$E$LXRth!grmrOu$XwA8it_jCqP3akw%<6L9r-US!qT- z{?^M|3+-hL2<0<}s-e@2cT=->Im7j%o9%?NT<_92;j!604Odycz+#-v>Vbl$P4sfr zc!xdHx@Tv)@#Sj37=&&y-8e%6381T}*$NE?gNjd0UWfPh(3EgNOF@Kg<B^8h}~Vyvy(882y90Wsa=hx1-Ta1A>999Ez}@~ePeLX_eXD7aMSoreSo$WaQS!;l>~m& zcct;E{ZY)KTIn{N>#xEnY898nU-c&2f6sfj2|1f6$)#4v#bX9#ig7DqlqNCtvOHow z$ID=!&PU=#;WpIeVi_uK4gT5DzDHn=x$;iGG7%WKk_(4l?qaXMxsc&m;QZm1@32?^m=6tR&2n0rkoRl- z&Q`(y!IwV2n9fU)W2?XApv`74%I*$eHII5p5nLwBp0h{ii_py}5DhY{>W^dy4>9Ga zT~_8~zP3#7bcS@jSp3_;cjy2aW|y68K#TI+ z;(7l_K$qmh)_nCDNX+TYIC$np;J7UB+P>5KoSfmiYR$>X>~o6$r7HQYpS>p!x+PDZ z_3Nd!0O5!HYl&IKX5;NVz^jPVcW?B{_*mkeIWe5#fNK6o-T4z?}) zl7)oOk6fZAq4gHL)5Q%6O~P!J9nQ0L=D_ayG(rs|M3xbgi_QW!hzEAjwHR(1H$E># zEu-6X_qKqJfnR1vk!5f#+E4Wa_ngy7$M`13qy<*-d5VlpJ6;)tkFfyc!AFLNSQ}PJ zos4lnvC(zaJfB3=#7-2O-0`07Xn6g?*3+<+hvuKZLHy6z+Y^okn61650(7O?X zCJw-G@~B@Q=ZTT>`fQSgpfjU@7-A9mg%GL`JqCzRbA=k?CmCk7=n~ebXPFiToJ@I`^*Jm32rb4uhP(@F4J*;5|nL5vcP!7|DE6~h`Zn%9(Gu-Gv`z);GT zghMc9hD20WspoFqfC!IaXE4OF(4A3rZ&T*cw>pj3TQlcfkDg2NZyNdr4wzd;>m7+Dsu0dC6^x|l(yh^A|%{h1UH*fkK`URsRx(?{3hveD_dx{bLGC1g9Bi1<67lCNEtT&2~dqpF&(!?#%+_i^xKyxk*WW%PqOO6>&O`Y*Q~U^<>l~gc6c8W zIhZjP>SSn>xKAeWsFmqR7n}WgEe0D`2GAi8N;98_G3_)bjmt_oa>eWP_WzS@!~NVp`t+3B9Uw(I1wXBGpqPubo9;-qNvLynTUNM| z=yl$+l4EyGWg z!R3dygw<3wk0i8r4}^h&`av_`@EEI+{)i2%#$mqo+2VAJb9}Ce{_929AeVy^w}MjT znDrLg^>OlfI7NsIv-#$b?P}JG_UALWz*7pM*%f2OJz?R1*?K2&~4q76W>X*4_jVk+v ztg}0Ok$Q>VpO^ThT9+b?&Qn52tDR0ANWo*d$iGdjF-MGx#+(NF{O&j0`=A~WOdjrf zeSBvzQHJsG;z!P%7U7urIu782V$>hf_n)Xc@zP$+@-Nj2>2TmcUaZc%x}jIuJX3Fq zN1WL#wuImP){%PAB9E6As4(CakAAa*+mWpwJ@@n24oF7 z;)Av?XVn|>$o58{=vO{4t|^1d^h9{+kcij>L_KbCCufQRc-glE40hk=j8AVuO3dFM zmF&dQ-8zozhr3jL2gvt5juol!$-vQ{*@`{W`?3u046HNpw;>-KDGid}V*Dph5g2Fr z^CV2ZnWsF8AK>^W4Zp(w!re|c@v-?rE6*dDSj8LNK>)WiOMsO4u1enL`*Ir>G&DRR z&?3b0n*NK-&7J9*<#!2nr=0I$jXJ(T$?E&aju1=YWycafcJ5F@;nmG^4~N6<*Wawl zNHU{!Ud+PgTQm;F+HsMToZG3;8G^Nbd8?`L%F1BiQ{yIIfDwZk19HpNQ;bw0Lb5Py zdcdsn61j6zInFDEHcUCOE*j;?_p0C!S8_3jiWC|I)i5UD%wNTer)$-O0#N)qU*>=5 z>)rr9P7*2MEHEU;5wanU!nOeq*UWu|jQVwAv!}LxtFxRn1rv|smEoPS71$r4_dk9P z_&74_BQXms<}6wq9wIJPrjn=db)DjY5MAkFYOCJvYaoRxRFR-Y;_wy7LSja@sv=uA z*yIU_(~lEGN_sFTqd&mh1y*XXt*F@EHvTYgI=s8Rl7_Q6rM^73?9p{$~F zk21-4a&q|MD8Y-;N85m8P}rO_mqMwH`|H{QdSWTWX}Z}GpYC2Hf93eh%m7l?31h1i zoYxeqo*%`()LDtwAVK$6ee&Aq_LN_Wlgq$YTI6@%VjXs<$_Q_I5)Rg%`ZQn74s_=( zxZ$49@#eq9vv}VvLD<5;{$bl3v_*g48Pf)-11e3;UG+7BrD%L}tBd69X4e5w1BX*- znq5Ywz%nTf{lx51-B1^++307RYJB(>A~z~J>-DB2>o^9UNlL#IUlCJ~UX+0BEPoM?bC2>zAbeD4F7! zcx-_K>zki&W4wqZ#j69;i$;ODDK<{~*Nn&eokni@C{Q&UL7}i%^QO9k@^baa?%+$A zDn)&Y;G-uT!_?EfRyU!}&ykDkhppIa7~YnO>15huaz5M^#>Vc~ZfPe15(J2l`>mJL zWl&Lrl1Y|D(dOE;JBZbF^Bidd7tss_GLc@?J}Jutrat8EHZY+_ zZ}G=&3oCXZnc~)==d#$131(+j85#aCFfwIFUloN0KF%51^_G@@L?yGO>|SD)#;0Wr zBbb(4&4wVG?!ong=7uHPt$>frNq5xJUT<;ZUo~mU; zcF??Y|7YG!``QC!J5&q4s3)T}Q@0$7ThmzEnW17pQ#bd8ts@66M9i7YnY3;cZpwQ) z9xZ2RtdKDcUvu}-wMgN4KjT7o<@&FITV~%Wu3U3ej#pIZp2fipt=uE%Rt|eNtBInq zcmo%hbh}WRg??J8a;1^s;Ojk^WO*ztxJ^~lB>>rjDn{^Z-edBY;)dw+s8z^HLr8uz+h~uOwPqVRDvM(gf&o zJT)+Mo!{;FJvm>qc53L9(5L=Jr1>pX|I#$Ixa@4UKMkv_^}$GzP3(7J8&hD%htBk0J~XJ<+Kj6O|eT9#Zqy6 zE36Mpc;AeqZ0}uNCE>?)SIbda=l`i_m33e_EcmPo;bqVA`AAxIZpOUAVk{y`=k`Id zeJ`e=t7p3C)4_o^PQkyMGZMc!MaphG8j{1J5r}VRo=}wXy@xn$b8R-mci<1-Pjk=R z$amBA)vlnLXLX-!|9yHci9f_S30UAz=bNw$dsgGEKejc=6(tj@ONT@77RoYTyx`7z z*jdD;JwYIcvVC8V8ds0w2rgB@ z%VTy`5kPXlm6++CTJ=Ra5EO9P0LIG;_|4M>dW1Z+!wmywoe)tKt zc)OoahrAO9#|dlNoq3ga!$d9a6t24ZL9XmL-N=W0ii3wl(jaY~g`xUY*Zh5LJ6)=# zv{?KiS3$}1)FRu^)Fa59&OeBKY|LXnI(!y&gmA>X2Wy-;n7#p82Wi<8*m2-g&We3?MNteRqNWw zCso_xqy8^%FihADnq$}Ah^J>}YW^c`e!(Mb-QF>W#n+8))*Vi#sjkBUV7xSi)Gte- z6kNV$X1LI5K(BY#9poI-W;>cQAALD%VO;{LWcP_45rN)--b*ZB3+b63q4lpt-L7Ee z(DuT-VG^^t4{HF&sHkCfeCh$L`E)Uxe!)l~2&KBY_Ivv$%=qWqCZU5}gVubx%4u0B zk$P?GdQ0`zh2tkfkw)dLwN?#RR!gYw7URKcmfy#3yEvR}jl-}w4z;7fe3heoO|b>2 z3VMz?Qqz}nxlGdz$&S)|3y8plfU%1K9J8h}l`C$F467}e-0+}QT7=7Fn?HuO^0-0bwv^KLR?ThSY{VHSOpLrvwzTUwR-*7 zn|JznISKLYFK@0w<{)^g@!u^Q=X53q zsS{vQkgr^>IH;Y3qV1w=@`41i=)LoN+r+rMwWSv+_qrZ!b)Eq?fae}keTVJeuIp1z zF*-|dLm3kxYezU^l+CTht!__i+nx8<|6r+4hZ2-iKqI9iXO4ocvy14O`>WQHh5r8i zh-v=MUfrrMu+M3Ra!=9i5&xDE^!>O-!_Rq8_tN5MzGo#_hZfZNqBtA-w2-M$fTWAO z(iC6CMxhcfVdQwlANq><%;`|L@IQaIi@;tMpcn;sclazOarVXfnFKZFd2|neo>;3u z4%}G6o2UPbV#FY>t#$Vs3I%1R`nQDkBAyeXyAtZ!3CZd2J$}^<-x#K_Gc+{3<*eDg z@wicEg(}B)v(H)X{hI-hu_an|@F+HK{IN&=qpsCnPG+X5XOOpIp#`it`d87Xlx$i7B98CXRJbKduI{w$Y{ilHj z5zl4*Q|*6!=P;V;|5MfflG|V=NU#5T7U)+JWwb}!yUA=OfjSyv8`*p zvjE^rti!=>z<#ODNX@$vHWGuCK$qD^0?ebLYi4CTywcRmQ3;mxXO-UFPi8|y$K3R$ z;}MbzyLy%BhYgfmT||Rsf<&4yd><^2KEDA!v&?5ZVSq;f*~st$%|vl%sQluIgHG}Clp~oNL8J6*PUc$#E4RV!;2r8^cp+& z#VPg42BJr80Q9{{=9m~{!Cs74$*Y> zdXnlG_f;*Kqe~bJ^-^X@6?B4u^f)t8uk@A#;m==jw(qA9TTge4UiKL1dVE~B@f{tc zKKa9WGo%M?m}d`JUoZr+J?^tnTK2H(vp+pL#wGN)U}u&EJK(JvlaWOx!Y{)G7l+ZC)bjO9p8ariu=?cp2UTiZ zA3Fi0SC_SH+@; zoaGC;%nM$yqx;>qOr;mD`!wB&Bt$}}cLcXTJ+JdiGsg~|ZuJn}0!B~&N>};4^1IX> z$uhg1eswf@Qxl-GIW01B?eZH?(>BV=^FA%^E4tmO_qk9(TviyLvU z{^&bSxa^}mEBQ0}!5?^?cQMGf#_s;@_9ZV1i;5i#>P_kf9ON1VtwuFj4juR5X9ew; z0?JGradDbHKFEAMC1CXU|o-*hRrlJi6$EcC@fDOfTC&)Y~ zrZ07TqZX+G&pE>FH>*^ZWAWyv(&iVc*}Dnz=xiT9zdxWmAJ}<1-^b8Y!2l~t-_5kM z_U|4a_0omP(^)+b5*0*mr?aU-uiH?#{L~f%elmySER!;Lba3*ubXI=NZDtPt?azX9 zwD4AAVg6egndO`iGXaMNhe$o!T_}p~2gBE&-{sGf=O4lATs69AbDewzAF1SCw2N0g zs`Q60Z%`2#zD9jvU^!Royr$PFUZ^;=SszY%D~=A~f3Q{Inz&4&RgJfTFT2Tw27cS@ z#*30d2wvwf8(J%x@*WO1Uu3khGkX4wfjozeEcF#>k65)NZTpRxwzj()7vXn`5HoNn zxezCk9#uV?An=YU6;truqw!+}i}L*Hh$@m9N#(2^HI74^tf_w&3TCg|B;gB@yWn$} z?)T&2HrIlfsrs#2HF>nRv33ol{A|LcNj$}5%fF)8**Vy~Qss0ZRVK{;cEHBJh59im z_c(G0vYM7$fcH!$a}0Z1N0?s|)X_A@I1~o*wGW;x|FDAO+d9`3k56}c;5Ea0XX!su ziNZ5M;i8t9r^f{c43)=~YZ;@8rhwe7XKCsHjdAm3XI%L4E1#FRj+m(H2yc2HB%gLw z4kANH`JQhP%2fdr&l;QBC%e&Uaeam$RWgO^^xwE24@j^*iwR(hiKlQoZz z&^b{`%o&jI`Rf-_0JG5RJ1n}XHoN3%Z(lLZdDQkX>nfl^6wrGT6ZIgJzY3a1=>xU4 z$mGy_iMxRGj5A_T56yzGK51P3?}OC+ar04BtIoPkBs8!>k-pObU92uW$Rp!*5j4R+?1 z`crTQ#gmf(J66sB+xF`Hb-Dtt-Y>mmzI?5A_ud^&G)?{YlTIyV-!pugitl&6e3l$M z*Z1#zsjIR|g|pCPA^>S_j>7gVzn9pKy2x!^qJ;E57rEDF9fpK80W!UWwhu9}r57QE z)YL-?^JW5yI-9N-@7W6b_FQtc#CV<{g_>OuWk|%R|IpiLV|t!frq+k308WC{1B=V**>N|vgy5IInBq&Mg44>_ggbt& zNiFLh9ZQFtqotU)PyL*+NQoVhV8)Ss+uR9yo!jT}rTH#p7nn`m3@KF}kt}!jM|tO9 z)*s6fzK)FaXHdaPjv>uXas#=+Dbij>4o)or*K#ZD2GMKzu32By4)@-}JB zGi50NS+mnTYX@OA73;T{Q18K>CgBGLLJzhzr5#^KCh1S)WJ-UUp)J25-Iec@ffyxo zvHp?;f8^2c3I|9+4mjE)WaKc{wc6c7XvFHiRPr7%ZFSrDO&G=ok`*uwL{BXM!)hO< zZ06;XyqlHsW{`$U>{s$s?55*IZtKMVR3rAf->!*?Hc+TYum^gAAr(=a)ooPWcI5yp zF0vI0B-sf`8#ss8+PC+w5lg@HjytuZKQmNDk-QWLAtR7vyX)G&M)Vufi3V9(CmDFIHYYDwiUJ3vE^YZdZJ|k6jl^fnE9?+^UejHbv-DR@PV?M1DH{=U@MZaV ztYnk1WTOMj5l<2Po{qv44K^sWxzlCd239~YiI8&k0#PCEJ#lW*T)mx%Ly|dC99fxC zoDb_LORI)Db$oSjXlRWpA^rGl#+uff2Mnk^I$y}uy8e?A9bayxpEZWfYctBwDwV{p zZ!1sL>41;2h`|-(4;>)MSePA)_(rS0>}N99tAuc}F0+%F5ptf2;nN0tt87PwY!*E( ztH~sC6Iv05Dla7FC79-saWlxZKYN6TM~MI?)iueoGQin2*g2K5>n&79NQ`q`RkKby z22<=9=icPDSb9Z@tPfU z{pfU06*TNqC=xa$)Epp;{2qF02utmo<`Gr0<|e6%4Z7zG%HpASXnaFy4%v(EQFJIp z;zVlrV34|h_p9Gc^@9`t=fhe;l~ilFwic{`z*qs5h~oi!fV{xPT7ELa+28=n)Z4xN zj|J`xlc}1f$!jUyuB@}F<;F7+<~8a^=03i1DHb{I0+YPrv2Tu1#?d_>6FZoUB=`=HQ+;PI4lrw;2q|IyMj&nB$vND)=Wm}J(VH&wHfbLLe3L@xGC zC(&6%VSG*F5Wk-sW(UzVT=qyWuI#_Pid*Lsjf>j*ezAH%Y*ZlA(->NE`@TfIUo^(F zFYDTm`Cqeobi&sIHLN)z@zPhvN#18PC(4V%w+B1lMOE%XjJHLUPs9*W`}!0}I+_BOA8tBjiCg%Jz;Ry2lzc_baY zY#1%xwSg-WQO9{Y=uLU4kiDptE}jYv4nEDAVJ#_qM_-SvcYIo-`jC8If`7|~^g<*; zaUZeZJ8A!(zR?irWf1hNI2<4JKR5&;#NR!C{eO53x3jzwiM)w3sP>^tRi~e>*|WZh z`vJj@O+zIN1pJ-HP%)U^V-7h{gq-o@%z&Zb&B>?X9cZ8zm!q5U&=WY0lNs?+?lNIr??YCQ z{Itvmck3$acV*w%3weSTB(Xnj$V3-hEWeCpAswQj8@cNSr+)@YSme<<5)9gnkYt0( zFiY=h*EMSLBJ{~TJt4?-y`9H_cAYbLi*Rt3LqT6{f=QV=g!`w*ib*QSJ?lrCTR2yY zysCc+N!Nq&(%1wM+lBk{iTwhnzT=~|3QTD|VcPV=PNx}|I;U18Vc=lMU9eT;l1v;A zry9jR*+37hKJrv`ro=T%dU3-#r;N$lJUw_B{KC*i3;Zz|r$jdAwQn2I0W(*exWX3b z$-_dMNruU=)~qp-C~Yb}7DTX_-_mUJZ<0nh!)w)Xc;7txNnK$2is{r{g8THBIbw)M zQcFolg|eWlQ*pZ}6EdUW8{-6U>v`U96c02H})fPYwfaq4fJM1 zxbU`&A68Wj!t4@aVyI+)mLCj%1A5u~ANd?tt!4cGgU?|N{BL}YqMrXZpCh)RccCgd zdPPh?%4(?@uwoykx}uJ-cjJCDEqwBsp4mXNACn>EWgPNg^=_G&L)pn&Q2rvC@b;1i zvk>M0o zZNvp>c7s*NjG11k&*kLzBI!6G+9#(geUp&MUrxtyaLfM?aMk>q zr*JG^)NN3jYh4z8z?~4o(T^nr<<0NS-)ulSwX(Hj6S=Li>$3a%qqzmPb6MYJ5Z-*= z5vYyk7Zr!a@Nl)%j|iZgxXdkE;q$>*IyED&<-GMdid-i{-8%jvleZSVATAacA>Kr; zs{@KF8*pGEs0xOpkzCDNPumxmTlD-k(Nb-u>g zJ@Y?=>=}kwI^D-A;KE-XEcJU)!qOo_)FLhRwV9QqI(_pzBD2dJ6Cpfwjt~inOJ<==p0!SMEokRM>kZ%FFsL9${z4k^FBK%t5L4#%-q2Hf z?9?W+lONI=UG*nW@9p+(%3J%g3%&OcA@3<#u!Db@(H+a^{p{=p2e}}0_W0%b@-)9& znr!~*Eta-@{Pxa7RTc9j2jZCe$d3SjJDMAoA@tsSEjW~ukJ>4TmEE9cV%uXK}|aa6by6y-?h z*MrkitXpxgz+CZT$JF=DdpQQ11VIT7P&NvZ1n^95?F1@cKAHmMV~5+plr1KQ;6o&{ zdQoDvlceRtEWz4(B`WS~_Zb)Zx~u0owXNH^U*H-uHL??^I$nKo0)D#>uWu?sTTgx7 zP(eLtpK$i1s@R#pq=V9H!QA=?e;(=nVU{9g$zdN~2-n`I_k(V<$nVUB#Mu&Qe$St4 z0Ka9{y7#NStCH{VRC)frtS$Z!SjDhN)aSkQ=Y|`F4)9`eSz85-s$J{iBa(n8%g^Ix zFPHiRTat~lav!`6%0;=_do3IeS2WPSM9e`Ye9P&b`w0&HO`dVUClY&Y`3uCdZ13ij z6wC_s_R!#S6VGhSL?)aQ0pRAlaR^S-wXUh}t%&6PoYV)O>e1L#`$KI2xRTKC$ z(()4wf=W>)bEValT_4E59VS*w{exrYt6!q_+9Tj7G)@!xiQO0DemVac;_~Xvy0o_9 zz`CcfVBYn9EiS->B6Ql@!IHp6;z<7>S3pCfrpSOz*Y7t^4T z12G?0&ujOr&q1^nU~+B_9U4m8llWYI@`f4kAou09{1c@8c37tc4E}O%rJIxM3)>S0-mCFnohUX;ij5c( z^5fU6nJ~AGW!nWAHbo=3n_-1*v8b|?wonqrKAv&&3hxzkfD(&+y~HJr+R)RjNfX$i z*yGnDvZwZt#M*1Xtn#tgGHWJEFwZT?+S$9Gb=5rLQ|xQV!WQoBe>IVZ8?W*93pqF# zs3&7bnsa<22$j&56oVTKr144%MC(>Wp?u;kK3L@dTIP4!MCtWt2IF>)PpPh!XTF}oD z+#5b!9!0`iP)d=&`iO=#f(vvP9uZfp>A_Xuii!CEDE)xEk|Tcj^W`rtXU)?Ojv!6U`H z;JSWvM`|X#Lyx`ZHoID3>1nzsPwU?!MLkygIvcdZ!{Z)Yb&~p;FlOdPdU4%nAlCKB zygfd6?l%?pghb_F;Xc(2=S^?h?z8wqc8(L#*R)@}l0gBruwntdsD!eisrDctWt7DZ!m2a$yv? z!7>&@I;ukSotz*xF&sxfGr8^RDpq2qG+qHQ@e{**-W&{k(5`FmjMZR(1%dk4;IgvN;@Se=z(`TWA=NnLFKPvt&C)+zUxUUJ}FF@H9ZJ6#`56WjxkB=(h-hG!D_k64) zo~cuEC48f1Qq#KwMc$C>+(o^W;^ex|Bua*_fcc#L(c-yg5W7#dqyoi+TLtWL3n73c@jKp~dG=M8&N&yH;j_>?Z5|W^)H;93hAZT$)u!1J?pC8k zPU@fQkT3UE;Jvb`JqcOanM}tSSH!5t4`Z1}N0{H8ZMWgFDSlZiSviBDKz$|alW#gr z*8!euiFwdvEfg7m5~V0mC1-QomjJ~l@{^8daLHHd`{$1L+#IAqT#N;ewF#O-MvkBj z*VvO8D*jy8UDDQLikb4mVZ1GYwYmA>qpXhRo^J?zOQw$wO{?84HI|p~eJq;#abYJ1 zS00#r#&#S+P1al)T4P)ljyvp{%%pPVHXl|9ef!?0UZ%1(%QsOP1R$$-HY;^{23jtj zG>fq`qA%->ny5`~Sub-a=(tHT-PAIiFJkaToh@RDCJ9yqG0N?`%X`6jl-$y_Gz`cw z3a-Y6riLdP4tkbmjy)GvS<-JjfpVHgEkkRUcHi%T4BVOeZ2ar8d}b33Q!q$H>axYu zCL2CEr9}Zn=mHU#t!G%v(Cx7NCH_HUgn>3+d2 z_=L{u1z>g6==^m{X+ikv|xg?R2#)7qLIBH@1WB~yB_|d zhQrSB-BIYyg@DHHTVVYH!=nbwHxhmxXjP1IcVR0J0z&-p#E6(*-isQ)b~7TFMKa1X ziU(PVw+oN0j*h;QiAidkfy8px+Ew;3c> zwNL~&W)k+ricUUbz4y+THEWOskCW+ZND#Fm1m1w*AlaC`S+oPg9Pip_4ZFE2%w<2_ z!Pi^tE#%gQI;Vy{DUQESqG`*^En>H~nV+j#zV7WoD|Z~xSM68zVmQ3ngji-547fr_ z(nwb|e`LcPH(MWj+`adW710Y0=E2yr=jSSHd5upb9UIU$-*)8i5buofd+y(O6W&=> z>&2_qi4(5DDEG5sT-2Vzwp2goT&jJKE0x^xoLApKtKQNc*^E@Ci8YH*75kJUEVq~j zWowFCY6zN@%!}b2uRHgYUXV!3dKa->ZYPYCQ$ZwPYs|oTw-@N}?~i z(|2Y^8o5prz;n+%z@@$~XoQFo^dR`$5Oq+h##|CUcQ38JS8xf~a&rmUcS&y08Mq!w zxYI?7*${bl+7M^y4|d5d&^XR(nr<%TX;(pfnMsi37-OX1sCk0o)X|u2LK6HlRh@~G znD*l@%HbgB9e-Vj%F zxKYioCA-esrrwC1`f$|w zD;)2ThNFr8ygzA%4jDfB1dx1|2E>!SIzy+A?N68Fp`)5(Mn z9d4kLUfrx@y-v-t&jW7#C!3~5vzF3GfF1CZ1V;VVj&$J8c=IT}z!>`Zp&jIZEdz9Z^@%jpp@p=0uSYW=Ak;>CR#*D78 z*V{Jne4M>VXjRtp51qLHv;MuxxI9ewH1Tp-`XtGt>>@m8Ih{4*Blsi7fYLYxq-~$* zmZsk6JORzK4=qe+83HafCd3o5?Lw`A>4wl>bC?gf88MF9X`GVX=ZTc;A6KTt;@0_I z3=$*cI&Al!%p4)Tdi(pntQ5-t_ruY@3N4{$L+!Le?*i76Gd=1Kkar|8=f05gi&@T_ z`GLam{xwpnr?Gcy8$xlZk!3MlkN;_%Aci7CATTv+P3WW?U|cQW^D9a7fYnPq-!3qD z)gmJr7c(;W#%Q*%_eLTr$D)phvVCo0<{lb$lHT5JRfy;-akxY_yx7o>RJ+?9&%~p@ zaNiwFf#kif_CVvavm!T&l7uFv8~xa;;^fAq5H)JRqGh0mZcWtX#|KR2~RPSh4(?*`>Z znRC0kJHGVMr1W5h@xnWlF2hPa+1ks|`WU8m<2e1Q9W;&fBdoQxX}!O!AJuPhh>^6{pVg+?aqy{Vxj#2KOAKx!S}N@bemes}C&b97nw5tq*=hq- z>dJXfqYI-a@0O^MSxwPr8~R>KiEal}%GJ zH&dy3KFIO+CJ-f;$$lODaz7TL$yL>oWV{n4@yM%Sy7y&85Wil#z<{%;=e_pwYI(0c znI;_%>jyU{+hxY@3;2(NVrhHTH?W9gCCdQISm|nRYOn^X&X*9Z>L+(UN1g}dp=@*l zcWt79KrQt8biQqyMTqus`a;nyER684E>eZ6cSW1nE?OR&7-A1>@U*aCMaOQ`TE;UWP3RrGuzQL7jm(}aF48=K*0t=s>Bud<R!e$yYMl+%xW)P#7oa9h|UCNZeDOcPQC5B7}=2Bm~CBGZ>|8o5F=ca zeO7njSst3j6GYr;r?u~(Alig_frUyz(WXp7Q@6W6Npp*gA)h740Fi{TYrbLgeqR2W z!YJLNx9m>hwMf!M>fakLZ(yE_lPav=`nUYvY2_9%!(otC7a(BPfLR>{pZy1ywpBmY z(pR*v5N9e$JUG(t2Tfm-B~SH084?aTEg`=Po5C2+T^0edO}v^}%oQfTZ7|C@D5kM1 zHbt&ko1FfPZw<2|^ZvO_kFsQT1F;Y!;~Hywl)?8KMQ03|62@ZE4IOd)&Hm(b{gU%g z>8Z5fd+8_JxZ+_3n=G>YsL@tDiO< zyvt3j08qW(D`{kK%T{bQRrz_3Pw=`9rnBR2#Jto{^KvM?)`4!>`%z{o29qqydUyPQ z!)N-hZl6syiL_6hKPj&^AE-6B($~{5y=tkPh;Yo{|7M!pij+7zG0p(Sv$dz7U>;G^ z0YloTd9tQXNqw~0qEUMtY1RbERK}Z%Ei-EEo%KE(He)z{Y%gktUc~7sv&mIobeJ)> zWokGVe}foNM;iuuE^(C|dr@P{T9oY@>wk<_*~OC@g})}H-HId+P&8(knRX+Bb;za*@_Xl;@1IaE zbA9%XVZ(3TB=u+Wh_T~STbn^^SQM>q@u0)C+{fbtH^Rv9_Pzk&%tWIJ5Tvnx0=gf^I;0+Y9jYDFPOmit|4XxHpkq+juEmcDd#f=(MREUJs(4wlTnHIUOny#cI1TBJ4bE%n_N=%KJ zsyTUi_x=IzhxhCK{J7Uy>zwsn=j^@KK46SDDdq?w>ncjO|S)ZQpB@C;tUtrwMcW^(lcEyV%2yn)2ifQ1Cl3sZ~ z2-(}4a&RiVNsl+UB$_Qy?d*Ppw(g8Yj?uOAbe%mR@E1>DX9qt9Z7#KERjS77Nr|f` z5**@6+4KCAJoJ>^9Pjn{ZIi9en=4hO)YCubZFXH6c?GI)4zRIebUcDyGPo4^WVE8^ zuS&1s_{}c`!`yOlcM{S2gk#q7pb%`#l5VeIe4hb_s0NP0xj;Z*HG63Vg|jK&iEk!r zf^N@Mrlx8@zwNGtzF^*O^jM~Al~B?`=^dj74v;$+9f@2;-u<#l)O~7q?4$t>_r-rWskP%hZNT6AV z?_h}}rsfhuY6OD?U;Rx3aACLvmi8{9cdO zJ*ph|@>^y21OcT zu3q*^)Fic~4zJ7Y@@!8y^-2UVb0@wD<_PA|hGLVC4uuNCGjMCNsEDDmp>bmY6MPD# zFvox3TK(Kgv4a5qe3eg5TDR?l%iIbG&rewhEVY`rmK;fXA(WKj=q$T<(4@)`Zoe_= z9|s7Pfv3?mdnUV-5ani7D-L-m{~I?2rEkS_;S(I7)W#jm@y~CIA*B|b0nE-$IXKU> z@lQt$p_h2QbG#;S?@4`w>WP>dbG2^o$Ya{uC%Q&jZf=?ilJ9}LgZQybiJvBFptn=l z`#3w6_mue5)1>)KB;)ru*J|#e3E}ZI<|~a{t~1g#InRn87Pvq$=$j4qNnzU`HsFV; z=CW`0;PhIPXBtMb-wT~pwH2Jya$C74o$4+;cVR}Xk^SCG&k%L1z&eY%JSxByfCnTA z{G?PV0wKhty^}BcYI2AnQ$!Kq%rv|#OSN<7f+xCoPD`Sqf-xy}Z3bYo(u9sz0(%cmK z3&L$;$K!8Tdp>^1vT?3+W@}`?+MB?NXcBaqt@GmNo&ErKB9vrs+tvjE;l+?_CkMR= z1Uv?n-AWS=ZZGe!^QVMxSMoM5TV53LfCs*^`21?e4gxtoc}WtxNdL(*jT@Crqg9mw zg{*yNn2&%LRUyXfEhAt1ffX^OL~o{cJRXSab5^QOLm z(ph{DT*u^x`nu4f{b_@50=jAKnBGO!OlrrFY*ejdiF`Zn}u9+>xzk4+{8}3a*!Y2G(DgSVrkulq1_K zH?Kiqsu!@`YgbIvh-3=Q9dq)OT0NtGhZ~DqglAtHta@(`5j+R&^M&Ub^hJ26$eUXP zP42>N|7tVi2_;GoO%{UFouP zun>ek;T1c*{&u?C!_GW_P&qgQkS5l5(ah$^r|P!o#3SI0HElM0qxDr3{Nl&o52$4- zUnhO5*A3v|dp7DoK*H|EL5d}eAiU<2or6e~Xx1{9kkB=G`5b|r(uUOCEB1zHSBM*| zUlrIvGQ*`WHOsfU1$~l)9$=hV1Z-I%5^++s@vTAkWw|Bcf;uNs9gD! zafG?X#!wk_w9H<_4kH>Cb6=p8on-%M0s%N2M+5B{-e(vi5-MKQyK$N+?jaGmUoL*~ z_!x?Dh9X5Ak6&)Q_OBk)X8t`~27Vgt)?)o^7Bp^e{s2y7)e>7ZR`5}6AcxL~`9U{Q zDk(!>Q|hFee-m|e_n@+D6=23;kq5)o;wIb66t>Sg1co8@&}&8Xx_RaxxRIzqbBZu z4ti<^2liRg85Z}yUe87zJa-gA6c_R#zTD9}o3r6D1pRDtvl&ZlmViLQxBvXmJX+Ie zRS^Bq*NrOoZAm{sU3~0iX44vYzklihW6;~Sq;{=?gN*|{^oE&!f5i0BLyq4$&vTs( z$K0h#fk2UlsupERJea<~ffTEVQ6dN>l*-`MonQ`9! zDSg(*GPBbOrESM)RX#!rL=BDJU^!j#iT({89tFD>ZO^^DibE(%t`T`W>UOnXB0c90 zhw`gRa&1e9KW0EMM>UGZbkkSjK_JE-U|42UIPk~giFJD{%5_WrnWH+5cqXZO2ROEQ z$nk>Ac1HhwZ@0?f5{b$PsO|pQF4f0$!4fFsX#RbCiCVxCrOM~B7054)GikRzl$2@I z0y~UG3mA7=9!9YLYSc^$4bZcW8CPbs)$F8-j3sn5qN$qJ2U~w|HOtXgHu%E5u4eGj zq{jHlz1);#RPcvvzhr`%4VWcV5oKHS5K8H7i5%*5daWLElbRPgAn_! z3==?q>js|T{6noo-G7yGW8>F=WLl2Sw_v_F^B_5y?HfdKb;_D>dI9Tz_vHx!zw<)A zok&7_d_2;YYZY|4a1?n$_?A9KwnnaTt|VAz@Yx%DKyx8LsIQTsBbi+T>EZ18XY zok>NF{TD_M_4-NGx-6B$*z_t6+zC{c*@kZlBp4=y`JF4rJatb_FO+QoPGqtmrO7rn z&va+;f9ZvtJT5A73?t|FDVAo&ci8L3lKG2X^G0oIvCkON^{&A4nCoHE!Dh3q%l|jY zoJCD827lujEngw>k2TwkYt`@{D=_Oc;@_eFrvkw|ky)osv0O1VxNZBd#{WZsUknyS WF+syvHD%l>CZ>i~1|RRZMgIrtJ)0Z= literal 0 HcmV?d00001 From 5f8697b06cfbb00a2cf793d400ece0d700979cec Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Wed, 31 Jul 2024 19:25:39 +0900 Subject: [PATCH 071/304] feat: improve description output of RelativeClearanceCondition --- .../syntax/relative_clearance_condition.cpp | 23 ++++++++++++++++--- 1 file changed, 20 insertions(+), 3 deletions(-) diff --git a/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp b/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp index 5d210b1f039..ba584c7edb4 100644 --- a/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp @@ -55,12 +55,29 @@ auto RelativeClearanceCondition::description() const -> String { std::stringstream description; - description << triggering_entities.description() - << "'s have relative clearance to given entities ["; + description << triggering_entities.description() << " have clearances to given entities ["; print_to(description, entity_refs); - description << "]?"; + description << "] with relative longitudinal ranges ( forward: " << distance_forward + << ", backward: " << distance_backward << " ) and relative lateral ranges ["; + + if (relative_lane_range.empty()) { + description << "all lanes"; + } else { + for (auto range = relative_lane_range.begin(); range != relative_lane_range.end(); range++) { + description << ((range != relative_lane_range.begin()) ? std::string(", ") : std::string("")) + << range->from << " to " << range->to; + } + } + + description << "] "; + + if (opposite_lanes) { + description << " including opposite lanes?"; + } else { + description << " excluding opposite lanes?"; + } return description.str(); } From 8a055492398c3af84bfbedca5631e82e6792edcf Mon Sep 17 00:00:00 2001 From: Dawid Moszynski Date: Wed, 31 Jul 2024 15:25:01 +0200 Subject: [PATCH 072/304] feat(traffic_controller, api): add rviz marker for TrafficSink --- .../traffic/traffic_controller.hpp | 2 ++ .../traffic/traffic_module_base.hpp | 3 ++ .../traffic/traffic_sink.hpp | 6 +++- simulation/traffic_simulator/src/api/api.cpp | 1 + .../src/traffic/traffic_controller.cpp | 15 ++++++++- .../src/traffic/traffic_sink.cpp | 33 ++++++++++++++++++- 6 files changed, 57 insertions(+), 3 deletions(-) diff --git a/simulation/traffic_simulator/include/traffic_simulator/traffic/traffic_controller.hpp b/simulation/traffic_simulator/include/traffic_simulator/traffic/traffic_controller.hpp index ac47927668d..75c2a53ea83 100644 --- a/simulation/traffic_simulator/include/traffic_simulator/traffic/traffic_controller.hpp +++ b/simulation/traffic_simulator/include/traffic_simulator/traffic/traffic_controller.hpp @@ -46,6 +46,7 @@ class TrafficController const std::function(void)> & get_entity_names_function, const std::function & get_entity_pose_function, const std::function & despawn_function, bool auto_sink = false); + template void addModule(Ts &&... xs) { @@ -53,6 +54,7 @@ class TrafficController modules_.emplace_back(module_ptr); } void execute(const double current_time, const double step_time); + auto makeDebugMarker() const -> const visualization_msgs::msg::MarkerArray; private: void autoSink(); diff --git a/simulation/traffic_simulator/include/traffic_simulator/traffic/traffic_module_base.hpp b/simulation/traffic_simulator/include/traffic_simulator/traffic/traffic_module_base.hpp index 816e2c2faf2..e21e73b8a0f 100644 --- a/simulation/traffic_simulator/include/traffic_simulator/traffic/traffic_module_base.hpp +++ b/simulation/traffic_simulator/include/traffic_simulator/traffic/traffic_module_base.hpp @@ -26,6 +26,8 @@ #ifndef TRAFFIC_SIMULATOR__TRAFFIC__TRAFFIC_MODULE_BASE_HPP_ #define TRAFFIC_SIMULATOR__TRAFFIC__TRAFFIC_MODULE_BASE_HPP_ +#include + namespace traffic_simulator { namespace traffic @@ -35,6 +37,7 @@ class TrafficModuleBase public: TrafficModuleBase() {} virtual void execute(const double current_time, const double step_time) = 0; + virtual auto makeDebugMarker(visualization_msgs::msg::MarkerArray &) const -> void{}; }; } // namespace traffic } // namespace traffic_simulator diff --git a/simulation/traffic_simulator/include/traffic_simulator/traffic/traffic_sink.hpp b/simulation/traffic_simulator/include/traffic_simulator/traffic/traffic_sink.hpp index a6c68b1bfbc..5ec17397636 100644 --- a/simulation/traffic_simulator/include/traffic_simulator/traffic/traffic_sink.hpp +++ b/simulation/traffic_simulator/include/traffic_simulator/traffic/traffic_sink.hpp @@ -26,6 +26,8 @@ #ifndef TRAFFIC_SIMULATOR__TRAFFIC__TRAFFIC_SINK_HPP_ #define TRAFFIC_SIMULATOR__TRAFFIC__TRAFFIC_SINK_HPP_ +#include + #include #include #include @@ -40,13 +42,15 @@ class TrafficSink : public TrafficModuleBase { public: explicit TrafficSink( - double radius, const geometry_msgs::msg::Point & position, + lanelet::Id lanelet_id, double radius, const geometry_msgs::msg::Point & position, const std::function(void)> & get_entity_names_function, const std::function & get_entity_pose_function, const std::function & despawn_function); + const lanelet::Id lanelet_id; const double radius; const geometry_msgs::msg::Point position; void execute(const double current_time, const double step_time) override; + auto makeDebugMarker(visualization_msgs::msg::MarkerArray & marker_array) const -> void override; private: const std::function(void)> get_entity_names_function; diff --git a/simulation/traffic_simulator/src/api/api.cpp b/simulation/traffic_simulator/src/api/api.cpp index e001270d6d9..0bf4e86a742 100644 --- a/simulation/traffic_simulator/src/api/api.cpp +++ b/simulation/traffic_simulator/src/api/api.cpp @@ -355,6 +355,7 @@ bool API::updateFrame() clock_.update(); clock_pub_->publish(clock_.getCurrentRosTimeAsMsg()); debug_marker_pub_->publish(entity_manager_ptr_->makeDebugMarker()); + debug_marker_pub_->publish(traffic_controller_ptr_->makeDebugMarker()); return true; } diff --git a/simulation/traffic_simulator/src/traffic/traffic_controller.cpp b/simulation/traffic_simulator/src/traffic/traffic_controller.cpp index 0b87733cc37..27a5d42fd57 100644 --- a/simulation/traffic_simulator/src/traffic/traffic_controller.cpp +++ b/simulation/traffic_simulator/src/traffic/traffic_controller.cpp @@ -61,7 +61,8 @@ void TrafficController::autoSink() lanelet_pose.s = laneletLength(lanelet_id, hdmap_utils_); const auto pose = toMapPose(lanelet_pose, hdmap_utils_); addModule( - 1, pose.position, get_entity_names_function, get_entity_pose_function, despawn_function); + lanelet_id, 1, pose.position, get_entity_names_function, get_entity_pose_function, + despawn_function); } } } @@ -72,5 +73,17 @@ void TrafficController::execute(const double current_time, const double step_tim module->execute(current_time, step_time); } } + +auto TrafficController::makeDebugMarker() const -> const visualization_msgs::msg::MarkerArray +{ + static const auto marker_array = [&]() { + visualization_msgs::msg::MarkerArray marker_array; + for (size_t i = 0; i < modules_.size(); ++i) { + modules_[i]->makeDebugMarker(marker_array); + } + return marker_array; + }(); + return marker_array; +} } // namespace traffic } // namespace traffic_simulator diff --git a/simulation/traffic_simulator/src/traffic/traffic_sink.cpp b/simulation/traffic_simulator/src/traffic/traffic_sink.cpp index c98fcdf95bd..32934506e23 100644 --- a/simulation/traffic_simulator/src/traffic/traffic_sink.cpp +++ b/simulation/traffic_simulator/src/traffic/traffic_sink.cpp @@ -23,8 +23,10 @@ // See the License for the specific language governing permissions and // limitations under the License. +#include #include #include +#include #include #include #include @@ -36,11 +38,12 @@ namespace traffic_simulator namespace traffic { TrafficSink::TrafficSink( - double radius, const geometry_msgs::msg::Point & position, + lanelet::Id lanelet_id, double radius, const geometry_msgs::msg::Point & position, const std::function(void)> & get_entity_names_function, const std::function & get_entity_pose_function, const std::function & despawn_function) : TrafficModuleBase(), + lanelet_id(lanelet_id), radius(radius), position(position), get_entity_names_function(get_entity_names_function), @@ -60,5 +63,33 @@ void TrafficSink::execute( } } } + +auto TrafficSink::makeDebugMarker(visualization_msgs::msg::MarkerArray & marker_array) const -> void +{ + const auto lanelet_text = std::to_string(lanelet_id); + visualization_msgs::msg::Marker traffic_sink_marker; + traffic_sink_marker.header.frame_id = "map"; + traffic_sink_marker.ns = "traffic_controller/traffic_sink/" + lanelet_text; + traffic_sink_marker.id = 0; + traffic_sink_marker.action = traffic_sink_marker.ADD; + traffic_sink_marker.type = 3; // cylinder + traffic_sink_marker.pose = + geometry_msgs::build().position(position).orientation( + geometry_msgs::build().x(0).y(0).z(0).w(1)); + traffic_sink_marker.color = color_names::makeColorMsg("firebrick", 0.99); + traffic_sink_marker.scale.x = radius * 2; + traffic_sink_marker.scale.y = radius * 2; + traffic_sink_marker.scale.z = 1.0; + marker_array.markers.emplace_back(traffic_sink_marker); + + visualization_msgs::msg::Marker text_marker; + text_marker = traffic_sink_marker; + text_marker.id = 1; + text_marker.type = 9; //text + text_marker.text = lanelet_text; + text_marker.color = color_names::makeColorMsg("white", 0.99); + text_marker.scale.z = 0.6; + marker_array.markers.emplace_back(text_marker); +} } // namespace traffic } // namespace traffic_simulator From ed58cb9423546eef323f5bcca56a313b60db8506 Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Fri, 2 Aug 2024 12:58:37 +0900 Subject: [PATCH 073/304] Update test scenario `ByValueCondition.UserDefinedValueCondition.yaml` Signed-off-by: yamacir-kit --- ...ueCondition.UserDefinedValueCondition.yaml | 149 ++++++++---------- 1 file changed, 70 insertions(+), 79 deletions(-) diff --git a/test_runner/scenario_test_runner/scenario/ByValueCondition.UserDefinedValueCondition.yaml b/test_runner/scenario_test_runner/scenario/ByValueCondition.UserDefinedValueCondition.yaml index 0b340721977..502188c68f4 100644 --- a/test_runner/scenario_test_runner/scenario/ByValueCondition.UserDefinedValueCondition.yaml +++ b/test_runner/scenario_test_runner/scenario/ByValueCondition.UserDefinedValueCondition.yaml @@ -8,7 +8,9 @@ OpenSCENARIO: ParameterDeclarations: ParameterDeclaration: [] CatalogLocations: - CatalogLocation: [] + VehicleCatalog: + Directory: + path: $(ros2 pkg prefix --share openscenario_experimental_catalog)/vehicle RoadNetwork: LogicFile: filepath: $(find-pkg-share kashiwanoha_map)/map @@ -17,45 +19,32 @@ OpenSCENARIO: Entities: ScenarioObject: - name: ego - Vehicle: + CatalogReference: + catalogName: sample_vehicle + entryName: sample_vehicle + ObjectController: + Controller: + name: '' + Properties: + Property: + - name: isEgo + value: 'true' + - name: barricade + MiscObject: + mass: 1.0 + miscObjectCategory: obstacle name: '' - vehicleCategory: car BoundingBox: Center: x: 0 y: 0 - z: 1.25 + z: 0 Dimensions: - width: 2.25 - length: 4.77 - height: 2.5 - Performance: - maxSpeed: 50 - maxAcceleration: INF - maxDeceleration: INF - Axles: - FrontAxle: - maxSteering: 0.5236 - wheelDiameter: 0.6 - trackWidth: 4 - positionX: 1 - positionZ: 0.3 - RearAxle: - maxSteering: 0.5236 - wheelDiameter: 0.6 - trackWidth: 4 - positionX: 0 - positionZ: 0.3 + width: 10 + length: 1 + height: 10 Properties: Property: [] - ObjectController: - Controller: - name: '' - Properties: - Property: - - { name: isEgo, value: 'true' } - - { name: maxJerk, value: 1.5 } - - { name: minJerk, value: -1.5 } Storyboard: Init: Actions: @@ -69,33 +58,30 @@ OpenSCENARIO: laneId: '34513' s: 0 offset: 0 - Orientation: + Orientation: &ORIENTATION_ZERO type: relative h: 0 p: 0 r: 0 - RoutingAction: AcquirePositionAction: - Position: + Position: &EGO_DESTINATION LanePosition: roadId: '' laneId: '34507' s: 50 offset: 0 - Orientation: - type: relative - h: 0 - p: 0 - r: 0 - - LongitudinalAction: - SpeedAction: - SpeedActionDynamics: - dynamicsDimension: time - value: 0 - dynamicsShape: step - SpeedActionTarget: - AbsoluteTargetSpeed: - value: 2.778 + Orientation: *ORIENTATION_ZERO + - entityRef: barricade + PrivateAction: + - TeleportAction: + Position: + LanePosition: + roadId: '' + laneId: 34513 + s: 20 + offset: 0 + Orientation: *ORIENTATION_ZERO Story: - name: '' Act: @@ -133,26 +119,8 @@ OpenSCENARIO: - entityRef: ego EntityCondition: ReachPositionCondition: - Position: - LanePosition: - roadId: '' - laneId: '34507' - s: 50 - offset: 0 - Orientation: - type: relative - h: 0 - p: 0 - r: 0 + Position: *EGO_DESTINATION tolerance: 0.5 - - name: '' - delay: 0 - conditionEdge: none - ByValueCondition: - UserDefinedValueCondition: - name: ego.currentState - rule: equalTo - value: ArrivedGoal Action: - name: '' UserDefinedAction: @@ -163,23 +131,46 @@ OpenSCENARIO: StartTrigger: ConditionGroup: - Condition: - - name: '' + - &COUNT_UP + name: '' delay: 0 conditionEdge: none ByValueCondition: UserDefinedValueCondition: - name: /count_up - value: 500 + name: /count_up # ros2 run openscenario_interpreter_example count_up + value: 100 rule: greaterThan - # - Condition: - - name: '' - delay: 0 - conditionEdge: none - ByValueCondition: - UserDefinedValueCondition: - name: /timeout - value: true - rule: equalTo + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP Action: - name: '' UserDefinedAction: From 714dd8eda6fdd4cc190d5989610222a32be77e17 Mon Sep 17 00:00:00 2001 From: Release Bot Date: Mon, 5 Aug 2024 00:10:15 +0000 Subject: [PATCH 074/304] Bump version of scenario_simulator_v2 from version 3.4.1 to version 3.4.2 --- common/math/arithmetic/CHANGELOG.rst | 14 +++++++++++ common/math/arithmetic/package.xml | 2 +- common/math/geometry/CHANGELOG.rst | 14 +++++++++++ common/math/geometry/package.xml | 2 +- .../CHANGELOG.rst | 14 +++++++++++ .../scenario_simulator_exception/package.xml | 2 +- common/simple_junit/CHANGELOG.rst | 14 +++++++++++ common/simple_junit/package.xml | 2 +- common/status_monitor/CHANGELOG.rst | 14 +++++++++++ common/status_monitor/package.xml | 2 +- external/concealer/CHANGELOG.rst | 14 +++++++++++ external/concealer/package.xml | 2 +- external/embree_vendor/CHANGELOG.rst | 14 +++++++++++ external/embree_vendor/package.xml | 2 +- map/kashiwanoha_map/CHANGELOG.rst | 14 +++++++++++ map/kashiwanoha_map/package.xml | 2 +- map/simple_cross_map/CHANGELOG.rst | 14 +++++++++++ map/simple_cross_map/package.xml | 2 +- mock/cpp_mock_scenarios/CHANGELOG.rst | 14 +++++++++++ mock/cpp_mock_scenarios/package.xml | 2 +- .../CHANGELOG.rst | 14 +++++++++++ .../package.xml | 2 +- .../openscenario_interpreter/CHANGELOG.rst | 22 ++++++++++++++++ .../openscenario_interpreter/package.xml | 2 +- .../CHANGELOG.rst | 14 +++++++++++ .../package.xml | 2 +- .../CHANGELOG.rst | 14 +++++++++++ .../openscenario_interpreter_msgs/package.xml | 2 +- .../openscenario_preprocessor/CHANGELOG.rst | 14 +++++++++++ .../openscenario_preprocessor/package.xml | 2 +- .../CHANGELOG.rst | 14 +++++++++++ .../package.xml | 2 +- .../openscenario_utility/CHANGELOG.rst | 14 +++++++++++ openscenario/openscenario_utility/package.xml | 2 +- .../openscenario_validator/CHANGELOG.rst | 14 +++++++++++ .../openscenario_validator/package.xml | 2 +- .../openscenario_visualization/CHANGELOG.rst | 14 +++++++++++ .../openscenario_visualization/package.xml | 2 +- .../CHANGELOG.rst | 14 +++++++++++ .../package.xml | 2 +- scenario_simulator_v2/CHANGELOG.rst | 14 +++++++++++ scenario_simulator_v2/package.xml | 2 +- simulation/behavior_tree_plugin/CHANGELOG.rst | 14 +++++++++++ simulation/behavior_tree_plugin/package.xml | 2 +- simulation/do_nothing_plugin/CHANGELOG.rst | 14 +++++++++++ simulation/do_nothing_plugin/package.xml | 2 +- .../simple_sensor_simulator/CHANGELOG.rst | 25 +++++++++++++++++++ .../simple_sensor_simulator/package.xml | 2 +- simulation/simulation_interface/CHANGELOG.rst | 23 +++++++++++++++++ simulation/simulation_interface/package.xml | 2 +- simulation/traffic_simulator/CHANGELOG.rst | 17 +++++++++++++ simulation/traffic_simulator/package.xml | 2 +- .../traffic_simulator_msgs/CHANGELOG.rst | 14 +++++++++++ simulation/traffic_simulator_msgs/package.xml | 2 +- test_runner/random_test_runner/CHANGELOG.rst | 14 +++++++++++ test_runner/random_test_runner/package.xml | 2 +- .../scenario_test_runner/CHANGELOG.rst | 14 +++++++++++ test_runner/scenario_test_runner/package.xml | 2 +- 58 files changed, 466 insertions(+), 29 deletions(-) diff --git a/common/math/arithmetic/CHANGELOG.rst b/common/math/arithmetic/CHANGELOG.rst index 7b6c04cbcb2..36bf2adb8b8 100644 --- a/common/math/arithmetic/CHANGELOG.rst +++ b/common/math/arithmetic/CHANGELOG.rst @@ -21,6 +21,20 @@ Changelog for package arithmetic * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.2 (2024-08-05) +------------------ +* Merge commit 'c1cab6eb1ece2df58982f50a78fef5a5ecaa7234' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Contributors: Masaya Kataoka, SzymonParapura, koki suzuki + 3.4.1 (2024-07-30) ------------------ * Merge branch 'master' into doc/open_scenario_support diff --git a/common/math/arithmetic/package.xml b/common/math/arithmetic/package.xml index 4776b1d86b7..f533b05d41f 100644 --- a/common/math/arithmetic/package.xml +++ b/common/math/arithmetic/package.xml @@ -2,7 +2,7 @@ arithmetic - 3.4.1 + 3.4.2 arithmetic library for scenario_simulator_v2 Tatsuya Yamasaki Apache License 2.0 diff --git a/common/math/geometry/CHANGELOG.rst b/common/math/geometry/CHANGELOG.rst index 0ee3efa0b45..96ce8ab8d52 100644 --- a/common/math/geometry/CHANGELOG.rst +++ b/common/math/geometry/CHANGELOG.rst @@ -21,6 +21,20 @@ Changelog for package geometry * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.2 (2024-08-05) +------------------ +* Merge commit 'c1cab6eb1ece2df58982f50a78fef5a5ecaa7234' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Contributors: Masaya Kataoka, SzymonParapura, koki suzuki + 3.4.1 (2024-07-30) ------------------ * Merge branch 'master' into doc/open_scenario_support diff --git a/common/math/geometry/package.xml b/common/math/geometry/package.xml index 255a568654e..dbfe14571f1 100644 --- a/common/math/geometry/package.xml +++ b/common/math/geometry/package.xml @@ -2,7 +2,7 @@ geometry - 3.4.1 + 3.4.2 geometry math library for scenario_simulator_v2 application Masaya Kataoka Apache License 2.0 diff --git a/common/scenario_simulator_exception/CHANGELOG.rst b/common/scenario_simulator_exception/CHANGELOG.rst index 570387706e8..b6ce0b2ba89 100644 --- a/common/scenario_simulator_exception/CHANGELOG.rst +++ b/common/scenario_simulator_exception/CHANGELOG.rst @@ -21,6 +21,20 @@ Changelog for package scenario_simulator_exception * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.2 (2024-08-05) +------------------ +* Merge commit 'c1cab6eb1ece2df58982f50a78fef5a5ecaa7234' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Contributors: Masaya Kataoka, SzymonParapura, koki suzuki + 3.4.1 (2024-07-30) ------------------ * Merge branch 'master' into doc/open_scenario_support diff --git a/common/scenario_simulator_exception/package.xml b/common/scenario_simulator_exception/package.xml index 3dff5760fb1..431d38cbf2d 100644 --- a/common/scenario_simulator_exception/package.xml +++ b/common/scenario_simulator_exception/package.xml @@ -2,7 +2,7 @@ scenario_simulator_exception - 3.4.1 + 3.4.2 Exception types for scenario simulator Tatsuya Yamasaki Apache License 2.0 diff --git a/common/simple_junit/CHANGELOG.rst b/common/simple_junit/CHANGELOG.rst index 0b2782b93da..e43c26c2ef6 100644 --- a/common/simple_junit/CHANGELOG.rst +++ b/common/simple_junit/CHANGELOG.rst @@ -21,6 +21,20 @@ Changelog for package junit_exporter * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.2 (2024-08-05) +------------------ +* Merge commit 'c1cab6eb1ece2df58982f50a78fef5a5ecaa7234' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Contributors: Masaya Kataoka, SzymonParapura, koki suzuki + 3.4.1 (2024-07-30) ------------------ * Merge branch 'master' into doc/open_scenario_support diff --git a/common/simple_junit/package.xml b/common/simple_junit/package.xml index d4b9277a8b0..6386b24a4a0 100644 --- a/common/simple_junit/package.xml +++ b/common/simple_junit/package.xml @@ -2,7 +2,7 @@ simple_junit - 3.4.1 + 3.4.2 Lightweight JUnit library for ROS 2 Masaya Kataoka Tatsuya Yamasaki diff --git a/common/status_monitor/CHANGELOG.rst b/common/status_monitor/CHANGELOG.rst index fe49cc3ea4d..6149898fb8c 100644 --- a/common/status_monitor/CHANGELOG.rst +++ b/common/status_monitor/CHANGELOG.rst @@ -21,6 +21,20 @@ Changelog for package status_monitor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.2 (2024-08-05) +------------------ +* Merge commit 'c1cab6eb1ece2df58982f50a78fef5a5ecaa7234' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Contributors: Masaya Kataoka, SzymonParapura, koki suzuki + 3.4.1 (2024-07-30) ------------------ * Merge branch 'master' into doc/open_scenario_support diff --git a/common/status_monitor/package.xml b/common/status_monitor/package.xml index ade3b68ce5a..556364b8c62 100644 --- a/common/status_monitor/package.xml +++ b/common/status_monitor/package.xml @@ -2,7 +2,7 @@ status_monitor - 3.4.1 + 3.4.2 none Tatsuya Yamasaki Apache License 2.0 diff --git a/external/concealer/CHANGELOG.rst b/external/concealer/CHANGELOG.rst index 09953844e4f..f2690904d67 100644 --- a/external/concealer/CHANGELOG.rst +++ b/external/concealer/CHANGELOG.rst @@ -21,6 +21,20 @@ Changelog for package concealer * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.2 (2024-08-05) +------------------ +* Merge commit 'c1cab6eb1ece2df58982f50a78fef5a5ecaa7234' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Contributors: Masaya Kataoka, SzymonParapura, koki suzuki + 3.4.1 (2024-07-30) ------------------ * Merge branch 'master' into doc/open_scenario_support diff --git a/external/concealer/package.xml b/external/concealer/package.xml index 140b51e594f..79c73bc9be2 100644 --- a/external/concealer/package.xml +++ b/external/concealer/package.xml @@ -2,7 +2,7 @@ concealer - 3.4.1 + 3.4.2 Provides a class 'Autoware' to conceal miscellaneous things to simplify Autoware management of the simulator. Tatsuya Yamasaki Apache License 2.0 diff --git a/external/embree_vendor/CHANGELOG.rst b/external/embree_vendor/CHANGELOG.rst index b8da66880fe..f938dc27fa1 100644 --- a/external/embree_vendor/CHANGELOG.rst +++ b/external/embree_vendor/CHANGELOG.rst @@ -24,6 +24,20 @@ Changelog for package embree_vendor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.2 (2024-08-05) +------------------ +* Merge commit 'c1cab6eb1ece2df58982f50a78fef5a5ecaa7234' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Contributors: Masaya Kataoka, SzymonParapura, koki suzuki + 3.4.1 (2024-07-30) ------------------ * Merge branch 'master' into doc/open_scenario_support diff --git a/external/embree_vendor/package.xml b/external/embree_vendor/package.xml index 17206d671a3..15568e6da44 100644 --- a/external/embree_vendor/package.xml +++ b/external/embree_vendor/package.xml @@ -2,7 +2,7 @@ embree_vendor - 3.4.1 + 3.4.2 vendor packages for intel raytracing kernel library masaya Apache 2.0 diff --git a/map/kashiwanoha_map/CHANGELOG.rst b/map/kashiwanoha_map/CHANGELOG.rst index 09a29d4f889..abdc07a51be 100644 --- a/map/kashiwanoha_map/CHANGELOG.rst +++ b/map/kashiwanoha_map/CHANGELOG.rst @@ -21,6 +21,20 @@ Changelog for package kashiwanoha_map * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.2 (2024-08-05) +------------------ +* Merge commit 'c1cab6eb1ece2df58982f50a78fef5a5ecaa7234' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Contributors: Masaya Kataoka, SzymonParapura, koki suzuki + 3.4.1 (2024-07-30) ------------------ * Merge branch 'master' into doc/open_scenario_support diff --git a/map/kashiwanoha_map/package.xml b/map/kashiwanoha_map/package.xml index cfceebfce25..6ef23698055 100644 --- a/map/kashiwanoha_map/package.xml +++ b/map/kashiwanoha_map/package.xml @@ -2,7 +2,7 @@ kashiwanoha_map - 3.4.1 + 3.4.2 map package for kashiwanoha Masaya Kataoka Apache License 2.0 diff --git a/map/simple_cross_map/CHANGELOG.rst b/map/simple_cross_map/CHANGELOG.rst index d3a2ba16657..dbdbd51742d 100644 --- a/map/simple_cross_map/CHANGELOG.rst +++ b/map/simple_cross_map/CHANGELOG.rst @@ -9,6 +9,20 @@ Changelog for package simple_cross_map * Merge branch 'master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.2 (2024-08-05) +------------------ +* Merge commit 'c1cab6eb1ece2df58982f50a78fef5a5ecaa7234' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Contributors: Masaya Kataoka, SzymonParapura, koki suzuki + 3.4.1 (2024-07-30) ------------------ * Merge branch 'master' into doc/open_scenario_support diff --git a/map/simple_cross_map/package.xml b/map/simple_cross_map/package.xml index 1d3ba40ee26..7a08689d18a 100644 --- a/map/simple_cross_map/package.xml +++ b/map/simple_cross_map/package.xml @@ -2,7 +2,7 @@ simple_cross_map - 3.4.1 + 3.4.2 map package for simple cross Masaya Kataoka Apache License 2.0 diff --git a/mock/cpp_mock_scenarios/CHANGELOG.rst b/mock/cpp_mock_scenarios/CHANGELOG.rst index 88ee30ed5c0..ee2ea566a0a 100644 --- a/mock/cpp_mock_scenarios/CHANGELOG.rst +++ b/mock/cpp_mock_scenarios/CHANGELOG.rst @@ -21,6 +21,20 @@ Changelog for package cpp_mock_scenarios * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.2 (2024-08-05) +------------------ +* Merge commit 'c1cab6eb1ece2df58982f50a78fef5a5ecaa7234' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Contributors: Masaya Kataoka, SzymonParapura, koki suzuki + 3.4.1 (2024-07-30) ------------------ * Merge branch 'master' into doc/open_scenario_support diff --git a/mock/cpp_mock_scenarios/package.xml b/mock/cpp_mock_scenarios/package.xml index f971dad5d0e..84f86210815 100644 --- a/mock/cpp_mock_scenarios/package.xml +++ b/mock/cpp_mock_scenarios/package.xml @@ -2,7 +2,7 @@ cpp_mock_scenarios - 3.4.1 + 3.4.2 C++ mock scenarios masaya Apache License 2.0 diff --git a/openscenario/openscenario_experimental_catalog/CHANGELOG.rst b/openscenario/openscenario_experimental_catalog/CHANGELOG.rst index 5584f01a717..fc47e7693bb 100644 --- a/openscenario/openscenario_experimental_catalog/CHANGELOG.rst +++ b/openscenario/openscenario_experimental_catalog/CHANGELOG.rst @@ -21,6 +21,20 @@ Changelog for package openscenario_experimental_catalog * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.2 (2024-08-05) +------------------ +* Merge commit 'c1cab6eb1ece2df58982f50a78fef5a5ecaa7234' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Contributors: Masaya Kataoka, SzymonParapura, koki suzuki + 3.4.1 (2024-07-30) ------------------ * Merge branch 'master' into doc/open_scenario_support diff --git a/openscenario/openscenario_experimental_catalog/package.xml b/openscenario/openscenario_experimental_catalog/package.xml index 4a8fda2841c..8e3160af2e6 100644 --- a/openscenario/openscenario_experimental_catalog/package.xml +++ b/openscenario/openscenario_experimental_catalog/package.xml @@ -2,7 +2,7 @@ openscenario_experimental_catalog - 3.4.1 + 3.4.2 TIER IV experimental catalogs for OpenSCENARIO Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter/CHANGELOG.rst b/openscenario/openscenario_interpreter/CHANGELOG.rst index 633d6a844ec..5e8546533e3 100644 --- a/openscenario/openscenario_interpreter/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter/CHANGELOG.rst @@ -32,6 +32,28 @@ Changelog for package openscenario_interpreter * add publish_empty_context parameter * Contributors: Masaya Kataoka +3.4.2 (2024-08-05) +------------------ +* Merge branch 'master' into doc/longitudinal-control +* Merge pull request `#1321 `_ from tier4/feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge commit 'c1cab6eb1ece2df58982f50a78fef5a5ecaa7234' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* feat: Enhance IMU sensor configuration and initialization + - Added frame_id to ImuSensorConfiguration + - Separated noise standard deviations for orientation, twist, and acceleration + - Updated ImuSensorBase and ImuSensor classes for new noise distributions +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* feat(simple_sensor_simulator, imu): add gravity vector, tidy up +* feat(simulator_core, api, zmq): add attachImuSensor, add update imu sensors +* Contributors: Dawid Moszynski, Koki Suzuki, Kotaro Yoshimoto, Masaya Kataoka, SzymonParapura, koki suzuki + 3.4.1 (2024-07-30) ------------------ * Merge branch 'master' into doc/open_scenario_support diff --git a/openscenario/openscenario_interpreter/package.xml b/openscenario/openscenario_interpreter/package.xml index 4959c10deef..00d7949643c 100644 --- a/openscenario/openscenario_interpreter/package.xml +++ b/openscenario/openscenario_interpreter/package.xml @@ -2,7 +2,7 @@ openscenario_interpreter - 3.4.1 + 3.4.2 OpenSCENARIO 1.2.0 interpreter package for Autoware Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter_example/CHANGELOG.rst b/openscenario/openscenario_interpreter_example/CHANGELOG.rst index 430a037ac03..6a6b0242dc8 100644 --- a/openscenario/openscenario_interpreter_example/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter_example/CHANGELOG.rst @@ -21,6 +21,20 @@ Changelog for package openscenario_interpreter_example * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.2 (2024-08-05) +------------------ +* Merge commit 'c1cab6eb1ece2df58982f50a78fef5a5ecaa7234' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Contributors: Masaya Kataoka, SzymonParapura, koki suzuki + 3.4.1 (2024-07-30) ------------------ * Merge branch 'master' into doc/open_scenario_support diff --git a/openscenario/openscenario_interpreter_example/package.xml b/openscenario/openscenario_interpreter_example/package.xml index 4c9b91216db..06c82717359 100644 --- a/openscenario/openscenario_interpreter_example/package.xml +++ b/openscenario/openscenario_interpreter_example/package.xml @@ -3,7 +3,7 @@ openscenario_interpreter_example - 3.4.1 + 3.4.2 Examples for some TIER IV OpenSCENARIO Interpreter's features Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst b/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst index 96cd09eb6ea..1c8ae389b5c 100644 --- a/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst @@ -21,6 +21,20 @@ Changelog for package openscenario_interpreter_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.2 (2024-08-05) +------------------ +* Merge commit 'c1cab6eb1ece2df58982f50a78fef5a5ecaa7234' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Contributors: Masaya Kataoka, SzymonParapura, koki suzuki + 3.4.1 (2024-07-30) ------------------ * Merge branch 'master' into doc/open_scenario_support diff --git a/openscenario/openscenario_interpreter_msgs/package.xml b/openscenario/openscenario_interpreter_msgs/package.xml index b18a3f7a9ba..697d6261d74 100644 --- a/openscenario/openscenario_interpreter_msgs/package.xml +++ b/openscenario/openscenario_interpreter_msgs/package.xml @@ -2,7 +2,7 @@ openscenario_interpreter_msgs - 3.4.1 + 3.4.2 ROS message types for package openscenario_interpreter Yamasaki Tatsuya Apache License 2.0 diff --git a/openscenario/openscenario_preprocessor/CHANGELOG.rst b/openscenario/openscenario_preprocessor/CHANGELOG.rst index e1de288583e..5b9c6ab78ad 100644 --- a/openscenario/openscenario_preprocessor/CHANGELOG.rst +++ b/openscenario/openscenario_preprocessor/CHANGELOG.rst @@ -21,6 +21,20 @@ Changelog for package openscenario_preprocessor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.2 (2024-08-05) +------------------ +* Merge commit 'c1cab6eb1ece2df58982f50a78fef5a5ecaa7234' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Contributors: Masaya Kataoka, SzymonParapura, koki suzuki + 3.4.1 (2024-07-30) ------------------ * Merge branch 'master' into doc/open_scenario_support diff --git a/openscenario/openscenario_preprocessor/package.xml b/openscenario/openscenario_preprocessor/package.xml index ff3cce230d6..a1bcfe5d27d 100644 --- a/openscenario/openscenario_preprocessor/package.xml +++ b/openscenario/openscenario_preprocessor/package.xml @@ -3,7 +3,7 @@ openscenario_preprocessor - 3.4.1 + 3.4.2 Example package for TIER IV OpenSCENARIO Interpreter Kotaro Yoshimoto Apache License 2.0 diff --git a/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst b/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst index 45a0949520f..d85a9885d89 100644 --- a/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst +++ b/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst @@ -21,6 +21,20 @@ Changelog for package openscenario_preprocessor_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.2 (2024-08-05) +------------------ +* Merge commit 'c1cab6eb1ece2df58982f50a78fef5a5ecaa7234' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Contributors: Masaya Kataoka, SzymonParapura, koki suzuki + 3.4.1 (2024-07-30) ------------------ * Merge branch 'master' into doc/open_scenario_support diff --git a/openscenario/openscenario_preprocessor_msgs/package.xml b/openscenario/openscenario_preprocessor_msgs/package.xml index b9b00b6a039..6efd1246130 100644 --- a/openscenario/openscenario_preprocessor_msgs/package.xml +++ b/openscenario/openscenario_preprocessor_msgs/package.xml @@ -2,7 +2,7 @@ openscenario_preprocessor_msgs - 3.4.1 + 3.4.2 ROS message types for package openscenario_preprocessor Kotaro Yoshimoto Apache License 2.0 diff --git a/openscenario/openscenario_utility/CHANGELOG.rst b/openscenario/openscenario_utility/CHANGELOG.rst index 6c2760604c4..f5447823350 100644 --- a/openscenario/openscenario_utility/CHANGELOG.rst +++ b/openscenario/openscenario_utility/CHANGELOG.rst @@ -24,6 +24,20 @@ Changelog for package openscenario_utility * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.2 (2024-08-05) +------------------ +* Merge commit 'c1cab6eb1ece2df58982f50a78fef5a5ecaa7234' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Contributors: Masaya Kataoka, SzymonParapura, koki suzuki + 3.4.1 (2024-07-30) ------------------ * Merge branch 'master' into doc/open_scenario_support diff --git a/openscenario/openscenario_utility/package.xml b/openscenario/openscenario_utility/package.xml index ab2e12c6b85..01b23b31e5f 100644 --- a/openscenario/openscenario_utility/package.xml +++ b/openscenario/openscenario_utility/package.xml @@ -2,7 +2,7 @@ openscenario_utility - 3.4.1 + 3.4.2 Utility tools for ASAM OpenSCENARIO 1.2.0 Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_validator/CHANGELOG.rst b/openscenario/openscenario_validator/CHANGELOG.rst index 8eeea4a1c84..8e1f1f599ec 100644 --- a/openscenario/openscenario_validator/CHANGELOG.rst +++ b/openscenario/openscenario_validator/CHANGELOG.rst @@ -10,6 +10,20 @@ Changelog for package openscenario_validator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.2 (2024-08-05) +------------------ +* Merge commit 'c1cab6eb1ece2df58982f50a78fef5a5ecaa7234' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Contributors: Masaya Kataoka, SzymonParapura, koki suzuki + 3.4.1 (2024-07-30) ------------------ * Merge branch 'master' into doc/open_scenario_support diff --git a/openscenario/openscenario_validator/package.xml b/openscenario/openscenario_validator/package.xml index 30348686cdc..bd21a92e59f 100644 --- a/openscenario/openscenario_validator/package.xml +++ b/openscenario/openscenario_validator/package.xml @@ -2,7 +2,7 @@ openscenario_validator - 3.4.1 + 3.4.2 Validator for OpenSCENARIO 1.3 Kotaro Yoshimoto Apache License 2.0 diff --git a/rviz_plugins/openscenario_visualization/CHANGELOG.rst b/rviz_plugins/openscenario_visualization/CHANGELOG.rst index 474305a1de6..b3e1b9e5c14 100644 --- a/rviz_plugins/openscenario_visualization/CHANGELOG.rst +++ b/rviz_plugins/openscenario_visualization/CHANGELOG.rst @@ -21,6 +21,20 @@ Changelog for package openscenario_visualization * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.2 (2024-08-05) +------------------ +* Merge commit 'c1cab6eb1ece2df58982f50a78fef5a5ecaa7234' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Contributors: Masaya Kataoka, SzymonParapura, koki suzuki + 3.4.1 (2024-07-30) ------------------ * Merge branch 'master' into doc/open_scenario_support diff --git a/rviz_plugins/openscenario_visualization/package.xml b/rviz_plugins/openscenario_visualization/package.xml index f140c14f106..fd3e3bb1708 100644 --- a/rviz_plugins/openscenario_visualization/package.xml +++ b/rviz_plugins/openscenario_visualization/package.xml @@ -2,7 +2,7 @@ openscenario_visualization - 3.4.1 + 3.4.2 Visualization tools for simulation results Masaya Kataoka Kyoichi Sugahara diff --git a/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst b/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst index 448b4c17643..3c00a040c3f 100644 --- a/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst +++ b/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst @@ -21,6 +21,20 @@ Changelog for package real_time_factor_control_rviz_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.2 (2024-08-05) +------------------ +* Merge commit 'c1cab6eb1ece2df58982f50a78fef5a5ecaa7234' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Contributors: Masaya Kataoka, SzymonParapura, koki suzuki + 3.4.1 (2024-07-30) ------------------ * Merge branch 'master' into doc/open_scenario_support diff --git a/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml b/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml index ed803ceac17..115f07ed1c1 100644 --- a/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml +++ b/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml @@ -2,7 +2,7 @@ real_time_factor_control_rviz_plugin - 3.4.1 + 3.4.2 Slider controlling real time factor value. Paweł Lech Apache License 2.0 diff --git a/scenario_simulator_v2/CHANGELOG.rst b/scenario_simulator_v2/CHANGELOG.rst index 6410f0674ed..b263feb86c0 100644 --- a/scenario_simulator_v2/CHANGELOG.rst +++ b/scenario_simulator_v2/CHANGELOG.rst @@ -21,6 +21,20 @@ Changelog for package scenario_simulator_v2 * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.2 (2024-08-05) +------------------ +* Merge commit 'c1cab6eb1ece2df58982f50a78fef5a5ecaa7234' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Contributors: Masaya Kataoka, SzymonParapura, koki suzuki + 3.4.1 (2024-07-30) ------------------ * Merge branch 'master' into doc/open_scenario_support diff --git a/scenario_simulator_v2/package.xml b/scenario_simulator_v2/package.xml index cee69b01c8b..0f087fc6af4 100644 --- a/scenario_simulator_v2/package.xml +++ b/scenario_simulator_v2/package.xml @@ -2,7 +2,7 @@ scenario_simulator_v2 - 3.4.1 + 3.4.2 scenario testing framework for Autoware Masaya Kataoka Apache License 2.0 diff --git a/simulation/behavior_tree_plugin/CHANGELOG.rst b/simulation/behavior_tree_plugin/CHANGELOG.rst index a09ba91219f..c8f6ccd7f2b 100644 --- a/simulation/behavior_tree_plugin/CHANGELOG.rst +++ b/simulation/behavior_tree_plugin/CHANGELOG.rst @@ -21,6 +21,20 @@ Changelog for package behavior_tree_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.2 (2024-08-05) +------------------ +* Merge commit 'c1cab6eb1ece2df58982f50a78fef5a5ecaa7234' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Contributors: Masaya Kataoka, SzymonParapura, koki suzuki + 3.4.1 (2024-07-30) ------------------ * Merge branch 'master' into doc/open_scenario_support diff --git a/simulation/behavior_tree_plugin/package.xml b/simulation/behavior_tree_plugin/package.xml index aca3bfd10bc..77bf5abe99b 100644 --- a/simulation/behavior_tree_plugin/package.xml +++ b/simulation/behavior_tree_plugin/package.xml @@ -2,7 +2,7 @@ behavior_tree_plugin - 3.4.1 + 3.4.2 Behavior tree plugin for traffic_simulator masaya Apache 2.0 diff --git a/simulation/do_nothing_plugin/CHANGELOG.rst b/simulation/do_nothing_plugin/CHANGELOG.rst index 025faac304e..6fdde310518 100644 --- a/simulation/do_nothing_plugin/CHANGELOG.rst +++ b/simulation/do_nothing_plugin/CHANGELOG.rst @@ -21,6 +21,20 @@ Changelog for package do_nothing_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.2 (2024-08-05) +------------------ +* Merge commit 'c1cab6eb1ece2df58982f50a78fef5a5ecaa7234' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Contributors: Masaya Kataoka, SzymonParapura, koki suzuki + 3.4.1 (2024-07-30) ------------------ * Merge branch 'master' into doc/open_scenario_support diff --git a/simulation/do_nothing_plugin/package.xml b/simulation/do_nothing_plugin/package.xml index 0307a928e56..c2bc7f89c43 100644 --- a/simulation/do_nothing_plugin/package.xml +++ b/simulation/do_nothing_plugin/package.xml @@ -2,7 +2,7 @@ do_nothing_plugin - 3.4.1 + 3.4.2 Behavior plugin for do nothing Masaya Kataoka Apache 2.0 diff --git a/simulation/simple_sensor_simulator/CHANGELOG.rst b/simulation/simple_sensor_simulator/CHANGELOG.rst index f2a45f9d25b..b5f73466cc9 100644 --- a/simulation/simple_sensor_simulator/CHANGELOG.rst +++ b/simulation/simple_sensor_simulator/CHANGELOG.rst @@ -21,6 +21,31 @@ Changelog for package simple_sensor_simulator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.2 (2024-08-05) +------------------ +* Merge branch 'master' into doc/longitudinal-control +* Merge pull request `#1321 `_ from tier4/feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge commit 'c1cab6eb1ece2df58982f50a78fef5a5ecaa7234' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* feat: Enhance IMU sensor configuration and initialization + - Added frame_id to ImuSensorConfiguration + - Separated noise standard deviations for orientation, twist, and acceleration + - Updated ImuSensorBase and ImuSensor classes for new noise distributions +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Fix an issue with an invalid namespace imu_link +* Fix an issue with an invalid namespace imu_link +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* feat(simple_sensor_simulator, imu): add gravity vector, tidy up +* feat(simulator_core, api, zmq): add attachImuSensor, add update imu sensors +* feat(simple_sensor_simulator): add imu_sensor +* Contributors: Dawid Moszynski, Koki Suzuki, Kotaro Yoshimoto, Masaya Kataoka, SzymonParapura, koki suzuki + 3.4.1 (2024-07-30) ------------------ * Merge branch 'master' into doc/open_scenario_support diff --git a/simulation/simple_sensor_simulator/package.xml b/simulation/simple_sensor_simulator/package.xml index 9a96c82d724..90bb8780465 100644 --- a/simulation/simple_sensor_simulator/package.xml +++ b/simulation/simple_sensor_simulator/package.xml @@ -1,7 +1,7 @@ simple_sensor_simulator - 3.4.1 + 3.4.2 simple_sensor_simulator package masaya kataoka diff --git a/simulation/simulation_interface/CHANGELOG.rst b/simulation/simulation_interface/CHANGELOG.rst index 187a8a14b90..1ffa0eab9da 100644 --- a/simulation/simulation_interface/CHANGELOG.rst +++ b/simulation/simulation_interface/CHANGELOG.rst @@ -21,6 +21,29 @@ Changelog for package simulation_interface * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.2 (2024-08-05) +------------------ +* Merge branch 'master' into doc/longitudinal-control +* Merge pull request `#1321 `_ from tier4/feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge commit 'c1cab6eb1ece2df58982f50a78fef5a5ecaa7234' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* feat: Enhance IMU sensor configuration and initialization + - Added frame_id to ImuSensorConfiguration + - Separated noise standard deviations for orientation, twist, and acceleration + - Updated ImuSensorBase and ImuSensor classes for new noise distributions +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* feat(simple_sensor_simulator, imu): add gravity vector, tidy up +* feat(simulator_core, api, zmq): add attachImuSensor, add update imu sensors +* feat(simple_sensor_simulator): add imu_sensor +* Contributors: Dawid Moszynski, Koki Suzuki, Kotaro Yoshimoto, Masaya Kataoka, SzymonParapura, koki suzuki + 3.4.1 (2024-07-30) ------------------ * Merge branch 'master' into doc/open_scenario_support diff --git a/simulation/simulation_interface/package.xml b/simulation/simulation_interface/package.xml index d6d2668063d..885589fd270 100644 --- a/simulation/simulation_interface/package.xml +++ b/simulation/simulation_interface/package.xml @@ -2,7 +2,7 @@ simulation_interface - 3.4.1 + 3.4.2 packages to define interface between simulator and scenario interpreter Masaya Kataoka Apache License 2.0 diff --git a/simulation/traffic_simulator/CHANGELOG.rst b/simulation/traffic_simulator/CHANGELOG.rst index b2979f9d273..e3e93704b38 100644 --- a/simulation/traffic_simulator/CHANGELOG.rst +++ b/simulation/traffic_simulator/CHANGELOG.rst @@ -21,6 +21,23 @@ Changelog for package traffic_simulator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.2 (2024-08-05) +------------------ +* Merge branch 'master' into doc/longitudinal-control +* Merge pull request `#1321 `_ from tier4/feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge commit 'c1cab6eb1ece2df58982f50a78fef5a5ecaa7234' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* feat(simulator_core, api, zmq): add attachImuSensor, add update imu sensors +* Contributors: Dawid Moszynski, Koki Suzuki, Kotaro Yoshimoto, Masaya Kataoka, SzymonParapura, koki suzuki + 3.4.1 (2024-07-30) ------------------ * Merge branch 'master' into doc/open_scenario_support diff --git a/simulation/traffic_simulator/package.xml b/simulation/traffic_simulator/package.xml index 585537d7a8a..b2c8b089034 100644 --- a/simulation/traffic_simulator/package.xml +++ b/simulation/traffic_simulator/package.xml @@ -1,7 +1,7 @@ traffic_simulator - 3.4.1 + 3.4.2 control traffic flow masaya kataoka diff --git a/simulation/traffic_simulator_msgs/CHANGELOG.rst b/simulation/traffic_simulator_msgs/CHANGELOG.rst index 0a0876b5856..4c0b74852aa 100644 --- a/simulation/traffic_simulator_msgs/CHANGELOG.rst +++ b/simulation/traffic_simulator_msgs/CHANGELOG.rst @@ -21,6 +21,20 @@ Changelog for package openscenario_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.2 (2024-08-05) +------------------ +* Merge commit 'c1cab6eb1ece2df58982f50a78fef5a5ecaa7234' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Contributors: Masaya Kataoka, SzymonParapura, koki suzuki + 3.4.1 (2024-07-30) ------------------ * Merge branch 'master' into doc/open_scenario_support diff --git a/simulation/traffic_simulator_msgs/package.xml b/simulation/traffic_simulator_msgs/package.xml index 29d83e0fd73..2c1dedb6696 100644 --- a/simulation/traffic_simulator_msgs/package.xml +++ b/simulation/traffic_simulator_msgs/package.xml @@ -2,7 +2,7 @@ traffic_simulator_msgs - 3.4.1 + 3.4.2 ROS messages for openscenario Masaya Kataoka Apache License 2.0 diff --git a/test_runner/random_test_runner/CHANGELOG.rst b/test_runner/random_test_runner/CHANGELOG.rst index d5aa32cb2f2..6a1299f1137 100644 --- a/test_runner/random_test_runner/CHANGELOG.rst +++ b/test_runner/random_test_runner/CHANGELOG.rst @@ -21,6 +21,20 @@ Changelog for package random_test_runner * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.2 (2024-08-05) +------------------ +* Merge commit 'c1cab6eb1ece2df58982f50a78fef5a5ecaa7234' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Contributors: Masaya Kataoka, SzymonParapura, koki suzuki + 3.4.1 (2024-07-30) ------------------ * Merge branch 'master' into doc/open_scenario_support diff --git a/test_runner/random_test_runner/package.xml b/test_runner/random_test_runner/package.xml index 06bc95d02c7..bf4e1a5bcc6 100644 --- a/test_runner/random_test_runner/package.xml +++ b/test_runner/random_test_runner/package.xml @@ -2,7 +2,7 @@ random_test_runner - 3.4.1 + 3.4.2 Random behavior test runner piotr-zyskowski-rai Apache License 2.0 diff --git a/test_runner/scenario_test_runner/CHANGELOG.rst b/test_runner/scenario_test_runner/CHANGELOG.rst index 71adb8b8e11..d4fef8eb21c 100644 --- a/test_runner/scenario_test_runner/CHANGELOG.rst +++ b/test_runner/scenario_test_runner/CHANGELOG.rst @@ -35,6 +35,20 @@ Changelog for package scenario_test_runner * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.2 (2024-08-05) +------------------ +* Merge commit 'c1cab6eb1ece2df58982f50a78fef5a5ecaa7234' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Merge branch 'master' into doc/longitudinal-control +* Merge branch 'master' into feat/RJD-1199-add-imu-sensor-to-simple-sensor-simulator +* Contributors: Masaya Kataoka, SzymonParapura, koki suzuki + 3.4.1 (2024-07-30) ------------------ * Merge branch 'master' into doc/open_scenario_support diff --git a/test_runner/scenario_test_runner/package.xml b/test_runner/scenario_test_runner/package.xml index 80a6d8ba53c..f88e0c3572f 100644 --- a/test_runner/scenario_test_runner/package.xml +++ b/test_runner/scenario_test_runner/package.xml @@ -2,7 +2,7 @@ scenario_test_runner - 3.4.1 + 3.4.2 scenario test runner package Tatsuya Yamasaki Apache License 2.0 From 3f9c4c3efc40afdeb6a41b1a7c8edf2607bc2e65 Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Mon, 5 Aug 2024 14:29:49 +0900 Subject: [PATCH 075/304] Update MagicSubscription to share resources between instances Signed-off-by: yamacir-kit --- .../syntax/user_defined_value_condition.hpp | 2 - .../syntax/user_defined_value_condition.cpp | 84 ++++++++++++------- 2 files changed, 53 insertions(+), 33 deletions(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/user_defined_value_condition.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/user_defined_value_condition.hpp index 585d6d9e273..7ca1707fd9e 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/user_defined_value_condition.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/user_defined_value_condition.hpp @@ -45,8 +45,6 @@ class UserDefinedValueCondition : private SimulatorCore::NonStandardOperation std::function evaluate_value; - static uint64_t magic_subscription_counter; - public: const String name; diff --git a/openscenario/openscenario_interpreter/src/syntax/user_defined_value_condition.cpp b/openscenario/openscenario_interpreter/src/syntax/user_defined_value_condition.cpp index fd99947d906..c13b4d8edc1 100644 --- a/openscenario/openscenario_interpreter/src/syntax/user_defined_value_condition.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/user_defined_value_condition.cpp @@ -33,48 +33,72 @@ namespace openscenario_interpreter inline namespace syntax { template -struct MagicSubscription : private rclcpp::Node, public T +struct MagicSubscription : public T { - std::promise promise; + struct Subscriber + { + rclcpp::Node node; - std::thread thread; + std::atomic_bool stop_requested = false; - std::exception_ptr thrown; + std::promise promise; - typename rclcpp::Subscription::SharedPtr subscription; + std::future future; -public: - explicit MagicSubscription(const std::string & node_name, const std::string & topic_name) - : rclcpp::Node(node_name), - thread( - [this](auto future) { - while (rclcpp::ok() and - future.wait_for(std::chrono::milliseconds(1)) == std::future_status::timeout) { - try { - rclcpp::spin_some(get_node_base_interface()); - } catch (...) { - thrown = std::current_exception(); + std::thread thread; + + explicit Subscriber() + : node("magic_subscription"), + future(promise.get_future()), + thread( + [this](std::promise promise) { + while (rclcpp::ok() and not stop_requested) { + try { + rclcpp::spin_some(node.get_node_base_interface()); + } catch (...) { + promise.set_exception(std::current_exception()); + } } - } - }, - std::move(promise.get_future())), - subscription(create_subscription(topic_name, 1, [this](const typename T::SharedPtr message) { - static_cast(*this) = *message; - })) + }, + std::move(promise)) + { + } + }; + + static auto subscriber() -> auto & + { + static std::unique_ptr subscriber = nullptr; + + if (not subscriber) { + subscriber = std::make_unique(); + } + + return subscriber; + } + + typename rclcpp::Subscription::SharedPtr subscription; + + static inline std::size_t count = 0; + + explicit MagicSubscription(const std::string & topic_name) + : subscription(subscriber()->node.template create_subscription( + topic_name, 1, [this, count = count++](const typename T::SharedPtr message) { + static_cast(*this) = *message; + })) { } ~MagicSubscription() { - if (thread.joinable()) { - promise.set_value(); - thread.join(); + if ( + not --count and subscriber()->thread.joinable() and + not subscriber()->stop_requested.exchange(true)) { + subscriber()->thread.join(); + subscriber().reset(); } } }; -uint64_t UserDefinedValueCondition::magic_subscription_counter = 0; - UserDefinedValueCondition::UserDefinedValueCondition(const pugi::xml_node & node, Scope & scope) : name(readAttribute("name", node, scope)), value(readAttribute("value", node, scope)), @@ -134,9 +158,7 @@ UserDefinedValueCondition::UserDefinedValueCondition(const pugi::xml_node & node using tier4_simulation_msgs::msg::UserDefinedValueType; evaluate_value = - [&, current_message = std::make_shared>( - result.str(1) + "_subscription_" + std::to_string(++magic_subscription_counter), - result.str(0))]() { + [this, message = std::make_shared>(result.str(0))]() { auto evaluate = [](const auto & user_defined_value) { switch (user_defined_value.type.data) { case UserDefinedValueType::BOOLEAN: @@ -158,7 +180,7 @@ UserDefinedValueCondition::UserDefinedValueCondition(const pugi::xml_node & node } }; - return not current_message->value.empty() ? evaluate(*current_message) : unspecified; + return message->value.empty() ? unspecified : evaluate(*message); }; #else throw SyntaxError( From 1f6c0d72701981fb5ceabaf624610ca102fdb3ea Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Mon, 5 Aug 2024 14:32:21 +0900 Subject: [PATCH 076/304] Update test scenario `ByValueCondition.UserDefinedValueCondition.yaml` Signed-off-by: yamacir-kit --- ...ueCondition.UserDefinedValueCondition.yaml | 134 +++++++++++++++++- 1 file changed, 133 insertions(+), 1 deletion(-) diff --git a/test_runner/scenario_test_runner/scenario/ByValueCondition.UserDefinedValueCondition.yaml b/test_runner/scenario_test_runner/scenario/ByValueCondition.UserDefinedValueCondition.yaml index 502188c68f4..427fcce95df 100644 --- a/test_runner/scenario_test_runner/scenario/ByValueCondition.UserDefinedValueCondition.yaml +++ b/test_runner/scenario_test_runner/scenario/ByValueCondition.UserDefinedValueCondition.yaml @@ -106,7 +106,7 @@ OpenSCENARIO: conditionEdge: none ByValueCondition: SimulationTimeCondition: - value: 120 + value: 180 rule: greaterThan - Condition: - name: '' @@ -144,11 +144,33 @@ OpenSCENARIO: - *COUNT_UP - *COUNT_UP - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP # 10 + + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP # 20 + - *COUNT_UP - *COUNT_UP - *COUNT_UP - *COUNT_UP - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP # 30 - *COUNT_UP - *COUNT_UP @@ -156,12 +178,121 @@ OpenSCENARIO: - *COUNT_UP - *COUNT_UP - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP # 40 + - *COUNT_UP - *COUNT_UP - *COUNT_UP - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP # 50 - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP # 60 + + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP # 70 + + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP # 80 + + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP # 90 + + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP # 100 + + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP # 110 + + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP # 120 + + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP # 130 + + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP + - *COUNT_UP # 140 + - *COUNT_UP - *COUNT_UP - *COUNT_UP @@ -171,6 +302,7 @@ OpenSCENARIO: - *COUNT_UP - *COUNT_UP - *COUNT_UP + - *COUNT_UP # 150 Action: - name: '' UserDefinedAction: From db4690e6d88bfd72468e05eb0d3a6cf7d7421e56 Mon Sep 17 00:00:00 2001 From: Dawid Moszynski Date: Mon, 5 Aug 2024 10:21:52 +0200 Subject: [PATCH 077/304] ref(traffic_controller): rename make->appendDebugMarker --- .../include/traffic_simulator/traffic/traffic_module_base.hpp | 2 +- .../include/traffic_simulator/traffic/traffic_sink.hpp | 3 ++- .../traffic_simulator/src/traffic/traffic_controller.cpp | 2 +- simulation/traffic_simulator/src/traffic/traffic_sink.cpp | 3 ++- 4 files changed, 6 insertions(+), 4 deletions(-) diff --git a/simulation/traffic_simulator/include/traffic_simulator/traffic/traffic_module_base.hpp b/simulation/traffic_simulator/include/traffic_simulator/traffic/traffic_module_base.hpp index e21e73b8a0f..41e52aaf0e4 100644 --- a/simulation/traffic_simulator/include/traffic_simulator/traffic/traffic_module_base.hpp +++ b/simulation/traffic_simulator/include/traffic_simulator/traffic/traffic_module_base.hpp @@ -37,7 +37,7 @@ class TrafficModuleBase public: TrafficModuleBase() {} virtual void execute(const double current_time, const double step_time) = 0; - virtual auto makeDebugMarker(visualization_msgs::msg::MarkerArray &) const -> void{}; + virtual auto appendDebugMarker(visualization_msgs::msg::MarkerArray &) const -> void{}; }; } // namespace traffic } // namespace traffic_simulator diff --git a/simulation/traffic_simulator/include/traffic_simulator/traffic/traffic_sink.hpp b/simulation/traffic_simulator/include/traffic_simulator/traffic/traffic_sink.hpp index 5ec17397636..0754ace3f92 100644 --- a/simulation/traffic_simulator/include/traffic_simulator/traffic/traffic_sink.hpp +++ b/simulation/traffic_simulator/include/traffic_simulator/traffic/traffic_sink.hpp @@ -50,7 +50,8 @@ class TrafficSink : public TrafficModuleBase const double radius; const geometry_msgs::msg::Point position; void execute(const double current_time, const double step_time) override; - auto makeDebugMarker(visualization_msgs::msg::MarkerArray & marker_array) const -> void override; + auto appendDebugMarker(visualization_msgs::msg::MarkerArray & marker_array) const + -> void override; private: const std::function(void)> get_entity_names_function; diff --git a/simulation/traffic_simulator/src/traffic/traffic_controller.cpp b/simulation/traffic_simulator/src/traffic/traffic_controller.cpp index 27a5d42fd57..7ebdb8710dd 100644 --- a/simulation/traffic_simulator/src/traffic/traffic_controller.cpp +++ b/simulation/traffic_simulator/src/traffic/traffic_controller.cpp @@ -79,7 +79,7 @@ auto TrafficController::makeDebugMarker() const -> const visualization_msgs::msg static const auto marker_array = [&]() { visualization_msgs::msg::MarkerArray marker_array; for (size_t i = 0; i < modules_.size(); ++i) { - modules_[i]->makeDebugMarker(marker_array); + modules_[i]->appendDebugMarker(marker_array); } return marker_array; }(); diff --git a/simulation/traffic_simulator/src/traffic/traffic_sink.cpp b/simulation/traffic_simulator/src/traffic/traffic_sink.cpp index 32934506e23..b85663f17d6 100644 --- a/simulation/traffic_simulator/src/traffic/traffic_sink.cpp +++ b/simulation/traffic_simulator/src/traffic/traffic_sink.cpp @@ -64,7 +64,8 @@ void TrafficSink::execute( } } -auto TrafficSink::makeDebugMarker(visualization_msgs::msg::MarkerArray & marker_array) const -> void +auto TrafficSink::appendDebugMarker(visualization_msgs::msg::MarkerArray & marker_array) const + -> void { const auto lanelet_text = std::to_string(lanelet_id); visualization_msgs::msg::Marker traffic_sink_marker; From af4170d05b3126a566b12f9e7f777aff74f54e89 Mon Sep 17 00:00:00 2001 From: robomic Date: Mon, 5 Aug 2024 11:24:24 +0200 Subject: [PATCH 078/304] add a proper structure to the test files --- common/math/geometry/test/CMakeLists.txt | 35 +++++++------------ .../test/{ => src}/expect_eq_macros.hpp | 0 .../test/src/intersection/CMakeLists.txt | 5 +++ .../{ => src/intersection}/test_collision.cpp | 2 +- .../intersection}/test_intersection.cpp | 4 +-- .../geometry/test/src/polygon/CMakeLists.txt | 5 +++ .../{ => src/polygon}/test_line_segment.cpp | 4 +-- .../test/{ => src/polygon}/test_polygon.cpp | 4 +-- .../test/src/quaternion/CMakeLists.txt | 2 ++ .../{ => src/quaternion}/test_quaternion.cpp | 4 +-- .../geometry/test/src/solver/CMakeLists.txt | 2 ++ .../solver}/test_polynomial_solver.cpp | 0 .../geometry/test/src/spline/CMakeLists.txt | 8 +++++ .../spline}/test_catmull_rom_spline.cpp | 4 +-- .../spline}/test_catmull_rom_subspline.cpp | 4 +-- .../{ => src/spline}/test_hermite_curve.cpp | 4 +-- .../test/{ => src}/test_bounding_box.cpp | 0 .../geometry/test/{ => src}/test_distance.cpp | 0 .../test/{ => src}/test_transform.cpp | 0 .../geometry/test/{ => src}/test_utils.hpp | 0 .../test/{ => src}/vector3/CMakeLists.txt | 0 .../vector3/test_truncate_custom.cpp | 0 .../{ => src}/vector3/test_truncate_msg.cpp | 0 .../test/{ => src}/vector3/test_vector3.cpp | 0 24 files changed, 49 insertions(+), 38 deletions(-) rename common/math/geometry/test/{ => src}/expect_eq_macros.hpp (100%) create mode 100644 common/math/geometry/test/src/intersection/CMakeLists.txt rename common/math/geometry/test/{ => src/intersection}/test_collision.cpp (99%) rename common/math/geometry/test/{ => src/intersection}/test_intersection.cpp (98%) create mode 100644 common/math/geometry/test/src/polygon/CMakeLists.txt rename common/math/geometry/test/{ => src/polygon}/test_line_segment.cpp (99%) rename common/math/geometry/test/{ => src/polygon}/test_polygon.cpp (98%) create mode 100644 common/math/geometry/test/src/quaternion/CMakeLists.txt rename common/math/geometry/test/{ => src/quaternion}/test_quaternion.cpp (96%) create mode 100644 common/math/geometry/test/src/solver/CMakeLists.txt rename common/math/geometry/test/{ => src/solver}/test_polynomial_solver.cpp (100%) create mode 100644 common/math/geometry/test/src/spline/CMakeLists.txt rename common/math/geometry/test/{ => src/spline}/test_catmull_rom_spline.cpp (99%) rename common/math/geometry/test/{ => src/spline}/test_catmull_rom_subspline.cpp (98%) rename common/math/geometry/test/{ => src/spline}/test_hermite_curve.cpp (99%) rename common/math/geometry/test/{ => src}/test_bounding_box.cpp (100%) rename common/math/geometry/test/{ => src}/test_distance.cpp (100%) rename common/math/geometry/test/{ => src}/test_transform.cpp (100%) rename common/math/geometry/test/{ => src}/test_utils.hpp (100%) rename common/math/geometry/test/{ => src}/vector3/CMakeLists.txt (100%) rename common/math/geometry/test/{ => src}/vector3/test_truncate_custom.cpp (100%) rename common/math/geometry/test/{ => src}/vector3/test_truncate_msg.cpp (100%) rename common/math/geometry/test/{ => src}/vector3/test_vector3.cpp (100%) diff --git a/common/math/geometry/test/CMakeLists.txt b/common/math/geometry/test/CMakeLists.txt index dfd0a09460b..eed4ab3431c 100644 --- a/common/math/geometry/test/CMakeLists.txt +++ b/common/math/geometry/test/CMakeLists.txt @@ -1,26 +1,15 @@ -add_subdirectory(vector3) +add_subdirectory(src/intersection) +add_subdirectory(src/polygon) +add_subdirectory(src/quaternion) +add_subdirectory(src/solver) +add_subdirectory(src/spline) +add_subdirectory(src/vector3) -ament_add_gtest(test_bounding_box test_bounding_box.cpp) -ament_add_gtest(test_catmull_rom_spline test_catmull_rom_spline.cpp) -ament_add_gtest(test_catmull_rom_subspline test_catmull_rom_subspline.cpp) -ament_add_gtest(test_collision test_collision.cpp) -ament_add_gtest(test_distance test_distance.cpp) -ament_add_gtest(test_hermite_curve test_hermite_curve.cpp) -ament_add_gtest(test_polygon test_polygon.cpp) -ament_add_gtest(test_polynomial_solver test_polynomial_solver.cpp) -ament_add_gtest(test_transform test_transform.cpp) -ament_add_gtest(test_intersection test_intersection.cpp) -ament_add_gtest(test_line_segment test_line_segment.cpp) -ament_add_gtest(test_quaternion test_quaternion.cpp) -target_link_libraries(test_bounding_box geometry) -target_link_libraries(test_catmull_rom_spline geometry) -target_link_libraries(test_catmull_rom_subspline geometry) -target_link_libraries(test_collision geometry) +ament_add_gtest(test_distance src/test_distance.cpp) target_link_libraries(test_distance geometry) -target_link_libraries(test_hermite_curve geometry) -target_link_libraries(test_polygon geometry) -target_link_libraries(test_polynomial_solver geometry) + +ament_add_gtest(test_bounding_box src/test_bounding_box.cpp) +target_link_libraries(test_bounding_box geometry) + +ament_add_gtest(test_transform src/test_transform.cpp) target_link_libraries(test_transform geometry) -target_link_libraries(test_intersection geometry) -target_link_libraries(test_line_segment geometry) -target_link_libraries(test_quaternion geometry) diff --git a/common/math/geometry/test/expect_eq_macros.hpp b/common/math/geometry/test/src/expect_eq_macros.hpp similarity index 100% rename from common/math/geometry/test/expect_eq_macros.hpp rename to common/math/geometry/test/src/expect_eq_macros.hpp diff --git a/common/math/geometry/test/src/intersection/CMakeLists.txt b/common/math/geometry/test/src/intersection/CMakeLists.txt new file mode 100644 index 00000000000..ea171973a2c --- /dev/null +++ b/common/math/geometry/test/src/intersection/CMakeLists.txt @@ -0,0 +1,5 @@ +ament_add_gtest(test_collision test_collision.cpp) +target_link_libraries(test_collision geometry) + +ament_add_gtest(test_intersection test_intersection.cpp) +target_link_libraries(test_intersection geometry) diff --git a/common/math/geometry/test/test_collision.cpp b/common/math/geometry/test/src/intersection/test_collision.cpp similarity index 99% rename from common/math/geometry/test/test_collision.cpp rename to common/math/geometry/test/src/intersection/test_collision.cpp index cf60a70eba2..a32622d4f0c 100644 --- a/common/math/geometry/test/test_collision.cpp +++ b/common/math/geometry/test/src/intersection/test_collision.cpp @@ -17,7 +17,7 @@ #include #include -#include "test_utils.hpp" +#include "../test_utils.hpp" TEST(Collision, DifferentHeight) { diff --git a/common/math/geometry/test/test_intersection.cpp b/common/math/geometry/test/src/intersection/test_intersection.cpp similarity index 98% rename from common/math/geometry/test/test_intersection.cpp rename to common/math/geometry/test/src/intersection/test_intersection.cpp index 4ee95a08cd9..b57723e461e 100644 --- a/common/math/geometry/test/test_intersection.cpp +++ b/common/math/geometry/test/src/intersection/test_intersection.cpp @@ -17,8 +17,8 @@ #include #include -#include "expect_eq_macros.hpp" -#include "test_utils.hpp" +#include "../expect_eq_macros.hpp" +#include "../test_utils.hpp" TEST(Intersection, isIntersect2DDisjoint) { diff --git a/common/math/geometry/test/src/polygon/CMakeLists.txt b/common/math/geometry/test/src/polygon/CMakeLists.txt new file mode 100644 index 00000000000..8a2eae13418 --- /dev/null +++ b/common/math/geometry/test/src/polygon/CMakeLists.txt @@ -0,0 +1,5 @@ +ament_add_gtest(test_line_segment test_line_segment.cpp) +target_link_libraries(test_line_segment geometry) + +ament_add_gtest(test_polygon test_polygon.cpp) +target_link_libraries(test_polygon geometry) diff --git a/common/math/geometry/test/test_line_segment.cpp b/common/math/geometry/test/src/polygon/test_line_segment.cpp similarity index 99% rename from common/math/geometry/test/test_line_segment.cpp rename to common/math/geometry/test/src/polygon/test_line_segment.cpp index 4c21cc35626..8b0353eead4 100644 --- a/common/math/geometry/test/test_line_segment.cpp +++ b/common/math/geometry/test/src/polygon/test_line_segment.cpp @@ -19,8 +19,8 @@ #include #include -#include "expect_eq_macros.hpp" -#include "test_utils.hpp" +#include "../expect_eq_macros.hpp" +#include "../test_utils.hpp" TEST(LineSegment, initializeDifferentPoints) { diff --git a/common/math/geometry/test/test_polygon.cpp b/common/math/geometry/test/src/polygon/test_polygon.cpp similarity index 98% rename from common/math/geometry/test/test_polygon.cpp rename to common/math/geometry/test/src/polygon/test_polygon.cpp index 8ec0ea97ad9..e7278fa6566 100644 --- a/common/math/geometry/test/test_polygon.cpp +++ b/common/math/geometry/test/src/polygon/test_polygon.cpp @@ -17,8 +17,8 @@ #include #include -#include "expect_eq_macros.hpp" -#include "test_utils.hpp" +#include "../expect_eq_macros.hpp" +#include "../test_utils.hpp" TEST(Polygon, filterByAxis) { diff --git a/common/math/geometry/test/src/quaternion/CMakeLists.txt b/common/math/geometry/test/src/quaternion/CMakeLists.txt new file mode 100644 index 00000000000..2ea2aaf3d91 --- /dev/null +++ b/common/math/geometry/test/src/quaternion/CMakeLists.txt @@ -0,0 +1,2 @@ +ament_add_gtest(test_quaternion test_quaternion.cpp) +target_link_libraries(test_quaternion geometry) diff --git a/common/math/geometry/test/test_quaternion.cpp b/common/math/geometry/test/src/quaternion/test_quaternion.cpp similarity index 96% rename from common/math/geometry/test/test_quaternion.cpp rename to common/math/geometry/test/src/quaternion/test_quaternion.cpp index 7dfd1285664..14c7f3a82ba 100644 --- a/common/math/geometry/test/test_quaternion.cpp +++ b/common/math/geometry/test/src/quaternion/test_quaternion.cpp @@ -18,8 +18,8 @@ #include #include -#include "expect_eq_macros.hpp" -#include "test_utils.hpp" +#include "../expect_eq_macros.hpp" +#include "../test_utils.hpp" constexpr double EPS = 1e-6; diff --git a/common/math/geometry/test/src/solver/CMakeLists.txt b/common/math/geometry/test/src/solver/CMakeLists.txt new file mode 100644 index 00000000000..0716910f184 --- /dev/null +++ b/common/math/geometry/test/src/solver/CMakeLists.txt @@ -0,0 +1,2 @@ +ament_add_gtest(test_polynomial_solver test_polynomial_solver.cpp) +target_link_libraries(test_polynomial_solver geometry) diff --git a/common/math/geometry/test/test_polynomial_solver.cpp b/common/math/geometry/test/src/solver/test_polynomial_solver.cpp similarity index 100% rename from common/math/geometry/test/test_polynomial_solver.cpp rename to common/math/geometry/test/src/solver/test_polynomial_solver.cpp diff --git a/common/math/geometry/test/src/spline/CMakeLists.txt b/common/math/geometry/test/src/spline/CMakeLists.txt new file mode 100644 index 00000000000..d6a2793f80d --- /dev/null +++ b/common/math/geometry/test/src/spline/CMakeLists.txt @@ -0,0 +1,8 @@ +ament_add_gtest(test_catmull_rom_spline test_catmull_rom_spline.cpp) +target_link_libraries(test_catmull_rom_spline geometry) + +ament_add_gtest(test_catmull_rom_subspline test_catmull_rom_subspline.cpp) +target_link_libraries(test_catmull_rom_subspline geometry) + +ament_add_gtest(test_hermite_curve test_hermite_curve.cpp) +target_link_libraries(test_hermite_curve geometry) diff --git a/common/math/geometry/test/test_catmull_rom_spline.cpp b/common/math/geometry/test/src/spline/test_catmull_rom_spline.cpp similarity index 99% rename from common/math/geometry/test/test_catmull_rom_spline.cpp rename to common/math/geometry/test/src/spline/test_catmull_rom_spline.cpp index b29aba00130..b224e7d0d45 100644 --- a/common/math/geometry/test/test_catmull_rom_spline.cpp +++ b/common/math/geometry/test/src/spline/test_catmull_rom_spline.cpp @@ -18,8 +18,8 @@ #include #include -#include "expect_eq_macros.hpp" -#include "test_utils.hpp" +#include "../expect_eq_macros.hpp" +#include "../test_utils.hpp" constexpr double EPS = 1e-6; diff --git a/common/math/geometry/test/test_catmull_rom_subspline.cpp b/common/math/geometry/test/src/spline/test_catmull_rom_subspline.cpp similarity index 98% rename from common/math/geometry/test/test_catmull_rom_subspline.cpp rename to common/math/geometry/test/src/spline/test_catmull_rom_subspline.cpp index 567d1bf089e..10b2b56124c 100644 --- a/common/math/geometry/test/test_catmull_rom_subspline.cpp +++ b/common/math/geometry/test/src/spline/test_catmull_rom_subspline.cpp @@ -17,8 +17,8 @@ #include #include -#include "expect_eq_macros.hpp" -#include "test_utils.hpp" +#include "../expect_eq_macros.hpp" +#include "../test_utils.hpp" constexpr double EPS = 1e-6; diff --git a/common/math/geometry/test/test_hermite_curve.cpp b/common/math/geometry/test/src/spline/test_hermite_curve.cpp similarity index 99% rename from common/math/geometry/test/test_hermite_curve.cpp rename to common/math/geometry/test/src/spline/test_hermite_curve.cpp index 9efbccef633..08ab6c3c4a0 100644 --- a/common/math/geometry/test/test_hermite_curve.cpp +++ b/common/math/geometry/test/src/spline/test_hermite_curve.cpp @@ -16,8 +16,8 @@ #include -#include "expect_eq_macros.hpp" -#include "test_utils.hpp" +#include "../expect_eq_macros.hpp" +#include "../test_utils.hpp" constexpr double EPS = 1e-3; diff --git a/common/math/geometry/test/test_bounding_box.cpp b/common/math/geometry/test/src/test_bounding_box.cpp similarity index 100% rename from common/math/geometry/test/test_bounding_box.cpp rename to common/math/geometry/test/src/test_bounding_box.cpp diff --git a/common/math/geometry/test/test_distance.cpp b/common/math/geometry/test/src/test_distance.cpp similarity index 100% rename from common/math/geometry/test/test_distance.cpp rename to common/math/geometry/test/src/test_distance.cpp diff --git a/common/math/geometry/test/test_transform.cpp b/common/math/geometry/test/src/test_transform.cpp similarity index 100% rename from common/math/geometry/test/test_transform.cpp rename to common/math/geometry/test/src/test_transform.cpp diff --git a/common/math/geometry/test/test_utils.hpp b/common/math/geometry/test/src/test_utils.hpp similarity index 100% rename from common/math/geometry/test/test_utils.hpp rename to common/math/geometry/test/src/test_utils.hpp diff --git a/common/math/geometry/test/vector3/CMakeLists.txt b/common/math/geometry/test/src/vector3/CMakeLists.txt similarity index 100% rename from common/math/geometry/test/vector3/CMakeLists.txt rename to common/math/geometry/test/src/vector3/CMakeLists.txt diff --git a/common/math/geometry/test/vector3/test_truncate_custom.cpp b/common/math/geometry/test/src/vector3/test_truncate_custom.cpp similarity index 100% rename from common/math/geometry/test/vector3/test_truncate_custom.cpp rename to common/math/geometry/test/src/vector3/test_truncate_custom.cpp diff --git a/common/math/geometry/test/vector3/test_truncate_msg.cpp b/common/math/geometry/test/src/vector3/test_truncate_msg.cpp similarity index 100% rename from common/math/geometry/test/vector3/test_truncate_msg.cpp rename to common/math/geometry/test/src/vector3/test_truncate_msg.cpp diff --git a/common/math/geometry/test/vector3/test_vector3.cpp b/common/math/geometry/test/src/vector3/test_vector3.cpp similarity index 100% rename from common/math/geometry/test/vector3/test_vector3.cpp rename to common/math/geometry/test/src/vector3/test_vector3.cpp From d34f9bbd3c37b0a28928487f905917da7f9fbf41 Mon Sep 17 00:00:00 2001 From: robomic Date: Mon, 5 Aug 2024 14:37:48 +0200 Subject: [PATCH 079/304] getPose, getPoint refactor --- .../test/src/polygon/test_line_segment.cpp | 198 ++++++++++-------- 1 file changed, 111 insertions(+), 87 deletions(-) diff --git a/common/math/geometry/test/src/polygon/test_line_segment.cpp b/common/math/geometry/test/src/polygon/test_line_segment.cpp index 8b0353eead4..e8ce13d44b4 100644 --- a/common/math/geometry/test/src/polygon/test_line_segment.cpp +++ b/common/math/geometry/test/src/polygon/test_line_segment.cpp @@ -17,6 +17,7 @@ #include #include #include +#include #include #include "../expect_eq_macros.hpp" @@ -326,97 +327,120 @@ TEST(LineSegment, getSValue_parallelDenormalize) EXPECT_FALSE(s); } -/// @brief In this test case, testing the `LineSegment::getPoint` function can find the point on the line segment with start point (x,y,z) = (0,0,0) and end point (x,y,z) = (1,1,1) in the cartesian coordinate system. (variable name `line`). -TEST(LineSegment, GetPoint) +TEST(LineSegment, GetPoint_outOfBounds_denormalized) { - { - math::geometry::LineSegment line( - geometry_msgs::build().x(0).y(0).z(0), - geometry_msgs::build().x(1).y(1).z(1)); - /// @note If s = 0 and denormalize_s = false, the return value of the `getPoint` function should be a start point of the `line`. - /// If the `denormalize_s = false`, the return value `s` of the function is normalized and in range `s = [0,1]`. - // [Snippet_getPoint_with_s_0] - EXPECT_POINT_EQ( - line.getPoint(0, false), geometry_msgs::build().x(0).y(0).z(0)); - // [Snippet_getPoint_with_s_0] - /// @snippet test/test_line_segment.cpp Snippet_getPoint_with_s_0 - - /// @note If s = 0 and denormalize_s = false, the return value of the `LineSegment::getPoint` function should be a end point of the `line`. - /// If the `denormalize_s = false`, the return value `s` of the function is normalized and in range `s = [0,1]`. - // [Snippet_getPoint_with_s_1] - EXPECT_POINT_EQ( - line.getPoint(1, false), geometry_msgs::build().x(1).y(1).z(1)); - // [Snippet_getPoint_with_s_1] - /// @snippet test/test_line_segment.cpp Snippet_getPoint_with_s_1 - - /// @note If s = sqrt(3) and denormalize_s = true, the return value of the `LineSegment::getPoint` function should be a end point of the `line`. - /// If the `denormalize_s = true`, the return value `s` is denormalized and it returns the value `s` times the length of the curve. - // [Snippet_getPoint_with_sqrt_3_denormalized] - EXPECT_POINT_EQ( - line.getPoint(std::sqrt(3), true), - geometry_msgs::build().x(1).y(1).z(1)); - // [Snippet_getPoint_with_sqrt_3_denormalized] - /// @snippet test/test_line_segment.cpp Snippet_getPoint_with_sqrt_3_denormalized - - /// @note If s is not in range s = [0,1], testing the `LineSegment::getPoint` function can throw error. If s is not in range s = [0,1], it means the point is not on the line. - // [Snippet_getPoint_out_of_range] - EXPECT_THROW(line.getPoint(2, false), common::SimulationError); - EXPECT_THROW(line.getPoint(-1, false), common::SimulationError); - // [Snippet_getPoint_out_of_range] - /// @snippet test/test_line_segment.cpp Snippet_getPoint_out_of_range - - /// @note If s is not in range s = [0,sqrt(3)] and denormalize, testing the `LineSegment::getPoint` function can throw error. If s is not in range s = [0,sqrt(3)], it means the point is not on the line. - // [Snippet_getPoint_out_of_range_with_denormalize] - EXPECT_THROW(line.getPoint(2, true), common::SimulationError); - EXPECT_THROW(line.getPoint(-1, true), common::SimulationError); - EXPECT_NO_THROW(line.getPoint(0, true)); - EXPECT_NO_THROW(line.getPoint(std::sqrt(3.0), true)); - // [Snippet_getPoint_out_of_range_with_denormalize] - /// @snippet test/test_line_segment.cpp Snippet_getPoint_out_of_range_with_denormalize - } + const auto line = + math::geometry::LineSegment(makePoint(-1.0, -2.0, 1.0), makePoint(3.0, 2.0, -1.0)); + ASSERT_DOUBLE_EQ(line.getLength(), 6.0); + + EXPECT_THROW(line.getPoint(7.0, true), common::SimulationError); + EXPECT_THROW(line.getPoint(-1.0, true), common::SimulationError); } -/// @brief In this test case, testing the `LineSegment::getPose` function can find the pose on the line segment with start point (x,y,z) = (0,0,0) and end point (x,y,z) = (0,0,1) in the cartesian coordinate system. (variable name `line`). -TEST(LineSegment, GetPose) +TEST(LineSegment, GetPoint_outOfBounds_normalized) { - { - math::geometry::LineSegment line( - geometry_msgs::build().x(0).y(0).z(0), - geometry_msgs::build().x(0).y(0).z(1)); - /// @note When the `s = 0`(1st argument of the `LineSegment::getPose` function), the return value of the `LineSegment::getPose` function should be a start point of the `line`. - /// Orientation should be defined by the direction of the `line`, so the orientation should be parallel to the z axis. - // [Snippet_getPose_with_s_0] - EXPECT_POSE_EQ( - line.getPose(0, false, false), - geometry_msgs::build() - .position(geometry_msgs::build().x(0).y(0).z(0)) - .orientation(geometry_msgs::build().x(0).y(0).z(0).w(1))); - EXPECT_POSE_EQ( - line.getPose(0, false, true), - geometry_msgs::build() - .position(geometry_msgs::build().x(0).y(0).z(0)) - .orientation(math::geometry::convertEulerAngleToQuaternion( - geometry_msgs::build().x(0).y(-M_PI * 0.5).z(0)))); - // [Snippet_getPose_with_s_0] - /// @snippet test/test_line_segment.cpp Snippet_getPose_with_s_0 - - /// @note When the `s = 1`(1st argument of the `LineSegment::getPose` function), the return value of the `LineSegment::getPose` function should be an end point of the `line`. - /// Orientation should be defined by the direction of the `line`, so the orientation should be parallel to the z axis. - // [Snippet_getPose_with_s_1] - EXPECT_POSE_EQ( - line.getPose(1, false, false), - geometry_msgs::build() - .position(geometry_msgs::build().x(0).y(0).z(1)) - .orientation(geometry_msgs::build().x(0).y(0).z(0).w(1))); - EXPECT_POSE_EQ( - line.getPose(1, false, true), - geometry_msgs::build() - .position(geometry_msgs::build().x(0).y(0).z(1)) - .orientation(math::geometry::convertEulerAngleToQuaternion( - geometry_msgs::build().x(0).y(-M_PI * 0.5).z(0)))); - // [Snippet_getPose_with_s_1] - /// @snippet test/test_line_segment.cpp Snippet_getPose_with_s_1 - } + const auto line = + math::geometry::LineSegment(makePoint(-1.0, -2.0, 1.0), makePoint(3.0, 2.0, -1.0)); + ASSERT_DOUBLE_EQ(line.getLength(), 6.0); + + EXPECT_THROW(line.getPoint(1.1, false), common::SimulationError); + EXPECT_THROW(line.getPoint(-0.1, false), common::SimulationError); +} + +TEST(LineSegment, GetPoint_inside_denormalized) +{ + const auto line = + math::geometry::LineSegment(makePoint(-1.0, -2.0, 1.0), makePoint(3.0, 2.0, -1.0)); + ASSERT_DOUBLE_EQ(line.getLength(), 6.0); + + EXPECT_POINT_EQ(line.getPoint(0.0, true), makePoint(-1.0, -2.0, 1.0)); + EXPECT_POINT_EQ(line.getPoint(3.0, true), makePoint(1.0, 0.0, 0.0)); + EXPECT_POINT_EQ(line.getPoint(6.0, true), makePoint(3.0, 2.0, -1.0)); +} + +TEST(LineSegment, GetPoint_inside_normalized) +{ + const auto line = + math::geometry::LineSegment(makePoint(-1.0, -2.0, 1.0), makePoint(3.0, 2.0, -1.0)); + ASSERT_DOUBLE_EQ(line.getLength(), 6.0); + + EXPECT_POINT_EQ(line.getPoint(0.0, false), makePoint(-1.0, -2.0, 1.0)); + EXPECT_POINT_EQ(line.getPoint(0.5, false), makePoint(1.0, 0.0, 0.0)); + EXPECT_POINT_EQ(line.getPoint(1.0, false), makePoint(3.0, 2.0, -1.0)); +} + +TEST(LineSegment, getPose_denormalized) +{ + const auto line = + math::geometry::LineSegment(makePoint(-1.0, -2.0, 0.0), makePoint(3.0, 2.0, 4.0)); + const double length = 4.0 * std::sqrt(3.0); + ASSERT_DOUBLE_EQ(line.getLength(), length); + + EXPECT_POSE_EQ( + line.getPose(0.0 * length, true, false), + makePose( + -1.0, -2.0, 0.0, + math::geometry::convertEulerAngleToQuaternion(makeVector(0.0, 0.0, M_PI_4)))); + + EXPECT_POSE_EQ( + line.getPose(0.5 * length, true, false), + makePose( + 1.0, 0.0, 2.0, math::geometry::convertEulerAngleToQuaternion(makeVector(0.0, 0.0, M_PI_4)))); + + EXPECT_POSE_EQ( + line.getPose(1.0 * length, true, false), + makePose( + 3.0, 2.0, 4.0, math::geometry::convertEulerAngleToQuaternion(makeVector(0.0, 0.0, M_PI_4)))); +} + +TEST(LineSegment, getPose_normalized) +{ + const auto line = + math::geometry::LineSegment(makePoint(-1.0, -2.0, 0.0), makePoint(3.0, 2.0, 4.0)); + const double length = 4.0 * std::sqrt(3.0); + ASSERT_DOUBLE_EQ(line.getLength(), length); + + EXPECT_POSE_EQ( + line.getPose(0.0, false, false), + makePose( + -1.0, -2.0, 0.0, + math::geometry::convertEulerAngleToQuaternion(makeVector(0.0, 0.0, M_PI_4)))); + + EXPECT_POSE_EQ( + line.getPose(0.5, false, false), + makePose( + 1.0, 0.0, 2.0, math::geometry::convertEulerAngleToQuaternion(makeVector(0.0, 0.0, M_PI_4)))); + + EXPECT_POSE_EQ( + line.getPose(1.0, false, false), + makePose( + 3.0, 2.0, 4.0, math::geometry::convertEulerAngleToQuaternion(makeVector(0.0, 0.0, M_PI_4)))); +} + +TEST(LineSegment, getPose_pitch) +{ + const auto line = math::geometry::LineSegment( + makePoint(-1.0, -2.0, 0.0 * std::sqrt(2.0)), makePoint(3.0, 2.0, 4.0 * std::sqrt(2.0))); + const double length = 8.0; + ASSERT_DOUBLE_EQ(line.getLength(), length); + + EXPECT_POSE_EQ( + line.getPose(0.0 * length, true, true), + makePose( + -1.0, -2.0, 0.0 * std::sqrt(2.0), + math::geometry::convertEulerAngleToQuaternion(makeVector(0.0, -M_PI_4, M_PI_4)))); + + EXPECT_POSE_EQ( + line.getPose(0.5 * length, true, true), + makePose( + 1.0, 0.0, 2.0 * std::sqrt(2.0), + math::geometry::convertEulerAngleToQuaternion(makeVector(0.0, -M_PI_4, M_PI_4)))); + + EXPECT_POSE_EQ( + line.getPose(1.0 * length, true, true), + makePose( + 3.0, 2.0, 4.0 * std::sqrt(2.0), + math::geometry::convertEulerAngleToQuaternion(makeVector(0.0, -M_PI_4, M_PI_4)))); } /// @brief In this test case, we check collision with the point and the line segment with start point (x,y,z) = (0,-1,0) and end point (x,y,z) = (0,1,0) in the cartesian coordinate system. (variable name `line`). From 28b9476ff5172badbef0294a7979773c937b8a3d Mon Sep 17 00:00:00 2001 From: robomic Date: Mon, 5 Aug 2024 18:08:32 +0200 Subject: [PATCH 080/304] getIntersection2DSValue and isIntersect2D functions --- .../test/src/polygon/test_line_segment.cpp | 390 +++++++++++------- 1 file changed, 230 insertions(+), 160 deletions(-) diff --git a/common/math/geometry/test/src/polygon/test_line_segment.cpp b/common/math/geometry/test/src/polygon/test_line_segment.cpp index e8ce13d44b4..5cfc5094078 100644 --- a/common/math/geometry/test/src/polygon/test_line_segment.cpp +++ b/common/math/geometry/test/src/polygon/test_line_segment.cpp @@ -443,178 +443,248 @@ TEST(LineSegment, getPose_pitch) math::geometry::convertEulerAngleToQuaternion(makeVector(0.0, -M_PI_4, M_PI_4)))); } -/// @brief In this test case, we check collision with the point and the line segment with start point (x,y,z) = (0,-1,0) and end point (x,y,z) = (0,1,0) in the cartesian coordinate system. (variable name `line`). -TEST(LineSegment, isIntersect2D) +TEST(LineSegment, isIntersect2D_pointInside) { + const auto line = + math::geometry::LineSegment(makePoint(-1.0, -2.0, 0.0), makePoint(3.0, 2.0, 4.0)); + + EXPECT_TRUE(line.isIntersect2D(makePoint(0.0, -1.0, 1.0))); + EXPECT_TRUE(line.isIntersect2D(makePoint(0.0, -1.0, 0.0))); +} + +TEST(LineSegment, isIntersect2D_pointOutside) +{ + const auto line = + math::geometry::LineSegment(makePoint(-1.0, -2.0, 0.0), makePoint(3.0, 2.0, 4.0)); + + EXPECT_FALSE(line.isIntersect2D(makePoint(-1.0, -1.0, 1.0))); + EXPECT_FALSE(line.isIntersect2D( + makePoint(0.0, std::numeric_limits::max(), std::numeric_limits::max()))); + + EXPECT_FALSE(line.isIntersect2D(makePoint(-3.0, 0.0, 0.0))); + EXPECT_FALSE(line.isIntersect2D(makePoint(4.0, 0.0, 0.0))); +} + +TEST(LineSegment, isIntersect2D_pointCollinear) +{ + const auto line = + math::geometry::LineSegment(makePoint(-1.0, -2.0, 0.0), makePoint(3.0, 2.0, 4.0)); + + EXPECT_FALSE(line.isIntersect2D(makePoint(-2.0, -3.0, -1.0))); + EXPECT_FALSE(line.isIntersect2D(makePoint(-2.0, -3.0, 0.0))); + + EXPECT_FALSE(line.isIntersect2D(makePoint(4.0, 3.0, 5.0))); + EXPECT_FALSE(line.isIntersect2D(makePoint(4.0, 3.0, 0.0))); +} + +TEST(LineSegment, isIntersect2D_pointOnEnd) +{ + const auto line = + math::geometry::LineSegment(makePoint(-1.0, -2.0, 0.0), makePoint(3.0, 2.0, 4.0)); + + EXPECT_TRUE(line.isIntersect2D(makePoint(-1.0, -2.0, 0.0))); + EXPECT_TRUE(line.isIntersect2D(makePoint(-1.0, -2.0, 7.0))); + + EXPECT_TRUE(line.isIntersect2D(makePoint(3.0, 2.0, 4.0))); + EXPECT_TRUE(line.isIntersect2D(makePoint(3.0, 2.0, -5.0))); +} + +TEST(LineSegment, getIntersection2DSValue_line_vertical) +{ + const auto line = + math::geometry::LineSegment(makePoint(-1.0, -2.0, 0.0), makePoint(-1.0, 2.0, 0.0)); { - math::geometry::LineSegment line( - geometry_msgs::build().x(0).y(-1).z(0), - geometry_msgs::build().x(0).y(1).z(0)); - /// @note Testing the `LineSegment::isIntersect2D` function can find intersection with point (0,0,0) and `line`. - // [Snippet_isIntersect2D_with_point_0_0_0] - EXPECT_TRUE( - line.isIntersect2D(geometry_msgs::build().x(0).y(0).z(0))); - // [Snippet_isIntersect2D_with_point_0_0_0] - /// @snippet test/test_line_segment.cpp Snippet_isIntersect2D_with_point_0_0_0 - - /// @note Testing the `LineSegment::isIntersect2D` function can find intersection with point (0,0,-1) - // [Snippet_isIntersect2D_with_point_0_0_-1] - EXPECT_TRUE( - line.isIntersect2D(geometry_msgs::build().x(0).y(0).z(-1))); - // [Snippet_isIntersect2D_with_point_0_0_-1] - /// @snippet test/test_line_segment.cpp Snippet_isIntersect2D_with_point_0_0_-1 - - /// @note Testing the `LineSegment::isIntersect2D` function can find intersection with point (0,1,0) and `line`. - // [Snippet_isIntersect2D_with_point_0_1_0] - EXPECT_TRUE( - line.isIntersect2D(geometry_msgs::build().x(0).y(1).z(0))); - // [Snippet_isIntersect2D_with_point_0_1_0] - /// @snippet test/test_line_segment.cpp Snippet_isIntersect2D_with_point_0_1_0 - - /// @note Testing the `LineSegment::isIntersect2D` function can find that there is no intersection with point (0,2,0) and `line`. - // [Snippet_isIntersect2D_with_point_0_2_0] - EXPECT_FALSE( - line.isIntersect2D(geometry_msgs::build().x(0).y(2).z(0))); - // [Snippet_isIntersect2D_with_point_0_2_0] - /// @snippet test/test_line_segment.cpp Snippet_isIntersect2D_with_point_0_2_0 - - /// @note Testing the `LineSegment::isIntersect2D` function can find that there is no intersection with point (0,-2,0) and `line`. - // [Snippet_isIntersect2D_with_point_0_-2_0] - EXPECT_FALSE( - line.isIntersect2D(geometry_msgs::build().x(0).y(-2).z(0))); - // [Snippet_isIntersect2D_with_point_0_-2_0] - /// @snippet test/test_line_segment.cpp Snippet_isIntersect2D_with_point_0_-2_0 + const auto s_value = line.getIntersection2DSValue( + math::geometry::LineSegment(makePoint(-2.0, -2.0, 0.0), makePoint(1.0, 1.0, 0.0)), true); + ASSERT_TRUE(s_value.has_value()); + EXPECT_DOUBLE_EQ(s_value.value(), 1.0); + } + { + const auto s_value = line.getIntersection2DSValue( + math::geometry::LineSegment(makePoint(-2.0, -2.0, 0.0), makePoint(1.0, 1.0, 0.0)), false); + ASSERT_TRUE(s_value.has_value()); + EXPECT_DOUBLE_EQ(s_value.value(), 0.25); } } -/// @brief In this test case, we check collision with the line segment with start point (x,y,z) = (0,-1,0) and end point (x,y,z) = (0,1,0) in the cartesian coordinate system. (variable name `line`). -TEST(LineSegment, getIntersection2DSValue) +TEST(LineSegment, getIntersection2DSValue_line_horizontal) { + const auto line = + math::geometry::LineSegment(makePoint(-1.0, 2.0, 0.0), makePoint(1.0, 2.0, 0.0)); { - math::geometry::LineSegment line( - geometry_msgs::build().x(0).y(-1).z(0), - geometry_msgs::build().x(0).y(1).z(0)); - /** - * @note Testing the `LineSegment::getIntersection2DSValue` function can find a collision with the point with (x,y,z) = (0,0,0) in the cartesian coordinate system. - * In the frenet coordinate system along the `line`, the s value should be 0.5. - * If so, the variable `collision_s` should be `std::optional(0.5)`. - */ - // [Snippet_getIntersection2DSValue_with_point_0_0_0] - { - const auto collision_s = line.getIntersection2DSValue( - geometry_msgs::build().x(0).y(0).z(0), false); - EXPECT_TRUE(collision_s); - if (collision_s) { - EXPECT_DOUBLE_EQ(collision_s.value(), 0.5); - } - } - // [Snippet_getIntersection2DSValue_with_point_0_0_0] - /// @snippet test/test_line_segment.cpp Snippet_getIntersection2DSValue_with_point_0_0_0 + const auto s_value = line.getIntersection2DSValue( + math::geometry::LineSegment(makePoint(-1.0, 0.0, 0.0), makePoint(1.0, 4.0, 0.0)), true); + ASSERT_TRUE(s_value.has_value()); + EXPECT_DOUBLE_EQ(s_value.value(), 1.0); + } + { + const auto s_value = line.getIntersection2DSValue( + math::geometry::LineSegment(makePoint(-1.0, 0.0, 0.0), makePoint(1.0, 4.0, 0.0)), false); + ASSERT_TRUE(s_value.has_value()); + EXPECT_DOUBLE_EQ(s_value.value(), 0.5); + } +} - /** - * @note Testing the `LineSegment::getIntersection2DSValue` function can find a collision with the point with (x,y,z) = (0,1,0) in the cartesian coordinate system. - * In the frenet coordinate system along the `line`, the s value should be 1.0. - * If so, the variable `collision_s` should be `std::optional(1.0)`. - */ - // [Snippet_getIntersection2DSValue_with_point_0_1_0] - { - const auto collision_s = line.getIntersection2DSValue( - geometry_msgs::build().x(0).y(1).z(0), false); - EXPECT_TRUE(collision_s); - if (collision_s) { - EXPECT_DOUBLE_EQ(collision_s.value(), 1.0); - } - } - // [Snippet_getIntersection2DSValue_with_point_0_1_0] - /// @snippet test/test_line_segment.cpp Snippet_getIntersection2DSValue_with_point_0_1_0 +TEST(LineSegment, getIntersection2DSValue_line_bounds) +{ + const auto line = + math::geometry::LineSegment(makePoint(-1.0, 1.0, 0.0), makePoint(1.0, 3.0, 0.0)); + { + const auto s_value = line.getIntersection2DSValue( + math::geometry::LineSegment(makePoint(-2.0, 2.0, 0.0), makePoint(0.0, 0.0, 0.0)), false); + ASSERT_TRUE(s_value.has_value()); + EXPECT_DOUBLE_EQ(s_value.value(), 0.0); + } + { + const auto s_value = line.getIntersection2DSValue( + math::geometry::LineSegment(makePoint(1.0, 3.0, 0.0), makePoint(2.0, 2.0, 0.0)), false); + ASSERT_TRUE(s_value.has_value()); + EXPECT_DOUBLE_EQ(s_value.value(), 1.0); + } +} - /** - * @note Testing the `LineSegment::getIntersection2DSValue` function can find a collision with the point with (x,y,z) = (0,1,0) in the cartesian coordinate system. - * In the frenet coordinate system along the `line`, the s value should be 1.0. - * And, the 2nd argument of the `LineSegment::getIntersection2DSValue` (denormalized_s) is true, so the return value should be 1.0 (normalized s value.) * 2.0 (length of the `line`) = 2.0. - * If so, the variable `collision_s` should be `std::optional(2.0)`. - */ - // [Snippet_getIntersection2DSValue_with_point_0_1_0_denormalized] - { - const auto collision_s = line.getIntersection2DSValue( - geometry_msgs::build().x(0).y(1).z(0), true); - EXPECT_TRUE(collision_s); - if (collision_s) { - EXPECT_DOUBLE_EQ(collision_s.value(), 2.0); - } - } - // [Snippet_getIntersection2DSValue_with_point_0_1_0_denormalized] - /// @snippet test/test_line_segment.cpp Snippet_getIntersection2DSValue_with_point_0_1_0_denormalized +TEST(LineSegment, getIntersection2DSValue_line_outside) +{ + const auto line = + math::geometry::LineSegment(makePoint(-1.0, 1.0, 0.0), makePoint(1.0, 3.0, 0.0)); - /** - * @note Testing the `LineSegment::getIntersection2DSValue` function can find a collision with the point with (x,y,z) = (0,0,0) in the cartesian coordinate system. - * In the frenet coordinate system along the `line`, the s value should be 0.5. - * And, the 2nd argument of the `LineSegment::getIntersection2DSValue` (denormalized_s) is true, so the return value should be 0.5 (normalized s value.) * 2.0 (length of the `line`) = 1.0. - * If so, the variable `collision_s` should be `std::optional(1.0)`. - */ - // [Snippet_getIntersection2DSValue_with_point_0_0_0_denormalized] - { - const auto collision_s = line.getIntersection2DSValue( - geometry_msgs::build().x(0).y(0).z(0), true); - EXPECT_TRUE(collision_s); - if (collision_s) { - EXPECT_DOUBLE_EQ(collision_s.value(), 1.0); - } - } - // [Snippet_getIntersection2DSValue_with_point_0_0_0_denormalized] - /// @snippet test/test_line_segment.cpp Snippet_getIntersection2DSValue_with_point_0_0_0_denormalized + EXPECT_FALSE( + line + .getIntersection2DSValue( + math::geometry::LineSegment(makePoint(-2.0, 1.0, 0.0), makePoint(0.0, 0.0, 0.0)), false) + .has_value()); - /** - * @note Testing the `LineSegment::getIntersection2DSValue` function can find that the point with (x,y,z) = (1,0,0) in the cartesian coordinate system does not collide to `line.`. - * If the function works valid, the variable `collision_s` should be `std::nullopt`. - */ - // [Snippet_getIntersection2DSValue_with_point_1_0_0] - { - const auto collision_s = line.getIntersection2DSValue( - geometry_msgs::build().x(1).y(0).z(0), false); - EXPECT_FALSE(collision_s); - } - // [Snippet_getIntersection2DSValue_with_point_1_0_0] - /// @snippet test/test_line_segment.cpp Snippet_getIntersection2DSValue_with_point_1_0_0 + EXPECT_FALSE( + line + .getIntersection2DSValue( + math::geometry::LineSegment(makePoint(1.0, 4.0, 0.0), makePoint(2.0, 2.0, 0.0)), false) + .has_value()); +} - { // parallel no denormalize - EXPECT_THROW( - line.getIntersection2DSValue( - math::geometry::LineSegment(makePoint(0.0, -1.0), makePoint(0.0, 1.0)), false), - common::SimulationError); - } - { // parallel denormalize - EXPECT_THROW( - line.getIntersection2DSValue( - math::geometry::LineSegment(makePoint(0.0, -1.0), makePoint(0.0, 1.0)), true), - common::SimulationError); - } - { // intersect no denormalize - const auto collision_s = line.getIntersection2DSValue( - math::geometry::LineSegment(makePoint(-1.0, 0.5), makePoint(1.0, 0.5)), false); - EXPECT_TRUE(collision_s); - if (collision_s) { - EXPECT_DOUBLE_EQ(collision_s.value(), 0.75); - } - } - { // intersect denormalize - const auto collision_s = line.getIntersection2DSValue( - math::geometry::LineSegment(makePoint(-1.0, 0.5), makePoint(1.0, 0.5)), true); - EXPECT_TRUE(collision_s); - if (collision_s) { - EXPECT_DOUBLE_EQ(collision_s.value(), 1.5); - } - } - { // no intersect no denormalize - const auto collision_s = line.getIntersection2DSValue( - math::geometry::LineSegment(makePoint(-1.0, 1.5), makePoint(1.0, 1.5)), false); - EXPECT_FALSE(collision_s); - } - { // no intersect denormalize - const auto collision_s = line.getIntersection2DSValue( - math::geometry::LineSegment(makePoint(-1.0, 1.5), makePoint(1.0, 1.5)), true); - EXPECT_FALSE(collision_s); - } +TEST(LineSegment, getIntersection2DSValue_line_collinear) +{ + const auto line = + math::geometry::LineSegment(makePoint(-1.0, 1.0, 0.0), makePoint(1.0, 3.0, 0.0)); + + EXPECT_THROW(line.getIntersection2DSValue(line, false), common::SimulationError); + + EXPECT_FALSE( + line + .getIntersection2DSValue( + math::geometry::LineSegment(makePoint(3.0, 5.0, 0.0), makePoint(5.0, 7.0, 0.0)), false) + .has_value()); +} + +TEST(LineSegment, getIntersection2DSValue_point_vertical) +{ + const auto line = + math::geometry::LineSegment(makePoint(-1.0, -2.0, 0.0), makePoint(-1.0, 2.0, 0.0)); + + { + const auto s_value = line.getIntersection2DSValue(makePoint(-1.0, 0.0, 0.0), true); + ASSERT_TRUE(s_value.has_value()); + EXPECT_DOUBLE_EQ(s_value.value(), 2.0); + } + { + const auto s_value = line.getIntersection2DSValue(makePoint(-1.0, 0.0, 0.0), false); + ASSERT_TRUE(s_value.has_value()); + EXPECT_DOUBLE_EQ(s_value.value(), 0.5); + } + { + EXPECT_FALSE(line.getIntersection2DSValue(makePoint(-101.0, 0.0, 0.0), true).has_value()); + EXPECT_FALSE(line.getIntersection2DSValue(makePoint(103.0, 0.0, 0.0), false).has_value()); + EXPECT_FALSE(line.getIntersection2DSValue(makePoint(-1.0, -107.0, 0.0), true).has_value()); + EXPECT_FALSE(line.getIntersection2DSValue(makePoint(-1.0, 109.0, 0.0), false).has_value()); + } +} + +TEST(LineSegment, getIntersection2DSValue_point_horizontal) +{ + const auto line = + math::geometry::LineSegment(makePoint(-1.0, 2.0, 0.0), makePoint(1.0, 2.0, 0.0)); + + { + const auto s_value = line.getIntersection2DSValue(makePoint(0.0, 2.0, 0.0), true); + ASSERT_TRUE(s_value.has_value()); + EXPECT_DOUBLE_EQ(s_value.value(), 1.0); + } + { + const auto s_value = line.getIntersection2DSValue(makePoint(0.0, 2.0, 0.0), false); + ASSERT_TRUE(s_value.has_value()); + EXPECT_DOUBLE_EQ(s_value.value(), 0.5); + } + { + EXPECT_FALSE(line.getIntersection2DSValue(makePoint(-113.0, 2.0, 0.0), true).has_value()); + EXPECT_FALSE(line.getIntersection2DSValue(makePoint(127.0, 2.0, 0.0), false).has_value()); + EXPECT_FALSE(line.getIntersection2DSValue(makePoint(0.0, -131.0, 0.0), true).has_value()); + EXPECT_FALSE(line.getIntersection2DSValue(makePoint(0.0, 137.0, 0.0), false).has_value()); + } +} + +TEST(LineSegment, getIntersection2DSValue_point_bounds) +{ + const auto line = + math::geometry::LineSegment(makePoint(-2.0, -2.0, 0.0), makePoint(1.0, 4.0, 0.0)); + + { + const auto s_value = line.getIntersection2DSValue(makePoint(-2.0, -2.0, 0.0), true); + ASSERT_TRUE(s_value.has_value()); + EXPECT_DOUBLE_EQ(s_value.value(), 0.0); + } + { + const auto s_value = line.getIntersection2DSValue(makePoint(-2.0, -2.0, 0.0), false); + ASSERT_TRUE(s_value.has_value()); + EXPECT_DOUBLE_EQ(s_value.value(), 0.0); + } + { + EXPECT_FALSE(line.getIntersection2DSValue(makePoint(-139.0, -2.0, 0.0), true).has_value()); + EXPECT_FALSE(line.getIntersection2DSValue(makePoint(149.0, -2.0, 0.0), false).has_value()); + } + + { + const auto s_value = line.getIntersection2DSValue(makePoint(1.0, 4.0, 0.0), true); + ASSERT_TRUE(s_value.has_value()); + EXPECT_DOUBLE_EQ(s_value.value(), 3.0 * std::sqrt(5)); + } + { + const auto s_value = line.getIntersection2DSValue(makePoint(1.0, 4.0, 0.0), false); + ASSERT_TRUE(s_value.has_value()); + EXPECT_DOUBLE_EQ(s_value.value(), 1.0); + } + { + EXPECT_FALSE(line.getIntersection2DSValue(makePoint(-151.0, 4.0, 0.0), true).has_value()); + EXPECT_FALSE(line.getIntersection2DSValue(makePoint(157.0, 4.0, 0.0), false).has_value()); + } +} + +TEST(LineSegment, getIntersection2DSValue_point_outside) +{ + const auto line = + math::geometry::LineSegment(makePoint(-2.0, -2.0, 0.0), makePoint(1.0, 4.0, 0.0)); + + EXPECT_FALSE(line.getIntersection2DSValue(makePoint(-3.0, 1.0, 0.0), true).has_value()); + EXPECT_FALSE(line.getIntersection2DSValue(makePoint(-1.0, 1.0, 0.0), true).has_value()); + EXPECT_FALSE(line.getIntersection2DSValue(makePoint(0.0, 1.0, 0.0), true).has_value()); + EXPECT_FALSE(line.getIntersection2DSValue(makePoint(2.0, 1.0, 0.0), true).has_value()); + + EXPECT_FALSE(line.getIntersection2DSValue(makePoint(-0.5, -5.0, 0.0), true).has_value()); + EXPECT_FALSE(line.getIntersection2DSValue(makePoint(-0.5, -1.0, 0.0), true).has_value()); + EXPECT_FALSE(line.getIntersection2DSValue(makePoint(-0.5, 3.0, 0.0), true).has_value()); + EXPECT_FALSE(line.getIntersection2DSValue(makePoint(-0.5, 7.0, 0.0), true).has_value()); + + EXPECT_FALSE(line.getIntersection2DSValue(makePoint(7.0, 7.0, 0.0), true).has_value()); + EXPECT_FALSE(line.getIntersection2DSValue(makePoint(7.0, -7.0, 0.0), true).has_value()); + EXPECT_FALSE(line.getIntersection2DSValue(makePoint(-7.0, 7.0, 0.0), true).has_value()); + EXPECT_FALSE(line.getIntersection2DSValue(makePoint(-7.0, -7.0, 0.0), true).has_value()); +} + +/// @brief In this test case, we check collision with the line segment with start point (x,y,z) = (0,-1,0) and end point (x,y,z) = (0,1,0) in the cartesian coordinate system. (variable name `line`). +TEST(LineSegment, getIntersection2DSValue) +{ + { + math::geometry::LineSegment line( + geometry_msgs::build().x(0).y(-1).z(0), + geometry_msgs::build().x(0).y(1).z(0)); /** * @note Testing the `LineSegment::getIntersection2D` function can throw error getting intersection with exact same line segment. From 2dbb4e55ea1950ac18c78fb1b7482ae6d4e4827d Mon Sep 17 00:00:00 2001 From: Mateusz Palczuk Date: Mon, 5 Aug 2024 18:09:04 +0200 Subject: [PATCH 081/304] Fix EgoEntity error where map pose was unable to be set after scenario start, which should be possible for Ego Signed-off-by: Mateusz Palczuk --- simulation/traffic_simulator/src/entity/ego_entity.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/simulation/traffic_simulator/src/entity/ego_entity.cpp b/simulation/traffic_simulator/src/entity/ego_entity.cpp index 65d6c56772a..dccfafb41e3 100644 --- a/simulation/traffic_simulator/src/entity/ego_entity.cpp +++ b/simulation/traffic_simulator/src/entity/ego_entity.cpp @@ -286,7 +286,9 @@ auto EgoEntity::setMapPose(const geometry_msgs::msg::Pose & map_pose) -> void entity_status.pose = map_pose; entity_status.lanelet_pose_valid = false; // prefer current lanelet on Autoware side - setStatus(entity_status, helper::getUniqueValues(getRouteLanelets())); + status_->set( + entity_status, helper::getUniqueValues(getRouteLanelets()), + getDefaultMatchingDistanceForLaneletPoseCalculation(), hdmap_utils_ptr_); } } // namespace entity } // namespace traffic_simulator From f9dbfec9468f95ae51a2216f6f873539ff210e2f Mon Sep 17 00:00:00 2001 From: Mateusz Palczuk Date: Mon, 5 Aug 2024 18:12:31 +0200 Subject: [PATCH 082/304] Fix EgoEntity bug where status time was incremented only when Ego was controlled by simulator This bug lead to problems in other checks which relied on the correct status time Signed-off-by: Mateusz Palczuk --- simulation/traffic_simulator/src/entity/ego_entity.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/simulation/traffic_simulator/src/entity/ego_entity.cpp b/simulation/traffic_simulator/src/entity/ego_entity.cpp index dccfafb41e3..836f597d166 100644 --- a/simulation/traffic_simulator/src/entity/ego_entity.cpp +++ b/simulation/traffic_simulator/src/entity/ego_entity.cpp @@ -152,6 +152,9 @@ void EgoEntity::onUpdate(double current_time, double step_time) is_controlled_by_simulator_ = false; } } + if (not is_controlled_by_simulator_) { + updateEntityStatusTimestamp(current_time + step_time); + } updateStandStillDuration(step_time); updateTraveledDistance(step_time); From 29bbac4258f0dd4c4c5381d959bd354ccc46d0dc Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Tue, 6 Aug 2024 14:26:28 +0900 Subject: [PATCH 083/304] fix: implement Integer::min/max instead of Integer::infinity --- .../include/openscenario_interpreter/syntax/integer.hpp | 4 +++- .../openscenario_interpreter/src/syntax/integer.cpp | 9 +++++++-- .../src/syntax/relative_lane_range.cpp | 4 ++-- 3 files changed, 12 insertions(+), 5 deletions(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/integer.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/integer.hpp index 7c8a00e37fc..4b57eb67cb8 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/integer.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/integer.hpp @@ -35,7 +35,9 @@ struct Integer explicit Integer(const std::string &); - static auto infinity() noexcept -> Integer; + static auto max() noexcept -> Integer; + + static auto min() noexcept -> Integer; auto operator+=(const double &) -> Integer &; diff --git a/openscenario/openscenario_interpreter/src/syntax/integer.cpp b/openscenario/openscenario_interpreter/src/syntax/integer.cpp index f9632ec2624..e85244d50ac 100644 --- a/openscenario/openscenario_interpreter/src/syntax/integer.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/integer.cpp @@ -34,9 +34,14 @@ Integer::Integer(const std::string & s) } } -auto Integer::infinity() noexcept -> Integer +auto Integer::max() noexcept -> Integer { - return static_cast(std::numeric_limits::infinity()); + return static_cast(std::numeric_limits::max()); +} + +auto Integer::min() noexcept -> Integer +{ + return static_cast(std::numeric_limits::min()); } auto Integer::operator+=(const double & rhs) -> Integer & diff --git a/openscenario/openscenario_interpreter/src/syntax/relative_lane_range.cpp b/openscenario/openscenario_interpreter/src/syntax/relative_lane_range.cpp index 2911617b6bd..1061128a077 100644 --- a/openscenario/openscenario_interpreter/src/syntax/relative_lane_range.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/relative_lane_range.cpp @@ -20,8 +20,8 @@ namespace openscenario_interpreter inline namespace syntax { RelativeLaneRange::RelativeLaneRange(const pugi::xml_node & node, Scope & scope) -: from(readAttribute("from", node, scope, -Integer::infinity())), - to(readAttribute("to", node, scope, Integer::infinity())) +: from(readAttribute("from", node, scope, Integer::min())), + to(readAttribute("to", node, scope, Integer::max())) { } } // namespace syntax From 88c672b15c651e7176ce0de7145aa86709eb370e Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Tue, 6 Aug 2024 15:02:44 +0900 Subject: [PATCH 084/304] refactor: use boost::math::constants::pi() instead of M_PI --- .../src/syntax/relative_clearance_condition.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp b/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp index ba584c7edb4..94d29503186 100644 --- a/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp @@ -12,6 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. +#include #include #include #include @@ -88,7 +89,8 @@ auto RelativeClearanceCondition::evaluate() -> Object return std::all_of( entity_refs.begin(), entity_refs.end(), [&, is_back = - (std::abs(evaluateRelativeHeading(triggering_entity)) > M_2_PI)](const auto & entity) { + (std::abs(evaluateRelativeHeading(triggering_entity)) > + 0.5 * boost::math::constants::pi())](const auto & entity) { auto is_in_lateral_range = [&]() { // The lanes to be checked to left and right of the triggering entity (positive to the y-axis). If omitted: all lanes are checked. if (relative_lane_range.empty()) { From b531b44327ee54a18e201337180bd7868b5626b2 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Tue, 6 Aug 2024 15:04:50 +0900 Subject: [PATCH 085/304] feat: add test scenarios for RelativeClearanceCondition to CI test --- test_runner/scenario_test_runner/config/workflow.txt | 2 ++ 1 file changed, 2 insertions(+) diff --git a/test_runner/scenario_test_runner/config/workflow.txt b/test_runner/scenario_test_runner/config/workflow.txt index 632b7495ced..06d459988cc 100644 --- a/test_runner/scenario_test_runner/config/workflow.txt +++ b/test_runner/scenario_test_runner/config/workflow.txt @@ -4,6 +4,8 @@ $(find-pkg-share scenario_test_runner)/scenario/ByEntityCondition.EntityConditio $(find-pkg-share scenario_test_runner)/scenario/ByEntityCondition.EntityCondition.DistanceCondition.yaml $(find-pkg-share scenario_test_runner)/scenario/ByEntityCondition.EntityCondition.DistanceCondition.Shortest.yaml $(find-pkg-share scenario_test_runner)/scenario/ByEntityCondition.EntityCondition.RelativeDistanceCondition.yaml +$(find-pkg-share scenario_test_runner)/scenario/ByEntityCondition.EntityCondition.RelativeClearanceCondition.yaml +$(find-pkg-share scenario_test_runner)/scenario/ByEntityCondition.EntityCondition.RelativeClearanceCondition-back.yaml $(find-pkg-share scenario_test_runner)/scenario/ControllerAction.AssignControllerAction.yaml $(find-pkg-share scenario_test_runner)/scenario/LongitudinalAction.SpeedAction.yaml $(find-pkg-share scenario_test_runner)/scenario/Property.isBlind.yaml From e1e505bb504d9c5c1ec74877b59439b6a0d7a659 Mon Sep 17 00:00:00 2001 From: robomic Date: Tue, 6 Aug 2024 08:44:18 +0200 Subject: [PATCH 086/304] getIntersection2D function --- .../test/src/polygon/test_line_segment.cpp | 21 +++++++++++++++++++ 1 file changed, 21 insertions(+) diff --git a/common/math/geometry/test/src/polygon/test_line_segment.cpp b/common/math/geometry/test/src/polygon/test_line_segment.cpp index 5cfc5094078..1dd370967b2 100644 --- a/common/math/geometry/test/src/polygon/test_line_segment.cpp +++ b/common/math/geometry/test/src/polygon/test_line_segment.cpp @@ -97,6 +97,27 @@ TEST(LineSegment, getIntersection2DDisjoint) EXPECT_FALSE(line0.getIntersection2D(line1)); } +TEST(LineSegment, getIntersection2DIntersect) +{ + const auto line0 = math::geometry::LineSegment(makePoint(0.0, 0.0), makePoint(1.0, 1.0)); + const auto line1 = math::geometry::LineSegment(makePoint(1.0, 0.0), makePoint(0.0, 1.0)); + + const auto p0 = line0.getIntersection2D(line1); + const auto p1 = line1.getIntersection2D(line0); + + ASSERT_TRUE(p0.has_value()); + ASSERT_TRUE(p1.has_value()); + EXPECT_POINT_EQ(p0.value(), makePoint(0.5, 0.5)); + EXPECT_POINT_EQ(p1.value(), makePoint(0.5, 0.5)); +} + +TEST(LineSegment, getIntersection2DIdentical) +{ + const auto line = math::geometry::LineSegment(makePoint(0.0, 0.0), makePoint(1.0, 1.0)); + + EXPECT_THROW(line.getIntersection2D(line), common::SimulationError); +} + TEST(LineSegment, getVector) { const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(2.0, 3.0, 4.0)); From f85c45bb3d50a2ece6aae35a59a3c47d344c435a Mon Sep 17 00:00:00 2001 From: robomic Date: Tue, 6 Aug 2024 08:51:56 +0200 Subject: [PATCH 087/304] sort tests, rm old duplicate --- .../test/src/polygon/test_line_segment.cpp | 607 ++++++++---------- 1 file changed, 278 insertions(+), 329 deletions(-) diff --git a/common/math/geometry/test/src/polygon/test_line_segment.cpp b/common/math/geometry/test/src/polygon/test_line_segment.cpp index 1dd370967b2..6423a3447b2 100644 --- a/common/math/geometry/test/src/polygon/test_line_segment.cpp +++ b/common/math/geometry/test/src/polygon/test_line_segment.cpp @@ -70,285 +70,7 @@ TEST(LineSegment, initializeVectorZeroLength) EXPECT_POINT_EQ(line_segment.end_point, point); } -TEST(LineSegment, isIntersect2DDisjoint) -{ - const math::geometry::LineSegment line0(makePoint(0.0, 0.0), makePoint(1.0, 1.0)); - const math::geometry::LineSegment line1(makePoint(1.0, 0.0), makePoint(2.0, 1.0)); - EXPECT_FALSE(line0.isIntersect2D(line1)); -} - -TEST(LineSegment, isIntersect2DIntersect) -{ - const math::geometry::LineSegment line0(makePoint(1.0, 1.0), makePoint(2.0, 1.0)); - const math::geometry::LineSegment line1(makePoint(1.0, 0.0), makeVector(1.0, 1.0), 3.0); - EXPECT_TRUE(line0.isIntersect2D(line1)); -} - -TEST(LineSegment, isIntersect2DIdentical) -{ - const math::geometry::LineSegment line(makePoint(0.0, 0.0), makePoint(1.0, 1.0)); - EXPECT_TRUE(line.isIntersect2D(line)); -} - -TEST(LineSegment, getIntersection2DDisjoint) -{ - const math::geometry::LineSegment line0(makePoint(0.0, 0.0), makePoint(1.0, 1.0)); - const math::geometry::LineSegment line1(makePoint(1.0, 0.0), makePoint(2.0, 1.0)); - EXPECT_FALSE(line0.getIntersection2D(line1)); -} - -TEST(LineSegment, getIntersection2DIntersect) -{ - const auto line0 = math::geometry::LineSegment(makePoint(0.0, 0.0), makePoint(1.0, 1.0)); - const auto line1 = math::geometry::LineSegment(makePoint(1.0, 0.0), makePoint(0.0, 1.0)); - - const auto p0 = line0.getIntersection2D(line1); - const auto p1 = line1.getIntersection2D(line0); - - ASSERT_TRUE(p0.has_value()); - ASSERT_TRUE(p1.has_value()); - EXPECT_POINT_EQ(p0.value(), makePoint(0.5, 0.5)); - EXPECT_POINT_EQ(p1.value(), makePoint(0.5, 0.5)); -} - -TEST(LineSegment, getIntersection2DIdentical) -{ - const auto line = math::geometry::LineSegment(makePoint(0.0, 0.0), makePoint(1.0, 1.0)); - - EXPECT_THROW(line.getIntersection2D(line), common::SimulationError); -} - -TEST(LineSegment, getVector) -{ - const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(2.0, 3.0, 4.0)); - EXPECT_VECTOR3_EQ(line.getVector(), makeVector(1.0, 1.0, 1.0)); -} - -TEST(LineSegment, getVectorZeroLength) -{ - const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(1.0, 2.0, 3.0)); - EXPECT_VECTOR3_EQ(line.getVector(), makeVector(0.0, 0.0, 0.0)); -} - -TEST(LineSegment, getNormalVector) -{ - const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(2.0, 3.0, 4.0)); - EXPECT_VECTOR3_EQ(line.getNormalVector(), makeVector(-1.0, 1.0, 0.0)); -} - -TEST(LineSegment, getNormalVector_zeroLength) -{ - const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(1.0, 2.0, 3.0)); - EXPECT_VECTOR3_EQ(line.getNormalVector(), makeVector(0.0, 0.0, 0.0)); -} - -TEST(LineSegment, get2DVector) -{ - const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(2.0, 3.0, 4.0)); - EXPECT_VECTOR3_EQ(line.get2DVector(), makeVector(1.0, 1.0, 0.0)); -} - -TEST(LineSegment, get2DVectorZeroLength) -{ - const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(1.0, 2.0, 3.0)); - EXPECT_VECTOR3_EQ(line.get2DVector(), makeVector(0.0, 0.0, 0.0)); -} - -TEST(LineSegment, getLength) -{ - const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(2.0, 3.0, 4.0)); - EXPECT_DOUBLE_EQ(line.getLength(), std::sqrt(3.0)); -} - -TEST(LineSegment, getLengthZeroLength) -{ - const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(1.0, 2.0, 3.0)); - EXPECT_DOUBLE_EQ(line.getLength(), 0.0); -} - -TEST(LineSegment, get2DLength) -{ - const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(2.0, 3.0, 4.0)); - EXPECT_DOUBLE_EQ(line.get2DLength(), std::sqrt(2.0)); -} - -TEST(LineSegment, get2DLengthZeroLength) -{ - const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(1.0, 2.0, 3.0)); - EXPECT_DOUBLE_EQ(line.get2DLength(), 0.0); -} - -TEST(LineSegment, getSlope) -{ - const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(3.0, 3.0, 4.0)); - EXPECT_DOUBLE_EQ(line.getSlope(), 0.5); -} - -TEST(LineSegment, getSlopeZeroLength) -{ - const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(1.0, 2.0, 3.0)); - EXPECT_TRUE(std::isnan(line.getSlope())); -} - -TEST(LineSegment, getSquaredDistanceIn2D) -{ - const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(3.0, 4.0, 5.0)); - EXPECT_DOUBLE_EQ(line.getSquaredDistanceIn2D(makePoint(0.0, 1.0, 2.0), 0.5, false), 8.0); -} - -TEST(LineSegment, getSquaredDistanceIn2D_denormalize) -{ - const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(3.0, 4.0, 5.0)); - EXPECT_DOUBLE_EQ( - line.getSquaredDistanceIn2D(makePoint(0.0, 1.0, 2.0), std::sqrt(3.0), true), 8.0); -} - -TEST(LineSegment, getSquaredDistanceVector) -{ - const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(3.0, 4.0, 5.0)); - EXPECT_VECTOR3_EQ( - line.getSquaredDistanceVector(makePoint(0.0, 1.0, 2.0), 0.5, false), - makeVector(-2.0, -2.0, -2.0)); -} - -TEST(LineSegment, getSquaredDistanceVector_denormalize) -{ - const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(3.0, 4.0, 5.0)); - EXPECT_VECTOR3_EQ( - line.getSquaredDistanceVector(makePoint(0.0, 1.0, 2.0), std::sqrt(3.0), true), - makeVector(-2.0, -2.0, -2.0)); -} - -TEST(LineSegment, getLineSegments) -{ - const std::vector points{ - makePoint(1.0, 2.0, 3.0), makePoint(2.0, 3.0, 4.0), makePoint(3.0, 4.0, 5.0), - makePoint(4.0, 5.0, 6.0)}; - const std::vector lines = - math::geometry::getLineSegments(points, false); - EXPECT_EQ(lines.size(), size_t(3)); - EXPECT_POINT_EQ(lines[0].start_point, points[0]); - EXPECT_POINT_EQ(lines[0].end_point, points[1]); - EXPECT_POINT_EQ(lines[1].start_point, points[1]); - EXPECT_POINT_EQ(lines[1].end_point, points[2]); - EXPECT_POINT_EQ(lines[2].start_point, points[2]); - EXPECT_POINT_EQ(lines[2].end_point, points[3]); -} - -TEST(LineSegment, getLineSegments_closeStartEnd) -{ - const std::vector points{ - makePoint(1.0, 2.0, 3.0), makePoint(2.0, 3.0, 4.0), makePoint(3.0, 4.0, 5.0), - makePoint(4.0, 5.0, 6.0)}; - const std::vector lines = - math::geometry::getLineSegments(points, true); - EXPECT_EQ(lines.size(), size_t(4)); - EXPECT_POINT_EQ(lines[0].start_point, points[0]); - EXPECT_POINT_EQ(lines[0].end_point, points[1]); - EXPECT_POINT_EQ(lines[1].start_point, points[1]); - EXPECT_POINT_EQ(lines[1].end_point, points[2]); - EXPECT_POINT_EQ(lines[2].start_point, points[2]); - EXPECT_POINT_EQ(lines[2].end_point, points[3]); - EXPECT_POINT_EQ(lines[3].start_point, points[3]); - EXPECT_POINT_EQ(lines[3].end_point, points[0]); -} - -TEST(LineSegment, getLineSegmentsVectorEmpty) -{ - const std::vector points; - const std::vector lines = math::geometry::getLineSegments(points); - EXPECT_EQ(lines.size(), size_t(0)); -} - -TEST(LineSegment, getLineSegmentsVectorIdentical) -{ - geometry_msgs::msg::Point point = makePoint(1.0, 2.0, 3.0); - const std::vector points{point, point, point, point}; - const std::vector lines = - math::geometry::getLineSegments(points, false); - EXPECT_EQ(lines.size(), size_t(3)); - EXPECT_POINT_EQ(lines[0].start_point, point); - EXPECT_POINT_EQ(lines[0].end_point, point); - EXPECT_POINT_EQ(lines[1].start_point, point); - EXPECT_POINT_EQ(lines[1].end_point, point); - EXPECT_POINT_EQ(lines[2].start_point, point); - EXPECT_POINT_EQ(lines[2].end_point, point); -} - -TEST(LineSegment, getLineSegmentsVectorIdentical_closeStartEnd) -{ - geometry_msgs::msg::Point point = makePoint(1.0, 2.0, 3.0); - const std::vector points{point, point, point, point}; - const std::vector lines = - math::geometry::getLineSegments(points, true); - EXPECT_EQ(lines.size(), size_t(4)); - EXPECT_POINT_EQ(lines[0].start_point, point); - EXPECT_POINT_EQ(lines[0].end_point, point); - EXPECT_POINT_EQ(lines[1].start_point, point); - EXPECT_POINT_EQ(lines[1].end_point, point); - EXPECT_POINT_EQ(lines[2].start_point, point); - EXPECT_POINT_EQ(lines[2].end_point, point); - EXPECT_POINT_EQ(lines[3].start_point, point); - EXPECT_POINT_EQ(lines[3].end_point, point); -} - -TEST(LineSegment, getSValue) -{ - math::geometry::LineSegment line(makePoint(0.0, 0.0, 0.0), makePoint(3.0, 3.0, 3.0)); - const auto s = line.getSValue(makePose(2.0, 2.0, 2.0), 1.0, false); - EXPECT_TRUE(s); - if (s) { - EXPECT_DOUBLE_EQ(s.value(), 2.0 / 3.0); - } -} - -TEST(LineSegment, getSValue_denormalize) -{ - math::geometry::LineSegment line(makePoint(0.0, 0.0, 0.0), makePoint(3.0, 3.0, 3.0)); - const auto s = line.getSValue(makePose(2.0, 2.0, 2.0), 1.0, true); - EXPECT_TRUE(s); - if (s) { - EXPECT_DOUBLE_EQ(s.value(), std::hypot(2.0, 2.0, 2.0)); - } -} - -TEST(LineSegment, getSValue_outOfRange) -{ - math::geometry::LineSegment line(makePoint(0.0, 0.0, 0.0), makePoint(3.0, 3.0, 3.0)); - const auto s = line.getSValue(makePose(4.0, 4.0, 4.0), 1.0, false); - EXPECT_FALSE(s); -} - -TEST(LineSegment, getSValue_outOfRangeDenormalize) -{ - math::geometry::LineSegment line(makePoint(0.0, 0.0, 0.0), makePoint(3.0, 3.0, 3.0)); - const auto s = line.getSValue(makePose(4.0, 4.0, 4.0), 1.0, true); - EXPECT_FALSE(s); -} - -TEST(LineSegment, getSValue_parallel) -{ - math::geometry::LineSegment line(makePoint(0.0, 0.0, 0.0), makePoint(3.0, 3.0, 0.0)); - const auto s = line.getSValue( - makePose( - 1.0, 0.0, 0.0, - math::geometry::convertEulerAngleToQuaternion(makeVector(0.0, 0.0, M_PI_4 * 3.0))), - 1000.0, false); - EXPECT_FALSE(s); -} - -TEST(LineSegment, getSValue_parallelDenormalize) -{ - math::geometry::LineSegment line(makePoint(0.0, 0.0, 0.0), makePoint(3.0, 3.0, 0.0)); - const auto s = line.getSValue( - makePose( - 1.0, 0.0, 0.0, - math::geometry::convertEulerAngleToQuaternion(makeVector(0.0, 0.0, M_PI_4 * 3.0))), - 1000.0, true); - EXPECT_FALSE(s); -} - -TEST(LineSegment, GetPoint_outOfBounds_denormalized) +TEST(LineSegment, getPoint_outOfBounds_denormalized) { const auto line = math::geometry::LineSegment(makePoint(-1.0, -2.0, 1.0), makePoint(3.0, 2.0, -1.0)); @@ -358,7 +80,7 @@ TEST(LineSegment, GetPoint_outOfBounds_denormalized) EXPECT_THROW(line.getPoint(-1.0, true), common::SimulationError); } -TEST(LineSegment, GetPoint_outOfBounds_normalized) +TEST(LineSegment, getPoint_outOfBounds_normalized) { const auto line = math::geometry::LineSegment(makePoint(-1.0, -2.0, 1.0), makePoint(3.0, 2.0, -1.0)); @@ -368,7 +90,7 @@ TEST(LineSegment, GetPoint_outOfBounds_normalized) EXPECT_THROW(line.getPoint(-0.1, false), common::SimulationError); } -TEST(LineSegment, GetPoint_inside_denormalized) +TEST(LineSegment, getPoint_inside_denormalized) { const auto line = math::geometry::LineSegment(makePoint(-1.0, -2.0, 1.0), makePoint(3.0, 2.0, -1.0)); @@ -379,7 +101,7 @@ TEST(LineSegment, GetPoint_inside_denormalized) EXPECT_POINT_EQ(line.getPoint(6.0, true), makePoint(3.0, 2.0, -1.0)); } -TEST(LineSegment, GetPoint_inside_normalized) +TEST(LineSegment, getPoint_inside_normalized) { const auto line = math::geometry::LineSegment(makePoint(-1.0, -2.0, 1.0), makePoint(3.0, 2.0, -1.0)); @@ -464,6 +186,26 @@ TEST(LineSegment, getPose_pitch) math::geometry::convertEulerAngleToQuaternion(makeVector(0.0, -M_PI_4, M_PI_4)))); } +TEST(LineSegment, isIntersect2DDisjoint) +{ + const math::geometry::LineSegment line0(makePoint(0.0, 0.0), makePoint(1.0, 1.0)); + const math::geometry::LineSegment line1(makePoint(1.0, 0.0), makePoint(2.0, 1.0)); + EXPECT_FALSE(line0.isIntersect2D(line1)); +} + +TEST(LineSegment, isIntersect2DIntersect) +{ + const math::geometry::LineSegment line0(makePoint(1.0, 1.0), makePoint(2.0, 1.0)); + const math::geometry::LineSegment line1(makePoint(1.0, 0.0), makeVector(1.0, 1.0), 3.0); + EXPECT_TRUE(line0.isIntersect2D(line1)); +} + +TEST(LineSegment, isIntersect2DIdentical) +{ + const math::geometry::LineSegment line(makePoint(0.0, 0.0), makePoint(1.0, 1.0)); + EXPECT_TRUE(line.isIntersect2D(line)); +} + TEST(LineSegment, isIntersect2D_pointInside) { const auto line = @@ -699,57 +441,264 @@ TEST(LineSegment, getIntersection2DSValue_point_outside) EXPECT_FALSE(line.getIntersection2DSValue(makePoint(-7.0, -7.0, 0.0), true).has_value()); } -/// @brief In this test case, we check collision with the line segment with start point (x,y,z) = (0,-1,0) and end point (x,y,z) = (0,1,0) in the cartesian coordinate system. (variable name `line`). -TEST(LineSegment, getIntersection2DSValue) +TEST(LineSegment, getIntersection2DDisjoint) { - { - math::geometry::LineSegment line( - geometry_msgs::build().x(0).y(-1).z(0), - geometry_msgs::build().x(0).y(1).z(0)); - - /** - * @note Testing the `LineSegment::getIntersection2D` function can throw error getting intersection with exact same line segment. - * In this case, any s value can be a intersection point, so we cannot return single value. - */ - // [Snippet_getIntersection2D_with_line] - { - EXPECT_THROW(line.getIntersection2D(line), common::SimulationError); - } - // [Snippet_getIntersection2D_with_line] - /// @snippet test/test_line_segment.cpp Snippet_getIntersection2D_with_line - - /** - * @note Testing the `LineSegment::getIntersection2D` function can throw error getting intersection with part of the line segment `line`. - * In this case, any s value can be a intersection point, so we cannot return single value. - */ - // [Snippet_getIntersection2D_with_part_of_line] - { - EXPECT_THROW( - line.getIntersection2D(math::geometry::LineSegment( - geometry_msgs::build().x(0).y(-1).z(0), - geometry_msgs::build().x(0).y(0).z(0))), - common::SimulationError); - } - // [Snippet_getIntersection2D_with_part_of_line] - /// @snippet test/test_line_segment.cpp Snippet_getIntersection2D_with_part_of_line - - /// @note @note Testing the `LineSegment::getIntersection2D` function can find collision with the line segment with start point (x,y,z) = (1,0,0) and end point (x,y,z) = (-1,0,0) in the cartesian coordinate system and `line`. - // [Snippet_getIntersection2D_line_1_0_0_-1_0_0] - { - const auto point = line.getIntersection2D(math::geometry::LineSegment( - geometry_msgs::build().x(1).y(0).z(0), - geometry_msgs::build().x(-1).y(0).z(0))); - EXPECT_TRUE(point); - if (point) { - EXPECT_POINT_EQ( - point.value(), geometry_msgs::build().x(0).y(0).z(0)); - } - } - // [Snippet_getIntersection2D_line_1_0_0_-1_0_0] - /// @snippet test/test_line_segment.cpp Snippet_getIntersection2D_line_1_0_0_-1_0_0 + const math::geometry::LineSegment line0(makePoint(0.0, 0.0), makePoint(1.0, 1.0)); + const math::geometry::LineSegment line1(makePoint(1.0, 0.0), makePoint(2.0, 1.0)); + EXPECT_FALSE(line0.getIntersection2D(line1)); +} + +TEST(LineSegment, getIntersection2DIntersect) +{ + const auto line0 = math::geometry::LineSegment(makePoint(0.0, 0.0), makePoint(1.0, 1.0)); + const auto line1 = math::geometry::LineSegment(makePoint(1.0, 0.0), makePoint(0.0, 1.0)); + + const auto p0 = line0.getIntersection2D(line1); + const auto p1 = line1.getIntersection2D(line0); + + ASSERT_TRUE(p0.has_value()); + ASSERT_TRUE(p1.has_value()); + EXPECT_POINT_EQ(p0.value(), makePoint(0.5, 0.5)); + EXPECT_POINT_EQ(p1.value(), makePoint(0.5, 0.5)); +} + +TEST(LineSegment, getIntersection2DIdentical) +{ + const auto line = math::geometry::LineSegment(makePoint(0.0, 0.0), makePoint(1.0, 1.0)); + + EXPECT_THROW(line.getIntersection2D(line), common::SimulationError); +} + +TEST(LineSegment, getSValue) +{ + math::geometry::LineSegment line(makePoint(0.0, 0.0, 0.0), makePoint(3.0, 3.0, 3.0)); + const auto s = line.getSValue(makePose(2.0, 2.0, 2.0), 1.0, false); + EXPECT_TRUE(s); + if (s) { + EXPECT_DOUBLE_EQ(s.value(), 2.0 / 3.0); + } +} + +TEST(LineSegment, getSValue_denormalize) +{ + math::geometry::LineSegment line(makePoint(0.0, 0.0, 0.0), makePoint(3.0, 3.0, 3.0)); + const auto s = line.getSValue(makePose(2.0, 2.0, 2.0), 1.0, true); + EXPECT_TRUE(s); + if (s) { + EXPECT_DOUBLE_EQ(s.value(), std::hypot(2.0, 2.0, 2.0)); } } +TEST(LineSegment, getSValue_outOfRange) +{ + math::geometry::LineSegment line(makePoint(0.0, 0.0, 0.0), makePoint(3.0, 3.0, 3.0)); + const auto s = line.getSValue(makePose(4.0, 4.0, 4.0), 1.0, false); + EXPECT_FALSE(s); +} + +TEST(LineSegment, getSValue_outOfRangeDenormalize) +{ + math::geometry::LineSegment line(makePoint(0.0, 0.0, 0.0), makePoint(3.0, 3.0, 3.0)); + const auto s = line.getSValue(makePose(4.0, 4.0, 4.0), 1.0, true); + EXPECT_FALSE(s); +} + +TEST(LineSegment, getSValue_parallel) +{ + math::geometry::LineSegment line(makePoint(0.0, 0.0, 0.0), makePoint(3.0, 3.0, 0.0)); + const auto s = line.getSValue( + makePose( + 1.0, 0.0, 0.0, + math::geometry::convertEulerAngleToQuaternion(makeVector(0.0, 0.0, M_PI_4 * 3.0))), + 1000.0, false); + EXPECT_FALSE(s); +} + +TEST(LineSegment, getSValue_parallelDenormalize) +{ + math::geometry::LineSegment line(makePoint(0.0, 0.0, 0.0), makePoint(3.0, 3.0, 0.0)); + const auto s = line.getSValue( + makePose( + 1.0, 0.0, 0.0, + math::geometry::convertEulerAngleToQuaternion(makeVector(0.0, 0.0, M_PI_4 * 3.0))), + 1000.0, true); + EXPECT_FALSE(s); +} + +TEST(LineSegment, getVector) +{ + const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(2.0, 3.0, 4.0)); + EXPECT_VECTOR3_EQ(line.getVector(), makeVector(1.0, 1.0, 1.0)); +} + +TEST(LineSegment, getVectorZeroLength) +{ + const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(1.0, 2.0, 3.0)); + EXPECT_VECTOR3_EQ(line.getVector(), makeVector(0.0, 0.0, 0.0)); +} + +TEST(LineSegment, getNormalVector) +{ + const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(2.0, 3.0, 4.0)); + EXPECT_VECTOR3_EQ(line.getNormalVector(), makeVector(-1.0, 1.0, 0.0)); +} + +TEST(LineSegment, getNormalVector_zeroLength) +{ + const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(1.0, 2.0, 3.0)); + EXPECT_VECTOR3_EQ(line.getNormalVector(), makeVector(0.0, 0.0, 0.0)); +} + +TEST(LineSegment, get2DVector) +{ + const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(2.0, 3.0, 4.0)); + EXPECT_VECTOR3_EQ(line.get2DVector(), makeVector(1.0, 1.0, 0.0)); +} + +TEST(LineSegment, get2DVectorZeroLength) +{ + const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(1.0, 2.0, 3.0)); + EXPECT_VECTOR3_EQ(line.get2DVector(), makeVector(0.0, 0.0, 0.0)); +} + +TEST(LineSegment, getLength) +{ + const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(2.0, 3.0, 4.0)); + EXPECT_DOUBLE_EQ(line.getLength(), std::sqrt(3.0)); +} + +TEST(LineSegment, getLengthZeroLength) +{ + const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(1.0, 2.0, 3.0)); + EXPECT_DOUBLE_EQ(line.getLength(), 0.0); +} + +TEST(LineSegment, get2DLength) +{ + const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(2.0, 3.0, 4.0)); + EXPECT_DOUBLE_EQ(line.get2DLength(), std::sqrt(2.0)); +} + +TEST(LineSegment, get2DLengthZeroLength) +{ + const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(1.0, 2.0, 3.0)); + EXPECT_DOUBLE_EQ(line.get2DLength(), 0.0); +} + +TEST(LineSegment, getSlope) +{ + const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(3.0, 3.0, 4.0)); + EXPECT_DOUBLE_EQ(line.getSlope(), 0.5); +} + +TEST(LineSegment, getSlopeZeroLength) +{ + const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(1.0, 2.0, 3.0)); + EXPECT_TRUE(std::isnan(line.getSlope())); +} + +TEST(LineSegment, getSquaredDistanceIn2D) +{ + const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(3.0, 4.0, 5.0)); + EXPECT_DOUBLE_EQ(line.getSquaredDistanceIn2D(makePoint(0.0, 1.0, 2.0), 0.5, false), 8.0); +} + +TEST(LineSegment, getSquaredDistanceIn2D_denormalize) +{ + const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(3.0, 4.0, 5.0)); + EXPECT_DOUBLE_EQ( + line.getSquaredDistanceIn2D(makePoint(0.0, 1.0, 2.0), std::sqrt(3.0), true), 8.0); +} + +TEST(LineSegment, getSquaredDistanceVector) +{ + const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(3.0, 4.0, 5.0)); + EXPECT_VECTOR3_EQ( + line.getSquaredDistanceVector(makePoint(0.0, 1.0, 2.0), 0.5, false), + makeVector(-2.0, -2.0, -2.0)); +} + +TEST(LineSegment, getSquaredDistanceVector_denormalize) +{ + const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(3.0, 4.0, 5.0)); + EXPECT_VECTOR3_EQ( + line.getSquaredDistanceVector(makePoint(0.0, 1.0, 2.0), std::sqrt(3.0), true), + makeVector(-2.0, -2.0, -2.0)); +} + +TEST(LineSegment, getLineSegments) +{ + const std::vector points{ + makePoint(1.0, 2.0, 3.0), makePoint(2.0, 3.0, 4.0), makePoint(3.0, 4.0, 5.0), + makePoint(4.0, 5.0, 6.0)}; + const std::vector lines = + math::geometry::getLineSegments(points, false); + EXPECT_EQ(lines.size(), size_t(3)); + EXPECT_POINT_EQ(lines[0].start_point, points[0]); + EXPECT_POINT_EQ(lines[0].end_point, points[1]); + EXPECT_POINT_EQ(lines[1].start_point, points[1]); + EXPECT_POINT_EQ(lines[1].end_point, points[2]); + EXPECT_POINT_EQ(lines[2].start_point, points[2]); + EXPECT_POINT_EQ(lines[2].end_point, points[3]); +} + +TEST(LineSegment, getLineSegments_closeStartEnd) +{ + const std::vector points{ + makePoint(1.0, 2.0, 3.0), makePoint(2.0, 3.0, 4.0), makePoint(3.0, 4.0, 5.0), + makePoint(4.0, 5.0, 6.0)}; + const std::vector lines = + math::geometry::getLineSegments(points, true); + EXPECT_EQ(lines.size(), size_t(4)); + EXPECT_POINT_EQ(lines[0].start_point, points[0]); + EXPECT_POINT_EQ(lines[0].end_point, points[1]); + EXPECT_POINT_EQ(lines[1].start_point, points[1]); + EXPECT_POINT_EQ(lines[1].end_point, points[2]); + EXPECT_POINT_EQ(lines[2].start_point, points[2]); + EXPECT_POINT_EQ(lines[2].end_point, points[3]); + EXPECT_POINT_EQ(lines[3].start_point, points[3]); + EXPECT_POINT_EQ(lines[3].end_point, points[0]); +} + +TEST(LineSegment, getLineSegmentsVectorEmpty) +{ + const std::vector points; + const std::vector lines = math::geometry::getLineSegments(points); + EXPECT_EQ(lines.size(), size_t(0)); +} + +TEST(LineSegment, getLineSegmentsVectorIdentical) +{ + geometry_msgs::msg::Point point = makePoint(1.0, 2.0, 3.0); + const std::vector points{point, point, point, point}; + const std::vector lines = + math::geometry::getLineSegments(points, false); + EXPECT_EQ(lines.size(), size_t(3)); + EXPECT_POINT_EQ(lines[0].start_point, point); + EXPECT_POINT_EQ(lines[0].end_point, point); + EXPECT_POINT_EQ(lines[1].start_point, point); + EXPECT_POINT_EQ(lines[1].end_point, point); + EXPECT_POINT_EQ(lines[2].start_point, point); + EXPECT_POINT_EQ(lines[2].end_point, point); +} + +TEST(LineSegment, getLineSegmentsVectorIdentical_closeStartEnd) +{ + geometry_msgs::msg::Point point = makePoint(1.0, 2.0, 3.0); + const std::vector points{point, point, point, point}; + const std::vector lines = + math::geometry::getLineSegments(points, true); + EXPECT_EQ(lines.size(), size_t(4)); + EXPECT_POINT_EQ(lines[0].start_point, point); + EXPECT_POINT_EQ(lines[0].end_point, point); + EXPECT_POINT_EQ(lines[1].start_point, point); + EXPECT_POINT_EQ(lines[1].end_point, point); + EXPECT_POINT_EQ(lines[2].start_point, point); + EXPECT_POINT_EQ(lines[2].end_point, point); + EXPECT_POINT_EQ(lines[3].start_point, point); + EXPECT_POINT_EQ(lines[3].end_point, point); +} + int main(int argc, char ** argv) { testing::InitGoogleTest(&argc, argv); From e53de65f30c5f59e7420eff91df3f744c1b4c406 Mon Sep 17 00:00:00 2001 From: robomic Date: Tue, 6 Aug 2024 08:55:25 +0200 Subject: [PATCH 088/304] tune down numbers --- common/math/geometry/test/src/polygon/test_line_segment.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/common/math/geometry/test/src/polygon/test_line_segment.cpp b/common/math/geometry/test/src/polygon/test_line_segment.cpp index 6423a3447b2..3d3b590394b 100644 --- a/common/math/geometry/test/src/polygon/test_line_segment.cpp +++ b/common/math/geometry/test/src/polygon/test_line_segment.cpp @@ -221,8 +221,7 @@ TEST(LineSegment, isIntersect2D_pointOutside) math::geometry::LineSegment(makePoint(-1.0, -2.0, 0.0), makePoint(3.0, 2.0, 4.0)); EXPECT_FALSE(line.isIntersect2D(makePoint(-1.0, -1.0, 1.0))); - EXPECT_FALSE(line.isIntersect2D( - makePoint(0.0, std::numeric_limits::max(), std::numeric_limits::max()))); + EXPECT_FALSE(line.isIntersect2D(makePoint(0.0, 89.0, 97.0))); EXPECT_FALSE(line.isIntersect2D(makePoint(-3.0, 0.0, 0.0))); EXPECT_FALSE(line.isIntersect2D(makePoint(4.0, 0.0, 0.0))); From a0bbb4574aa9d5ff304e189620d185d7f9542080 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Tue, 6 Aug 2024 16:13:26 +0900 Subject: [PATCH 089/304] fix: update target entities of RelativeClearanceCondition in every frame --- .../syntax/relative_clearance_condition.cpp | 37 ++++++++++--------- 1 file changed, 20 insertions(+), 17 deletions(-) diff --git a/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp b/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp index 94d29503186..e8ab07f7897 100644 --- a/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp @@ -32,22 +32,7 @@ RelativeClearanceCondition::RelativeClearanceCondition( free_space(readAttribute("freeSpace", node, scope)), opposite_lanes(readAttribute("oppositeLanes", node, scope)), relative_lane_range(readElements("RelativeLaneRange", node, scope)), - entity_refs([&]() { - auto entities = readElements("EntityRef", node, scope); - if (entities.empty()) { - for (const auto & entity : *global().entities) { - if ( - std::find_if( - triggering_entities.entity_refs.begin(), triggering_entities.entity_refs.end(), - [&](const auto & triggering_entity) { - return triggering_entity.name() == entity.first; - }) == triggering_entities.entity_refs.end()) { - entities.emplace_back(entity.first); - } - } - } - return entities; - }()), + entity_refs(readElements("EntityRef", node, scope)), triggering_entities(triggering_entities) { } @@ -85,9 +70,27 @@ auto RelativeClearanceCondition::description() const -> String auto RelativeClearanceCondition::evaluate() -> Object { + auto target_entities = [&]() { + if (not entity_refs.empty()) { + return entity_refs; + } else { + std::list entities; + for (const auto & entity : *global().entities) { + if ( + std::find_if( + triggering_entities.entity_refs.begin(), triggering_entities.entity_refs.end(), + [&](const auto & triggering_entity) { + return triggering_entity.name() == entity.first; + }) == triggering_entities.entity_refs.end()) { + entities.emplace_back(entity.first); + } + } + return entities; + } + }(); return asBoolean(triggering_entities.apply([&](const auto & triggering_entity) { return std::all_of( - entity_refs.begin(), entity_refs.end(), + target_entities.begin(), target_entities.end(), [&, is_back = (std::abs(evaluateRelativeHeading(triggering_entity)) > 0.5 * boost::math::constants::pi())](const auto & entity) { From 21110dfccb7905cde8ea4a68a914afe5565e0f38 Mon Sep 17 00:00:00 2001 From: robomic Date: Tue, 6 Aug 2024 09:47:57 +0200 Subject: [PATCH 090/304] quaternion operators --- .../test/src/quaternion/test_quaternion.cpp | 30 +++++++++---------- 1 file changed, 15 insertions(+), 15 deletions(-) diff --git a/common/math/geometry/test/src/quaternion/test_quaternion.cpp b/common/math/geometry/test/src/quaternion/test_quaternion.cpp index 14c7f3a82ba..0b15b1b777b 100644 --- a/common/math/geometry/test/src/quaternion/test_quaternion.cpp +++ b/common/math/geometry/test/src/quaternion/test_quaternion.cpp @@ -23,42 +23,42 @@ constexpr double EPS = 1e-6; -TEST(Quaternion, testCase1) +TEST(Quaternion, operator_addition) { using math::geometry::operator+; - auto q1 = math::geometry::makeQuaternion(0, 1, 0, 1); - auto q2 = math::geometry::makeQuaternion(0, 1, 0, 1); - auto ans = q1 + q2; + const auto q1 = math::geometry::makeQuaternion(0, 1, 0, 1); + const auto q2 = math::geometry::makeQuaternion(0, 1, 0, 1); + const auto ans = q1 + q2; EXPECT_QUATERNION_EQ(ans, math::geometry::makeQuaternion(0, 2, 0, 2)) } -TEST(Quaternion, testCase2) +TEST(Quaternion, operator_subtraction) { using math::geometry::operator-; - auto q1 = math::geometry::makeQuaternion(0, 1, 0, 1); - auto q2 = math::geometry::makeQuaternion(0, 1, 0, 1); - auto ans = q1 - q2; + const auto q1 = math::geometry::makeQuaternion(0, 1, 0, 1); + const auto q2 = math::geometry::makeQuaternion(0, 1, 0, 1); + const auto ans = q1 - q2; EXPECT_QUATERNION_EQ(ans, math::geometry::makeQuaternion(0, 0, 0, 0)) } -TEST(Quaternion, testCase3) +TEST(Quaternion, operator_multiplication) { using math::geometry::operator*; - auto q1 = math::geometry::makeQuaternion(0, 1, 0, 1); - auto q2 = math::geometry::makeQuaternion(0, 1, 0, 1); - auto ans = q1 * q2; + const auto q1 = math::geometry::makeQuaternion(0, 1, 0, 1); + const auto q2 = math::geometry::makeQuaternion(0, 1, 0, 1); + const auto ans = q1 * q2; EXPECT_QUATERNION_EQ(ans, math::geometry::makeQuaternion(0, 2, 0, 0)) } -TEST(Quaternion, testCase4) +TEST(Quaternion, operator_additionAssignment) { using math::geometry::operator+=; - auto q1 = math::geometry::makeQuaternion(0, 1, 0, 1); - auto q2 = math::geometry::makeQuaternion(0, 1, 0, 1); + const auto q1 = math::geometry::makeQuaternion(0, 1, 0, 1); + const auto q2 = math::geometry::makeQuaternion(0, 1, 0, 1); q1 += q2; EXPECT_QUATERNION_EQ(q1, math::geometry::makeQuaternion(0, 2, 0, 2)) } From 0f44b0caf1973bec4cecfc7236283ef96b512f91 Mon Sep 17 00:00:00 2001 From: robomic Date: Tue, 6 Aug 2024 09:57:54 +0200 Subject: [PATCH 091/304] rename tests in CatmullRomSpline --- common/math/geometry/test/src/quaternion/test_quaternion.cpp | 2 +- .../math/geometry/test/src/spline/test_catmull_rom_spline.cpp | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/common/math/geometry/test/src/quaternion/test_quaternion.cpp b/common/math/geometry/test/src/quaternion/test_quaternion.cpp index 0b15b1b777b..d2b7aa857c8 100644 --- a/common/math/geometry/test/src/quaternion/test_quaternion.cpp +++ b/common/math/geometry/test/src/quaternion/test_quaternion.cpp @@ -57,7 +57,7 @@ TEST(Quaternion, operator_additionAssignment) { using math::geometry::operator+=; - const auto q1 = math::geometry::makeQuaternion(0, 1, 0, 1); + auto q1 = math::geometry::makeQuaternion(0, 1, 0, 1); const auto q2 = math::geometry::makeQuaternion(0, 1, 0, 1); q1 += q2; EXPECT_QUATERNION_EQ(q1, math::geometry::makeQuaternion(0, 2, 0, 2)) diff --git a/common/math/geometry/test/src/spline/test_catmull_rom_spline.cpp b/common/math/geometry/test/src/spline/test_catmull_rom_spline.cpp index b224e7d0d45..68ad3855eca 100644 --- a/common/math/geometry/test/src/spline/test_catmull_rom_spline.cpp +++ b/common/math/geometry/test/src/spline/test_catmull_rom_spline.cpp @@ -70,7 +70,7 @@ void addOffset(geometry_msgs::msg::Point & point, const double offset, const dou /// @brief Testing the `CatmullRomSpline::getCollisionPointIn2D` function works valid. /// In this test case, number of the control points of the catmull-rom spline (variable name `spline`) is 2, so the shape of the value `spline` is line segment. -TEST(CatmullRomSpline, GetCollisionWith2ControlPoints) +TEST(CatmullRomSpline, getCollisionPointIn2D_2ControlPoints) { /// @note The `spline` has control points p0 and p1. Control point p0 is point (x,y,z) = (0,0,0) and control point p1 is point (x,y,z) = (1,0,0) in the cartesian coordinate system. // [Snippet_construct_spline] @@ -149,7 +149,7 @@ TEST(CatmullRomSpline, GetCollisionWith2ControlPoints) /// @brief Testing the `CatmullRomSpline::getCollisionPointIn2D` function works valid /// In this test case, number of the control points of the catmull-rom spline (variable name `spline`) is 1, so the shape of the value `spline` is single point. -TEST(CatmullRomSpline, GetCollisionWith1ControlPoint) +TEST(CatmullRomSpline, getCollisionPointIn2D_1ControlPoint) { /// @note The variable `spline` has control point with point (x,y,z) = (0,1,0) in the cartesian coordinate system. So, `spline` is same as point (x,y,z) = (0,1,0). auto spline = math::geometry::CatmullRomSpline( From 2085b6c22f175ded15ff67532c10d2691156a245 Mon Sep 17 00:00:00 2001 From: robomic Date: Tue, 6 Aug 2024 10:20:31 +0200 Subject: [PATCH 092/304] rename tests in HermiteCurve --- .../test/src/spline/test_hermite_curve.cpp | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/common/math/geometry/test/src/spline/test_hermite_curve.cpp b/common/math/geometry/test/src/spline/test_hermite_curve.cpp index 08ab6c3c4a0..833a2079322 100644 --- a/common/math/geometry/test/src/spline/test_hermite_curve.cpp +++ b/common/math/geometry/test/src/spline/test_hermite_curve.cpp @@ -503,7 +503,7 @@ TEST(HermiteCurveTest, getTangentVector4) EXPECT_DOUBLE_EQ(curve.getTangentVector(0.5, false).y / norm, 1.0 / std::sqrt(2.0)); } -TEST(HermiteCurveTest, getTangentVectorAutoscale1) +TEST(HermiteCurveTest, getTangentVectorDenormalized1) { //p(0,0) v(1,0)-> p(1,1) v(0,1) const auto curve = makeCurve1(); constexpr double eps = 0.1; @@ -513,7 +513,7 @@ TEST(HermiteCurveTest, getTangentVectorAutoscale1) EXPECT_NEAR(curve.getTangentVector(0.75, true).y / norm, 1.0 / std::sqrt(2.0), eps); } -TEST(HermiteCurveTest, getTangentVectorAutoscale2) +TEST(HermiteCurveTest, getTangentVectorDenormalized2) { //p(0,0) v(1,0)-> p(1,-1) v(0,-1) const auto curve = makeCurve2(); constexpr double eps = 0.1; @@ -523,7 +523,7 @@ TEST(HermiteCurveTest, getTangentVectorAutoscale2) EXPECT_NEAR(curve.getTangentVector(0.75, true).y / norm, -1.0 / std::sqrt(2.0), eps); } -TEST(HermiteCurveTest, getTangentVectorAutoscale3) +TEST(HermiteCurveTest, getTangentVectorDenormalized3) { //p(1,1) v(0,-1)-> p(0,0) v(-1,0) const auto curve = makeCurve3(); constexpr double eps = 0.1; @@ -533,7 +533,7 @@ TEST(HermiteCurveTest, getTangentVectorAutoscale3) EXPECT_NEAR(curve.getTangentVector(0.75, true).y / norm, -1.0 / std::sqrt(2.0), eps); } -TEST(HermiteCurveTest, getTangentVectorAutoscale4) +TEST(HermiteCurveTest, getTangentVectorDenormalized4) { //p(1,-1) v(0,1)-> p(0,0) v(-1,0) const auto curve = makeCurve4(); constexpr double eps = 0.1; @@ -579,7 +579,7 @@ TEST(HermiteCurveTest, getNormalVector4) EXPECT_DOUBLE_EQ(curve.getNormalVector(0.5, false).y / norm, -1.0 / std::sqrt(2.0)); } -TEST(HermiteCurveTest, getNormalVectorAutoscale1) +TEST(HermiteCurveTest, getNormalVectorDenormalized1) { //p(0,0) v(1,0)-> p(1,1) v(0,1) const auto curve = makeCurve1(); constexpr double eps = 0.1; @@ -589,7 +589,7 @@ TEST(HermiteCurveTest, getNormalVectorAutoscale1) EXPECT_NEAR(curve.getNormalVector(0.75, true).y / norm, 1.0 / std::sqrt(2.0), eps); } -TEST(HermiteCurveTest, getNormalVectorAutoscale2) +TEST(HermiteCurveTest, getNormalVectorDenormalized2) { //p(0,0) v(1,0)-> p(1,-1) v(0,-1) const auto curve = makeCurve2(); constexpr double eps = 0.1; @@ -599,7 +599,7 @@ TEST(HermiteCurveTest, getNormalVectorAutoscale2) EXPECT_NEAR(curve.getNormalVector(0.75, true).y / norm, 1.0 / std::sqrt(2.0), eps); } -TEST(HermiteCurveTest, getNormalVectorAutoscale3) +TEST(HermiteCurveTest, getNormalVectorDenormalized3) { //p(1,1) v(0,-1)-> p(0,0) v(-1,0) const auto curve = makeCurve3(); constexpr double eps = 0.1; @@ -609,7 +609,7 @@ TEST(HermiteCurveTest, getNormalVectorAutoscale3) EXPECT_NEAR(curve.getNormalVector(0.75, true).y / norm, -1.0 / std::sqrt(2.0), eps); } -TEST(HermiteCurveTest, getNormalVectorAutoscale4) +TEST(HermiteCurveTest, getNormalVectorDenormalized4) { //p(1,-1) v(0,1)-> p(0,0) v(-1,0) const auto curve = makeCurve4(); constexpr double eps = 0.1; From 86f1f8f377f5ddf569b3598c18ac3168d90a7eed Mon Sep 17 00:00:00 2001 From: robomic Date: Tue, 6 Aug 2024 10:28:13 +0200 Subject: [PATCH 093/304] clean up vector3 --- .../test/src/spline/test_hermite_curve.cpp | 2 +- .../test/src/vector3/test_vector3.cpp | 22 +++++++------------ 2 files changed, 9 insertions(+), 15 deletions(-) diff --git a/common/math/geometry/test/src/spline/test_hermite_curve.cpp b/common/math/geometry/test/src/spline/test_hermite_curve.cpp index 833a2079322..0ea5f153526 100644 --- a/common/math/geometry/test/src/spline/test_hermite_curve.cpp +++ b/common/math/geometry/test/src/spline/test_hermite_curve.cpp @@ -320,7 +320,7 @@ TEST(HermiteCurveTest, getSValue) EXPECT_NEAR(s2.value(), 1.0, EPS); } -TEST(HermiteCurveTest, getSValueAutoscale) +TEST(HermiteCurveTest, getSValueDenormalized) { const auto curve = makeLine2(); diff --git a/common/math/geometry/test/src/vector3/test_vector3.cpp b/common/math/geometry/test/src/vector3/test_vector3.cpp index b07cfede363..45f24c3b726 100644 --- a/common/math/geometry/test/src/vector3/test_vector3.cpp +++ b/common/math/geometry/test/src/vector3/test_vector3.cpp @@ -75,6 +75,12 @@ TEST(Vector3, normalize_msgVector) const double norm = std::sqrt(14.0); EXPECT_VECTOR3_EQ( math::geometry::normalize(vec0), makeVector(1.0 / norm, 2.0 / norm, 3.0 / norm)); + + geometry_msgs::msg::Vector3 vec1; + EXPECT_DOUBLE_EQ(math::geometry::norm(vec1), 0.0); + + geometry_msgs::msg::Vector3 vec2 = makeVector(1.0, 0.0, 3.0); + EXPECT_DOUBLE_EQ(math::geometry::norm(vec2), std::sqrt(10.0)); } TEST(Vector3, normalize_customVector) @@ -184,25 +190,13 @@ TEST(Vector3, additionAssignment_customVector) EXPECT_VECTOR3_EQ(vec0, makeVector(0.0, 0.0, 2.0)); } -TEST(Vector3, vector3_getSizeZero) -{ - geometry_msgs::msg::Vector3 vec; - EXPECT_DOUBLE_EQ(math::geometry::norm(vec), 0.0); -} - -TEST(Vector3, vector3_getSize) -{ - geometry_msgs::msg::Vector3 vec = makeVector(1.0, 0.0, 3.0); - EXPECT_DOUBLE_EQ(math::geometry::norm(vec), std::sqrt(10.0)); -} - -TEST(Vector3, vector3_normalizeZero) +TEST(Vector3, normalize_zeroLength) { geometry_msgs::msg::Vector3 vec; EXPECT_THROW(math::geometry::normalize(vec), common::SimulationError); } -TEST(Vector3, vector3_normalize) +TEST(Vector3, normalize) { geometry_msgs::msg::Vector3 vec = makeVector(1.0, 0.0, 3.0); vec = math::geometry::normalize(vec); From 132ede4236c08394468966fa37a3eca5e211c376 Mon Sep 17 00:00:00 2001 From: robomic Date: Tue, 6 Aug 2024 10:29:37 +0200 Subject: [PATCH 094/304] bounding_box clean up --- common/math/geometry/test/src/test_bounding_box.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/common/math/geometry/test/src/test_bounding_box.cpp b/common/math/geometry/test/src/test_bounding_box.cpp index c6df82911d0..36abed690c3 100644 --- a/common/math/geometry/test/src/test_bounding_box.cpp +++ b/common/math/geometry/test/src/test_bounding_box.cpp @@ -46,7 +46,7 @@ TEST(BoundingBox, getPointsFromBboxCustom) EXPECT_POINT_EQ(points[3], makePoint(6.5, -2.0, 1.0)); } -TEST(BoundingBox, get2DPolygonZeroPose) +TEST(BoundingBox, toPolygon2D_zeroPose) { geometry_msgs::msg::Pose pose; traffic_simulator_msgs::msg::BoundingBox bounding_box = makeBbox(2.0, 2.0, 2.0); @@ -61,7 +61,7 @@ TEST(BoundingBox, get2DPolygonZeroPose) EXPECT_BOOST_POINT_2D_AND_POINT_EQ(poly.outer()[4], makePoint(1.0, 1.0)); } -TEST(BoundingBox, get2DPolygonOnlyTranslation) +TEST(BoundingBox, toPolygon2D_onlyTranslation) { geometry_msgs::msg::Pose pose = makePose(1.0, 2.0); traffic_simulator_msgs::msg::BoundingBox bounding_box = makeBbox(2.0, 2.0, 2.0); @@ -76,7 +76,7 @@ TEST(BoundingBox, get2DPolygonOnlyTranslation) EXPECT_BOOST_POINT_2D_AND_POINT_EQ(poly.outer()[4], makePoint(2.0, 3.0)); } -TEST(BoundingBox, get2DPolygonFullPose) +TEST(BoundingBox, toPolygon2D_fullPose) { geometry_msgs::msg::Pose pose = makePose(1.0, 2.0); pose.orientation = math::geometry::convertEulerAngleToQuaternion( From 21730c7962ac2418f245dedede8242dde7501cc4 Mon Sep 17 00:00:00 2001 From: robomic Date: Tue, 6 Aug 2024 11:49:28 +0200 Subject: [PATCH 095/304] add comments --- .../test/src/polygon/test_line_segment.cpp | 66 +++++++++++++++++++ .../test/src/quaternion/test_quaternion.cpp | 12 ++++ .../test/src/spline/test_hermite_curve.cpp | 27 ++++++++ .../geometry/test/src/test_bounding_box.cpp | 9 +++ .../test/src/vector3/test_vector3.cpp | 6 ++ 5 files changed, 120 insertions(+) diff --git a/common/math/geometry/test/src/polygon/test_line_segment.cpp b/common/math/geometry/test/src/polygon/test_line_segment.cpp index 3d3b590394b..9ab3829d121 100644 --- a/common/math/geometry/test/src/polygon/test_line_segment.cpp +++ b/common/math/geometry/test/src/polygon/test_line_segment.cpp @@ -70,6 +70,9 @@ TEST(LineSegment, initializeVectorZeroLength) EXPECT_POINT_EQ(line_segment.end_point, point); } +/** + * @note Test error throwing when s is out of bounds. + */ TEST(LineSegment, getPoint_outOfBounds_denormalized) { const auto line = @@ -80,6 +83,9 @@ TEST(LineSegment, getPoint_outOfBounds_denormalized) EXPECT_THROW(line.getPoint(-1.0, true), common::SimulationError); } +/** + * @note Test error throwing when normalized s is out of bounds. + */ TEST(LineSegment, getPoint_outOfBounds_normalized) { const auto line = @@ -90,6 +96,9 @@ TEST(LineSegment, getPoint_outOfBounds_normalized) EXPECT_THROW(line.getPoint(-0.1, false), common::SimulationError); } +/** + * @note Test calculation correctness when s is out of bounds. + */ TEST(LineSegment, getPoint_inside_denormalized) { const auto line = @@ -101,6 +110,9 @@ TEST(LineSegment, getPoint_inside_denormalized) EXPECT_POINT_EQ(line.getPoint(6.0, true), makePoint(3.0, 2.0, -1.0)); } +/** + * @note Test calculation correctness when normalized s is out of bounds. + */ TEST(LineSegment, getPoint_inside_normalized) { const auto line = @@ -112,6 +124,9 @@ TEST(LineSegment, getPoint_inside_normalized) EXPECT_POINT_EQ(line.getPoint(1.0, false), makePoint(3.0, 2.0, -1.0)); } +/** + * @note Test calculation correctness with denormalized s. + */ TEST(LineSegment, getPose_denormalized) { const auto line = @@ -136,6 +151,9 @@ TEST(LineSegment, getPose_denormalized) 3.0, 2.0, 4.0, math::geometry::convertEulerAngleToQuaternion(makeVector(0.0, 0.0, M_PI_4)))); } +/** + * @note Test calculation correctness with normalized s. + */ TEST(LineSegment, getPose_normalized) { const auto line = @@ -160,6 +178,9 @@ TEST(LineSegment, getPose_normalized) 3.0, 2.0, 4.0, math::geometry::convertEulerAngleToQuaternion(makeVector(0.0, 0.0, M_PI_4)))); } +/** + * @note Test pitch calculation correctness with fill_pitch = true. + */ TEST(LineSegment, getPose_pitch) { const auto line = math::geometry::LineSegment( @@ -206,6 +227,9 @@ TEST(LineSegment, isIntersect2DIdentical) EXPECT_TRUE(line.isIntersect2D(line)); } +/** + * @note Test function behavior with a point on the line. + */ TEST(LineSegment, isIntersect2D_pointInside) { const auto line = @@ -215,6 +239,9 @@ TEST(LineSegment, isIntersect2D_pointInside) EXPECT_TRUE(line.isIntersect2D(makePoint(0.0, -1.0, 0.0))); } +/** + * @note Test function behavior with a point outside of the line. + */ TEST(LineSegment, isIntersect2D_pointOutside) { const auto line = @@ -227,6 +254,9 @@ TEST(LineSegment, isIntersect2D_pointOutside) EXPECT_FALSE(line.isIntersect2D(makePoint(4.0, 0.0, 0.0))); } +/** + * @note Test function behavior with a point that is collinear and external to the line. + */ TEST(LineSegment, isIntersect2D_pointCollinear) { const auto line = @@ -239,6 +269,9 @@ TEST(LineSegment, isIntersect2D_pointCollinear) EXPECT_FALSE(line.isIntersect2D(makePoint(4.0, 3.0, 0.0))); } +/** + * @note Test function behavior with a point on an end of the line. + */ TEST(LineSegment, isIntersect2D_pointOnEnd) { const auto line = @@ -251,6 +284,9 @@ TEST(LineSegment, isIntersect2D_pointOnEnd) EXPECT_TRUE(line.isIntersect2D(makePoint(3.0, 2.0, -5.0))); } +/** + * @note Test result correctness with a line intersecting with a vertical line. + */ TEST(LineSegment, getIntersection2DSValue_line_vertical) { const auto line = @@ -269,6 +305,9 @@ TEST(LineSegment, getIntersection2DSValue_line_vertical) } } +/** + * @note Test result correctness with a line intersecting with a horizontal line. + */ TEST(LineSegment, getIntersection2DSValue_line_horizontal) { const auto line = @@ -287,6 +326,9 @@ TEST(LineSegment, getIntersection2DSValue_line_horizontal) } } +/** + * @note Test result correctness with lines intersecting at the start and end of a line. + */ TEST(LineSegment, getIntersection2DSValue_line_bounds) { const auto line = @@ -305,6 +347,9 @@ TEST(LineSegment, getIntersection2DSValue_line_bounds) } } +/** + * @note Test result correctness with a line outside of the line. + */ TEST(LineSegment, getIntersection2DSValue_line_outside) { const auto line = @@ -323,6 +368,9 @@ TEST(LineSegment, getIntersection2DSValue_line_outside) .has_value()); } +/** + * @note Test result correctness when lines are collinear. + */ TEST(LineSegment, getIntersection2DSValue_line_collinear) { const auto line = @@ -337,6 +385,9 @@ TEST(LineSegment, getIntersection2DSValue_line_collinear) .has_value()); } +/** + * @note Test result correctness with a point inside a vertical line. + */ TEST(LineSegment, getIntersection2DSValue_point_vertical) { const auto line = @@ -360,6 +411,9 @@ TEST(LineSegment, getIntersection2DSValue_point_vertical) } } +/** + * @note Test result correctness with a point inside a horizontal line. + */ TEST(LineSegment, getIntersection2DSValue_point_horizontal) { const auto line = @@ -383,6 +437,9 @@ TEST(LineSegment, getIntersection2DSValue_point_horizontal) } } +/** + * @note Test result correctness with points at the start and end of a line. + */ TEST(LineSegment, getIntersection2DSValue_point_bounds) { const auto line = @@ -419,6 +476,9 @@ TEST(LineSegment, getIntersection2DSValue_point_bounds) } } +/** + * @note Test result correctness with a point outside of the line. + */ TEST(LineSegment, getIntersection2DSValue_point_outside) { const auto line = @@ -447,6 +507,9 @@ TEST(LineSegment, getIntersection2DDisjoint) EXPECT_FALSE(line0.getIntersection2D(line1)); } +/** + * @note Test function behavior with two intersecting lines. + */ TEST(LineSegment, getIntersection2DIntersect) { const auto line0 = math::geometry::LineSegment(makePoint(0.0, 0.0), makePoint(1.0, 1.0)); @@ -461,6 +524,9 @@ TEST(LineSegment, getIntersection2DIntersect) EXPECT_POINT_EQ(p1.value(), makePoint(0.5, 0.5)); } +/** + * @note Test function behavior with two identical lines. + */ TEST(LineSegment, getIntersection2DIdentical) { const auto line = math::geometry::LineSegment(makePoint(0.0, 0.0), makePoint(1.0, 1.0)); diff --git a/common/math/geometry/test/src/quaternion/test_quaternion.cpp b/common/math/geometry/test/src/quaternion/test_quaternion.cpp index d2b7aa857c8..0b31df60805 100644 --- a/common/math/geometry/test/src/quaternion/test_quaternion.cpp +++ b/common/math/geometry/test/src/quaternion/test_quaternion.cpp @@ -23,6 +23,9 @@ constexpr double EPS = 1e-6; +/** + * @note Test result correctness with a basic example. + */ TEST(Quaternion, operator_addition) { using math::geometry::operator+; @@ -33,6 +36,9 @@ TEST(Quaternion, operator_addition) EXPECT_QUATERNION_EQ(ans, math::geometry::makeQuaternion(0, 2, 0, 2)) } +/** + * @note Test result correctness with a basic example. + */ TEST(Quaternion, operator_subtraction) { using math::geometry::operator-; @@ -43,6 +49,9 @@ TEST(Quaternion, operator_subtraction) EXPECT_QUATERNION_EQ(ans, math::geometry::makeQuaternion(0, 0, 0, 0)) } +/** + * @note Test result correctness with a basic example. + */ TEST(Quaternion, operator_multiplication) { using math::geometry::operator*; @@ -53,6 +62,9 @@ TEST(Quaternion, operator_multiplication) EXPECT_QUATERNION_EQ(ans, math::geometry::makeQuaternion(0, 2, 0, 0)) } +/** + * @note Test result correctness with a basic example. + */ TEST(Quaternion, operator_additionAssignment) { using math::geometry::operator+=; diff --git a/common/math/geometry/test/src/spline/test_hermite_curve.cpp b/common/math/geometry/test/src/spline/test_hermite_curve.cpp index 0ea5f153526..96eb39fd2ec 100644 --- a/common/math/geometry/test/src/spline/test_hermite_curve.cpp +++ b/common/math/geometry/test/src/spline/test_hermite_curve.cpp @@ -320,6 +320,9 @@ TEST(HermiteCurveTest, getSValue) EXPECT_NEAR(s2.value(), 1.0, EPS); } +/** + * @note Test function correctness with parameter denormalize_s = true. + */ TEST(HermiteCurveTest, getSValueDenormalized) { const auto curve = makeLine2(); @@ -503,6 +506,9 @@ TEST(HermiteCurveTest, getTangentVector4) EXPECT_DOUBLE_EQ(curve.getTangentVector(0.5, false).y / norm, 1.0 / std::sqrt(2.0)); } +/** + * @note Test function correctness with parameter denormalize_s = true with different curves. + */ TEST(HermiteCurveTest, getTangentVectorDenormalized1) { //p(0,0) v(1,0)-> p(1,1) v(0,1) const auto curve = makeCurve1(); @@ -513,6 +519,9 @@ TEST(HermiteCurveTest, getTangentVectorDenormalized1) EXPECT_NEAR(curve.getTangentVector(0.75, true).y / norm, 1.0 / std::sqrt(2.0), eps); } +/** + * @note Test function correctness with parameter denormalize_s = true with different curves. + */ TEST(HermiteCurveTest, getTangentVectorDenormalized2) { //p(0,0) v(1,0)-> p(1,-1) v(0,-1) const auto curve = makeCurve2(); @@ -523,6 +532,9 @@ TEST(HermiteCurveTest, getTangentVectorDenormalized2) EXPECT_NEAR(curve.getTangentVector(0.75, true).y / norm, -1.0 / std::sqrt(2.0), eps); } +/** + * @note Test function correctness with parameter denormalize_s = true with different curves. + */ TEST(HermiteCurveTest, getTangentVectorDenormalized3) { //p(1,1) v(0,-1)-> p(0,0) v(-1,0) const auto curve = makeCurve3(); @@ -533,6 +545,9 @@ TEST(HermiteCurveTest, getTangentVectorDenormalized3) EXPECT_NEAR(curve.getTangentVector(0.75, true).y / norm, -1.0 / std::sqrt(2.0), eps); } +/** + * @note Test function correctness with parameter denormalize_s = true with different curves. + */ TEST(HermiteCurveTest, getTangentVectorDenormalized4) { //p(1,-1) v(0,1)-> p(0,0) v(-1,0) const auto curve = makeCurve4(); @@ -579,6 +594,9 @@ TEST(HermiteCurveTest, getNormalVector4) EXPECT_DOUBLE_EQ(curve.getNormalVector(0.5, false).y / norm, -1.0 / std::sqrt(2.0)); } +/** + * @note Test function correctness with parameter denormalize_s = true with different curves. + */ TEST(HermiteCurveTest, getNormalVectorDenormalized1) { //p(0,0) v(1,0)-> p(1,1) v(0,1) const auto curve = makeCurve1(); @@ -589,6 +607,9 @@ TEST(HermiteCurveTest, getNormalVectorDenormalized1) EXPECT_NEAR(curve.getNormalVector(0.75, true).y / norm, 1.0 / std::sqrt(2.0), eps); } +/** + * @note Test function correctness with parameter denormalize_s = true with different curves. + */ TEST(HermiteCurveTest, getNormalVectorDenormalized2) { //p(0,0) v(1,0)-> p(1,-1) v(0,-1) const auto curve = makeCurve2(); @@ -599,6 +620,9 @@ TEST(HermiteCurveTest, getNormalVectorDenormalized2) EXPECT_NEAR(curve.getNormalVector(0.75, true).y / norm, 1.0 / std::sqrt(2.0), eps); } +/** + * @note Test function correctness with parameter denormalize_s = true with different curves. + */ TEST(HermiteCurveTest, getNormalVectorDenormalized3) { //p(1,1) v(0,-1)-> p(0,0) v(-1,0) const auto curve = makeCurve3(); @@ -609,6 +633,9 @@ TEST(HermiteCurveTest, getNormalVectorDenormalized3) EXPECT_NEAR(curve.getNormalVector(0.75, true).y / norm, -1.0 / std::sqrt(2.0), eps); } +/** + * @note Test function correctness with parameter denormalize_s = true with different curves. + */ TEST(HermiteCurveTest, getNormalVectorDenormalized4) { //p(1,-1) v(0,1)-> p(0,0) v(-1,0) const auto curve = makeCurve4(); diff --git a/common/math/geometry/test/src/test_bounding_box.cpp b/common/math/geometry/test/src/test_bounding_box.cpp index 36abed690c3..7ee06e9cfa3 100644 --- a/common/math/geometry/test/src/test_bounding_box.cpp +++ b/common/math/geometry/test/src/test_bounding_box.cpp @@ -46,6 +46,9 @@ TEST(BoundingBox, getPointsFromBboxCustom) EXPECT_POINT_EQ(points[3], makePoint(6.5, -2.0, 1.0)); } +/** + * @note Test obtaining polygon from bounding box with no transformation applied. + */ TEST(BoundingBox, toPolygon2D_zeroPose) { geometry_msgs::msg::Pose pose; @@ -61,6 +64,9 @@ TEST(BoundingBox, toPolygon2D_zeroPose) EXPECT_BOOST_POINT_2D_AND_POINT_EQ(poly.outer()[4], makePoint(1.0, 1.0)); } +/** + * @note Test obtaining polygon from bounding box with only translation applied. + */ TEST(BoundingBox, toPolygon2D_onlyTranslation) { geometry_msgs::msg::Pose pose = makePose(1.0, 2.0); @@ -76,6 +82,9 @@ TEST(BoundingBox, toPolygon2D_onlyTranslation) EXPECT_BOOST_POINT_2D_AND_POINT_EQ(poly.outer()[4], makePoint(2.0, 3.0)); } +/** + * @note Test obtaining polygon from bounding box with full transformation applied (translation + rotation). + */ TEST(BoundingBox, toPolygon2D_fullPose) { geometry_msgs::msg::Pose pose = makePose(1.0, 2.0); diff --git a/common/math/geometry/test/src/vector3/test_vector3.cpp b/common/math/geometry/test/src/vector3/test_vector3.cpp index 45f24c3b726..c75f7177d3e 100644 --- a/common/math/geometry/test/src/vector3/test_vector3.cpp +++ b/common/math/geometry/test/src/vector3/test_vector3.cpp @@ -54,6 +54,9 @@ TEST(Vector3, hypot_customVector) EXPECT_DOUBLE_EQ(math::geometry::hypot(vec0, vec1), 6.0); } +/** + * @note Test function correctness with parameter that is ros message vector. + */ TEST(Vector3, norm_msgVector) { geometry_msgs::msg::Vector3 vec0 = makeVector(1.0, 2.0, 3.0); @@ -190,6 +193,9 @@ TEST(Vector3, additionAssignment_customVector) EXPECT_VECTOR3_EQ(vec0, makeVector(0.0, 0.0, 2.0)); } +/** + * @note Test function correctness when one of the vectors has length of 0. + */ TEST(Vector3, normalize_zeroLength) { geometry_msgs::msg::Vector3 vec; From acf3488fcb15d65e3b19c939577d986807c9709b Mon Sep 17 00:00:00 2001 From: robomic Date: Tue, 6 Aug 2024 14:13:19 +0200 Subject: [PATCH 096/304] refactor toPolygon2D tests --- .../geometry/test/src/test_bounding_box.cpp | 72 ++++++++++--------- 1 file changed, 37 insertions(+), 35 deletions(-) diff --git a/common/math/geometry/test/src/test_bounding_box.cpp b/common/math/geometry/test/src/test_bounding_box.cpp index 7ee06e9cfa3..b3449f994e4 100644 --- a/common/math/geometry/test/src/test_bounding_box.cpp +++ b/common/math/geometry/test/src/test_bounding_box.cpp @@ -51,17 +51,17 @@ TEST(BoundingBox, getPointsFromBboxCustom) */ TEST(BoundingBox, toPolygon2D_zeroPose) { - geometry_msgs::msg::Pose pose; - traffic_simulator_msgs::msg::BoundingBox bounding_box = makeBbox(2.0, 2.0, 2.0); - boost::geometry::model::polygon> poly = - math::geometry::toPolygon2D(pose, bounding_box); - EXPECT_EQ(poly.inners().size(), size_t(0)); - EXPECT_EQ(poly.outer().size(), size_t(5)); - EXPECT_BOOST_POINT_2D_AND_POINT_EQ(poly.outer()[0], makePoint(1.0, 1.0)); - EXPECT_BOOST_POINT_2D_AND_POINT_EQ(poly.outer()[1], makePoint(-1.0, 1.0)); - EXPECT_BOOST_POINT_2D_AND_POINT_EQ(poly.outer()[2], makePoint(-1.0, -1.0)); - EXPECT_BOOST_POINT_2D_AND_POINT_EQ(poly.outer()[3], makePoint(1.0, -1.0)); - EXPECT_BOOST_POINT_2D_AND_POINT_EQ(poly.outer()[4], makePoint(1.0, 1.0)); + const auto pose = geometry_msgs::msg::Pose(); + const auto bounding_box = makeBbox(2.0, 2.0, 2.0); + const auto polygon = math::geometry::toPolygon2D(pose, bounding_box); + + ASSERT_EQ(polygon.inners().size(), static_cast(0)); + ASSERT_EQ(polygon.outer().size(), static_cast(5)); + EXPECT_BOOST_POINT_2D_AND_POINT_EQ(polygon.outer()[0], makePoint(1.0, 1.0)); + EXPECT_BOOST_POINT_2D_AND_POINT_EQ(polygon.outer()[1], makePoint(-1.0, 1.0)); + EXPECT_BOOST_POINT_2D_AND_POINT_EQ(polygon.outer()[2], makePoint(-1.0, -1.0)); + EXPECT_BOOST_POINT_2D_AND_POINT_EQ(polygon.outer()[3], makePoint(1.0, -1.0)); + EXPECT_BOOST_POINT_2D_AND_POINT_EQ(polygon.outer()[4], makePoint(1.0, 1.0)); } /** @@ -69,17 +69,17 @@ TEST(BoundingBox, toPolygon2D_zeroPose) */ TEST(BoundingBox, toPolygon2D_onlyTranslation) { - geometry_msgs::msg::Pose pose = makePose(1.0, 2.0); - traffic_simulator_msgs::msg::BoundingBox bounding_box = makeBbox(2.0, 2.0, 2.0); - boost::geometry::model::polygon> poly = - math::geometry::toPolygon2D(pose, bounding_box); - EXPECT_EQ(poly.inners().size(), size_t(0)); - EXPECT_EQ(poly.outer().size(), size_t(5)); - EXPECT_BOOST_POINT_2D_AND_POINT_EQ(poly.outer()[0], makePoint(2.0, 3.0)); - EXPECT_BOOST_POINT_2D_AND_POINT_EQ(poly.outer()[1], makePoint(0.0, 3.0)); - EXPECT_BOOST_POINT_2D_AND_POINT_EQ(poly.outer()[2], makePoint(0.0, 1.0)); - EXPECT_BOOST_POINT_2D_AND_POINT_EQ(poly.outer()[3], makePoint(2.0, 1.0)); - EXPECT_BOOST_POINT_2D_AND_POINT_EQ(poly.outer()[4], makePoint(2.0, 3.0)); + const auto pose = makePose(1.0, 2.0); + const auto bounding_box = makeBbox(2.0, 2.0, 2.0); + const auto polygon = math::geometry::toPolygon2D(pose, bounding_box); + + ASSERT_EQ(polygon.inners().size(), static_cast(0)); + ASSERT_EQ(polygon.outer().size(), static_cast(5)); + EXPECT_BOOST_POINT_2D_AND_POINT_EQ(polygon.outer()[0], makePoint(2.0, 3.0)); + EXPECT_BOOST_POINT_2D_AND_POINT_EQ(polygon.outer()[1], makePoint(0.0, 3.0)); + EXPECT_BOOST_POINT_2D_AND_POINT_EQ(polygon.outer()[2], makePoint(0.0, 1.0)); + EXPECT_BOOST_POINT_2D_AND_POINT_EQ(polygon.outer()[3], makePoint(2.0, 1.0)); + EXPECT_BOOST_POINT_2D_AND_POINT_EQ(polygon.outer()[4], makePoint(2.0, 3.0)); } /** @@ -87,21 +87,23 @@ TEST(BoundingBox, toPolygon2D_onlyTranslation) */ TEST(BoundingBox, toPolygon2D_fullPose) { - geometry_msgs::msg::Pose pose = makePose(1.0, 2.0); - pose.orientation = math::geometry::convertEulerAngleToQuaternion( - geometry_msgs::build().x(0.0).y(0.0).z(30.0 * M_PI / 180.0)); - traffic_simulator_msgs::msg::BoundingBox bounding_box = makeBbox(2.0, 2.0, 2.0); - boost::geometry::model::polygon> poly = - math::geometry::toPolygon2D(pose, bounding_box); - EXPECT_EQ(poly.inners().size(), size_t(0)); - EXPECT_EQ(poly.outer().size(), size_t(5)); + const auto pose = makePose( + 1.0, 2.0, 0.0, + math::geometry::convertEulerAngleToQuaternion( + geometry_msgs::build().x(0.0).y(0.0).z(30.0 * M_PI / 180.0))); + + const auto bounding_box = makeBbox(2.0, 2.0, 2.0); + const auto polygon = math::geometry::toPolygon2D(pose, bounding_box); + ASSERT_EQ(polygon.inners().size(), static_cast(0)); + ASSERT_EQ(polygon.outer().size(), static_cast(5)); + const double x = std::sqrt(2.0) * std::cos((30.0 + 45.0) * M_PI / 180.0); const double y = std::sqrt(2.0) * std::sin((30.0 + 45.0) * M_PI / 180.0); - EXPECT_BOOST_POINT_2D_AND_POINT_EQ(poly.outer()[0], makePoint(x + 1.0, y + 2.0)); - EXPECT_BOOST_POINT_2D_AND_POINT_EQ(poly.outer()[1], makePoint(-y + 1.0, x + 2.0)); - EXPECT_BOOST_POINT_2D_AND_POINT_EQ(poly.outer()[2], makePoint(-x + 1.0, -y + 2.0)); - EXPECT_BOOST_POINT_2D_AND_POINT_EQ(poly.outer()[3], makePoint(y + 1.0, -x + 2.0)); - EXPECT_BOOST_POINT_2D_AND_POINT_EQ(poly.outer()[4], makePoint(x + 1.0, y + 2.0)); + EXPECT_BOOST_POINT_2D_AND_POINT_EQ(polygon.outer()[0], makePoint(x + 1.0, y + 2.0)); + EXPECT_BOOST_POINT_2D_AND_POINT_EQ(polygon.outer()[1], makePoint(-y + 1.0, x + 2.0)); + EXPECT_BOOST_POINT_2D_AND_POINT_EQ(polygon.outer()[2], makePoint(-x + 1.0, -y + 2.0)); + EXPECT_BOOST_POINT_2D_AND_POINT_EQ(polygon.outer()[3], makePoint(y + 1.0, -x + 2.0)); + EXPECT_BOOST_POINT_2D_AND_POINT_EQ(polygon.outer()[4], makePoint(x + 1.0, y + 2.0)); } TEST(BoundingBox, getPolygonDistanceWithCollision) From 31ac62c7269467bd7d06c433820cf82228f1f61a Mon Sep 17 00:00:00 2001 From: robomic Date: Wed, 7 Aug 2024 12:11:35 +0200 Subject: [PATCH 097/304] refactor test_helper.cpp file --- .../test/src/helper/test_helper.cpp | 142 ++++++++++++------ 1 file changed, 92 insertions(+), 50 deletions(-) diff --git a/simulation/traffic_simulator/test/src/helper/test_helper.cpp b/simulation/traffic_simulator/test/src/helper/test_helper.cpp index 06c2f02e24a..b2b352f5174 100644 --- a/simulation/traffic_simulator/test/src/helper/test_helper.cpp +++ b/simulation/traffic_simulator/test/src/helper/test_helper.cpp @@ -14,78 +14,103 @@ #include +#include #include #include #include #include "../expect_eq_macros.hpp" -TEST(HELPER, RPY) +/** + * @note Test basic functionality. Test construction correctness of an action status. + */ +TEST(helper, constructActionStatus) { - const auto rpy = traffic_simulator::helper::constructRPY(1, 2, 1); - geometry_msgs::msg::Vector3 vec; - vec.x = 1.0; - vec.y = 2.0; - vec.z = 1.0; - EXPECT_VECTOR3_EQ(rpy, vec); -} + traffic_simulator_msgs::msg::ActionStatus actual_action_status; + actual_action_status.twist.linear.x = 2.0; + actual_action_status.twist.angular.z = 3.0; + actual_action_status.accel.linear.x = 5.0; + actual_action_status.accel.angular.z = 7.0; -TEST(HELPER, QUATERNION) -{ - const auto rpy = - traffic_simulator::helper::constructRPYfromQuaternion(geometry_msgs::msg::Quaternion()); - EXPECT_VECTOR3_EQ(rpy, geometry_msgs::msg::Vector3()); + const auto result_action_status = + traffic_simulator::helper::constructActionStatus(2.0, 3.0, 5.0, 7.0); + + EXPECT_ACTION_STATUS_EQ(result_action_status, actual_action_status); } -TEST(HELPER, POSE) +/** + * @note Test basic functionality. Test construction correctness of a lanelet pose. + */ +TEST(helper, constructLaneletPose) { - const auto pose = traffic_simulator::helper::constructPose(1, 1, 1, 0, 0, 0); - geometry_msgs::msg::Pose expect_pose; - expect_pose.position.x = 1; - expect_pose.position.y = 1; - expect_pose.position.z = 1; - EXPECT_POSE_EQ(pose, expect_pose); + const auto actual_lanelet_pose = + traffic_simulator_msgs::build() + .lanelet_id(11LL) + .s(13.0) + .offset(17.0) + .rpy(geometry_msgs::build().x(19.0).y(23.0).z(29.0)); + + const auto result_lanelet_pose = + traffic_simulator::helper::constructLaneletPose(11LL, 13.0, 17.0, 19.0, 23.0, 29.0); + + std::stringstream ss; + ss << result_lanelet_pose; + EXPECT_LANELET_POSE_EQ(result_lanelet_pose, actual_lanelet_pose); + EXPECT_STREQ(ss.str().c_str(), "lanelet id : 11\ns : 13"); } -TEST(HELPER, LANELET_POSE) +/** + * @note Test basic functionality. Test construction correctness of RPY vector. + */ +TEST(helper, constructRPY) { - const auto lanelet_pose = traffic_simulator::helper::constructLaneletPose(5, 10, 2, 0, 0, 0); - traffic_simulator::LaneletPose expected_pose; - expected_pose.lanelet_id = 5; - expected_pose.s = 10.0; - expected_pose.offset = 2.0; - expected_pose.rpy.x = 0; - expected_pose.rpy.y = 0; - expected_pose.rpy.z = 0; - EXPECT_LANELET_POSE_EQ(lanelet_pose, expected_pose); - std::stringstream ss; - ss << lanelet_pose; - EXPECT_STREQ(ss.str().c_str(), "lanelet id : 5\ns : 10"); + const auto vec = geometry_msgs::build().x(31.0).y(37.0).z(41.0); + const auto rpy = traffic_simulator::helper::constructRPY(31.0, 37.0, 41.0); + EXPECT_VECTOR3_EQ(rpy, vec); } -TEST(HELPER, ACTION_STATUS) +/** + * @note Test basic functionality. Test construction correctness of a quaternion. + */ +TEST(helper, constructRPYfromQuaternion) { - const auto action_status = traffic_simulator::helper::constructActionStatus(3, 4, 5, 1); - traffic_simulator_msgs::msg::ActionStatus expect_action_status; - expect_action_status.twist.linear.x = 3; - expect_action_status.twist.angular.z = 4; - expect_action_status.accel.linear.x = 5; - expect_action_status.accel.angular.z = 1; - EXPECT_ACTION_STATUS_EQ(action_status, expect_action_status); + { + const auto default_vec = geometry_msgs::msg::Vector3(); + const auto default_rpy = + traffic_simulator::helper::constructRPYfromQuaternion(geometry_msgs::msg::Quaternion()); + EXPECT_VECTOR3_EQ(default_rpy, default_vec); + } + { + const auto vec = + geometry_msgs::build().x(-M_PI / 3.0).y(-M_PI / 6.0).z(M_PI / 2); + const auto rpy = traffic_simulator::helper::constructRPYfromQuaternion( + geometry_msgs::build().x(-0.183).y(-0.5).z(0.5).w(0.683)); + EXPECT_VECTOR3_NEAR(rpy, vec, 1.0e-3); + } } -TEST(HELPER, DETECTION_SENSOR_CONFIGURATION) +/** + * @note Test basic functionality. Test construction correctness of a pose. + */ +TEST(helper, constructPose) { - const auto configuration = - traffic_simulator::helper::constructDetectionSensorConfiguration("ego", "test", 3); - simulation_api_schema::DetectionSensorConfiguration expect_configuration; - expect_configuration.set_architecture_type("test"); - expect_configuration.set_entity("ego"); - expect_configuration.set_update_duration(3.0); - EXPECT_DETECTION_SENSOR_CONFIGURATION_EQ(configuration, expect_configuration); + const auto actual_pose = + geometry_msgs::build() + .position(geometry_msgs::build().x(43.0).y(47.0).z(53.0)) + .orientation( + geometry_msgs::build().x(-0.183).y(-0.5).z(0.5).w(0.683)); + + const auto result_pose = + traffic_simulator::helper::constructPose(43.0, 47.0, 53.0, -M_PI / 3.0, -M_PI / 6.0, M_PI / 2); + + EXPECT_POSE_NEAR(result_pose, actual_pose, 1.0e-3); } -TEST(HELPER, LIDAR_SENSOR_CONFIGURATION) +/** + * @note Test basic functionality. Test construction correctness of + * a lidar sensor with both VLP16 and VLP32 configurations. + */ +TEST(helper, constructLidarConfiguration) { EXPECT_NO_THROW(traffic_simulator::helper::constructLidarConfiguration( traffic_simulator::helper::LidarType::VLP16, "ego", "test")); @@ -93,6 +118,23 @@ TEST(HELPER, LIDAR_SENSOR_CONFIGURATION) traffic_simulator::helper::LidarType::VLP32, "ego", "test")); } +/** + * @note Test basic functionality. Test construction correctness of + * a detection sensor with a given configuration. + */ +TEST(helper, constructDetectionSensorConfiguration) +{ + simulation_api_schema::DetectionSensorConfiguration actual_configuration; + actual_configuration.set_architecture_type("test"); + actual_configuration.set_entity("ego"); + actual_configuration.set_update_duration(3.0); + + const auto result_configuration = + traffic_simulator::helper::constructDetectionSensorConfiguration("ego", "test", 3); + + EXPECT_DETECTION_SENSOR_CONFIGURATION_EQ(result_configuration, actual_configuration); +} + int main(int argc, char ** argv) { testing::InitGoogleTest(&argc, argv); From 0540c02cca68427e88d6d4e5fc751b50d33921e1 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Wed, 7 Aug 2024 19:19:52 +0900 Subject: [PATCH 098/304] refactor: use boost::math::constants::half_pi instead of 0.5 * boost::math::constants::pi --- .../src/syntax/relative_clearance_condition.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp b/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp index e8ab07f7897..da665422b22 100644 --- a/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp @@ -93,7 +93,7 @@ auto RelativeClearanceCondition::evaluate() -> Object target_entities.begin(), target_entities.end(), [&, is_back = (std::abs(evaluateRelativeHeading(triggering_entity)) > - 0.5 * boost::math::constants::pi())](const auto & entity) { + boost::math::constants::half_pi())](const auto & entity) { auto is_in_lateral_range = [&]() { // The lanes to be checked to left and right of the triggering entity (positive to the y-axis). If omitted: all lanes are checked. if (relative_lane_range.empty()) { From 33d9de56e9af713dcbb4b07e32eb761f0af3c0a3 Mon Sep 17 00:00:00 2001 From: robomic Date: Wed, 7 Aug 2024 12:29:21 +0200 Subject: [PATCH 099/304] test_simulation_clock.cpp refacton --- .../test/src/simulation_clock/test_simulation_clock.cpp | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/simulation/traffic_simulator/test/src/simulation_clock/test_simulation_clock.cpp b/simulation/traffic_simulator/test/src/simulation_clock/test_simulation_clock.cpp index 96e57887d90..9a88e0ab995 100644 --- a/simulation/traffic_simulator/test/src/simulation_clock/test_simulation_clock.cpp +++ b/simulation/traffic_simulator/test/src/simulation_clock/test_simulation_clock.cpp @@ -14,6 +14,7 @@ #include +#include #include /** @@ -21,7 +22,7 @@ * Test initialization logic by calling update without initialized clock * - the goal is to verify that mandatory initialization works. */ -TEST(SimulationClock, Initialize) +TEST(SimulationClock, SimulationClock) { auto simulation_clock = traffic_simulator::SimulationClock(true, 1.0, 10.0); @@ -31,7 +32,7 @@ TEST(SimulationClock, Initialize) EXPECT_TRUE(simulation_clock.started()); simulation_clock.update(); - EXPECT_THROW(simulation_clock.start(), std::runtime_error); + EXPECT_THROW(simulation_clock.start(), common::SimulationError); } /** From 885afa4e1eafa2c49cb31676a4cf706a12734062 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Wed, 7 Aug 2024 19:35:29 +0900 Subject: [PATCH 100/304] refactor: use std::find instead of std::find_if --- .../src/hdmap_utils/hdmap_utils.cpp | 12 +++--------- 1 file changed, 3 insertions(+), 9 deletions(-) diff --git a/simulation/traffic_simulator/src/hdmap_utils/hdmap_utils.cpp b/simulation/traffic_simulator/src/hdmap_utils/hdmap_utils.cpp index 775dcf0af99..b44bd1f08de 100644 --- a/simulation/traffic_simulator/src/hdmap_utils/hdmap_utils.cpp +++ b/simulation/traffic_simulator/src/hdmap_utils/hdmap_utils.cpp @@ -229,20 +229,14 @@ auto HdMapUtils::countLaneChanges( const auto & current = route[i]; if (auto followings = getNextLaneletIds(previous); - std::find_if(followings.begin(), followings.end(), [¤t](const auto & lanelet) { - return lanelet == current; - }) == followings.end()) { + std::find(followings.begin(), followings.end(), current) == followings.end()) { traffic_simulator_msgs::msg::EntityType type; type.type = traffic_simulator_msgs::msg::EntityType::VEHICLE; if (auto lefts = getLeftLaneletIds(previous, type); - std::find_if(lefts.begin(), lefts.end(), [¤t](const auto & lanelet) { - return lanelet == current; - }) != lefts.end()) { + std::find(lefts.begin(), lefts.end(), current) != lefts.end()) { lane_changes.first++; } else if (auto rights = getRightLaneletIds(previous, type); - std::find_if(rights.begin(), rights.end(), [¤t](const auto & lanelet) { - return lanelet == current; - }) != rights.end()) { + std::find(rights.begin(), rights.end(), current) != rights.end()) { lane_changes.second++; } } From 4c6ee73641f13ae360585c67c7e9e08af0645642 Mon Sep 17 00:00:00 2001 From: robomic Date: Wed, 7 Aug 2024 12:55:09 +0200 Subject: [PATCH 101/304] remove ros nodes --- .../test/src/traffic_lights/test_traffic_light_manager.cpp | 4 ---- 1 file changed, 4 deletions(-) diff --git a/simulation/traffic_simulator/test/src/traffic_lights/test_traffic_light_manager.cpp b/simulation/traffic_simulator/test/src/traffic_lights/test_traffic_light_manager.cpp index fa6b3aad1ad..b584bfc48b9 100644 --- a/simulation/traffic_simulator/test/src/traffic_lights/test_traffic_light_manager.cpp +++ b/simulation/traffic_simulator/test/src/traffic_lights/test_traffic_light_manager.cpp @@ -20,7 +20,6 @@ TEST(TrafficLightManager, getIds) { - const auto node = std::make_shared("getIds"); std::string path = ament_index_cpp::get_package_share_directory("traffic_simulator") + "/map/lanelet2_map.osm"; geographic_msgs::msg::GeoPoint origin; @@ -37,7 +36,6 @@ TEST(TrafficLightManager, getIds) TEST(TrafficLightManager, setColor) { - const auto node = std::make_shared("setColor"); std::string path = ament_index_cpp::get_package_share_directory("traffic_simulator") + "/map/lanelet2_map.osm"; geographic_msgs::msg::GeoPoint origin; @@ -65,7 +63,6 @@ TEST(TrafficLightManager, setColor) TEST(TrafficLightManager, setArrow) { - const auto node = std::make_shared("setArrow"); std::string path = ament_index_cpp::get_package_share_directory("traffic_simulator") + "/map/lanelet2_map.osm"; geographic_msgs::msg::GeoPoint origin; @@ -93,6 +90,5 @@ TEST(TrafficLightManager, setArrow) int main(int argc, char ** argv) { testing::InitGoogleTest(&argc, argv); - rclcpp::init(argc, argv); return RUN_ALL_TESTS(); } From b6cf0e00d0c3ed22a1b31c6347406a6908d90729 Mon Sep 17 00:00:00 2001 From: robomic Date: Wed, 7 Aug 2024 15:39:02 +0200 Subject: [PATCH 102/304] test_traffic_lights_manager.cpp refactor --- .../test_traffic_light_manager.cpp | 76 ++++++++++--------- 1 file changed, 40 insertions(+), 36 deletions(-) diff --git a/simulation/traffic_simulator/test/src/traffic_lights/test_traffic_light_manager.cpp b/simulation/traffic_simulator/test/src/traffic_lights/test_traffic_light_manager.cpp index b584bfc48b9..f5b58616f44 100644 --- a/simulation/traffic_simulator/test/src/traffic_lights/test_traffic_light_manager.cpp +++ b/simulation/traffic_simulator/test/src/traffic_lights/test_traffic_light_manager.cpp @@ -18,15 +18,33 @@ #include #include -TEST(TrafficLightManager, getIds) +class TrafficLightManagerTest : public testing::Test +{ +protected: + TrafficLightManagerTest() + : manager(std::make_shared( + ament_index_cpp::get_package_share_directory("traffic_simulator") + "/map/lanelet2_map.osm", + geographic_msgs::build() + .latitude(35.61836750154) + .longitude(139.78066608243) + .altitude(0.0))) + { + } + traffic_simulator::TrafficLightManager manager; +}; + +int main(int argc, char ** argv) +{ + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} + +/** + * @note Test basic functionality. Test obtaining traffic light functionality + * with a non-existant laneletId. A traffic light should be created. + */ +TEST_F(TrafficLightManagerTest, getTrafficLight) { - std::string path = - ament_index_cpp::get_package_share_directory("traffic_simulator") + "/map/lanelet2_map.osm"; - geographic_msgs::msg::GeoPoint origin; - origin.latitude = 35.61836750154; - origin.longitude = 139.78066608243; - const auto hdmap_utils_ptr = std::make_shared(path, origin); - traffic_simulator::TrafficLightManager manager(hdmap_utils_ptr); manager.getTrafficLight(34836); EXPECT_FALSE(manager.getTrafficLights().find(34836) == std::end(manager.getTrafficLights())); manager.getTrafficLight(34802); @@ -34,19 +52,15 @@ TEST(TrafficLightManager, getIds) EXPECT_EQ(manager.getTrafficLights().size(), static_cast(2)); } -TEST(TrafficLightManager, setColor) +/** + * @note Test basic functionality. Test adding a bulb to a specific traffic light with only a color specified. + */ +TEST_F(TrafficLightManagerTest, getTrafficLights_setColor) { - std::string path = - ament_index_cpp::get_package_share_directory("traffic_simulator") + "/map/lanelet2_map.osm"; - geographic_msgs::msg::GeoPoint origin; - origin.latitude = 35.61836750154; - origin.longitude = 139.78066608243; - const auto hdmap_utils_ptr = std::make_shared(path, origin); - traffic_simulator::TrafficLightManager manager(hdmap_utils_ptr); + using Color = traffic_simulator::TrafficLight::Color; + using Status = traffic_simulator::TrafficLight::Status; + using Shape = traffic_simulator::TrafficLight::Shape; for (const auto & [id, traffic_light] : manager.getTrafficLights()) { - using Color = traffic_simulator::TrafficLight::Color; - using Status = traffic_simulator::TrafficLight::Status; - using Shape = traffic_simulator::TrafficLight::Shape; manager.getTrafficLight(id).clear(); manager.getTrafficLight(id).emplace(Color::green); EXPECT_TRUE( @@ -61,19 +75,15 @@ TEST(TrafficLightManager, setColor) } } -TEST(TrafficLightManager, setArrow) +/** + * @note Test basic functionality. Test adding a bulb to a specific traffic light with all parameters specified. + */ +TEST_F(TrafficLightManagerTest, getTrafficLights_setArrow) { - std::string path = - ament_index_cpp::get_package_share_directory("traffic_simulator") + "/map/lanelet2_map.osm"; - geographic_msgs::msg::GeoPoint origin; - origin.latitude = 35.61836750154; - origin.longitude = 139.78066608243; - const auto hdmap_utils_ptr = std::make_shared(path, origin); - traffic_simulator::TrafficLightManager manager(hdmap_utils_ptr); + using Color = traffic_simulator::TrafficLight::Color; + using Status = traffic_simulator::TrafficLight::Status; + using Shape = traffic_simulator::TrafficLight::Shape; for (const auto & [id, traffic_light] : manager.getTrafficLights()) { - using Color = traffic_simulator::TrafficLight::Color; - using Status = traffic_simulator::TrafficLight::Status; - using Shape = traffic_simulator::TrafficLight::Shape; manager.getTrafficLight(id).clear(); manager.getTrafficLight(id).emplace(Color::green, Status::solid_on, Shape::left); EXPECT_TRUE(manager.getTrafficLight(id).contains(Color::green, Status::solid_on, Shape::left)); @@ -86,9 +96,3 @@ TEST(TrafficLightManager, setArrow) EXPECT_TRUE(manager.getTrafficLight(id).contains(Color::green, Status::solid_on, Shape::up)); } } - -int main(int argc, char ** argv) -{ - testing::InitGoogleTest(&argc, argv); - return RUN_ALL_TESTS(); -} From b342574edb7aff8f224133b9f1f70f9a3ad00f4b Mon Sep 17 00:00:00 2001 From: robomic Date: Wed, 7 Aug 2024 16:42:37 +0200 Subject: [PATCH 103/304] test_traffic_light.cpp refactor, sort --- .../src/traffic_lights/test_traffic_light.cpp | 528 ++++++++++-------- 1 file changed, 280 insertions(+), 248 deletions(-) diff --git a/simulation/traffic_simulator/test/src/traffic_lights/test_traffic_light.cpp b/simulation/traffic_simulator/test/src/traffic_lights/test_traffic_light.cpp index b77ec381cab..bf228bfcf71 100644 --- a/simulation/traffic_simulator/test/src/traffic_lights/test_traffic_light.cpp +++ b/simulation/traffic_simulator/test/src/traffic_lights/test_traffic_light.cpp @@ -26,7 +26,10 @@ int main(int argc, char ** argv) return RUN_ALL_TESTS(); } -TEST(TrafficLight, Color) +/** + * @note Test object creation correcness. + */ +TEST(Color, Color) { using Color = traffic_simulator::TrafficLight::Color; @@ -76,7 +79,71 @@ TEST(TrafficLight, Color) } } -TEST(TrafficLight, Status) +/** + * @note Test basic functionality. Test whether the function + * creates Color object appropriate to the argument. + */ +TEST(Color, make) +{ + using Color = traffic_simulator::TrafficLight::Color; + { + const auto color = Color::make("green"); + + EXPECT_TRUE(color == Color::green); + EXPECT_TRUE(color.is(Color::green)); + EXPECT_TRUE(boost::lexical_cast("green") == Color::green); + EXPECT_TRUE(boost::lexical_cast(color) == "green"); + } + + { + const auto color = Color::make("yellow"); + + EXPECT_TRUE(color == Color::yellow); + EXPECT_TRUE(color.is(Color::yellow)); + EXPECT_TRUE(boost::lexical_cast("yellow") == Color::yellow); + EXPECT_TRUE(boost::lexical_cast(color) == "yellow"); + } + + { + const auto color = Color::make("red"); + + EXPECT_TRUE(color == Color::red); + EXPECT_TRUE(color.is(Color::red)); + EXPECT_TRUE(boost::lexical_cast("red") == Color::red); + EXPECT_TRUE(boost::lexical_cast(color) == "red"); + } + + { + const auto color = Color::make("white"); + + EXPECT_TRUE(color == Color::white); + EXPECT_TRUE(color.is(Color::white)); + EXPECT_TRUE(boost::lexical_cast("white") == Color::white); + EXPECT_TRUE(boost::lexical_cast(color) == "white"); + } + + { + const auto color = Color::make("amber"); + + EXPECT_TRUE(color == Color::yellow); + EXPECT_TRUE(color.is(Color::yellow)); + EXPECT_TRUE(boost::lexical_cast("amber") == Color::yellow); + EXPECT_TRUE(boost::lexical_cast(color) == "yellow"); + } +} + +/** + * @note Test basic functionality. Test function behavior when called with invalid name. + */ +TEST(Color, make_wrong) +{ + EXPECT_THROW(traffic_simulator::TrafficLight::Color::make("wrong_color"), common::SyntaxError); +} + +/** + * @note Test object creation correcness. + */ +TEST(Status, Status) { using Status = traffic_simulator::TrafficLight::Status; @@ -117,7 +184,62 @@ TEST(TrafficLight, Status) } } -TEST(TrafficLight, Shape) +/** + * @note Test basic functionality. Test whether the function creates Status object appropriate to the argument. + */ +TEST(Status, make) +{ + using Status = traffic_simulator::TrafficLight::Status; + + { + const auto status = Status::make("solidOn"); + + EXPECT_TRUE(status == Status::solid_on); + EXPECT_TRUE(status.is(Status::solid_on)); + EXPECT_TRUE(boost::lexical_cast("solidOn") == Status::solid_on); + EXPECT_TRUE(boost::lexical_cast(status) == "solidOn"); + } + + { + const auto status = Status::make("solidOff"); + + EXPECT_TRUE(status == Status::solid_off); + EXPECT_TRUE(status.is(Status::solid_off)); + EXPECT_TRUE(boost::lexical_cast("solidOff") == Status::solid_off); + EXPECT_TRUE(boost::lexical_cast(status) == "solidOff"); + } + + { + const auto status = Status::make("flashing"); + + EXPECT_TRUE(status == Status::flashing); + EXPECT_TRUE(status.is(Status::flashing)); + EXPECT_TRUE(boost::lexical_cast("flashing") == Status::flashing); + EXPECT_TRUE(boost::lexical_cast(status) == "flashing"); + } + + { + const auto status = Status::make("unknown"); + + EXPECT_TRUE(status == Status::unknown); + EXPECT_TRUE(status.is(Status::unknown)); + EXPECT_TRUE(boost::lexical_cast("unknown") == Status::unknown); + EXPECT_TRUE(boost::lexical_cast(status) == "unknown"); + } +} + +/** + * @note Test basic functionality. Test function behavior when called with invalid name. + */ +TEST(Status, make_wrong) +{ + EXPECT_THROW(traffic_simulator::TrafficLight::Status::make("wrong_status"), common::SyntaxError); +} + +/** + * @note Test object creation correcness. + */ +TEST(Shape, Shape) { using Shape = traffic_simulator::TrafficLight::Shape; @@ -232,204 +354,10 @@ TEST(TrafficLight, Shape) } } -TEST(TrafficLight, Bulb) -{ - using TrafficLight = traffic_simulator::TrafficLight; - using Color = TrafficLight::Color; - using Status = TrafficLight::Status; - using Shape = TrafficLight::Shape; - using Bulb = TrafficLight::Bulb; - - // clang-format off - static_assert(Bulb(Color::green, Status::solid_on, Shape::circle ).hash() == 0b0000'0000'0000'0000'0000'0000'0000'0000); - static_assert(Bulb(Color::yellow, Status::solid_on, Shape::circle ).hash() == 0b0000'0001'0000'0000'0000'0000'0000'0000); - static_assert(Bulb(Color::red, Status::solid_on, Shape::circle ).hash() == 0b0000'0010'0000'0000'0000'0000'0000'0000); - static_assert(Bulb(Color::white, Status::solid_on, Shape::circle ).hash() == 0b0000'0011'0000'0000'0000'0000'0000'0000); - - static_assert(Bulb(Color::green, Status::solid_on, Shape::circle ).hash() == 0b0000'0000'0000'0000'0000'0000'0000'0000); - static_assert(Bulb(Color::green, Status::solid_off, Shape::circle ).hash() == 0b0000'0000'0000'0001'0000'0000'0000'0000); - static_assert(Bulb(Color::green, Status::flashing, Shape::circle ).hash() == 0b0000'0000'0000'0010'0000'0000'0000'0000); - static_assert(Bulb(Color::green, Status::unknown, Shape::circle ).hash() == 0b0000'0000'0000'0011'0000'0000'0000'0000); - - static_assert(Bulb(Color::green, Status::solid_on, Shape::circle ).hash() == 0b0000'0000'0000'0000'0000'0000'0000'0000); - static_assert(Bulb(Color::green, Status::solid_on, Shape::cross ).hash() == 0b0000'0000'0000'0000'0000'0000'0000'0001); - static_assert(Bulb(Color::green, Status::solid_on, Shape::left ).hash() == 0b0000'0000'0000'0000'0000'1000'0000'0010); - static_assert(Bulb(Color::green, Status::solid_on, Shape::down ).hash() == 0b0000'0000'0000'0000'0000'0100'0000'0010); - static_assert(Bulb(Color::green, Status::solid_on, Shape::up ).hash() == 0b0000'0000'0000'0000'0000'0010'0000'0010); - static_assert(Bulb(Color::green, Status::solid_on, Shape::right ).hash() == 0b0000'0000'0000'0000'0000'0001'0000'0010); - static_assert(Bulb(Color::green, Status::solid_on, Shape::lower_left ).hash() == 0b0000'0000'0000'0000'0000'1100'0000'0010); - static_assert(Bulb(Color::green, Status::solid_on, Shape::upper_left ).hash() == 0b0000'0000'0000'0000'0000'1010'0000'0010); - static_assert(Bulb(Color::green, Status::solid_on, Shape::lower_right).hash() == 0b0000'0000'0000'0000'0000'0101'0000'0010); - static_assert(Bulb(Color::green, Status::solid_on, Shape::upper_right).hash() == 0b0000'0000'0000'0000'0000'0011'0000'0010); - // clang-format on - - { - constexpr auto bulb = Bulb(Color::red, Status::flashing, Shape::circle); - - EXPECT_TRUE(bulb.is(Color::red)); - EXPECT_TRUE(bulb.is(Status::flashing)); - EXPECT_TRUE(bulb.is(Shape::circle)); - EXPECT_TRUE(bulb.is(Shape::Category::circle)); - } - - { - constexpr auto bulb = Bulb(Color::green, Status::solid_on, Shape::right); - - EXPECT_TRUE(bulb.is(Color::green)); - EXPECT_TRUE(bulb.is(Status::solid_on)); - EXPECT_TRUE(bulb.is(Shape::right)); - EXPECT_TRUE(bulb.is(Shape::Category::arrow)); - } - - { - const auto bulb = Bulb("red flashing circle"); - - EXPECT_TRUE(bulb.is(Color::red)); - EXPECT_TRUE(bulb.is(Status::flashing)); - EXPECT_TRUE(bulb.is(Shape::circle)); - EXPECT_TRUE(bulb.is(Shape::Category::circle)); - } - - { - const auto bulb = Bulb("red flashing"); - - EXPECT_TRUE(bulb.is(Color::red)); - EXPECT_TRUE(bulb.is(Status::flashing)); - EXPECT_TRUE(bulb.is(Shape::circle)); - EXPECT_TRUE(bulb.is(Shape::Category::circle)); - } - - { - const auto bulb = Bulb("red"); - - EXPECT_TRUE(bulb.is(Color::red)); - EXPECT_TRUE(bulb.is(Status::solid_on)); - EXPECT_TRUE(bulb.is(Shape::circle)); - EXPECT_TRUE(bulb.is(Shape::Category::circle)); - } - - { - const auto bulb = Bulb("green solidOn right"); - - EXPECT_TRUE(bulb.is(Color::green)); - EXPECT_TRUE(bulb.is(Status::solid_on)); - EXPECT_TRUE(bulb.is(Shape::right)); - EXPECT_TRUE(bulb.is(Shape::Category::arrow)); - } - - { - const auto bulb = Bulb("green right"); - - EXPECT_TRUE(bulb.is(Color::green)); - EXPECT_TRUE(bulb.is(Status::solid_on)); - EXPECT_TRUE(bulb.is(Shape::right)); - EXPECT_TRUE(bulb.is(Shape::Category::arrow)); - } -} - -TEST(TrafficLight, TrafficLight) -{ - using TrafficLight = traffic_simulator::TrafficLight; - using Color = TrafficLight::Color; - using Status = TrafficLight::Status; - using Shape = TrafficLight::Shape; - - hdmap_utils::HdMapUtils map_manager( - ament_index_cpp::get_package_share_directory("traffic_simulator") + "/map/lanelet2_map.osm", - []() { - geographic_msgs::msg::GeoPoint geo_point; - geo_point.latitude = 35.61836750154; - geo_point.longitude = 139.78066608243; - return geo_point; - }()); - - { - auto traffic_light = TrafficLight(34802, map_manager); - - traffic_light.emplace(Color::red, Status::flashing, Shape::circle); - traffic_light.emplace(Color::green, Status::solid_on, Shape::right); - - EXPECT_TRUE(traffic_light.contains(Color::red, Status::flashing, Shape::circle)); - EXPECT_TRUE(traffic_light.contains(Color::green, Status::solid_on, Shape::right)); - } - - { - auto traffic_light = TrafficLight(34802, map_manager); - - traffic_light.emplace("red flashing circle"); - traffic_light.emplace("green solidOn right"); - - EXPECT_TRUE(traffic_light.contains(Color::red, Status::flashing, Shape::circle)); - EXPECT_TRUE(traffic_light.contains(Color::green, Status::solid_on, Shape::right)); - } - - { - auto traffic_light = TrafficLight(34802, map_manager); - - traffic_light.set("red flashing circle, green solidOn right"); - - EXPECT_TRUE(traffic_light.contains(Color::red, Status::flashing, Shape::circle)); - EXPECT_TRUE(traffic_light.contains(Color::green, Status::solid_on, Shape::right)); - } -} - -/** - * @note Test basic functionality. Test whether the function - * creates Color object appropriate to the argument. - */ -TEST(TrafficLight, Color_make) -{ - using Color = traffic_simulator::TrafficLight::Color; - { - const auto color = Color::make("green"); - - EXPECT_TRUE(color == Color::green); - EXPECT_TRUE(color.is(Color::green)); - EXPECT_TRUE(boost::lexical_cast("green") == Color::green); - EXPECT_TRUE(boost::lexical_cast(color) == "green"); - } - - { - const auto color = Color::make("yellow"); - - EXPECT_TRUE(color == Color::yellow); - EXPECT_TRUE(color.is(Color::yellow)); - EXPECT_TRUE(boost::lexical_cast("yellow") == Color::yellow); - EXPECT_TRUE(boost::lexical_cast(color) == "yellow"); - } - - { - const auto color = Color::make("red"); - - EXPECT_TRUE(color == Color::red); - EXPECT_TRUE(color.is(Color::red)); - EXPECT_TRUE(boost::lexical_cast("red") == Color::red); - EXPECT_TRUE(boost::lexical_cast(color) == "red"); - } - - { - const auto color = Color::make("white"); - - EXPECT_TRUE(color == Color::white); - EXPECT_TRUE(color.is(Color::white)); - EXPECT_TRUE(boost::lexical_cast("white") == Color::white); - EXPECT_TRUE(boost::lexical_cast(color) == "white"); - } - - { - const auto color = Color::make("amber"); - - EXPECT_TRUE(color == Color::yellow); - EXPECT_TRUE(color.is(Color::yellow)); - EXPECT_TRUE(boost::lexical_cast("amber") == Color::yellow); - EXPECT_TRUE(boost::lexical_cast(color) == "yellow"); - } -} - /** - * @note Test basic functionality. Test whether the function creates Color object appropriate to the argument. + * @note Test basic functionality. Test whether the function creates Shape object appropriate to the argument. */ -TEST(TrafficLight, Shape_make) +TEST(Shape, make) { using Shape = traffic_simulator::TrafficLight::Shape; @@ -545,53 +473,115 @@ TEST(TrafficLight, Shape_make) } /** - * @note Test basic functionality. Test whether the function creates Status object appropriate to the argument. + * @note Test basic functionality. Test function behavior when called with invalid name. */ -TEST(TrafficLight, Status_make) +TEST(Shape, make_wrong) { - using Status = traffic_simulator::TrafficLight::Status; + EXPECT_THROW(traffic_simulator::TrafficLight::Shape::make("wrong_shape"), common::SyntaxError); +} + +/** + * @note Test object creation correcness. + */ +TEST(Bulb, Bulb) +{ + using TrafficLight = traffic_simulator::TrafficLight; + using Color = TrafficLight::Color; + using Status = TrafficLight::Status; + using Shape = TrafficLight::Shape; + using Bulb = TrafficLight::Bulb; + + // clang-format off + static_assert(Bulb(Color::green, Status::solid_on, Shape::circle ).hash() == 0b0000'0000'0000'0000'0000'0000'0000'0000); + static_assert(Bulb(Color::yellow, Status::solid_on, Shape::circle ).hash() == 0b0000'0001'0000'0000'0000'0000'0000'0000); + static_assert(Bulb(Color::red, Status::solid_on, Shape::circle ).hash() == 0b0000'0010'0000'0000'0000'0000'0000'0000); + static_assert(Bulb(Color::white, Status::solid_on, Shape::circle ).hash() == 0b0000'0011'0000'0000'0000'0000'0000'0000); + + static_assert(Bulb(Color::green, Status::solid_on, Shape::circle ).hash() == 0b0000'0000'0000'0000'0000'0000'0000'0000); + static_assert(Bulb(Color::green, Status::solid_off, Shape::circle ).hash() == 0b0000'0000'0000'0001'0000'0000'0000'0000); + static_assert(Bulb(Color::green, Status::flashing, Shape::circle ).hash() == 0b0000'0000'0000'0010'0000'0000'0000'0000); + static_assert(Bulb(Color::green, Status::unknown, Shape::circle ).hash() == 0b0000'0000'0000'0011'0000'0000'0000'0000); + + static_assert(Bulb(Color::green, Status::solid_on, Shape::circle ).hash() == 0b0000'0000'0000'0000'0000'0000'0000'0000); + static_assert(Bulb(Color::green, Status::solid_on, Shape::cross ).hash() == 0b0000'0000'0000'0000'0000'0000'0000'0001); + static_assert(Bulb(Color::green, Status::solid_on, Shape::left ).hash() == 0b0000'0000'0000'0000'0000'1000'0000'0010); + static_assert(Bulb(Color::green, Status::solid_on, Shape::down ).hash() == 0b0000'0000'0000'0000'0000'0100'0000'0010); + static_assert(Bulb(Color::green, Status::solid_on, Shape::up ).hash() == 0b0000'0000'0000'0000'0000'0010'0000'0010); + static_assert(Bulb(Color::green, Status::solid_on, Shape::right ).hash() == 0b0000'0000'0000'0000'0000'0001'0000'0010); + static_assert(Bulb(Color::green, Status::solid_on, Shape::lower_left ).hash() == 0b0000'0000'0000'0000'0000'1100'0000'0010); + static_assert(Bulb(Color::green, Status::solid_on, Shape::upper_left ).hash() == 0b0000'0000'0000'0000'0000'1010'0000'0010); + static_assert(Bulb(Color::green, Status::solid_on, Shape::lower_right).hash() == 0b0000'0000'0000'0000'0000'0101'0000'0010); + static_assert(Bulb(Color::green, Status::solid_on, Shape::upper_right).hash() == 0b0000'0000'0000'0000'0000'0011'0000'0010); + // clang-format on { - const auto status = Status::make("solidOn"); + constexpr auto bulb = Bulb(Color::red, Status::flashing, Shape::circle); - EXPECT_TRUE(status == Status::solid_on); - EXPECT_TRUE(status.is(Status::solid_on)); - EXPECT_TRUE(boost::lexical_cast("solidOn") == Status::solid_on); - EXPECT_TRUE(boost::lexical_cast(status) == "solidOn"); + EXPECT_TRUE(bulb.is(Color::red)); + EXPECT_TRUE(bulb.is(Status::flashing)); + EXPECT_TRUE(bulb.is(Shape::circle)); + EXPECT_TRUE(bulb.is(Shape::Category::circle)); } { - const auto status = Status::make("solidOff"); + constexpr auto bulb = Bulb(Color::green, Status::solid_on, Shape::right); - EXPECT_TRUE(status == Status::solid_off); - EXPECT_TRUE(status.is(Status::solid_off)); - EXPECT_TRUE(boost::lexical_cast("solidOff") == Status::solid_off); - EXPECT_TRUE(boost::lexical_cast(status) == "solidOff"); + EXPECT_TRUE(bulb.is(Color::green)); + EXPECT_TRUE(bulb.is(Status::solid_on)); + EXPECT_TRUE(bulb.is(Shape::right)); + EXPECT_TRUE(bulb.is(Shape::Category::arrow)); } { - const auto status = Status::make("flashing"); + const auto bulb = Bulb("red flashing circle"); - EXPECT_TRUE(status == Status::flashing); - EXPECT_TRUE(status.is(Status::flashing)); - EXPECT_TRUE(boost::lexical_cast("flashing") == Status::flashing); - EXPECT_TRUE(boost::lexical_cast(status) == "flashing"); + EXPECT_TRUE(bulb.is(Color::red)); + EXPECT_TRUE(bulb.is(Status::flashing)); + EXPECT_TRUE(bulb.is(Shape::circle)); + EXPECT_TRUE(bulb.is(Shape::Category::circle)); } { - const auto status = Status::make("unknown"); + const auto bulb = Bulb("red flashing"); - EXPECT_TRUE(status == Status::unknown); - EXPECT_TRUE(status.is(Status::unknown)); - EXPECT_TRUE(boost::lexical_cast("unknown") == Status::unknown); - EXPECT_TRUE(boost::lexical_cast(status) == "unknown"); + EXPECT_TRUE(bulb.is(Color::red)); + EXPECT_TRUE(bulb.is(Status::flashing)); + EXPECT_TRUE(bulb.is(Shape::circle)); + EXPECT_TRUE(bulb.is(Shape::Category::circle)); + } + + { + const auto bulb = Bulb("red"); + + EXPECT_TRUE(bulb.is(Color::red)); + EXPECT_TRUE(bulb.is(Status::solid_on)); + EXPECT_TRUE(bulb.is(Shape::circle)); + EXPECT_TRUE(bulb.is(Shape::Category::circle)); + } + + { + const auto bulb = Bulb("green solidOn right"); + + EXPECT_TRUE(bulb.is(Color::green)); + EXPECT_TRUE(bulb.is(Status::solid_on)); + EXPECT_TRUE(bulb.is(Shape::right)); + EXPECT_TRUE(bulb.is(Shape::Category::arrow)); + } + + { + const auto bulb = Bulb("green right"); + + EXPECT_TRUE(bulb.is(Color::green)); + EXPECT_TRUE(bulb.is(Status::solid_on)); + EXPECT_TRUE(bulb.is(Shape::right)); + EXPECT_TRUE(bulb.is(Shape::Category::arrow)); } } /** - * @note Test basic functionality. Test whether the function creates Color object appropriate to the argument. + * @note Test basic functionality. Test whether the function creates Bulb object appropriate to the argument. */ -TEST(TrafficLight, Bulb_make) +TEST(Bulb, make) { using TrafficLight = traffic_simulator::TrafficLight; using Color = TrafficLight::Color; @@ -662,11 +652,24 @@ TEST(TrafficLight, Bulb_make) } } +/** + * @note Test basic functionality. Test function behavior when called with invalid name. + */ +TEST(Bulb, make_wrong) +{ + using Bulb = traffic_simulator::TrafficLight::Bulb; + + EXPECT_THROW(Bulb("red flashing wrong_shape"), common::SyntaxError); + EXPECT_THROW(Bulb("red wrong_status circle"), common::SyntaxError); + EXPECT_THROW(Bulb("wrong_color flashing circle"), common::SyntaxError); + EXPECT_THROW(Bulb("wrong_color wrong_status wrong_shape"), common::SyntaxError); +} + /** * @note Test basic functionality. Test whether the TrafficLight message * is constructed configured according to the Bulb object. */ -TEST(TrafficLight, Bulb_trafficLightMessageConversion) +TEST(Bulb, operator_TrafficLight) { using Color = traffic_simulator::TrafficLight::Color; using Status = traffic_simulator::TrafficLight::Status; @@ -723,39 +726,68 @@ TEST(TrafficLight, Bulb_trafficLightMessageConversion) } } -/** - * @note Test basic functionality. Test function behavior when called with invalid name. - */ -TEST(TrafficLight, Color_make_wrong) +class TrafficLightTest : public testing::Test { - EXPECT_THROW(traffic_simulator::TrafficLight::Color::make("wrong_color"), common::SyntaxError); -} +protected: + TrafficLightTest() + : map_manager( + ament_index_cpp::get_package_share_directory("traffic_simulator") + "/map/lanelet2_map.osm", + geographic_msgs::build() + .latitude(35.61836750154) + .longitude(139.78066608243) + .altitude(0.0)) + { + } + hdmap_utils::HdMapUtils map_manager; +}; /** - * @note Test basic functionality. Test function behavior when called with invalid name. + * @note test if function correctly determines if a given bulb + * is in the bulbs vector given a Color, Status, Shape triple. */ -TEST(TrafficLight, Shape_make_wrong) +TEST_F(TrafficLightTest, contains_colorStatusShape) { - EXPECT_THROW(traffic_simulator::TrafficLight::Shape::make("wrong_shape"), common::SyntaxError); -} + using TrafficLight = traffic_simulator::TrafficLight; + using Color = TrafficLight::Color; + using Status = TrafficLight::Status; + using Shape = TrafficLight::Shape; -/** - * @note Test basic functionality. Test function behavior when called with invalid name. - */ -TEST(TrafficLight, Status_make_wrong) -{ - EXPECT_THROW(traffic_simulator::TrafficLight::Status::make("wrong_status"), common::SyntaxError); + { + auto traffic_light = TrafficLight(34802, map_manager); + + traffic_light.bulbs.emplace(Color::red, Status::flashing, Shape::circle); + traffic_light.bulbs.emplace(Color::green, Status::solid_on, Shape::right); + + ASSERT_TRUE(traffic_light.bulbs.size() == static_cast(2)); + EXPECT_TRUE(traffic_light.contains(Color::red, Status::flashing, Shape::circle)); + EXPECT_TRUE(traffic_light.contains(Color::green, Status::solid_on, Shape::right)); + } + + { + auto traffic_light = TrafficLight(34802, map_manager); + + traffic_light.bulbs.emplace("red flashing circle"); + traffic_light.bulbs.emplace("green solidOn right"); + + EXPECT_TRUE(traffic_light.contains(Color::red, Status::flashing, Shape::circle)); + EXPECT_TRUE(traffic_light.contains(Color::green, Status::solid_on, Shape::right)); + } } /** - * @note Test basic functionality. Test function behavior when called with invalid name. + * @note Test function behavior with a valid string. */ -TEST(TrafficLight, Bulb_make_wrong) +TEST_F(TrafficLightTest, set_valid) { - using Bulb = traffic_simulator::TrafficLight::Bulb; + using TrafficLight = traffic_simulator::TrafficLight; + using Color = TrafficLight::Color; + using Status = TrafficLight::Status; + using Shape = TrafficLight::Shape; - EXPECT_THROW(Bulb("red flashing wrong_shape"), common::SyntaxError); - EXPECT_THROW(Bulb("red wrong_status circle"), common::SyntaxError); - EXPECT_THROW(Bulb("wrong_color flashing circle"), common::SyntaxError); - EXPECT_THROW(Bulb("wrong_color wrong_status wrong_shape"), common::SyntaxError); + auto traffic_light = TrafficLight(34802, map_manager); + + traffic_light.set("red flashing circle, green solidOn right"); + + EXPECT_TRUE(traffic_light.contains(Color::red, Status::flashing, Shape::circle)); + EXPECT_TRUE(traffic_light.contains(Color::green, Status::solid_on, Shape::right)); } From 565a8ed86aff2fb493e50f80833ec742db41b643 Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Thu, 8 Aug 2024 14:09:29 +0900 Subject: [PATCH 104/304] Change QoS of `/api/localization/initialization_state` to transient local Signed-off-by: yamacir-kit --- ...rator_application_for_autoware_universe.hpp | 18 +++++++++--------- .../include/concealer/subscriber_wrapper.hpp | 6 ++++-- external/concealer/src/autoware_universe.cpp | 9 +++++---- 3 files changed, 18 insertions(+), 15 deletions(-) diff --git a/external/concealer/include/concealer/field_operator_application_for_autoware_universe.hpp b/external/concealer/include/concealer/field_operator_application_for_autoware_universe.hpp index e9d14665928..0202d488eb3 100644 --- a/external/concealer/include/concealer/field_operator_application_for_autoware_universe.hpp +++ b/external/concealer/include/concealer/field_operator_application_for_autoware_universe.hpp @@ -114,17 +114,17 @@ class FieldOperatorApplicationFor CONCEALER_PUBLIC explicit FieldOperatorApplicationFor(Ts &&... xs) : FieldOperatorApplication(std::forward(xs)...), // clang-format off - getAckermannControlCommand("/control/command/control_cmd", *this), - getAutowareState("/api/iv_msgs/autoware/state", *this), - getCooperateStatusArray("/api/external/get/rtc_status", *this, [this](const auto & v) { latest_cooperate_status_array = v; }), - getEmergencyState("/api/external/get/emergency", *this, [this](const auto & v) { receiveEmergencyState(v); }), + getAckermannControlCommand("/control/command/control_cmd", rclcpp::QoS(1), *this), + getAutowareState("/api/iv_msgs/autoware/state", rclcpp::QoS(1), *this), + getCooperateStatusArray("/api/external/get/rtc_status", rclcpp::QoS(1), *this, [this](const auto & v) { latest_cooperate_status_array = v; }), + getEmergencyState("/api/external/get/emergency", rclcpp::QoS(1), *this, [this](const auto & v) { receiveEmergencyState(v); }), #if __has_include() - getLocalizationState("/api/localization/initialization_state", *this), + getLocalizationState("/api/localization/initialization_state", rclcpp::QoS(1).transient_local(), *this), #endif - getMrmState("/api/fail_safe/mrm_state", *this, [this](const auto & v) { receiveMrmState(v); }), - getPathWithLaneId("/planning/scenario_planning/lane_driving/behavior_planning/path_with_lane_id", *this), - getTrajectory("/api/iv_msgs/planning/scenario_planning/trajectory", *this), - getTurnIndicatorsCommandImpl("/control/command/turn_indicators_cmd", *this), + getMrmState("/api/fail_safe/mrm_state", rclcpp::QoS(1), *this, [this](const auto & v) { receiveMrmState(v); }), + getPathWithLaneId("/planning/scenario_planning/lane_driving/behavior_planning/path_with_lane_id", rclcpp::QoS(1), *this), + getTrajectory("/api/iv_msgs/planning/scenario_planning/trajectory", rclcpp::QoS(1), *this), + getTurnIndicatorsCommandImpl("/control/command/turn_indicators_cmd", rclcpp::QoS(1), *this), requestClearRoute("/api/routing/clear_route", *this), requestCooperateCommands("/api/external/set/rtc_commands", *this), requestEngage("/api/external/set/engage", *this), diff --git a/external/concealer/include/concealer/subscriber_wrapper.hpp b/external/concealer/include/concealer/subscriber_wrapper.hpp index e8869fb86ce..8247a872e3a 100644 --- a/external/concealer/include/concealer/subscriber_wrapper.hpp +++ b/external/concealer/include/concealer/subscriber_wrapper.hpp @@ -41,10 +41,12 @@ class SubscriberWrapper template SubscriberWrapper( - const std::string & topic, NodeInterface & autoware_interface, + const std::string & topic, const rclcpp::QoS & quality_of_service, + NodeInterface & autoware_interface, const std::function & callback = {}) : subscription(autoware_interface.template create_subscription( - topic, 1, [this, callback](const typename MessageType::ConstSharedPtr message) { + topic, quality_of_service, + [this, callback](const typename MessageType::ConstSharedPtr message) { if constexpr (thread_safety == ThreadSafety::safe) { std::atomic_store(¤t_value, message); if (current_value and callback) { diff --git a/external/concealer/src/autoware_universe.cpp b/external/concealer/src/autoware_universe.cpp index 6016eb0d322..dbecc8b51d9 100644 --- a/external/concealer/src/autoware_universe.cpp +++ b/external/concealer/src/autoware_universe.cpp @@ -17,11 +17,12 @@ namespace concealer { AutowareUniverse::AutowareUniverse() -: getAckermannControlCommand("/control/command/control_cmd", *this), - getGearCommandImpl("/control/command/gear_cmd", *this), - getTurnIndicatorsCommand("/control/command/turn_indicators_cmd", *this), +: getAckermannControlCommand("/control/command/control_cmd", rclcpp::QoS(1), *this), + getGearCommandImpl("/control/command/gear_cmd", rclcpp::QoS(1), *this), + getTurnIndicatorsCommand("/control/command/turn_indicators_cmd", rclcpp::QoS(1), *this), getPathWithLaneId( - "/planning/scenario_planning/lane_driving/behavior_planning/path_with_lane_id", *this), + "/planning/scenario_planning/lane_driving/behavior_planning/path_with_lane_id", rclcpp::QoS(1), + *this), setAcceleration("/localization/acceleration", *this), setOdometry("/localization/kinematic_state", *this), setSteeringReport("/vehicle/status/steering_status", *this), From 35ad312cb92ec2bc7dd816b9fa570bc984441ad3 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Thu, 8 Aug 2024 15:52:27 +0900 Subject: [PATCH 105/304] feat: support EntitySelection in RelativeClearanceCondition --- .../syntax/relative_clearance_condition.hpp | 2 +- .../syntax/relative_clearance_condition.cpp | 154 +++++++++++------- 2 files changed, 99 insertions(+), 57 deletions(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_clearance_condition.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_clearance_condition.hpp index 970650516e4..2348a6436be 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_clearance_condition.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_clearance_condition.hpp @@ -72,7 +72,7 @@ struct RelativeClearanceCondition : private Scope, /* Constraint to check only specific entities. If it is not used then all entities are considered. */ - const std::list entity_refs; + const std::list entity_refs; const TriggeringEntities triggering_entities; diff --git a/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp b/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp index da665422b22..be7be2c1c5e 100644 --- a/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp @@ -16,7 +16,9 @@ #include #include #include +#include #include +#include #include #include @@ -32,7 +34,7 @@ RelativeClearanceCondition::RelativeClearanceCondition( free_space(readAttribute("freeSpace", node, scope)), opposite_lanes(readAttribute("oppositeLanes", node, scope)), relative_lane_range(readElements("RelativeLaneRange", node, scope)), - entity_refs(readElements("EntityRef", node, scope)), + entity_refs(readElements("EntityRef", node, scope)), triggering_entities(triggering_entities) { } @@ -70,69 +72,109 @@ auto RelativeClearanceCondition::description() const -> String auto RelativeClearanceCondition::evaluate() -> Object { - auto target_entities = [&]() { - if (not entity_refs.empty()) { - return entity_refs; - } else { - std::list entities; - for (const auto & entity : *global().entities) { - if ( - std::find_if( - triggering_entities.entity_refs.begin(), triggering_entities.entity_refs.end(), - [&](const auto & triggering_entity) { - return triggering_entity.name() == entity.first; - }) == triggering_entities.entity_refs.end()) { - entities.emplace_back(entity.first); + auto is_relative_clearance_exist = [&]( + const auto & triggering_entity, const auto & target_entity) { + auto is_back = + (std::abs(evaluateRelativeHeading(triggering_entity)) > + boost::math::constants::half_pi()); + auto is_in_lateral_range = [&]() { + // The lanes to be checked to left and right of the triggering entity (positive to the y-axis). If omitted: all lanes are checked. + if (relative_lane_range.empty()) { + return true; + } else { + if (auto relative_lateral_lane = evaluateLateralRelativeLanes( + triggering_entity, target_entity, RoutingAlgorithm::shortest); + relative_lateral_lane.has_value()) { + if (is_back) { + relative_lateral_lane.value() = -relative_lateral_lane.value(); + } + return std::any_of( + relative_lane_range.begin(), relative_lane_range.end(), [&](const auto & range) { + return range.from <= relative_lateral_lane.value() && + range.to >= relative_lateral_lane.value(); + }); + } else { + throw common::Error("Relative lateral lane is not available"); } } - return entities; - } - }(); - return asBoolean(triggering_entities.apply([&](const auto & triggering_entity) { - return std::all_of( - target_entities.begin(), target_entities.end(), - [&, is_back = - (std::abs(evaluateRelativeHeading(triggering_entity)) > - boost::math::constants::half_pi())](const auto & entity) { - auto is_in_lateral_range = [&]() { - // The lanes to be checked to left and right of the triggering entity (positive to the y-axis). If omitted: all lanes are checked. - if (relative_lane_range.empty()) { + }; + + auto is_in_longitudinal_range = [&]() { + auto relative_longitudinal = + getRelativeLanePosition(triggering_entity, target_entity, free_space).s; + if (is_back) { + relative_longitudinal = -relative_longitudinal; + } + if (relative_longitudinal < 0) { + return std::abs(relative_longitudinal) <= distance_backward; + } else { + return relative_longitudinal <= distance_forward; + } + }; + + auto lat_ok = is_in_lateral_range(); + auto lon_ok = is_in_longitudinal_range(); + return not(lat_ok && lon_ok); + }; + + return asBoolean(triggering_entities.apply([&](const auto & triggering_scenario_object) { + assert(triggering_scenario_object.is()); + if (not entity_refs.empty()) { + return std::all_of( + entity_refs.begin(), entity_refs.end(), [&](const auto & target_entity_ref) { + const auto & target_entity = global().entities->ref(target_entity_ref); + if (target_entity.template is()) { + return is_relative_clearance_exist( + triggering_scenario_object, target_entity.template as().name); + ; + } else if (target_entity.template is()) { // + auto target_scenario_objects = target_entity.template as().objects(); + return std::all_of( + target_scenario_objects.begin(), target_scenario_objects.end(), + [&](const auto & target_scenario_object) { + return is_relative_clearance_exist( + triggering_scenario_object, target_scenario_object.name()); + }); + } else { + throw common::Error( + "Unexpected entity interface is detected. RelativeClearanceCondition expects " + "ScenarioObject or EntitySelection."); + } + }); + } else { + return std::all_of( + global().entities->begin(), global().entities->end(), + [&](const auto & target_candidate_entity) { + if (not target_candidate_entity.second.template is()) { return true; } else { - if (auto relative_lateral_lane = evaluateLateralRelativeLanes( - triggering_entity, entity, RoutingAlgorithm::shortest); - relative_lateral_lane.has_value()) { - if (is_back) { - relative_lateral_lane.value() = -relative_lateral_lane.value(); - } - return std::any_of( - relative_lane_range.begin(), relative_lane_range.end(), [&](const auto & range) { - return range.from <= relative_lateral_lane.value() && - range.to >= relative_lateral_lane.value(); + const ScenarioObject & target_candidate_scenario_object = + target_candidate_entity.second.template as(); + // exclude entities included in TriggeringEntities + auto is_target_candidate_scenario_object_in_triggering_entities = + [&](const ScenarioObject & target_candidate) -> bool { + bool is_included = false; + triggering_entities.apply( + [target_candidate, &is_included](const auto & triggering_scenario_object) { + assert(triggering_scenario_object.is()); + if (triggering_scenario_object.name() == target_candidate.name) { + is_included = true; + } + return true; }); + return is_included; + }; + if (is_target_candidate_scenario_object_in_triggering_entities( + target_candidate_scenario_object)) { + return true; } else { - throw common::Error("Relative lateral lane is not available"); + const auto & target_scenario_object = target_candidate_scenario_object; + return is_relative_clearance_exist( + triggering_scenario_object, target_scenario_object.name); } } - }; - - auto is_in_longitudinal_range = [&]() { - auto relative_longitudinal = - getRelativeLanePosition(triggering_entity, entity, free_space).s; - if (is_back) { - relative_longitudinal = -relative_longitudinal; - } - if (relative_longitudinal < 0) { - return std::abs(relative_longitudinal) <= distance_backward; - } else { - return relative_longitudinal <= distance_forward; - } - }; - - auto lat_ok = is_in_lateral_range(); - auto lon_ok = is_in_longitudinal_range(); - return not(lat_ok && lon_ok); - }); + }); + } })); } From d6bf5c60d28095ca7735bff2741eeae40e7a9c49 Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Thu, 8 Aug 2024 16:16:59 +0900 Subject: [PATCH 106/304] Cleanup struct `MagicSubscription` Signed-off-by: yamacir-kit --- .../syntax/user_defined_value_condition.cpp | 108 +++++++++--------- 1 file changed, 57 insertions(+), 51 deletions(-) diff --git a/openscenario/openscenario_interpreter/src/syntax/user_defined_value_condition.cpp b/openscenario/openscenario_interpreter/src/syntax/user_defined_value_condition.cpp index c13b4d8edc1..c850016dc52 100644 --- a/openscenario/openscenario_interpreter/src/syntax/user_defined_value_condition.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/user_defined_value_condition.cpp @@ -33,70 +33,76 @@ namespace openscenario_interpreter inline namespace syntax { template -struct MagicSubscription : public T +struct MagicSubscription : private T { - struct Subscriber + struct Node : public rclcpp::Node { - rclcpp::Node node; - std::atomic_bool stop_requested = false; - std::promise promise; + std::mutex mutex; - std::future future; + std::exception_ptr thrown; std::thread thread; - explicit Subscriber() - : node("magic_subscription"), - future(promise.get_future()), - thread( - [this](std::promise promise) { - while (rclcpp::ok() and not stop_requested) { - try { - rclcpp::spin_some(node.get_node_base_interface()); - } catch (...) { - promise.set_exception(std::current_exception()); - } + explicit Node() + : rclcpp::Node("magic_subscription"), thread([this]() { + while (rclcpp::ok() and not stop_requested) { + try { + rclcpp::spin_some(get_node_base_interface()); + } catch (...) { + auto lock = std::lock_guard(mutex); + thrown = std::current_exception(); } - }, - std::move(promise)) + } + }) { } - }; - static auto subscriber() -> auto & - { - static std::unique_ptr subscriber = nullptr; + ~Node() + { + if (thread.joinable() and not stop_requested.exchange(true)) { + thread.join(); + } + } - if (not subscriber) { - subscriber = std::make_unique(); + auto rethrow() + { + if (auto lock = std::lock_guard(mutex); thrown) { + std::rethrow_exception(thrown); + } } + }; - return subscriber; - } + static inline std::size_t count = 0; - typename rclcpp::Subscription::SharedPtr subscription; + static inline std::unique_ptr node = nullptr; - static inline std::size_t count = 0; + typename rclcpp::Subscription::SharedPtr subscription; explicit MagicSubscription(const std::string & topic_name) - : subscription(subscriber()->node.template create_subscription( - topic_name, 1, [this, count = count++](const typename T::SharedPtr message) { - static_cast(*this) = *message; - })) { + if (not count++) { + node = std::make_unique(); + } + + subscription = node->template create_subscription( + topic_name, 1, + [this](const typename T::SharedPtr message) { static_cast(*this) = *message; }); } ~MagicSubscription() { - if ( - not --count and subscriber()->thread.joinable() and - not subscriber()->stop_requested.exchange(true)) { - subscriber()->thread.join(); - subscriber().reset(); + if (not --count) { + node.reset(); } } + + auto get() const -> const auto & + { + node->rethrow(); + return static_cast(*this); + } }; UserDefinedValueCondition::UserDefinedValueCondition(const pugi::xml_node & node, Scope & scope) @@ -158,29 +164,29 @@ UserDefinedValueCondition::UserDefinedValueCondition(const pugi::xml_node & node using tier4_simulation_msgs::msg::UserDefinedValueType; evaluate_value = - [this, message = std::make_shared>(result.str(0))]() { - auto evaluate = [](const auto & user_defined_value) { - switch (user_defined_value.type.data) { + [this, subscriber = std::make_shared>(result.str(0))]() { + if (const auto message = subscriber->get(); message.value.empty()) { + return unspecified; + } else { + switch (message.type.data) { case UserDefinedValueType::BOOLEAN: - return make(user_defined_value.value); + return make(message.value); case UserDefinedValueType::DATE_TIME: - return make(user_defined_value.value); + return make(message.value); case UserDefinedValueType::DOUBLE: - return make(user_defined_value.value); + return make(message.value); case UserDefinedValueType::INTEGER: - return make(user_defined_value.value); + return make(message.value); case UserDefinedValueType::STRING: - return make(user_defined_value.value); + return make(message.value); case UserDefinedValueType::UNSIGNED_INT: - return make(user_defined_value.value); + return make(message.value); case UserDefinedValueType::UNSIGNED_SHORT: - return make(user_defined_value.value); + return make(message.value); default: return unspecified; } - }; - - return message->value.empty() ? unspecified : evaluate(*message); + } }; #else throw SyntaxError( From c955d19e49029873e23a52477e138fb68b1462e4 Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Thu, 8 Aug 2024 16:52:07 +0900 Subject: [PATCH 107/304] Update `MagicSubscription`'s QoS to best effort Signed-off-by: yamacir-kit --- .../src/syntax/user_defined_value_condition.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/openscenario/openscenario_interpreter/src/syntax/user_defined_value_condition.cpp b/openscenario/openscenario_interpreter/src/syntax/user_defined_value_condition.cpp index c850016dc52..29d0424434d 100644 --- a/openscenario/openscenario_interpreter/src/syntax/user_defined_value_condition.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/user_defined_value_condition.cpp @@ -87,7 +87,7 @@ struct MagicSubscription : private T } subscription = node->template create_subscription( - topic_name, 1, + topic_name, rclcpp::QoS(1).best_effort(), [this](const typename T::SharedPtr message) { static_cast(*this) = *message; }); } From be1470c7fb20c7667b0558da4b649a155b8a0381 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Thu, 8 Aug 2024 17:10:16 +0900 Subject: [PATCH 108/304] refactor: use std::optional for optional attribute in RelativeLaneRange --- .../reader/attribute.hpp | 11 +++++++++++ .../syntax/relative_lane_range.hpp | 7 +++++-- .../src/syntax/relative_clearance_condition.cpp | 17 +++++++++++++---- .../src/syntax/relative_lane_range.cpp | 9 +++++++-- 4 files changed, 36 insertions(+), 8 deletions(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/reader/attribute.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/reader/attribute.hpp index 06568802cbe..945e1a346a3 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/reader/attribute.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/reader/attribute.hpp @@ -22,6 +22,7 @@ #include #include #include +#include #include #include #include @@ -164,6 +165,16 @@ auto readAttribute(const std::string & name, const Node & node, const Scope & sc return value; } } + +template +auto readAttribute(const std::string & name, const Node & node, const Scope & scope, std::nullopt_t) +{ + if (node.attribute(name.c_str())) { + return std::make_optional(readAttribute(name, node, scope)); + } else { + return std::optional(); + } +} } // namespace reader } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_lane_range.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_lane_range.hpp index f6f94e9332e..f20d562173e 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_lane_range.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_lane_range.hpp @@ -17,6 +17,7 @@ #include #include +#include #include namespace openscenario_interpreter @@ -36,14 +37,16 @@ struct RelativeLaneRange /* The lower limit of the range. Range: [-inf, inf[. Default if omitted: -inf */ - const Integer from; + const std::optional from; /* The upper limit of the range. Range: ]-inf, inf]. Default if omitted: +inf */ - const Integer to; + const std::optional to; explicit RelativeLaneRange(const pugi::xml_node &, Scope &); + + auto evaluate(Integer::value_type value) const -> bool; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp b/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp index be7be2c1c5e..e78eae1c03e 100644 --- a/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp @@ -54,8 +54,18 @@ auto RelativeClearanceCondition::description() const -> String description << "all lanes"; } else { for (auto range = relative_lane_range.begin(); range != relative_lane_range.end(); range++) { - description << ((range != relative_lane_range.begin()) ? std::string(", ") : std::string("")) - << range->from << " to " << range->to; + description << ((range != relative_lane_range.begin()) ? std::string(", ") : std::string("")); + if (range->from) { + if (range->to) { + description << range->from.value() << " to " << range->to.value(); + } else { + description << range->from.value() << "or more"; + } + } else { + if (range->to) { + description << range->to.value() << " or less"; + } + } } } @@ -90,8 +100,7 @@ auto RelativeClearanceCondition::evaluate() -> Object } return std::any_of( relative_lane_range.begin(), relative_lane_range.end(), [&](const auto & range) { - return range.from <= relative_lateral_lane.value() && - range.to >= relative_lateral_lane.value(); + return range.evaluate(relative_lateral_lane.value()); }); } else { throw common::Error("Relative lateral lane is not available"); diff --git a/openscenario/openscenario_interpreter/src/syntax/relative_lane_range.cpp b/openscenario/openscenario_interpreter/src/syntax/relative_lane_range.cpp index 1061128a077..cd5fbe32950 100644 --- a/openscenario/openscenario_interpreter/src/syntax/relative_lane_range.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/relative_lane_range.cpp @@ -20,9 +20,14 @@ namespace openscenario_interpreter inline namespace syntax { RelativeLaneRange::RelativeLaneRange(const pugi::xml_node & node, Scope & scope) -: from(readAttribute("from", node, scope, Integer::min())), - to(readAttribute("to", node, scope, Integer::max())) +: from(readAttribute("from", node, scope, std::nullopt)), + to(readAttribute("to", node, scope, std::nullopt)) { } + +auto RelativeLaneRange::evaluate(Integer::value_type value) const -> bool +{ + return (not from || from.value() <= value) && (not to || to >= value); +} } // namespace syntax } // namespace openscenario_interpreter From 609b3ef86114514f09613565cf73347648579f22 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Thu, 8 Aug 2024 18:48:59 +0900 Subject: [PATCH 109/304] refactor: use exception when errors are occurred in SimulatorCore::evaluateLateralRelativeLanes --- .../simulator_core.hpp | 7 ++--- .../syntax/relative_clearance_condition.cpp | 26 ++++++++++--------- 2 files changed, 18 insertions(+), 15 deletions(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/simulator_core.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/simulator_core.hpp index 58716a3abb5..fc3a3f9edb6 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/simulator_core.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/simulator_core.hpp @@ -259,8 +259,7 @@ class SimulatorCore static auto evaluateLateralRelativeLanes( const std::string & from_entity_name, const std::string & to_entity_name, - const RoutingAlgorithm::value_type routing_algorithm = RoutingAlgorithm::undefined) - -> std::optional + const RoutingAlgorithm::value_type routing_algorithm = RoutingAlgorithm::undefined) -> int { if (const auto from_entity = core->getEntity(from_entity_name)) { if (const auto to_entity = core->getEntity(to_entity_name)) { @@ -275,7 +274,9 @@ class SimulatorCore } } } - return std::nullopt; + throw common::Error( + "Failed to evaluate lateral relative lanes between ", from_entity_name, " and ", + to_entity_name); } }; diff --git a/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp b/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp index e78eae1c03e..236f316eb4c 100644 --- a/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp @@ -92,19 +92,21 @@ auto RelativeClearanceCondition::evaluate() -> Object if (relative_lane_range.empty()) { return true; } else { - if (auto relative_lateral_lane = evaluateLateralRelativeLanes( - triggering_entity, target_entity, RoutingAlgorithm::shortest); - relative_lateral_lane.has_value()) { - if (is_back) { - relative_lateral_lane.value() = -relative_lateral_lane.value(); - } - return std::any_of( - relative_lane_range.begin(), relative_lane_range.end(), [&](const auto & range) { - return range.evaluate(relative_lateral_lane.value()); - }); - } else { - throw common::Error("Relative lateral lane is not available"); + int relative_lateral_lane; + try { + relative_lateral_lane = evaluateLateralRelativeLanes( + triggering_entity, target_entity, RoutingAlgorithm::shortest); + } catch (const std::exception &) { + // occurring errors means that the target entity is not in the specified range, + // under the assumption that relative lane range is defined in routable range . + return false; + } + if (is_back) { + relative_lateral_lane = -relative_lateral_lane; } + return std::any_of( + relative_lane_range.begin(), relative_lane_range.end(), + [&](const auto & range) { return range.evaluate(relative_lateral_lane); }); } }; From eaf95099061aea96a05a20a9f1d5bcf896779222 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Thu, 8 Aug 2024 18:55:55 +0900 Subject: [PATCH 110/304] refactor: delete RelativeClearanceCondition::getRelativeLanePosition --- .../syntax/relative_clearance_condition.hpp | 4 --- .../syntax/relative_clearance_condition.cpp | 29 +++++++++---------- 2 files changed, 14 insertions(+), 19 deletions(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_clearance_condition.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_clearance_condition.hpp index 2348a6436be..804c60e50e6 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_clearance_condition.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_clearance_condition.hpp @@ -81,10 +81,6 @@ struct RelativeClearanceCondition : private Scope, auto description() const -> String; auto evaluate() -> Object; - - [[nodiscard]] auto getRelativeLanePosition( - const EntityRef & triggering_entity, const EntityRef & entity, bool use_bounding_box) const - -> traffic_simulator::LaneletPose; }; } // namespace syntax } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp b/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp index 236f316eb4c..82d471ea70e 100644 --- a/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp @@ -111,8 +111,20 @@ auto RelativeClearanceCondition::evaluate() -> Object }; auto is_in_longitudinal_range = [&]() { - auto relative_longitudinal = - getRelativeLanePosition(triggering_entity, target_entity, free_space).s; + auto relative_longitudinal = [&]() { + if (free_space) { + return static_cast( + makeNativeBoundingBoxRelativeLanePosition( + triggering_entity, target_entity, RoutingAlgorithm::shortest)) + .s; + } else { + return static_cast( + makeNativeRelativeLanePosition( + triggering_entity, target_entity, RoutingAlgorithm::shortest)) + .s; + } + }(); + if (is_back) { relative_longitudinal = -relative_longitudinal; } @@ -188,18 +200,5 @@ auto RelativeClearanceCondition::evaluate() -> Object } })); } - -auto RelativeClearanceCondition::getRelativeLanePosition( - const EntityRef & triggering_entity, const EntityRef & entity, bool use_bounding_box) const - -> traffic_simulator::LaneletPose -{ - if (use_bounding_box) { - return static_cast(makeNativeBoundingBoxRelativeLanePosition( - triggering_entity, entity, RoutingAlgorithm::shortest)); - } else { - return static_cast( - makeNativeRelativeLanePosition(triggering_entity, entity, RoutingAlgorithm::shortest)); - } -} } // namespace syntax } // namespace openscenario_interpreter From d17e600ae6ee9ad7376715f9a9b298f1f640f5d5 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Thu, 8 Aug 2024 18:58:41 +0900 Subject: [PATCH 111/304] fix: treat added entity only in RelativeClearanceCondition --- .../src/syntax/relative_clearance_condition.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp b/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp index 82d471ea70e..5de182c649f 100644 --- a/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/relative_clearance_condition.cpp @@ -170,6 +170,8 @@ auto RelativeClearanceCondition::evaluate() -> Object [&](const auto & target_candidate_entity) { if (not target_candidate_entity.second.template is()) { return true; + } else if (not target_candidate_entity.second.template as().is_added) { + return true; } else { const ScenarioObject & target_candidate_scenario_object = target_candidate_entity.second.template as(); From e8143fedf58f49172b8e5e67863f38475113f01b Mon Sep 17 00:00:00 2001 From: SzymonParapura Date: Fri, 9 Aug 2024 18:17:31 +0200 Subject: [PATCH 112/304] Test: [RJD-937] to Implement Unit tests on simple_sensor_simulator - Removed dummy class - Updated unit tests --- .../primitives/test_primitive.cpp | 35 ++++++----- .../primitives/test_primitive.hpp | 58 ++----------------- 2 files changed, 23 insertions(+), 70 deletions(-) diff --git a/simulation/simple_sensor_simulator/test/src/sensor_simulation/primitives/test_primitive.cpp b/simulation/simple_sensor_simulator/test/src/sensor_simulation/primitives/test_primitive.cpp index 1f5b1330c19..6438a0b2bb7 100644 --- a/simulation/simple_sensor_simulator/test/src/sensor_simulation/primitives/test_primitive.cpp +++ b/simulation/simple_sensor_simulator/test/src/sensor_simulation/primitives/test_primitive.cpp @@ -14,7 +14,9 @@ #include "test_primitive.hpp" +#include #include +#include #include "../../utils/expect_eq_macros.hpp" @@ -24,8 +26,8 @@ TEST_F(PrimitiveTest, addToScene_sample) { const std::vector expected_vertices = { - {0.0f, 1.0f, -1.0f}, {2.0f, 1.0f, -1.0f}, {0.0f, 3.0f, -1.0f}, {2.0f, 3.0f, -1.0f}, - {0.0f, 1.0f, 1.0f}, {2.0f, 1.0f, 1.0f}, {0.0f, 3.0f, 1.0f}, {2.0f, 3.0f, 1.0f}}; + {0.0f, 1.0f, -1.0f}, {0.0f, 1.0f, 1.0f}, {0.0f, 3.0f, -1.0f}, {0.0f, 3.0f, 1.0f}, + {2.0f, 1.0f, -1.0f}, {2.0f, 1.0f, 1.0f}, {2.0f, 3.0f, -1.0f}, {2.0f, 3.0f, 1.0f}}; const auto expected_triangles = primitive_->getTriangles(); RTCDevice device = rtcNewDevice(nullptr); @@ -60,15 +62,15 @@ TEST_F(PrimitiveTest, addToScene_sample) } /** - * @note Test function behavior with vertices and triangles set to only zeros. + * @note Test function behavior with vertices set to only zeros. */ TEST_F(PrimitiveTest, addToScene_zeros) { - const std::vector expected_triangles = {{0, 0, 0}}; - const std::vector expected_vertices = {{1.0f, 2.0f, 0.0f}}; + const std::vector expected_triangles = {{0, 1, 2}}; + const std::vector expected_vertices = {{0.0f, 0.0f, 0.0f}}; - primitive_->setVertices({{0.0f, 0.0f, 0.0f}}); - primitive_->setTriangles(expected_triangles); + primitive_ = + std::make_unique(0.0f, 0.0f, 0.0f, utils::makePose(0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0)); RTCDevice device = rtcNewDevice(nullptr); RTCScene scene = rtcNewScene(device); @@ -106,9 +108,9 @@ TEST_F(PrimitiveTest, addToScene_zeros) */ TEST_F(PrimitiveTest, getTriangles) { - const std::vector expected_triangles = {{0, 1, 2}, {1, 3, 2}, {4, 5, 6}, {5, 7, 6}, - {0, 1, 4}, {1, 5, 4}, {2, 3, 6}, {3, 7, 6}, - {0, 2, 4}, {2, 6, 4}, {1, 3, 5}, {3, 7, 5}}; + const std::vector expected_triangles = {{0, 1, 2}, {1, 3, 2}, {4, 6, 5}, {5, 6, 7}, + {0, 4, 1}, {1, 4, 5}, {2, 3, 6}, {3, 7, 6}, + {0, 2, 4}, {2, 6, 4}, {1, 5, 3}, {3, 5, 7}}; const auto triangles = primitive_->getTriangles(); @@ -119,14 +121,13 @@ TEST_F(PrimitiveTest, getTriangles) } /** - * @note Test basic functionality. Test obtaining vertex correctness with a sample vertex and a non - * trivial Primitive pose - the goal is to test transformation of vertex elements. + * @note Test basic functionality. Test obtaining vertexes correctness. */ TEST_F(PrimitiveTest, getVertex) { const std::vector expected_vertices = { - {0.0f, 1.0f, -1.0f}, {2.0f, 1.0f, -1.0f}, {0.0f, 3.0f, -1.0f}, {2.0f, 3.0f, -1.0f}, - {0.0f, 1.0f, 1.0f}, {2.0f, 1.0f, 1.0f}, {0.0f, 3.0f, 1.0f}, {2.0f, 3.0f, 1.0f}}; + {0.0f, 1.0f, -1.0f}, {0.0f, 1.0f, 1.0f}, {0.0f, 3.0f, -1.0f}, {0.0f, 3.0f, 1.0f}, + {2.0f, 1.0f, -1.0f}, {2.0f, 1.0f, 1.0f}, {2.0f, 3.0f, -1.0f}, {2.0f, 3.0f, 1.0f}}; const auto vertices = primitive_->getVertex(); @@ -207,7 +208,8 @@ TEST_F(PrimitiveTest, getMin_withTransform) */ TEST_F(PrimitiveTest, getMin_empty) { - primitive_->setVertices(std::vector{}); + primitive_ = std::make_unique("Unknown", pose_); + const auto min_x = primitive_->getMin(math::geometry::Axis::X); EXPECT_FALSE(min_x.has_value()); @@ -243,7 +245,8 @@ TEST_F(PrimitiveTest, getMax_withTransform) */ TEST_F(PrimitiveTest, getMax_empty) { - primitive_->setVertices(std::vector{}); + primitive_ = std::make_unique("Unknown", pose_); + const auto max_x = primitive_->getMax(math::geometry::Axis::X); EXPECT_FALSE(max_x.has_value()); diff --git a/simulation/simple_sensor_simulator/test/src/sensor_simulation/primitives/test_primitive.hpp b/simulation/simple_sensor_simulator/test/src/sensor_simulation/primitives/test_primitive.hpp index 3a752620be1..2343104aa81 100644 --- a/simulation/simple_sensor_simulator/test/src/sensor_simulation/primitives/test_primitive.hpp +++ b/simulation/simple_sensor_simulator/test/src/sensor_simulation/primitives/test_primitive.hpp @@ -17,76 +17,26 @@ #include -#include -#include -#include +#include +#include #include -#include #include "../../utils/helper_functions.hpp" using namespace simple_sensor_simulator::primitives; using namespace simple_sensor_simulator; -namespace simple_sensor_simulator -{ -namespace primitives -{ - -class DummyPrimitive : public Primitive -{ -public: - DummyPrimitive(const std::string & type, const geometry_msgs::msg::Pose & pose) - : Primitive(type, pose) - { - } - - auto setVertices(const std::vector & vertices) -> void { vertices_ = vertices; } - auto setTriangles(const std::vector & triangles) -> void { triangles_ = triangles; } - - auto getVerticesSize() const -> size_t { return vertices_.size(); } - auto getTrianglesSize() const -> size_t { return triangles_.size(); } - - auto getVertices() const -> const std::vector & { return vertices_; } - auto getTriangles() const -> const std::vector & { return triangles_; } -}; - -} // namespace primitives -} // namespace simple_sensor_simulator - class PrimitiveTest : public ::testing::Test { protected: PrimitiveTest() : pose_(utils::makePose(1.0, 2.0, 0.0, 0.0, 0.0, 0.0, 1.0)), - primitive_(std::make_unique("DummyPrimitive", pose_)) + primitive_(std::make_unique(2.0f, 2.0f, 2.0f, pose_)) { - primitive_->setVertices( - {{-1.0f, -1.0f, -1.0f}, - {1.0f, -1.0f, -1.0f}, - {-1.0f, 1.0f, -1.0f}, - {1.0f, 1.0f, -1.0f}, - {-1.0f, -1.0f, 1.0f}, - {1.0f, -1.0f, 1.0f}, - {-1.0f, 1.0f, 1.0f}, - {1.0f, 1.0f, 1.0f}}); - primitive_->setTriangles( - {{0, 1, 2}, - {1, 3, 2}, - {4, 5, 6}, - {5, 7, 6}, - {0, 1, 4}, - {1, 5, 4}, - {2, 3, 6}, - {3, 7, 6}, - {0, 2, 4}, - {2, 6, 4}, - {1, 3, 5}, - {3, 7, 5}}); } geometry_msgs::msg::Pose pose_; - std::unique_ptr primitive_; + std::unique_ptr primitive_; }; #endif // SIMPLE_SENSOR_SIMULATOR__TEST__TEST_PRIMITIVE_HPP_ From 1cb560a64e96beff75bf77cc6e3fc8937db3b1ee Mon Sep 17 00:00:00 2001 From: Masaya Kataoka Date: Tue, 13 Aug 2024 16:34:23 +0900 Subject: [PATCH 113/304] fix ament_auto_package macro Signed-off-by: Masaya Kataoka --- mock/cpp_mock_scenarios/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/mock/cpp_mock_scenarios/CMakeLists.txt b/mock/cpp_mock_scenarios/CMakeLists.txt index 308df5bf84a..84a18e37be7 100644 --- a/mock/cpp_mock_scenarios/CMakeLists.txt +++ b/mock/cpp_mock_scenarios/CMakeLists.txt @@ -73,4 +73,4 @@ if(BUILD_TESTING) # add_cpp_mock_scenario_test(${PROJECT_NAME} "traffic_simulation_demo" "70") endif() -ament_auto_package(CONFIG_EXTRAS "${PROJECT_NAME}-extras.cmake") +ament_auto_package(CONFIG_EXTRAS "${PROJECT_NAME}_ament_cmake-extras.cmake") From b1e93f5f5110f3f143c2728b35c8aea19c38921f Mon Sep 17 00:00:00 2001 From: Masaya Kataoka Date: Tue, 13 Aug 2024 17:31:29 +0900 Subject: [PATCH 114/304] update Release Action Signed-off-by: Masaya Kataoka --- .github/workflows/Docekr.yaml | 70 ++++++++++++++++++++++++++++++++++ .github/workflows/Release.yaml | 47 ----------------------- 2 files changed, 70 insertions(+), 47 deletions(-) create mode 100644 .github/workflows/Docekr.yaml diff --git a/.github/workflows/Docekr.yaml b/.github/workflows/Docekr.yaml new file mode 100644 index 00000000000..e43d6efe20d --- /dev/null +++ b/.github/workflows/Docekr.yaml @@ -0,0 +1,70 @@ +name: Docker +on: + pull_request: + branches: + - master + push: + tags: + +jobs: + push_docker: + name: Push Docker Image + runs-on: ubuntu-22.04 + timeout-minutes: 720 + strategy: + matrix: + rosdistro: [humble] + arch: [amd64] + # Build test for arm64 CPU is broken. + # This is a temporary solution and will be repaired in the future. + # See also https://github.com/tier4/scenario_simulator_v2/pull/1295 + # arch: [amd64, arm64] + steps: + - name: Free Disk Space (Ubuntu) + uses: jlumbroso/free-disk-space@main + with: + tool-cache: false + + - name: Install docker for ubuntu runner + uses: docker/setup-buildx-action@v3 + + - name: Install QEMU + uses: docker/setup-qemu-action@v3 + + - uses: actions/checkout@v3 + + - name: Login to GitHub Container Registry + uses: docker/login-action@v2 + with: + registry: ghcr.io + username: ${{ github.actor }} + password: ${{ secrets.GITHUB_TOKEN }} + + - name: Build (${{ matrix.arch }}) + if: github.event_name == 'pull_request' + uses: docker/bake-action@v3 + with: + files: | + ./docker-bake.hcl + workdir: . + set: | + *.cache-to=type=gha,mode=max + *.cache-from=type=gha + push: false + targets: | + ${{ matrix.rosdistro }}_base_${{ matrix.arch }} + + - name: Build and push (${{ matrix.arch }}) + if: github.event_name != 'pull_request' + uses: docker/bake-action@v3 + with: + files: | + ./docker-bake.hcl + workdir: . + set: | + *.cache-to=type=gha,mode=max + *.cache-from=type=gha + *.tags=ghcr.io/tier4/scenario_simulator_v2:humble-${{ github.ref_name }} + push: true + targets: | + ${{ matrix.rosdistro }}_base_${{ matrix.arch }} diff --git a/.github/workflows/Release.yaml b/.github/workflows/Release.yaml index fbbc78ff620..39b5508f735 100644 --- a/.github/workflows/Release.yaml +++ b/.github/workflows/Release.yaml @@ -142,50 +142,3 @@ jobs: repo: context.repo.repo, ref: `heads/${context.payload.pull_request.head.ref}`, }) - push_docker: - needs: release - name: Push Docker Image - runs-on: ubuntu-22.04 - timeout-minutes: 720 - strategy: - matrix: - rosdistro: [humble] - arch: [amd64] - # Build test for arm64 CPU is broken. - # This is a temporary solution and will be repaired in the future. - # See also https://github.com/tier4/scenario_simulator_v2/pull/1295 - # arch: [amd64, arm64] - steps: - - name: Free Disk Space (Ubuntu) - uses: jlumbroso/free-disk-space@main - with: - tool-cache: false - - - name: Install docker for ubuntu runner - uses: docker/setup-buildx-action@v3 - - - name: Install QEMU - uses: docker/setup-qemu-action@v3 - - - uses: actions/checkout@v3 - - - name: Login to GitHub Container Registry - uses: docker/login-action@v2 - with: - registry: ghcr.io - username: ${{ github.actor }} - password: ${{ secrets.GITHUB_TOKEN }} - - - name: Build and push (${{ matrix.arch }}) - uses: docker/bake-action@v3 - with: - files: | - ./docker-bake.hcl - workdir: . - set: | - *.cache-to=type=gha,mode=max - *.cache-from=type=gha - *.tags=ghcr.io/tier4/scenario_simulator_v2:humble-${{ needs.release.outputs.new_version }} - push: ${{ github.event.pull_request.merged == true }} - targets: | - ${{ matrix.rosdistro }}_base_${{ matrix.arch }} From 9c868b77ed48aa621530187bbcdfd69d60c9ae10 Mon Sep 17 00:00:00 2001 From: Masaya Kataoka Date: Tue, 13 Aug 2024 17:49:00 +0900 Subject: [PATCH 115/304] print event_name Signed-off-by: Masaya Kataoka --- .github/workflows/Docekr.yaml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/.github/workflows/Docekr.yaml b/.github/workflows/Docekr.yaml index e43d6efe20d..0736749f2d0 100644 --- a/.github/workflows/Docekr.yaml +++ b/.github/workflows/Docekr.yaml @@ -20,6 +20,8 @@ jobs: # See also https://github.com/tier4/scenario_simulator_v2/pull/1295 # arch: [amd64, arm64] steps: + - name: echo github.event_name + run: echo '${{ github.event_name }}' - name: Free Disk Space (Ubuntu) uses: jlumbroso/free-disk-space@main with: From 04606920c2d234b0fde70fd77a8800e04f9c1031 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Dawid=20Moszy=C5=84ski?= <121798334+dmoszynski@users.noreply.github.com> Date: Tue, 13 Aug 2024 11:13:41 +0200 Subject: [PATCH 116/304] doc(distance): use doxygen format Co-authored-by: Masaya Kataoka --- simulation/traffic_simulator/src/utils/distance.cpp | 5 +---- 1 file changed, 1 insertion(+), 4 deletions(-) diff --git a/simulation/traffic_simulator/src/utils/distance.cpp b/simulation/traffic_simulator/src/utils/distance.cpp index bf235e9a85c..3f582ea1446 100644 --- a/simulation/traffic_simulator/src/utils/distance.cpp +++ b/simulation/traffic_simulator/src/utils/distance.cpp @@ -45,10 +45,7 @@ auto lateralDistance( } } -/* - See doc: - https://github.com/tier4/scenario_simulator_v2/blob/729e4e6372cdba60e377ae097d032905b80763a9/docs/developer_guide/lane_pose_calculation/GetLongitudinalDistance.md -*/ +/// @sa https://github.com/tier4/scenario_simulator_v2/blob/729e4e6372cdba60e377ae097d032905b80763a9/docs/developer_guide/lane_pose_calculation/GetLongitudinalDistance.md auto longitudinalDistance( const CanonicalizedLaneletPose & from, const CanonicalizedLaneletPose & to, bool include_adjacent_lanelet, bool include_opposite_direction, bool allow_lane_change, From 8bd998a01e7cf8993be52c5c661db83e60b129a4 Mon Sep 17 00:00:00 2001 From: Dawid Moszynski Date: Tue, 13 Aug 2024 11:14:30 +0200 Subject: [PATCH 117/304] ref(behavior_tree): remove unused variable --- .../include/behavior_tree_plugin/action_node.hpp | 1 - 1 file changed, 1 deletion(-) diff --git a/simulation/behavior_tree_plugin/include/behavior_tree_plugin/action_node.hpp b/simulation/behavior_tree_plugin/include/behavior_tree_plugin/action_node.hpp index d167045dfb0..67d0059618c 100644 --- a/simulation/behavior_tree_plugin/include/behavior_tree_plugin/action_node.hpp +++ b/simulation/behavior_tree_plugin/include/behavior_tree_plugin/action_node.hpp @@ -118,7 +118,6 @@ class ActionNode : public BT::ActionNodeBase double step_time; double default_matching_distance_for_lanelet_pose_calculation; std::optional target_speed; - std::shared_ptr non_canonicalized_updated_status; EntityStatusDict other_entity_status; lanelet::Ids route_lanelets; From 1e87af8407913d9c48529e942b87e4629b9800a8 Mon Sep 17 00:00:00 2001 From: Masaya Kataoka Date: Wed, 14 Aug 2024 15:38:46 +0900 Subject: [PATCH 118/304] update push flag Signed-off-by: Masaya Kataoka --- .github/workflows/Docekr.yaml | 1 + 1 file changed, 1 insertion(+) diff --git a/.github/workflows/Docekr.yaml b/.github/workflows/Docekr.yaml index 0736749f2d0..8ebc3e4ff57 100644 --- a/.github/workflows/Docekr.yaml +++ b/.github/workflows/Docekr.yaml @@ -5,6 +5,7 @@ on: - master push: tags: + - '*.*.*' jobs: push_docker: From 7463271f3da633c71095d3955efc3bedabb5fc5c Mon Sep 17 00:00:00 2001 From: Masaya Kataoka Date: Wed, 14 Aug 2024 15:40:07 +0900 Subject: [PATCH 119/304] remove debug step Signed-off-by: Masaya Kataoka --- .github/workflows/Docekr.yaml | 2 -- 1 file changed, 2 deletions(-) diff --git a/.github/workflows/Docekr.yaml b/.github/workflows/Docekr.yaml index 8ebc3e4ff57..8344abc4f21 100644 --- a/.github/workflows/Docekr.yaml +++ b/.github/workflows/Docekr.yaml @@ -21,8 +21,6 @@ jobs: # See also https://github.com/tier4/scenario_simulator_v2/pull/1295 # arch: [amd64, arm64] steps: - - name: echo github.event_name - run: echo '${{ github.event_name }}' - name: Free Disk Space (Ubuntu) uses: jlumbroso/free-disk-space@main with: From ef1914883be7c7def04395d34bdb565ad3cf35d3 Mon Sep 17 00:00:00 2001 From: Masaya Kataoka Date: Wed, 14 Aug 2024 16:07:30 +0900 Subject: [PATCH 120/304] remove \n Signed-off-by: Masaya Kataoka --- .../include/random_test_runner/data_types.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/test_runner/random_test_runner/include/random_test_runner/data_types.hpp b/test_runner/random_test_runner/include/random_test_runner/data_types.hpp index b6dbf773b5a..d79e8e03055 100644 --- a/test_runner/random_test_runner/include/random_test_runner/data_types.hpp +++ b/test_runner/random_test_runner/include/random_test_runner/data_types.hpp @@ -166,7 +166,7 @@ struct fmt::formatter fmt::format_to( ctx.out(), "ego_start_position: {} ego_goal_position: {} " - "ego_goal_pose: {}\nnpc_descriptions:", + "ego_goal_pose: {} npc_descriptions:", v.ego_start_position, v.ego_goal_position, v.ego_goal_pose); for (size_t idx = 0; idx < v.npcs_descriptions.size(); idx++) { fmt::format_to(ctx.out(), "[{}]: {}\n", idx, v.npcs_descriptions[idx]); From 0c257cf180c2d6a48683b6adf548998eb14f9f55 Mon Sep 17 00:00:00 2001 From: Masaya Kataoka Date: Thu, 15 Aug 2024 15:51:05 +0900 Subject: [PATCH 121/304] configure triggers Signed-off-by: Masaya Kataoka --- .github/workflows/Docekr.yaml | 14 +++++++++++--- 1 file changed, 11 insertions(+), 3 deletions(-) diff --git a/.github/workflows/Docekr.yaml b/.github/workflows/Docekr.yaml index 8344abc4f21..e32e78737a5 100644 --- a/.github/workflows/Docekr.yaml +++ b/.github/workflows/Docekr.yaml @@ -1,11 +1,19 @@ name: Docker on: pull_request: - branches: - - master + paths: + - "**" + - "!docs/**" + - "!README.md" + - "!CONTRIBUTING.md" + - "!.github/**" + - ".github/workflows/Docker.yaml" + - "!mkdocs.yml" + - "!pyproject.toml" + - "!poetry.lock" push: tags: - - '*.*.*' + - '*' jobs: push_docker: From 8abcdf0b9f3b18fc66d96024e45686368d67cbb3 Mon Sep 17 00:00:00 2001 From: Masaya Kataoka Date: Thu, 15 Aug 2024 15:53:45 +0900 Subject: [PATCH 122/304] empty commit Signed-off-by: Masaya Kataoka From bdf88fb65fd2a2e3a0c8a9603ed43818bcb7c003 Mon Sep 17 00:00:00 2001 From: Masaya Kataoka Date: Thu, 15 Aug 2024 16:21:16 +0900 Subject: [PATCH 123/304] fix timestamp in status_with_trajectory Signed-off-by: Masaya Kataoka --- simulation/traffic_simulator/src/entity/entity_manager.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/simulation/traffic_simulator/src/entity/entity_manager.cpp b/simulation/traffic_simulator/src/entity/entity_manager.cpp index ca1e411ddc0..70ae4131f79 100644 --- a/simulation/traffic_simulator/src/entity/entity_manager.cpp +++ b/simulation/traffic_simulator/src/entity/entity_manager.cpp @@ -440,7 +440,7 @@ void EntityManager::update(const double current_time, const double step_time) } status_with_trajectory.status = static_cast(status); status_with_trajectory.name = name; - status_with_trajectory.time = current_time + step_time; + status_with_trajectory.time = current_time; status_array_msg.data.emplace_back(status_with_trajectory); } entity_status_array_pub_ptr_->publish(status_array_msg); From 0ccbfc468595244ca370c945b9c7556012b40061 Mon Sep 17 00:00:00 2001 From: Masaya Kataoka Date: Thu, 15 Aug 2024 16:22:57 +0900 Subject: [PATCH 124/304] fix timestamp Signed-off-by: Masaya Kataoka --- simulation/traffic_simulator/src/entity/entity_manager.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/simulation/traffic_simulator/src/entity/entity_manager.cpp b/simulation/traffic_simulator/src/entity/entity_manager.cpp index 70ae4131f79..17a89ddf6f4 100644 --- a/simulation/traffic_simulator/src/entity/entity_manager.cpp +++ b/simulation/traffic_simulator/src/entity/entity_manager.cpp @@ -439,8 +439,9 @@ void EntityManager::update(const double current_time, const double step_time) status_with_trajectory.obstacle_find = false; } status_with_trajectory.status = static_cast(status); + status_with_trajectory.status.time = current_time + step_time; status_with_trajectory.name = name; - status_with_trajectory.time = current_time; + status_with_trajectory.time = current_time + step_time; status_array_msg.data.emplace_back(status_with_trajectory); } entity_status_array_pub_ptr_->publish(status_array_msg); From d277bdd7e2e5af62bb02f854d836376ab85463f4 Mon Sep 17 00:00:00 2001 From: Masaya Kataoka Date: Fri, 16 Aug 2024 14:54:12 +0900 Subject: [PATCH 125/304] fix interpolate ration calculation Signed-off-by: Masaya Kataoka --- simulation/do_nothing_plugin/src/plugin.cpp | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/simulation/do_nothing_plugin/src/plugin.cpp b/simulation/do_nothing_plugin/src/plugin.cpp index ca84dc72406..f606392fb9a 100644 --- a/simulation/do_nothing_plugin/src/plugin.cpp +++ b/simulation/do_nothing_plugin/src/plugin.cpp @@ -111,10 +111,14 @@ auto interpolateEntityStatusFromPolylineTrajectory( return interpolated_entity_status; }; - if ((current_time + step_time) <= trajectory->shape.vertices.begin()->time) { + if ( + (current_time + step_time) <= + (trajectory->base_time + trajectory->shape.vertices.begin()->time)) { return std::nullopt; } - if (trajectory->shape.vertices.back().time <= (current_time + step_time)) { + if ( + (trajectory->base_time + trajectory->shape.vertices.back().time) <= + (current_time + step_time)) { return interpolate_entity_status( 1, *std::prev(trajectory->shape.vertices.end(), 2), *std::prev(trajectory->shape.vertices.end(), 1)); From 1d219827a28b82a5d0359c0918862e6b0a7c4d2a Mon Sep 17 00:00:00 2001 From: Release Bot Date: Mon, 19 Aug 2024 05:42:43 +0000 Subject: [PATCH 126/304] Bump version of scenario_simulator_v2 from version 3.4.2 to version 3.4.3 --- common/math/arithmetic/CHANGELOG.rst | 3 +++ common/math/arithmetic/package.xml | 2 +- common/math/geometry/CHANGELOG.rst | 3 +++ common/math/geometry/package.xml | 2 +- common/scenario_simulator_exception/CHANGELOG.rst | 3 +++ common/scenario_simulator_exception/package.xml | 2 +- common/simple_junit/CHANGELOG.rst | 3 +++ common/simple_junit/package.xml | 2 +- common/status_monitor/CHANGELOG.rst | 3 +++ common/status_monitor/package.xml | 2 +- external/concealer/CHANGELOG.rst | 3 +++ external/concealer/package.xml | 2 +- external/embree_vendor/CHANGELOG.rst | 3 +++ external/embree_vendor/package.xml | 2 +- map/kashiwanoha_map/CHANGELOG.rst | 3 +++ map/kashiwanoha_map/package.xml | 2 +- map/simple_cross_map/CHANGELOG.rst | 3 +++ map/simple_cross_map/package.xml | 2 +- mock/cpp_mock_scenarios/CHANGELOG.rst | 7 +++++++ mock/cpp_mock_scenarios/package.xml | 2 +- .../openscenario_experimental_catalog/CHANGELOG.rst | 3 +++ openscenario/openscenario_experimental_catalog/package.xml | 2 +- openscenario/openscenario_interpreter/CHANGELOG.rst | 3 +++ openscenario/openscenario_interpreter/package.xml | 2 +- .../openscenario_interpreter_example/CHANGELOG.rst | 3 +++ openscenario/openscenario_interpreter_example/package.xml | 2 +- openscenario/openscenario_interpreter_msgs/CHANGELOG.rst | 3 +++ openscenario/openscenario_interpreter_msgs/package.xml | 2 +- openscenario/openscenario_preprocessor/CHANGELOG.rst | 3 +++ openscenario/openscenario_preprocessor/package.xml | 2 +- openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst | 3 +++ openscenario/openscenario_preprocessor_msgs/package.xml | 2 +- openscenario/openscenario_utility/CHANGELOG.rst | 3 +++ openscenario/openscenario_utility/package.xml | 2 +- openscenario/openscenario_validator/CHANGELOG.rst | 3 +++ openscenario/openscenario_validator/package.xml | 2 +- rviz_plugins/openscenario_visualization/CHANGELOG.rst | 3 +++ rviz_plugins/openscenario_visualization/package.xml | 2 +- .../real_time_factor_control_rviz_plugin/CHANGELOG.rst | 3 +++ .../real_time_factor_control_rviz_plugin/package.xml | 2 +- scenario_simulator_v2/CHANGELOG.rst | 3 +++ scenario_simulator_v2/package.xml | 2 +- simulation/behavior_tree_plugin/CHANGELOG.rst | 3 +++ simulation/behavior_tree_plugin/package.xml | 2 +- simulation/do_nothing_plugin/CHANGELOG.rst | 3 +++ simulation/do_nothing_plugin/package.xml | 2 +- simulation/simple_sensor_simulator/CHANGELOG.rst | 3 +++ simulation/simple_sensor_simulator/package.xml | 2 +- simulation/simulation_interface/CHANGELOG.rst | 3 +++ simulation/simulation_interface/package.xml | 2 +- simulation/traffic_simulator/CHANGELOG.rst | 3 +++ simulation/traffic_simulator/package.xml | 2 +- simulation/traffic_simulator_msgs/CHANGELOG.rst | 3 +++ simulation/traffic_simulator_msgs/package.xml | 2 +- test_runner/random_test_runner/CHANGELOG.rst | 3 +++ test_runner/random_test_runner/package.xml | 2 +- test_runner/scenario_test_runner/CHANGELOG.rst | 3 +++ test_runner/scenario_test_runner/package.xml | 2 +- 58 files changed, 120 insertions(+), 29 deletions(-) diff --git a/common/math/arithmetic/CHANGELOG.rst b/common/math/arithmetic/CHANGELOG.rst index 36bf2adb8b8..1eeb23b4df2 100644 --- a/common/math/arithmetic/CHANGELOG.rst +++ b/common/math/arithmetic/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package arithmetic * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.3 (2024-08-19) +------------------ + 3.4.2 (2024-08-05) ------------------ * Merge commit 'c1cab6eb1ece2df58982f50a78fef5a5ecaa7234' into doc/longitudinal-control diff --git a/common/math/arithmetic/package.xml b/common/math/arithmetic/package.xml index f533b05d41f..29d6d08c935 100644 --- a/common/math/arithmetic/package.xml +++ b/common/math/arithmetic/package.xml @@ -2,7 +2,7 @@ arithmetic - 3.4.2 + 3.4.3 arithmetic library for scenario_simulator_v2 Tatsuya Yamasaki Apache License 2.0 diff --git a/common/math/geometry/CHANGELOG.rst b/common/math/geometry/CHANGELOG.rst index 96ce8ab8d52..954697a1319 100644 --- a/common/math/geometry/CHANGELOG.rst +++ b/common/math/geometry/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package geometry * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.3 (2024-08-19) +------------------ + 3.4.2 (2024-08-05) ------------------ * Merge commit 'c1cab6eb1ece2df58982f50a78fef5a5ecaa7234' into doc/longitudinal-control diff --git a/common/math/geometry/package.xml b/common/math/geometry/package.xml index dbfe14571f1..0dea6c489d9 100644 --- a/common/math/geometry/package.xml +++ b/common/math/geometry/package.xml @@ -2,7 +2,7 @@ geometry - 3.4.2 + 3.4.3 geometry math library for scenario_simulator_v2 application Masaya Kataoka Apache License 2.0 diff --git a/common/scenario_simulator_exception/CHANGELOG.rst b/common/scenario_simulator_exception/CHANGELOG.rst index b6ce0b2ba89..ab65d5a5863 100644 --- a/common/scenario_simulator_exception/CHANGELOG.rst +++ b/common/scenario_simulator_exception/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package scenario_simulator_exception * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.3 (2024-08-19) +------------------ + 3.4.2 (2024-08-05) ------------------ * Merge commit 'c1cab6eb1ece2df58982f50a78fef5a5ecaa7234' into doc/longitudinal-control diff --git a/common/scenario_simulator_exception/package.xml b/common/scenario_simulator_exception/package.xml index 431d38cbf2d..180c3dc2d29 100644 --- a/common/scenario_simulator_exception/package.xml +++ b/common/scenario_simulator_exception/package.xml @@ -2,7 +2,7 @@ scenario_simulator_exception - 3.4.2 + 3.4.3 Exception types for scenario simulator Tatsuya Yamasaki Apache License 2.0 diff --git a/common/simple_junit/CHANGELOG.rst b/common/simple_junit/CHANGELOG.rst index e43c26c2ef6..563363b4b19 100644 --- a/common/simple_junit/CHANGELOG.rst +++ b/common/simple_junit/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package junit_exporter * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.3 (2024-08-19) +------------------ + 3.4.2 (2024-08-05) ------------------ * Merge commit 'c1cab6eb1ece2df58982f50a78fef5a5ecaa7234' into doc/longitudinal-control diff --git a/common/simple_junit/package.xml b/common/simple_junit/package.xml index 6386b24a4a0..32c55fc3f56 100644 --- a/common/simple_junit/package.xml +++ b/common/simple_junit/package.xml @@ -2,7 +2,7 @@ simple_junit - 3.4.2 + 3.4.3 Lightweight JUnit library for ROS 2 Masaya Kataoka Tatsuya Yamasaki diff --git a/common/status_monitor/CHANGELOG.rst b/common/status_monitor/CHANGELOG.rst index 6149898fb8c..c9006e3918b 100644 --- a/common/status_monitor/CHANGELOG.rst +++ b/common/status_monitor/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package status_monitor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.3 (2024-08-19) +------------------ + 3.4.2 (2024-08-05) ------------------ * Merge commit 'c1cab6eb1ece2df58982f50a78fef5a5ecaa7234' into doc/longitudinal-control diff --git a/common/status_monitor/package.xml b/common/status_monitor/package.xml index 556364b8c62..b013d229f3b 100644 --- a/common/status_monitor/package.xml +++ b/common/status_monitor/package.xml @@ -2,7 +2,7 @@ status_monitor - 3.4.2 + 3.4.3 none Tatsuya Yamasaki Apache License 2.0 diff --git a/external/concealer/CHANGELOG.rst b/external/concealer/CHANGELOG.rst index f2690904d67..a58fe96b161 100644 --- a/external/concealer/CHANGELOG.rst +++ b/external/concealer/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package concealer * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.3 (2024-08-19) +------------------ + 3.4.2 (2024-08-05) ------------------ * Merge commit 'c1cab6eb1ece2df58982f50a78fef5a5ecaa7234' into doc/longitudinal-control diff --git a/external/concealer/package.xml b/external/concealer/package.xml index 79c73bc9be2..36735099f96 100644 --- a/external/concealer/package.xml +++ b/external/concealer/package.xml @@ -2,7 +2,7 @@ concealer - 3.4.2 + 3.4.3 Provides a class 'Autoware' to conceal miscellaneous things to simplify Autoware management of the simulator. Tatsuya Yamasaki Apache License 2.0 diff --git a/external/embree_vendor/CHANGELOG.rst b/external/embree_vendor/CHANGELOG.rst index f938dc27fa1..b8bbff4cab1 100644 --- a/external/embree_vendor/CHANGELOG.rst +++ b/external/embree_vendor/CHANGELOG.rst @@ -24,6 +24,9 @@ Changelog for package embree_vendor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.3 (2024-08-19) +------------------ + 3.4.2 (2024-08-05) ------------------ * Merge commit 'c1cab6eb1ece2df58982f50a78fef5a5ecaa7234' into doc/longitudinal-control diff --git a/external/embree_vendor/package.xml b/external/embree_vendor/package.xml index 15568e6da44..f663d103f1a 100644 --- a/external/embree_vendor/package.xml +++ b/external/embree_vendor/package.xml @@ -2,7 +2,7 @@ embree_vendor - 3.4.2 + 3.4.3 vendor packages for intel raytracing kernel library masaya Apache 2.0 diff --git a/map/kashiwanoha_map/CHANGELOG.rst b/map/kashiwanoha_map/CHANGELOG.rst index abdc07a51be..2fed4769185 100644 --- a/map/kashiwanoha_map/CHANGELOG.rst +++ b/map/kashiwanoha_map/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package kashiwanoha_map * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.3 (2024-08-19) +------------------ + 3.4.2 (2024-08-05) ------------------ * Merge commit 'c1cab6eb1ece2df58982f50a78fef5a5ecaa7234' into doc/longitudinal-control diff --git a/map/kashiwanoha_map/package.xml b/map/kashiwanoha_map/package.xml index 6ef23698055..ebbc0089807 100644 --- a/map/kashiwanoha_map/package.xml +++ b/map/kashiwanoha_map/package.xml @@ -2,7 +2,7 @@ kashiwanoha_map - 3.4.2 + 3.4.3 map package for kashiwanoha Masaya Kataoka Apache License 2.0 diff --git a/map/simple_cross_map/CHANGELOG.rst b/map/simple_cross_map/CHANGELOG.rst index dbdbd51742d..d0f9daf2610 100644 --- a/map/simple_cross_map/CHANGELOG.rst +++ b/map/simple_cross_map/CHANGELOG.rst @@ -9,6 +9,9 @@ Changelog for package simple_cross_map * Merge branch 'master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.3 (2024-08-19) +------------------ + 3.4.2 (2024-08-05) ------------------ * Merge commit 'c1cab6eb1ece2df58982f50a78fef5a5ecaa7234' into doc/longitudinal-control diff --git a/map/simple_cross_map/package.xml b/map/simple_cross_map/package.xml index 7a08689d18a..f6a38767c1f 100644 --- a/map/simple_cross_map/package.xml +++ b/map/simple_cross_map/package.xml @@ -2,7 +2,7 @@ simple_cross_map - 3.4.2 + 3.4.3 map package for simple cross Masaya Kataoka Apache License 2.0 diff --git a/mock/cpp_mock_scenarios/CHANGELOG.rst b/mock/cpp_mock_scenarios/CHANGELOG.rst index ee2ea566a0a..89b11d52e29 100644 --- a/mock/cpp_mock_scenarios/CHANGELOG.rst +++ b/mock/cpp_mock_scenarios/CHANGELOG.rst @@ -21,6 +21,13 @@ Changelog for package cpp_mock_scenarios * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.3 (2024-08-19) +------------------ +* Merge pull request `#1339 `_ from tier4/fix/ament_auto_package + fix CONFIG_EXTRAS argument of ament_auto_package macro +* fix ament_auto_package macro +* Contributors: Masaya Kataoka + 3.4.2 (2024-08-05) ------------------ * Merge commit 'c1cab6eb1ece2df58982f50a78fef5a5ecaa7234' into doc/longitudinal-control diff --git a/mock/cpp_mock_scenarios/package.xml b/mock/cpp_mock_scenarios/package.xml index 84f86210815..a19b7761245 100644 --- a/mock/cpp_mock_scenarios/package.xml +++ b/mock/cpp_mock_scenarios/package.xml @@ -2,7 +2,7 @@ cpp_mock_scenarios - 3.4.2 + 3.4.3 C++ mock scenarios masaya Apache License 2.0 diff --git a/openscenario/openscenario_experimental_catalog/CHANGELOG.rst b/openscenario/openscenario_experimental_catalog/CHANGELOG.rst index fc47e7693bb..23882ec8753 100644 --- a/openscenario/openscenario_experimental_catalog/CHANGELOG.rst +++ b/openscenario/openscenario_experimental_catalog/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package openscenario_experimental_catalog * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.3 (2024-08-19) +------------------ + 3.4.2 (2024-08-05) ------------------ * Merge commit 'c1cab6eb1ece2df58982f50a78fef5a5ecaa7234' into doc/longitudinal-control diff --git a/openscenario/openscenario_experimental_catalog/package.xml b/openscenario/openscenario_experimental_catalog/package.xml index 8e3160af2e6..9e2d1db51f5 100644 --- a/openscenario/openscenario_experimental_catalog/package.xml +++ b/openscenario/openscenario_experimental_catalog/package.xml @@ -2,7 +2,7 @@ openscenario_experimental_catalog - 3.4.2 + 3.4.3 TIER IV experimental catalogs for OpenSCENARIO Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter/CHANGELOG.rst b/openscenario/openscenario_interpreter/CHANGELOG.rst index 5e8546533e3..1634255e7ce 100644 --- a/openscenario/openscenario_interpreter/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter/CHANGELOG.rst @@ -32,6 +32,9 @@ Changelog for package openscenario_interpreter * add publish_empty_context parameter * Contributors: Masaya Kataoka +3.4.3 (2024-08-19) +------------------ + 3.4.2 (2024-08-05) ------------------ * Merge branch 'master' into doc/longitudinal-control diff --git a/openscenario/openscenario_interpreter/package.xml b/openscenario/openscenario_interpreter/package.xml index 00d7949643c..b3395f2d1d1 100644 --- a/openscenario/openscenario_interpreter/package.xml +++ b/openscenario/openscenario_interpreter/package.xml @@ -2,7 +2,7 @@ openscenario_interpreter - 3.4.2 + 3.4.3 OpenSCENARIO 1.2.0 interpreter package for Autoware Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter_example/CHANGELOG.rst b/openscenario/openscenario_interpreter_example/CHANGELOG.rst index 6a6b0242dc8..60512ecdf9e 100644 --- a/openscenario/openscenario_interpreter_example/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter_example/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package openscenario_interpreter_example * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.3 (2024-08-19) +------------------ + 3.4.2 (2024-08-05) ------------------ * Merge commit 'c1cab6eb1ece2df58982f50a78fef5a5ecaa7234' into doc/longitudinal-control diff --git a/openscenario/openscenario_interpreter_example/package.xml b/openscenario/openscenario_interpreter_example/package.xml index 06c82717359..448f23702be 100644 --- a/openscenario/openscenario_interpreter_example/package.xml +++ b/openscenario/openscenario_interpreter_example/package.xml @@ -3,7 +3,7 @@ openscenario_interpreter_example - 3.4.2 + 3.4.3 Examples for some TIER IV OpenSCENARIO Interpreter's features Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst b/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst index 1c8ae389b5c..575b7303d34 100644 --- a/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package openscenario_interpreter_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.3 (2024-08-19) +------------------ + 3.4.2 (2024-08-05) ------------------ * Merge commit 'c1cab6eb1ece2df58982f50a78fef5a5ecaa7234' into doc/longitudinal-control diff --git a/openscenario/openscenario_interpreter_msgs/package.xml b/openscenario/openscenario_interpreter_msgs/package.xml index 697d6261d74..a0e4a546396 100644 --- a/openscenario/openscenario_interpreter_msgs/package.xml +++ b/openscenario/openscenario_interpreter_msgs/package.xml @@ -2,7 +2,7 @@ openscenario_interpreter_msgs - 3.4.2 + 3.4.3 ROS message types for package openscenario_interpreter Yamasaki Tatsuya Apache License 2.0 diff --git a/openscenario/openscenario_preprocessor/CHANGELOG.rst b/openscenario/openscenario_preprocessor/CHANGELOG.rst index 5b9c6ab78ad..788c4453052 100644 --- a/openscenario/openscenario_preprocessor/CHANGELOG.rst +++ b/openscenario/openscenario_preprocessor/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package openscenario_preprocessor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.3 (2024-08-19) +------------------ + 3.4.2 (2024-08-05) ------------------ * Merge commit 'c1cab6eb1ece2df58982f50a78fef5a5ecaa7234' into doc/longitudinal-control diff --git a/openscenario/openscenario_preprocessor/package.xml b/openscenario/openscenario_preprocessor/package.xml index a1bcfe5d27d..38413a3438f 100644 --- a/openscenario/openscenario_preprocessor/package.xml +++ b/openscenario/openscenario_preprocessor/package.xml @@ -3,7 +3,7 @@ openscenario_preprocessor - 3.4.2 + 3.4.3 Example package for TIER IV OpenSCENARIO Interpreter Kotaro Yoshimoto Apache License 2.0 diff --git a/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst b/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst index d85a9885d89..b2ed33a0052 100644 --- a/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst +++ b/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package openscenario_preprocessor_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.3 (2024-08-19) +------------------ + 3.4.2 (2024-08-05) ------------------ * Merge commit 'c1cab6eb1ece2df58982f50a78fef5a5ecaa7234' into doc/longitudinal-control diff --git a/openscenario/openscenario_preprocessor_msgs/package.xml b/openscenario/openscenario_preprocessor_msgs/package.xml index 6efd1246130..eb63629f883 100644 --- a/openscenario/openscenario_preprocessor_msgs/package.xml +++ b/openscenario/openscenario_preprocessor_msgs/package.xml @@ -2,7 +2,7 @@ openscenario_preprocessor_msgs - 3.4.2 + 3.4.3 ROS message types for package openscenario_preprocessor Kotaro Yoshimoto Apache License 2.0 diff --git a/openscenario/openscenario_utility/CHANGELOG.rst b/openscenario/openscenario_utility/CHANGELOG.rst index f5447823350..95f39c1d2ad 100644 --- a/openscenario/openscenario_utility/CHANGELOG.rst +++ b/openscenario/openscenario_utility/CHANGELOG.rst @@ -24,6 +24,9 @@ Changelog for package openscenario_utility * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.3 (2024-08-19) +------------------ + 3.4.2 (2024-08-05) ------------------ * Merge commit 'c1cab6eb1ece2df58982f50a78fef5a5ecaa7234' into doc/longitudinal-control diff --git a/openscenario/openscenario_utility/package.xml b/openscenario/openscenario_utility/package.xml index 01b23b31e5f..3f817de2a6e 100644 --- a/openscenario/openscenario_utility/package.xml +++ b/openscenario/openscenario_utility/package.xml @@ -2,7 +2,7 @@ openscenario_utility - 3.4.2 + 3.4.3 Utility tools for ASAM OpenSCENARIO 1.2.0 Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_validator/CHANGELOG.rst b/openscenario/openscenario_validator/CHANGELOG.rst index 8e1f1f599ec..78a9c047648 100644 --- a/openscenario/openscenario_validator/CHANGELOG.rst +++ b/openscenario/openscenario_validator/CHANGELOG.rst @@ -10,6 +10,9 @@ Changelog for package openscenario_validator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.3 (2024-08-19) +------------------ + 3.4.2 (2024-08-05) ------------------ * Merge commit 'c1cab6eb1ece2df58982f50a78fef5a5ecaa7234' into doc/longitudinal-control diff --git a/openscenario/openscenario_validator/package.xml b/openscenario/openscenario_validator/package.xml index bd21a92e59f..68cc76df948 100644 --- a/openscenario/openscenario_validator/package.xml +++ b/openscenario/openscenario_validator/package.xml @@ -2,7 +2,7 @@ openscenario_validator - 3.4.2 + 3.4.3 Validator for OpenSCENARIO 1.3 Kotaro Yoshimoto Apache License 2.0 diff --git a/rviz_plugins/openscenario_visualization/CHANGELOG.rst b/rviz_plugins/openscenario_visualization/CHANGELOG.rst index b3e1b9e5c14..abf9e183b17 100644 --- a/rviz_plugins/openscenario_visualization/CHANGELOG.rst +++ b/rviz_plugins/openscenario_visualization/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package openscenario_visualization * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.3 (2024-08-19) +------------------ + 3.4.2 (2024-08-05) ------------------ * Merge commit 'c1cab6eb1ece2df58982f50a78fef5a5ecaa7234' into doc/longitudinal-control diff --git a/rviz_plugins/openscenario_visualization/package.xml b/rviz_plugins/openscenario_visualization/package.xml index fd3e3bb1708..88b06431162 100644 --- a/rviz_plugins/openscenario_visualization/package.xml +++ b/rviz_plugins/openscenario_visualization/package.xml @@ -2,7 +2,7 @@ openscenario_visualization - 3.4.2 + 3.4.3 Visualization tools for simulation results Masaya Kataoka Kyoichi Sugahara diff --git a/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst b/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst index 3c00a040c3f..23e52eddd1d 100644 --- a/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst +++ b/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package real_time_factor_control_rviz_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.3 (2024-08-19) +------------------ + 3.4.2 (2024-08-05) ------------------ * Merge commit 'c1cab6eb1ece2df58982f50a78fef5a5ecaa7234' into doc/longitudinal-control diff --git a/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml b/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml index 115f07ed1c1..6574e60f8e7 100644 --- a/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml +++ b/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml @@ -2,7 +2,7 @@ real_time_factor_control_rviz_plugin - 3.4.2 + 3.4.3 Slider controlling real time factor value. Paweł Lech Apache License 2.0 diff --git a/scenario_simulator_v2/CHANGELOG.rst b/scenario_simulator_v2/CHANGELOG.rst index b263feb86c0..7bcb0e54782 100644 --- a/scenario_simulator_v2/CHANGELOG.rst +++ b/scenario_simulator_v2/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package scenario_simulator_v2 * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.3 (2024-08-19) +------------------ + 3.4.2 (2024-08-05) ------------------ * Merge commit 'c1cab6eb1ece2df58982f50a78fef5a5ecaa7234' into doc/longitudinal-control diff --git a/scenario_simulator_v2/package.xml b/scenario_simulator_v2/package.xml index 0f087fc6af4..e755afeabf1 100644 --- a/scenario_simulator_v2/package.xml +++ b/scenario_simulator_v2/package.xml @@ -2,7 +2,7 @@ scenario_simulator_v2 - 3.4.2 + 3.4.3 scenario testing framework for Autoware Masaya Kataoka Apache License 2.0 diff --git a/simulation/behavior_tree_plugin/CHANGELOG.rst b/simulation/behavior_tree_plugin/CHANGELOG.rst index c8f6ccd7f2b..450e562ab03 100644 --- a/simulation/behavior_tree_plugin/CHANGELOG.rst +++ b/simulation/behavior_tree_plugin/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package behavior_tree_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.3 (2024-08-19) +------------------ + 3.4.2 (2024-08-05) ------------------ * Merge commit 'c1cab6eb1ece2df58982f50a78fef5a5ecaa7234' into doc/longitudinal-control diff --git a/simulation/behavior_tree_plugin/package.xml b/simulation/behavior_tree_plugin/package.xml index 77bf5abe99b..45c763805bd 100644 --- a/simulation/behavior_tree_plugin/package.xml +++ b/simulation/behavior_tree_plugin/package.xml @@ -2,7 +2,7 @@ behavior_tree_plugin - 3.4.2 + 3.4.3 Behavior tree plugin for traffic_simulator masaya Apache 2.0 diff --git a/simulation/do_nothing_plugin/CHANGELOG.rst b/simulation/do_nothing_plugin/CHANGELOG.rst index 6fdde310518..cb54d773c58 100644 --- a/simulation/do_nothing_plugin/CHANGELOG.rst +++ b/simulation/do_nothing_plugin/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package do_nothing_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.3 (2024-08-19) +------------------ + 3.4.2 (2024-08-05) ------------------ * Merge commit 'c1cab6eb1ece2df58982f50a78fef5a5ecaa7234' into doc/longitudinal-control diff --git a/simulation/do_nothing_plugin/package.xml b/simulation/do_nothing_plugin/package.xml index c2bc7f89c43..710bce1d396 100644 --- a/simulation/do_nothing_plugin/package.xml +++ b/simulation/do_nothing_plugin/package.xml @@ -2,7 +2,7 @@ do_nothing_plugin - 3.4.2 + 3.4.3 Behavior plugin for do nothing Masaya Kataoka Apache 2.0 diff --git a/simulation/simple_sensor_simulator/CHANGELOG.rst b/simulation/simple_sensor_simulator/CHANGELOG.rst index b5f73466cc9..90542cbc3b5 100644 --- a/simulation/simple_sensor_simulator/CHANGELOG.rst +++ b/simulation/simple_sensor_simulator/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package simple_sensor_simulator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.3 (2024-08-19) +------------------ + 3.4.2 (2024-08-05) ------------------ * Merge branch 'master' into doc/longitudinal-control diff --git a/simulation/simple_sensor_simulator/package.xml b/simulation/simple_sensor_simulator/package.xml index 90bb8780465..4447456cbeb 100644 --- a/simulation/simple_sensor_simulator/package.xml +++ b/simulation/simple_sensor_simulator/package.xml @@ -1,7 +1,7 @@ simple_sensor_simulator - 3.4.2 + 3.4.3 simple_sensor_simulator package masaya kataoka diff --git a/simulation/simulation_interface/CHANGELOG.rst b/simulation/simulation_interface/CHANGELOG.rst index 1ffa0eab9da..a04bab28d96 100644 --- a/simulation/simulation_interface/CHANGELOG.rst +++ b/simulation/simulation_interface/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package simulation_interface * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.3 (2024-08-19) +------------------ + 3.4.2 (2024-08-05) ------------------ * Merge branch 'master' into doc/longitudinal-control diff --git a/simulation/simulation_interface/package.xml b/simulation/simulation_interface/package.xml index 885589fd270..a14ee2e6843 100644 --- a/simulation/simulation_interface/package.xml +++ b/simulation/simulation_interface/package.xml @@ -2,7 +2,7 @@ simulation_interface - 3.4.2 + 3.4.3 packages to define interface between simulator and scenario interpreter Masaya Kataoka Apache License 2.0 diff --git a/simulation/traffic_simulator/CHANGELOG.rst b/simulation/traffic_simulator/CHANGELOG.rst index e3e93704b38..47c587abe52 100644 --- a/simulation/traffic_simulator/CHANGELOG.rst +++ b/simulation/traffic_simulator/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package traffic_simulator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.3 (2024-08-19) +------------------ + 3.4.2 (2024-08-05) ------------------ * Merge branch 'master' into doc/longitudinal-control diff --git a/simulation/traffic_simulator/package.xml b/simulation/traffic_simulator/package.xml index b2c8b089034..87a2384992a 100644 --- a/simulation/traffic_simulator/package.xml +++ b/simulation/traffic_simulator/package.xml @@ -1,7 +1,7 @@ traffic_simulator - 3.4.2 + 3.4.3 control traffic flow masaya kataoka diff --git a/simulation/traffic_simulator_msgs/CHANGELOG.rst b/simulation/traffic_simulator_msgs/CHANGELOG.rst index 4c0b74852aa..cbe4e3fa8fa 100644 --- a/simulation/traffic_simulator_msgs/CHANGELOG.rst +++ b/simulation/traffic_simulator_msgs/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package openscenario_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.3 (2024-08-19) +------------------ + 3.4.2 (2024-08-05) ------------------ * Merge commit 'c1cab6eb1ece2df58982f50a78fef5a5ecaa7234' into doc/longitudinal-control diff --git a/simulation/traffic_simulator_msgs/package.xml b/simulation/traffic_simulator_msgs/package.xml index 2c1dedb6696..c0c9a3d8074 100644 --- a/simulation/traffic_simulator_msgs/package.xml +++ b/simulation/traffic_simulator_msgs/package.xml @@ -2,7 +2,7 @@ traffic_simulator_msgs - 3.4.2 + 3.4.3 ROS messages for openscenario Masaya Kataoka Apache License 2.0 diff --git a/test_runner/random_test_runner/CHANGELOG.rst b/test_runner/random_test_runner/CHANGELOG.rst index 6a1299f1137..9a783f89d38 100644 --- a/test_runner/random_test_runner/CHANGELOG.rst +++ b/test_runner/random_test_runner/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package random_test_runner * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.3 (2024-08-19) +------------------ + 3.4.2 (2024-08-05) ------------------ * Merge commit 'c1cab6eb1ece2df58982f50a78fef5a5ecaa7234' into doc/longitudinal-control diff --git a/test_runner/random_test_runner/package.xml b/test_runner/random_test_runner/package.xml index bf4e1a5bcc6..693c71ee434 100644 --- a/test_runner/random_test_runner/package.xml +++ b/test_runner/random_test_runner/package.xml @@ -2,7 +2,7 @@ random_test_runner - 3.4.2 + 3.4.3 Random behavior test runner piotr-zyskowski-rai Apache License 2.0 diff --git a/test_runner/scenario_test_runner/CHANGELOG.rst b/test_runner/scenario_test_runner/CHANGELOG.rst index d4fef8eb21c..87394569b74 100644 --- a/test_runner/scenario_test_runner/CHANGELOG.rst +++ b/test_runner/scenario_test_runner/CHANGELOG.rst @@ -35,6 +35,9 @@ Changelog for package scenario_test_runner * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.3 (2024-08-19) +------------------ + 3.4.2 (2024-08-05) ------------------ * Merge commit 'c1cab6eb1ece2df58982f50a78fef5a5ecaa7234' into doc/longitudinal-control diff --git a/test_runner/scenario_test_runner/package.xml b/test_runner/scenario_test_runner/package.xml index f88e0c3572f..64838e3fc0d 100644 --- a/test_runner/scenario_test_runner/package.xml +++ b/test_runner/scenario_test_runner/package.xml @@ -2,7 +2,7 @@ scenario_test_runner - 3.4.2 + 3.4.3 scenario test runner package Tatsuya Yamasaki Apache License 2.0 From b48ee4db8e22359c7ea7a11804623a743b4203cd Mon Sep 17 00:00:00 2001 From: Masaya Kataoka Date: Mon, 19 Aug 2024 14:51:52 +0900 Subject: [PATCH 127/304] change trigger Signed-off-by: Masaya Kataoka --- .github/workflows/Docekr.yaml | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/.github/workflows/Docekr.yaml b/.github/workflows/Docekr.yaml index e32e78737a5..18ab80fa928 100644 --- a/.github/workflows/Docekr.yaml +++ b/.github/workflows/Docekr.yaml @@ -11,9 +11,9 @@ on: - "!mkdocs.yml" - "!pyproject.toml" - "!poetry.lock" - push: - tags: - - '*' + release: + types: [published] + jobs: push_docker: @@ -73,7 +73,7 @@ jobs: set: | *.cache-to=type=gha,mode=max *.cache-from=type=gha - *.tags=ghcr.io/tier4/scenario_simulator_v2:humble-${{ github.ref_name }} + *.tags=ghcr.io/tier4/scenario_simulator_v2:humble-${{ github.event.release.tag_name }} push: true targets: | ${{ matrix.rosdistro }}_base_${{ matrix.arch }} From f6b89d67023ef6ee09f7dc5b6540022b5dba6fff Mon Sep 17 00:00:00 2001 From: robomic Date: Mon, 19 Aug 2024 10:19:33 +0200 Subject: [PATCH 128/304] review changes --- .../test/src/helper/test_helper.cpp | 12 +-- .../src/traffic_lights/test_traffic_light.cpp | 73 ++++++------------- 2 files changed, 30 insertions(+), 55 deletions(-) diff --git a/simulation/traffic_simulator/test/src/helper/test_helper.cpp b/simulation/traffic_simulator/test/src/helper/test_helper.cpp index b2b352f5174..4ddfdfa28e1 100644 --- a/simulation/traffic_simulator/test/src/helper/test_helper.cpp +++ b/simulation/traffic_simulator/test/src/helper/test_helper.cpp @@ -81,8 +81,10 @@ TEST(helper, constructRPYfromQuaternion) EXPECT_VECTOR3_EQ(default_rpy, default_vec); } { - const auto vec = - geometry_msgs::build().x(-M_PI / 3.0).y(-M_PI / 6.0).z(M_PI / 2); + const auto vec = geometry_msgs::build() + .x(-M_PI / 3.0) + .y(-M_PI / 6.0) + .z(M_PI / 2.0); const auto rpy = traffic_simulator::helper::constructRPYfromQuaternion( geometry_msgs::build().x(-0.183).y(-0.5).z(0.5).w(0.683)); EXPECT_VECTOR3_NEAR(rpy, vec, 1.0e-3); @@ -100,8 +102,8 @@ TEST(helper, constructPose) .orientation( geometry_msgs::build().x(-0.183).y(-0.5).z(0.5).w(0.683)); - const auto result_pose = - traffic_simulator::helper::constructPose(43.0, 47.0, 53.0, -M_PI / 3.0, -M_PI / 6.0, M_PI / 2); + const auto result_pose = traffic_simulator::helper::constructPose( + 43.0, 47.0, 53.0, -M_PI / 3.0, -M_PI / 6.0, M_PI / 2.0); EXPECT_POSE_NEAR(result_pose, actual_pose, 1.0e-3); } @@ -130,7 +132,7 @@ TEST(helper, constructDetectionSensorConfiguration) actual_configuration.set_update_duration(3.0); const auto result_configuration = - traffic_simulator::helper::constructDetectionSensorConfiguration("ego", "test", 3); + traffic_simulator::helper::constructDetectionSensorConfiguration("ego", "test", 3.0); EXPECT_DETECTION_SENSOR_CONFIGURATION_EQ(result_configuration, actual_configuration); } diff --git a/simulation/traffic_simulator/test/src/traffic_lights/test_traffic_light.cpp b/simulation/traffic_simulator/test/src/traffic_lights/test_traffic_light.cpp index bf228bfcf71..4401334baa9 100644 --- a/simulation/traffic_simulator/test/src/traffic_lights/test_traffic_light.cpp +++ b/simulation/traffic_simulator/test/src/traffic_lights/test_traffic_light.cpp @@ -20,6 +20,12 @@ #include #include +using TrafficLight = traffic_simulator::TrafficLight; +using Color = TrafficLight::Color; +using Status = TrafficLight::Status; +using Shape = TrafficLight::Shape; +using Bulb = TrafficLight::Bulb; + int main(int argc, char ** argv) { testing::InitGoogleTest(&argc, argv); @@ -31,8 +37,6 @@ int main(int argc, char ** argv) */ TEST(Color, Color) { - using Color = traffic_simulator::TrafficLight::Color; - { const auto color = Color("green"); @@ -85,13 +89,12 @@ TEST(Color, Color) */ TEST(Color, make) { - using Color = traffic_simulator::TrafficLight::Color; { const auto color = Color::make("green"); EXPECT_TRUE(color == Color::green); EXPECT_TRUE(color.is(Color::green)); - EXPECT_TRUE(boost::lexical_cast("green") == Color::green); + EXPECT_TRUE(boost::lexical_cast(color) == Color::green); EXPECT_TRUE(boost::lexical_cast(color) == "green"); } @@ -100,7 +103,7 @@ TEST(Color, make) EXPECT_TRUE(color == Color::yellow); EXPECT_TRUE(color.is(Color::yellow)); - EXPECT_TRUE(boost::lexical_cast("yellow") == Color::yellow); + EXPECT_TRUE(boost::lexical_cast(color) == Color::yellow); EXPECT_TRUE(boost::lexical_cast(color) == "yellow"); } @@ -109,7 +112,7 @@ TEST(Color, make) EXPECT_TRUE(color == Color::red); EXPECT_TRUE(color.is(Color::red)); - EXPECT_TRUE(boost::lexical_cast("red") == Color::red); + EXPECT_TRUE(boost::lexical_cast(color) == Color::red); EXPECT_TRUE(boost::lexical_cast(color) == "red"); } @@ -118,7 +121,7 @@ TEST(Color, make) EXPECT_TRUE(color == Color::white); EXPECT_TRUE(color.is(Color::white)); - EXPECT_TRUE(boost::lexical_cast("white") == Color::white); + EXPECT_TRUE(boost::lexical_cast(color) == Color::white); EXPECT_TRUE(boost::lexical_cast(color) == "white"); } @@ -127,7 +130,7 @@ TEST(Color, make) EXPECT_TRUE(color == Color::yellow); EXPECT_TRUE(color.is(Color::yellow)); - EXPECT_TRUE(boost::lexical_cast("amber") == Color::yellow); + EXPECT_TRUE(boost::lexical_cast(color) == Color::yellow); EXPECT_TRUE(boost::lexical_cast(color) == "yellow"); } } @@ -145,8 +148,6 @@ TEST(Color, make_wrong) */ TEST(Status, Status) { - using Status = traffic_simulator::TrafficLight::Status; - { const auto status = Status("solidOn"); @@ -189,14 +190,12 @@ TEST(Status, Status) */ TEST(Status, make) { - using Status = traffic_simulator::TrafficLight::Status; - { const auto status = Status::make("solidOn"); EXPECT_TRUE(status == Status::solid_on); EXPECT_TRUE(status.is(Status::solid_on)); - EXPECT_TRUE(boost::lexical_cast("solidOn") == Status::solid_on); + EXPECT_TRUE(boost::lexical_cast(status) == Status::solid_on); EXPECT_TRUE(boost::lexical_cast(status) == "solidOn"); } @@ -205,7 +204,7 @@ TEST(Status, make) EXPECT_TRUE(status == Status::solid_off); EXPECT_TRUE(status.is(Status::solid_off)); - EXPECT_TRUE(boost::lexical_cast("solidOff") == Status::solid_off); + EXPECT_TRUE(boost::lexical_cast(status) == Status::solid_off); EXPECT_TRUE(boost::lexical_cast(status) == "solidOff"); } @@ -214,7 +213,7 @@ TEST(Status, make) EXPECT_TRUE(status == Status::flashing); EXPECT_TRUE(status.is(Status::flashing)); - EXPECT_TRUE(boost::lexical_cast("flashing") == Status::flashing); + EXPECT_TRUE(boost::lexical_cast(status) == Status::flashing); EXPECT_TRUE(boost::lexical_cast(status) == "flashing"); } @@ -223,7 +222,7 @@ TEST(Status, make) EXPECT_TRUE(status == Status::unknown); EXPECT_TRUE(status.is(Status::unknown)); - EXPECT_TRUE(boost::lexical_cast("unknown") == Status::unknown); + EXPECT_TRUE(boost::lexical_cast(status) == Status::unknown); EXPECT_TRUE(boost::lexical_cast(status) == "unknown"); } } @@ -241,8 +240,6 @@ TEST(Status, make_wrong) */ TEST(Shape, Shape) { - using Shape = traffic_simulator::TrafficLight::Shape; - { const auto shape = Shape("circle"); @@ -359,8 +356,6 @@ TEST(Shape, Shape) */ TEST(Shape, make) { - using Shape = traffic_simulator::TrafficLight::Shape; - { const auto shape = Shape::make("circle"); @@ -481,16 +476,10 @@ TEST(Shape, make_wrong) } /** - * @note Test object creation correcness. + * @note Test hashing function. An object must be assigned the same hash every time. */ -TEST(Bulb, Bulb) +TEST(Bulb, hash) { - using TrafficLight = traffic_simulator::TrafficLight; - using Color = TrafficLight::Color; - using Status = TrafficLight::Status; - using Shape = TrafficLight::Shape; - using Bulb = TrafficLight::Bulb; - // clang-format off static_assert(Bulb(Color::green, Status::solid_on, Shape::circle ).hash() == 0b0000'0000'0000'0000'0000'0000'0000'0000); static_assert(Bulb(Color::yellow, Status::solid_on, Shape::circle ).hash() == 0b0000'0001'0000'0000'0000'0000'0000'0000); @@ -513,7 +502,13 @@ TEST(Bulb, Bulb) static_assert(Bulb(Color::green, Status::solid_on, Shape::lower_right).hash() == 0b0000'0000'0000'0000'0000'0101'0000'0010); static_assert(Bulb(Color::green, Status::solid_on, Shape::upper_right).hash() == 0b0000'0000'0000'0000'0000'0011'0000'0010); // clang-format on +} +/** + * @note Test basic functionality. Test Bulb comparisons with different configurations. + */ +TEST(Bulb, is) +{ { constexpr auto bulb = Bulb(Color::red, Status::flashing, Shape::circle); @@ -583,11 +578,6 @@ TEST(Bulb, Bulb) */ TEST(Bulb, make) { - using TrafficLight = traffic_simulator::TrafficLight; - using Color = TrafficLight::Color; - using Status = TrafficLight::Status; - using Shape = TrafficLight::Shape; - using Bulb = TrafficLight::Bulb; { constexpr auto bulb = Bulb(Color::red, Status::flashing, Shape::circle); @@ -657,8 +647,6 @@ TEST(Bulb, make) */ TEST(Bulb, make_wrong) { - using Bulb = traffic_simulator::TrafficLight::Bulb; - EXPECT_THROW(Bulb("red flashing wrong_shape"), common::SyntaxError); EXPECT_THROW(Bulb("red wrong_status circle"), common::SyntaxError); EXPECT_THROW(Bulb("wrong_color flashing circle"), common::SyntaxError); @@ -671,11 +659,6 @@ TEST(Bulb, make_wrong) */ TEST(Bulb, operator_TrafficLight) { - using Color = traffic_simulator::TrafficLight::Color; - using Status = traffic_simulator::TrafficLight::Status; - using Shape = traffic_simulator::TrafficLight::Shape; - using Bulb = traffic_simulator::TrafficLight::Bulb; - { constexpr auto bulb = Bulb(Color::red, Status::flashing, Shape::circle); std::ostringstream oss; @@ -747,11 +730,6 @@ class TrafficLightTest : public testing::Test */ TEST_F(TrafficLightTest, contains_colorStatusShape) { - using TrafficLight = traffic_simulator::TrafficLight; - using Color = TrafficLight::Color; - using Status = TrafficLight::Status; - using Shape = TrafficLight::Shape; - { auto traffic_light = TrafficLight(34802, map_manager); @@ -779,11 +757,6 @@ TEST_F(TrafficLightTest, contains_colorStatusShape) */ TEST_F(TrafficLightTest, set_valid) { - using TrafficLight = traffic_simulator::TrafficLight; - using Color = TrafficLight::Color; - using Status = TrafficLight::Status; - using Shape = TrafficLight::Shape; - auto traffic_light = TrafficLight(34802, map_manager); traffic_light.set("red flashing circle, green solidOn right"); From 09e53410e5ea006de49690985402cdacd3ff7077 Mon Sep 17 00:00:00 2001 From: robomic Date: Mon, 19 Aug 2024 10:35:23 +0200 Subject: [PATCH 129/304] spellcheck --- .../test/src/traffic_lights/test_traffic_light.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/simulation/traffic_simulator/test/src/traffic_lights/test_traffic_light.cpp b/simulation/traffic_simulator/test/src/traffic_lights/test_traffic_light.cpp index 4401334baa9..6ab5ba9c6f9 100644 --- a/simulation/traffic_simulator/test/src/traffic_lights/test_traffic_light.cpp +++ b/simulation/traffic_simulator/test/src/traffic_lights/test_traffic_light.cpp @@ -33,7 +33,7 @@ int main(int argc, char ** argv) } /** - * @note Test object creation correcness. + * @note Test object creation correctness. */ TEST(Color, Color) { @@ -144,7 +144,7 @@ TEST(Color, make_wrong) } /** - * @note Test object creation correcness. + * @note Test object creation correctness. */ TEST(Status, Status) { @@ -236,7 +236,7 @@ TEST(Status, make_wrong) } /** - * @note Test object creation correcness. + * @note Test object creation correctness. */ TEST(Shape, Shape) { From 84c19dbc0baf33b2e21243325945c7c6f1e989c4 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Mon, 19 Aug 2024 18:03:58 +0900 Subject: [PATCH 130/304] refactor: use std::size_t instead of raw size_t Co-authored-by: Tatsuya Yamasaki --- simulation/traffic_simulator/src/hdmap_utils/hdmap_utils.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/simulation/traffic_simulator/src/hdmap_utils/hdmap_utils.cpp b/simulation/traffic_simulator/src/hdmap_utils/hdmap_utils.cpp index b44bd1f08de..335138ad7f8 100644 --- a/simulation/traffic_simulator/src/hdmap_utils/hdmap_utils.cpp +++ b/simulation/traffic_simulator/src/hdmap_utils/hdmap_utils.cpp @@ -224,7 +224,7 @@ auto HdMapUtils::countLaneChanges( return std::nullopt; } else { std::pair lane_changes{0, 0}; - for (size_t i = 1; i < route.size(); ++i) { + for (std::size_t i = 1; i < route.size(); ++i) { const auto & previous = route[i - 1]; const auto & current = route[i]; From dfd841be274d989be2a1b11938ba5f6f7ab18c2a Mon Sep 17 00:00:00 2001 From: robomic Date: Mon, 19 Aug 2024 11:52:04 +0200 Subject: [PATCH 131/304] isIntersect2D_collinear --- .../test/src/polygon/test_line_segment.cpp | 15 +++++++++++++++ 1 file changed, 15 insertions(+) diff --git a/common/math/geometry/test/src/polygon/test_line_segment.cpp b/common/math/geometry/test/src/polygon/test_line_segment.cpp index 9ab3829d121..0cddb807aa7 100644 --- a/common/math/geometry/test/src/polygon/test_line_segment.cpp +++ b/common/math/geometry/test/src/polygon/test_line_segment.cpp @@ -227,6 +227,21 @@ TEST(LineSegment, isIntersect2DIdentical) EXPECT_TRUE(line.isIntersect2D(line)); } +/** + * @note Test function behavior with two disjoint, collinear lines. + */ + +TEST(LineSegment, isIntersect2D_collinear) +{ + const auto line = + math::geometry::LineSegment(makePoint(-1.0, 1.0, 0.0), makePoint(1.0, 3.0, 0.0)); + + EXPECT_FALSE(line.isIntersect2D( + math::geometry::LineSegment(makePoint(3.0, 5.0, 0.0), makePoint(5.0, 7.0, 0.0)))); + EXPECT_FALSE(line.isIntersect2D( + math::geometry::LineSegment(makePoint(-3.0, -1.0, 0.0), makePoint(-1.0, 1.0, 0.0)))); +} + /** * @note Test function behavior with a point on the line. */ From 338ba5ae714add024e92776e4c208a2f1c4a87c1 Mon Sep 17 00:00:00 2001 From: robomic Date: Mon, 19 Aug 2024 15:16:55 +0200 Subject: [PATCH 132/304] remove empty line --- common/math/geometry/test/src/polygon/test_line_segment.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/common/math/geometry/test/src/polygon/test_line_segment.cpp b/common/math/geometry/test/src/polygon/test_line_segment.cpp index 0cddb807aa7..b6e7bec4f0a 100644 --- a/common/math/geometry/test/src/polygon/test_line_segment.cpp +++ b/common/math/geometry/test/src/polygon/test_line_segment.cpp @@ -230,7 +230,6 @@ TEST(LineSegment, isIntersect2DIdentical) /** * @note Test function behavior with two disjoint, collinear lines. */ - TEST(LineSegment, isIntersect2D_collinear) { const auto line = From e74ea14a970eff157307655847221fbb99a81407 Mon Sep 17 00:00:00 2001 From: robomic Date: Mon, 19 Aug 2024 15:22:17 +0200 Subject: [PATCH 133/304] update testcase --- common/math/geometry/test/src/polygon/test_line_segment.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/common/math/geometry/test/src/polygon/test_line_segment.cpp b/common/math/geometry/test/src/polygon/test_line_segment.cpp index b6e7bec4f0a..eac5222db07 100644 --- a/common/math/geometry/test/src/polygon/test_line_segment.cpp +++ b/common/math/geometry/test/src/polygon/test_line_segment.cpp @@ -238,7 +238,7 @@ TEST(LineSegment, isIntersect2D_collinear) EXPECT_FALSE(line.isIntersect2D( math::geometry::LineSegment(makePoint(3.0, 5.0, 0.0), makePoint(5.0, 7.0, 0.0)))); EXPECT_FALSE(line.isIntersect2D( - math::geometry::LineSegment(makePoint(-3.0, -1.0, 0.0), makePoint(-1.0, 1.0, 0.0)))); + math::geometry::LineSegment(makePoint(-3.0, -1.0, 0.0), makePoint(-2.0, 0.0, 0.0)))); } /** From 0306503fdf199349759182ef76f4d5e9d46d8811 Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Tue, 20 Aug 2024 12:02:54 +0900 Subject: [PATCH 134/304] =?UTF-8?q?Split=20the=20string=20=E2=80=9C\nnpc?= =?UTF-8?q?=E2=80=9D=20into=20=E2=80=9C\n=E2=80=9D=20and=20=E2=80=9Cnpc?= =?UTF-8?q?=E2=80=9D.?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: yamacir-kit --- .../include/random_test_runner/data_types.hpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/test_runner/random_test_runner/include/random_test_runner/data_types.hpp b/test_runner/random_test_runner/include/random_test_runner/data_types.hpp index b6dbf773b5a..1a63c8955fc 100644 --- a/test_runner/random_test_runner/include/random_test_runner/data_types.hpp +++ b/test_runner/random_test_runner/include/random_test_runner/data_types.hpp @@ -166,7 +166,8 @@ struct fmt::formatter fmt::format_to( ctx.out(), "ego_start_position: {} ego_goal_position: {} " - "ego_goal_pose: {}\nnpc_descriptions:", + "ego_goal_pose: {}\n" // + "npc_descriptions:", v.ego_start_position, v.ego_goal_position, v.ego_goal_pose); for (size_t idx = 0; idx < v.npcs_descriptions.size(); idx++) { fmt::format_to(ctx.out(), "[{}]: {}\n", idx, v.npcs_descriptions[idx]); From e3aeb8a64ac7b657ed38c6398f7a72e92afd0d1c Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Tue, 20 Aug 2024 12:43:28 +0900 Subject: [PATCH 135/304] Add a comment explaining the background of the hack Signed-off-by: yamacir-kit --- .../include/random_test_runner/data_types.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/test_runner/random_test_runner/include/random_test_runner/data_types.hpp b/test_runner/random_test_runner/include/random_test_runner/data_types.hpp index 1a63c8955fc..855b7468b5a 100644 --- a/test_runner/random_test_runner/include/random_test_runner/data_types.hpp +++ b/test_runner/random_test_runner/include/random_test_runner/data_types.hpp @@ -166,7 +166,7 @@ struct fmt::formatter fmt::format_to( ctx.out(), "ego_start_position: {} ego_goal_position: {} " - "ego_goal_pose: {}\n" // + "ego_goal_pose: {}\n" // The spell checker detects the string "\nnpc" as an illegal word "nnpc", so it is necessary to split the string like this. "npc_descriptions:", v.ego_start_position, v.ego_goal_position, v.ego_goal_pose); for (size_t idx = 0; idx < v.npcs_descriptions.size(); idx++) { From 6057c4487353b1043862813b528b5f21b7215f58 Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Tue, 20 Aug 2024 12:48:35 +0900 Subject: [PATCH 136/304] Lipsticks Signed-off-by: yamacir-kit --- .../include/random_test_runner/data_types.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/test_runner/random_test_runner/include/random_test_runner/data_types.hpp b/test_runner/random_test_runner/include/random_test_runner/data_types.hpp index 855b7468b5a..e0c168c43dc 100644 --- a/test_runner/random_test_runner/include/random_test_runner/data_types.hpp +++ b/test_runner/random_test_runner/include/random_test_runner/data_types.hpp @@ -166,7 +166,7 @@ struct fmt::formatter fmt::format_to( ctx.out(), "ego_start_position: {} ego_goal_position: {} " - "ego_goal_pose: {}\n" // The spell checker detects the string "\nnpc" as an illegal word "nnpc", so it is necessary to split the string like this. + "ego_goal_pose: {}\n" // The spell checker detects the string as an illegal word, so it is necessary to split the string like this. "npc_descriptions:", v.ego_start_position, v.ego_goal_position, v.ego_goal_pose); for (size_t idx = 0; idx < v.npcs_descriptions.size(); idx++) { From 34f2a1c7e4351de02131a41519d3f48e86594286 Mon Sep 17 00:00:00 2001 From: Release Bot Date: Tue, 20 Aug 2024 06:10:28 +0000 Subject: [PATCH 137/304] Bump version of scenario_simulator_v2 from version 3.4.3 to version 3.4.4 --- common/math/arithmetic/CHANGELOG.rst | 3 +++ common/math/arithmetic/package.xml | 2 +- common/math/geometry/CHANGELOG.rst | 3 +++ common/math/geometry/package.xml | 2 +- common/scenario_simulator_exception/CHANGELOG.rst | 3 +++ common/scenario_simulator_exception/package.xml | 2 +- common/simple_junit/CHANGELOG.rst | 3 +++ common/simple_junit/package.xml | 2 +- common/status_monitor/CHANGELOG.rst | 3 +++ common/status_monitor/package.xml | 2 +- external/concealer/CHANGELOG.rst | 3 +++ external/concealer/package.xml | 2 +- external/embree_vendor/CHANGELOG.rst | 3 +++ external/embree_vendor/package.xml | 2 +- map/kashiwanoha_map/CHANGELOG.rst | 3 +++ map/kashiwanoha_map/package.xml | 2 +- map/simple_cross_map/CHANGELOG.rst | 3 +++ map/simple_cross_map/package.xml | 2 +- mock/cpp_mock_scenarios/CHANGELOG.rst | 3 +++ mock/cpp_mock_scenarios/package.xml | 2 +- .../openscenario_experimental_catalog/CHANGELOG.rst | 3 +++ .../openscenario_experimental_catalog/package.xml | 2 +- openscenario/openscenario_interpreter/CHANGELOG.rst | 3 +++ openscenario/openscenario_interpreter/package.xml | 2 +- .../openscenario_interpreter_example/CHANGELOG.rst | 3 +++ .../openscenario_interpreter_example/package.xml | 2 +- openscenario/openscenario_interpreter_msgs/CHANGELOG.rst | 3 +++ openscenario/openscenario_interpreter_msgs/package.xml | 2 +- openscenario/openscenario_preprocessor/CHANGELOG.rst | 3 +++ openscenario/openscenario_preprocessor/package.xml | 2 +- .../openscenario_preprocessor_msgs/CHANGELOG.rst | 3 +++ openscenario/openscenario_preprocessor_msgs/package.xml | 2 +- openscenario/openscenario_utility/CHANGELOG.rst | 3 +++ openscenario/openscenario_utility/package.xml | 2 +- openscenario/openscenario_validator/CHANGELOG.rst | 3 +++ openscenario/openscenario_validator/package.xml | 2 +- rviz_plugins/openscenario_visualization/CHANGELOG.rst | 3 +++ rviz_plugins/openscenario_visualization/package.xml | 2 +- .../real_time_factor_control_rviz_plugin/CHANGELOG.rst | 3 +++ .../real_time_factor_control_rviz_plugin/package.xml | 2 +- scenario_simulator_v2/CHANGELOG.rst | 3 +++ scenario_simulator_v2/package.xml | 2 +- simulation/behavior_tree_plugin/CHANGELOG.rst | 3 +++ simulation/behavior_tree_plugin/package.xml | 2 +- simulation/do_nothing_plugin/CHANGELOG.rst | 3 +++ simulation/do_nothing_plugin/package.xml | 2 +- simulation/simple_sensor_simulator/CHANGELOG.rst | 3 +++ simulation/simple_sensor_simulator/package.xml | 2 +- simulation/simulation_interface/CHANGELOG.rst | 3 +++ simulation/simulation_interface/package.xml | 2 +- simulation/traffic_simulator/CHANGELOG.rst | 3 +++ simulation/traffic_simulator/package.xml | 2 +- simulation/traffic_simulator_msgs/CHANGELOG.rst | 3 +++ simulation/traffic_simulator_msgs/package.xml | 2 +- test_runner/random_test_runner/CHANGELOG.rst | 9 +++++++++ test_runner/random_test_runner/package.xml | 2 +- test_runner/scenario_test_runner/CHANGELOG.rst | 3 +++ test_runner/scenario_test_runner/package.xml | 2 +- 58 files changed, 122 insertions(+), 29 deletions(-) diff --git a/common/math/arithmetic/CHANGELOG.rst b/common/math/arithmetic/CHANGELOG.rst index 1eeb23b4df2..5c7e462b720 100644 --- a/common/math/arithmetic/CHANGELOG.rst +++ b/common/math/arithmetic/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package arithmetic * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.4 (2024-08-20) +------------------ + 3.4.3 (2024-08-19) ------------------ diff --git a/common/math/arithmetic/package.xml b/common/math/arithmetic/package.xml index 29d6d08c935..0da099eb60b 100644 --- a/common/math/arithmetic/package.xml +++ b/common/math/arithmetic/package.xml @@ -2,7 +2,7 @@ arithmetic - 3.4.3 + 3.4.4 arithmetic library for scenario_simulator_v2 Tatsuya Yamasaki Apache License 2.0 diff --git a/common/math/geometry/CHANGELOG.rst b/common/math/geometry/CHANGELOG.rst index 954697a1319..f0d209adba8 100644 --- a/common/math/geometry/CHANGELOG.rst +++ b/common/math/geometry/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package geometry * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.4 (2024-08-20) +------------------ + 3.4.3 (2024-08-19) ------------------ diff --git a/common/math/geometry/package.xml b/common/math/geometry/package.xml index 0dea6c489d9..92df7e330b0 100644 --- a/common/math/geometry/package.xml +++ b/common/math/geometry/package.xml @@ -2,7 +2,7 @@ geometry - 3.4.3 + 3.4.4 geometry math library for scenario_simulator_v2 application Masaya Kataoka Apache License 2.0 diff --git a/common/scenario_simulator_exception/CHANGELOG.rst b/common/scenario_simulator_exception/CHANGELOG.rst index ab65d5a5863..487470d36fb 100644 --- a/common/scenario_simulator_exception/CHANGELOG.rst +++ b/common/scenario_simulator_exception/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package scenario_simulator_exception * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.4 (2024-08-20) +------------------ + 3.4.3 (2024-08-19) ------------------ diff --git a/common/scenario_simulator_exception/package.xml b/common/scenario_simulator_exception/package.xml index 180c3dc2d29..1197e52944b 100644 --- a/common/scenario_simulator_exception/package.xml +++ b/common/scenario_simulator_exception/package.xml @@ -2,7 +2,7 @@ scenario_simulator_exception - 3.4.3 + 3.4.4 Exception types for scenario simulator Tatsuya Yamasaki Apache License 2.0 diff --git a/common/simple_junit/CHANGELOG.rst b/common/simple_junit/CHANGELOG.rst index 563363b4b19..c592d190f77 100644 --- a/common/simple_junit/CHANGELOG.rst +++ b/common/simple_junit/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package junit_exporter * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.4 (2024-08-20) +------------------ + 3.4.3 (2024-08-19) ------------------ diff --git a/common/simple_junit/package.xml b/common/simple_junit/package.xml index 32c55fc3f56..833f982f813 100644 --- a/common/simple_junit/package.xml +++ b/common/simple_junit/package.xml @@ -2,7 +2,7 @@ simple_junit - 3.4.3 + 3.4.4 Lightweight JUnit library for ROS 2 Masaya Kataoka Tatsuya Yamasaki diff --git a/common/status_monitor/CHANGELOG.rst b/common/status_monitor/CHANGELOG.rst index c9006e3918b..e9b647c3acf 100644 --- a/common/status_monitor/CHANGELOG.rst +++ b/common/status_monitor/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package status_monitor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.4 (2024-08-20) +------------------ + 3.4.3 (2024-08-19) ------------------ diff --git a/common/status_monitor/package.xml b/common/status_monitor/package.xml index b013d229f3b..cf7184c3d2e 100644 --- a/common/status_monitor/package.xml +++ b/common/status_monitor/package.xml @@ -2,7 +2,7 @@ status_monitor - 3.4.3 + 3.4.4 none Tatsuya Yamasaki Apache License 2.0 diff --git a/external/concealer/CHANGELOG.rst b/external/concealer/CHANGELOG.rst index a58fe96b161..3db8bd4f0a8 100644 --- a/external/concealer/CHANGELOG.rst +++ b/external/concealer/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package concealer * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.4 (2024-08-20) +------------------ + 3.4.3 (2024-08-19) ------------------ diff --git a/external/concealer/package.xml b/external/concealer/package.xml index 36735099f96..de2a2e7d693 100644 --- a/external/concealer/package.xml +++ b/external/concealer/package.xml @@ -2,7 +2,7 @@ concealer - 3.4.3 + 3.4.4 Provides a class 'Autoware' to conceal miscellaneous things to simplify Autoware management of the simulator. Tatsuya Yamasaki Apache License 2.0 diff --git a/external/embree_vendor/CHANGELOG.rst b/external/embree_vendor/CHANGELOG.rst index b8bbff4cab1..eeef6ad7d37 100644 --- a/external/embree_vendor/CHANGELOG.rst +++ b/external/embree_vendor/CHANGELOG.rst @@ -24,6 +24,9 @@ Changelog for package embree_vendor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.4 (2024-08-20) +------------------ + 3.4.3 (2024-08-19) ------------------ diff --git a/external/embree_vendor/package.xml b/external/embree_vendor/package.xml index f663d103f1a..c73699f1a7d 100644 --- a/external/embree_vendor/package.xml +++ b/external/embree_vendor/package.xml @@ -2,7 +2,7 @@ embree_vendor - 3.4.3 + 3.4.4 vendor packages for intel raytracing kernel library masaya Apache 2.0 diff --git a/map/kashiwanoha_map/CHANGELOG.rst b/map/kashiwanoha_map/CHANGELOG.rst index 2fed4769185..de0e5acea78 100644 --- a/map/kashiwanoha_map/CHANGELOG.rst +++ b/map/kashiwanoha_map/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package kashiwanoha_map * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.4 (2024-08-20) +------------------ + 3.4.3 (2024-08-19) ------------------ diff --git a/map/kashiwanoha_map/package.xml b/map/kashiwanoha_map/package.xml index ebbc0089807..18cb1638c0b 100644 --- a/map/kashiwanoha_map/package.xml +++ b/map/kashiwanoha_map/package.xml @@ -2,7 +2,7 @@ kashiwanoha_map - 3.4.3 + 3.4.4 map package for kashiwanoha Masaya Kataoka Apache License 2.0 diff --git a/map/simple_cross_map/CHANGELOG.rst b/map/simple_cross_map/CHANGELOG.rst index d0f9daf2610..772f73d5cc5 100644 --- a/map/simple_cross_map/CHANGELOG.rst +++ b/map/simple_cross_map/CHANGELOG.rst @@ -9,6 +9,9 @@ Changelog for package simple_cross_map * Merge branch 'master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.4 (2024-08-20) +------------------ + 3.4.3 (2024-08-19) ------------------ diff --git a/map/simple_cross_map/package.xml b/map/simple_cross_map/package.xml index f6a38767c1f..39a067adc53 100644 --- a/map/simple_cross_map/package.xml +++ b/map/simple_cross_map/package.xml @@ -2,7 +2,7 @@ simple_cross_map - 3.4.3 + 3.4.4 map package for simple cross Masaya Kataoka Apache License 2.0 diff --git a/mock/cpp_mock_scenarios/CHANGELOG.rst b/mock/cpp_mock_scenarios/CHANGELOG.rst index 89b11d52e29..e0e8b07fc54 100644 --- a/mock/cpp_mock_scenarios/CHANGELOG.rst +++ b/mock/cpp_mock_scenarios/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package cpp_mock_scenarios * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.4 (2024-08-20) +------------------ + 3.4.3 (2024-08-19) ------------------ * Merge pull request `#1339 `_ from tier4/fix/ament_auto_package diff --git a/mock/cpp_mock_scenarios/package.xml b/mock/cpp_mock_scenarios/package.xml index a19b7761245..db4ef6602f5 100644 --- a/mock/cpp_mock_scenarios/package.xml +++ b/mock/cpp_mock_scenarios/package.xml @@ -2,7 +2,7 @@ cpp_mock_scenarios - 3.4.3 + 3.4.4 C++ mock scenarios masaya Apache License 2.0 diff --git a/openscenario/openscenario_experimental_catalog/CHANGELOG.rst b/openscenario/openscenario_experimental_catalog/CHANGELOG.rst index 23882ec8753..d97c2985fcf 100644 --- a/openscenario/openscenario_experimental_catalog/CHANGELOG.rst +++ b/openscenario/openscenario_experimental_catalog/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package openscenario_experimental_catalog * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.4 (2024-08-20) +------------------ + 3.4.3 (2024-08-19) ------------------ diff --git a/openscenario/openscenario_experimental_catalog/package.xml b/openscenario/openscenario_experimental_catalog/package.xml index 9e2d1db51f5..77d42cad597 100644 --- a/openscenario/openscenario_experimental_catalog/package.xml +++ b/openscenario/openscenario_experimental_catalog/package.xml @@ -2,7 +2,7 @@ openscenario_experimental_catalog - 3.4.3 + 3.4.4 TIER IV experimental catalogs for OpenSCENARIO Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter/CHANGELOG.rst b/openscenario/openscenario_interpreter/CHANGELOG.rst index 1634255e7ce..b337aae118f 100644 --- a/openscenario/openscenario_interpreter/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter/CHANGELOG.rst @@ -32,6 +32,9 @@ Changelog for package openscenario_interpreter * add publish_empty_context parameter * Contributors: Masaya Kataoka +3.4.4 (2024-08-20) +------------------ + 3.4.3 (2024-08-19) ------------------ diff --git a/openscenario/openscenario_interpreter/package.xml b/openscenario/openscenario_interpreter/package.xml index b3395f2d1d1..50a7d6efcba 100644 --- a/openscenario/openscenario_interpreter/package.xml +++ b/openscenario/openscenario_interpreter/package.xml @@ -2,7 +2,7 @@ openscenario_interpreter - 3.4.3 + 3.4.4 OpenSCENARIO 1.2.0 interpreter package for Autoware Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter_example/CHANGELOG.rst b/openscenario/openscenario_interpreter_example/CHANGELOG.rst index 60512ecdf9e..773a7ad458e 100644 --- a/openscenario/openscenario_interpreter_example/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter_example/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package openscenario_interpreter_example * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.4 (2024-08-20) +------------------ + 3.4.3 (2024-08-19) ------------------ diff --git a/openscenario/openscenario_interpreter_example/package.xml b/openscenario/openscenario_interpreter_example/package.xml index 448f23702be..a0c094b0681 100644 --- a/openscenario/openscenario_interpreter_example/package.xml +++ b/openscenario/openscenario_interpreter_example/package.xml @@ -3,7 +3,7 @@ openscenario_interpreter_example - 3.4.3 + 3.4.4 Examples for some TIER IV OpenSCENARIO Interpreter's features Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst b/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst index 575b7303d34..d0f1db72106 100644 --- a/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package openscenario_interpreter_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.4 (2024-08-20) +------------------ + 3.4.3 (2024-08-19) ------------------ diff --git a/openscenario/openscenario_interpreter_msgs/package.xml b/openscenario/openscenario_interpreter_msgs/package.xml index a0e4a546396..eec031739a3 100644 --- a/openscenario/openscenario_interpreter_msgs/package.xml +++ b/openscenario/openscenario_interpreter_msgs/package.xml @@ -2,7 +2,7 @@ openscenario_interpreter_msgs - 3.4.3 + 3.4.4 ROS message types for package openscenario_interpreter Yamasaki Tatsuya Apache License 2.0 diff --git a/openscenario/openscenario_preprocessor/CHANGELOG.rst b/openscenario/openscenario_preprocessor/CHANGELOG.rst index 788c4453052..5ecc01bd933 100644 --- a/openscenario/openscenario_preprocessor/CHANGELOG.rst +++ b/openscenario/openscenario_preprocessor/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package openscenario_preprocessor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.4 (2024-08-20) +------------------ + 3.4.3 (2024-08-19) ------------------ diff --git a/openscenario/openscenario_preprocessor/package.xml b/openscenario/openscenario_preprocessor/package.xml index 38413a3438f..de8f7beb199 100644 --- a/openscenario/openscenario_preprocessor/package.xml +++ b/openscenario/openscenario_preprocessor/package.xml @@ -3,7 +3,7 @@ openscenario_preprocessor - 3.4.3 + 3.4.4 Example package for TIER IV OpenSCENARIO Interpreter Kotaro Yoshimoto Apache License 2.0 diff --git a/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst b/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst index b2ed33a0052..8acb108dbeb 100644 --- a/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst +++ b/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package openscenario_preprocessor_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.4 (2024-08-20) +------------------ + 3.4.3 (2024-08-19) ------------------ diff --git a/openscenario/openscenario_preprocessor_msgs/package.xml b/openscenario/openscenario_preprocessor_msgs/package.xml index eb63629f883..55e5693b836 100644 --- a/openscenario/openscenario_preprocessor_msgs/package.xml +++ b/openscenario/openscenario_preprocessor_msgs/package.xml @@ -2,7 +2,7 @@ openscenario_preprocessor_msgs - 3.4.3 + 3.4.4 ROS message types for package openscenario_preprocessor Kotaro Yoshimoto Apache License 2.0 diff --git a/openscenario/openscenario_utility/CHANGELOG.rst b/openscenario/openscenario_utility/CHANGELOG.rst index 95f39c1d2ad..9c401ddf272 100644 --- a/openscenario/openscenario_utility/CHANGELOG.rst +++ b/openscenario/openscenario_utility/CHANGELOG.rst @@ -24,6 +24,9 @@ Changelog for package openscenario_utility * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.4 (2024-08-20) +------------------ + 3.4.3 (2024-08-19) ------------------ diff --git a/openscenario/openscenario_utility/package.xml b/openscenario/openscenario_utility/package.xml index 3f817de2a6e..c4af7f97493 100644 --- a/openscenario/openscenario_utility/package.xml +++ b/openscenario/openscenario_utility/package.xml @@ -2,7 +2,7 @@ openscenario_utility - 3.4.3 + 3.4.4 Utility tools for ASAM OpenSCENARIO 1.2.0 Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_validator/CHANGELOG.rst b/openscenario/openscenario_validator/CHANGELOG.rst index 78a9c047648..8bea91d21a1 100644 --- a/openscenario/openscenario_validator/CHANGELOG.rst +++ b/openscenario/openscenario_validator/CHANGELOG.rst @@ -10,6 +10,9 @@ Changelog for package openscenario_validator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.4 (2024-08-20) +------------------ + 3.4.3 (2024-08-19) ------------------ diff --git a/openscenario/openscenario_validator/package.xml b/openscenario/openscenario_validator/package.xml index 68cc76df948..5632a8479df 100644 --- a/openscenario/openscenario_validator/package.xml +++ b/openscenario/openscenario_validator/package.xml @@ -2,7 +2,7 @@ openscenario_validator - 3.4.3 + 3.4.4 Validator for OpenSCENARIO 1.3 Kotaro Yoshimoto Apache License 2.0 diff --git a/rviz_plugins/openscenario_visualization/CHANGELOG.rst b/rviz_plugins/openscenario_visualization/CHANGELOG.rst index abf9e183b17..abbe25a0c99 100644 --- a/rviz_plugins/openscenario_visualization/CHANGELOG.rst +++ b/rviz_plugins/openscenario_visualization/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package openscenario_visualization * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.4 (2024-08-20) +------------------ + 3.4.3 (2024-08-19) ------------------ diff --git a/rviz_plugins/openscenario_visualization/package.xml b/rviz_plugins/openscenario_visualization/package.xml index 88b06431162..3a4939f91e9 100644 --- a/rviz_plugins/openscenario_visualization/package.xml +++ b/rviz_plugins/openscenario_visualization/package.xml @@ -2,7 +2,7 @@ openscenario_visualization - 3.4.3 + 3.4.4 Visualization tools for simulation results Masaya Kataoka Kyoichi Sugahara diff --git a/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst b/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst index 23e52eddd1d..e4224082b90 100644 --- a/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst +++ b/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package real_time_factor_control_rviz_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.4 (2024-08-20) +------------------ + 3.4.3 (2024-08-19) ------------------ diff --git a/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml b/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml index 6574e60f8e7..23d385493df 100644 --- a/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml +++ b/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml @@ -2,7 +2,7 @@ real_time_factor_control_rviz_plugin - 3.4.3 + 3.4.4 Slider controlling real time factor value. Paweł Lech Apache License 2.0 diff --git a/scenario_simulator_v2/CHANGELOG.rst b/scenario_simulator_v2/CHANGELOG.rst index 7bcb0e54782..bb67c6847ad 100644 --- a/scenario_simulator_v2/CHANGELOG.rst +++ b/scenario_simulator_v2/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package scenario_simulator_v2 * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.4 (2024-08-20) +------------------ + 3.4.3 (2024-08-19) ------------------ diff --git a/scenario_simulator_v2/package.xml b/scenario_simulator_v2/package.xml index e755afeabf1..38ae9270ca5 100644 --- a/scenario_simulator_v2/package.xml +++ b/scenario_simulator_v2/package.xml @@ -2,7 +2,7 @@ scenario_simulator_v2 - 3.4.3 + 3.4.4 scenario testing framework for Autoware Masaya Kataoka Apache License 2.0 diff --git a/simulation/behavior_tree_plugin/CHANGELOG.rst b/simulation/behavior_tree_plugin/CHANGELOG.rst index 450e562ab03..dc2d5080d96 100644 --- a/simulation/behavior_tree_plugin/CHANGELOG.rst +++ b/simulation/behavior_tree_plugin/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package behavior_tree_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.4 (2024-08-20) +------------------ + 3.4.3 (2024-08-19) ------------------ diff --git a/simulation/behavior_tree_plugin/package.xml b/simulation/behavior_tree_plugin/package.xml index 45c763805bd..b9050d79f14 100644 --- a/simulation/behavior_tree_plugin/package.xml +++ b/simulation/behavior_tree_plugin/package.xml @@ -2,7 +2,7 @@ behavior_tree_plugin - 3.4.3 + 3.4.4 Behavior tree plugin for traffic_simulator masaya Apache 2.0 diff --git a/simulation/do_nothing_plugin/CHANGELOG.rst b/simulation/do_nothing_plugin/CHANGELOG.rst index cb54d773c58..cb071e4f97c 100644 --- a/simulation/do_nothing_plugin/CHANGELOG.rst +++ b/simulation/do_nothing_plugin/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package do_nothing_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.4 (2024-08-20) +------------------ + 3.4.3 (2024-08-19) ------------------ diff --git a/simulation/do_nothing_plugin/package.xml b/simulation/do_nothing_plugin/package.xml index 710bce1d396..fcbb05bccd6 100644 --- a/simulation/do_nothing_plugin/package.xml +++ b/simulation/do_nothing_plugin/package.xml @@ -2,7 +2,7 @@ do_nothing_plugin - 3.4.3 + 3.4.4 Behavior plugin for do nothing Masaya Kataoka Apache 2.0 diff --git a/simulation/simple_sensor_simulator/CHANGELOG.rst b/simulation/simple_sensor_simulator/CHANGELOG.rst index 90542cbc3b5..6a0f38d0bd2 100644 --- a/simulation/simple_sensor_simulator/CHANGELOG.rst +++ b/simulation/simple_sensor_simulator/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package simple_sensor_simulator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.4 (2024-08-20) +------------------ + 3.4.3 (2024-08-19) ------------------ diff --git a/simulation/simple_sensor_simulator/package.xml b/simulation/simple_sensor_simulator/package.xml index 4447456cbeb..36f7759fe79 100644 --- a/simulation/simple_sensor_simulator/package.xml +++ b/simulation/simple_sensor_simulator/package.xml @@ -1,7 +1,7 @@ simple_sensor_simulator - 3.4.3 + 3.4.4 simple_sensor_simulator package masaya kataoka diff --git a/simulation/simulation_interface/CHANGELOG.rst b/simulation/simulation_interface/CHANGELOG.rst index a04bab28d96..a6fc4785e02 100644 --- a/simulation/simulation_interface/CHANGELOG.rst +++ b/simulation/simulation_interface/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package simulation_interface * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.4 (2024-08-20) +------------------ + 3.4.3 (2024-08-19) ------------------ diff --git a/simulation/simulation_interface/package.xml b/simulation/simulation_interface/package.xml index a14ee2e6843..74e8e8039d1 100644 --- a/simulation/simulation_interface/package.xml +++ b/simulation/simulation_interface/package.xml @@ -2,7 +2,7 @@ simulation_interface - 3.4.3 + 3.4.4 packages to define interface between simulator and scenario interpreter Masaya Kataoka Apache License 2.0 diff --git a/simulation/traffic_simulator/CHANGELOG.rst b/simulation/traffic_simulator/CHANGELOG.rst index 47c587abe52..567fd4a7619 100644 --- a/simulation/traffic_simulator/CHANGELOG.rst +++ b/simulation/traffic_simulator/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package traffic_simulator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.4 (2024-08-20) +------------------ + 3.4.3 (2024-08-19) ------------------ diff --git a/simulation/traffic_simulator/package.xml b/simulation/traffic_simulator/package.xml index 87a2384992a..7ecd9902c03 100644 --- a/simulation/traffic_simulator/package.xml +++ b/simulation/traffic_simulator/package.xml @@ -1,7 +1,7 @@ traffic_simulator - 3.4.3 + 3.4.4 control traffic flow masaya kataoka diff --git a/simulation/traffic_simulator_msgs/CHANGELOG.rst b/simulation/traffic_simulator_msgs/CHANGELOG.rst index cbe4e3fa8fa..6101cee915d 100644 --- a/simulation/traffic_simulator_msgs/CHANGELOG.rst +++ b/simulation/traffic_simulator_msgs/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package openscenario_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.4 (2024-08-20) +------------------ + 3.4.3 (2024-08-19) ------------------ diff --git a/simulation/traffic_simulator_msgs/package.xml b/simulation/traffic_simulator_msgs/package.xml index c0c9a3d8074..517e478699b 100644 --- a/simulation/traffic_simulator_msgs/package.xml +++ b/simulation/traffic_simulator_msgs/package.xml @@ -2,7 +2,7 @@ traffic_simulator_msgs - 3.4.3 + 3.4.4 ROS messages for openscenario Masaya Kataoka Apache License 2.0 diff --git a/test_runner/random_test_runner/CHANGELOG.rst b/test_runner/random_test_runner/CHANGELOG.rst index 9a783f89d38..d025b37fbda 100644 --- a/test_runner/random_test_runner/CHANGELOG.rst +++ b/test_runner/random_test_runner/CHANGELOG.rst @@ -21,6 +21,15 @@ Changelog for package random_test_runner * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.4 (2024-08-20) +------------------ +* Merge pull request `#1345 `_ from tier4/newline-character-literal + Avoid false detection of newline character literals by spell check. +* Lipsticks +* Add a comment explaining the background of the hack +* Split the string “\nnpc” into “\n” and “npc”. +* Contributors: Masaya Kataoka, yamacir-kit + 3.4.3 (2024-08-19) ------------------ diff --git a/test_runner/random_test_runner/package.xml b/test_runner/random_test_runner/package.xml index 693c71ee434..4f773aebdeb 100644 --- a/test_runner/random_test_runner/package.xml +++ b/test_runner/random_test_runner/package.xml @@ -2,7 +2,7 @@ random_test_runner - 3.4.3 + 3.4.4 Random behavior test runner piotr-zyskowski-rai Apache License 2.0 diff --git a/test_runner/scenario_test_runner/CHANGELOG.rst b/test_runner/scenario_test_runner/CHANGELOG.rst index 87394569b74..c4c9a01a447 100644 --- a/test_runner/scenario_test_runner/CHANGELOG.rst +++ b/test_runner/scenario_test_runner/CHANGELOG.rst @@ -35,6 +35,9 @@ Changelog for package scenario_test_runner * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.4.4 (2024-08-20) +------------------ + 3.4.3 (2024-08-19) ------------------ diff --git a/test_runner/scenario_test_runner/package.xml b/test_runner/scenario_test_runner/package.xml index 64838e3fc0d..673f48e4723 100644 --- a/test_runner/scenario_test_runner/package.xml +++ b/test_runner/scenario_test_runner/package.xml @@ -2,7 +2,7 @@ scenario_test_runner - 3.4.3 + 3.4.4 scenario test runner package Tatsuya Yamasaki Apache License 2.0 From 9e8415fd99a01b36f1fedc715425beb4c738e21c Mon Sep 17 00:00:00 2001 From: robomic Date: Tue, 20 Aug 2024 12:09:40 +0200 Subject: [PATCH 138/304] 1344 fix initial solution --- .../geometry/src/polygon/line_segment.cpp | 41 +++++++------------ 1 file changed, 14 insertions(+), 27 deletions(-) diff --git a/common/math/geometry/src/polygon/line_segment.cpp b/common/math/geometry/src/polygon/line_segment.cpp index 5238a24b307..c415ba23bc6 100644 --- a/common/math/geometry/src/polygon/line_segment.cpp +++ b/common/math/geometry/src/polygon/line_segment.cpp @@ -120,7 +120,17 @@ auto LineSegment::getPose(const double s, const bool denormalize_s, const bool f */ auto LineSegment::isIntersect2D(const geometry_msgs::msg::Point & point) const -> bool { - return getIntersection2DSValue(point, true) ? true : false; + const bool x_outside = ((point.x - start_point.x) * (end_point.x - point.x) < 0.0); + const bool y_outside = ((point.y - start_point.y) * (end_point.y - point.y) < 0.0); + if (x_outside || y_outside) { + return false; + } + const double dx = end_point.x - start_point.x; + const double dy = end_point.y - start_point.y; + const double squared_length = dx * dx + dy * dy; + const double cross_product = (point.y - start_point.y) * dx - (point.x - start_point.x) * dy; + constexpr double tolerance = std::numeric_limits::epsilon(); + return cross_product * cross_product <= squared_length * tolerance * tolerance; } auto LineSegment::getSValue( @@ -170,32 +180,9 @@ auto LineSegment::isIntersect2D(const LineSegment & l0) const -> bool auto LineSegment::getIntersection2DSValue( const geometry_msgs::msg::Point & point, const bool denormalize_s) const -> std::optional { - const auto get_s_normalized = [this](const auto & point) -> std::optional { - const auto get_s_from_x = [this](const auto & point) { - const auto s = (point.x - start_point.x) / (end_point.x - start_point.x); - return 0 <= s && s <= 1 ? s : std::optional(); - }; - const auto get_s_from_y = [this](const auto & point) { - const auto s = (point.y - start_point.y) / (end_point.y - start_point.y); - return 0 <= s && s <= 1 ? s : std::optional(); - }; - constexpr double epsilon = std::numeric_limits::epsilon(); - if (std::abs(end_point.x - start_point.x) <= epsilon) { - if (std::abs(end_point.y - start_point.y) <= epsilon) { - /// @note If start_point and end_point is a same point, checking the point is same as end_point or not. - return (std::abs(end_point.x - point.x) <= epsilon && - std::abs(end_point.y - point.y) <= epsilon) - ? std::optional(0) - : std::optional(); - } - /// @note If the line segment is parallel to y axis, calculate s value from y axis value. - return std::abs(point.x - start_point.x) <= epsilon ? get_s_from_y(point) - : std::optional(); - } - /// @note If the line segment is not parallel to x and y axis, calculate s value from x axis value. - return get_s_from_x(point); - }; - return denormalize_s ? denormalize(get_s_normalized(point)) : get_s_normalized(point); + if (not isIntersect2D(point)) return std::nullopt; + const double distance = std::hypot(point.x - start_point.x, point.y - start_point.y); + return denormalize_s ? std::make_optional(distance) : std::make_optional(distance / getLength()); } /** From dd33ae3e24f66391aabc830fcb88447eba97c221 Mon Sep 17 00:00:00 2001 From: robomic Date: Tue, 20 Aug 2024 15:46:21 +0200 Subject: [PATCH 139/304] isIntesect2D initial solution --- .../src/intersection/intersection.cpp | 52 +++++++++++++------ .../geometry/src/polygon/line_segment.cpp | 18 +------ 2 files changed, 39 insertions(+), 31 deletions(-) diff --git a/common/math/geometry/src/intersection/intersection.cpp b/common/math/geometry/src/intersection/intersection.cpp index 07a32df0b9a..0c8e83571a6 100644 --- a/common/math/geometry/src/intersection/intersection.cpp +++ b/common/math/geometry/src/intersection/intersection.cpp @@ -21,22 +21,44 @@ namespace geometry { bool isIntersect2D(const LineSegment & line0, const LineSegment & line1) { - double s, t; - s = (line0.start_point.x - line0.end_point.x) * (line1.start_point.y - line0.start_point.y) - - (line0.start_point.y - line0.end_point.y) * (line1.start_point.x - line0.start_point.x); - t = (line0.start_point.x - line0.end_point.x) * (line1.end_point.y - line0.start_point.y) - - (line0.start_point.y - line0.end_point.y) * (line1.end_point.x - line0.start_point.x); - if (s * t > 0) { - return false; - } - s = (line1.start_point.x - line1.end_point.x) * (line0.start_point.y - line1.start_point.y) - - (line1.start_point.y - line1.end_point.y) * (line0.start_point.x - line1.start_point.x); - t = (line1.start_point.x - line1.end_point.x) * (line0.end_point.y - line1.start_point.y) - - (line1.start_point.y - line1.end_point.y) * (line0.end_point.x - line1.start_point.x); - if (s * t > 0) { - return false; + using Point = geometry_msgs::msg::Point; + + const auto p0 = line0.start_point, q0 = line0.end_point; + const auto p1 = line1.start_point, q1 = line1.end_point; + + constexpr auto within_bounding_box = + [](const Point & start, const Point & end, const Point & to_check) -> bool { + const bool x_inside = ((to_check.x - start.x) * (end.x - to_check.x) >= 0.0); + const bool y_inside = ((to_check.y - start.y) * (end.y - to_check.y) >= 0.0); + return x_inside && y_inside; + }; + + constexpr auto orientation = + [](const Point & start, const Point & end, const Point & to_check) -> double { + return (end.y - start.y) * (to_check.x - end.x) - (end.x - start.x) * (to_check.y - end.y); + }; + + constexpr auto sign = [](const double x) -> int { + constexpr double tolerance = 1.0e-10; + if (x > +tolerance) return +1; + if (x < -tolerance) return -1; + return 0; + }; + + const int ori_p0 = sign(orientation(p1, q1, p0)); + const int ori_q0 = sign(orientation(p1, q1, q0)); + const int ori_p1 = sign(orientation(p0, q0, p1)); + const int ori_q1 = sign(orientation(p0, q0, q1)); + + // Special case + // If the lines are collinear; they intersect if and only if their bounding boxes overlap + if (ori_p1 == 0 && ori_q1 == 0 && ori_p0 == 0 && ori_q0 == 0) { + return within_bounding_box(p0, q0, p1) || within_bounding_box(p0, q0, p1) || + within_bounding_box(p1, q1, p0) || within_bounding_box(p1, q1, p0); } - return true; + + // General case + return ori_p1 != ori_q1 && ori_p0 != ori_q0; } bool isIntersect2D(const std::vector & lines) diff --git a/common/math/geometry/src/polygon/line_segment.cpp b/common/math/geometry/src/polygon/line_segment.cpp index 5238a24b307..89fff5cf5e2 100644 --- a/common/math/geometry/src/polygon/line_segment.cpp +++ b/common/math/geometry/src/polygon/line_segment.cpp @@ -13,6 +13,7 @@ // limitations under the License. #include +#include #include #include #include @@ -144,22 +145,7 @@ auto LineSegment::getSValue( */ auto LineSegment::isIntersect2D(const LineSegment & l0) const -> bool { - double s, t; - s = (l0.start_point.x - l0.end_point.x) * (start_point.y - l0.start_point.y) - - (l0.start_point.y - l0.end_point.y) * (start_point.x - l0.start_point.x); - t = (l0.start_point.x - l0.end_point.x) * (end_point.y - l0.start_point.y) - - (l0.start_point.y - l0.end_point.y) * (end_point.x - l0.start_point.x); - if (s * t > 0) { - return false; - } - s = (start_point.x - end_point.x) * (l0.start_point.y - start_point.y) - - (start_point.y - end_point.y) * (l0.start_point.x - start_point.x); - t = (start_point.x - end_point.x) * (l0.end_point.y - start_point.y) - - (start_point.y - end_point.y) * (l0.end_point.x - start_point.x); - if (s * t > 0) { - return false; - } - return true; + return math::geometry::isIntersect2D(*this, l0); } /** From ed4731a8327fcf695f12e88c68bd48f33a5778d5 Mon Sep 17 00:00:00 2001 From: Masaya Kataoka Date: Wed, 21 Aug 2024 10:24:16 +0900 Subject: [PATCH 140/304] modify tag Signed-off-by: Masaya Kataoka --- .github/workflows/Docekr.yaml | 2 -- 1 file changed, 2 deletions(-) diff --git a/.github/workflows/Docekr.yaml b/.github/workflows/Docekr.yaml index 18ab80fa928..8609da5fffe 100644 --- a/.github/workflows/Docekr.yaml +++ b/.github/workflows/Docekr.yaml @@ -12,8 +12,6 @@ on: - "!pyproject.toml" - "!poetry.lock" release: - types: [published] - jobs: push_docker: From c7d526c4142dee667f86e65a072f56b18e113802 Mon Sep 17 00:00:00 2001 From: Masaya Kataoka Date: Wed, 21 Aug 2024 11:40:53 +0900 Subject: [PATCH 141/304] change trigger Signed-off-by: Masaya Kataoka --- .github/workflows/Docekr.yaml | 1 - 1 file changed, 1 deletion(-) diff --git a/.github/workflows/Docekr.yaml b/.github/workflows/Docekr.yaml index 8609da5fffe..28b543cb6ed 100644 --- a/.github/workflows/Docekr.yaml +++ b/.github/workflows/Docekr.yaml @@ -6,7 +6,6 @@ on: - "!docs/**" - "!README.md" - "!CONTRIBUTING.md" - - "!.github/**" - ".github/workflows/Docker.yaml" - "!mkdocs.yml" - "!pyproject.toml" From 33cb1266136bd81dd7173c8621619371d556d3d3 Mon Sep 17 00:00:00 2001 From: Release Bot Date: Wed, 21 Aug 2024 07:06:25 +0000 Subject: [PATCH 142/304] Bump version of scenario_simulator_v2 from version 3.4.4 to version 3.5.0 --- common/math/arithmetic/CHANGELOG.rst | 13 +++++ common/math/arithmetic/package.xml | 2 +- common/math/geometry/CHANGELOG.rst | 13 +++++ common/math/geometry/package.xml | 2 +- .../CHANGELOG.rst | 13 +++++ .../scenario_simulator_exception/package.xml | 2 +- common/simple_junit/CHANGELOG.rst | 13 +++++ common/simple_junit/package.xml | 2 +- common/status_monitor/CHANGELOG.rst | 13 +++++ common/status_monitor/package.xml | 2 +- external/concealer/CHANGELOG.rst | 13 +++++ external/concealer/package.xml | 2 +- external/embree_vendor/CHANGELOG.rst | 13 +++++ external/embree_vendor/package.xml | 2 +- map/kashiwanoha_map/CHANGELOG.rst | 13 +++++ map/kashiwanoha_map/package.xml | 2 +- map/simple_cross_map/CHANGELOG.rst | 13 +++++ map/simple_cross_map/package.xml | 2 +- mock/cpp_mock_scenarios/CHANGELOG.rst | 13 +++++ mock/cpp_mock_scenarios/package.xml | 2 +- .../CHANGELOG.rst | 13 +++++ .../package.xml | 2 +- .../openscenario_interpreter/CHANGELOG.rst | 52 +++++++++++++++++++ .../openscenario_interpreter/package.xml | 2 +- .../CHANGELOG.rst | 13 +++++ .../package.xml | 2 +- .../CHANGELOG.rst | 13 +++++ .../openscenario_interpreter_msgs/package.xml | 2 +- .../openscenario_preprocessor/CHANGELOG.rst | 13 +++++ .../openscenario_preprocessor/package.xml | 2 +- .../CHANGELOG.rst | 13 +++++ .../package.xml | 2 +- .../openscenario_utility/CHANGELOG.rst | 13 +++++ openscenario/openscenario_utility/package.xml | 2 +- .../openscenario_validator/CHANGELOG.rst | 13 +++++ .../openscenario_validator/package.xml | 2 +- .../openscenario_visualization/CHANGELOG.rst | 13 +++++ .../openscenario_visualization/package.xml | 2 +- .../CHANGELOG.rst | 13 +++++ .../package.xml | 2 +- scenario_simulator_v2/CHANGELOG.rst | 13 +++++ scenario_simulator_v2/package.xml | 2 +- simulation/behavior_tree_plugin/CHANGELOG.rst | 13 +++++ simulation/behavior_tree_plugin/package.xml | 2 +- simulation/do_nothing_plugin/CHANGELOG.rst | 13 +++++ simulation/do_nothing_plugin/package.xml | 2 +- .../simple_sensor_simulator/CHANGELOG.rst | 14 +++++ .../simple_sensor_simulator/package.xml | 2 +- simulation/simulation_interface/CHANGELOG.rst | 14 +++++ simulation/simulation_interface/package.xml | 2 +- simulation/traffic_simulator/CHANGELOG.rst | 21 ++++++++ simulation/traffic_simulator/package.xml | 2 +- .../traffic_simulator_msgs/CHANGELOG.rst | 13 +++++ simulation/traffic_simulator_msgs/package.xml | 2 +- test_runner/random_test_runner/CHANGELOG.rst | 13 +++++ test_runner/random_test_runner/package.xml | 2 +- .../scenario_test_runner/CHANGELOG.rst | 19 +++++++ test_runner/scenario_test_runner/package.xml | 2 +- 58 files changed, 461 insertions(+), 29 deletions(-) diff --git a/common/math/arithmetic/CHANGELOG.rst b/common/math/arithmetic/CHANGELOG.rst index 5c7e462b720..64c3bbb98d9 100644 --- a/common/math/arithmetic/CHANGELOG.rst +++ b/common/math/arithmetic/CHANGELOG.rst @@ -21,6 +21,19 @@ Changelog for package arithmetic * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.0 (2024-08-21) +------------------ +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/relative-clearance-condition' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Contributors: Kotaro Yoshimoto, Tatsuya Yamasaki + 3.4.4 (2024-08-20) ------------------ diff --git a/common/math/arithmetic/package.xml b/common/math/arithmetic/package.xml index 0da099eb60b..dc0b9148053 100644 --- a/common/math/arithmetic/package.xml +++ b/common/math/arithmetic/package.xml @@ -2,7 +2,7 @@ arithmetic - 3.4.4 + 3.5.0 arithmetic library for scenario_simulator_v2 Tatsuya Yamasaki Apache License 2.0 diff --git a/common/math/geometry/CHANGELOG.rst b/common/math/geometry/CHANGELOG.rst index f0d209adba8..62b75383b52 100644 --- a/common/math/geometry/CHANGELOG.rst +++ b/common/math/geometry/CHANGELOG.rst @@ -21,6 +21,19 @@ Changelog for package geometry * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.0 (2024-08-21) +------------------ +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/relative-clearance-condition' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Contributors: Kotaro Yoshimoto, Tatsuya Yamasaki + 3.4.4 (2024-08-20) ------------------ diff --git a/common/math/geometry/package.xml b/common/math/geometry/package.xml index 92df7e330b0..7dfdbe1d948 100644 --- a/common/math/geometry/package.xml +++ b/common/math/geometry/package.xml @@ -2,7 +2,7 @@ geometry - 3.4.4 + 3.5.0 geometry math library for scenario_simulator_v2 application Masaya Kataoka Apache License 2.0 diff --git a/common/scenario_simulator_exception/CHANGELOG.rst b/common/scenario_simulator_exception/CHANGELOG.rst index 487470d36fb..54850734521 100644 --- a/common/scenario_simulator_exception/CHANGELOG.rst +++ b/common/scenario_simulator_exception/CHANGELOG.rst @@ -21,6 +21,19 @@ Changelog for package scenario_simulator_exception * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.0 (2024-08-21) +------------------ +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/relative-clearance-condition' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Contributors: Kotaro Yoshimoto, Tatsuya Yamasaki + 3.4.4 (2024-08-20) ------------------ diff --git a/common/scenario_simulator_exception/package.xml b/common/scenario_simulator_exception/package.xml index 1197e52944b..283b46d76c3 100644 --- a/common/scenario_simulator_exception/package.xml +++ b/common/scenario_simulator_exception/package.xml @@ -2,7 +2,7 @@ scenario_simulator_exception - 3.4.4 + 3.5.0 Exception types for scenario simulator Tatsuya Yamasaki Apache License 2.0 diff --git a/common/simple_junit/CHANGELOG.rst b/common/simple_junit/CHANGELOG.rst index c592d190f77..054e9449524 100644 --- a/common/simple_junit/CHANGELOG.rst +++ b/common/simple_junit/CHANGELOG.rst @@ -21,6 +21,19 @@ Changelog for package junit_exporter * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.0 (2024-08-21) +------------------ +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/relative-clearance-condition' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Contributors: Kotaro Yoshimoto, Tatsuya Yamasaki + 3.4.4 (2024-08-20) ------------------ diff --git a/common/simple_junit/package.xml b/common/simple_junit/package.xml index 833f982f813..cf00d05b43f 100644 --- a/common/simple_junit/package.xml +++ b/common/simple_junit/package.xml @@ -2,7 +2,7 @@ simple_junit - 3.4.4 + 3.5.0 Lightweight JUnit library for ROS 2 Masaya Kataoka Tatsuya Yamasaki diff --git a/common/status_monitor/CHANGELOG.rst b/common/status_monitor/CHANGELOG.rst index e9b647c3acf..65c1e11f5a0 100644 --- a/common/status_monitor/CHANGELOG.rst +++ b/common/status_monitor/CHANGELOG.rst @@ -21,6 +21,19 @@ Changelog for package status_monitor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.0 (2024-08-21) +------------------ +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/relative-clearance-condition' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Contributors: Kotaro Yoshimoto, Tatsuya Yamasaki + 3.4.4 (2024-08-20) ------------------ diff --git a/common/status_monitor/package.xml b/common/status_monitor/package.xml index cf7184c3d2e..d6a76edb2b3 100644 --- a/common/status_monitor/package.xml +++ b/common/status_monitor/package.xml @@ -2,7 +2,7 @@ status_monitor - 3.4.4 + 3.5.0 none Tatsuya Yamasaki Apache License 2.0 diff --git a/external/concealer/CHANGELOG.rst b/external/concealer/CHANGELOG.rst index 3db8bd4f0a8..c7c1a86aa2e 100644 --- a/external/concealer/CHANGELOG.rst +++ b/external/concealer/CHANGELOG.rst @@ -21,6 +21,19 @@ Changelog for package concealer * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.0 (2024-08-21) +------------------ +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/relative-clearance-condition' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Contributors: Kotaro Yoshimoto, Tatsuya Yamasaki + 3.4.4 (2024-08-20) ------------------ diff --git a/external/concealer/package.xml b/external/concealer/package.xml index de2a2e7d693..7e79e340797 100644 --- a/external/concealer/package.xml +++ b/external/concealer/package.xml @@ -2,7 +2,7 @@ concealer - 3.4.4 + 3.5.0 Provides a class 'Autoware' to conceal miscellaneous things to simplify Autoware management of the simulator. Tatsuya Yamasaki Apache License 2.0 diff --git a/external/embree_vendor/CHANGELOG.rst b/external/embree_vendor/CHANGELOG.rst index eeef6ad7d37..a3cbd42d32f 100644 --- a/external/embree_vendor/CHANGELOG.rst +++ b/external/embree_vendor/CHANGELOG.rst @@ -24,6 +24,19 @@ Changelog for package embree_vendor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.0 (2024-08-21) +------------------ +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/relative-clearance-condition' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Contributors: Kotaro Yoshimoto, Tatsuya Yamasaki + 3.4.4 (2024-08-20) ------------------ diff --git a/external/embree_vendor/package.xml b/external/embree_vendor/package.xml index c73699f1a7d..3b0833adddb 100644 --- a/external/embree_vendor/package.xml +++ b/external/embree_vendor/package.xml @@ -2,7 +2,7 @@ embree_vendor - 3.4.4 + 3.5.0 vendor packages for intel raytracing kernel library masaya Apache 2.0 diff --git a/map/kashiwanoha_map/CHANGELOG.rst b/map/kashiwanoha_map/CHANGELOG.rst index de0e5acea78..4ac41d7f364 100644 --- a/map/kashiwanoha_map/CHANGELOG.rst +++ b/map/kashiwanoha_map/CHANGELOG.rst @@ -21,6 +21,19 @@ Changelog for package kashiwanoha_map * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.0 (2024-08-21) +------------------ +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/relative-clearance-condition' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Contributors: Kotaro Yoshimoto, Tatsuya Yamasaki + 3.4.4 (2024-08-20) ------------------ diff --git a/map/kashiwanoha_map/package.xml b/map/kashiwanoha_map/package.xml index 18cb1638c0b..0bdc0dcd63e 100644 --- a/map/kashiwanoha_map/package.xml +++ b/map/kashiwanoha_map/package.xml @@ -2,7 +2,7 @@ kashiwanoha_map - 3.4.4 + 3.5.0 map package for kashiwanoha Masaya Kataoka Apache License 2.0 diff --git a/map/simple_cross_map/CHANGELOG.rst b/map/simple_cross_map/CHANGELOG.rst index 772f73d5cc5..fbb3748f1d9 100644 --- a/map/simple_cross_map/CHANGELOG.rst +++ b/map/simple_cross_map/CHANGELOG.rst @@ -9,6 +9,19 @@ Changelog for package simple_cross_map * Merge branch 'master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.0 (2024-08-21) +------------------ +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/relative-clearance-condition' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Contributors: Kotaro Yoshimoto, Tatsuya Yamasaki + 3.4.4 (2024-08-20) ------------------ diff --git a/map/simple_cross_map/package.xml b/map/simple_cross_map/package.xml index 39a067adc53..fff5d6ae9c8 100644 --- a/map/simple_cross_map/package.xml +++ b/map/simple_cross_map/package.xml @@ -2,7 +2,7 @@ simple_cross_map - 3.4.4 + 3.5.0 map package for simple cross Masaya Kataoka Apache License 2.0 diff --git a/mock/cpp_mock_scenarios/CHANGELOG.rst b/mock/cpp_mock_scenarios/CHANGELOG.rst index e0e8b07fc54..cf545f94612 100644 --- a/mock/cpp_mock_scenarios/CHANGELOG.rst +++ b/mock/cpp_mock_scenarios/CHANGELOG.rst @@ -21,6 +21,19 @@ Changelog for package cpp_mock_scenarios * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.0 (2024-08-21) +------------------ +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/relative-clearance-condition' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Contributors: Kotaro Yoshimoto, Tatsuya Yamasaki + 3.4.4 (2024-08-20) ------------------ diff --git a/mock/cpp_mock_scenarios/package.xml b/mock/cpp_mock_scenarios/package.xml index db4ef6602f5..4f4b0ed260a 100644 --- a/mock/cpp_mock_scenarios/package.xml +++ b/mock/cpp_mock_scenarios/package.xml @@ -2,7 +2,7 @@ cpp_mock_scenarios - 3.4.4 + 3.5.0 C++ mock scenarios masaya Apache License 2.0 diff --git a/openscenario/openscenario_experimental_catalog/CHANGELOG.rst b/openscenario/openscenario_experimental_catalog/CHANGELOG.rst index d97c2985fcf..9f522ae7066 100644 --- a/openscenario/openscenario_experimental_catalog/CHANGELOG.rst +++ b/openscenario/openscenario_experimental_catalog/CHANGELOG.rst @@ -21,6 +21,19 @@ Changelog for package openscenario_experimental_catalog * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.0 (2024-08-21) +------------------ +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/relative-clearance-condition' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Contributors: Kotaro Yoshimoto, Tatsuya Yamasaki + 3.4.4 (2024-08-20) ------------------ diff --git a/openscenario/openscenario_experimental_catalog/package.xml b/openscenario/openscenario_experimental_catalog/package.xml index 77d42cad597..dc9ed56c35f 100644 --- a/openscenario/openscenario_experimental_catalog/package.xml +++ b/openscenario/openscenario_experimental_catalog/package.xml @@ -2,7 +2,7 @@ openscenario_experimental_catalog - 3.4.4 + 3.5.0 TIER IV experimental catalogs for OpenSCENARIO Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter/CHANGELOG.rst b/openscenario/openscenario_interpreter/CHANGELOG.rst index b337aae118f..60a133f014f 100644 --- a/openscenario/openscenario_interpreter/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter/CHANGELOG.rst @@ -32,6 +32,58 @@ Changelog for package openscenario_interpreter * add publish_empty_context parameter * Contributors: Masaya Kataoka +3.5.0 (2024-08-21) +------------------ +* Merge pull request `#1316 `_ from tier4/relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* fix: treat added entity only in RelativeClearanceCondition +* refactor: delete RelativeClearanceCondition::getRelativeLanePosition +* refactor: use exception when errors are occurred in SimulatorCore::evaluateLateralRelativeLanes +* refactor: use std::optional for optional attribute in RelativeLaneRange +* feat: support EntitySelection in RelativeClearanceCondition +* refactor: use boost::math::constants::half_pi instead of 0.5 * boost::math::constants::pi +* fix: update target entities of RelativeClearanceCondition in every frame +* refactor: use boost::math::constants::pi() instead of M_PI +* fix: implement Integer::min/max instead of Integer::infinity +* Merge branch 'master' into relative-clearance-condition +* feat: improve description output of RelativeClearanceCondition +* Merge branch 'master' into relative-clearance-condition +* refactor: format comment-outs +* Merge branch 'master' into relative-clearance-condition +* refactor: clean up includes in relative_lane_range.hpp +* Fix RelativeLaneRange to use default values in the specification +* Add Integer::infinity function +* apply linter +* Fix copy bugs in RelativeClearanceCondition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Implement switching by relative heading of triggering_entity in RelativeClearanceCondition +* fix condition logic of RelativeClearanceCondition +* Correct initialization of RelativeClearanceCondition::entity_refs along the standard +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Revert "Move entity existence check into `distance` from speceialized `distance`" + This reverts commit 727d57dc93f29badb41661fcb8543c9ce7840392. +* Revert "Update `RelativeDistanceCondition::distance` to static member function" + This reverts commit 86f489f0 +* Add temporary implementation of RelativeClearanceCondition::evaluate function +* Implement RelativeClearanceCondition::getRelativeLanePosition function +* Implement SimulatorCore::evaluateLateralRelativeLanes function +* Merge remote-tracking branch 'origin/relative-clearance-condition' into relative-clearance-condition +* refactor: import RelativeDistanceCondition updates from feature/time-to-collision-condition branch + Co-authored-by: yamacir-kit +* Merge branch 'master' into relative-clearance-condition +* Update `RelativeDistanceCondition::distance` to static member function +* Move entity existence check into `distance` from speceialized `distance` +* fix: replace freespace with freeSpace in RelativeClearanceCondition +* chore: update OpenSCENARIO version of EntityCondition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* feat(openscenario_interpreter): add RelativeClearanceCondition(empty implementation) +* feat(openscenario_interpreter): add RelativeLaneRange +* Revert "fix(RelativeDistanceCondition): Fixed a bug where RelativeDistance showed negative values" + This reverts commit 84c8b0c101b8e680ad6029d8702387e5495e2646. +* fix(RelativeDistanceCondition): Fixed a bug where RelativeDistance showed negative values +* Contributors: Kotaro Yoshimoto, Tatsuya Yamasaki, yamacir-kit + 3.4.4 (2024-08-20) ------------------ diff --git a/openscenario/openscenario_interpreter/package.xml b/openscenario/openscenario_interpreter/package.xml index 50a7d6efcba..d89bf384717 100644 --- a/openscenario/openscenario_interpreter/package.xml +++ b/openscenario/openscenario_interpreter/package.xml @@ -2,7 +2,7 @@ openscenario_interpreter - 3.4.4 + 3.5.0 OpenSCENARIO 1.2.0 interpreter package for Autoware Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter_example/CHANGELOG.rst b/openscenario/openscenario_interpreter_example/CHANGELOG.rst index 773a7ad458e..65d65074842 100644 --- a/openscenario/openscenario_interpreter_example/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter_example/CHANGELOG.rst @@ -21,6 +21,19 @@ Changelog for package openscenario_interpreter_example * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.0 (2024-08-21) +------------------ +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/relative-clearance-condition' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Contributors: Kotaro Yoshimoto, Tatsuya Yamasaki + 3.4.4 (2024-08-20) ------------------ diff --git a/openscenario/openscenario_interpreter_example/package.xml b/openscenario/openscenario_interpreter_example/package.xml index a0c094b0681..12da0f14943 100644 --- a/openscenario/openscenario_interpreter_example/package.xml +++ b/openscenario/openscenario_interpreter_example/package.xml @@ -3,7 +3,7 @@ openscenario_interpreter_example - 3.4.4 + 3.5.0 Examples for some TIER IV OpenSCENARIO Interpreter's features Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst b/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst index d0f1db72106..afb80f1e887 100644 --- a/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst @@ -21,6 +21,19 @@ Changelog for package openscenario_interpreter_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.0 (2024-08-21) +------------------ +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/relative-clearance-condition' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Contributors: Kotaro Yoshimoto, Tatsuya Yamasaki + 3.4.4 (2024-08-20) ------------------ diff --git a/openscenario/openscenario_interpreter_msgs/package.xml b/openscenario/openscenario_interpreter_msgs/package.xml index eec031739a3..0e5eae005dd 100644 --- a/openscenario/openscenario_interpreter_msgs/package.xml +++ b/openscenario/openscenario_interpreter_msgs/package.xml @@ -2,7 +2,7 @@ openscenario_interpreter_msgs - 3.4.4 + 3.5.0 ROS message types for package openscenario_interpreter Yamasaki Tatsuya Apache License 2.0 diff --git a/openscenario/openscenario_preprocessor/CHANGELOG.rst b/openscenario/openscenario_preprocessor/CHANGELOG.rst index 5ecc01bd933..f87d7ff9a93 100644 --- a/openscenario/openscenario_preprocessor/CHANGELOG.rst +++ b/openscenario/openscenario_preprocessor/CHANGELOG.rst @@ -21,6 +21,19 @@ Changelog for package openscenario_preprocessor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.0 (2024-08-21) +------------------ +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/relative-clearance-condition' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Contributors: Kotaro Yoshimoto, Tatsuya Yamasaki + 3.4.4 (2024-08-20) ------------------ diff --git a/openscenario/openscenario_preprocessor/package.xml b/openscenario/openscenario_preprocessor/package.xml index de8f7beb199..da55adb6e8c 100644 --- a/openscenario/openscenario_preprocessor/package.xml +++ b/openscenario/openscenario_preprocessor/package.xml @@ -3,7 +3,7 @@ openscenario_preprocessor - 3.4.4 + 3.5.0 Example package for TIER IV OpenSCENARIO Interpreter Kotaro Yoshimoto Apache License 2.0 diff --git a/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst b/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst index 8acb108dbeb..6cf120d924c 100644 --- a/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst +++ b/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst @@ -21,6 +21,19 @@ Changelog for package openscenario_preprocessor_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.0 (2024-08-21) +------------------ +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/relative-clearance-condition' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Contributors: Kotaro Yoshimoto, Tatsuya Yamasaki + 3.4.4 (2024-08-20) ------------------ diff --git a/openscenario/openscenario_preprocessor_msgs/package.xml b/openscenario/openscenario_preprocessor_msgs/package.xml index 55e5693b836..2e0d1f8fd00 100644 --- a/openscenario/openscenario_preprocessor_msgs/package.xml +++ b/openscenario/openscenario_preprocessor_msgs/package.xml @@ -2,7 +2,7 @@ openscenario_preprocessor_msgs - 3.4.4 + 3.5.0 ROS message types for package openscenario_preprocessor Kotaro Yoshimoto Apache License 2.0 diff --git a/openscenario/openscenario_utility/CHANGELOG.rst b/openscenario/openscenario_utility/CHANGELOG.rst index 9c401ddf272..14ecb74f6de 100644 --- a/openscenario/openscenario_utility/CHANGELOG.rst +++ b/openscenario/openscenario_utility/CHANGELOG.rst @@ -24,6 +24,19 @@ Changelog for package openscenario_utility * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.0 (2024-08-21) +------------------ +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/relative-clearance-condition' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Contributors: Kotaro Yoshimoto, Tatsuya Yamasaki + 3.4.4 (2024-08-20) ------------------ diff --git a/openscenario/openscenario_utility/package.xml b/openscenario/openscenario_utility/package.xml index c4af7f97493..94998e36263 100644 --- a/openscenario/openscenario_utility/package.xml +++ b/openscenario/openscenario_utility/package.xml @@ -2,7 +2,7 @@ openscenario_utility - 3.4.4 + 3.5.0 Utility tools for ASAM OpenSCENARIO 1.2.0 Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_validator/CHANGELOG.rst b/openscenario/openscenario_validator/CHANGELOG.rst index 8bea91d21a1..1024f4e94e1 100644 --- a/openscenario/openscenario_validator/CHANGELOG.rst +++ b/openscenario/openscenario_validator/CHANGELOG.rst @@ -10,6 +10,19 @@ Changelog for package openscenario_validator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.0 (2024-08-21) +------------------ +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/relative-clearance-condition' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Contributors: Kotaro Yoshimoto, Tatsuya Yamasaki + 3.4.4 (2024-08-20) ------------------ diff --git a/openscenario/openscenario_validator/package.xml b/openscenario/openscenario_validator/package.xml index 5632a8479df..fd3beac056c 100644 --- a/openscenario/openscenario_validator/package.xml +++ b/openscenario/openscenario_validator/package.xml @@ -2,7 +2,7 @@ openscenario_validator - 3.4.4 + 3.5.0 Validator for OpenSCENARIO 1.3 Kotaro Yoshimoto Apache License 2.0 diff --git a/rviz_plugins/openscenario_visualization/CHANGELOG.rst b/rviz_plugins/openscenario_visualization/CHANGELOG.rst index abbe25a0c99..848d948bf39 100644 --- a/rviz_plugins/openscenario_visualization/CHANGELOG.rst +++ b/rviz_plugins/openscenario_visualization/CHANGELOG.rst @@ -21,6 +21,19 @@ Changelog for package openscenario_visualization * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.0 (2024-08-21) +------------------ +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/relative-clearance-condition' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Contributors: Kotaro Yoshimoto, Tatsuya Yamasaki + 3.4.4 (2024-08-20) ------------------ diff --git a/rviz_plugins/openscenario_visualization/package.xml b/rviz_plugins/openscenario_visualization/package.xml index 3a4939f91e9..6f77a5b65ea 100644 --- a/rviz_plugins/openscenario_visualization/package.xml +++ b/rviz_plugins/openscenario_visualization/package.xml @@ -2,7 +2,7 @@ openscenario_visualization - 3.4.4 + 3.5.0 Visualization tools for simulation results Masaya Kataoka Kyoichi Sugahara diff --git a/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst b/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst index e4224082b90..e96bed42787 100644 --- a/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst +++ b/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst @@ -21,6 +21,19 @@ Changelog for package real_time_factor_control_rviz_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.0 (2024-08-21) +------------------ +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/relative-clearance-condition' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Contributors: Kotaro Yoshimoto, Tatsuya Yamasaki + 3.4.4 (2024-08-20) ------------------ diff --git a/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml b/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml index 23d385493df..5e5e9b4267e 100644 --- a/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml +++ b/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml @@ -2,7 +2,7 @@ real_time_factor_control_rviz_plugin - 3.4.4 + 3.5.0 Slider controlling real time factor value. Paweł Lech Apache License 2.0 diff --git a/scenario_simulator_v2/CHANGELOG.rst b/scenario_simulator_v2/CHANGELOG.rst index bb67c6847ad..110e106a1f6 100644 --- a/scenario_simulator_v2/CHANGELOG.rst +++ b/scenario_simulator_v2/CHANGELOG.rst @@ -21,6 +21,19 @@ Changelog for package scenario_simulator_v2 * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.0 (2024-08-21) +------------------ +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/relative-clearance-condition' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Contributors: Kotaro Yoshimoto, Tatsuya Yamasaki + 3.4.4 (2024-08-20) ------------------ diff --git a/scenario_simulator_v2/package.xml b/scenario_simulator_v2/package.xml index 38ae9270ca5..a6d95d78fad 100644 --- a/scenario_simulator_v2/package.xml +++ b/scenario_simulator_v2/package.xml @@ -2,7 +2,7 @@ scenario_simulator_v2 - 3.4.4 + 3.5.0 scenario testing framework for Autoware Masaya Kataoka Apache License 2.0 diff --git a/simulation/behavior_tree_plugin/CHANGELOG.rst b/simulation/behavior_tree_plugin/CHANGELOG.rst index dc2d5080d96..46bb38e4585 100644 --- a/simulation/behavior_tree_plugin/CHANGELOG.rst +++ b/simulation/behavior_tree_plugin/CHANGELOG.rst @@ -21,6 +21,19 @@ Changelog for package behavior_tree_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.0 (2024-08-21) +------------------ +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/relative-clearance-condition' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Contributors: Kotaro Yoshimoto, Tatsuya Yamasaki + 3.4.4 (2024-08-20) ------------------ diff --git a/simulation/behavior_tree_plugin/package.xml b/simulation/behavior_tree_plugin/package.xml index b9050d79f14..ccb25126242 100644 --- a/simulation/behavior_tree_plugin/package.xml +++ b/simulation/behavior_tree_plugin/package.xml @@ -2,7 +2,7 @@ behavior_tree_plugin - 3.4.4 + 3.5.0 Behavior tree plugin for traffic_simulator masaya Apache 2.0 diff --git a/simulation/do_nothing_plugin/CHANGELOG.rst b/simulation/do_nothing_plugin/CHANGELOG.rst index cb071e4f97c..33aa50daaf7 100644 --- a/simulation/do_nothing_plugin/CHANGELOG.rst +++ b/simulation/do_nothing_plugin/CHANGELOG.rst @@ -21,6 +21,19 @@ Changelog for package do_nothing_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.0 (2024-08-21) +------------------ +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/relative-clearance-condition' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Contributors: Kotaro Yoshimoto, Tatsuya Yamasaki + 3.4.4 (2024-08-20) ------------------ diff --git a/simulation/do_nothing_plugin/package.xml b/simulation/do_nothing_plugin/package.xml index fcbb05bccd6..a755ce78ec0 100644 --- a/simulation/do_nothing_plugin/package.xml +++ b/simulation/do_nothing_plugin/package.xml @@ -2,7 +2,7 @@ do_nothing_plugin - 3.4.4 + 3.5.0 Behavior plugin for do nothing Masaya Kataoka Apache 2.0 diff --git a/simulation/simple_sensor_simulator/CHANGELOG.rst b/simulation/simple_sensor_simulator/CHANGELOG.rst index 6a0f38d0bd2..0f4b53a7f56 100644 --- a/simulation/simple_sensor_simulator/CHANGELOG.rst +++ b/simulation/simple_sensor_simulator/CHANGELOG.rst @@ -21,6 +21,20 @@ Changelog for package simple_sensor_simulator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.0 (2024-08-21) +------------------ +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/relative-clearance-condition' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Contributors: Kotaro Yoshimoto, Tatsuya Yamasaki + 3.4.4 (2024-08-20) ------------------ diff --git a/simulation/simple_sensor_simulator/package.xml b/simulation/simple_sensor_simulator/package.xml index 36f7759fe79..e589b75cda2 100644 --- a/simulation/simple_sensor_simulator/package.xml +++ b/simulation/simple_sensor_simulator/package.xml @@ -1,7 +1,7 @@ simple_sensor_simulator - 3.4.4 + 3.5.0 simple_sensor_simulator package masaya kataoka diff --git a/simulation/simulation_interface/CHANGELOG.rst b/simulation/simulation_interface/CHANGELOG.rst index a6fc4785e02..8f53e81a059 100644 --- a/simulation/simulation_interface/CHANGELOG.rst +++ b/simulation/simulation_interface/CHANGELOG.rst @@ -21,6 +21,20 @@ Changelog for package simulation_interface * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.0 (2024-08-21) +------------------ +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/relative-clearance-condition' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Contributors: Kotaro Yoshimoto, Tatsuya Yamasaki + 3.4.4 (2024-08-20) ------------------ diff --git a/simulation/simulation_interface/package.xml b/simulation/simulation_interface/package.xml index 74e8e8039d1..7eac6ccca06 100644 --- a/simulation/simulation_interface/package.xml +++ b/simulation/simulation_interface/package.xml @@ -2,7 +2,7 @@ simulation_interface - 3.4.4 + 3.5.0 packages to define interface between simulator and scenario interpreter Masaya Kataoka Apache License 2.0 diff --git a/simulation/traffic_simulator/CHANGELOG.rst b/simulation/traffic_simulator/CHANGELOG.rst index 567fd4a7619..0b77efa5042 100644 --- a/simulation/traffic_simulator/CHANGELOG.rst +++ b/simulation/traffic_simulator/CHANGELOG.rst @@ -21,6 +21,27 @@ Changelog for package traffic_simulator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.0 (2024-08-21) +------------------ +* Merge pull request `#1316 `_ from tier4/relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* refactor: use std::size_t instead of raw size_t + Co-authored-by: Tatsuya Yamasaki +* Merge branch 'master' into relative-clearance-condition +* refactor: use std::find instead of std::find_if +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* fix tests for HdMapUtils::countLaneChanges +* Merge remote-tracking branch 'origin/relative-clearance-condition' into relative-clearance-condition +* Implement HdMapUtils::countLaneChanges +* Implement HdMapUtils::countLaneChangesAlongRoute +* Merge branch 'master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Contributors: Kotaro Yoshimoto, Tatsuya Yamasaki + 3.4.4 (2024-08-20) ------------------ diff --git a/simulation/traffic_simulator/package.xml b/simulation/traffic_simulator/package.xml index 7ecd9902c03..540e9d980fc 100644 --- a/simulation/traffic_simulator/package.xml +++ b/simulation/traffic_simulator/package.xml @@ -1,7 +1,7 @@ traffic_simulator - 3.4.4 + 3.5.0 control traffic flow masaya kataoka diff --git a/simulation/traffic_simulator_msgs/CHANGELOG.rst b/simulation/traffic_simulator_msgs/CHANGELOG.rst index 6101cee915d..2a75d18c2b9 100644 --- a/simulation/traffic_simulator_msgs/CHANGELOG.rst +++ b/simulation/traffic_simulator_msgs/CHANGELOG.rst @@ -21,6 +21,19 @@ Changelog for package openscenario_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.0 (2024-08-21) +------------------ +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/relative-clearance-condition' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Contributors: Kotaro Yoshimoto, Tatsuya Yamasaki + 3.4.4 (2024-08-20) ------------------ diff --git a/simulation/traffic_simulator_msgs/package.xml b/simulation/traffic_simulator_msgs/package.xml index 517e478699b..a757a7725c8 100644 --- a/simulation/traffic_simulator_msgs/package.xml +++ b/simulation/traffic_simulator_msgs/package.xml @@ -2,7 +2,7 @@ traffic_simulator_msgs - 3.4.4 + 3.5.0 ROS messages for openscenario Masaya Kataoka Apache License 2.0 diff --git a/test_runner/random_test_runner/CHANGELOG.rst b/test_runner/random_test_runner/CHANGELOG.rst index d025b37fbda..5fc9292f0c0 100644 --- a/test_runner/random_test_runner/CHANGELOG.rst +++ b/test_runner/random_test_runner/CHANGELOG.rst @@ -21,6 +21,19 @@ Changelog for package random_test_runner * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.0 (2024-08-21) +------------------ +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/relative-clearance-condition' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Contributors: Kotaro Yoshimoto, Tatsuya Yamasaki + 3.4.4 (2024-08-20) ------------------ * Merge pull request `#1345 `_ from tier4/newline-character-literal diff --git a/test_runner/random_test_runner/package.xml b/test_runner/random_test_runner/package.xml index 4f773aebdeb..d0dbd53a058 100644 --- a/test_runner/random_test_runner/package.xml +++ b/test_runner/random_test_runner/package.xml @@ -2,7 +2,7 @@ random_test_runner - 3.4.4 + 3.5.0 Random behavior test runner piotr-zyskowski-rai Apache License 2.0 diff --git a/test_runner/scenario_test_runner/CHANGELOG.rst b/test_runner/scenario_test_runner/CHANGELOG.rst index c4c9a01a447..33ccb31848d 100644 --- a/test_runner/scenario_test_runner/CHANGELOG.rst +++ b/test_runner/scenario_test_runner/CHANGELOG.rst @@ -35,6 +35,25 @@ Changelog for package scenario_test_runner * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.0 (2024-08-21) +------------------ +* Merge pull request `#1316 `_ from tier4/relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* feat: add test scenarios for RelativeClearanceCondition to CI test +* Merge branch 'master' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Add ByEntityCondition.EntityCondition.RelativeClearanceCondition-back.yaml +* Update ByEntityCondition.EntityCondition.RelativeClearanceCondition.yaml to be a better test +* Update ByEntityCondition.EntityCondition.RelativeClearanceCondition.yaml to check RelativeClearanceCondition in more detail +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Merge remote-tracking branch 'origin/relative-clearance-condition' into relative-clearance-condition +* Merge branch 'master' into relative-clearance-condition +* feat: add ByEntityCondition.EntityCondition.RelativeClearanceCondition.yaml +* Merge remote-tracking branch 'origin/master' into relative-clearance-condition +* Contributors: Kotaro Yoshimoto, Tatsuya Yamasaki + 3.4.4 (2024-08-20) ------------------ diff --git a/test_runner/scenario_test_runner/package.xml b/test_runner/scenario_test_runner/package.xml index 673f48e4723..0883d2fd03f 100644 --- a/test_runner/scenario_test_runner/package.xml +++ b/test_runner/scenario_test_runner/package.xml @@ -2,7 +2,7 @@ scenario_test_runner - 3.4.4 + 3.5.0 scenario test runner package Tatsuya Yamasaki Apache License 2.0 From 0456a5203c9be905cee7c1bcebabebdca8da331e Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Wed, 21 Aug 2024 17:22:21 +0900 Subject: [PATCH 143/304] chore: add corner case to fix into a scenario --- ...yCondition.DistanceCondition.Shortest.yaml | 29 +++++++++++++++++++ 1 file changed, 29 insertions(+) diff --git a/test_runner/scenario_test_runner/scenario/ByEntityCondition.EntityCondition.DistanceCondition.Shortest.yaml b/test_runner/scenario_test_runner/scenario/ByEntityCondition.EntityCondition.DistanceCondition.Shortest.yaml index 712febf2313..68d0bea8762 100644 --- a/test_runner/scenario_test_runner/scenario/ByEntityCondition.EntityCondition.DistanceCondition.Shortest.yaml +++ b/test_runner/scenario_test_runner/scenario/ByEntityCondition.EntityCondition.DistanceCondition.Shortest.yaml @@ -92,6 +92,17 @@ OpenSCENARIO: offset: 0 Orientation: *DEFAULT_ORIENTATION - LongitudinalAction: *SPEED_ACTION_ZERO + - entityRef: car_4 + PrivateAction: + - TeleportAction: + Position: &POSITION_4 + LanePosition: + roadId: "" + laneId: 34795 + s: 5 + offset: 0 + Orientation: *DEFAULT_ORIENTATION + - LongitudinalAction: *SPEED_ACTION_ZERO Story: - name: story Act: @@ -582,6 +593,24 @@ OpenSCENARIO: routingAlgorithm: shortest rule: notEqualTo value: 1.262040583529198123358128214022 + - Condition: + - name: "corner case fixed in #1348" + delay: 0 + conditionEdge: none + ByEntityCondition: + TriggeringEntities: + triggeringEntitiesRule: all + EntityRef: + - entityRef: car_1 + EntityCondition: + RelativeDistanceCondition: + coordinateSystem: lane + entityRef: car_4 + freespace: false + relativeDistanceType: longitudinal + routingAlgorithm: shortest + rule: notEqualTo + value: 54.18867466433655977198213804513216018676757812500000 StartTrigger: ConditionGroup: - Condition: From 74695139820b14d5e341d8d5748d2dbcf4f4aaa9 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Wed, 21 Aug 2024 17:24:36 +0900 Subject: [PATCH 144/304] fix: longitudinal calculation with lane-change --- simulation/traffic_simulator/src/hdmap_utils/hdmap_utils.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/simulation/traffic_simulator/src/hdmap_utils/hdmap_utils.cpp b/simulation/traffic_simulator/src/hdmap_utils/hdmap_utils.cpp index 36842da9b7a..9ffa6c81030 100644 --- a/simulation/traffic_simulator/src/hdmap_utils/hdmap_utils.cpp +++ b/simulation/traffic_simulator/src/hdmap_utils/hdmap_utils.cpp @@ -1560,9 +1560,9 @@ auto HdMapUtils::getLongitudinalDistance( /// @note "first lanelet before the lane change" case if (route[i] == from.lanelet_id) { - distance += getLaneletLength(route[i + 1]) - from.s; + distance -= from.s; if (route[i + 1] == to.lanelet_id) { - distance -= getLaneletLength(route[i + 1]) - to.s; + distance += to.s; return distance; } } From fe29d6b2d0af6bfb92e34ad66dc16007aafe3f8d Mon Sep 17 00:00:00 2001 From: robomic Date: Wed, 21 Aug 2024 15:22:45 +0200 Subject: [PATCH 145/304] combine 2 PR, apply review requests --- .../include/geometry/polygon/line_segment.hpp | 6 +- .../src/intersection/intersection.cpp | 49 +++------ .../geometry/src/polygon/line_segment.cpp | 100 ++++++++++++------ 3 files changed, 89 insertions(+), 66 deletions(-) diff --git a/common/math/geometry/include/geometry/polygon/line_segment.hpp b/common/math/geometry/include/geometry/polygon/line_segment.hpp index ec17419f31d..1da41a504e4 100644 --- a/common/math/geometry/include/geometry/polygon/line_segment.hpp +++ b/common/math/geometry/include/geometry/polygon/line_segment.hpp @@ -43,7 +43,7 @@ class LineSegment auto getPose(const double s, const bool denormalize_s = false, const bool fill_pitch = true) const -> geometry_msgs::msg::Pose; auto isIntersect2D(const geometry_msgs::msg::Point & point) const -> bool; - auto isIntersect2D(const LineSegment & l0) const -> bool; + auto isIntersect2D(const LineSegment & line) const -> bool; auto getIntersection2DSValue( const geometry_msgs::msg::Point & point, const bool denormalize_s = false) const -> std::optional; @@ -66,8 +66,12 @@ class LineSegment auto getSquaredDistanceVector( const geometry_msgs::msg::Point & point, const double s, const bool denormalize_s = false) const -> geometry_msgs::msg::Vector3; + auto isInBounds2D(const geometry_msgs::msg::Point & point) const -> bool; + auto relativePointPosition2D(const geometry_msgs::msg::Point & point) const -> int; private: + const double length; + const double length2D; auto denormalize(const std::optional & s, const bool throw_error_on_out_of_range = true) const -> std::optional; auto denormalize(const double s) const -> double; diff --git a/common/math/geometry/src/intersection/intersection.cpp b/common/math/geometry/src/intersection/intersection.cpp index 0c8e83571a6..c2a7665eac3 100644 --- a/common/math/geometry/src/intersection/intersection.cpp +++ b/common/math/geometry/src/intersection/intersection.cpp @@ -21,44 +21,23 @@ namespace geometry { bool isIntersect2D(const LineSegment & line0, const LineSegment & line1) { - using Point = geometry_msgs::msg::Point; + const auto &p0 = line0.start_point, &q0 = line0.end_point; + const auto &p1 = line1.start_point, &q1 = line1.end_point; - const auto p0 = line0.start_point, q0 = line0.end_point; - const auto p1 = line1.start_point, q1 = line1.end_point; + const int relative_position_p0 = line1.relativePointPosition2D(p0); + const int relative_position_q0 = line1.relativePointPosition2D(q0); + const int relative_position_p1 = line0.relativePointPosition2D(p1); + const int relative_position_q1 = line0.relativePointPosition2D(q1); - constexpr auto within_bounding_box = - [](const Point & start, const Point & end, const Point & to_check) -> bool { - const bool x_inside = ((to_check.x - start.x) * (end.x - to_check.x) >= 0.0); - const bool y_inside = ((to_check.y - start.y) * (end.y - to_check.y) >= 0.0); - return x_inside && y_inside; - }; - - constexpr auto orientation = - [](const Point & start, const Point & end, const Point & to_check) -> double { - return (end.y - start.y) * (to_check.x - end.x) - (end.x - start.x) * (to_check.y - end.y); - }; - - constexpr auto sign = [](const double x) -> int { - constexpr double tolerance = 1.0e-10; - if (x > +tolerance) return +1; - if (x < -tolerance) return -1; - return 0; - }; - - const int ori_p0 = sign(orientation(p1, q1, p0)); - const int ori_q0 = sign(orientation(p1, q1, q0)); - const int ori_p1 = sign(orientation(p0, q0, p1)); - const int ori_q1 = sign(orientation(p0, q0, q1)); - - // Special case - // If the lines are collinear; they intersect if and only if their bounding boxes overlap - if (ori_p1 == 0 && ori_q1 == 0 && ori_p0 == 0 && ori_q0 == 0) { - return within_bounding_box(p0, q0, p1) || within_bounding_box(p0, q0, p1) || - within_bounding_box(p1, q1, p0) || within_bounding_box(p1, q1, p0); + if ( + relative_position_p1 == 0 && relative_position_q1 == 0 && relative_position_p0 == 0 && + relative_position_q0 == 0) { + return line0.isInBounds2D(p1) || line0.isInBounds2D(q1) || line1.isInBounds2D(p0) || + line1.isInBounds2D(q0); + } else { + return relative_position_p1 != relative_position_q1 && + relative_position_p0 != relative_position_q0; } - - // General case - return ori_p1 != ori_q1 && ori_p0 != ori_q0; } bool isIntersect2D(const std::vector & lines) diff --git a/common/math/geometry/src/polygon/line_segment.cpp b/common/math/geometry/src/polygon/line_segment.cpp index 80388c6913e..a0a16d979f9 100644 --- a/common/math/geometry/src/polygon/line_segment.cpp +++ b/common/math/geometry/src/polygon/line_segment.cpp @@ -29,14 +29,18 @@ namespace geometry { LineSegment::LineSegment( const geometry_msgs::msg::Point & start_point, const geometry_msgs::msg::Point & end_point) -: start_point(start_point), end_point(end_point) +: start_point(start_point), + end_point(end_point), + length(hypot(end_point, start_point)), + length2D(std::hypot(end_point.x - start_point.x, end_point.y - start_point.y)) { } LineSegment::LineSegment( const geometry_msgs::msg::Point & start_point, const geometry_msgs::msg::Vector3 & vec, double length) -: start_point(start_point), end_point([&]() -> geometry_msgs::msg::Point { +: start_point(start_point), + end_point([&]() -> geometry_msgs::msg::Point { geometry_msgs::msg::Point ret; double vec_size = std::hypot(vec.x, vec.y); if (vec_size == 0.0) { @@ -50,7 +54,9 @@ LineSegment::LineSegment( ret.y = start_point.y + vec.y / vec_size * length; ret.z = start_point.z + vec.z / vec_size * length; return ret; - }()) + }()), + length(hypot(end_point, start_point)), + length2D(std::hypot(end_point.x - start_point.x, end_point.y - start_point.y)) { } @@ -117,7 +123,7 @@ auto LineSegment::getPose(const double s, const bool denormalize_s, const bool f * @brief Checking the intersection with 1 line segment and 1 point in 2D (x,y) coordinate. Ignore z axis. * @param point point you want to check intersection. * @return true Intersection detected. - * @return false Intersection does not detected. + * @return false Intersection not detected. */ auto LineSegment::isIntersect2D(const geometry_msgs::msg::Point & point) const -> bool { @@ -126,12 +132,10 @@ auto LineSegment::isIntersect2D(const geometry_msgs::msg::Point & point) const - if (x_outside || y_outside) { return false; } - const double dx = end_point.x - start_point.x; - const double dy = end_point.y - start_point.y; - const double squared_length = dx * dx + dy * dy; - const double cross_product = (point.y - start_point.y) * dx - (point.x - start_point.x) * dy; + const double cross_product = (point.y - start_point.y) * (end_point.x - start_point.x) - + (point.x - start_point.x) * (end_point.y - start_point.y); constexpr double tolerance = std::numeric_limits::epsilon(); - return cross_product * cross_product <= squared_length * tolerance * tolerance; + return std::abs(cross_product) <= get2DLength() * tolerance; } auto LineSegment::getSValue( @@ -149,13 +153,13 @@ auto LineSegment::getSValue( /** * @brief Checking the intersection with 2 line segments in 2D (x,y) coordinate. Ignore z axis. - * @param l0 line segments you want to check intersection. + * @param line line segments you want to check intersection. * @return true Intersection detected. - * @return false Intersection does not detected. + * @return false Intersection not detected. */ -auto LineSegment::isIntersect2D(const LineSegment & l0) const -> bool +auto LineSegment::isIntersect2D(const LineSegment & line) const -> bool { - return math::geometry::isIntersect2D(*this, l0); + return math::geometry::isIntersect2D(*this, line); } /** @@ -166,9 +170,13 @@ auto LineSegment::isIntersect2D(const LineSegment & l0) const -> bool auto LineSegment::getIntersection2DSValue( const geometry_msgs::msg::Point & point, const bool denormalize_s) const -> std::optional { - if (not isIntersect2D(point)) return std::nullopt; - const double distance = std::hypot(point.x - start_point.x, point.y - start_point.y); - return denormalize_s ? std::make_optional(distance) : std::make_optional(distance / getLength()); + if (isIntersect2D(point)) { + const double distance = std::hypot(point.x - start_point.x, point.y - start_point.y); + return denormalize_s ? std::make_optional(distance) + : std::make_optional(distance / get2DLength()); + } else { + return std::nullopt; + } } /** @@ -224,13 +232,10 @@ auto LineSegment::getIntersection2D(const LineSegment & line) const auto LineSegment::getVector() const -> geometry_msgs::msg::Vector3 { - using math::geometry::operator-; - const auto result_pt = end_point - start_point; - auto result = geometry_msgs::msg::Vector3(); - result.x = result_pt.x; - result.y = result_pt.y; - result.z = result_pt.z; - return result; + return geometry_msgs::build() + .x(end_point.x - start_point.x) + .y(end_point.y - start_point.y) + .z(end_point.z - start_point.z); } /** @@ -244,7 +249,7 @@ auto LineSegment::getNormalVector() const -> geometry_msgs::msg::Vector3 return geometry_msgs::build() .x(tangent_vec.x * std::cos(theta) - tangent_vec.y * std::sin(theta)) .y(tangent_vec.x * std::sin(theta) + tangent_vec.y * std::cos(theta)) - .z(0); + .z(0.0); } auto LineSegment::get2DVector() const -> geometry_msgs::msg::Vector3 @@ -252,15 +257,12 @@ auto LineSegment::get2DVector() const -> geometry_msgs::msg::Vector3 return geometry_msgs::build() .x(end_point.x - start_point.x) .y(end_point.y - start_point.y) - .z(0); + .z(0.0); } -auto LineSegment::get2DLength() const -> double -{ - return std::hypot(end_point.x - start_point.x, end_point.y - start_point.y); -} +auto LineSegment::get2DLength() const -> double { return length2D; } -auto LineSegment::getLength() const -> double { return hypot(end_point, start_point); } +auto LineSegment::getLength() const -> double { return length; } auto LineSegment::getSlope() const -> double { @@ -359,5 +361,43 @@ auto getLineSegments( } } +/** + * @brief Checks if the given point lies within the bounding box of the line segment. + * @param point Points you want to test. + * @return + * - `true` if the points is within the bounds. + * - `false` otherwise. + */ +auto LineSegment::isInBounds2D(const geometry_msgs::msg::Point & point) const -> bool +{ + return ( + point.x >= std::min(start_point.x, end_point.x) && + point.x <= std::max(start_point.x, end_point.x) && + point.y >= std::min(start_point.y, end_point.y) && + point.y <= std::max(start_point.y, end_point.y)); +} + +/** + * @brief Determines the relative position of a point with respect to the line segment. + * + * This method computes the relative position of a given point with respect to the line segment defined by + * `start_point` and `end_point` using a cross product. The result indicates on which side of the line + * segment the point lies. + * + * @param point The point to be evaluated. + * @return + * - `1` if the point is to the left of the line segment (when moving from `start_point` to `end_point`). + * - `-1` if the point is to the right of the line segment. + * - `0` if the point is collinear with the line segment (i.e., lies exactly on the line defined by + * `start_point` and `end_point`). + */ +auto LineSegment::relativePointPosition2D(const geometry_msgs::msg::Point & point) const -> int +{ + constexpr double tolerance = std::numeric_limits::epsilon(); + const double determinant = (end_point.y - start_point.y) * (point.x - end_point.x) - + (end_point.x - start_point.x) * (point.y - end_point.y); + return static_cast(determinant > tolerance) - static_cast(determinant < -tolerance); +} + } // namespace geometry } // namespace math From 05376cbc974d53566dff51e0bc12dd93edaa330b Mon Sep 17 00:00:00 2001 From: robomic Date: Wed, 21 Aug 2024 15:42:15 +0200 Subject: [PATCH 146/304] use isInBounds function --- common/math/geometry/src/polygon/line_segment.cpp | 13 ++++++------- 1 file changed, 6 insertions(+), 7 deletions(-) diff --git a/common/math/geometry/src/polygon/line_segment.cpp b/common/math/geometry/src/polygon/line_segment.cpp index a0a16d979f9..9b0c7857445 100644 --- a/common/math/geometry/src/polygon/line_segment.cpp +++ b/common/math/geometry/src/polygon/line_segment.cpp @@ -127,15 +127,14 @@ auto LineSegment::getPose(const double s, const bool denormalize_s, const bool f */ auto LineSegment::isIntersect2D(const geometry_msgs::msg::Point & point) const -> bool { - const bool x_outside = ((point.x - start_point.x) * (end_point.x - point.x) < 0.0); - const bool y_outside = ((point.y - start_point.y) * (end_point.y - point.y) < 0.0); - if (x_outside || y_outside) { + if (isInBounds2D(point)) { + const double cross_product = (point.y - start_point.y) * (end_point.x - start_point.x) - + (point.x - start_point.x) * (end_point.y - start_point.y); + constexpr double tolerance = std::numeric_limits::epsilon(); + return std::abs(cross_product) <= get2DLength() * tolerance; + } else { return false; } - const double cross_product = (point.y - start_point.y) * (end_point.x - start_point.x) - - (point.x - start_point.x) * (end_point.y - start_point.y); - constexpr double tolerance = std::numeric_limits::epsilon(); - return std::abs(cross_product) <= get2DLength() * tolerance; } auto LineSegment::getSValue( From 8b508a9c99b4b2cf48cf4c3c2ef3bcec09f0efb7 Mon Sep 17 00:00:00 2001 From: robomic Date: Wed, 21 Aug 2024 16:29:55 +0200 Subject: [PATCH 147/304] vector fields for LineSegment class, cleanup --- .../include/geometry/polygon/line_segment.hpp | 4 +- .../geometry/src/polygon/line_segment.cpp | 63 ++++++++----------- 2 files changed, 29 insertions(+), 38 deletions(-) diff --git a/common/math/geometry/include/geometry/polygon/line_segment.hpp b/common/math/geometry/include/geometry/polygon/line_segment.hpp index 1da41a504e4..3a424c3e315 100644 --- a/common/math/geometry/include/geometry/polygon/line_segment.hpp +++ b/common/math/geometry/include/geometry/polygon/line_segment.hpp @@ -71,7 +71,9 @@ class LineSegment private: const double length; - const double length2D; + const double length_2d; + const geometry_msgs::msg::Vector3 vector; + const geometry_msgs::msg::Vector3 vector_2d; auto denormalize(const std::optional & s, const bool throw_error_on_out_of_range = true) const -> std::optional; auto denormalize(const double s) const -> double; diff --git a/common/math/geometry/src/polygon/line_segment.cpp b/common/math/geometry/src/polygon/line_segment.cpp index 9b0c7857445..6c11f0716f9 100644 --- a/common/math/geometry/src/polygon/line_segment.cpp +++ b/common/math/geometry/src/polygon/line_segment.cpp @@ -32,16 +32,22 @@ LineSegment::LineSegment( : start_point(start_point), end_point(end_point), length(hypot(end_point, start_point)), - length2D(std::hypot(end_point.x - start_point.x, end_point.y - start_point.y)) + length_2d(std::hypot(end_point.x - start_point.x, end_point.y - start_point.y)), + vector(geometry_msgs::build() + .x(end_point.x - start_point.x) + .y(end_point.y - start_point.y) + .z(end_point.z - start_point.z)), + vector_2d(geometry_msgs::build() + .x(end_point.x - start_point.x) + .y(end_point.y - start_point.y) + .z(0.0)) { } LineSegment::LineSegment( const geometry_msgs::msg::Point & start_point, const geometry_msgs::msg::Vector3 & vec, - double length) -: start_point(start_point), - end_point([&]() -> geometry_msgs::msg::Point { - geometry_msgs::msg::Point ret; + const double length) +: LineSegment::LineSegment(start_point, [&]() -> geometry_msgs::msg::Point { double vec_size = std::hypot(vec.x, vec.y); if (vec_size == 0.0) { THROW_SIMULATION_ERROR( @@ -50,13 +56,11 @@ LineSegment::LineSegment( "This message is not originally intended to be displayed, if you see it, please " "contact the developer of traffic_simulator."); } - ret.x = start_point.x + vec.x / vec_size * length; - ret.y = start_point.y + vec.y / vec_size * length; - ret.z = start_point.z + vec.z / vec_size * length; - return ret; - }()), - length(hypot(end_point, start_point)), - length2D(std::hypot(end_point.x - start_point.x, end_point.y - start_point.y)) + return geometry_msgs::build() + .x(start_point.x + vec.x / vec_size * length) + .y(start_point.y + vec.y / vec_size * length) + .z(start_point.z + vec.z / vec_size * length); + }()) { } @@ -74,8 +78,8 @@ auto LineSegment::getPoint(const double s, const bool denormalize_s) const const double s_normalized = denormalize_s ? s / getLength() : s; if (0 <= s_normalized && s_normalized <= 1) { return geometry_msgs::build() - .x(start_point.x + (end_point.x - start_point.x) * s_normalized) - .y(start_point.y + (end_point.y - start_point.y) * s_normalized) + .x(start_point.x + get2DVector().x * s_normalized) + .y(start_point.y + get2DVector().y * s_normalized) .z(start_point.z + (end_point.z - start_point.z) * s_normalized); } if (denormalize_s) { @@ -128,8 +132,8 @@ auto LineSegment::getPose(const double s, const bool denormalize_s, const bool f auto LineSegment::isIntersect2D(const geometry_msgs::msg::Point & point) const -> bool { if (isInBounds2D(point)) { - const double cross_product = (point.y - start_point.y) * (end_point.x - start_point.x) - - (point.x - start_point.x) * (end_point.y - start_point.y); + const double cross_product = + (point.y - start_point.y) * get2DVector().x - (point.x - start_point.x) * get2DVector().y; constexpr double tolerance = std::numeric_limits::epsilon(); return std::abs(cross_product) <= get2DLength() * tolerance; } else { @@ -229,13 +233,7 @@ auto LineSegment::getIntersection2D(const LineSegment & line) const : std::optional(); } -auto LineSegment::getVector() const -> geometry_msgs::msg::Vector3 -{ - return geometry_msgs::build() - .x(end_point.x - start_point.x) - .y(end_point.y - start_point.y) - .z(end_point.z - start_point.z); -} +auto LineSegment::getVector() const -> geometry_msgs::msg::Vector3 { return vector; } /** * @brief Get normal vector of the line segment. @@ -251,22 +249,13 @@ auto LineSegment::getNormalVector() const -> geometry_msgs::msg::Vector3 .z(0.0); } -auto LineSegment::get2DVector() const -> geometry_msgs::msg::Vector3 -{ - return geometry_msgs::build() - .x(end_point.x - start_point.x) - .y(end_point.y - start_point.y) - .z(0.0); -} +auto LineSegment::get2DVector() const -> geometry_msgs::msg::Vector3 { return vector_2d; } -auto LineSegment::get2DLength() const -> double { return length2D; } +auto LineSegment::get2DLength() const -> double { return length_2d; } auto LineSegment::getLength() const -> double { return length; } -auto LineSegment::getSlope() const -> double -{ - return (end_point.y - start_point.y) / (end_point.x - start_point.x); -} +auto LineSegment::getSlope() const -> double { return get2DVector().y / get2DVector().x; } /** * @brief Get squared distance (Square of euclidean distance) between specified 3D point and specified 3D point on line segment in 2D. (x,y) @@ -393,8 +382,8 @@ auto LineSegment::isInBounds2D(const geometry_msgs::msg::Point & point) const -> auto LineSegment::relativePointPosition2D(const geometry_msgs::msg::Point & point) const -> int { constexpr double tolerance = std::numeric_limits::epsilon(); - const double determinant = (end_point.y - start_point.y) * (point.x - end_point.x) - - (end_point.x - start_point.x) * (point.y - end_point.y); + const double determinant = + get2DVector().y * (point.x - end_point.x) - get2DVector().x * (point.y - end_point.y); return static_cast(determinant > tolerance) - static_cast(determinant < -tolerance); } From a2d84a63e5ebde24bb287c96f3b9ea257d17037a Mon Sep 17 00:00:00 2001 From: robomic Date: Wed, 21 Aug 2024 17:02:12 +0200 Subject: [PATCH 148/304] return const& and remove implicit conversions --- .../include/geometry/polygon/line_segment.hpp | 10 +++--- .../geometry/src/polygon/line_segment.cpp | 34 +++++++++---------- 2 files changed, 23 insertions(+), 21 deletions(-) diff --git a/common/math/geometry/include/geometry/polygon/line_segment.hpp b/common/math/geometry/include/geometry/polygon/line_segment.hpp index 3a424c3e315..d3efd8679a6 100644 --- a/common/math/geometry/include/geometry/polygon/line_segment.hpp +++ b/common/math/geometry/include/geometry/polygon/line_segment.hpp @@ -29,6 +29,9 @@ namespace geometry class LineSegment { public: + const geometry_msgs::msg::Point start_point; + const geometry_msgs::msg::Point end_point; + LineSegment( const geometry_msgs::msg::Point & start_point, const geometry_msgs::msg::Point & end_point); LineSegment( @@ -36,8 +39,6 @@ class LineSegment double length); ~LineSegment(); LineSegment & operator=(const LineSegment &); - const geometry_msgs::msg::Point start_point; - const geometry_msgs::msg::Point end_point; auto getPoint(const double s, const bool denormalize_s = false) const -> geometry_msgs::msg::Point; auto getPose(const double s, const bool denormalize_s = false, const bool fill_pitch = true) const @@ -54,9 +55,9 @@ class LineSegment auto getSValue( const geometry_msgs::msg::Pose & pose, double threshold_distance, bool denormalize_s) const -> std::optional; - auto getVector() const -> geometry_msgs::msg::Vector3; + auto getVector() const -> const geometry_msgs::msg::Vector3 &; auto getNormalVector() const -> geometry_msgs::msg::Vector3; - auto get2DVector() const -> geometry_msgs::msg::Vector3; + auto get2DVector() const -> const geometry_msgs::msg::Vector3 &; auto getLength() const -> double; auto get2DLength() const -> double; auto getSlope() const -> double; @@ -74,6 +75,7 @@ class LineSegment const double length_2d; const geometry_msgs::msg::Vector3 vector; const geometry_msgs::msg::Vector3 vector_2d; + auto denormalize(const std::optional & s, const bool throw_error_on_out_of_range = true) const -> std::optional; auto denormalize(const double s) const -> double; diff --git a/common/math/geometry/src/polygon/line_segment.cpp b/common/math/geometry/src/polygon/line_segment.cpp index 6c11f0716f9..196565215ff 100644 --- a/common/math/geometry/src/polygon/line_segment.cpp +++ b/common/math/geometry/src/polygon/line_segment.cpp @@ -76,7 +76,7 @@ auto LineSegment::getPoint(const double s, const bool denormalize_s) const -> geometry_msgs::msg::Point { const double s_normalized = denormalize_s ? s / getLength() : s; - if (0 <= s_normalized && s_normalized <= 1) { + if (0.0 <= s_normalized && s_normalized <= 1.0) { return geometry_msgs::build() .x(start_point.x + get2DVector().x * s_normalized) .y(start_point.y + get2DVector().y * s_normalized) @@ -113,13 +113,12 @@ auto LineSegment::getPose(const double s, const bool denormalize_s, const bool f return geometry_msgs::build() .position(getPoint(s, denormalize_s)) .orientation([this, fill_pitch]() -> geometry_msgs::msg::Quaternion { - const auto tangent_vec = getVector(); return math::geometry::convertEulerAngleToQuaternion( geometry_msgs::build() .x(0.0) .y( - fill_pitch ? std::atan2(-tangent_vec.z, std::hypot(tangent_vec.x, tangent_vec.y)) : 0.0) - .z(std::atan2(tangent_vec.y, tangent_vec.x))); + fill_pitch ? std::atan2(-getVector().z, std::hypot(getVector().x, getVector().y)) : 0.0) + .z(std::atan2(getVector().y, getVector().x))); }()); } @@ -148,9 +147,11 @@ auto LineSegment::getSValue( return getIntersection2DSValue( LineSegment( math::geometry::transformPoint( - pose, geometry_msgs::build().x(0).y(threshold_distance).z(0)), + pose, + geometry_msgs::build().x(0.0).y(threshold_distance).z(0.0)), math::geometry::transformPoint( - pose, geometry_msgs::build().x(0).y(-threshold_distance).z(0))), + pose, + geometry_msgs::build().x(0.0).y(-threshold_distance).z(0.0))), denormalize_s); } @@ -200,9 +201,9 @@ auto LineSegment::getIntersection2DSValue(const LineSegment & line, const bool d const double det = (start_point.x - end_point.x) * (line.end_point.y - line.start_point.y) - (line.end_point.x - line.start_point.x) * (start_point.y - end_point.y); const double s = - 1 - ((line.end_point.y - line.start_point.y) * (line.end_point.x - end_point.x) + - (line.start_point.x - line.end_point.x) * (line.end_point.y - end_point.y)) / - det; + 1.0 - ((line.end_point.y - line.start_point.y) * (line.end_point.x - end_point.x) + + (line.start_point.x - line.end_point.x) * (line.end_point.y - end_point.y)) / + det; if (std::isnan(s)) { THROW_SIMULATION_ERROR( "One line segment is on top of the other. So determinant is zero.", @@ -210,7 +211,7 @@ auto LineSegment::getIntersection2DSValue(const LineSegment & line, const bool d "This message is not originally intended to be displayed, if you see it, please " "contact the developer of traffic_simulator."); } - return (-s_tolerance <= s && s <= 1 + s_tolerance) + return (-s_tolerance <= s && s <= 1.0 + s_tolerance) ? std::optional(std::clamp(s, 0.0, 1.0)) : std::optional(); }; @@ -233,7 +234,7 @@ auto LineSegment::getIntersection2D(const LineSegment & line) const : std::optional(); } -auto LineSegment::getVector() const -> geometry_msgs::msg::Vector3 { return vector; } +auto LineSegment::getVector() const -> const geometry_msgs::msg::Vector3 & { return vector; } /** * @brief Get normal vector of the line segment. @@ -241,15 +242,14 @@ auto LineSegment::getVector() const -> geometry_msgs::msg::Vector3 { return vect */ auto LineSegment::getNormalVector() const -> geometry_msgs::msg::Vector3 { - geometry_msgs::msg::Vector3 tangent_vec = getVector(); double theta = M_PI / 2.0; return geometry_msgs::build() - .x(tangent_vec.x * std::cos(theta) - tangent_vec.y * std::sin(theta)) - .y(tangent_vec.x * std::sin(theta) + tangent_vec.y * std::cos(theta)) + .x(getVector().x * std::cos(theta) - getVector().y * std::sin(theta)) + .y(getVector().x * std::sin(theta) + getVector().y * std::cos(theta)) .z(0.0); } -auto LineSegment::get2DVector() const -> geometry_msgs::msg::Vector3 { return vector_2d; } +auto LineSegment::get2DVector() const -> const geometry_msgs::msg::Vector3 & { return vector_2d; } auto LineSegment::get2DLength() const -> double { return length_2d; } @@ -300,7 +300,7 @@ auto LineSegment::denormalize( const std::optional & s, const bool throw_error_on_out_of_range) const -> std::optional { - if (!throw_error_on_out_of_range && s && !(0 <= s.value() && s.value() <= 1)) { + if (!throw_error_on_out_of_range && s && !(0.0 <= s.value() && s.value() <= 1.0)) { return std::optional(); } return s ? denormalize(s.value()) : std::optional(); @@ -313,7 +313,7 @@ auto LineSegment::denormalize( */ auto LineSegment::denormalize(const double s) const -> double { - if (0 <= s && s <= 1) { + if (0.0 <= s && s <= 1.0) { return s * getLength(); } THROW_SIMULATION_ERROR( From 4d88bb0eb694953ea3bd9c7460fd5c6910389167 Mon Sep 17 00:00:00 2001 From: Release Bot Date: Thu, 22 Aug 2024 02:04:58 +0000 Subject: [PATCH 149/304] Bump version of scenario_simulator_v2 from version 3.5.0 to version 3.5.1 --- common/math/arithmetic/CHANGELOG.rst | 8 ++++++++ common/math/arithmetic/package.xml | 2 +- common/math/geometry/CHANGELOG.rst | 8 ++++++++ common/math/geometry/package.xml | 2 +- common/scenario_simulator_exception/CHANGELOG.rst | 8 ++++++++ common/scenario_simulator_exception/package.xml | 2 +- common/simple_junit/CHANGELOG.rst | 8 ++++++++ common/simple_junit/package.xml | 2 +- common/status_monitor/CHANGELOG.rst | 8 ++++++++ common/status_monitor/package.xml | 2 +- external/concealer/CHANGELOG.rst | 8 ++++++++ external/concealer/package.xml | 2 +- external/embree_vendor/CHANGELOG.rst | 8 ++++++++ external/embree_vendor/package.xml | 2 +- map/kashiwanoha_map/CHANGELOG.rst | 8 ++++++++ map/kashiwanoha_map/package.xml | 2 +- map/simple_cross_map/CHANGELOG.rst | 8 ++++++++ map/simple_cross_map/package.xml | 2 +- mock/cpp_mock_scenarios/CHANGELOG.rst | 8 ++++++++ mock/cpp_mock_scenarios/package.xml | 2 +- .../openscenario_experimental_catalog/CHANGELOG.rst | 8 ++++++++ .../openscenario_experimental_catalog/package.xml | 2 +- openscenario/openscenario_interpreter/CHANGELOG.rst | 8 ++++++++ openscenario/openscenario_interpreter/package.xml | 2 +- .../openscenario_interpreter_example/CHANGELOG.rst | 8 ++++++++ .../openscenario_interpreter_example/package.xml | 2 +- .../openscenario_interpreter_msgs/CHANGELOG.rst | 8 ++++++++ .../openscenario_interpreter_msgs/package.xml | 2 +- openscenario/openscenario_preprocessor/CHANGELOG.rst | 8 ++++++++ openscenario/openscenario_preprocessor/package.xml | 2 +- .../openscenario_preprocessor_msgs/CHANGELOG.rst | 8 ++++++++ .../openscenario_preprocessor_msgs/package.xml | 2 +- openscenario/openscenario_utility/CHANGELOG.rst | 8 ++++++++ openscenario/openscenario_utility/package.xml | 2 +- openscenario/openscenario_validator/CHANGELOG.rst | 8 ++++++++ openscenario/openscenario_validator/package.xml | 2 +- .../openscenario_visualization/CHANGELOG.rst | 8 ++++++++ rviz_plugins/openscenario_visualization/package.xml | 2 +- .../CHANGELOG.rst | 8 ++++++++ .../real_time_factor_control_rviz_plugin/package.xml | 2 +- scenario_simulator_v2/CHANGELOG.rst | 8 ++++++++ scenario_simulator_v2/package.xml | 2 +- simulation/behavior_tree_plugin/CHANGELOG.rst | 8 ++++++++ simulation/behavior_tree_plugin/package.xml | 2 +- simulation/do_nothing_plugin/CHANGELOG.rst | 8 ++++++++ simulation/do_nothing_plugin/package.xml | 2 +- simulation/simple_sensor_simulator/CHANGELOG.rst | 8 ++++++++ simulation/simple_sensor_simulator/package.xml | 2 +- simulation/simulation_interface/CHANGELOG.rst | 8 ++++++++ simulation/simulation_interface/package.xml | 2 +- simulation/traffic_simulator/CHANGELOG.rst | 12 ++++++++++++ simulation/traffic_simulator/package.xml | 2 +- simulation/traffic_simulator_msgs/CHANGELOG.rst | 8 ++++++++ simulation/traffic_simulator_msgs/package.xml | 2 +- test_runner/random_test_runner/CHANGELOG.rst | 8 ++++++++ test_runner/random_test_runner/package.xml | 2 +- test_runner/scenario_test_runner/CHANGELOG.rst | 8 ++++++++ test_runner/scenario_test_runner/package.xml | 2 +- 58 files changed, 265 insertions(+), 29 deletions(-) diff --git a/common/math/arithmetic/CHANGELOG.rst b/common/math/arithmetic/CHANGELOG.rst index 64c3bbb98d9..ac0f5ca5f33 100644 --- a/common/math/arithmetic/CHANGELOG.rst +++ b/common/math/arithmetic/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package arithmetic * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.1 (2024-08-22) +------------------ +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Contributors: Dawid Moszyński, Tatsuya Yamasaki + 3.5.0 (2024-08-21) ------------------ * Merge branch 'master' into relative-clearance-condition diff --git a/common/math/arithmetic/package.xml b/common/math/arithmetic/package.xml index dc0b9148053..1542cfbbd32 100644 --- a/common/math/arithmetic/package.xml +++ b/common/math/arithmetic/package.xml @@ -2,7 +2,7 @@ arithmetic - 3.5.0 + 3.5.1 arithmetic library for scenario_simulator_v2 Tatsuya Yamasaki Apache License 2.0 diff --git a/common/math/geometry/CHANGELOG.rst b/common/math/geometry/CHANGELOG.rst index 62b75383b52..8b3636f5ba8 100644 --- a/common/math/geometry/CHANGELOG.rst +++ b/common/math/geometry/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package geometry * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.1 (2024-08-22) +------------------ +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Contributors: Dawid Moszyński, Tatsuya Yamasaki + 3.5.0 (2024-08-21) ------------------ * Merge branch 'master' into relative-clearance-condition diff --git a/common/math/geometry/package.xml b/common/math/geometry/package.xml index 7dfdbe1d948..09e966802a6 100644 --- a/common/math/geometry/package.xml +++ b/common/math/geometry/package.xml @@ -2,7 +2,7 @@ geometry - 3.5.0 + 3.5.1 geometry math library for scenario_simulator_v2 application Masaya Kataoka Apache License 2.0 diff --git a/common/scenario_simulator_exception/CHANGELOG.rst b/common/scenario_simulator_exception/CHANGELOG.rst index 54850734521..b8b7cf2f5ed 100644 --- a/common/scenario_simulator_exception/CHANGELOG.rst +++ b/common/scenario_simulator_exception/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package scenario_simulator_exception * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.1 (2024-08-22) +------------------ +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Contributors: Dawid Moszyński, Tatsuya Yamasaki + 3.5.0 (2024-08-21) ------------------ * Merge branch 'master' into relative-clearance-condition diff --git a/common/scenario_simulator_exception/package.xml b/common/scenario_simulator_exception/package.xml index 283b46d76c3..ad4a4cac524 100644 --- a/common/scenario_simulator_exception/package.xml +++ b/common/scenario_simulator_exception/package.xml @@ -2,7 +2,7 @@ scenario_simulator_exception - 3.5.0 + 3.5.1 Exception types for scenario simulator Tatsuya Yamasaki Apache License 2.0 diff --git a/common/simple_junit/CHANGELOG.rst b/common/simple_junit/CHANGELOG.rst index 054e9449524..e68f4933db7 100644 --- a/common/simple_junit/CHANGELOG.rst +++ b/common/simple_junit/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package junit_exporter * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.1 (2024-08-22) +------------------ +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Contributors: Dawid Moszyński, Tatsuya Yamasaki + 3.5.0 (2024-08-21) ------------------ * Merge branch 'master' into relative-clearance-condition diff --git a/common/simple_junit/package.xml b/common/simple_junit/package.xml index cf00d05b43f..1a49e5ad5d1 100644 --- a/common/simple_junit/package.xml +++ b/common/simple_junit/package.xml @@ -2,7 +2,7 @@ simple_junit - 3.5.0 + 3.5.1 Lightweight JUnit library for ROS 2 Masaya Kataoka Tatsuya Yamasaki diff --git a/common/status_monitor/CHANGELOG.rst b/common/status_monitor/CHANGELOG.rst index 65c1e11f5a0..ad75075183c 100644 --- a/common/status_monitor/CHANGELOG.rst +++ b/common/status_monitor/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package status_monitor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.1 (2024-08-22) +------------------ +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Contributors: Dawid Moszyński, Tatsuya Yamasaki + 3.5.0 (2024-08-21) ------------------ * Merge branch 'master' into relative-clearance-condition diff --git a/common/status_monitor/package.xml b/common/status_monitor/package.xml index d6a76edb2b3..5bbfcbe8b86 100644 --- a/common/status_monitor/package.xml +++ b/common/status_monitor/package.xml @@ -2,7 +2,7 @@ status_monitor - 3.5.0 + 3.5.1 none Tatsuya Yamasaki Apache License 2.0 diff --git a/external/concealer/CHANGELOG.rst b/external/concealer/CHANGELOG.rst index c7c1a86aa2e..deda8815c72 100644 --- a/external/concealer/CHANGELOG.rst +++ b/external/concealer/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package concealer * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.1 (2024-08-22) +------------------ +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Contributors: Dawid Moszyński, Tatsuya Yamasaki + 3.5.0 (2024-08-21) ------------------ * Merge branch 'master' into relative-clearance-condition diff --git a/external/concealer/package.xml b/external/concealer/package.xml index 7e79e340797..c78d2eef81b 100644 --- a/external/concealer/package.xml +++ b/external/concealer/package.xml @@ -2,7 +2,7 @@ concealer - 3.5.0 + 3.5.1 Provides a class 'Autoware' to conceal miscellaneous things to simplify Autoware management of the simulator. Tatsuya Yamasaki Apache License 2.0 diff --git a/external/embree_vendor/CHANGELOG.rst b/external/embree_vendor/CHANGELOG.rst index a3cbd42d32f..e62e13ad4fb 100644 --- a/external/embree_vendor/CHANGELOG.rst +++ b/external/embree_vendor/CHANGELOG.rst @@ -24,6 +24,14 @@ Changelog for package embree_vendor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.1 (2024-08-22) +------------------ +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Contributors: Dawid Moszyński, Tatsuya Yamasaki + 3.5.0 (2024-08-21) ------------------ * Merge branch 'master' into relative-clearance-condition diff --git a/external/embree_vendor/package.xml b/external/embree_vendor/package.xml index 3b0833adddb..baf82bb0137 100644 --- a/external/embree_vendor/package.xml +++ b/external/embree_vendor/package.xml @@ -2,7 +2,7 @@ embree_vendor - 3.5.0 + 3.5.1 vendor packages for intel raytracing kernel library masaya Apache 2.0 diff --git a/map/kashiwanoha_map/CHANGELOG.rst b/map/kashiwanoha_map/CHANGELOG.rst index 4ac41d7f364..d875dfa071f 100644 --- a/map/kashiwanoha_map/CHANGELOG.rst +++ b/map/kashiwanoha_map/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package kashiwanoha_map * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.1 (2024-08-22) +------------------ +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Contributors: Dawid Moszyński, Tatsuya Yamasaki + 3.5.0 (2024-08-21) ------------------ * Merge branch 'master' into relative-clearance-condition diff --git a/map/kashiwanoha_map/package.xml b/map/kashiwanoha_map/package.xml index 0bdc0dcd63e..41bc8eece20 100644 --- a/map/kashiwanoha_map/package.xml +++ b/map/kashiwanoha_map/package.xml @@ -2,7 +2,7 @@ kashiwanoha_map - 3.5.0 + 3.5.1 map package for kashiwanoha Masaya Kataoka Apache License 2.0 diff --git a/map/simple_cross_map/CHANGELOG.rst b/map/simple_cross_map/CHANGELOG.rst index fbb3748f1d9..99eb97082be 100644 --- a/map/simple_cross_map/CHANGELOG.rst +++ b/map/simple_cross_map/CHANGELOG.rst @@ -9,6 +9,14 @@ Changelog for package simple_cross_map * Merge branch 'master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.1 (2024-08-22) +------------------ +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Contributors: Dawid Moszyński, Tatsuya Yamasaki + 3.5.0 (2024-08-21) ------------------ * Merge branch 'master' into relative-clearance-condition diff --git a/map/simple_cross_map/package.xml b/map/simple_cross_map/package.xml index fff5d6ae9c8..ce243fd32c9 100644 --- a/map/simple_cross_map/package.xml +++ b/map/simple_cross_map/package.xml @@ -2,7 +2,7 @@ simple_cross_map - 3.5.0 + 3.5.1 map package for simple cross Masaya Kataoka Apache License 2.0 diff --git a/mock/cpp_mock_scenarios/CHANGELOG.rst b/mock/cpp_mock_scenarios/CHANGELOG.rst index cf545f94612..3b79763d377 100644 --- a/mock/cpp_mock_scenarios/CHANGELOG.rst +++ b/mock/cpp_mock_scenarios/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package cpp_mock_scenarios * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.1 (2024-08-22) +------------------ +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Contributors: Dawid Moszyński, Tatsuya Yamasaki + 3.5.0 (2024-08-21) ------------------ * Merge branch 'master' into relative-clearance-condition diff --git a/mock/cpp_mock_scenarios/package.xml b/mock/cpp_mock_scenarios/package.xml index 4f4b0ed260a..3fe9da935d1 100644 --- a/mock/cpp_mock_scenarios/package.xml +++ b/mock/cpp_mock_scenarios/package.xml @@ -2,7 +2,7 @@ cpp_mock_scenarios - 3.5.0 + 3.5.1 C++ mock scenarios masaya Apache License 2.0 diff --git a/openscenario/openscenario_experimental_catalog/CHANGELOG.rst b/openscenario/openscenario_experimental_catalog/CHANGELOG.rst index 9f522ae7066..6bae1ecad5f 100644 --- a/openscenario/openscenario_experimental_catalog/CHANGELOG.rst +++ b/openscenario/openscenario_experimental_catalog/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package openscenario_experimental_catalog * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.1 (2024-08-22) +------------------ +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Contributors: Dawid Moszyński, Tatsuya Yamasaki + 3.5.0 (2024-08-21) ------------------ * Merge branch 'master' into relative-clearance-condition diff --git a/openscenario/openscenario_experimental_catalog/package.xml b/openscenario/openscenario_experimental_catalog/package.xml index dc9ed56c35f..b94f7bb8cb2 100644 --- a/openscenario/openscenario_experimental_catalog/package.xml +++ b/openscenario/openscenario_experimental_catalog/package.xml @@ -2,7 +2,7 @@ openscenario_experimental_catalog - 3.5.0 + 3.5.1 TIER IV experimental catalogs for OpenSCENARIO Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter/CHANGELOG.rst b/openscenario/openscenario_interpreter/CHANGELOG.rst index 60a133f014f..4eac3623e5c 100644 --- a/openscenario/openscenario_interpreter/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter/CHANGELOG.rst @@ -32,6 +32,14 @@ Changelog for package openscenario_interpreter * add publish_empty_context parameter * Contributors: Masaya Kataoka +3.5.1 (2024-08-22) +------------------ +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Contributors: Dawid Moszyński, Tatsuya Yamasaki + 3.5.0 (2024-08-21) ------------------ * Merge pull request `#1316 `_ from tier4/relative-clearance-condition diff --git a/openscenario/openscenario_interpreter/package.xml b/openscenario/openscenario_interpreter/package.xml index d89bf384717..1f4c6f5557f 100644 --- a/openscenario/openscenario_interpreter/package.xml +++ b/openscenario/openscenario_interpreter/package.xml @@ -2,7 +2,7 @@ openscenario_interpreter - 3.5.0 + 3.5.1 OpenSCENARIO 1.2.0 interpreter package for Autoware Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter_example/CHANGELOG.rst b/openscenario/openscenario_interpreter_example/CHANGELOG.rst index 65d65074842..6d1a1ce0044 100644 --- a/openscenario/openscenario_interpreter_example/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter_example/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package openscenario_interpreter_example * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.1 (2024-08-22) +------------------ +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Contributors: Dawid Moszyński, Tatsuya Yamasaki + 3.5.0 (2024-08-21) ------------------ * Merge branch 'master' into relative-clearance-condition diff --git a/openscenario/openscenario_interpreter_example/package.xml b/openscenario/openscenario_interpreter_example/package.xml index 12da0f14943..2ec093360de 100644 --- a/openscenario/openscenario_interpreter_example/package.xml +++ b/openscenario/openscenario_interpreter_example/package.xml @@ -3,7 +3,7 @@ openscenario_interpreter_example - 3.5.0 + 3.5.1 Examples for some TIER IV OpenSCENARIO Interpreter's features Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst b/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst index afb80f1e887..1e197535985 100644 --- a/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package openscenario_interpreter_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.1 (2024-08-22) +------------------ +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Contributors: Dawid Moszyński, Tatsuya Yamasaki + 3.5.0 (2024-08-21) ------------------ * Merge branch 'master' into relative-clearance-condition diff --git a/openscenario/openscenario_interpreter_msgs/package.xml b/openscenario/openscenario_interpreter_msgs/package.xml index 0e5eae005dd..de45a893ce3 100644 --- a/openscenario/openscenario_interpreter_msgs/package.xml +++ b/openscenario/openscenario_interpreter_msgs/package.xml @@ -2,7 +2,7 @@ openscenario_interpreter_msgs - 3.5.0 + 3.5.1 ROS message types for package openscenario_interpreter Yamasaki Tatsuya Apache License 2.0 diff --git a/openscenario/openscenario_preprocessor/CHANGELOG.rst b/openscenario/openscenario_preprocessor/CHANGELOG.rst index f87d7ff9a93..d96e08f900a 100644 --- a/openscenario/openscenario_preprocessor/CHANGELOG.rst +++ b/openscenario/openscenario_preprocessor/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package openscenario_preprocessor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.1 (2024-08-22) +------------------ +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Contributors: Dawid Moszyński, Tatsuya Yamasaki + 3.5.0 (2024-08-21) ------------------ * Merge branch 'master' into relative-clearance-condition diff --git a/openscenario/openscenario_preprocessor/package.xml b/openscenario/openscenario_preprocessor/package.xml index da55adb6e8c..469df484683 100644 --- a/openscenario/openscenario_preprocessor/package.xml +++ b/openscenario/openscenario_preprocessor/package.xml @@ -3,7 +3,7 @@ openscenario_preprocessor - 3.5.0 + 3.5.1 Example package for TIER IV OpenSCENARIO Interpreter Kotaro Yoshimoto Apache License 2.0 diff --git a/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst b/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst index 6cf120d924c..bf55f43e420 100644 --- a/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst +++ b/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package openscenario_preprocessor_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.1 (2024-08-22) +------------------ +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Contributors: Dawid Moszyński, Tatsuya Yamasaki + 3.5.0 (2024-08-21) ------------------ * Merge branch 'master' into relative-clearance-condition diff --git a/openscenario/openscenario_preprocessor_msgs/package.xml b/openscenario/openscenario_preprocessor_msgs/package.xml index 2e0d1f8fd00..f877b8b8650 100644 --- a/openscenario/openscenario_preprocessor_msgs/package.xml +++ b/openscenario/openscenario_preprocessor_msgs/package.xml @@ -2,7 +2,7 @@ openscenario_preprocessor_msgs - 3.5.0 + 3.5.1 ROS message types for package openscenario_preprocessor Kotaro Yoshimoto Apache License 2.0 diff --git a/openscenario/openscenario_utility/CHANGELOG.rst b/openscenario/openscenario_utility/CHANGELOG.rst index 14ecb74f6de..a931872c047 100644 --- a/openscenario/openscenario_utility/CHANGELOG.rst +++ b/openscenario/openscenario_utility/CHANGELOG.rst @@ -24,6 +24,14 @@ Changelog for package openscenario_utility * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.1 (2024-08-22) +------------------ +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Contributors: Dawid Moszyński, Tatsuya Yamasaki + 3.5.0 (2024-08-21) ------------------ * Merge branch 'master' into relative-clearance-condition diff --git a/openscenario/openscenario_utility/package.xml b/openscenario/openscenario_utility/package.xml index 94998e36263..071914f2725 100644 --- a/openscenario/openscenario_utility/package.xml +++ b/openscenario/openscenario_utility/package.xml @@ -2,7 +2,7 @@ openscenario_utility - 3.5.0 + 3.5.1 Utility tools for ASAM OpenSCENARIO 1.2.0 Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_validator/CHANGELOG.rst b/openscenario/openscenario_validator/CHANGELOG.rst index 1024f4e94e1..78c63ece427 100644 --- a/openscenario/openscenario_validator/CHANGELOG.rst +++ b/openscenario/openscenario_validator/CHANGELOG.rst @@ -10,6 +10,14 @@ Changelog for package openscenario_validator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.1 (2024-08-22) +------------------ +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Contributors: Dawid Moszyński, Tatsuya Yamasaki + 3.5.0 (2024-08-21) ------------------ * Merge branch 'master' into relative-clearance-condition diff --git a/openscenario/openscenario_validator/package.xml b/openscenario/openscenario_validator/package.xml index fd3beac056c..612bc188111 100644 --- a/openscenario/openscenario_validator/package.xml +++ b/openscenario/openscenario_validator/package.xml @@ -2,7 +2,7 @@ openscenario_validator - 3.5.0 + 3.5.1 Validator for OpenSCENARIO 1.3 Kotaro Yoshimoto Apache License 2.0 diff --git a/rviz_plugins/openscenario_visualization/CHANGELOG.rst b/rviz_plugins/openscenario_visualization/CHANGELOG.rst index 848d948bf39..3f9f2f8ce24 100644 --- a/rviz_plugins/openscenario_visualization/CHANGELOG.rst +++ b/rviz_plugins/openscenario_visualization/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package openscenario_visualization * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.1 (2024-08-22) +------------------ +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Contributors: Dawid Moszyński, Tatsuya Yamasaki + 3.5.0 (2024-08-21) ------------------ * Merge branch 'master' into relative-clearance-condition diff --git a/rviz_plugins/openscenario_visualization/package.xml b/rviz_plugins/openscenario_visualization/package.xml index 6f77a5b65ea..83c4ac7a053 100644 --- a/rviz_plugins/openscenario_visualization/package.xml +++ b/rviz_plugins/openscenario_visualization/package.xml @@ -2,7 +2,7 @@ openscenario_visualization - 3.5.0 + 3.5.1 Visualization tools for simulation results Masaya Kataoka Kyoichi Sugahara diff --git a/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst b/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst index e96bed42787..afc1bad3634 100644 --- a/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst +++ b/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package real_time_factor_control_rviz_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.1 (2024-08-22) +------------------ +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Contributors: Dawid Moszyński, Tatsuya Yamasaki + 3.5.0 (2024-08-21) ------------------ * Merge branch 'master' into relative-clearance-condition diff --git a/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml b/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml index 5e5e9b4267e..c759188b370 100644 --- a/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml +++ b/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml @@ -2,7 +2,7 @@ real_time_factor_control_rviz_plugin - 3.5.0 + 3.5.1 Slider controlling real time factor value. Paweł Lech Apache License 2.0 diff --git a/scenario_simulator_v2/CHANGELOG.rst b/scenario_simulator_v2/CHANGELOG.rst index 110e106a1f6..a2c49f91b0b 100644 --- a/scenario_simulator_v2/CHANGELOG.rst +++ b/scenario_simulator_v2/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package scenario_simulator_v2 * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.1 (2024-08-22) +------------------ +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Contributors: Dawid Moszyński, Tatsuya Yamasaki + 3.5.0 (2024-08-21) ------------------ * Merge branch 'master' into relative-clearance-condition diff --git a/scenario_simulator_v2/package.xml b/scenario_simulator_v2/package.xml index a6d95d78fad..3ea8822c0f9 100644 --- a/scenario_simulator_v2/package.xml +++ b/scenario_simulator_v2/package.xml @@ -2,7 +2,7 @@ scenario_simulator_v2 - 3.5.0 + 3.5.1 scenario testing framework for Autoware Masaya Kataoka Apache License 2.0 diff --git a/simulation/behavior_tree_plugin/CHANGELOG.rst b/simulation/behavior_tree_plugin/CHANGELOG.rst index 46bb38e4585..2df22173009 100644 --- a/simulation/behavior_tree_plugin/CHANGELOG.rst +++ b/simulation/behavior_tree_plugin/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package behavior_tree_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.1 (2024-08-22) +------------------ +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Contributors: Dawid Moszyński, Tatsuya Yamasaki + 3.5.0 (2024-08-21) ------------------ * Merge branch 'master' into relative-clearance-condition diff --git a/simulation/behavior_tree_plugin/package.xml b/simulation/behavior_tree_plugin/package.xml index ccb25126242..cbbc43380d6 100644 --- a/simulation/behavior_tree_plugin/package.xml +++ b/simulation/behavior_tree_plugin/package.xml @@ -2,7 +2,7 @@ behavior_tree_plugin - 3.5.0 + 3.5.1 Behavior tree plugin for traffic_simulator masaya Apache 2.0 diff --git a/simulation/do_nothing_plugin/CHANGELOG.rst b/simulation/do_nothing_plugin/CHANGELOG.rst index 33aa50daaf7..803937311a8 100644 --- a/simulation/do_nothing_plugin/CHANGELOG.rst +++ b/simulation/do_nothing_plugin/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package do_nothing_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.1 (2024-08-22) +------------------ +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Contributors: Dawid Moszyński, Tatsuya Yamasaki + 3.5.0 (2024-08-21) ------------------ * Merge branch 'master' into relative-clearance-condition diff --git a/simulation/do_nothing_plugin/package.xml b/simulation/do_nothing_plugin/package.xml index a755ce78ec0..e007b91b5d6 100644 --- a/simulation/do_nothing_plugin/package.xml +++ b/simulation/do_nothing_plugin/package.xml @@ -2,7 +2,7 @@ do_nothing_plugin - 3.5.0 + 3.5.1 Behavior plugin for do nothing Masaya Kataoka Apache 2.0 diff --git a/simulation/simple_sensor_simulator/CHANGELOG.rst b/simulation/simple_sensor_simulator/CHANGELOG.rst index 0f4b53a7f56..7a73f0c06a2 100644 --- a/simulation/simple_sensor_simulator/CHANGELOG.rst +++ b/simulation/simple_sensor_simulator/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package simple_sensor_simulator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.1 (2024-08-22) +------------------ +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Contributors: Dawid Moszyński, Tatsuya Yamasaki + 3.5.0 (2024-08-21) ------------------ * Merge branch 'master' into relative-clearance-condition diff --git a/simulation/simple_sensor_simulator/package.xml b/simulation/simple_sensor_simulator/package.xml index e589b75cda2..f476f419da9 100644 --- a/simulation/simple_sensor_simulator/package.xml +++ b/simulation/simple_sensor_simulator/package.xml @@ -1,7 +1,7 @@ simple_sensor_simulator - 3.5.0 + 3.5.1 simple_sensor_simulator package masaya kataoka diff --git a/simulation/simulation_interface/CHANGELOG.rst b/simulation/simulation_interface/CHANGELOG.rst index 8f53e81a059..adbcdbfc3b6 100644 --- a/simulation/simulation_interface/CHANGELOG.rst +++ b/simulation/simulation_interface/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package simulation_interface * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.1 (2024-08-22) +------------------ +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Contributors: Dawid Moszyński, Tatsuya Yamasaki + 3.5.0 (2024-08-21) ------------------ * Merge branch 'master' into relative-clearance-condition diff --git a/simulation/simulation_interface/package.xml b/simulation/simulation_interface/package.xml index 7eac6ccca06..1f7e923e7a2 100644 --- a/simulation/simulation_interface/package.xml +++ b/simulation/simulation_interface/package.xml @@ -2,7 +2,7 @@ simulation_interface - 3.5.0 + 3.5.1 packages to define interface between simulator and scenario interpreter Masaya Kataoka Apache License 2.0 diff --git a/simulation/traffic_simulator/CHANGELOG.rst b/simulation/traffic_simulator/CHANGELOG.rst index 0b77efa5042..b929a03977c 100644 --- a/simulation/traffic_simulator/CHANGELOG.rst +++ b/simulation/traffic_simulator/CHANGELOG.rst @@ -21,6 +21,18 @@ Changelog for package traffic_simulator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.1 (2024-08-22) +------------------ +* Merge pull request `#1335 `_ from tier4/feat/RJD-1283-add-traffic-controller-visualization + feat(traffic_controller, api): add rviz marker for TrafficSink +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* ref(traffic_controller): rename make->appendDebugMarker +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* feat(traffic_controller, api): add rviz marker for TrafficSink +* Contributors: Dawid Moszynski, Dawid Moszyński, Tatsuya Yamasaki + 3.5.0 (2024-08-21) ------------------ * Merge pull request `#1316 `_ from tier4/relative-clearance-condition diff --git a/simulation/traffic_simulator/package.xml b/simulation/traffic_simulator/package.xml index 540e9d980fc..c5390564628 100644 --- a/simulation/traffic_simulator/package.xml +++ b/simulation/traffic_simulator/package.xml @@ -1,7 +1,7 @@ traffic_simulator - 3.5.0 + 3.5.1 control traffic flow masaya kataoka diff --git a/simulation/traffic_simulator_msgs/CHANGELOG.rst b/simulation/traffic_simulator_msgs/CHANGELOG.rst index 2a75d18c2b9..fdb6b702e45 100644 --- a/simulation/traffic_simulator_msgs/CHANGELOG.rst +++ b/simulation/traffic_simulator_msgs/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package openscenario_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.1 (2024-08-22) +------------------ +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Contributors: Dawid Moszyński, Tatsuya Yamasaki + 3.5.0 (2024-08-21) ------------------ * Merge branch 'master' into relative-clearance-condition diff --git a/simulation/traffic_simulator_msgs/package.xml b/simulation/traffic_simulator_msgs/package.xml index a757a7725c8..0710d446627 100644 --- a/simulation/traffic_simulator_msgs/package.xml +++ b/simulation/traffic_simulator_msgs/package.xml @@ -2,7 +2,7 @@ traffic_simulator_msgs - 3.5.0 + 3.5.1 ROS messages for openscenario Masaya Kataoka Apache License 2.0 diff --git a/test_runner/random_test_runner/CHANGELOG.rst b/test_runner/random_test_runner/CHANGELOG.rst index 5fc9292f0c0..f04eede8929 100644 --- a/test_runner/random_test_runner/CHANGELOG.rst +++ b/test_runner/random_test_runner/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package random_test_runner * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.1 (2024-08-22) +------------------ +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Contributors: Dawid Moszyński, Tatsuya Yamasaki + 3.5.0 (2024-08-21) ------------------ * Merge branch 'master' into relative-clearance-condition diff --git a/test_runner/random_test_runner/package.xml b/test_runner/random_test_runner/package.xml index d0dbd53a058..2e885e4e655 100644 --- a/test_runner/random_test_runner/package.xml +++ b/test_runner/random_test_runner/package.xml @@ -2,7 +2,7 @@ random_test_runner - 3.5.0 + 3.5.1 Random behavior test runner piotr-zyskowski-rai Apache License 2.0 diff --git a/test_runner/scenario_test_runner/CHANGELOG.rst b/test_runner/scenario_test_runner/CHANGELOG.rst index 33ccb31848d..2e4ef49e606 100644 --- a/test_runner/scenario_test_runner/CHANGELOG.rst +++ b/test_runner/scenario_test_runner/CHANGELOG.rst @@ -35,6 +35,14 @@ Changelog for package scenario_test_runner * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.1 (2024-08-22) +------------------ +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization +* Contributors: Dawid Moszyński, Tatsuya Yamasaki + 3.5.0 (2024-08-21) ------------------ * Merge pull request `#1316 `_ from tier4/relative-clearance-condition diff --git a/test_runner/scenario_test_runner/package.xml b/test_runner/scenario_test_runner/package.xml index 0883d2fd03f..33269e1139d 100644 --- a/test_runner/scenario_test_runner/package.xml +++ b/test_runner/scenario_test_runner/package.xml @@ -2,7 +2,7 @@ scenario_test_runner - 3.5.0 + 3.5.1 scenario test runner package Tatsuya Yamasaki Apache License 2.0 From 1e0c0138fa1f769389912b130a6b7a6a79450f03 Mon Sep 17 00:00:00 2001 From: Masaya Kataoka Date: Thu, 22 Aug 2024 13:35:26 +0900 Subject: [PATCH 150/304] usw workflow dispatch Signed-off-by: Masaya Kataoka --- .github/workflows/Docekr.yaml | 10 +++++++--- .github/workflows/Release.yaml | 9 +++++++++ 2 files changed, 16 insertions(+), 3 deletions(-) diff --git a/.github/workflows/Docekr.yaml b/.github/workflows/Docekr.yaml index 28b543cb6ed..8f29d67e16d 100644 --- a/.github/workflows/Docekr.yaml +++ b/.github/workflows/Docekr.yaml @@ -10,7 +10,11 @@ on: - "!mkdocs.yml" - "!pyproject.toml" - "!poetry.lock" - release: + workflow_dispatch: + inputs: + version: + description: version of the scenario_simulator_v2 + required: true jobs: push_docker: @@ -61,7 +65,7 @@ jobs: ${{ matrix.rosdistro }}_base_${{ matrix.arch }} - name: Build and push (${{ matrix.arch }}) - if: github.event_name != 'pull_request' + if: github.event_name == 'workflow_dispatch' uses: docker/bake-action@v3 with: files: | @@ -70,7 +74,7 @@ jobs: set: | *.cache-to=type=gha,mode=max *.cache-from=type=gha - *.tags=ghcr.io/tier4/scenario_simulator_v2:humble-${{ github.event.release.tag_name }} + *.tags=ghcr.io/tier4/scenario_simulator_v2:humble-${{ github.event.inputs.version }} push: true targets: | ${{ matrix.rosdistro }}_base_${{ matrix.arch }} diff --git a/.github/workflows/Release.yaml b/.github/workflows/Release.yaml index 39b5508f735..051e9153b1b 100644 --- a/.github/workflows/Release.yaml +++ b/.github/workflows/Release.yaml @@ -142,3 +142,12 @@ jobs: repo: context.repo.repo, ref: `heads/${context.payload.pull_request.head.ref}`, }) + + - name: Kick docker build action + if: github.event.pull_request.merged == true + run: | + curl -X POST \ + -H "Accept: application/vnd.github.v3+json" \ + -H "Authorization: token ${{ secrets.PAT }}" \ + https://api.github.com/repos/${{ github.repository }}/actions/workflows/target-workflow.yml/dispatches \ + -d '{"ref":"main", "inputs": {"version":"${{ steps.new_version.outputs.new_version }}"}}' From 120d5fee6adcea466a774510ff5f84a964f0f037 Mon Sep 17 00:00:00 2001 From: Masaya Kataoka Date: Thu, 22 Aug 2024 15:33:09 +0900 Subject: [PATCH 151/304] update Release actions Signed-off-by: Masaya Kataoka --- .github/workflows/Release.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/Release.yaml b/.github/workflows/Release.yaml index 051e9153b1b..d163954ee75 100644 --- a/.github/workflows/Release.yaml +++ b/.github/workflows/Release.yaml @@ -149,5 +149,5 @@ jobs: curl -X POST \ -H "Accept: application/vnd.github.v3+json" \ -H "Authorization: token ${{ secrets.PAT }}" \ - https://api.github.com/repos/${{ github.repository }}/actions/workflows/target-workflow.yml/dispatches \ + https://api.github.com/repos/${{ github.repository }}/actions/workflows/Docker.yml/dispatches \ -d '{"ref":"main", "inputs": {"version":"${{ steps.new_version.outputs.new_version }}"}}' From 119e0a11d3d010ccb112964eb7a5f6d79bfe8c75 Mon Sep 17 00:00:00 2001 From: Masaya Kataoka Date: Thu, 22 Aug 2024 15:34:57 +0900 Subject: [PATCH 152/304] add curl Signed-off-by: Masaya Kataoka --- .github/workflows/Release.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/Release.yaml b/.github/workflows/Release.yaml index d163954ee75..0c2ab0e2e00 100644 --- a/.github/workflows/Release.yaml +++ b/.github/workflows/Release.yaml @@ -36,7 +36,7 @@ jobs: uses: levonet/action-restore-branch@master - name: Install bloom - run: apt update && apt install -y python3-bloom git + run: apt update && apt install -y python3-bloom git curl - name: Checkout uses: actions/checkout@v4 From f38b5611a89e4c0a329dfe528ce4cca0d0f07816 Mon Sep 17 00:00:00 2001 From: Masaya Kataoka Date: Thu, 22 Aug 2024 16:29:42 +0900 Subject: [PATCH 153/304] change token Signed-off-by: Masaya Kataoka --- .github/workflows/Release.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/Release.yaml b/.github/workflows/Release.yaml index 0c2ab0e2e00..2183cde0dbb 100644 --- a/.github/workflows/Release.yaml +++ b/.github/workflows/Release.yaml @@ -148,6 +148,6 @@ jobs: run: | curl -X POST \ -H "Accept: application/vnd.github.v3+json" \ - -H "Authorization: token ${{ secrets.PAT }}" \ + -H "Authorization: token ${{ secrets.BLOOM_GITHUB_TOKEN }}" \ https://api.github.com/repos/${{ github.repository }}/actions/workflows/Docker.yml/dispatches \ -d '{"ref":"main", "inputs": {"version":"${{ steps.new_version.outputs.new_version }}"}}' From c15d63755b39513049a50278b99eda1e3ba88a5f Mon Sep 17 00:00:00 2001 From: Masaya Kataoka Date: Thu, 22 Aug 2024 16:58:57 +0900 Subject: [PATCH 154/304] fix typo Signed-off-by: Masaya Kataoka --- .github/workflows/{Docekr.yaml => Docker.yaml} | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename .github/workflows/{Docekr.yaml => Docker.yaml} (100%) diff --git a/.github/workflows/Docekr.yaml b/.github/workflows/Docker.yaml similarity index 100% rename from .github/workflows/Docekr.yaml rename to .github/workflows/Docker.yaml From 21732a098156155724e5304f073009707fb33038 Mon Sep 17 00:00:00 2001 From: Masaya Kataoka Date: Thu, 22 Aug 2024 17:00:20 +0900 Subject: [PATCH 155/304] fix typo Signed-off-by: Masaya Kataoka --- .github/workflows/Release.yaml | 12 +++++++----- 1 file changed, 7 insertions(+), 5 deletions(-) diff --git a/.github/workflows/Release.yaml b/.github/workflows/Release.yaml index 2183cde0dbb..c3812e1f187 100644 --- a/.github/workflows/Release.yaml +++ b/.github/workflows/Release.yaml @@ -146,8 +146,10 @@ jobs: - name: Kick docker build action if: github.event.pull_request.merged == true run: | - curl -X POST \ - -H "Accept: application/vnd.github.v3+json" \ - -H "Authorization: token ${{ secrets.BLOOM_GITHUB_TOKEN }}" \ - https://api.github.com/repos/${{ github.repository }}/actions/workflows/Docker.yml/dispatches \ - -d '{"ref":"main", "inputs": {"version":"${{ steps.new_version.outputs.new_version }}"}}' + curl -L \ + -X POST \ + -H "Accept: application/vnd.github+json" \ + -H "Authorization: token ${{ secrets.BLOOM_GITHUB_TOKEN }}" \ + -H "X-GitHub-Api-Version: 2022-11-28" \ + https://api.github.com/repos/merge-queue-testing/scenario_simulator_v2/actions/workflows/Docker.yaml/dispatches \ + -d '{"ref":"master","inputs":{"version":"3.5.2"}}' From ccb7c09a217c0da41bb98571561894bae87246c1 Mon Sep 17 00:00:00 2001 From: robomic Date: Thu, 22 Aug 2024 12:04:16 +0200 Subject: [PATCH 156/304] LineSegment 2D vs 3D indistinction fixes --- .../include/geometry/polygon/line_segment.hpp | 2 +- .../src/intersection/intersection.cpp | 40 +++++++++---- .../geometry/src/polygon/line_segment.cpp | 60 ++++++------------- .../src/spline/catmull_rom_spline.cpp | 2 +- .../math/geometry/test/test_intersection.cpp | 14 +---- .../math/geometry/test/test_line_segment.cpp | 26 ++++---- 6 files changed, 63 insertions(+), 81 deletions(-) diff --git a/common/math/geometry/include/geometry/polygon/line_segment.hpp b/common/math/geometry/include/geometry/polygon/line_segment.hpp index d3efd8679a6..3cb3e178627 100644 --- a/common/math/geometry/include/geometry/polygon/line_segment.hpp +++ b/common/math/geometry/include/geometry/polygon/line_segment.hpp @@ -52,7 +52,7 @@ class LineSegment -> std::optional; auto getIntersection2D(const LineSegment & line) const -> std::optional; - auto getSValue( + auto get2DSValue( const geometry_msgs::msg::Pose & pose, double threshold_distance, bool denormalize_s) const -> std::optional; auto getVector() const -> const geometry_msgs::msg::Vector3 &; diff --git a/common/math/geometry/src/intersection/intersection.cpp b/common/math/geometry/src/intersection/intersection.cpp index c2a7665eac3..c87e2352662 100644 --- a/common/math/geometry/src/intersection/intersection.cpp +++ b/common/math/geometry/src/intersection/intersection.cpp @@ -14,6 +14,7 @@ #include #include +#include namespace math { @@ -55,21 +56,34 @@ bool isIntersect2D(const std::vector & lines) std::optional getIntersection2D( const LineSegment & line0, const LineSegment & line1) { - if (!isIntersect2D(line0, line1)) { + if (not line0.isIntersect2D(line1)) { return std::nullopt; } - const auto det = - (line0.start_point.x - line0.end_point.x) * (line1.end_point.y - line1.start_point.y) - - (line1.end_point.x - line1.start_point.x) * (line0.start_point.y - line0.end_point.y); - const auto t = - ((line1.end_point.y - line1.start_point.y) * (line1.end_point.x - line0.end_point.x) + - (line1.start_point.x - line1.end_point.x) * (line1.end_point.y - line0.end_point.y)) / - det; - geometry_msgs::msg::Point point; - point.x = t * line0.start_point.x + (1.0 - t) * line0.end_point.x; - point.y = t * line0.start_point.y + (1.0 - t) * line0.end_point.y; - point.z = t * line0.start_point.z + (1.0 - t) * line0.end_point.z; - return point; + // 'line0' represented as a0x + b0y = c0 + const double a0 = line0.get2DVector().y; + const double b0 = -line0.get2DVector().x; + const double c0 = a0 * line0.start_point.x + b0 * line0.start_point.y; + + // 'line1' represented as a1x + b1y = c1 + const double a1 = line1.get2DVector().y; + const double b1 = -line1.get2DVector().x; + const double c1 = a1 * line1.start_point.x + b1 * line1.start_point.y; + + const double determinant = a0 * b1 - a1 * b0; + + if (std::abs(determinant) < 1.0e-10) { + // The lines do intersect, but they are collinear and overlap. + THROW_SIMULATION_ERROR( + "Line segments are collinear. So determinant is zero.", + "If this message was displayed, something completely unexpected happens.", + "This message is not originally intended to be displayed, if you see it, please " + "contact the developer of traffic_simulator."); + } else { + return geometry_msgs::build() + .x((b1 * c0 - b0 * c1) / determinant) + .y((a0 * c1 - a1 * c0) / determinant) + .z(0.0); + } } std::vector getIntersection2D(const std::vector & lines) diff --git a/common/math/geometry/src/polygon/line_segment.cpp b/common/math/geometry/src/polygon/line_segment.cpp index 196565215ff..b4085ec69fe 100644 --- a/common/math/geometry/src/polygon/line_segment.cpp +++ b/common/math/geometry/src/polygon/line_segment.cpp @@ -48,18 +48,18 @@ LineSegment::LineSegment( const geometry_msgs::msg::Point & start_point, const geometry_msgs::msg::Vector3 & vec, const double length) : LineSegment::LineSegment(start_point, [&]() -> geometry_msgs::msg::Point { - double vec_size = std::hypot(vec.x, vec.y); - if (vec_size == 0.0) { + if (double vec_size = std::hypot(vec.x, vec.y); vec_size == 0.0) { THROW_SIMULATION_ERROR( "Invalid vector is specified, while constructing LineSegment. ", "The vector should have a non zero length to initialize the line segment correctly. ", "This message is not originally intended to be displayed, if you see it, please " "contact the developer of traffic_simulator."); + } else { + return geometry_msgs::build() + .x(start_point.x + vec.x / vec_size * length) + .y(start_point.y + vec.y / vec_size * length) + .z(start_point.z + vec.z / vec_size * length); } - return geometry_msgs::build() - .x(start_point.x + vec.x / vec_size * length) - .y(start_point.y + vec.y / vec_size * length) - .z(start_point.z + vec.z / vec_size * length); }()) { } @@ -78,9 +78,9 @@ auto LineSegment::getPoint(const double s, const bool denormalize_s) const const double s_normalized = denormalize_s ? s / getLength() : s; if (0.0 <= s_normalized && s_normalized <= 1.0) { return geometry_msgs::build() - .x(start_point.x + get2DVector().x * s_normalized) - .y(start_point.y + get2DVector().y * s_normalized) - .z(start_point.z + (end_point.z - start_point.z) * s_normalized); + .x(start_point.x + getVector().x * s_normalized) + .y(start_point.y + getVector().y * s_normalized) + .z(start_point.z + getVector().z * s_normalized); } if (denormalize_s) { THROW_SIMULATION_ERROR( @@ -140,7 +140,7 @@ auto LineSegment::isIntersect2D(const geometry_msgs::msg::Point & point) const - } } -auto LineSegment::getSValue( +auto LineSegment::get2DSValue( const geometry_msgs::msg::Pose & pose, double threshold_distance, bool denormalize_s) const -> std::optional { @@ -192,30 +192,11 @@ auto LineSegment::getIntersection2DSValue( auto LineSegment::getIntersection2DSValue(const LineSegment & line, const bool denormalize_s) const -> std::optional { - /// @note Hard coded parameter, this parameter describes the tolerance of the range of s value (-s_tolerance ~ 1.0 + s_tolerance) - constexpr double s_tolerance = 1e-10; - const auto get_s_normalized = [this](const auto & line) -> std::optional { - if (!isIntersect2D(line)) { - return std::optional(); - } - const double det = (start_point.x - end_point.x) * (line.end_point.y - line.start_point.y) - - (line.end_point.x - line.start_point.x) * (start_point.y - end_point.y); - const double s = - 1.0 - ((line.end_point.y - line.start_point.y) * (line.end_point.x - end_point.x) + - (line.start_point.x - line.end_point.x) * (line.end_point.y - end_point.y)) / - det; - if (std::isnan(s)) { - THROW_SIMULATION_ERROR( - "One line segment is on top of the other. So determinant is zero.", - "If this message was displayed, something completely unexpected happens.", - "This message is not originally intended to be displayed, if you see it, please " - "contact the developer of traffic_simulator."); - } - return (-s_tolerance <= s && s <= 1.0 + s_tolerance) - ? std::optional(std::clamp(s, 0.0, 1.0)) - : std::optional(); - }; - return denormalize_s ? denormalize(get_s_normalized(line)) : get_s_normalized(line); + if (const auto point = getIntersection2D(line); point.has_value()) { + return getIntersection2DSValue(point.value(), denormalize_s); + } else { + return std::nullopt; + } } /** @@ -226,12 +207,7 @@ auto LineSegment::getIntersection2DSValue(const LineSegment & line, const bool d auto LineSegment::getIntersection2D(const LineSegment & line) const -> std::optional { - const auto s = getIntersection2DSValue(line, false); - return s ? geometry_msgs::build() - .x(s.value() * start_point.x + (1.0 - s.value()) * end_point.x) - .y(s.value() * start_point.y + (1.0 - s.value()) * end_point.y) - .z(s.value() * start_point.z + (1.0 - s.value()) * end_point.z) - : std::optional(); + return math::geometry::getIntersection2D(*this, line); } auto LineSegment::getVector() const -> const geometry_msgs::msg::Vector3 & { return vector; } @@ -301,9 +277,9 @@ auto LineSegment::denormalize( -> std::optional { if (!throw_error_on_out_of_range && s && !(0.0 <= s.value() && s.value() <= 1.0)) { - return std::optional(); + return std::nullopt; } - return s ? denormalize(s.value()) : std::optional(); + return s ? std::make_optional(denormalize(s.value())) : std::nullopt; } /** diff --git a/common/math/geometry/src/spline/catmull_rom_spline.cpp b/common/math/geometry/src/spline/catmull_rom_spline.cpp index 523b6f28099..4f633488f00 100644 --- a/common/math/geometry/src/spline/catmull_rom_spline.cpp +++ b/common/math/geometry/src/spline/catmull_rom_spline.cpp @@ -425,7 +425,7 @@ auto CatmullRomSpline::getSValue( "This message is not originally intended to be displayed, if you see it, please " "contact the developer of traffic_simulator."); } - return line_segments_[0].getSValue(pose, threshold_distance, true); + return line_segments_[0].get2DSValue(pose, threshold_distance, true); default: double s = 0; for (size_t i = 0; i < curves_.size(); i++) { diff --git a/common/math/geometry/test/test_intersection.cpp b/common/math/geometry/test/test_intersection.cpp index 4ee95a08cd9..06b8925bbca 100644 --- a/common/math/geometry/test/test_intersection.cpp +++ b/common/math/geometry/test/test_intersection.cpp @@ -16,6 +16,7 @@ #include #include +#include #include "expect_eq_macros.hpp" #include "test_utils.hpp" @@ -108,9 +109,7 @@ TEST(Intersection, getIntersection2DIntersectVector) TEST(Intersection, getIntersection2DIdentical) { math::geometry::LineSegment line(makePoint(0.0, 0.0), makePoint(1.0, 1.0)); - auto ans = math::geometry::getIntersection2D(line, line); - EXPECT_TRUE(ans); - EXPECT_POINT_NAN(ans.value()); + EXPECT_THROW(math::geometry::getIntersection2D(line, line), common::SimulationError); } TEST(Intersection, getIntersection2DIdenticalVector) @@ -121,14 +120,7 @@ TEST(Intersection, getIntersection2DIdenticalVector) lines.push_back(line); lines.push_back(line); - auto ans = math::geometry::getIntersection2D(lines); - EXPECT_EQ(ans.size(), size_t(6)); - EXPECT_POINT_NAN(ans[0]); - EXPECT_POINT_NAN(ans[1]); - EXPECT_POINT_NAN(ans[2]); - EXPECT_POINT_NAN(ans[3]); - EXPECT_POINT_NAN(ans[4]); - EXPECT_POINT_NAN(ans[5]); + EXPECT_THROW(math::geometry::getIntersection2D(lines), common::SimulationError); } TEST(Intersection, getIntersection2DEmptyVector) diff --git a/common/math/geometry/test/test_line_segment.cpp b/common/math/geometry/test/test_line_segment.cpp index 4c21cc35626..157b59c3b98 100644 --- a/common/math/geometry/test/test_line_segment.cpp +++ b/common/math/geometry/test/test_line_segment.cpp @@ -270,44 +270,44 @@ TEST(LineSegment, getLineSegmentsVectorIdentical_closeStartEnd) EXPECT_POINT_EQ(lines[3].end_point, point); } -TEST(LineSegment, getSValue) +TEST(LineSegment, get2DSValue) { math::geometry::LineSegment line(makePoint(0.0, 0.0, 0.0), makePoint(3.0, 3.0, 3.0)); - const auto s = line.getSValue(makePose(2.0, 2.0, 2.0), 1.0, false); + const auto s = line.get2DSValue(makePose(2.0, 2.0, 2.0), 1.0, false); EXPECT_TRUE(s); if (s) { EXPECT_DOUBLE_EQ(s.value(), 2.0 / 3.0); } } -TEST(LineSegment, getSValue_denormalize) +TEST(LineSegment, get2DSValue_denormalize) { math::geometry::LineSegment line(makePoint(0.0, 0.0, 0.0), makePoint(3.0, 3.0, 3.0)); - const auto s = line.getSValue(makePose(2.0, 2.0, 2.0), 1.0, true); + const auto s = line.get2DSValue(makePose(2.0, 2.0, 2.0), 1.0, true); EXPECT_TRUE(s); if (s) { - EXPECT_DOUBLE_EQ(s.value(), std::hypot(2.0, 2.0, 2.0)); + EXPECT_DOUBLE_EQ(s.value(), std::hypot(2.0, 2.0)); } } -TEST(LineSegment, getSValue_outOfRange) +TEST(LineSegment, get2DSValue_outOfRange) { math::geometry::LineSegment line(makePoint(0.0, 0.0, 0.0), makePoint(3.0, 3.0, 3.0)); - const auto s = line.getSValue(makePose(4.0, 4.0, 4.0), 1.0, false); + const auto s = line.get2DSValue(makePose(4.0, 4.0, 4.0), 1.0, false); EXPECT_FALSE(s); } -TEST(LineSegment, getSValue_outOfRangeDenormalize) +TEST(LineSegment, get2DSValue_outOfRangeDenormalize) { math::geometry::LineSegment line(makePoint(0.0, 0.0, 0.0), makePoint(3.0, 3.0, 3.0)); - const auto s = line.getSValue(makePose(4.0, 4.0, 4.0), 1.0, true); + const auto s = line.get2DSValue(makePose(4.0, 4.0, 4.0), 1.0, true); EXPECT_FALSE(s); } -TEST(LineSegment, getSValue_parallel) +TEST(LineSegment, get2DSValue_parallel) { math::geometry::LineSegment line(makePoint(0.0, 0.0, 0.0), makePoint(3.0, 3.0, 0.0)); - const auto s = line.getSValue( + const auto s = line.get2DSValue( makePose( 1.0, 0.0, 0.0, math::geometry::convertEulerAngleToQuaternion(makeVector(0.0, 0.0, M_PI_4 * 3.0))), @@ -315,10 +315,10 @@ TEST(LineSegment, getSValue_parallel) EXPECT_FALSE(s); } -TEST(LineSegment, getSValue_parallelDenormalize) +TEST(LineSegment, get2DSValue_parallelDenormalize) { math::geometry::LineSegment line(makePoint(0.0, 0.0, 0.0), makePoint(3.0, 3.0, 0.0)); - const auto s = line.getSValue( + const auto s = line.get2DSValue( makePose( 1.0, 0.0, 0.0, math::geometry::convertEulerAngleToQuaternion(makeVector(0.0, 0.0, M_PI_4 * 3.0))), From b2fc237f601a09a0ef0dac5da9ee3765e35b1536 Mon Sep 17 00:00:00 2001 From: robomic Date: Thu, 22 Aug 2024 15:00:39 +0200 Subject: [PATCH 157/304] rename getIntersection2DSValue, minor logical fixes regarding 2D vs 3D --- .../include/geometry/polygon/line_segment.hpp | 6 +- .../geometry/src/polygon/line_segment.cpp | 17 ++-- .../src/spline/catmull_rom_spline.cpp | 4 +- .../math/geometry/test/test_line_segment.cpp | 94 +++++++++---------- 4 files changed, 61 insertions(+), 60 deletions(-) diff --git a/common/math/geometry/include/geometry/polygon/line_segment.hpp b/common/math/geometry/include/geometry/polygon/line_segment.hpp index 3cb3e178627..4a347d36332 100644 --- a/common/math/geometry/include/geometry/polygon/line_segment.hpp +++ b/common/math/geometry/include/geometry/polygon/line_segment.hpp @@ -45,14 +45,14 @@ class LineSegment -> geometry_msgs::msg::Pose; auto isIntersect2D(const geometry_msgs::msg::Point & point) const -> bool; auto isIntersect2D(const LineSegment & line) const -> bool; - auto getIntersection2DSValue( + auto get2DIntersectionSValue( const geometry_msgs::msg::Point & point, const bool denormalize_s = false) const -> std::optional; - auto getIntersection2DSValue(const LineSegment & line, const bool denormalize_s = false) const + auto get2DIntersectionSValue(const LineSegment & line, const bool denormalize_s = false) const -> std::optional; auto getIntersection2D(const LineSegment & line) const -> std::optional; - auto get2DSValue( + auto getSValue( const geometry_msgs::msg::Pose & pose, double threshold_distance, bool denormalize_s) const -> std::optional; auto getVector() const -> const geometry_msgs::msg::Vector3 &; diff --git a/common/math/geometry/src/polygon/line_segment.cpp b/common/math/geometry/src/polygon/line_segment.cpp index b4085ec69fe..14e227ea750 100644 --- a/common/math/geometry/src/polygon/line_segment.cpp +++ b/common/math/geometry/src/polygon/line_segment.cpp @@ -140,11 +140,11 @@ auto LineSegment::isIntersect2D(const geometry_msgs::msg::Point & point) const - } } -auto LineSegment::get2DSValue( +auto LineSegment::getSValue( const geometry_msgs::msg::Pose & pose, double threshold_distance, bool denormalize_s) const -> std::optional { - return getIntersection2DSValue( + return get2DIntersectionSValue( LineSegment( math::geometry::transformPoint( pose, @@ -171,13 +171,14 @@ auto LineSegment::isIntersect2D(const LineSegment & line) const -> bool * @param point point of you want to find intersection. * @return std::optional */ -auto LineSegment::getIntersection2DSValue( +auto LineSegment::get2DIntersectionSValue( const geometry_msgs::msg::Point & point, const bool denormalize_s) const -> std::optional { if (isIntersect2D(point)) { - const double distance = std::hypot(point.x - start_point.x, point.y - start_point.y); - return denormalize_s ? std::make_optional(distance) - : std::make_optional(distance / get2DLength()); + const double proportion_2d = + std::hypot(point.x - start_point.x, point.y - start_point.y) / get2DLength(); + return denormalize_s ? std::make_optional(proportion_2d * getLength()) + : std::make_optional(proportion_2d); } else { return std::nullopt; } @@ -189,11 +190,11 @@ auto LineSegment::getIntersection2DSValue( * @param denormalize_s If true, s value should be normalized in range [0,1]. If false, s value is not normalized. * @return std::optional */ -auto LineSegment::getIntersection2DSValue(const LineSegment & line, const bool denormalize_s) const +auto LineSegment::get2DIntersectionSValue(const LineSegment & line, const bool denormalize_s) const -> std::optional { if (const auto point = getIntersection2D(line); point.has_value()) { - return getIntersection2DSValue(point.value(), denormalize_s); + return get2DIntersectionSValue(point.value(), denormalize_s); } else { return std::nullopt; } diff --git a/common/math/geometry/src/spline/catmull_rom_spline.cpp b/common/math/geometry/src/spline/catmull_rom_spline.cpp index 4f633488f00..0c5b6830cce 100644 --- a/common/math/geometry/src/spline/catmull_rom_spline.cpp +++ b/common/math/geometry/src/spline/catmull_rom_spline.cpp @@ -316,7 +316,7 @@ auto CatmullRomSpline::getCollisionPointsIn2D( "This message is not originally intended to be displayed, if you see it, please " "contact the developer of traffic_simulator."); } - if (const auto s = line_segments_[0].getIntersection2DSValue(line, true)) { + if (const auto s = line_segments_[0].get2DIntersectionSValue(line, true)) { s_value_candidates.insert(s.value()); } } @@ -425,7 +425,7 @@ auto CatmullRomSpline::getSValue( "This message is not originally intended to be displayed, if you see it, please " "contact the developer of traffic_simulator."); } - return line_segments_[0].get2DSValue(pose, threshold_distance, true); + return line_segments_[0].getSValue(pose, threshold_distance, true); default: double s = 0; for (size_t i = 0; i < curves_.size(); i++) { diff --git a/common/math/geometry/test/test_line_segment.cpp b/common/math/geometry/test/test_line_segment.cpp index 157b59c3b98..655e9b8499e 100644 --- a/common/math/geometry/test/test_line_segment.cpp +++ b/common/math/geometry/test/test_line_segment.cpp @@ -270,44 +270,44 @@ TEST(LineSegment, getLineSegmentsVectorIdentical_closeStartEnd) EXPECT_POINT_EQ(lines[3].end_point, point); } -TEST(LineSegment, get2DSValue) +TEST(LineSegment, getSValue) { math::geometry::LineSegment line(makePoint(0.0, 0.0, 0.0), makePoint(3.0, 3.0, 3.0)); - const auto s = line.get2DSValue(makePose(2.0, 2.0, 2.0), 1.0, false); + const auto s = line.getSValue(makePose(2.0, 2.0, 2.0), 1.0, false); EXPECT_TRUE(s); if (s) { EXPECT_DOUBLE_EQ(s.value(), 2.0 / 3.0); } } -TEST(LineSegment, get2DSValue_denormalize) +TEST(LineSegment, getSValue_denormalize) { math::geometry::LineSegment line(makePoint(0.0, 0.0, 0.0), makePoint(3.0, 3.0, 3.0)); - const auto s = line.get2DSValue(makePose(2.0, 2.0, 2.0), 1.0, true); + const auto s = line.getSValue(makePose(2.0, 2.0, 2.0), 1.0, true); EXPECT_TRUE(s); if (s) { - EXPECT_DOUBLE_EQ(s.value(), std::hypot(2.0, 2.0)); + EXPECT_DOUBLE_EQ(s.value(), std::hypot(2.0, 2.0, 2.0)); } } -TEST(LineSegment, get2DSValue_outOfRange) +TEST(LineSegment, getSValue_outOfRange) { math::geometry::LineSegment line(makePoint(0.0, 0.0, 0.0), makePoint(3.0, 3.0, 3.0)); - const auto s = line.get2DSValue(makePose(4.0, 4.0, 4.0), 1.0, false); + const auto s = line.getSValue(makePose(4.0, 4.0, 4.0), 1.0, false); EXPECT_FALSE(s); } -TEST(LineSegment, get2DSValue_outOfRangeDenormalize) +TEST(LineSegment, getSValue_outOfRangeDenormalize) { math::geometry::LineSegment line(makePoint(0.0, 0.0, 0.0), makePoint(3.0, 3.0, 3.0)); - const auto s = line.get2DSValue(makePose(4.0, 4.0, 4.0), 1.0, true); + const auto s = line.getSValue(makePose(4.0, 4.0, 4.0), 1.0, true); EXPECT_FALSE(s); } -TEST(LineSegment, get2DSValue_parallel) +TEST(LineSegment, getSValue_parallel) { math::geometry::LineSegment line(makePoint(0.0, 0.0, 0.0), makePoint(3.0, 3.0, 0.0)); - const auto s = line.get2DSValue( + const auto s = line.getSValue( makePose( 1.0, 0.0, 0.0, math::geometry::convertEulerAngleToQuaternion(makeVector(0.0, 0.0, M_PI_4 * 3.0))), @@ -315,10 +315,10 @@ TEST(LineSegment, get2DSValue_parallel) EXPECT_FALSE(s); } -TEST(LineSegment, get2DSValue_parallelDenormalize) +TEST(LineSegment, getSValue_parallelDenormalize) { math::geometry::LineSegment line(makePoint(0.0, 0.0, 0.0), makePoint(3.0, 3.0, 0.0)); - const auto s = line.get2DSValue( + const auto s = line.getSValue( makePose( 1.0, 0.0, 0.0, math::geometry::convertEulerAngleToQuaternion(makeVector(0.0, 0.0, M_PI_4 * 3.0))), @@ -464,109 +464,109 @@ TEST(LineSegment, isIntersect2D) } /// @brief In this test case, we check collision with the line segment with start point (x,y,z) = (0,-1,0) and end point (x,y,z) = (0,1,0) in the cartesian coordinate system. (variable name `line`). -TEST(LineSegment, getIntersection2DSValue) +TEST(LineSegment, get2DIntersectionSValue) { { math::geometry::LineSegment line( geometry_msgs::build().x(0).y(-1).z(0), geometry_msgs::build().x(0).y(1).z(0)); /** - * @note Testing the `LineSegment::getIntersection2DSValue` function can find a collision with the point with (x,y,z) = (0,0,0) in the cartesian coordinate system. + * @note Testing the `LineSegment::get2DIntersectionSValue` function can find a collision with the point with (x,y,z) = (0,0,0) in the cartesian coordinate system. * In the frenet coordinate system along the `line`, the s value should be 0.5. * If so, the variable `collision_s` should be `std::optional(0.5)`. */ - // [Snippet_getIntersection2DSValue_with_point_0_0_0] + // [Snippet_get2DIntersectionSValue_with_point_0_0_0] { - const auto collision_s = line.getIntersection2DSValue( + const auto collision_s = line.get2DIntersectionSValue( geometry_msgs::build().x(0).y(0).z(0), false); EXPECT_TRUE(collision_s); if (collision_s) { EXPECT_DOUBLE_EQ(collision_s.value(), 0.5); } } - // [Snippet_getIntersection2DSValue_with_point_0_0_0] - /// @snippet test/test_line_segment.cpp Snippet_getIntersection2DSValue_with_point_0_0_0 + // [Snippet_get2DIntersectionSValue_with_point_0_0_0] + /// @snippet test/test_line_segment.cpp Snippet_get2DIntersectionSValue_with_point_0_0_0 /** - * @note Testing the `LineSegment::getIntersection2DSValue` function can find a collision with the point with (x,y,z) = (0,1,0) in the cartesian coordinate system. + * @note Testing the `LineSegment::get2DIntersectionSValue` function can find a collision with the point with (x,y,z) = (0,1,0) in the cartesian coordinate system. * In the frenet coordinate system along the `line`, the s value should be 1.0. * If so, the variable `collision_s` should be `std::optional(1.0)`. */ - // [Snippet_getIntersection2DSValue_with_point_0_1_0] + // [Snippet_get2DIntersectionSValue_with_point_0_1_0] { - const auto collision_s = line.getIntersection2DSValue( + const auto collision_s = line.get2DIntersectionSValue( geometry_msgs::build().x(0).y(1).z(0), false); EXPECT_TRUE(collision_s); if (collision_s) { EXPECT_DOUBLE_EQ(collision_s.value(), 1.0); } } - // [Snippet_getIntersection2DSValue_with_point_0_1_0] - /// @snippet test/test_line_segment.cpp Snippet_getIntersection2DSValue_with_point_0_1_0 + // [Snippet_get2DIntersectionSValue_with_point_0_1_0] + /// @snippet test/test_line_segment.cpp Snippet_get2DIntersectionSValue_with_point_0_1_0 /** - * @note Testing the `LineSegment::getIntersection2DSValue` function can find a collision with the point with (x,y,z) = (0,1,0) in the cartesian coordinate system. + * @note Testing the `LineSegment::get2DIntersectionSValue` function can find a collision with the point with (x,y,z) = (0,1,0) in the cartesian coordinate system. * In the frenet coordinate system along the `line`, the s value should be 1.0. - * And, the 2nd argument of the `LineSegment::getIntersection2DSValue` (denormalized_s) is true, so the return value should be 1.0 (normalized s value.) * 2.0 (length of the `line`) = 2.0. + * And, the 2nd argument of the `LineSegment::get2DIntersectionSValue` (denormalized_s) is true, so the return value should be 1.0 (normalized s value.) * 2.0 (length of the `line`) = 2.0. * If so, the variable `collision_s` should be `std::optional(2.0)`. */ - // [Snippet_getIntersection2DSValue_with_point_0_1_0_denormalized] + // [Snippet_get2DIntersectionSValue_with_point_0_1_0_denormalized] { - const auto collision_s = line.getIntersection2DSValue( + const auto collision_s = line.get2DIntersectionSValue( geometry_msgs::build().x(0).y(1).z(0), true); EXPECT_TRUE(collision_s); if (collision_s) { EXPECT_DOUBLE_EQ(collision_s.value(), 2.0); } } - // [Snippet_getIntersection2DSValue_with_point_0_1_0_denormalized] - /// @snippet test/test_line_segment.cpp Snippet_getIntersection2DSValue_with_point_0_1_0_denormalized + // [Snippet_get2DIntersectionSValue_with_point_0_1_0_denormalized] + /// @snippet test/test_line_segment.cpp Snippet_get2DIntersectionSValue_with_point_0_1_0_denormalized /** - * @note Testing the `LineSegment::getIntersection2DSValue` function can find a collision with the point with (x,y,z) = (0,0,0) in the cartesian coordinate system. + * @note Testing the `LineSegment::get2DIntersectionSValue` function can find a collision with the point with (x,y,z) = (0,0,0) in the cartesian coordinate system. * In the frenet coordinate system along the `line`, the s value should be 0.5. - * And, the 2nd argument of the `LineSegment::getIntersection2DSValue` (denormalized_s) is true, so the return value should be 0.5 (normalized s value.) * 2.0 (length of the `line`) = 1.0. + * And, the 2nd argument of the `LineSegment::get2DIntersectionSValue` (denormalized_s) is true, so the return value should be 0.5 (normalized s value.) * 2.0 (length of the `line`) = 1.0. * If so, the variable `collision_s` should be `std::optional(1.0)`. */ - // [Snippet_getIntersection2DSValue_with_point_0_0_0_denormalized] + // [Snippet_get2DIntersectionSValue_with_point_0_0_0_denormalized] { - const auto collision_s = line.getIntersection2DSValue( + const auto collision_s = line.get2DIntersectionSValue( geometry_msgs::build().x(0).y(0).z(0), true); EXPECT_TRUE(collision_s); if (collision_s) { EXPECT_DOUBLE_EQ(collision_s.value(), 1.0); } } - // [Snippet_getIntersection2DSValue_with_point_0_0_0_denormalized] - /// @snippet test/test_line_segment.cpp Snippet_getIntersection2DSValue_with_point_0_0_0_denormalized + // [Snippet_get2DIntersectionSValue_with_point_0_0_0_denormalized] + /// @snippet test/test_line_segment.cpp Snippet_get2DIntersectionSValue_with_point_0_0_0_denormalized /** - * @note Testing the `LineSegment::getIntersection2DSValue` function can find that the point with (x,y,z) = (1,0,0) in the cartesian coordinate system does not collide to `line.`. + * @note Testing the `LineSegment::get2DIntersectionSValue` function can find that the point with (x,y,z) = (1,0,0) in the cartesian coordinate system does not collide to `line.`. * If the function works valid, the variable `collision_s` should be `std::nullopt`. */ - // [Snippet_getIntersection2DSValue_with_point_1_0_0] + // [Snippet_get2DIntersectionSValue_with_point_1_0_0] { - const auto collision_s = line.getIntersection2DSValue( + const auto collision_s = line.get2DIntersectionSValue( geometry_msgs::build().x(1).y(0).z(0), false); EXPECT_FALSE(collision_s); } - // [Snippet_getIntersection2DSValue_with_point_1_0_0] - /// @snippet test/test_line_segment.cpp Snippet_getIntersection2DSValue_with_point_1_0_0 + // [Snippet_get2DIntersectionSValue_with_point_1_0_0] + /// @snippet test/test_line_segment.cpp Snippet_get2DIntersectionSValue_with_point_1_0_0 { // parallel no denormalize EXPECT_THROW( - line.getIntersection2DSValue( + line.get2DIntersectionSValue( math::geometry::LineSegment(makePoint(0.0, -1.0), makePoint(0.0, 1.0)), false), common::SimulationError); } { // parallel denormalize EXPECT_THROW( - line.getIntersection2DSValue( + line.get2DIntersectionSValue( math::geometry::LineSegment(makePoint(0.0, -1.0), makePoint(0.0, 1.0)), true), common::SimulationError); } { // intersect no denormalize - const auto collision_s = line.getIntersection2DSValue( + const auto collision_s = line.get2DIntersectionSValue( math::geometry::LineSegment(makePoint(-1.0, 0.5), makePoint(1.0, 0.5)), false); EXPECT_TRUE(collision_s); if (collision_s) { @@ -574,7 +574,7 @@ TEST(LineSegment, getIntersection2DSValue) } } { // intersect denormalize - const auto collision_s = line.getIntersection2DSValue( + const auto collision_s = line.get2DIntersectionSValue( math::geometry::LineSegment(makePoint(-1.0, 0.5), makePoint(1.0, 0.5)), true); EXPECT_TRUE(collision_s); if (collision_s) { @@ -582,12 +582,12 @@ TEST(LineSegment, getIntersection2DSValue) } } { // no intersect no denormalize - const auto collision_s = line.getIntersection2DSValue( + const auto collision_s = line.get2DIntersectionSValue( math::geometry::LineSegment(makePoint(-1.0, 1.5), makePoint(1.0, 1.5)), false); EXPECT_FALSE(collision_s); } { // no intersect denormalize - const auto collision_s = line.getIntersection2DSValue( + const auto collision_s = line.get2DIntersectionSValue( math::geometry::LineSegment(makePoint(-1.0, 1.5), makePoint(1.0, 1.5)), true); EXPECT_FALSE(collision_s); } From 2491871b779b9fe40f2eff16c97c14fff5be6357 Mon Sep 17 00:00:00 2001 From: robomic Date: Thu, 22 Aug 2024 15:14:14 +0200 Subject: [PATCH 158/304] use has_value --- common/math/geometry/src/polygon/line_segment.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/common/math/geometry/src/polygon/line_segment.cpp b/common/math/geometry/src/polygon/line_segment.cpp index 14e227ea750..50253b30a3b 100644 --- a/common/math/geometry/src/polygon/line_segment.cpp +++ b/common/math/geometry/src/polygon/line_segment.cpp @@ -277,10 +277,10 @@ auto LineSegment::denormalize( const std::optional & s, const bool throw_error_on_out_of_range) const -> std::optional { - if (!throw_error_on_out_of_range && s && !(0.0 <= s.value() && s.value() <= 1.0)) { + if (!throw_error_on_out_of_range && s.has_value() && !(0.0 <= s.value() && s.value() <= 1.0)) { return std::nullopt; } - return s ? std::make_optional(denormalize(s.value())) : std::nullopt; + return s.has_value() ? std::make_optional(denormalize(s.value())) : std::nullopt; } /** From bfd72c37a32d7b0c32f423267e0f362eccbb8ad7 Mon Sep 17 00:00:00 2001 From: robomic Date: Thu, 22 Aug 2024 15:24:14 +0200 Subject: [PATCH 159/304] simplify denormalize logic --- common/math/geometry/src/polygon/line_segment.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/common/math/geometry/src/polygon/line_segment.cpp b/common/math/geometry/src/polygon/line_segment.cpp index 50253b30a3b..6bb662aa1ba 100644 --- a/common/math/geometry/src/polygon/line_segment.cpp +++ b/common/math/geometry/src/polygon/line_segment.cpp @@ -277,10 +277,10 @@ auto LineSegment::denormalize( const std::optional & s, const bool throw_error_on_out_of_range) const -> std::optional { - if (!throw_error_on_out_of_range && s.has_value() && !(0.0 <= s.value() && s.value() <= 1.0)) { + if (!s.has_value() || (!throw_error_on_out_of_range && !(0.0 <= s.value() && s.value() <= 1.0))) { return std::nullopt; } - return s.has_value() ? std::make_optional(denormalize(s.value())) : std::nullopt; + return std::make_optional(denormalize(s.value())); } /** From 8d08efd76db0cd31fd086962f3bcb0e45e234e96 Mon Sep 17 00:00:00 2001 From: robomic Date: Thu, 22 Aug 2024 15:45:03 +0200 Subject: [PATCH 160/304] remove unnecessary lambda --- common/math/geometry/src/polygon/line_segment.cpp | 13 +++++-------- 1 file changed, 5 insertions(+), 8 deletions(-) diff --git a/common/math/geometry/src/polygon/line_segment.cpp b/common/math/geometry/src/polygon/line_segment.cpp index 6bb662aa1ba..792757e11ce 100644 --- a/common/math/geometry/src/polygon/line_segment.cpp +++ b/common/math/geometry/src/polygon/line_segment.cpp @@ -112,14 +112,11 @@ auto LineSegment::getPose(const double s, const bool denormalize_s, const bool f { return geometry_msgs::build() .position(getPoint(s, denormalize_s)) - .orientation([this, fill_pitch]() -> geometry_msgs::msg::Quaternion { - return math::geometry::convertEulerAngleToQuaternion( - geometry_msgs::build() - .x(0.0) - .y( - fill_pitch ? std::atan2(-getVector().z, std::hypot(getVector().x, getVector().y)) : 0.0) - .z(std::atan2(getVector().y, getVector().x))); - }()); + .orientation(math::geometry::convertEulerAngleToQuaternion( + geometry_msgs::build() + .x(0.0) + .y(fill_pitch ? std::atan2(-getVector().z, std::hypot(getVector().x, getVector().y)) : 0.0) + .z(std::atan2(getVector().y, getVector().x)))); } /** From 4d02d380eaa1e1c89844d112a6179666d46dce21 Mon Sep 17 00:00:00 2001 From: robomic Date: Thu, 22 Aug 2024 16:20:05 +0200 Subject: [PATCH 161/304] rename getSlope, add consts --- .../include/geometry/polygon/line_segment.hpp | 10 ++++++---- .../geometry/src/intersection/intersection.cpp | 3 ++- common/math/geometry/src/polygon/line_segment.cpp | 14 +++++++++++--- common/math/geometry/test/test_line_segment.cpp | 8 ++++---- 4 files changed, 23 insertions(+), 12 deletions(-) diff --git a/common/math/geometry/include/geometry/polygon/line_segment.hpp b/common/math/geometry/include/geometry/polygon/line_segment.hpp index 4a347d36332..6fb16991950 100644 --- a/common/math/geometry/include/geometry/polygon/line_segment.hpp +++ b/common/math/geometry/include/geometry/polygon/line_segment.hpp @@ -39,12 +39,15 @@ class LineSegment double length); ~LineSegment(); LineSegment & operator=(const LineSegment &); + + auto isIntersect2D(const geometry_msgs::msg::Point & point) const -> bool; + auto isIntersect2D(const LineSegment & line) const -> bool; + auto isInBounds2D(const geometry_msgs::msg::Point & point) const -> bool; + auto getPoint(const double s, const bool denormalize_s = false) const -> geometry_msgs::msg::Point; auto getPose(const double s, const bool denormalize_s = false, const bool fill_pitch = true) const -> geometry_msgs::msg::Pose; - auto isIntersect2D(const geometry_msgs::msg::Point & point) const -> bool; - auto isIntersect2D(const LineSegment & line) const -> bool; auto get2DIntersectionSValue( const geometry_msgs::msg::Point & point, const bool denormalize_s = false) const -> std::optional; @@ -60,14 +63,13 @@ class LineSegment auto get2DVector() const -> const geometry_msgs::msg::Vector3 &; auto getLength() const -> double; auto get2DLength() const -> double; - auto getSlope() const -> double; + auto get2DVectorSlope() const -> double; auto getSquaredDistanceIn2D( const geometry_msgs::msg::Point & point, const double s, const bool denormalize_s = false) const -> double; auto getSquaredDistanceVector( const geometry_msgs::msg::Point & point, const double s, const bool denormalize_s = false) const -> geometry_msgs::msg::Vector3; - auto isInBounds2D(const geometry_msgs::msg::Point & point) const -> bool; auto relativePointPosition2D(const geometry_msgs::msg::Point & point) const -> int; private: diff --git a/common/math/geometry/src/intersection/intersection.cpp b/common/math/geometry/src/intersection/intersection.cpp index c87e2352662..1b1a1f3e586 100644 --- a/common/math/geometry/src/intersection/intersection.cpp +++ b/common/math/geometry/src/intersection/intersection.cpp @@ -13,6 +13,7 @@ // limitations under the License. #include +#include #include #include @@ -71,7 +72,7 @@ std::optional getIntersection2D( const double determinant = a0 * b1 - a1 * b0; - if (std::abs(determinant) < 1.0e-10) { + if (std::abs(determinant) <= std::numeric_limits::epsilon()) { // The lines do intersect, but they are collinear and overlap. THROW_SIMULATION_ERROR( "Line segments are collinear. So determinant is zero.", diff --git a/common/math/geometry/src/polygon/line_segment.cpp b/common/math/geometry/src/polygon/line_segment.cpp index 792757e11ce..1325e4159af 100644 --- a/common/math/geometry/src/polygon/line_segment.cpp +++ b/common/math/geometry/src/polygon/line_segment.cpp @@ -48,7 +48,7 @@ LineSegment::LineSegment( const geometry_msgs::msg::Point & start_point, const geometry_msgs::msg::Vector3 & vec, const double length) : LineSegment::LineSegment(start_point, [&]() -> geometry_msgs::msg::Point { - if (double vec_size = std::hypot(vec.x, vec.y); vec_size == 0.0) { + if (const double vec_size = std::hypot(vec.x, vec.y); vec_size == 0.0) { THROW_SIMULATION_ERROR( "Invalid vector is specified, while constructing LineSegment. ", "The vector should have a non zero length to initialize the line segment correctly. ", @@ -171,6 +171,8 @@ auto LineSegment::isIntersect2D(const LineSegment & line) const -> bool auto LineSegment::get2DIntersectionSValue( const geometry_msgs::msg::Point & point, const bool denormalize_s) const -> std::optional { + // Note: We check for an SValue along the line. + // The term "2D" in the function name specifically refers to the intersection point, not SValue. if (isIntersect2D(point)) { const double proportion_2d = std::hypot(point.x - start_point.x, point.y - start_point.y) / get2DLength(); @@ -216,7 +218,7 @@ auto LineSegment::getVector() const -> const geometry_msgs::msg::Vector3 & { ret */ auto LineSegment::getNormalVector() const -> geometry_msgs::msg::Vector3 { - double theta = M_PI / 2.0; + const double theta = M_PI / 2.0; return geometry_msgs::build() .x(getVector().x * std::cos(theta) - getVector().y * std::sin(theta)) .y(getVector().x * std::sin(theta) + getVector().y * std::cos(theta)) @@ -229,7 +231,13 @@ auto LineSegment::get2DLength() const -> double { return length_2d; } auto LineSegment::getLength() const -> double { return length; } -auto LineSegment::getSlope() const -> double { return get2DVector().y / get2DVector().x; } +auto LineSegment::get2DVectorSlope() const -> double +{ + if (get2DVector().x <= std::numeric_limits::epsilon()) { + THROW_SIMULATION_ERROR("Slope of a vertical line is undefined"); + } + return get2DVector().y / get2DVector().x; +} /** * @brief Get squared distance (Square of euclidean distance) between specified 3D point and specified 3D point on line segment in 2D. (x,y) diff --git a/common/math/geometry/test/test_line_segment.cpp b/common/math/geometry/test/test_line_segment.cpp index 655e9b8499e..01011d528b6 100644 --- a/common/math/geometry/test/test_line_segment.cpp +++ b/common/math/geometry/test/test_line_segment.cpp @@ -156,16 +156,16 @@ TEST(LineSegment, get2DLengthZeroLength) EXPECT_DOUBLE_EQ(line.get2DLength(), 0.0); } -TEST(LineSegment, getSlope) +TEST(LineSegment, get2DVectorSlope) { const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(3.0, 3.0, 4.0)); - EXPECT_DOUBLE_EQ(line.getSlope(), 0.5); + EXPECT_DOUBLE_EQ(line.get2DVectorSlope(), 0.5); } -TEST(LineSegment, getSlopeZeroLength) +TEST(LineSegment, get2DVectorSlopeZeroLength) { const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(1.0, 2.0, 3.0)); - EXPECT_TRUE(std::isnan(line.getSlope())); + EXPECT_THROW(line.get2DVectorSlope(), common::SimulationError); } TEST(LineSegment, getSquaredDistanceIn2D) From 9a834f0ee0950bdb115eecb78e1fa9d5b94ea8e6 Mon Sep 17 00:00:00 2001 From: robomic Date: Thu, 22 Aug 2024 16:21:32 +0200 Subject: [PATCH 162/304] add else to if statements --- common/math/geometry/src/polygon/line_segment.cpp | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/common/math/geometry/src/polygon/line_segment.cpp b/common/math/geometry/src/polygon/line_segment.cpp index 1325e4159af..7e5a192ca11 100644 --- a/common/math/geometry/src/polygon/line_segment.cpp +++ b/common/math/geometry/src/polygon/line_segment.cpp @@ -235,8 +235,9 @@ auto LineSegment::get2DVectorSlope() const -> double { if (get2DVector().x <= std::numeric_limits::epsilon()) { THROW_SIMULATION_ERROR("Slope of a vertical line is undefined"); + } else { + return get2DVector().y / get2DVector().x; } - return get2DVector().y / get2DVector().x; } /** @@ -284,8 +285,9 @@ auto LineSegment::denormalize( { if (!s.has_value() || (!throw_error_on_out_of_range && !(0.0 <= s.value() && s.value() <= 1.0))) { return std::nullopt; + } else { + return std::make_optional(denormalize(s.value())); } - return std::make_optional(denormalize(s.value())); } /** From 634603360fba82d67c519d9f4a6ad7fbb7addd77 Mon Sep 17 00:00:00 2001 From: robomic Date: Thu, 22 Aug 2024 16:31:22 +0200 Subject: [PATCH 163/304] note --- common/math/geometry/src/polygon/line_segment.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/common/math/geometry/src/polygon/line_segment.cpp b/common/math/geometry/src/polygon/line_segment.cpp index 7e5a192ca11..8661b39015b 100644 --- a/common/math/geometry/src/polygon/line_segment.cpp +++ b/common/math/geometry/src/polygon/line_segment.cpp @@ -171,8 +171,7 @@ auto LineSegment::isIntersect2D(const LineSegment & line) const -> bool auto LineSegment::get2DIntersectionSValue( const geometry_msgs::msg::Point & point, const bool denormalize_s) const -> std::optional { - // Note: We check for an SValue along the line. - // The term "2D" in the function name specifically refers to the intersection point, not SValue. + /// @note This function checks for an SValue along the line. The term "2D" in the function name specifically refers to the intersection point, not SValue. if (isIntersect2D(point)) { const double proportion_2d = std::hypot(point.x - start_point.x, point.y - start_point.y) / get2DLength(); From 800a06cbcc79d1e977e77427677a20b6982a208e Mon Sep 17 00:00:00 2001 From: Release Bot Date: Fri, 23 Aug 2024 03:19:57 +0000 Subject: [PATCH 164/304] Bump version of scenario_simulator_v2 from version 3.5.1 to version 3.5.2 --- common/math/arithmetic/CHANGELOG.rst | 7 +++++++ common/math/arithmetic/package.xml | 2 +- common/math/geometry/CHANGELOG.rst | 7 +++++++ common/math/geometry/package.xml | 2 +- common/scenario_simulator_exception/CHANGELOG.rst | 7 +++++++ common/scenario_simulator_exception/package.xml | 2 +- common/simple_junit/CHANGELOG.rst | 7 +++++++ common/simple_junit/package.xml | 2 +- common/status_monitor/CHANGELOG.rst | 7 +++++++ common/status_monitor/package.xml | 2 +- external/concealer/CHANGELOG.rst | 10 ++++++++++ external/concealer/package.xml | 2 +- external/embree_vendor/CHANGELOG.rst | 7 +++++++ external/embree_vendor/package.xml | 2 +- map/kashiwanoha_map/CHANGELOG.rst | 7 +++++++ map/kashiwanoha_map/package.xml | 2 +- map/simple_cross_map/CHANGELOG.rst | 7 +++++++ map/simple_cross_map/package.xml | 2 +- mock/cpp_mock_scenarios/CHANGELOG.rst | 7 +++++++ mock/cpp_mock_scenarios/package.xml | 2 +- .../openscenario_experimental_catalog/CHANGELOG.rst | 7 +++++++ .../openscenario_experimental_catalog/package.xml | 2 +- openscenario/openscenario_interpreter/CHANGELOG.rst | 12 ++++++++++++ openscenario/openscenario_interpreter/package.xml | 2 +- .../openscenario_interpreter_example/CHANGELOG.rst | 7 +++++++ .../openscenario_interpreter_example/package.xml | 2 +- .../openscenario_interpreter_msgs/CHANGELOG.rst | 7 +++++++ .../openscenario_interpreter_msgs/package.xml | 2 +- openscenario/openscenario_preprocessor/CHANGELOG.rst | 7 +++++++ openscenario/openscenario_preprocessor/package.xml | 2 +- .../openscenario_preprocessor_msgs/CHANGELOG.rst | 7 +++++++ .../openscenario_preprocessor_msgs/package.xml | 2 +- openscenario/openscenario_utility/CHANGELOG.rst | 7 +++++++ openscenario/openscenario_utility/package.xml | 2 +- openscenario/openscenario_validator/CHANGELOG.rst | 7 +++++++ openscenario/openscenario_validator/package.xml | 2 +- .../openscenario_visualization/CHANGELOG.rst | 7 +++++++ rviz_plugins/openscenario_visualization/package.xml | 2 +- .../CHANGELOG.rst | 7 +++++++ .../real_time_factor_control_rviz_plugin/package.xml | 2 +- scenario_simulator_v2/CHANGELOG.rst | 7 +++++++ scenario_simulator_v2/package.xml | 2 +- simulation/behavior_tree_plugin/CHANGELOG.rst | 7 +++++++ simulation/behavior_tree_plugin/package.xml | 2 +- simulation/do_nothing_plugin/CHANGELOG.rst | 7 +++++++ simulation/do_nothing_plugin/package.xml | 2 +- simulation/simple_sensor_simulator/CHANGELOG.rst | 7 +++++++ simulation/simple_sensor_simulator/package.xml | 2 +- simulation/simulation_interface/CHANGELOG.rst | 7 +++++++ simulation/simulation_interface/package.xml | 2 +- simulation/traffic_simulator/CHANGELOG.rst | 7 +++++++ simulation/traffic_simulator/package.xml | 2 +- simulation/traffic_simulator_msgs/CHANGELOG.rst | 7 +++++++ simulation/traffic_simulator_msgs/package.xml | 2 +- test_runner/random_test_runner/CHANGELOG.rst | 7 +++++++ test_runner/random_test_runner/package.xml | 2 +- test_runner/scenario_test_runner/CHANGELOG.rst | 11 +++++++++++ test_runner/scenario_test_runner/package.xml | 2 +- 58 files changed, 244 insertions(+), 29 deletions(-) diff --git a/common/math/arithmetic/CHANGELOG.rst b/common/math/arithmetic/CHANGELOG.rst index ac0f5ca5f33..e6143092224 100644 --- a/common/math/arithmetic/CHANGELOG.rst +++ b/common/math/arithmetic/CHANGELOG.rst @@ -21,6 +21,13 @@ Changelog for package arithmetic * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.2 (2024-08-23) +------------------ +* Merge branch 'master' into fix/interpreter/user-defined-value-condition +* Merge branch 'master' into fix/interpreter/user-defined-value-condition +* Merge remote-tracking branch 'origin/master' into fix/interpreter/user-defined-value-condition +* Contributors: Tatsuya Yamasaki, yamacir-kit + 3.5.1 (2024-08-22) ------------------ * Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization diff --git a/common/math/arithmetic/package.xml b/common/math/arithmetic/package.xml index 1542cfbbd32..018ff9fb011 100644 --- a/common/math/arithmetic/package.xml +++ b/common/math/arithmetic/package.xml @@ -2,7 +2,7 @@ arithmetic - 3.5.1 + 3.5.2 arithmetic library for scenario_simulator_v2 Tatsuya Yamasaki Apache License 2.0 diff --git a/common/math/geometry/CHANGELOG.rst b/common/math/geometry/CHANGELOG.rst index 8b3636f5ba8..ef2f91fbdb1 100644 --- a/common/math/geometry/CHANGELOG.rst +++ b/common/math/geometry/CHANGELOG.rst @@ -21,6 +21,13 @@ Changelog for package geometry * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.2 (2024-08-23) +------------------ +* Merge branch 'master' into fix/interpreter/user-defined-value-condition +* Merge branch 'master' into fix/interpreter/user-defined-value-condition +* Merge remote-tracking branch 'origin/master' into fix/interpreter/user-defined-value-condition +* Contributors: Tatsuya Yamasaki, yamacir-kit + 3.5.1 (2024-08-22) ------------------ * Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization diff --git a/common/math/geometry/package.xml b/common/math/geometry/package.xml index 09e966802a6..e6a5e7a7188 100644 --- a/common/math/geometry/package.xml +++ b/common/math/geometry/package.xml @@ -2,7 +2,7 @@ geometry - 3.5.1 + 3.5.2 geometry math library for scenario_simulator_v2 application Masaya Kataoka Apache License 2.0 diff --git a/common/scenario_simulator_exception/CHANGELOG.rst b/common/scenario_simulator_exception/CHANGELOG.rst index b8b7cf2f5ed..d4d80b71f2b 100644 --- a/common/scenario_simulator_exception/CHANGELOG.rst +++ b/common/scenario_simulator_exception/CHANGELOG.rst @@ -21,6 +21,13 @@ Changelog for package scenario_simulator_exception * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.2 (2024-08-23) +------------------ +* Merge branch 'master' into fix/interpreter/user-defined-value-condition +* Merge branch 'master' into fix/interpreter/user-defined-value-condition +* Merge remote-tracking branch 'origin/master' into fix/interpreter/user-defined-value-condition +* Contributors: Tatsuya Yamasaki, yamacir-kit + 3.5.1 (2024-08-22) ------------------ * Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization diff --git a/common/scenario_simulator_exception/package.xml b/common/scenario_simulator_exception/package.xml index ad4a4cac524..4d092356a5a 100644 --- a/common/scenario_simulator_exception/package.xml +++ b/common/scenario_simulator_exception/package.xml @@ -2,7 +2,7 @@ scenario_simulator_exception - 3.5.1 + 3.5.2 Exception types for scenario simulator Tatsuya Yamasaki Apache License 2.0 diff --git a/common/simple_junit/CHANGELOG.rst b/common/simple_junit/CHANGELOG.rst index e68f4933db7..9818ba53118 100644 --- a/common/simple_junit/CHANGELOG.rst +++ b/common/simple_junit/CHANGELOG.rst @@ -21,6 +21,13 @@ Changelog for package junit_exporter * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.2 (2024-08-23) +------------------ +* Merge branch 'master' into fix/interpreter/user-defined-value-condition +* Merge branch 'master' into fix/interpreter/user-defined-value-condition +* Merge remote-tracking branch 'origin/master' into fix/interpreter/user-defined-value-condition +* Contributors: Tatsuya Yamasaki, yamacir-kit + 3.5.1 (2024-08-22) ------------------ * Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization diff --git a/common/simple_junit/package.xml b/common/simple_junit/package.xml index 1a49e5ad5d1..4ab46e09f15 100644 --- a/common/simple_junit/package.xml +++ b/common/simple_junit/package.xml @@ -2,7 +2,7 @@ simple_junit - 3.5.1 + 3.5.2 Lightweight JUnit library for ROS 2 Masaya Kataoka Tatsuya Yamasaki diff --git a/common/status_monitor/CHANGELOG.rst b/common/status_monitor/CHANGELOG.rst index ad75075183c..e39b9ece0eb 100644 --- a/common/status_monitor/CHANGELOG.rst +++ b/common/status_monitor/CHANGELOG.rst @@ -21,6 +21,13 @@ Changelog for package status_monitor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.2 (2024-08-23) +------------------ +* Merge branch 'master' into fix/interpreter/user-defined-value-condition +* Merge branch 'master' into fix/interpreter/user-defined-value-condition +* Merge remote-tracking branch 'origin/master' into fix/interpreter/user-defined-value-condition +* Contributors: Tatsuya Yamasaki, yamacir-kit + 3.5.1 (2024-08-22) ------------------ * Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization diff --git a/common/status_monitor/package.xml b/common/status_monitor/package.xml index 5bbfcbe8b86..f57550fbcc6 100644 --- a/common/status_monitor/package.xml +++ b/common/status_monitor/package.xml @@ -2,7 +2,7 @@ status_monitor - 3.5.1 + 3.5.2 none Tatsuya Yamasaki Apache License 2.0 diff --git a/external/concealer/CHANGELOG.rst b/external/concealer/CHANGELOG.rst index deda8815c72..8dc1e06f8ea 100644 --- a/external/concealer/CHANGELOG.rst +++ b/external/concealer/CHANGELOG.rst @@ -21,6 +21,16 @@ Changelog for package concealer * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.2 (2024-08-23) +------------------ +* Merge pull request `#1338 `_ from tier4/fix/interpreter/user-defined-value-condition + Fix/interpreter/user defined value condition +* Merge branch 'master' into fix/interpreter/user-defined-value-condition +* Merge branch 'master' into fix/interpreter/user-defined-value-condition +* Merge remote-tracking branch 'origin/master' into fix/interpreter/user-defined-value-condition +* Change QoS of `/api/localization/initialization_state` to transient local +* Contributors: Tatsuya Yamasaki, yamacir-kit + 3.5.1 (2024-08-22) ------------------ * Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization diff --git a/external/concealer/package.xml b/external/concealer/package.xml index c78d2eef81b..a81b6c11749 100644 --- a/external/concealer/package.xml +++ b/external/concealer/package.xml @@ -2,7 +2,7 @@ concealer - 3.5.1 + 3.5.2 Provides a class 'Autoware' to conceal miscellaneous things to simplify Autoware management of the simulator. Tatsuya Yamasaki Apache License 2.0 diff --git a/external/embree_vendor/CHANGELOG.rst b/external/embree_vendor/CHANGELOG.rst index e62e13ad4fb..bbfb8cd28ea 100644 --- a/external/embree_vendor/CHANGELOG.rst +++ b/external/embree_vendor/CHANGELOG.rst @@ -24,6 +24,13 @@ Changelog for package embree_vendor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.2 (2024-08-23) +------------------ +* Merge branch 'master' into fix/interpreter/user-defined-value-condition +* Merge branch 'master' into fix/interpreter/user-defined-value-condition +* Merge remote-tracking branch 'origin/master' into fix/interpreter/user-defined-value-condition +* Contributors: Tatsuya Yamasaki, yamacir-kit + 3.5.1 (2024-08-22) ------------------ * Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization diff --git a/external/embree_vendor/package.xml b/external/embree_vendor/package.xml index baf82bb0137..886e2ad4790 100644 --- a/external/embree_vendor/package.xml +++ b/external/embree_vendor/package.xml @@ -2,7 +2,7 @@ embree_vendor - 3.5.1 + 3.5.2 vendor packages for intel raytracing kernel library masaya Apache 2.0 diff --git a/map/kashiwanoha_map/CHANGELOG.rst b/map/kashiwanoha_map/CHANGELOG.rst index d875dfa071f..44adc3b2a99 100644 --- a/map/kashiwanoha_map/CHANGELOG.rst +++ b/map/kashiwanoha_map/CHANGELOG.rst @@ -21,6 +21,13 @@ Changelog for package kashiwanoha_map * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.2 (2024-08-23) +------------------ +* Merge branch 'master' into fix/interpreter/user-defined-value-condition +* Merge branch 'master' into fix/interpreter/user-defined-value-condition +* Merge remote-tracking branch 'origin/master' into fix/interpreter/user-defined-value-condition +* Contributors: Tatsuya Yamasaki, yamacir-kit + 3.5.1 (2024-08-22) ------------------ * Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization diff --git a/map/kashiwanoha_map/package.xml b/map/kashiwanoha_map/package.xml index 41bc8eece20..2e7eadce210 100644 --- a/map/kashiwanoha_map/package.xml +++ b/map/kashiwanoha_map/package.xml @@ -2,7 +2,7 @@ kashiwanoha_map - 3.5.1 + 3.5.2 map package for kashiwanoha Masaya Kataoka Apache License 2.0 diff --git a/map/simple_cross_map/CHANGELOG.rst b/map/simple_cross_map/CHANGELOG.rst index 99eb97082be..79f743c227e 100644 --- a/map/simple_cross_map/CHANGELOG.rst +++ b/map/simple_cross_map/CHANGELOG.rst @@ -9,6 +9,13 @@ Changelog for package simple_cross_map * Merge branch 'master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.2 (2024-08-23) +------------------ +* Merge branch 'master' into fix/interpreter/user-defined-value-condition +* Merge branch 'master' into fix/interpreter/user-defined-value-condition +* Merge remote-tracking branch 'origin/master' into fix/interpreter/user-defined-value-condition +* Contributors: Tatsuya Yamasaki, yamacir-kit + 3.5.1 (2024-08-22) ------------------ * Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization diff --git a/map/simple_cross_map/package.xml b/map/simple_cross_map/package.xml index ce243fd32c9..99e5424db70 100644 --- a/map/simple_cross_map/package.xml +++ b/map/simple_cross_map/package.xml @@ -2,7 +2,7 @@ simple_cross_map - 3.5.1 + 3.5.2 map package for simple cross Masaya Kataoka Apache License 2.0 diff --git a/mock/cpp_mock_scenarios/CHANGELOG.rst b/mock/cpp_mock_scenarios/CHANGELOG.rst index 3b79763d377..87db40be421 100644 --- a/mock/cpp_mock_scenarios/CHANGELOG.rst +++ b/mock/cpp_mock_scenarios/CHANGELOG.rst @@ -21,6 +21,13 @@ Changelog for package cpp_mock_scenarios * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.2 (2024-08-23) +------------------ +* Merge branch 'master' into fix/interpreter/user-defined-value-condition +* Merge branch 'master' into fix/interpreter/user-defined-value-condition +* Merge remote-tracking branch 'origin/master' into fix/interpreter/user-defined-value-condition +* Contributors: Tatsuya Yamasaki, yamacir-kit + 3.5.1 (2024-08-22) ------------------ * Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization diff --git a/mock/cpp_mock_scenarios/package.xml b/mock/cpp_mock_scenarios/package.xml index 3fe9da935d1..9f219e0de12 100644 --- a/mock/cpp_mock_scenarios/package.xml +++ b/mock/cpp_mock_scenarios/package.xml @@ -2,7 +2,7 @@ cpp_mock_scenarios - 3.5.1 + 3.5.2 C++ mock scenarios masaya Apache License 2.0 diff --git a/openscenario/openscenario_experimental_catalog/CHANGELOG.rst b/openscenario/openscenario_experimental_catalog/CHANGELOG.rst index 6bae1ecad5f..708e2e2a241 100644 --- a/openscenario/openscenario_experimental_catalog/CHANGELOG.rst +++ b/openscenario/openscenario_experimental_catalog/CHANGELOG.rst @@ -21,6 +21,13 @@ Changelog for package openscenario_experimental_catalog * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.2 (2024-08-23) +------------------ +* Merge branch 'master' into fix/interpreter/user-defined-value-condition +* Merge branch 'master' into fix/interpreter/user-defined-value-condition +* Merge remote-tracking branch 'origin/master' into fix/interpreter/user-defined-value-condition +* Contributors: Tatsuya Yamasaki, yamacir-kit + 3.5.1 (2024-08-22) ------------------ * Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization diff --git a/openscenario/openscenario_experimental_catalog/package.xml b/openscenario/openscenario_experimental_catalog/package.xml index b94f7bb8cb2..20ae47e3ab9 100644 --- a/openscenario/openscenario_experimental_catalog/package.xml +++ b/openscenario/openscenario_experimental_catalog/package.xml @@ -2,7 +2,7 @@ openscenario_experimental_catalog - 3.5.1 + 3.5.2 TIER IV experimental catalogs for OpenSCENARIO Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter/CHANGELOG.rst b/openscenario/openscenario_interpreter/CHANGELOG.rst index 4eac3623e5c..47d6db82b6b 100644 --- a/openscenario/openscenario_interpreter/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter/CHANGELOG.rst @@ -32,6 +32,18 @@ Changelog for package openscenario_interpreter * add publish_empty_context parameter * Contributors: Masaya Kataoka +3.5.2 (2024-08-23) +------------------ +* Merge pull request `#1338 `_ from tier4/fix/interpreter/user-defined-value-condition + Fix/interpreter/user defined value condition +* Merge branch 'master' into fix/interpreter/user-defined-value-condition +* Merge branch 'master' into fix/interpreter/user-defined-value-condition +* Update `MagicSubscription`'s QoS to best effort +* Merge remote-tracking branch 'origin/master' into fix/interpreter/user-defined-value-condition +* Cleanup struct `MagicSubscription` +* Update MagicSubscription to share resources between instances +* Contributors: Tatsuya Yamasaki, yamacir-kit + 3.5.1 (2024-08-22) ------------------ * Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization diff --git a/openscenario/openscenario_interpreter/package.xml b/openscenario/openscenario_interpreter/package.xml index 1f4c6f5557f..cacd0286ec4 100644 --- a/openscenario/openscenario_interpreter/package.xml +++ b/openscenario/openscenario_interpreter/package.xml @@ -2,7 +2,7 @@ openscenario_interpreter - 3.5.1 + 3.5.2 OpenSCENARIO 1.2.0 interpreter package for Autoware Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter_example/CHANGELOG.rst b/openscenario/openscenario_interpreter_example/CHANGELOG.rst index 6d1a1ce0044..88191f5be71 100644 --- a/openscenario/openscenario_interpreter_example/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter_example/CHANGELOG.rst @@ -21,6 +21,13 @@ Changelog for package openscenario_interpreter_example * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.2 (2024-08-23) +------------------ +* Merge branch 'master' into fix/interpreter/user-defined-value-condition +* Merge branch 'master' into fix/interpreter/user-defined-value-condition +* Merge remote-tracking branch 'origin/master' into fix/interpreter/user-defined-value-condition +* Contributors: Tatsuya Yamasaki, yamacir-kit + 3.5.1 (2024-08-22) ------------------ * Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization diff --git a/openscenario/openscenario_interpreter_example/package.xml b/openscenario/openscenario_interpreter_example/package.xml index 2ec093360de..1acb90e9b60 100644 --- a/openscenario/openscenario_interpreter_example/package.xml +++ b/openscenario/openscenario_interpreter_example/package.xml @@ -3,7 +3,7 @@ openscenario_interpreter_example - 3.5.1 + 3.5.2 Examples for some TIER IV OpenSCENARIO Interpreter's features Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst b/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst index 1e197535985..c3c48a56c77 100644 --- a/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst @@ -21,6 +21,13 @@ Changelog for package openscenario_interpreter_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.2 (2024-08-23) +------------------ +* Merge branch 'master' into fix/interpreter/user-defined-value-condition +* Merge branch 'master' into fix/interpreter/user-defined-value-condition +* Merge remote-tracking branch 'origin/master' into fix/interpreter/user-defined-value-condition +* Contributors: Tatsuya Yamasaki, yamacir-kit + 3.5.1 (2024-08-22) ------------------ * Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization diff --git a/openscenario/openscenario_interpreter_msgs/package.xml b/openscenario/openscenario_interpreter_msgs/package.xml index de45a893ce3..9354299e92a 100644 --- a/openscenario/openscenario_interpreter_msgs/package.xml +++ b/openscenario/openscenario_interpreter_msgs/package.xml @@ -2,7 +2,7 @@ openscenario_interpreter_msgs - 3.5.1 + 3.5.2 ROS message types for package openscenario_interpreter Yamasaki Tatsuya Apache License 2.0 diff --git a/openscenario/openscenario_preprocessor/CHANGELOG.rst b/openscenario/openscenario_preprocessor/CHANGELOG.rst index d96e08f900a..50bae38aae7 100644 --- a/openscenario/openscenario_preprocessor/CHANGELOG.rst +++ b/openscenario/openscenario_preprocessor/CHANGELOG.rst @@ -21,6 +21,13 @@ Changelog for package openscenario_preprocessor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.2 (2024-08-23) +------------------ +* Merge branch 'master' into fix/interpreter/user-defined-value-condition +* Merge branch 'master' into fix/interpreter/user-defined-value-condition +* Merge remote-tracking branch 'origin/master' into fix/interpreter/user-defined-value-condition +* Contributors: Tatsuya Yamasaki, yamacir-kit + 3.5.1 (2024-08-22) ------------------ * Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization diff --git a/openscenario/openscenario_preprocessor/package.xml b/openscenario/openscenario_preprocessor/package.xml index 469df484683..08eba27169b 100644 --- a/openscenario/openscenario_preprocessor/package.xml +++ b/openscenario/openscenario_preprocessor/package.xml @@ -3,7 +3,7 @@ openscenario_preprocessor - 3.5.1 + 3.5.2 Example package for TIER IV OpenSCENARIO Interpreter Kotaro Yoshimoto Apache License 2.0 diff --git a/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst b/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst index bf55f43e420..c2543266cad 100644 --- a/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst +++ b/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst @@ -21,6 +21,13 @@ Changelog for package openscenario_preprocessor_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.2 (2024-08-23) +------------------ +* Merge branch 'master' into fix/interpreter/user-defined-value-condition +* Merge branch 'master' into fix/interpreter/user-defined-value-condition +* Merge remote-tracking branch 'origin/master' into fix/interpreter/user-defined-value-condition +* Contributors: Tatsuya Yamasaki, yamacir-kit + 3.5.1 (2024-08-22) ------------------ * Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization diff --git a/openscenario/openscenario_preprocessor_msgs/package.xml b/openscenario/openscenario_preprocessor_msgs/package.xml index f877b8b8650..8506186a487 100644 --- a/openscenario/openscenario_preprocessor_msgs/package.xml +++ b/openscenario/openscenario_preprocessor_msgs/package.xml @@ -2,7 +2,7 @@ openscenario_preprocessor_msgs - 3.5.1 + 3.5.2 ROS message types for package openscenario_preprocessor Kotaro Yoshimoto Apache License 2.0 diff --git a/openscenario/openscenario_utility/CHANGELOG.rst b/openscenario/openscenario_utility/CHANGELOG.rst index a931872c047..f4ba46753eb 100644 --- a/openscenario/openscenario_utility/CHANGELOG.rst +++ b/openscenario/openscenario_utility/CHANGELOG.rst @@ -24,6 +24,13 @@ Changelog for package openscenario_utility * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.2 (2024-08-23) +------------------ +* Merge branch 'master' into fix/interpreter/user-defined-value-condition +* Merge branch 'master' into fix/interpreter/user-defined-value-condition +* Merge remote-tracking branch 'origin/master' into fix/interpreter/user-defined-value-condition +* Contributors: Tatsuya Yamasaki, yamacir-kit + 3.5.1 (2024-08-22) ------------------ * Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization diff --git a/openscenario/openscenario_utility/package.xml b/openscenario/openscenario_utility/package.xml index 071914f2725..cd83ace688e 100644 --- a/openscenario/openscenario_utility/package.xml +++ b/openscenario/openscenario_utility/package.xml @@ -2,7 +2,7 @@ openscenario_utility - 3.5.1 + 3.5.2 Utility tools for ASAM OpenSCENARIO 1.2.0 Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_validator/CHANGELOG.rst b/openscenario/openscenario_validator/CHANGELOG.rst index 78c63ece427..7d354995ab7 100644 --- a/openscenario/openscenario_validator/CHANGELOG.rst +++ b/openscenario/openscenario_validator/CHANGELOG.rst @@ -10,6 +10,13 @@ Changelog for package openscenario_validator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.2 (2024-08-23) +------------------ +* Merge branch 'master' into fix/interpreter/user-defined-value-condition +* Merge branch 'master' into fix/interpreter/user-defined-value-condition +* Merge remote-tracking branch 'origin/master' into fix/interpreter/user-defined-value-condition +* Contributors: Tatsuya Yamasaki, yamacir-kit + 3.5.1 (2024-08-22) ------------------ * Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization diff --git a/openscenario/openscenario_validator/package.xml b/openscenario/openscenario_validator/package.xml index 612bc188111..90f04e5d258 100644 --- a/openscenario/openscenario_validator/package.xml +++ b/openscenario/openscenario_validator/package.xml @@ -2,7 +2,7 @@ openscenario_validator - 3.5.1 + 3.5.2 Validator for OpenSCENARIO 1.3 Kotaro Yoshimoto Apache License 2.0 diff --git a/rviz_plugins/openscenario_visualization/CHANGELOG.rst b/rviz_plugins/openscenario_visualization/CHANGELOG.rst index 3f9f2f8ce24..d60a2466e3e 100644 --- a/rviz_plugins/openscenario_visualization/CHANGELOG.rst +++ b/rviz_plugins/openscenario_visualization/CHANGELOG.rst @@ -21,6 +21,13 @@ Changelog for package openscenario_visualization * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.2 (2024-08-23) +------------------ +* Merge branch 'master' into fix/interpreter/user-defined-value-condition +* Merge branch 'master' into fix/interpreter/user-defined-value-condition +* Merge remote-tracking branch 'origin/master' into fix/interpreter/user-defined-value-condition +* Contributors: Tatsuya Yamasaki, yamacir-kit + 3.5.1 (2024-08-22) ------------------ * Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization diff --git a/rviz_plugins/openscenario_visualization/package.xml b/rviz_plugins/openscenario_visualization/package.xml index 83c4ac7a053..ba83dacc798 100644 --- a/rviz_plugins/openscenario_visualization/package.xml +++ b/rviz_plugins/openscenario_visualization/package.xml @@ -2,7 +2,7 @@ openscenario_visualization - 3.5.1 + 3.5.2 Visualization tools for simulation results Masaya Kataoka Kyoichi Sugahara diff --git a/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst b/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst index afc1bad3634..f8c796d649f 100644 --- a/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst +++ b/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst @@ -21,6 +21,13 @@ Changelog for package real_time_factor_control_rviz_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.2 (2024-08-23) +------------------ +* Merge branch 'master' into fix/interpreter/user-defined-value-condition +* Merge branch 'master' into fix/interpreter/user-defined-value-condition +* Merge remote-tracking branch 'origin/master' into fix/interpreter/user-defined-value-condition +* Contributors: Tatsuya Yamasaki, yamacir-kit + 3.5.1 (2024-08-22) ------------------ * Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization diff --git a/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml b/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml index c759188b370..0b6d98faceb 100644 --- a/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml +++ b/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml @@ -2,7 +2,7 @@ real_time_factor_control_rviz_plugin - 3.5.1 + 3.5.2 Slider controlling real time factor value. Paweł Lech Apache License 2.0 diff --git a/scenario_simulator_v2/CHANGELOG.rst b/scenario_simulator_v2/CHANGELOG.rst index a2c49f91b0b..9fc146c46a7 100644 --- a/scenario_simulator_v2/CHANGELOG.rst +++ b/scenario_simulator_v2/CHANGELOG.rst @@ -21,6 +21,13 @@ Changelog for package scenario_simulator_v2 * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.2 (2024-08-23) +------------------ +* Merge branch 'master' into fix/interpreter/user-defined-value-condition +* Merge branch 'master' into fix/interpreter/user-defined-value-condition +* Merge remote-tracking branch 'origin/master' into fix/interpreter/user-defined-value-condition +* Contributors: Tatsuya Yamasaki, yamacir-kit + 3.5.1 (2024-08-22) ------------------ * Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization diff --git a/scenario_simulator_v2/package.xml b/scenario_simulator_v2/package.xml index 3ea8822c0f9..eb0a5155109 100644 --- a/scenario_simulator_v2/package.xml +++ b/scenario_simulator_v2/package.xml @@ -2,7 +2,7 @@ scenario_simulator_v2 - 3.5.1 + 3.5.2 scenario testing framework for Autoware Masaya Kataoka Apache License 2.0 diff --git a/simulation/behavior_tree_plugin/CHANGELOG.rst b/simulation/behavior_tree_plugin/CHANGELOG.rst index 2df22173009..012e56d0e24 100644 --- a/simulation/behavior_tree_plugin/CHANGELOG.rst +++ b/simulation/behavior_tree_plugin/CHANGELOG.rst @@ -21,6 +21,13 @@ Changelog for package behavior_tree_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.2 (2024-08-23) +------------------ +* Merge branch 'master' into fix/interpreter/user-defined-value-condition +* Merge branch 'master' into fix/interpreter/user-defined-value-condition +* Merge remote-tracking branch 'origin/master' into fix/interpreter/user-defined-value-condition +* Contributors: Tatsuya Yamasaki, yamacir-kit + 3.5.1 (2024-08-22) ------------------ * Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization diff --git a/simulation/behavior_tree_plugin/package.xml b/simulation/behavior_tree_plugin/package.xml index cbbc43380d6..1841f73241a 100644 --- a/simulation/behavior_tree_plugin/package.xml +++ b/simulation/behavior_tree_plugin/package.xml @@ -2,7 +2,7 @@ behavior_tree_plugin - 3.5.1 + 3.5.2 Behavior tree plugin for traffic_simulator masaya Apache 2.0 diff --git a/simulation/do_nothing_plugin/CHANGELOG.rst b/simulation/do_nothing_plugin/CHANGELOG.rst index 803937311a8..c9692148509 100644 --- a/simulation/do_nothing_plugin/CHANGELOG.rst +++ b/simulation/do_nothing_plugin/CHANGELOG.rst @@ -21,6 +21,13 @@ Changelog for package do_nothing_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.2 (2024-08-23) +------------------ +* Merge branch 'master' into fix/interpreter/user-defined-value-condition +* Merge branch 'master' into fix/interpreter/user-defined-value-condition +* Merge remote-tracking branch 'origin/master' into fix/interpreter/user-defined-value-condition +* Contributors: Tatsuya Yamasaki, yamacir-kit + 3.5.1 (2024-08-22) ------------------ * Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization diff --git a/simulation/do_nothing_plugin/package.xml b/simulation/do_nothing_plugin/package.xml index e007b91b5d6..c765f33b88f 100644 --- a/simulation/do_nothing_plugin/package.xml +++ b/simulation/do_nothing_plugin/package.xml @@ -2,7 +2,7 @@ do_nothing_plugin - 3.5.1 + 3.5.2 Behavior plugin for do nothing Masaya Kataoka Apache 2.0 diff --git a/simulation/simple_sensor_simulator/CHANGELOG.rst b/simulation/simple_sensor_simulator/CHANGELOG.rst index 7a73f0c06a2..23f476b0df6 100644 --- a/simulation/simple_sensor_simulator/CHANGELOG.rst +++ b/simulation/simple_sensor_simulator/CHANGELOG.rst @@ -21,6 +21,13 @@ Changelog for package simple_sensor_simulator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.2 (2024-08-23) +------------------ +* Merge branch 'master' into fix/interpreter/user-defined-value-condition +* Merge branch 'master' into fix/interpreter/user-defined-value-condition +* Merge remote-tracking branch 'origin/master' into fix/interpreter/user-defined-value-condition +* Contributors: Tatsuya Yamasaki, yamacir-kit + 3.5.1 (2024-08-22) ------------------ * Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization diff --git a/simulation/simple_sensor_simulator/package.xml b/simulation/simple_sensor_simulator/package.xml index f476f419da9..d51d3560824 100644 --- a/simulation/simple_sensor_simulator/package.xml +++ b/simulation/simple_sensor_simulator/package.xml @@ -1,7 +1,7 @@ simple_sensor_simulator - 3.5.1 + 3.5.2 simple_sensor_simulator package masaya kataoka diff --git a/simulation/simulation_interface/CHANGELOG.rst b/simulation/simulation_interface/CHANGELOG.rst index adbcdbfc3b6..39714c8a2c9 100644 --- a/simulation/simulation_interface/CHANGELOG.rst +++ b/simulation/simulation_interface/CHANGELOG.rst @@ -21,6 +21,13 @@ Changelog for package simulation_interface * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.2 (2024-08-23) +------------------ +* Merge branch 'master' into fix/interpreter/user-defined-value-condition +* Merge branch 'master' into fix/interpreter/user-defined-value-condition +* Merge remote-tracking branch 'origin/master' into fix/interpreter/user-defined-value-condition +* Contributors: Tatsuya Yamasaki, yamacir-kit + 3.5.1 (2024-08-22) ------------------ * Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization diff --git a/simulation/simulation_interface/package.xml b/simulation/simulation_interface/package.xml index 1f7e923e7a2..766331641db 100644 --- a/simulation/simulation_interface/package.xml +++ b/simulation/simulation_interface/package.xml @@ -2,7 +2,7 @@ simulation_interface - 3.5.1 + 3.5.2 packages to define interface between simulator and scenario interpreter Masaya Kataoka Apache License 2.0 diff --git a/simulation/traffic_simulator/CHANGELOG.rst b/simulation/traffic_simulator/CHANGELOG.rst index b929a03977c..5482cfc1f80 100644 --- a/simulation/traffic_simulator/CHANGELOG.rst +++ b/simulation/traffic_simulator/CHANGELOG.rst @@ -21,6 +21,13 @@ Changelog for package traffic_simulator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.2 (2024-08-23) +------------------ +* Merge branch 'master' into fix/interpreter/user-defined-value-condition +* Merge branch 'master' into fix/interpreter/user-defined-value-condition +* Merge remote-tracking branch 'origin/master' into fix/interpreter/user-defined-value-condition +* Contributors: Tatsuya Yamasaki, yamacir-kit + 3.5.1 (2024-08-22) ------------------ * Merge pull request `#1335 `_ from tier4/feat/RJD-1283-add-traffic-controller-visualization diff --git a/simulation/traffic_simulator/package.xml b/simulation/traffic_simulator/package.xml index c5390564628..54f8e104ad5 100644 --- a/simulation/traffic_simulator/package.xml +++ b/simulation/traffic_simulator/package.xml @@ -1,7 +1,7 @@ traffic_simulator - 3.5.1 + 3.5.2 control traffic flow masaya kataoka diff --git a/simulation/traffic_simulator_msgs/CHANGELOG.rst b/simulation/traffic_simulator_msgs/CHANGELOG.rst index fdb6b702e45..d82f98feb99 100644 --- a/simulation/traffic_simulator_msgs/CHANGELOG.rst +++ b/simulation/traffic_simulator_msgs/CHANGELOG.rst @@ -21,6 +21,13 @@ Changelog for package openscenario_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.2 (2024-08-23) +------------------ +* Merge branch 'master' into fix/interpreter/user-defined-value-condition +* Merge branch 'master' into fix/interpreter/user-defined-value-condition +* Merge remote-tracking branch 'origin/master' into fix/interpreter/user-defined-value-condition +* Contributors: Tatsuya Yamasaki, yamacir-kit + 3.5.1 (2024-08-22) ------------------ * Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization diff --git a/simulation/traffic_simulator_msgs/package.xml b/simulation/traffic_simulator_msgs/package.xml index 0710d446627..3a3437091be 100644 --- a/simulation/traffic_simulator_msgs/package.xml +++ b/simulation/traffic_simulator_msgs/package.xml @@ -2,7 +2,7 @@ traffic_simulator_msgs - 3.5.1 + 3.5.2 ROS messages for openscenario Masaya Kataoka Apache License 2.0 diff --git a/test_runner/random_test_runner/CHANGELOG.rst b/test_runner/random_test_runner/CHANGELOG.rst index f04eede8929..d2f9c7f28d4 100644 --- a/test_runner/random_test_runner/CHANGELOG.rst +++ b/test_runner/random_test_runner/CHANGELOG.rst @@ -21,6 +21,13 @@ Changelog for package random_test_runner * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.2 (2024-08-23) +------------------ +* Merge branch 'master' into fix/interpreter/user-defined-value-condition +* Merge branch 'master' into fix/interpreter/user-defined-value-condition +* Merge remote-tracking branch 'origin/master' into fix/interpreter/user-defined-value-condition +* Contributors: Tatsuya Yamasaki, yamacir-kit + 3.5.1 (2024-08-22) ------------------ * Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization diff --git a/test_runner/random_test_runner/package.xml b/test_runner/random_test_runner/package.xml index 2e885e4e655..d486c8b5fc8 100644 --- a/test_runner/random_test_runner/package.xml +++ b/test_runner/random_test_runner/package.xml @@ -2,7 +2,7 @@ random_test_runner - 3.5.1 + 3.5.2 Random behavior test runner piotr-zyskowski-rai Apache License 2.0 diff --git a/test_runner/scenario_test_runner/CHANGELOG.rst b/test_runner/scenario_test_runner/CHANGELOG.rst index 2e4ef49e606..7598508b4af 100644 --- a/test_runner/scenario_test_runner/CHANGELOG.rst +++ b/test_runner/scenario_test_runner/CHANGELOG.rst @@ -35,6 +35,17 @@ Changelog for package scenario_test_runner * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.2 (2024-08-23) +------------------ +* Merge pull request `#1338 `_ from tier4/fix/interpreter/user-defined-value-condition + Fix/interpreter/user defined value condition +* Merge branch 'master' into fix/interpreter/user-defined-value-condition +* Merge branch 'master' into fix/interpreter/user-defined-value-condition +* Merge remote-tracking branch 'origin/master' into fix/interpreter/user-defined-value-condition +* Update test scenario `ByValueCondition.UserDefinedValueCondition.yaml` +* Update test scenario `ByValueCondition.UserDefinedValueCondition.yaml` +* Contributors: Tatsuya Yamasaki, yamacir-kit + 3.5.1 (2024-08-22) ------------------ * Merge branch 'master' into feat/RJD-1283-add-traffic-controller-visualization diff --git a/test_runner/scenario_test_runner/package.xml b/test_runner/scenario_test_runner/package.xml index 33269e1139d..ee3961e5180 100644 --- a/test_runner/scenario_test_runner/package.xml +++ b/test_runner/scenario_test_runner/package.xml @@ -2,7 +2,7 @@ scenario_test_runner - 3.5.1 + 3.5.2 scenario test runner package Tatsuya Yamasaki Apache License 2.0 From 04a7af49ec2036fc9397718d92cb7270b4316906 Mon Sep 17 00:00:00 2001 From: robomic Date: Fri, 23 Aug 2024 09:15:39 +0200 Subject: [PATCH 165/304] expand on the note, add else to if-stmts --- .../src/intersection/intersection.cpp | 45 ++++++++++--------- .../geometry/src/polygon/line_segment.cpp | 44 ++++++++++-------- 2 files changed, 48 insertions(+), 41 deletions(-) diff --git a/common/math/geometry/src/intersection/intersection.cpp b/common/math/geometry/src/intersection/intersection.cpp index 1b1a1f3e586..013efbb4cbe 100644 --- a/common/math/geometry/src/intersection/intersection.cpp +++ b/common/math/geometry/src/intersection/intersection.cpp @@ -59,31 +59,32 @@ std::optional getIntersection2D( { if (not line0.isIntersect2D(line1)) { return std::nullopt; - } - // 'line0' represented as a0x + b0y = c0 - const double a0 = line0.get2DVector().y; - const double b0 = -line0.get2DVector().x; - const double c0 = a0 * line0.start_point.x + b0 * line0.start_point.y; + } else { + // 'line0' represented as a0x + b0y = c0 + const double a0 = line0.get2DVector().y; + const double b0 = -line0.get2DVector().x; + const double c0 = a0 * line0.start_point.x + b0 * line0.start_point.y; - // 'line1' represented as a1x + b1y = c1 - const double a1 = line1.get2DVector().y; - const double b1 = -line1.get2DVector().x; - const double c1 = a1 * line1.start_point.x + b1 * line1.start_point.y; + // 'line1' represented as a1x + b1y = c1 + const double a1 = line1.get2DVector().y; + const double b1 = -line1.get2DVector().x; + const double c1 = a1 * line1.start_point.x + b1 * line1.start_point.y; - const double determinant = a0 * b1 - a1 * b0; + const double determinant = a0 * b1 - a1 * b0; - if (std::abs(determinant) <= std::numeric_limits::epsilon()) { - // The lines do intersect, but they are collinear and overlap. - THROW_SIMULATION_ERROR( - "Line segments are collinear. So determinant is zero.", - "If this message was displayed, something completely unexpected happens.", - "This message is not originally intended to be displayed, if you see it, please " - "contact the developer of traffic_simulator."); - } else { - return geometry_msgs::build() - .x((b1 * c0 - b0 * c1) / determinant) - .y((a0 * c1 - a1 * c0) / determinant) - .z(0.0); + if (std::abs(determinant) <= std::numeric_limits::epsilon()) { + // The lines do intersect, but they are collinear and overlap. + THROW_SIMULATION_ERROR( + "Line segments are collinear. So determinant is zero.", + "If this message was displayed, something completely unexpected happens.", + "This message is not originally intended to be displayed, if you see it, please " + "contact the developer of traffic_simulator."); + } else { + return geometry_msgs::build() + .x((b1 * c0 - b0 * c1) / determinant) + .y((a0 * c1 - a1 * c0) / determinant) + .z(0.0); + } } } diff --git a/common/math/geometry/src/polygon/line_segment.cpp b/common/math/geometry/src/polygon/line_segment.cpp index 8661b39015b..ce7ab10b27c 100644 --- a/common/math/geometry/src/polygon/line_segment.cpp +++ b/common/math/geometry/src/polygon/line_segment.cpp @@ -81,21 +81,22 @@ auto LineSegment::getPoint(const double s, const bool denormalize_s) const .x(start_point.x + getVector().x * s_normalized) .y(start_point.y + getVector().y * s_normalized) .z(start_point.z + getVector().z * s_normalized); - } - if (denormalize_s) { - THROW_SIMULATION_ERROR( - "Invalid S value is specified, while getting point on a line segment.", - "The range of s_normalized value should be in range [0,", getLength(), "].", - "But, your values are = ", s, " and length = ", getLength(), - " This message is not originally intended to be displayed, if you see it, please " - "contact the developer of traffic_simulator."); } else { - THROW_SIMULATION_ERROR( - "Invalid S value is specified, while getting point on a line segment.", - "The range of s_normalized value should be in range [0,1].", "But, your values are = ", s, - " and length = ", getLength(), - " This message is not originally intended to be displayed, if you see it, please " - "contact the developer of traffic_simulator."); + if (denormalize_s) { + THROW_SIMULATION_ERROR( + "Invalid S value is specified, while getting point on a line segment.", + "The range of s_normalized value should be in range [0,", getLength(), "].", + "But, your values are = ", s, " and length = ", getLength(), + " This message is not originally intended to be displayed, if you see it, please " + "contact the developer of traffic_simulator."); + } else { + THROW_SIMULATION_ERROR( + "Invalid S value is specified, while getting point on a line segment.", + "The range of s_normalized value should be in range [0,1].", "But, your values are = ", s, + " and length = ", getLength(), + " This message is not originally intended to be displayed, if you see it, please " + "contact the developer of traffic_simulator."); + } } } @@ -171,7 +172,11 @@ auto LineSegment::isIntersect2D(const LineSegment & line) const -> bool auto LineSegment::get2DIntersectionSValue( const geometry_msgs::msg::Point & point, const bool denormalize_s) const -> std::optional { - /// @note This function checks for an SValue along the line. The term "2D" in the function name specifically refers to the intersection point, not SValue. + /// @note This function checks for an SValue along the line. + /// The term "2D" in the function name specifically refers to the intersection point, not the SValue. + /// Therefore, the intersection is determined by disregarding the z-coordinate, hence the term "2D." + /// After finding the intersection, we calculate its position using a proportion. + /// Finally, we multiply this proportion by the actual 3D length to obtain the total SValue. if (isIntersect2D(point)) { const double proportion_2d = std::hypot(point.x - start_point.x, point.y - start_point.y) / get2DLength(); @@ -298,11 +303,12 @@ auto LineSegment::denormalize(const double s) const -> double { if (0.0 <= s && s <= 1.0) { return s * getLength(); + } else { + THROW_SIMULATION_ERROR( + "Invalid normalized s value, s = ", s, ", S value should be in range [0,1].", + "This message is not originally intended to be displayed, if you see it, please " + "contact the developer of traffic_simulator."); } - THROW_SIMULATION_ERROR( - "Invalid normalized s value, s = ", s, ", S value should be in range [0,1].", - "This message is not originally intended to be displayed, if you see it, please " - "contact the developer of traffic_simulator."); } LineSegment & LineSegment::operator=(const LineSegment &) { return *this; } From cdc07dd0f0f7f552aaee2c71d6e9a0c1d822b9f0 Mon Sep 17 00:00:00 2001 From: robomic Date: Fri, 23 Aug 2024 09:21:49 +0200 Subject: [PATCH 166/304] remove{} --- .../geometry/src/polygon/line_segment.cpp | 28 +++++++++---------- 1 file changed, 13 insertions(+), 15 deletions(-) diff --git a/common/math/geometry/src/polygon/line_segment.cpp b/common/math/geometry/src/polygon/line_segment.cpp index ce7ab10b27c..47ade55b944 100644 --- a/common/math/geometry/src/polygon/line_segment.cpp +++ b/common/math/geometry/src/polygon/line_segment.cpp @@ -81,22 +81,20 @@ auto LineSegment::getPoint(const double s, const bool denormalize_s) const .x(start_point.x + getVector().x * s_normalized) .y(start_point.y + getVector().y * s_normalized) .z(start_point.z + getVector().z * s_normalized); + } else if (denormalize_s) { + THROW_SIMULATION_ERROR( + "Invalid S value is specified, while getting point on a line segment.", + "The range of s_normalized value should be in range [0,", getLength(), "].", + "But, your values are = ", s, " and length = ", getLength(), + " This message is not originally intended to be displayed, if you see it, please " + "contact the developer of traffic_simulator."); } else { - if (denormalize_s) { - THROW_SIMULATION_ERROR( - "Invalid S value is specified, while getting point on a line segment.", - "The range of s_normalized value should be in range [0,", getLength(), "].", - "But, your values are = ", s, " and length = ", getLength(), - " This message is not originally intended to be displayed, if you see it, please " - "contact the developer of traffic_simulator."); - } else { - THROW_SIMULATION_ERROR( - "Invalid S value is specified, while getting point on a line segment.", - "The range of s_normalized value should be in range [0,1].", "But, your values are = ", s, - " and length = ", getLength(), - " This message is not originally intended to be displayed, if you see it, please " - "contact the developer of traffic_simulator."); - } + THROW_SIMULATION_ERROR( + "Invalid S value is specified, while getting point on a line segment.", + "The range of s_normalized value should be in range [0,1].", "But, your values are = ", s, + " and length = ", getLength(), + " This message is not originally intended to be displayed, if you see it, please " + "contact the developer of traffic_simulator."); } } From 0bf70d730569cc139c1410f84f9edfb03d6007b7 Mon Sep 17 00:00:00 2001 From: Masaya Kataoka Date: Fri, 23 Aug 2024 18:09:03 +0900 Subject: [PATCH 167/304] Update .github/workflows/Docker.yaml Co-authored-by: Kotaro Yoshimoto --- .github/workflows/Docker.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/Docker.yaml b/.github/workflows/Docker.yaml index 8f29d67e16d..1a735ccaf7d 100644 --- a/.github/workflows/Docker.yaml +++ b/.github/workflows/Docker.yaml @@ -41,7 +41,7 @@ jobs: - name: Install QEMU uses: docker/setup-qemu-action@v3 - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 - name: Login to GitHub Container Registry uses: docker/login-action@v2 From 2c9a7aef074d3781daf7c7f0cc76234fb6df25f9 Mon Sep 17 00:00:00 2001 From: Masaya Kataoka Date: Fri, 23 Aug 2024 18:27:19 +0900 Subject: [PATCH 168/304] Update .github/workflows/Docker.yaml Co-authored-by: Kotaro Yoshimoto --- .github/workflows/Docker.yaml | 1 + 1 file changed, 1 insertion(+) diff --git a/.github/workflows/Docker.yaml b/.github/workflows/Docker.yaml index 1a735ccaf7d..4c2cad55c6e 100644 --- a/.github/workflows/Docker.yaml +++ b/.github/workflows/Docker.yaml @@ -6,6 +6,7 @@ on: - "!docs/**" - "!README.md" - "!CONTRIBUTING.md" + - "!.github/**" - ".github/workflows/Docker.yaml" - "!mkdocs.yml" - "!pyproject.toml" From 571a6cc48d951e62d0b2546e02e2147839e161fb Mon Sep 17 00:00:00 2001 From: Masaya Kataoka Date: Fri, 23 Aug 2024 18:53:10 +0900 Subject: [PATCH 169/304] use output Signed-off-by: Masaya Kataoka --- .github/workflows/Release.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/Release.yaml b/.github/workflows/Release.yaml index c3812e1f187..89173eaf5ad 100644 --- a/.github/workflows/Release.yaml +++ b/.github/workflows/Release.yaml @@ -152,4 +152,4 @@ jobs: -H "Authorization: token ${{ secrets.BLOOM_GITHUB_TOKEN }}" \ -H "X-GitHub-Api-Version: 2022-11-28" \ https://api.github.com/repos/merge-queue-testing/scenario_simulator_v2/actions/workflows/Docker.yaml/dispatches \ - -d '{"ref":"master","inputs":{"version":"3.5.2"}}' + -d '{"ref":"master","inputs":{"version":"${{ steps.get_release_description.outputs.stdout }}"}}' From c0681caa4c1db5a7f6577e6c53b0574ca541cef4 Mon Sep 17 00:00:00 2001 From: Masaya Kataoka Date: Mon, 26 Aug 2024 10:39:36 +0900 Subject: [PATCH 170/304] update json Signed-off-by: Masaya Kataoka --- .github/workflows/Release.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/Release.yaml b/.github/workflows/Release.yaml index 89173eaf5ad..e10ed1d84ac 100644 --- a/.github/workflows/Release.yaml +++ b/.github/workflows/Release.yaml @@ -152,4 +152,4 @@ jobs: -H "Authorization: token ${{ secrets.BLOOM_GITHUB_TOKEN }}" \ -H "X-GitHub-Api-Version: 2022-11-28" \ https://api.github.com/repos/merge-queue-testing/scenario_simulator_v2/actions/workflows/Docker.yaml/dispatches \ - -d '{"ref":"master","inputs":{"version":"${{ steps.get_release_description.outputs.stdout }}"}}' + -d '{\"ref\":\"master\",\"inputs\":{\"version\":\"${{ steps.get_release_description.outputs.stdout }}\"}}' From b431e90f96240e25148df22e2103dde5991f09c9 Mon Sep 17 00:00:00 2001 From: Masaya Kataoka Date: Mon, 26 Aug 2024 13:44:47 +0900 Subject: [PATCH 171/304] change argument Signed-off-by: Masaya Kataoka --- .github/workflows/Release.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/Release.yaml b/.github/workflows/Release.yaml index e10ed1d84ac..d6686624fd7 100644 --- a/.github/workflows/Release.yaml +++ b/.github/workflows/Release.yaml @@ -152,4 +152,4 @@ jobs: -H "Authorization: token ${{ secrets.BLOOM_GITHUB_TOKEN }}" \ -H "X-GitHub-Api-Version: 2022-11-28" \ https://api.github.com/repos/merge-queue-testing/scenario_simulator_v2/actions/workflows/Docker.yaml/dispatches \ - -d '{\"ref\":\"master\",\"inputs\":{\"version\":\"${{ steps.get_release_description.outputs.stdout }}\"}}' + -d '{\"ref\":\"master\",\"inputs\":{\"version\":\"${{ steps.new_version.outputs.new_version }}\"}}' From 7450367766464df873c3957bb228290539c119b7 Mon Sep 17 00:00:00 2001 From: Masaya Kataoka Date: Mon, 26 Aug 2024 14:00:17 +0900 Subject: [PATCH 172/304] remove escape Signed-off-by: Masaya Kataoka --- .github/workflows/Release.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/Release.yaml b/.github/workflows/Release.yaml index d6686624fd7..05d646d8cfa 100644 --- a/.github/workflows/Release.yaml +++ b/.github/workflows/Release.yaml @@ -152,4 +152,4 @@ jobs: -H "Authorization: token ${{ secrets.BLOOM_GITHUB_TOKEN }}" \ -H "X-GitHub-Api-Version: 2022-11-28" \ https://api.github.com/repos/merge-queue-testing/scenario_simulator_v2/actions/workflows/Docker.yaml/dispatches \ - -d '{\"ref\":\"master\",\"inputs\":{\"version\":\"${{ steps.new_version.outputs.new_version }}\"}}' + -d '{"ref":"master","inputs":{"version":"${{ steps.new_version.outputs.new_version }}"}}' From 24ec02471322879021781fcf3a40433eb9f32bb8 Mon Sep 17 00:00:00 2001 From: Release Bot Date: Mon, 26 Aug 2024 06:54:35 +0000 Subject: [PATCH 173/304] Bump version of scenario_simulator_v2 from version 3.5.2 to version 3.5.3 --- common/math/arithmetic/CHANGELOG.rst | 8 ++++++++ common/math/arithmetic/package.xml | 2 +- common/math/geometry/CHANGELOG.rst | 8 ++++++++ common/math/geometry/package.xml | 2 +- .../scenario_simulator_exception/CHANGELOG.rst | 8 ++++++++ common/scenario_simulator_exception/package.xml | 2 +- common/simple_junit/CHANGELOG.rst | 8 ++++++++ common/simple_junit/package.xml | 2 +- common/status_monitor/CHANGELOG.rst | 8 ++++++++ common/status_monitor/package.xml | 2 +- external/concealer/CHANGELOG.rst | 8 ++++++++ external/concealer/package.xml | 2 +- external/embree_vendor/CHANGELOG.rst | 8 ++++++++ external/embree_vendor/package.xml | 2 +- map/kashiwanoha_map/CHANGELOG.rst | 8 ++++++++ map/kashiwanoha_map/package.xml | 2 +- map/simple_cross_map/CHANGELOG.rst | 8 ++++++++ map/simple_cross_map/package.xml | 2 +- mock/cpp_mock_scenarios/CHANGELOG.rst | 8 ++++++++ mock/cpp_mock_scenarios/package.xml | 2 +- .../CHANGELOG.rst | 8 ++++++++ .../package.xml | 2 +- .../openscenario_interpreter/CHANGELOG.rst | 8 ++++++++ .../openscenario_interpreter/package.xml | 2 +- .../CHANGELOG.rst | 8 ++++++++ .../package.xml | 2 +- .../openscenario_interpreter_msgs/CHANGELOG.rst | 8 ++++++++ .../openscenario_interpreter_msgs/package.xml | 2 +- .../openscenario_preprocessor/CHANGELOG.rst | 8 ++++++++ .../openscenario_preprocessor/package.xml | 2 +- .../CHANGELOG.rst | 8 ++++++++ .../openscenario_preprocessor_msgs/package.xml | 2 +- openscenario/openscenario_utility/CHANGELOG.rst | 8 ++++++++ openscenario/openscenario_utility/package.xml | 2 +- .../openscenario_validator/CHANGELOG.rst | 8 ++++++++ openscenario/openscenario_validator/package.xml | 2 +- .../openscenario_visualization/CHANGELOG.rst | 8 ++++++++ .../openscenario_visualization/package.xml | 2 +- .../CHANGELOG.rst | 8 ++++++++ .../package.xml | 2 +- scenario_simulator_v2/CHANGELOG.rst | 8 ++++++++ scenario_simulator_v2/package.xml | 2 +- simulation/behavior_tree_plugin/CHANGELOG.rst | 8 ++++++++ simulation/behavior_tree_plugin/package.xml | 2 +- simulation/do_nothing_plugin/CHANGELOG.rst | 8 ++++++++ simulation/do_nothing_plugin/package.xml | 2 +- .../simple_sensor_simulator/CHANGELOG.rst | 8 ++++++++ simulation/simple_sensor_simulator/package.xml | 2 +- simulation/simulation_interface/CHANGELOG.rst | 8 ++++++++ simulation/simulation_interface/package.xml | 2 +- simulation/traffic_simulator/CHANGELOG.rst | 17 +++++++++++++++++ simulation/traffic_simulator/package.xml | 2 +- simulation/traffic_simulator_msgs/CHANGELOG.rst | 8 ++++++++ simulation/traffic_simulator_msgs/package.xml | 2 +- test_runner/random_test_runner/CHANGELOG.rst | 8 ++++++++ test_runner/random_test_runner/package.xml | 2 +- test_runner/scenario_test_runner/CHANGELOG.rst | 8 ++++++++ test_runner/scenario_test_runner/package.xml | 2 +- 58 files changed, 270 insertions(+), 29 deletions(-) diff --git a/common/math/arithmetic/CHANGELOG.rst b/common/math/arithmetic/CHANGELOG.rst index e6143092224..d5cdf085045 100644 --- a/common/math/arithmetic/CHANGELOG.rst +++ b/common/math/arithmetic/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package arithmetic * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.3 (2024-08-26) +------------------ +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Contributors: Michał Ciasnocha + 3.5.2 (2024-08-23) ------------------ * Merge branch 'master' into fix/interpreter/user-defined-value-condition diff --git a/common/math/arithmetic/package.xml b/common/math/arithmetic/package.xml index 018ff9fb011..ad71f08769a 100644 --- a/common/math/arithmetic/package.xml +++ b/common/math/arithmetic/package.xml @@ -2,7 +2,7 @@ arithmetic - 3.5.2 + 3.5.3 arithmetic library for scenario_simulator_v2 Tatsuya Yamasaki Apache License 2.0 diff --git a/common/math/geometry/CHANGELOG.rst b/common/math/geometry/CHANGELOG.rst index ef2f91fbdb1..5885a8312dd 100644 --- a/common/math/geometry/CHANGELOG.rst +++ b/common/math/geometry/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package geometry * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.3 (2024-08-26) +------------------ +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Contributors: Michał Ciasnocha + 3.5.2 (2024-08-23) ------------------ * Merge branch 'master' into fix/interpreter/user-defined-value-condition diff --git a/common/math/geometry/package.xml b/common/math/geometry/package.xml index e6a5e7a7188..cc2e1cbdfff 100644 --- a/common/math/geometry/package.xml +++ b/common/math/geometry/package.xml @@ -2,7 +2,7 @@ geometry - 3.5.2 + 3.5.3 geometry math library for scenario_simulator_v2 application Masaya Kataoka Apache License 2.0 diff --git a/common/scenario_simulator_exception/CHANGELOG.rst b/common/scenario_simulator_exception/CHANGELOG.rst index d4d80b71f2b..1039bd379fb 100644 --- a/common/scenario_simulator_exception/CHANGELOG.rst +++ b/common/scenario_simulator_exception/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package scenario_simulator_exception * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.3 (2024-08-26) +------------------ +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Contributors: Michał Ciasnocha + 3.5.2 (2024-08-23) ------------------ * Merge branch 'master' into fix/interpreter/user-defined-value-condition diff --git a/common/scenario_simulator_exception/package.xml b/common/scenario_simulator_exception/package.xml index 4d092356a5a..67fcb60a568 100644 --- a/common/scenario_simulator_exception/package.xml +++ b/common/scenario_simulator_exception/package.xml @@ -2,7 +2,7 @@ scenario_simulator_exception - 3.5.2 + 3.5.3 Exception types for scenario simulator Tatsuya Yamasaki Apache License 2.0 diff --git a/common/simple_junit/CHANGELOG.rst b/common/simple_junit/CHANGELOG.rst index 9818ba53118..df549834566 100644 --- a/common/simple_junit/CHANGELOG.rst +++ b/common/simple_junit/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package junit_exporter * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.3 (2024-08-26) +------------------ +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Contributors: Michał Ciasnocha + 3.5.2 (2024-08-23) ------------------ * Merge branch 'master' into fix/interpreter/user-defined-value-condition diff --git a/common/simple_junit/package.xml b/common/simple_junit/package.xml index 4ab46e09f15..0247d4d5e8b 100644 --- a/common/simple_junit/package.xml +++ b/common/simple_junit/package.xml @@ -2,7 +2,7 @@ simple_junit - 3.5.2 + 3.5.3 Lightweight JUnit library for ROS 2 Masaya Kataoka Tatsuya Yamasaki diff --git a/common/status_monitor/CHANGELOG.rst b/common/status_monitor/CHANGELOG.rst index e39b9ece0eb..d7f12fc6be0 100644 --- a/common/status_monitor/CHANGELOG.rst +++ b/common/status_monitor/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package status_monitor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.3 (2024-08-26) +------------------ +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Contributors: Michał Ciasnocha + 3.5.2 (2024-08-23) ------------------ * Merge branch 'master' into fix/interpreter/user-defined-value-condition diff --git a/common/status_monitor/package.xml b/common/status_monitor/package.xml index f57550fbcc6..acc92ec16a9 100644 --- a/common/status_monitor/package.xml +++ b/common/status_monitor/package.xml @@ -2,7 +2,7 @@ status_monitor - 3.5.2 + 3.5.3 none Tatsuya Yamasaki Apache License 2.0 diff --git a/external/concealer/CHANGELOG.rst b/external/concealer/CHANGELOG.rst index 8dc1e06f8ea..44a8b9df790 100644 --- a/external/concealer/CHANGELOG.rst +++ b/external/concealer/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package concealer * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.3 (2024-08-26) +------------------ +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Contributors: Michał Ciasnocha + 3.5.2 (2024-08-23) ------------------ * Merge pull request `#1338 `_ from tier4/fix/interpreter/user-defined-value-condition diff --git a/external/concealer/package.xml b/external/concealer/package.xml index a81b6c11749..c8efe8047fe 100644 --- a/external/concealer/package.xml +++ b/external/concealer/package.xml @@ -2,7 +2,7 @@ concealer - 3.5.2 + 3.5.3 Provides a class 'Autoware' to conceal miscellaneous things to simplify Autoware management of the simulator. Tatsuya Yamasaki Apache License 2.0 diff --git a/external/embree_vendor/CHANGELOG.rst b/external/embree_vendor/CHANGELOG.rst index bbfb8cd28ea..2bf8de40977 100644 --- a/external/embree_vendor/CHANGELOG.rst +++ b/external/embree_vendor/CHANGELOG.rst @@ -24,6 +24,14 @@ Changelog for package embree_vendor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.3 (2024-08-26) +------------------ +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Contributors: Michał Ciasnocha + 3.5.2 (2024-08-23) ------------------ * Merge branch 'master' into fix/interpreter/user-defined-value-condition diff --git a/external/embree_vendor/package.xml b/external/embree_vendor/package.xml index 886e2ad4790..59ee7f07864 100644 --- a/external/embree_vendor/package.xml +++ b/external/embree_vendor/package.xml @@ -2,7 +2,7 @@ embree_vendor - 3.5.2 + 3.5.3 vendor packages for intel raytracing kernel library masaya Apache 2.0 diff --git a/map/kashiwanoha_map/CHANGELOG.rst b/map/kashiwanoha_map/CHANGELOG.rst index 44adc3b2a99..b07a9b4888a 100644 --- a/map/kashiwanoha_map/CHANGELOG.rst +++ b/map/kashiwanoha_map/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package kashiwanoha_map * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.3 (2024-08-26) +------------------ +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Contributors: Michał Ciasnocha + 3.5.2 (2024-08-23) ------------------ * Merge branch 'master' into fix/interpreter/user-defined-value-condition diff --git a/map/kashiwanoha_map/package.xml b/map/kashiwanoha_map/package.xml index 2e7eadce210..5dea47966cb 100644 --- a/map/kashiwanoha_map/package.xml +++ b/map/kashiwanoha_map/package.xml @@ -2,7 +2,7 @@ kashiwanoha_map - 3.5.2 + 3.5.3 map package for kashiwanoha Masaya Kataoka Apache License 2.0 diff --git a/map/simple_cross_map/CHANGELOG.rst b/map/simple_cross_map/CHANGELOG.rst index 79f743c227e..6815e2f60c9 100644 --- a/map/simple_cross_map/CHANGELOG.rst +++ b/map/simple_cross_map/CHANGELOG.rst @@ -9,6 +9,14 @@ Changelog for package simple_cross_map * Merge branch 'master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.3 (2024-08-26) +------------------ +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Contributors: Michał Ciasnocha + 3.5.2 (2024-08-23) ------------------ * Merge branch 'master' into fix/interpreter/user-defined-value-condition diff --git a/map/simple_cross_map/package.xml b/map/simple_cross_map/package.xml index 99e5424db70..bb0898e739f 100644 --- a/map/simple_cross_map/package.xml +++ b/map/simple_cross_map/package.xml @@ -2,7 +2,7 @@ simple_cross_map - 3.5.2 + 3.5.3 map package for simple cross Masaya Kataoka Apache License 2.0 diff --git a/mock/cpp_mock_scenarios/CHANGELOG.rst b/mock/cpp_mock_scenarios/CHANGELOG.rst index 87db40be421..ee76ec7d322 100644 --- a/mock/cpp_mock_scenarios/CHANGELOG.rst +++ b/mock/cpp_mock_scenarios/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package cpp_mock_scenarios * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.3 (2024-08-26) +------------------ +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Contributors: Michał Ciasnocha + 3.5.2 (2024-08-23) ------------------ * Merge branch 'master' into fix/interpreter/user-defined-value-condition diff --git a/mock/cpp_mock_scenarios/package.xml b/mock/cpp_mock_scenarios/package.xml index 9f219e0de12..896499f1b84 100644 --- a/mock/cpp_mock_scenarios/package.xml +++ b/mock/cpp_mock_scenarios/package.xml @@ -2,7 +2,7 @@ cpp_mock_scenarios - 3.5.2 + 3.5.3 C++ mock scenarios masaya Apache License 2.0 diff --git a/openscenario/openscenario_experimental_catalog/CHANGELOG.rst b/openscenario/openscenario_experimental_catalog/CHANGELOG.rst index 708e2e2a241..0e647aaa997 100644 --- a/openscenario/openscenario_experimental_catalog/CHANGELOG.rst +++ b/openscenario/openscenario_experimental_catalog/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package openscenario_experimental_catalog * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.3 (2024-08-26) +------------------ +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Contributors: Michał Ciasnocha + 3.5.2 (2024-08-23) ------------------ * Merge branch 'master' into fix/interpreter/user-defined-value-condition diff --git a/openscenario/openscenario_experimental_catalog/package.xml b/openscenario/openscenario_experimental_catalog/package.xml index 20ae47e3ab9..2992fd5ba15 100644 --- a/openscenario/openscenario_experimental_catalog/package.xml +++ b/openscenario/openscenario_experimental_catalog/package.xml @@ -2,7 +2,7 @@ openscenario_experimental_catalog - 3.5.2 + 3.5.3 TIER IV experimental catalogs for OpenSCENARIO Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter/CHANGELOG.rst b/openscenario/openscenario_interpreter/CHANGELOG.rst index 47d6db82b6b..1b9739cf5c5 100644 --- a/openscenario/openscenario_interpreter/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter/CHANGELOG.rst @@ -32,6 +32,14 @@ Changelog for package openscenario_interpreter * add publish_empty_context parameter * Contributors: Masaya Kataoka +3.5.3 (2024-08-26) +------------------ +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Contributors: Michał Ciasnocha + 3.5.2 (2024-08-23) ------------------ * Merge pull request `#1338 `_ from tier4/fix/interpreter/user-defined-value-condition diff --git a/openscenario/openscenario_interpreter/package.xml b/openscenario/openscenario_interpreter/package.xml index cacd0286ec4..2aff49e8960 100644 --- a/openscenario/openscenario_interpreter/package.xml +++ b/openscenario/openscenario_interpreter/package.xml @@ -2,7 +2,7 @@ openscenario_interpreter - 3.5.2 + 3.5.3 OpenSCENARIO 1.2.0 interpreter package for Autoware Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter_example/CHANGELOG.rst b/openscenario/openscenario_interpreter_example/CHANGELOG.rst index 88191f5be71..472b0c8d739 100644 --- a/openscenario/openscenario_interpreter_example/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter_example/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package openscenario_interpreter_example * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.3 (2024-08-26) +------------------ +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Contributors: Michał Ciasnocha + 3.5.2 (2024-08-23) ------------------ * Merge branch 'master' into fix/interpreter/user-defined-value-condition diff --git a/openscenario/openscenario_interpreter_example/package.xml b/openscenario/openscenario_interpreter_example/package.xml index 1acb90e9b60..398177968bd 100644 --- a/openscenario/openscenario_interpreter_example/package.xml +++ b/openscenario/openscenario_interpreter_example/package.xml @@ -3,7 +3,7 @@ openscenario_interpreter_example - 3.5.2 + 3.5.3 Examples for some TIER IV OpenSCENARIO Interpreter's features Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst b/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst index c3c48a56c77..0ce9a237677 100644 --- a/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package openscenario_interpreter_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.3 (2024-08-26) +------------------ +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Contributors: Michał Ciasnocha + 3.5.2 (2024-08-23) ------------------ * Merge branch 'master' into fix/interpreter/user-defined-value-condition diff --git a/openscenario/openscenario_interpreter_msgs/package.xml b/openscenario/openscenario_interpreter_msgs/package.xml index 9354299e92a..2fe049a5434 100644 --- a/openscenario/openscenario_interpreter_msgs/package.xml +++ b/openscenario/openscenario_interpreter_msgs/package.xml @@ -2,7 +2,7 @@ openscenario_interpreter_msgs - 3.5.2 + 3.5.3 ROS message types for package openscenario_interpreter Yamasaki Tatsuya Apache License 2.0 diff --git a/openscenario/openscenario_preprocessor/CHANGELOG.rst b/openscenario/openscenario_preprocessor/CHANGELOG.rst index 50bae38aae7..81d8e2e410f 100644 --- a/openscenario/openscenario_preprocessor/CHANGELOG.rst +++ b/openscenario/openscenario_preprocessor/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package openscenario_preprocessor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.3 (2024-08-26) +------------------ +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Contributors: Michał Ciasnocha + 3.5.2 (2024-08-23) ------------------ * Merge branch 'master' into fix/interpreter/user-defined-value-condition diff --git a/openscenario/openscenario_preprocessor/package.xml b/openscenario/openscenario_preprocessor/package.xml index 08eba27169b..1aa6e64575b 100644 --- a/openscenario/openscenario_preprocessor/package.xml +++ b/openscenario/openscenario_preprocessor/package.xml @@ -3,7 +3,7 @@ openscenario_preprocessor - 3.5.2 + 3.5.3 Example package for TIER IV OpenSCENARIO Interpreter Kotaro Yoshimoto Apache License 2.0 diff --git a/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst b/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst index c2543266cad..b3ee19603e4 100644 --- a/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst +++ b/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package openscenario_preprocessor_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.3 (2024-08-26) +------------------ +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Contributors: Michał Ciasnocha + 3.5.2 (2024-08-23) ------------------ * Merge branch 'master' into fix/interpreter/user-defined-value-condition diff --git a/openscenario/openscenario_preprocessor_msgs/package.xml b/openscenario/openscenario_preprocessor_msgs/package.xml index 8506186a487..ea03060c1cb 100644 --- a/openscenario/openscenario_preprocessor_msgs/package.xml +++ b/openscenario/openscenario_preprocessor_msgs/package.xml @@ -2,7 +2,7 @@ openscenario_preprocessor_msgs - 3.5.2 + 3.5.3 ROS message types for package openscenario_preprocessor Kotaro Yoshimoto Apache License 2.0 diff --git a/openscenario/openscenario_utility/CHANGELOG.rst b/openscenario/openscenario_utility/CHANGELOG.rst index f4ba46753eb..9cafff75657 100644 --- a/openscenario/openscenario_utility/CHANGELOG.rst +++ b/openscenario/openscenario_utility/CHANGELOG.rst @@ -24,6 +24,14 @@ Changelog for package openscenario_utility * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.3 (2024-08-26) +------------------ +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Contributors: Michał Ciasnocha + 3.5.2 (2024-08-23) ------------------ * Merge branch 'master' into fix/interpreter/user-defined-value-condition diff --git a/openscenario/openscenario_utility/package.xml b/openscenario/openscenario_utility/package.xml index cd83ace688e..b052653092e 100644 --- a/openscenario/openscenario_utility/package.xml +++ b/openscenario/openscenario_utility/package.xml @@ -2,7 +2,7 @@ openscenario_utility - 3.5.2 + 3.5.3 Utility tools for ASAM OpenSCENARIO 1.2.0 Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_validator/CHANGELOG.rst b/openscenario/openscenario_validator/CHANGELOG.rst index 7d354995ab7..5862a955aad 100644 --- a/openscenario/openscenario_validator/CHANGELOG.rst +++ b/openscenario/openscenario_validator/CHANGELOG.rst @@ -10,6 +10,14 @@ Changelog for package openscenario_validator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.3 (2024-08-26) +------------------ +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Contributors: Michał Ciasnocha + 3.5.2 (2024-08-23) ------------------ * Merge branch 'master' into fix/interpreter/user-defined-value-condition diff --git a/openscenario/openscenario_validator/package.xml b/openscenario/openscenario_validator/package.xml index 90f04e5d258..d97006c053c 100644 --- a/openscenario/openscenario_validator/package.xml +++ b/openscenario/openscenario_validator/package.xml @@ -2,7 +2,7 @@ openscenario_validator - 3.5.2 + 3.5.3 Validator for OpenSCENARIO 1.3 Kotaro Yoshimoto Apache License 2.0 diff --git a/rviz_plugins/openscenario_visualization/CHANGELOG.rst b/rviz_plugins/openscenario_visualization/CHANGELOG.rst index d60a2466e3e..69111cfa28a 100644 --- a/rviz_plugins/openscenario_visualization/CHANGELOG.rst +++ b/rviz_plugins/openscenario_visualization/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package openscenario_visualization * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.3 (2024-08-26) +------------------ +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Contributors: Michał Ciasnocha + 3.5.2 (2024-08-23) ------------------ * Merge branch 'master' into fix/interpreter/user-defined-value-condition diff --git a/rviz_plugins/openscenario_visualization/package.xml b/rviz_plugins/openscenario_visualization/package.xml index ba83dacc798..e5e67ac0ea2 100644 --- a/rviz_plugins/openscenario_visualization/package.xml +++ b/rviz_plugins/openscenario_visualization/package.xml @@ -2,7 +2,7 @@ openscenario_visualization - 3.5.2 + 3.5.3 Visualization tools for simulation results Masaya Kataoka Kyoichi Sugahara diff --git a/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst b/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst index f8c796d649f..223867a2762 100644 --- a/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst +++ b/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package real_time_factor_control_rviz_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.3 (2024-08-26) +------------------ +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Contributors: Michał Ciasnocha + 3.5.2 (2024-08-23) ------------------ * Merge branch 'master' into fix/interpreter/user-defined-value-condition diff --git a/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml b/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml index 0b6d98faceb..81764f67368 100644 --- a/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml +++ b/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml @@ -2,7 +2,7 @@ real_time_factor_control_rviz_plugin - 3.5.2 + 3.5.3 Slider controlling real time factor value. Paweł Lech Apache License 2.0 diff --git a/scenario_simulator_v2/CHANGELOG.rst b/scenario_simulator_v2/CHANGELOG.rst index 9fc146c46a7..c85fcd501bd 100644 --- a/scenario_simulator_v2/CHANGELOG.rst +++ b/scenario_simulator_v2/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package scenario_simulator_v2 * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.3 (2024-08-26) +------------------ +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Contributors: Michał Ciasnocha + 3.5.2 (2024-08-23) ------------------ * Merge branch 'master' into fix/interpreter/user-defined-value-condition diff --git a/scenario_simulator_v2/package.xml b/scenario_simulator_v2/package.xml index eb0a5155109..da80c910f75 100644 --- a/scenario_simulator_v2/package.xml +++ b/scenario_simulator_v2/package.xml @@ -2,7 +2,7 @@ scenario_simulator_v2 - 3.5.2 + 3.5.3 scenario testing framework for Autoware Masaya Kataoka Apache License 2.0 diff --git a/simulation/behavior_tree_plugin/CHANGELOG.rst b/simulation/behavior_tree_plugin/CHANGELOG.rst index 012e56d0e24..b2e26f043f4 100644 --- a/simulation/behavior_tree_plugin/CHANGELOG.rst +++ b/simulation/behavior_tree_plugin/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package behavior_tree_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.3 (2024-08-26) +------------------ +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Contributors: Michał Ciasnocha + 3.5.2 (2024-08-23) ------------------ * Merge branch 'master' into fix/interpreter/user-defined-value-condition diff --git a/simulation/behavior_tree_plugin/package.xml b/simulation/behavior_tree_plugin/package.xml index 1841f73241a..6f9738e7c34 100644 --- a/simulation/behavior_tree_plugin/package.xml +++ b/simulation/behavior_tree_plugin/package.xml @@ -2,7 +2,7 @@ behavior_tree_plugin - 3.5.2 + 3.5.3 Behavior tree plugin for traffic_simulator masaya Apache 2.0 diff --git a/simulation/do_nothing_plugin/CHANGELOG.rst b/simulation/do_nothing_plugin/CHANGELOG.rst index c9692148509..567bc7f56cd 100644 --- a/simulation/do_nothing_plugin/CHANGELOG.rst +++ b/simulation/do_nothing_plugin/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package do_nothing_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.3 (2024-08-26) +------------------ +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Contributors: Michał Ciasnocha + 3.5.2 (2024-08-23) ------------------ * Merge branch 'master' into fix/interpreter/user-defined-value-condition diff --git a/simulation/do_nothing_plugin/package.xml b/simulation/do_nothing_plugin/package.xml index c765f33b88f..61cbf087fbd 100644 --- a/simulation/do_nothing_plugin/package.xml +++ b/simulation/do_nothing_plugin/package.xml @@ -2,7 +2,7 @@ do_nothing_plugin - 3.5.2 + 3.5.3 Behavior plugin for do nothing Masaya Kataoka Apache 2.0 diff --git a/simulation/simple_sensor_simulator/CHANGELOG.rst b/simulation/simple_sensor_simulator/CHANGELOG.rst index 23f476b0df6..5e89dfec737 100644 --- a/simulation/simple_sensor_simulator/CHANGELOG.rst +++ b/simulation/simple_sensor_simulator/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package simple_sensor_simulator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.3 (2024-08-26) +------------------ +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Contributors: Michał Ciasnocha + 3.5.2 (2024-08-23) ------------------ * Merge branch 'master' into fix/interpreter/user-defined-value-condition diff --git a/simulation/simple_sensor_simulator/package.xml b/simulation/simple_sensor_simulator/package.xml index d51d3560824..b6c835fe1f7 100644 --- a/simulation/simple_sensor_simulator/package.xml +++ b/simulation/simple_sensor_simulator/package.xml @@ -1,7 +1,7 @@ simple_sensor_simulator - 3.5.2 + 3.5.3 simple_sensor_simulator package masaya kataoka diff --git a/simulation/simulation_interface/CHANGELOG.rst b/simulation/simulation_interface/CHANGELOG.rst index 39714c8a2c9..6f77e285edf 100644 --- a/simulation/simulation_interface/CHANGELOG.rst +++ b/simulation/simulation_interface/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package simulation_interface * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.3 (2024-08-26) +------------------ +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Contributors: Michał Ciasnocha + 3.5.2 (2024-08-23) ------------------ * Merge branch 'master' into fix/interpreter/user-defined-value-condition diff --git a/simulation/simulation_interface/package.xml b/simulation/simulation_interface/package.xml index 766331641db..ccae6e66df8 100644 --- a/simulation/simulation_interface/package.xml +++ b/simulation/simulation_interface/package.xml @@ -2,7 +2,7 @@ simulation_interface - 3.5.2 + 3.5.3 packages to define interface between simulator and scenario interpreter Masaya Kataoka Apache License 2.0 diff --git a/simulation/traffic_simulator/CHANGELOG.rst b/simulation/traffic_simulator/CHANGELOG.rst index 5482cfc1f80..66424413e29 100644 --- a/simulation/traffic_simulator/CHANGELOG.rst +++ b/simulation/traffic_simulator/CHANGELOG.rst @@ -21,6 +21,23 @@ Changelog for package traffic_simulator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.3 (2024-08-26) +------------------ +* Merge pull request `#1340 `_ from tier4/RJD-1278/traffic_simulator-update + Rjd 1278/traffic simulator update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* spellcheck +* review changes +* test_traffic_light.cpp refactor, sort +* test_traffic_lights_manager.cpp refactor +* remove ros nodes +* test_simulation_clock.cpp refacton +* refactor test_helper.cpp file +* Contributors: Masaya Kataoka, Michał Ciasnocha, robomic + 3.5.2 (2024-08-23) ------------------ * Merge branch 'master' into fix/interpreter/user-defined-value-condition diff --git a/simulation/traffic_simulator/package.xml b/simulation/traffic_simulator/package.xml index 54f8e104ad5..871586b1346 100644 --- a/simulation/traffic_simulator/package.xml +++ b/simulation/traffic_simulator/package.xml @@ -1,7 +1,7 @@ traffic_simulator - 3.5.2 + 3.5.3 control traffic flow masaya kataoka diff --git a/simulation/traffic_simulator_msgs/CHANGELOG.rst b/simulation/traffic_simulator_msgs/CHANGELOG.rst index d82f98feb99..dec262db986 100644 --- a/simulation/traffic_simulator_msgs/CHANGELOG.rst +++ b/simulation/traffic_simulator_msgs/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package openscenario_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.3 (2024-08-26) +------------------ +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Contributors: Michał Ciasnocha + 3.5.2 (2024-08-23) ------------------ * Merge branch 'master' into fix/interpreter/user-defined-value-condition diff --git a/simulation/traffic_simulator_msgs/package.xml b/simulation/traffic_simulator_msgs/package.xml index 3a3437091be..ecb075268f2 100644 --- a/simulation/traffic_simulator_msgs/package.xml +++ b/simulation/traffic_simulator_msgs/package.xml @@ -2,7 +2,7 @@ traffic_simulator_msgs - 3.5.2 + 3.5.3 ROS messages for openscenario Masaya Kataoka Apache License 2.0 diff --git a/test_runner/random_test_runner/CHANGELOG.rst b/test_runner/random_test_runner/CHANGELOG.rst index d2f9c7f28d4..35edaec6f7d 100644 --- a/test_runner/random_test_runner/CHANGELOG.rst +++ b/test_runner/random_test_runner/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package random_test_runner * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.3 (2024-08-26) +------------------ +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Contributors: Michał Ciasnocha + 3.5.2 (2024-08-23) ------------------ * Merge branch 'master' into fix/interpreter/user-defined-value-condition diff --git a/test_runner/random_test_runner/package.xml b/test_runner/random_test_runner/package.xml index d486c8b5fc8..a95f5ee6675 100644 --- a/test_runner/random_test_runner/package.xml +++ b/test_runner/random_test_runner/package.xml @@ -2,7 +2,7 @@ random_test_runner - 3.5.2 + 3.5.3 Random behavior test runner piotr-zyskowski-rai Apache License 2.0 diff --git a/test_runner/scenario_test_runner/CHANGELOG.rst b/test_runner/scenario_test_runner/CHANGELOG.rst index 7598508b4af..6f6125ce848 100644 --- a/test_runner/scenario_test_runner/CHANGELOG.rst +++ b/test_runner/scenario_test_runner/CHANGELOG.rst @@ -35,6 +35,14 @@ Changelog for package scenario_test_runner * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.3 (2024-08-26) +------------------ +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Merge branch 'master' into RJD-1278/traffic_simulator-update +* Contributors: Michał Ciasnocha + 3.5.2 (2024-08-23) ------------------ * Merge pull request `#1338 `_ from tier4/fix/interpreter/user-defined-value-condition diff --git a/test_runner/scenario_test_runner/package.xml b/test_runner/scenario_test_runner/package.xml index ee3961e5180..bf3ff00d3ed 100644 --- a/test_runner/scenario_test_runner/package.xml +++ b/test_runner/scenario_test_runner/package.xml @@ -2,7 +2,7 @@ scenario_test_runner - 3.5.2 + 3.5.3 scenario test runner package Tatsuya Yamasaki Apache License 2.0 From c32adba435909a068b17932160f0e34e8f77b725 Mon Sep 17 00:00:00 2001 From: Masaya Kataoka Date: Mon, 26 Aug 2024 16:00:40 +0900 Subject: [PATCH 174/304] update Release Action Signed-off-by: Masaya Kataoka --- .github/workflows/Release.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/Release.yaml b/.github/workflows/Release.yaml index 05d646d8cfa..7fd8180a2b9 100644 --- a/.github/workflows/Release.yaml +++ b/.github/workflows/Release.yaml @@ -151,5 +151,5 @@ jobs: -H "Accept: application/vnd.github+json" \ -H "Authorization: token ${{ secrets.BLOOM_GITHUB_TOKEN }}" \ -H "X-GitHub-Api-Version: 2022-11-28" \ - https://api.github.com/repos/merge-queue-testing/scenario_simulator_v2/actions/workflows/Docker.yaml/dispatches \ + https://api.github.com/repos/tier4/scenario_simulator_v2/actions/workflows/Docker.yaml/dispatches \ -d '{"ref":"master","inputs":{"version":"${{ steps.new_version.outputs.new_version }}"}}' From 5eb34e7cc8ceed9679b6b0311bb4bf4ce2feb4bf Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Mon, 26 Aug 2024 16:46:15 +0900 Subject: [PATCH 175/304] chore: add a test for corner case --- simulation/traffic_simulator/package.xml | 1 + .../test/src/hdmap_utils/test_hdmap_utils.cpp | 28 +++++++++++++++++++ 2 files changed, 29 insertions(+) diff --git a/simulation/traffic_simulator/package.xml b/simulation/traffic_simulator/package.xml index 54f8e104ad5..69ca1eed853 100644 --- a/simulation/traffic_simulator/package.xml +++ b/simulation/traffic_simulator/package.xml @@ -51,6 +51,7 @@ ament_cmake_lint_cmake ament_cmake_pep257 ament_cmake_xmllint + kashiwanoha_map ament_cmake diff --git a/simulation/traffic_simulator/test/src/hdmap_utils/test_hdmap_utils.cpp b/simulation/traffic_simulator/test/src/hdmap_utils/test_hdmap_utils.cpp index 31c18a22a62..93512bda08d 100644 --- a/simulation/traffic_simulator/test/src/hdmap_utils/test_hdmap_utils.cpp +++ b/simulation/traffic_simulator/test/src/hdmap_utils/test_hdmap_utils.cpp @@ -109,6 +109,21 @@ class HdMapUtilsTest_CrossroadsWithStoplinesMap : public testing::Test hdmap_utils::HdMapUtils hdmap_utils; }; +class HdMapUtilsTest_KashiwanohaMap : public testing::Test +{ +protected: + HdMapUtilsTest_KashiwanohaMap() + : hdmap_utils(hdmap_utils::HdMapUtils( + ament_index_cpp::get_package_share_directory("kashiwanoha_map") + "/map/lanelet2_map.osm", + geographic_msgs::build() + .latitude(0.0) + .longitude(0.0) + .altitude(0.0))) + { + } + + hdmap_utils::HdMapUtils hdmap_utils; +}; /** * @note Test basic functionality. * Test initialization correctness with a correct path to a lanelet map. @@ -2024,6 +2039,19 @@ TEST_F(HdMapUtilsTest_FourTrackHighwayMap, getLongitudinalDistance_differentLane hdmap_utils.getLongitudinalDistance(pose_from.value(), pose_to.value(), false).has_value()); } +/** + * @note Test for the corner-case fixed in https://github.com/tier4/scenario_simulator_v2/pull/1348. + */ +TEST_F(HdMapUtilsTest_KashiwanohaMap, getLongitudinalDistance_PullRequest1348) +{ + auto pose_from = traffic_simulator::helper::constructLaneletPose(34468, 10.0); + auto pose_to = traffic_simulator::helper::constructLaneletPose(34795, 5.0); + + EXPECT_NO_THROW(EXPECT_DOUBLE_EQ( + hdmap_utils.getLongitudinalDistance(pose_from, pose_to, true).value(), + 54.18867466433655977198213804513216018676757812500000)); +} + /** * @note Test basic functionality. * Test obtaining stop line ids correctness with a route that has no stop lines. From c09934e672a0bee93f131c03bb02e34871b42b74 Mon Sep 17 00:00:00 2001 From: Masaya Kataoka Date: Mon, 26 Aug 2024 18:17:58 +0900 Subject: [PATCH 176/304] enabel calculate angular accel and jerk Signed-off-by: Masaya Kataoka --- simulation/do_nothing_plugin/src/plugin.cpp | 14 ++++++++++++-- 1 file changed, 12 insertions(+), 2 deletions(-) diff --git a/simulation/do_nothing_plugin/src/plugin.cpp b/simulation/do_nothing_plugin/src/plugin.cpp index f606392fb9a..15ec1418b2d 100644 --- a/simulation/do_nothing_plugin/src/plugin.cpp +++ b/simulation/do_nothing_plugin/src/plugin.cpp @@ -13,6 +13,8 @@ // limitations under the License. #include +#include +#include #include #include #include @@ -98,15 +100,23 @@ auto interpolateEntityStatusFromPolylineTrajectory( const auto linear_jerk = (entity_status->getAccel().linear.x - linear_acceleration) / (v1.time - v0.time); + const double angular_velocity = + math::geometry::convertQuaternionToEulerAngle( + math::geometry::getRotation(v0.position.orientation, v1.position.orientation)) + .z; + const auto angular_acceleration = + (entity_status->getTwist().angular.x - angular_velocity) / (v1.time - v0.time); + interpolated_entity_status.action_status.twist = geometry_msgs::build() .linear(geometry_msgs::build().x(linear_velocity).y(0).z(0)) - .angular(geometry_msgs::build().x(0).y(0).z(0)); + .angular(geometry_msgs::build().x(angular_velocity).y(0).z(0)); interpolated_entity_status.action_status.accel = geometry_msgs::build() .linear( geometry_msgs::build().x(linear_acceleration).y(0).z(0)) - .angular(geometry_msgs::build().x(0).y(0).z(0)); + .angular( + geometry_msgs::build().x(angular_acceleration).y(0).z(0)); interpolated_entity_status.action_status.linear_jerk = linear_jerk; return interpolated_entity_status; }; From 7c71fa0d56a9b4a3630f628fe51ef5c2e4a5969a Mon Sep 17 00:00:00 2001 From: Dawid Moszynski Date: Mon, 26 Aug 2024 14:28:27 +0200 Subject: [PATCH 177/304] Revert "feat(params): set use_sim_time default as True" This reverts commit da85edf4956083563715daa3d60f0da1f94a423d. --- .../simple_sensor_simulator/src/simple_sensor_simulator.cpp | 2 +- .../scenario_test_runner/launch/scenario_test_runner.launch.py | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/simulation/simple_sensor_simulator/src/simple_sensor_simulator.cpp b/simulation/simple_sensor_simulator/src/simple_sensor_simulator.cpp index a5d4a95c2d2..b762ac6453b 100644 --- a/simulation/simple_sensor_simulator/src/simple_sensor_simulator.cpp +++ b/simulation/simple_sensor_simulator/src/simple_sensor_simulator.cpp @@ -231,7 +231,7 @@ auto ScenarioSimulator::spawnVehicleEntity( simulation_interface::toMsg(req.pose(), initial_status.pose); ego_entity_simulation_ = std::make_shared( initial_status, parameters, step_time_, hdmap_utils_, - get_parameter_or("use_sim_time", rclcpp::Parameter("use_sim_time", true)), + get_parameter_or("use_sim_time", rclcpp::Parameter("use_sim_time", false)), get_consider_acceleration_by_road_slope()); } else { vehicles_.emplace_back(req.parameters()); diff --git a/test_runner/scenario_test_runner/launch/scenario_test_runner.launch.py b/test_runner/scenario_test_runner/launch/scenario_test_runner.launch.py index 961cd9a5f5d..4d0b80e55f3 100755 --- a/test_runner/scenario_test_runner/launch/scenario_test_runner.launch.py +++ b/test_runner/scenario_test_runner/launch/scenario_test_runner.launch.py @@ -81,7 +81,7 @@ def launch_setup(context, *args, **kwargs): scenario = LaunchConfiguration("scenario", default=Path("/dev/null")) sensor_model = LaunchConfiguration("sensor_model", default="") sigterm_timeout = LaunchConfiguration("sigterm_timeout", default=8) - use_sim_time = LaunchConfiguration("use_sim_time", default=True) + use_sim_time = LaunchConfiguration("use_sim_time", default=False) vehicle_model = LaunchConfiguration("vehicle_model", default="") # fmt: on From 0dee3c59cd7c25b218a17796fc0bcd5451ee09a3 Mon Sep 17 00:00:00 2001 From: Dawid Moszynski Date: Mon, 26 Aug 2024 14:41:28 +0200 Subject: [PATCH 178/304] feat(use_sim_time): set default as false --- simulation/traffic_simulator/src/entity/ego_entity.cpp | 2 +- .../scenario_test_runner/launch/scenario_test_runner.launch.py | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/simulation/traffic_simulator/src/entity/ego_entity.cpp b/simulation/traffic_simulator/src/entity/ego_entity.cpp index 40c770e2fd2..3b1694eee72 100644 --- a/simulation/traffic_simulator/src/entity/ego_entity.cpp +++ b/simulation/traffic_simulator/src/entity/ego_entity.cpp @@ -60,7 +60,7 @@ auto EgoEntity::makeFieldOperatorApplication( std::string((architecture_type >= "awf/universe/20230906") ? "true" : "false"), "use_sim_time:=" + std::string( - getParameter(node_parameters, "use_sim_time", true) ? "true" : "false")) + getParameter(node_parameters, "use_sim_time", false) ? "true" : "false")) : std::make_unique< concealer::FieldOperatorApplicationFor>(); } else { diff --git a/test_runner/scenario_test_runner/launch/scenario_test_runner.launch.py b/test_runner/scenario_test_runner/launch/scenario_test_runner.launch.py index 4d0b80e55f3..33c5161e927 100755 --- a/test_runner/scenario_test_runner/launch/scenario_test_runner.launch.py +++ b/test_runner/scenario_test_runner/launch/scenario_test_runner.launch.py @@ -192,7 +192,7 @@ def description(): namespace="simulation", output="screen", on_exit=ShutdownOnce(), - parameters=make_parameters() + [{"use_sim_time": True}], + parameters=make_parameters() + [{"use_sim_time": use_sim_time}], condition=IfCondition(launch_simple_sensor_simulator), ), # The `name` keyword overrides the name for all created nodes, so duplicated nodes appear. From 501f6649176145f0dd69ba7f9a7c82866d6a7e18 Mon Sep 17 00:00:00 2001 From: Dawid Moszynski Date: Mon, 26 Aug 2024 14:42:58 +0200 Subject: [PATCH 179/304] feat(doc): adapt doc to use_sim_time default as False --- docs/user_guide/scenario_test_runner/RealtimeFactor.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/user_guide/scenario_test_runner/RealtimeFactor.md b/docs/user_guide/scenario_test_runner/RealtimeFactor.md index 08c70f3249d..61aa1c3b180 100644 --- a/docs/user_guide/scenario_test_runner/RealtimeFactor.md +++ b/docs/user_guide/scenario_test_runner/RealtimeFactor.md @@ -42,7 +42,7 @@ It is possible to modify the speed of simulation (the speed of time published on ## Configure `use_sim_time` parameter -Parameter `use_sim_time` of `openscenario_interpreter` is true by default and can be modified by passing it using command line. +Parameter `use_sim_time` of `openscenario_interpreter` is **false** by default and can be modified by passing it using command line. ```bash @@ -53,7 +53,7 @@ Parameter `use_sim_time` of `openscenario_interpreter` is true by default and ca sensor_model:=sample_sensor_kit \ vehicle_model:=sample_vehicle \ global_real_time_factor:="0.5" \ - use_sim_time:=False + use_sim_time:=true ``` However, this impacts the time published on the `/clock` topic and the time used by `Autoware`. From 9ec6a4b1c9f51be8ae2677953b9ad9488b91b510 Mon Sep 17 00:00:00 2001 From: Release Bot Date: Mon, 26 Aug 2024 13:44:09 +0000 Subject: [PATCH 180/304] Bump version of scenario_simulator_v2 from version 3.5.3 to version 3.5.4 --- common/math/arithmetic/CHANGELOG.rst | 8 ++++++++ common/math/arithmetic/package.xml | 2 +- common/math/geometry/CHANGELOG.rst | 8 ++++++++ common/math/geometry/package.xml | 2 +- common/scenario_simulator_exception/CHANGELOG.rst | 8 ++++++++ common/scenario_simulator_exception/package.xml | 2 +- common/simple_junit/CHANGELOG.rst | 8 ++++++++ common/simple_junit/package.xml | 2 +- common/status_monitor/CHANGELOG.rst | 8 ++++++++ common/status_monitor/package.xml | 2 +- external/concealer/CHANGELOG.rst | 8 ++++++++ external/concealer/package.xml | 2 +- external/embree_vendor/CHANGELOG.rst | 8 ++++++++ external/embree_vendor/package.xml | 2 +- map/kashiwanoha_map/CHANGELOG.rst | 8 ++++++++ map/kashiwanoha_map/package.xml | 2 +- map/simple_cross_map/CHANGELOG.rst | 8 ++++++++ map/simple_cross_map/package.xml | 2 +- mock/cpp_mock_scenarios/CHANGELOG.rst | 8 ++++++++ mock/cpp_mock_scenarios/package.xml | 2 +- .../openscenario_experimental_catalog/CHANGELOG.rst | 8 ++++++++ .../openscenario_experimental_catalog/package.xml | 2 +- openscenario/openscenario_interpreter/CHANGELOG.rst | 8 ++++++++ openscenario/openscenario_interpreter/package.xml | 2 +- .../openscenario_interpreter_example/CHANGELOG.rst | 8 ++++++++ .../openscenario_interpreter_example/package.xml | 2 +- openscenario/openscenario_interpreter_msgs/CHANGELOG.rst | 8 ++++++++ openscenario/openscenario_interpreter_msgs/package.xml | 2 +- openscenario/openscenario_preprocessor/CHANGELOG.rst | 8 ++++++++ openscenario/openscenario_preprocessor/package.xml | 2 +- .../openscenario_preprocessor_msgs/CHANGELOG.rst | 8 ++++++++ openscenario/openscenario_preprocessor_msgs/package.xml | 2 +- openscenario/openscenario_utility/CHANGELOG.rst | 8 ++++++++ openscenario/openscenario_utility/package.xml | 2 +- openscenario/openscenario_validator/CHANGELOG.rst | 8 ++++++++ openscenario/openscenario_validator/package.xml | 2 +- rviz_plugins/openscenario_visualization/CHANGELOG.rst | 8 ++++++++ rviz_plugins/openscenario_visualization/package.xml | 2 +- .../real_time_factor_control_rviz_plugin/CHANGELOG.rst | 8 ++++++++ .../real_time_factor_control_rviz_plugin/package.xml | 2 +- scenario_simulator_v2/CHANGELOG.rst | 8 ++++++++ scenario_simulator_v2/package.xml | 2 +- simulation/behavior_tree_plugin/CHANGELOG.rst | 8 ++++++++ simulation/behavior_tree_plugin/package.xml | 2 +- simulation/do_nothing_plugin/CHANGELOG.rst | 8 ++++++++ simulation/do_nothing_plugin/package.xml | 2 +- simulation/simple_sensor_simulator/CHANGELOG.rst | 8 ++++++++ simulation/simple_sensor_simulator/package.xml | 2 +- simulation/simulation_interface/CHANGELOG.rst | 8 ++++++++ simulation/simulation_interface/package.xml | 2 +- simulation/traffic_simulator/CHANGELOG.rst | 8 ++++++++ simulation/traffic_simulator/package.xml | 2 +- simulation/traffic_simulator_msgs/CHANGELOG.rst | 8 ++++++++ simulation/traffic_simulator_msgs/package.xml | 2 +- test_runner/random_test_runner/CHANGELOG.rst | 9 +++++++++ test_runner/random_test_runner/package.xml | 2 +- test_runner/scenario_test_runner/CHANGELOG.rst | 8 ++++++++ test_runner/scenario_test_runner/package.xml | 2 +- 58 files changed, 262 insertions(+), 29 deletions(-) diff --git a/common/math/arithmetic/CHANGELOG.rst b/common/math/arithmetic/CHANGELOG.rst index d5cdf085045..467c47fe864 100644 --- a/common/math/arithmetic/CHANGELOG.rst +++ b/common/math/arithmetic/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package arithmetic * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.4 (2024-08-26) +------------------ +* Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build +* Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build +* Merge remote-tracking branch 'origin/master' into feature/use_workflow_dispatch_in_docker_build +* Merge remote-tracking branch 'origin/master' into feature/trigger_docker_build_by_tag +* Contributors: Masaya Kataoka + 3.5.3 (2024-08-26) ------------------ * Merge branch 'master' into RJD-1278/traffic_simulator-update diff --git a/common/math/arithmetic/package.xml b/common/math/arithmetic/package.xml index ad71f08769a..46b7785af61 100644 --- a/common/math/arithmetic/package.xml +++ b/common/math/arithmetic/package.xml @@ -2,7 +2,7 @@ arithmetic - 3.5.3 + 3.5.4 arithmetic library for scenario_simulator_v2 Tatsuya Yamasaki Apache License 2.0 diff --git a/common/math/geometry/CHANGELOG.rst b/common/math/geometry/CHANGELOG.rst index 5885a8312dd..89ccf45a518 100644 --- a/common/math/geometry/CHANGELOG.rst +++ b/common/math/geometry/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package geometry * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.4 (2024-08-26) +------------------ +* Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build +* Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build +* Merge remote-tracking branch 'origin/master' into feature/use_workflow_dispatch_in_docker_build +* Merge remote-tracking branch 'origin/master' into feature/trigger_docker_build_by_tag +* Contributors: Masaya Kataoka + 3.5.3 (2024-08-26) ------------------ * Merge branch 'master' into RJD-1278/traffic_simulator-update diff --git a/common/math/geometry/package.xml b/common/math/geometry/package.xml index cc2e1cbdfff..f1fffa30b8d 100644 --- a/common/math/geometry/package.xml +++ b/common/math/geometry/package.xml @@ -2,7 +2,7 @@ geometry - 3.5.3 + 3.5.4 geometry math library for scenario_simulator_v2 application Masaya Kataoka Apache License 2.0 diff --git a/common/scenario_simulator_exception/CHANGELOG.rst b/common/scenario_simulator_exception/CHANGELOG.rst index 1039bd379fb..1b43946e6b9 100644 --- a/common/scenario_simulator_exception/CHANGELOG.rst +++ b/common/scenario_simulator_exception/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package scenario_simulator_exception * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.4 (2024-08-26) +------------------ +* Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build +* Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build +* Merge remote-tracking branch 'origin/master' into feature/use_workflow_dispatch_in_docker_build +* Merge remote-tracking branch 'origin/master' into feature/trigger_docker_build_by_tag +* Contributors: Masaya Kataoka + 3.5.3 (2024-08-26) ------------------ * Merge branch 'master' into RJD-1278/traffic_simulator-update diff --git a/common/scenario_simulator_exception/package.xml b/common/scenario_simulator_exception/package.xml index 67fcb60a568..79e3c5275e0 100644 --- a/common/scenario_simulator_exception/package.xml +++ b/common/scenario_simulator_exception/package.xml @@ -2,7 +2,7 @@ scenario_simulator_exception - 3.5.3 + 3.5.4 Exception types for scenario simulator Tatsuya Yamasaki Apache License 2.0 diff --git a/common/simple_junit/CHANGELOG.rst b/common/simple_junit/CHANGELOG.rst index df549834566..c1e0ed3d0b7 100644 --- a/common/simple_junit/CHANGELOG.rst +++ b/common/simple_junit/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package junit_exporter * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.4 (2024-08-26) +------------------ +* Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build +* Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build +* Merge remote-tracking branch 'origin/master' into feature/use_workflow_dispatch_in_docker_build +* Merge remote-tracking branch 'origin/master' into feature/trigger_docker_build_by_tag +* Contributors: Masaya Kataoka + 3.5.3 (2024-08-26) ------------------ * Merge branch 'master' into RJD-1278/traffic_simulator-update diff --git a/common/simple_junit/package.xml b/common/simple_junit/package.xml index 0247d4d5e8b..bb9246a5c99 100644 --- a/common/simple_junit/package.xml +++ b/common/simple_junit/package.xml @@ -2,7 +2,7 @@ simple_junit - 3.5.3 + 3.5.4 Lightweight JUnit library for ROS 2 Masaya Kataoka Tatsuya Yamasaki diff --git a/common/status_monitor/CHANGELOG.rst b/common/status_monitor/CHANGELOG.rst index d7f12fc6be0..60671a9b95e 100644 --- a/common/status_monitor/CHANGELOG.rst +++ b/common/status_monitor/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package status_monitor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.4 (2024-08-26) +------------------ +* Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build +* Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build +* Merge remote-tracking branch 'origin/master' into feature/use_workflow_dispatch_in_docker_build +* Merge remote-tracking branch 'origin/master' into feature/trigger_docker_build_by_tag +* Contributors: Masaya Kataoka + 3.5.3 (2024-08-26) ------------------ * Merge branch 'master' into RJD-1278/traffic_simulator-update diff --git a/common/status_monitor/package.xml b/common/status_monitor/package.xml index acc92ec16a9..31549fef4d0 100644 --- a/common/status_monitor/package.xml +++ b/common/status_monitor/package.xml @@ -2,7 +2,7 @@ status_monitor - 3.5.3 + 3.5.4 none Tatsuya Yamasaki Apache License 2.0 diff --git a/external/concealer/CHANGELOG.rst b/external/concealer/CHANGELOG.rst index 44a8b9df790..fbbee447a43 100644 --- a/external/concealer/CHANGELOG.rst +++ b/external/concealer/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package concealer * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.4 (2024-08-26) +------------------ +* Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build +* Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build +* Merge remote-tracking branch 'origin/master' into feature/use_workflow_dispatch_in_docker_build +* Merge remote-tracking branch 'origin/master' into feature/trigger_docker_build_by_tag +* Contributors: Masaya Kataoka + 3.5.3 (2024-08-26) ------------------ * Merge branch 'master' into RJD-1278/traffic_simulator-update diff --git a/external/concealer/package.xml b/external/concealer/package.xml index c8efe8047fe..f72f33f6f00 100644 --- a/external/concealer/package.xml +++ b/external/concealer/package.xml @@ -2,7 +2,7 @@ concealer - 3.5.3 + 3.5.4 Provides a class 'Autoware' to conceal miscellaneous things to simplify Autoware management of the simulator. Tatsuya Yamasaki Apache License 2.0 diff --git a/external/embree_vendor/CHANGELOG.rst b/external/embree_vendor/CHANGELOG.rst index 2bf8de40977..8e5adc53cc8 100644 --- a/external/embree_vendor/CHANGELOG.rst +++ b/external/embree_vendor/CHANGELOG.rst @@ -24,6 +24,14 @@ Changelog for package embree_vendor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.4 (2024-08-26) +------------------ +* Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build +* Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build +* Merge remote-tracking branch 'origin/master' into feature/use_workflow_dispatch_in_docker_build +* Merge remote-tracking branch 'origin/master' into feature/trigger_docker_build_by_tag +* Contributors: Masaya Kataoka + 3.5.3 (2024-08-26) ------------------ * Merge branch 'master' into RJD-1278/traffic_simulator-update diff --git a/external/embree_vendor/package.xml b/external/embree_vendor/package.xml index 59ee7f07864..5aceb9da6d6 100644 --- a/external/embree_vendor/package.xml +++ b/external/embree_vendor/package.xml @@ -2,7 +2,7 @@ embree_vendor - 3.5.3 + 3.5.4 vendor packages for intel raytracing kernel library masaya Apache 2.0 diff --git a/map/kashiwanoha_map/CHANGELOG.rst b/map/kashiwanoha_map/CHANGELOG.rst index b07a9b4888a..012ff0e86d8 100644 --- a/map/kashiwanoha_map/CHANGELOG.rst +++ b/map/kashiwanoha_map/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package kashiwanoha_map * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.4 (2024-08-26) +------------------ +* Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build +* Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build +* Merge remote-tracking branch 'origin/master' into feature/use_workflow_dispatch_in_docker_build +* Merge remote-tracking branch 'origin/master' into feature/trigger_docker_build_by_tag +* Contributors: Masaya Kataoka + 3.5.3 (2024-08-26) ------------------ * Merge branch 'master' into RJD-1278/traffic_simulator-update diff --git a/map/kashiwanoha_map/package.xml b/map/kashiwanoha_map/package.xml index 5dea47966cb..71f5521b4d3 100644 --- a/map/kashiwanoha_map/package.xml +++ b/map/kashiwanoha_map/package.xml @@ -2,7 +2,7 @@ kashiwanoha_map - 3.5.3 + 3.5.4 map package for kashiwanoha Masaya Kataoka Apache License 2.0 diff --git a/map/simple_cross_map/CHANGELOG.rst b/map/simple_cross_map/CHANGELOG.rst index 6815e2f60c9..76cb3e0ffde 100644 --- a/map/simple_cross_map/CHANGELOG.rst +++ b/map/simple_cross_map/CHANGELOG.rst @@ -9,6 +9,14 @@ Changelog for package simple_cross_map * Merge branch 'master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.4 (2024-08-26) +------------------ +* Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build +* Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build +* Merge remote-tracking branch 'origin/master' into feature/use_workflow_dispatch_in_docker_build +* Merge remote-tracking branch 'origin/master' into feature/trigger_docker_build_by_tag +* Contributors: Masaya Kataoka + 3.5.3 (2024-08-26) ------------------ * Merge branch 'master' into RJD-1278/traffic_simulator-update diff --git a/map/simple_cross_map/package.xml b/map/simple_cross_map/package.xml index bb0898e739f..ae69291a68e 100644 --- a/map/simple_cross_map/package.xml +++ b/map/simple_cross_map/package.xml @@ -2,7 +2,7 @@ simple_cross_map - 3.5.3 + 3.5.4 map package for simple cross Masaya Kataoka Apache License 2.0 diff --git a/mock/cpp_mock_scenarios/CHANGELOG.rst b/mock/cpp_mock_scenarios/CHANGELOG.rst index ee76ec7d322..2388ab61f61 100644 --- a/mock/cpp_mock_scenarios/CHANGELOG.rst +++ b/mock/cpp_mock_scenarios/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package cpp_mock_scenarios * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.4 (2024-08-26) +------------------ +* Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build +* Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build +* Merge remote-tracking branch 'origin/master' into feature/use_workflow_dispatch_in_docker_build +* Merge remote-tracking branch 'origin/master' into feature/trigger_docker_build_by_tag +* Contributors: Masaya Kataoka + 3.5.3 (2024-08-26) ------------------ * Merge branch 'master' into RJD-1278/traffic_simulator-update diff --git a/mock/cpp_mock_scenarios/package.xml b/mock/cpp_mock_scenarios/package.xml index 896499f1b84..5aa027dabfa 100644 --- a/mock/cpp_mock_scenarios/package.xml +++ b/mock/cpp_mock_scenarios/package.xml @@ -2,7 +2,7 @@ cpp_mock_scenarios - 3.5.3 + 3.5.4 C++ mock scenarios masaya Apache License 2.0 diff --git a/openscenario/openscenario_experimental_catalog/CHANGELOG.rst b/openscenario/openscenario_experimental_catalog/CHANGELOG.rst index 0e647aaa997..b93ba4c67dc 100644 --- a/openscenario/openscenario_experimental_catalog/CHANGELOG.rst +++ b/openscenario/openscenario_experimental_catalog/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package openscenario_experimental_catalog * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.4 (2024-08-26) +------------------ +* Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build +* Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build +* Merge remote-tracking branch 'origin/master' into feature/use_workflow_dispatch_in_docker_build +* Merge remote-tracking branch 'origin/master' into feature/trigger_docker_build_by_tag +* Contributors: Masaya Kataoka + 3.5.3 (2024-08-26) ------------------ * Merge branch 'master' into RJD-1278/traffic_simulator-update diff --git a/openscenario/openscenario_experimental_catalog/package.xml b/openscenario/openscenario_experimental_catalog/package.xml index 2992fd5ba15..52579a5a314 100644 --- a/openscenario/openscenario_experimental_catalog/package.xml +++ b/openscenario/openscenario_experimental_catalog/package.xml @@ -2,7 +2,7 @@ openscenario_experimental_catalog - 3.5.3 + 3.5.4 TIER IV experimental catalogs for OpenSCENARIO Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter/CHANGELOG.rst b/openscenario/openscenario_interpreter/CHANGELOG.rst index 1b9739cf5c5..942b38865ca 100644 --- a/openscenario/openscenario_interpreter/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter/CHANGELOG.rst @@ -32,6 +32,14 @@ Changelog for package openscenario_interpreter * add publish_empty_context parameter * Contributors: Masaya Kataoka +3.5.4 (2024-08-26) +------------------ +* Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build +* Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build +* Merge remote-tracking branch 'origin/master' into feature/use_workflow_dispatch_in_docker_build +* Merge remote-tracking branch 'origin/master' into feature/trigger_docker_build_by_tag +* Contributors: Masaya Kataoka + 3.5.3 (2024-08-26) ------------------ * Merge branch 'master' into RJD-1278/traffic_simulator-update diff --git a/openscenario/openscenario_interpreter/package.xml b/openscenario/openscenario_interpreter/package.xml index 2aff49e8960..bddb03798d1 100644 --- a/openscenario/openscenario_interpreter/package.xml +++ b/openscenario/openscenario_interpreter/package.xml @@ -2,7 +2,7 @@ openscenario_interpreter - 3.5.3 + 3.5.4 OpenSCENARIO 1.2.0 interpreter package for Autoware Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter_example/CHANGELOG.rst b/openscenario/openscenario_interpreter_example/CHANGELOG.rst index 472b0c8d739..e49baa04a82 100644 --- a/openscenario/openscenario_interpreter_example/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter_example/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package openscenario_interpreter_example * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.4 (2024-08-26) +------------------ +* Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build +* Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build +* Merge remote-tracking branch 'origin/master' into feature/use_workflow_dispatch_in_docker_build +* Merge remote-tracking branch 'origin/master' into feature/trigger_docker_build_by_tag +* Contributors: Masaya Kataoka + 3.5.3 (2024-08-26) ------------------ * Merge branch 'master' into RJD-1278/traffic_simulator-update diff --git a/openscenario/openscenario_interpreter_example/package.xml b/openscenario/openscenario_interpreter_example/package.xml index 398177968bd..b6dfae61436 100644 --- a/openscenario/openscenario_interpreter_example/package.xml +++ b/openscenario/openscenario_interpreter_example/package.xml @@ -3,7 +3,7 @@ openscenario_interpreter_example - 3.5.3 + 3.5.4 Examples for some TIER IV OpenSCENARIO Interpreter's features Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst b/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst index 0ce9a237677..0982794c22b 100644 --- a/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package openscenario_interpreter_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.4 (2024-08-26) +------------------ +* Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build +* Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build +* Merge remote-tracking branch 'origin/master' into feature/use_workflow_dispatch_in_docker_build +* Merge remote-tracking branch 'origin/master' into feature/trigger_docker_build_by_tag +* Contributors: Masaya Kataoka + 3.5.3 (2024-08-26) ------------------ * Merge branch 'master' into RJD-1278/traffic_simulator-update diff --git a/openscenario/openscenario_interpreter_msgs/package.xml b/openscenario/openscenario_interpreter_msgs/package.xml index 2fe049a5434..051f9bf690f 100644 --- a/openscenario/openscenario_interpreter_msgs/package.xml +++ b/openscenario/openscenario_interpreter_msgs/package.xml @@ -2,7 +2,7 @@ openscenario_interpreter_msgs - 3.5.3 + 3.5.4 ROS message types for package openscenario_interpreter Yamasaki Tatsuya Apache License 2.0 diff --git a/openscenario/openscenario_preprocessor/CHANGELOG.rst b/openscenario/openscenario_preprocessor/CHANGELOG.rst index 81d8e2e410f..26450c6c221 100644 --- a/openscenario/openscenario_preprocessor/CHANGELOG.rst +++ b/openscenario/openscenario_preprocessor/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package openscenario_preprocessor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.4 (2024-08-26) +------------------ +* Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build +* Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build +* Merge remote-tracking branch 'origin/master' into feature/use_workflow_dispatch_in_docker_build +* Merge remote-tracking branch 'origin/master' into feature/trigger_docker_build_by_tag +* Contributors: Masaya Kataoka + 3.5.3 (2024-08-26) ------------------ * Merge branch 'master' into RJD-1278/traffic_simulator-update diff --git a/openscenario/openscenario_preprocessor/package.xml b/openscenario/openscenario_preprocessor/package.xml index 1aa6e64575b..883de3e4019 100644 --- a/openscenario/openscenario_preprocessor/package.xml +++ b/openscenario/openscenario_preprocessor/package.xml @@ -3,7 +3,7 @@ openscenario_preprocessor - 3.5.3 + 3.5.4 Example package for TIER IV OpenSCENARIO Interpreter Kotaro Yoshimoto Apache License 2.0 diff --git a/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst b/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst index b3ee19603e4..daad6ed5a0c 100644 --- a/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst +++ b/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package openscenario_preprocessor_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.4 (2024-08-26) +------------------ +* Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build +* Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build +* Merge remote-tracking branch 'origin/master' into feature/use_workflow_dispatch_in_docker_build +* Merge remote-tracking branch 'origin/master' into feature/trigger_docker_build_by_tag +* Contributors: Masaya Kataoka + 3.5.3 (2024-08-26) ------------------ * Merge branch 'master' into RJD-1278/traffic_simulator-update diff --git a/openscenario/openscenario_preprocessor_msgs/package.xml b/openscenario/openscenario_preprocessor_msgs/package.xml index ea03060c1cb..4137dc03397 100644 --- a/openscenario/openscenario_preprocessor_msgs/package.xml +++ b/openscenario/openscenario_preprocessor_msgs/package.xml @@ -2,7 +2,7 @@ openscenario_preprocessor_msgs - 3.5.3 + 3.5.4 ROS message types for package openscenario_preprocessor Kotaro Yoshimoto Apache License 2.0 diff --git a/openscenario/openscenario_utility/CHANGELOG.rst b/openscenario/openscenario_utility/CHANGELOG.rst index 9cafff75657..021f3c18dfb 100644 --- a/openscenario/openscenario_utility/CHANGELOG.rst +++ b/openscenario/openscenario_utility/CHANGELOG.rst @@ -24,6 +24,14 @@ Changelog for package openscenario_utility * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.4 (2024-08-26) +------------------ +* Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build +* Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build +* Merge remote-tracking branch 'origin/master' into feature/use_workflow_dispatch_in_docker_build +* Merge remote-tracking branch 'origin/master' into feature/trigger_docker_build_by_tag +* Contributors: Masaya Kataoka + 3.5.3 (2024-08-26) ------------------ * Merge branch 'master' into RJD-1278/traffic_simulator-update diff --git a/openscenario/openscenario_utility/package.xml b/openscenario/openscenario_utility/package.xml index b052653092e..94fe00e3f49 100644 --- a/openscenario/openscenario_utility/package.xml +++ b/openscenario/openscenario_utility/package.xml @@ -2,7 +2,7 @@ openscenario_utility - 3.5.3 + 3.5.4 Utility tools for ASAM OpenSCENARIO 1.2.0 Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_validator/CHANGELOG.rst b/openscenario/openscenario_validator/CHANGELOG.rst index 5862a955aad..37bbdaeef80 100644 --- a/openscenario/openscenario_validator/CHANGELOG.rst +++ b/openscenario/openscenario_validator/CHANGELOG.rst @@ -10,6 +10,14 @@ Changelog for package openscenario_validator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.4 (2024-08-26) +------------------ +* Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build +* Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build +* Merge remote-tracking branch 'origin/master' into feature/use_workflow_dispatch_in_docker_build +* Merge remote-tracking branch 'origin/master' into feature/trigger_docker_build_by_tag +* Contributors: Masaya Kataoka + 3.5.3 (2024-08-26) ------------------ * Merge branch 'master' into RJD-1278/traffic_simulator-update diff --git a/openscenario/openscenario_validator/package.xml b/openscenario/openscenario_validator/package.xml index d97006c053c..804c7023e43 100644 --- a/openscenario/openscenario_validator/package.xml +++ b/openscenario/openscenario_validator/package.xml @@ -2,7 +2,7 @@ openscenario_validator - 3.5.3 + 3.5.4 Validator for OpenSCENARIO 1.3 Kotaro Yoshimoto Apache License 2.0 diff --git a/rviz_plugins/openscenario_visualization/CHANGELOG.rst b/rviz_plugins/openscenario_visualization/CHANGELOG.rst index 69111cfa28a..b8cbe34be33 100644 --- a/rviz_plugins/openscenario_visualization/CHANGELOG.rst +++ b/rviz_plugins/openscenario_visualization/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package openscenario_visualization * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.4 (2024-08-26) +------------------ +* Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build +* Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build +* Merge remote-tracking branch 'origin/master' into feature/use_workflow_dispatch_in_docker_build +* Merge remote-tracking branch 'origin/master' into feature/trigger_docker_build_by_tag +* Contributors: Masaya Kataoka + 3.5.3 (2024-08-26) ------------------ * Merge branch 'master' into RJD-1278/traffic_simulator-update diff --git a/rviz_plugins/openscenario_visualization/package.xml b/rviz_plugins/openscenario_visualization/package.xml index e5e67ac0ea2..f8f21ccb236 100644 --- a/rviz_plugins/openscenario_visualization/package.xml +++ b/rviz_plugins/openscenario_visualization/package.xml @@ -2,7 +2,7 @@ openscenario_visualization - 3.5.3 + 3.5.4 Visualization tools for simulation results Masaya Kataoka Kyoichi Sugahara diff --git a/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst b/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst index 223867a2762..dc7ebe4370a 100644 --- a/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst +++ b/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package real_time_factor_control_rviz_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.4 (2024-08-26) +------------------ +* Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build +* Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build +* Merge remote-tracking branch 'origin/master' into feature/use_workflow_dispatch_in_docker_build +* Merge remote-tracking branch 'origin/master' into feature/trigger_docker_build_by_tag +* Contributors: Masaya Kataoka + 3.5.3 (2024-08-26) ------------------ * Merge branch 'master' into RJD-1278/traffic_simulator-update diff --git a/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml b/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml index 81764f67368..bafebc256bf 100644 --- a/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml +++ b/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml @@ -2,7 +2,7 @@ real_time_factor_control_rviz_plugin - 3.5.3 + 3.5.4 Slider controlling real time factor value. Paweł Lech Apache License 2.0 diff --git a/scenario_simulator_v2/CHANGELOG.rst b/scenario_simulator_v2/CHANGELOG.rst index c85fcd501bd..fbde618feba 100644 --- a/scenario_simulator_v2/CHANGELOG.rst +++ b/scenario_simulator_v2/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package scenario_simulator_v2 * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.4 (2024-08-26) +------------------ +* Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build +* Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build +* Merge remote-tracking branch 'origin/master' into feature/use_workflow_dispatch_in_docker_build +* Merge remote-tracking branch 'origin/master' into feature/trigger_docker_build_by_tag +* Contributors: Masaya Kataoka + 3.5.3 (2024-08-26) ------------------ * Merge branch 'master' into RJD-1278/traffic_simulator-update diff --git a/scenario_simulator_v2/package.xml b/scenario_simulator_v2/package.xml index da80c910f75..d509f074439 100644 --- a/scenario_simulator_v2/package.xml +++ b/scenario_simulator_v2/package.xml @@ -2,7 +2,7 @@ scenario_simulator_v2 - 3.5.3 + 3.5.4 scenario testing framework for Autoware Masaya Kataoka Apache License 2.0 diff --git a/simulation/behavior_tree_plugin/CHANGELOG.rst b/simulation/behavior_tree_plugin/CHANGELOG.rst index b2e26f043f4..46cb9fc6eb3 100644 --- a/simulation/behavior_tree_plugin/CHANGELOG.rst +++ b/simulation/behavior_tree_plugin/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package behavior_tree_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.4 (2024-08-26) +------------------ +* Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build +* Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build +* Merge remote-tracking branch 'origin/master' into feature/use_workflow_dispatch_in_docker_build +* Merge remote-tracking branch 'origin/master' into feature/trigger_docker_build_by_tag +* Contributors: Masaya Kataoka + 3.5.3 (2024-08-26) ------------------ * Merge branch 'master' into RJD-1278/traffic_simulator-update diff --git a/simulation/behavior_tree_plugin/package.xml b/simulation/behavior_tree_plugin/package.xml index 6f9738e7c34..d8aa1397a6e 100644 --- a/simulation/behavior_tree_plugin/package.xml +++ b/simulation/behavior_tree_plugin/package.xml @@ -2,7 +2,7 @@ behavior_tree_plugin - 3.5.3 + 3.5.4 Behavior tree plugin for traffic_simulator masaya Apache 2.0 diff --git a/simulation/do_nothing_plugin/CHANGELOG.rst b/simulation/do_nothing_plugin/CHANGELOG.rst index 567bc7f56cd..c69dad60f58 100644 --- a/simulation/do_nothing_plugin/CHANGELOG.rst +++ b/simulation/do_nothing_plugin/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package do_nothing_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.4 (2024-08-26) +------------------ +* Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build +* Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build +* Merge remote-tracking branch 'origin/master' into feature/use_workflow_dispatch_in_docker_build +* Merge remote-tracking branch 'origin/master' into feature/trigger_docker_build_by_tag +* Contributors: Masaya Kataoka + 3.5.3 (2024-08-26) ------------------ * Merge branch 'master' into RJD-1278/traffic_simulator-update diff --git a/simulation/do_nothing_plugin/package.xml b/simulation/do_nothing_plugin/package.xml index 61cbf087fbd..8b93d7aaec0 100644 --- a/simulation/do_nothing_plugin/package.xml +++ b/simulation/do_nothing_plugin/package.xml @@ -2,7 +2,7 @@ do_nothing_plugin - 3.5.3 + 3.5.4 Behavior plugin for do nothing Masaya Kataoka Apache 2.0 diff --git a/simulation/simple_sensor_simulator/CHANGELOG.rst b/simulation/simple_sensor_simulator/CHANGELOG.rst index 5e89dfec737..13d459b31ec 100644 --- a/simulation/simple_sensor_simulator/CHANGELOG.rst +++ b/simulation/simple_sensor_simulator/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package simple_sensor_simulator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.4 (2024-08-26) +------------------ +* Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build +* Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build +* Merge remote-tracking branch 'origin/master' into feature/use_workflow_dispatch_in_docker_build +* Merge remote-tracking branch 'origin/master' into feature/trigger_docker_build_by_tag +* Contributors: Masaya Kataoka + 3.5.3 (2024-08-26) ------------------ * Merge branch 'master' into RJD-1278/traffic_simulator-update diff --git a/simulation/simple_sensor_simulator/package.xml b/simulation/simple_sensor_simulator/package.xml index b6c835fe1f7..76c52cbb8ff 100644 --- a/simulation/simple_sensor_simulator/package.xml +++ b/simulation/simple_sensor_simulator/package.xml @@ -1,7 +1,7 @@ simple_sensor_simulator - 3.5.3 + 3.5.4 simple_sensor_simulator package masaya kataoka diff --git a/simulation/simulation_interface/CHANGELOG.rst b/simulation/simulation_interface/CHANGELOG.rst index 6f77e285edf..aceae32f4e6 100644 --- a/simulation/simulation_interface/CHANGELOG.rst +++ b/simulation/simulation_interface/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package simulation_interface * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.4 (2024-08-26) +------------------ +* Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build +* Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build +* Merge remote-tracking branch 'origin/master' into feature/use_workflow_dispatch_in_docker_build +* Merge remote-tracking branch 'origin/master' into feature/trigger_docker_build_by_tag +* Contributors: Masaya Kataoka + 3.5.3 (2024-08-26) ------------------ * Merge branch 'master' into RJD-1278/traffic_simulator-update diff --git a/simulation/simulation_interface/package.xml b/simulation/simulation_interface/package.xml index ccae6e66df8..84aa025158e 100644 --- a/simulation/simulation_interface/package.xml +++ b/simulation/simulation_interface/package.xml @@ -2,7 +2,7 @@ simulation_interface - 3.5.3 + 3.5.4 packages to define interface between simulator and scenario interpreter Masaya Kataoka Apache License 2.0 diff --git a/simulation/traffic_simulator/CHANGELOG.rst b/simulation/traffic_simulator/CHANGELOG.rst index 66424413e29..00755cffd6b 100644 --- a/simulation/traffic_simulator/CHANGELOG.rst +++ b/simulation/traffic_simulator/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package traffic_simulator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.4 (2024-08-26) +------------------ +* Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build +* Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build +* Merge remote-tracking branch 'origin/master' into feature/use_workflow_dispatch_in_docker_build +* Merge remote-tracking branch 'origin/master' into feature/trigger_docker_build_by_tag +* Contributors: Masaya Kataoka + 3.5.3 (2024-08-26) ------------------ * Merge pull request `#1340 `_ from tier4/RJD-1278/traffic_simulator-update diff --git a/simulation/traffic_simulator/package.xml b/simulation/traffic_simulator/package.xml index 871586b1346..c3d2af6d430 100644 --- a/simulation/traffic_simulator/package.xml +++ b/simulation/traffic_simulator/package.xml @@ -1,7 +1,7 @@ traffic_simulator - 3.5.3 + 3.5.4 control traffic flow masaya kataoka diff --git a/simulation/traffic_simulator_msgs/CHANGELOG.rst b/simulation/traffic_simulator_msgs/CHANGELOG.rst index dec262db986..77cd19e3c59 100644 --- a/simulation/traffic_simulator_msgs/CHANGELOG.rst +++ b/simulation/traffic_simulator_msgs/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package openscenario_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.4 (2024-08-26) +------------------ +* Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build +* Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build +* Merge remote-tracking branch 'origin/master' into feature/use_workflow_dispatch_in_docker_build +* Merge remote-tracking branch 'origin/master' into feature/trigger_docker_build_by_tag +* Contributors: Masaya Kataoka + 3.5.3 (2024-08-26) ------------------ * Merge branch 'master' into RJD-1278/traffic_simulator-update diff --git a/simulation/traffic_simulator_msgs/package.xml b/simulation/traffic_simulator_msgs/package.xml index ecb075268f2..ac5e3f83550 100644 --- a/simulation/traffic_simulator_msgs/package.xml +++ b/simulation/traffic_simulator_msgs/package.xml @@ -2,7 +2,7 @@ traffic_simulator_msgs - 3.5.3 + 3.5.4 ROS messages for openscenario Masaya Kataoka Apache License 2.0 diff --git a/test_runner/random_test_runner/CHANGELOG.rst b/test_runner/random_test_runner/CHANGELOG.rst index 35edaec6f7d..c1cb5787edd 100644 --- a/test_runner/random_test_runner/CHANGELOG.rst +++ b/test_runner/random_test_runner/CHANGELOG.rst @@ -21,6 +21,15 @@ Changelog for package random_test_runner * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.4 (2024-08-26) +------------------ +* Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build +* Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build +* Merge remote-tracking branch 'origin/master' into feature/use_workflow_dispatch_in_docker_build +* Merge remote-tracking branch 'origin/master' into feature/trigger_docker_build_by_tag +* remove \n +* Contributors: Masaya Kataoka + 3.5.3 (2024-08-26) ------------------ * Merge branch 'master' into RJD-1278/traffic_simulator-update diff --git a/test_runner/random_test_runner/package.xml b/test_runner/random_test_runner/package.xml index a95f5ee6675..88e9d090a7f 100644 --- a/test_runner/random_test_runner/package.xml +++ b/test_runner/random_test_runner/package.xml @@ -2,7 +2,7 @@ random_test_runner - 3.5.3 + 3.5.4 Random behavior test runner piotr-zyskowski-rai Apache License 2.0 diff --git a/test_runner/scenario_test_runner/CHANGELOG.rst b/test_runner/scenario_test_runner/CHANGELOG.rst index 6f6125ce848..0bcaa51945b 100644 --- a/test_runner/scenario_test_runner/CHANGELOG.rst +++ b/test_runner/scenario_test_runner/CHANGELOG.rst @@ -35,6 +35,14 @@ Changelog for package scenario_test_runner * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.4 (2024-08-26) +------------------ +* Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build +* Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build +* Merge remote-tracking branch 'origin/master' into feature/use_workflow_dispatch_in_docker_build +* Merge remote-tracking branch 'origin/master' into feature/trigger_docker_build_by_tag +* Contributors: Masaya Kataoka + 3.5.3 (2024-08-26) ------------------ * Merge branch 'master' into RJD-1278/traffic_simulator-update diff --git a/test_runner/scenario_test_runner/package.xml b/test_runner/scenario_test_runner/package.xml index bf3ff00d3ed..66278236c94 100644 --- a/test_runner/scenario_test_runner/package.xml +++ b/test_runner/scenario_test_runner/package.xml @@ -2,7 +2,7 @@ scenario_test_runner - 3.5.3 + 3.5.4 scenario test runner package Tatsuya Yamasaki Apache License 2.0 From b136c8429d6ca99c0179e3fc14f19f679c6914d5 Mon Sep 17 00:00:00 2001 From: Release Bot Date: Tue, 27 Aug 2024 02:20:46 +0000 Subject: [PATCH 181/304] Bump version of scenario_simulator_v2 from version 3.5.4 to version 3.5.5 --- common/math/arithmetic/CHANGELOG.rst | 8 ++++++++ common/math/arithmetic/package.xml | 2 +- common/math/geometry/CHANGELOG.rst | 8 ++++++++ common/math/geometry/package.xml | 2 +- common/scenario_simulator_exception/CHANGELOG.rst | 8 ++++++++ common/scenario_simulator_exception/package.xml | 2 +- common/simple_junit/CHANGELOG.rst | 8 ++++++++ common/simple_junit/package.xml | 2 +- common/status_monitor/CHANGELOG.rst | 8 ++++++++ common/status_monitor/package.xml | 2 +- external/concealer/CHANGELOG.rst | 8 ++++++++ external/concealer/package.xml | 2 +- external/embree_vendor/CHANGELOG.rst | 8 ++++++++ external/embree_vendor/package.xml | 2 +- map/kashiwanoha_map/CHANGELOG.rst | 8 ++++++++ map/kashiwanoha_map/package.xml | 2 +- map/simple_cross_map/CHANGELOG.rst | 8 ++++++++ map/simple_cross_map/package.xml | 2 +- mock/cpp_mock_scenarios/CHANGELOG.rst | 8 ++++++++ mock/cpp_mock_scenarios/package.xml | 2 +- .../openscenario_experimental_catalog/CHANGELOG.rst | 8 ++++++++ .../openscenario_experimental_catalog/package.xml | 2 +- openscenario/openscenario_interpreter/CHANGELOG.rst | 8 ++++++++ openscenario/openscenario_interpreter/package.xml | 2 +- .../openscenario_interpreter_example/CHANGELOG.rst | 8 ++++++++ .../openscenario_interpreter_example/package.xml | 2 +- .../openscenario_interpreter_msgs/CHANGELOG.rst | 8 ++++++++ .../openscenario_interpreter_msgs/package.xml | 2 +- openscenario/openscenario_preprocessor/CHANGELOG.rst | 8 ++++++++ openscenario/openscenario_preprocessor/package.xml | 2 +- .../openscenario_preprocessor_msgs/CHANGELOG.rst | 8 ++++++++ .../openscenario_preprocessor_msgs/package.xml | 2 +- openscenario/openscenario_utility/CHANGELOG.rst | 8 ++++++++ openscenario/openscenario_utility/package.xml | 2 +- openscenario/openscenario_validator/CHANGELOG.rst | 8 ++++++++ openscenario/openscenario_validator/package.xml | 2 +- .../openscenario_visualization/CHANGELOG.rst | 8 ++++++++ rviz_plugins/openscenario_visualization/package.xml | 2 +- .../CHANGELOG.rst | 8 ++++++++ .../real_time_factor_control_rviz_plugin/package.xml | 2 +- scenario_simulator_v2/CHANGELOG.rst | 8 ++++++++ scenario_simulator_v2/package.xml | 2 +- simulation/behavior_tree_plugin/CHANGELOG.rst | 8 ++++++++ simulation/behavior_tree_plugin/package.xml | 2 +- simulation/do_nothing_plugin/CHANGELOG.rst | 8 ++++++++ simulation/do_nothing_plugin/package.xml | 2 +- simulation/simple_sensor_simulator/CHANGELOG.rst | 8 ++++++++ simulation/simple_sensor_simulator/package.xml | 2 +- simulation/simulation_interface/CHANGELOG.rst | 8 ++++++++ simulation/simulation_interface/package.xml | 2 +- simulation/traffic_simulator/CHANGELOG.rst | 12 ++++++++++++ simulation/traffic_simulator/package.xml | 2 +- simulation/traffic_simulator_msgs/CHANGELOG.rst | 8 ++++++++ simulation/traffic_simulator_msgs/package.xml | 2 +- test_runner/random_test_runner/CHANGELOG.rst | 8 ++++++++ test_runner/random_test_runner/package.xml | 2 +- test_runner/scenario_test_runner/CHANGELOG.rst | 11 +++++++++++ test_runner/scenario_test_runner/package.xml | 2 +- 58 files changed, 268 insertions(+), 29 deletions(-) diff --git a/common/math/arithmetic/CHANGELOG.rst b/common/math/arithmetic/CHANGELOG.rst index 467c47fe864..8d95f2507bf 100644 --- a/common/math/arithmetic/CHANGELOG.rst +++ b/common/math/arithmetic/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package arithmetic * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.5 (2024-08-27) +------------------ +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Contributors: Kotaro Yoshimoto + 3.5.4 (2024-08-26) ------------------ * Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build diff --git a/common/math/arithmetic/package.xml b/common/math/arithmetic/package.xml index 46b7785af61..80822986ba2 100644 --- a/common/math/arithmetic/package.xml +++ b/common/math/arithmetic/package.xml @@ -2,7 +2,7 @@ arithmetic - 3.5.4 + 3.5.5 arithmetic library for scenario_simulator_v2 Tatsuya Yamasaki Apache License 2.0 diff --git a/common/math/geometry/CHANGELOG.rst b/common/math/geometry/CHANGELOG.rst index 89ccf45a518..8d6f6602bf9 100644 --- a/common/math/geometry/CHANGELOG.rst +++ b/common/math/geometry/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package geometry * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.5 (2024-08-27) +------------------ +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Contributors: Kotaro Yoshimoto + 3.5.4 (2024-08-26) ------------------ * Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build diff --git a/common/math/geometry/package.xml b/common/math/geometry/package.xml index f1fffa30b8d..ab400ec03a7 100644 --- a/common/math/geometry/package.xml +++ b/common/math/geometry/package.xml @@ -2,7 +2,7 @@ geometry - 3.5.4 + 3.5.5 geometry math library for scenario_simulator_v2 application Masaya Kataoka Apache License 2.0 diff --git a/common/scenario_simulator_exception/CHANGELOG.rst b/common/scenario_simulator_exception/CHANGELOG.rst index 1b43946e6b9..63833bad90b 100644 --- a/common/scenario_simulator_exception/CHANGELOG.rst +++ b/common/scenario_simulator_exception/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package scenario_simulator_exception * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.5 (2024-08-27) +------------------ +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Contributors: Kotaro Yoshimoto + 3.5.4 (2024-08-26) ------------------ * Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build diff --git a/common/scenario_simulator_exception/package.xml b/common/scenario_simulator_exception/package.xml index 79e3c5275e0..3ef06abc051 100644 --- a/common/scenario_simulator_exception/package.xml +++ b/common/scenario_simulator_exception/package.xml @@ -2,7 +2,7 @@ scenario_simulator_exception - 3.5.4 + 3.5.5 Exception types for scenario simulator Tatsuya Yamasaki Apache License 2.0 diff --git a/common/simple_junit/CHANGELOG.rst b/common/simple_junit/CHANGELOG.rst index c1e0ed3d0b7..4e42bf48f5b 100644 --- a/common/simple_junit/CHANGELOG.rst +++ b/common/simple_junit/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package junit_exporter * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.5 (2024-08-27) +------------------ +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Contributors: Kotaro Yoshimoto + 3.5.4 (2024-08-26) ------------------ * Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build diff --git a/common/simple_junit/package.xml b/common/simple_junit/package.xml index bb9246a5c99..208e16e125e 100644 --- a/common/simple_junit/package.xml +++ b/common/simple_junit/package.xml @@ -2,7 +2,7 @@ simple_junit - 3.5.4 + 3.5.5 Lightweight JUnit library for ROS 2 Masaya Kataoka Tatsuya Yamasaki diff --git a/common/status_monitor/CHANGELOG.rst b/common/status_monitor/CHANGELOG.rst index 60671a9b95e..ef178805641 100644 --- a/common/status_monitor/CHANGELOG.rst +++ b/common/status_monitor/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package status_monitor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.5 (2024-08-27) +------------------ +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Contributors: Kotaro Yoshimoto + 3.5.4 (2024-08-26) ------------------ * Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build diff --git a/common/status_monitor/package.xml b/common/status_monitor/package.xml index 31549fef4d0..1ea1e1962d5 100644 --- a/common/status_monitor/package.xml +++ b/common/status_monitor/package.xml @@ -2,7 +2,7 @@ status_monitor - 3.5.4 + 3.5.5 none Tatsuya Yamasaki Apache License 2.0 diff --git a/external/concealer/CHANGELOG.rst b/external/concealer/CHANGELOG.rst index fbbee447a43..496b5cc1478 100644 --- a/external/concealer/CHANGELOG.rst +++ b/external/concealer/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package concealer * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.5 (2024-08-27) +------------------ +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Contributors: Kotaro Yoshimoto + 3.5.4 (2024-08-26) ------------------ * Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build diff --git a/external/concealer/package.xml b/external/concealer/package.xml index f72f33f6f00..f9d1b400e66 100644 --- a/external/concealer/package.xml +++ b/external/concealer/package.xml @@ -2,7 +2,7 @@ concealer - 3.5.4 + 3.5.5 Provides a class 'Autoware' to conceal miscellaneous things to simplify Autoware management of the simulator. Tatsuya Yamasaki Apache License 2.0 diff --git a/external/embree_vendor/CHANGELOG.rst b/external/embree_vendor/CHANGELOG.rst index 8e5adc53cc8..8500522b236 100644 --- a/external/embree_vendor/CHANGELOG.rst +++ b/external/embree_vendor/CHANGELOG.rst @@ -24,6 +24,14 @@ Changelog for package embree_vendor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.5 (2024-08-27) +------------------ +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Contributors: Kotaro Yoshimoto + 3.5.4 (2024-08-26) ------------------ * Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build diff --git a/external/embree_vendor/package.xml b/external/embree_vendor/package.xml index 5aceb9da6d6..c190c5d3bb9 100644 --- a/external/embree_vendor/package.xml +++ b/external/embree_vendor/package.xml @@ -2,7 +2,7 @@ embree_vendor - 3.5.4 + 3.5.5 vendor packages for intel raytracing kernel library masaya Apache 2.0 diff --git a/map/kashiwanoha_map/CHANGELOG.rst b/map/kashiwanoha_map/CHANGELOG.rst index 012ff0e86d8..7356e061c79 100644 --- a/map/kashiwanoha_map/CHANGELOG.rst +++ b/map/kashiwanoha_map/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package kashiwanoha_map * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.5 (2024-08-27) +------------------ +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Contributors: Kotaro Yoshimoto + 3.5.4 (2024-08-26) ------------------ * Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build diff --git a/map/kashiwanoha_map/package.xml b/map/kashiwanoha_map/package.xml index 71f5521b4d3..6ca6d218b1b 100644 --- a/map/kashiwanoha_map/package.xml +++ b/map/kashiwanoha_map/package.xml @@ -2,7 +2,7 @@ kashiwanoha_map - 3.5.4 + 3.5.5 map package for kashiwanoha Masaya Kataoka Apache License 2.0 diff --git a/map/simple_cross_map/CHANGELOG.rst b/map/simple_cross_map/CHANGELOG.rst index 76cb3e0ffde..506f5b401e8 100644 --- a/map/simple_cross_map/CHANGELOG.rst +++ b/map/simple_cross_map/CHANGELOG.rst @@ -9,6 +9,14 @@ Changelog for package simple_cross_map * Merge branch 'master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.5 (2024-08-27) +------------------ +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Contributors: Kotaro Yoshimoto + 3.5.4 (2024-08-26) ------------------ * Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build diff --git a/map/simple_cross_map/package.xml b/map/simple_cross_map/package.xml index ae69291a68e..916ccdb0f93 100644 --- a/map/simple_cross_map/package.xml +++ b/map/simple_cross_map/package.xml @@ -2,7 +2,7 @@ simple_cross_map - 3.5.4 + 3.5.5 map package for simple cross Masaya Kataoka Apache License 2.0 diff --git a/mock/cpp_mock_scenarios/CHANGELOG.rst b/mock/cpp_mock_scenarios/CHANGELOG.rst index 2388ab61f61..2ad6a3324e6 100644 --- a/mock/cpp_mock_scenarios/CHANGELOG.rst +++ b/mock/cpp_mock_scenarios/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package cpp_mock_scenarios * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.5 (2024-08-27) +------------------ +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Contributors: Kotaro Yoshimoto + 3.5.4 (2024-08-26) ------------------ * Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build diff --git a/mock/cpp_mock_scenarios/package.xml b/mock/cpp_mock_scenarios/package.xml index 5aa027dabfa..51337dcd9d9 100644 --- a/mock/cpp_mock_scenarios/package.xml +++ b/mock/cpp_mock_scenarios/package.xml @@ -2,7 +2,7 @@ cpp_mock_scenarios - 3.5.4 + 3.5.5 C++ mock scenarios masaya Apache License 2.0 diff --git a/openscenario/openscenario_experimental_catalog/CHANGELOG.rst b/openscenario/openscenario_experimental_catalog/CHANGELOG.rst index b93ba4c67dc..83ddd710daf 100644 --- a/openscenario/openscenario_experimental_catalog/CHANGELOG.rst +++ b/openscenario/openscenario_experimental_catalog/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package openscenario_experimental_catalog * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.5 (2024-08-27) +------------------ +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Contributors: Kotaro Yoshimoto + 3.5.4 (2024-08-26) ------------------ * Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build diff --git a/openscenario/openscenario_experimental_catalog/package.xml b/openscenario/openscenario_experimental_catalog/package.xml index 52579a5a314..9d0beec7acd 100644 --- a/openscenario/openscenario_experimental_catalog/package.xml +++ b/openscenario/openscenario_experimental_catalog/package.xml @@ -2,7 +2,7 @@ openscenario_experimental_catalog - 3.5.4 + 3.5.5 TIER IV experimental catalogs for OpenSCENARIO Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter/CHANGELOG.rst b/openscenario/openscenario_interpreter/CHANGELOG.rst index 942b38865ca..7f9d432ec0b 100644 --- a/openscenario/openscenario_interpreter/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter/CHANGELOG.rst @@ -32,6 +32,14 @@ Changelog for package openscenario_interpreter * add publish_empty_context parameter * Contributors: Masaya Kataoka +3.5.5 (2024-08-27) +------------------ +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Contributors: Kotaro Yoshimoto + 3.5.4 (2024-08-26) ------------------ * Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build diff --git a/openscenario/openscenario_interpreter/package.xml b/openscenario/openscenario_interpreter/package.xml index bddb03798d1..e3675d53fe6 100644 --- a/openscenario/openscenario_interpreter/package.xml +++ b/openscenario/openscenario_interpreter/package.xml @@ -2,7 +2,7 @@ openscenario_interpreter - 3.5.4 + 3.5.5 OpenSCENARIO 1.2.0 interpreter package for Autoware Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter_example/CHANGELOG.rst b/openscenario/openscenario_interpreter_example/CHANGELOG.rst index e49baa04a82..19793ec1e0c 100644 --- a/openscenario/openscenario_interpreter_example/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter_example/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package openscenario_interpreter_example * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.5 (2024-08-27) +------------------ +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Contributors: Kotaro Yoshimoto + 3.5.4 (2024-08-26) ------------------ * Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build diff --git a/openscenario/openscenario_interpreter_example/package.xml b/openscenario/openscenario_interpreter_example/package.xml index b6dfae61436..cc446b72940 100644 --- a/openscenario/openscenario_interpreter_example/package.xml +++ b/openscenario/openscenario_interpreter_example/package.xml @@ -3,7 +3,7 @@ openscenario_interpreter_example - 3.5.4 + 3.5.5 Examples for some TIER IV OpenSCENARIO Interpreter's features Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst b/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst index 0982794c22b..1d18fc6d4eb 100644 --- a/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package openscenario_interpreter_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.5 (2024-08-27) +------------------ +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Contributors: Kotaro Yoshimoto + 3.5.4 (2024-08-26) ------------------ * Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build diff --git a/openscenario/openscenario_interpreter_msgs/package.xml b/openscenario/openscenario_interpreter_msgs/package.xml index 051f9bf690f..991f3c93ce0 100644 --- a/openscenario/openscenario_interpreter_msgs/package.xml +++ b/openscenario/openscenario_interpreter_msgs/package.xml @@ -2,7 +2,7 @@ openscenario_interpreter_msgs - 3.5.4 + 3.5.5 ROS message types for package openscenario_interpreter Yamasaki Tatsuya Apache License 2.0 diff --git a/openscenario/openscenario_preprocessor/CHANGELOG.rst b/openscenario/openscenario_preprocessor/CHANGELOG.rst index 26450c6c221..3140170a4b2 100644 --- a/openscenario/openscenario_preprocessor/CHANGELOG.rst +++ b/openscenario/openscenario_preprocessor/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package openscenario_preprocessor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.5 (2024-08-27) +------------------ +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Contributors: Kotaro Yoshimoto + 3.5.4 (2024-08-26) ------------------ * Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build diff --git a/openscenario/openscenario_preprocessor/package.xml b/openscenario/openscenario_preprocessor/package.xml index 883de3e4019..055c3084485 100644 --- a/openscenario/openscenario_preprocessor/package.xml +++ b/openscenario/openscenario_preprocessor/package.xml @@ -3,7 +3,7 @@ openscenario_preprocessor - 3.5.4 + 3.5.5 Example package for TIER IV OpenSCENARIO Interpreter Kotaro Yoshimoto Apache License 2.0 diff --git a/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst b/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst index daad6ed5a0c..51e7aac4ed4 100644 --- a/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst +++ b/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package openscenario_preprocessor_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.5 (2024-08-27) +------------------ +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Contributors: Kotaro Yoshimoto + 3.5.4 (2024-08-26) ------------------ * Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build diff --git a/openscenario/openscenario_preprocessor_msgs/package.xml b/openscenario/openscenario_preprocessor_msgs/package.xml index 4137dc03397..cc559bbb190 100644 --- a/openscenario/openscenario_preprocessor_msgs/package.xml +++ b/openscenario/openscenario_preprocessor_msgs/package.xml @@ -2,7 +2,7 @@ openscenario_preprocessor_msgs - 3.5.4 + 3.5.5 ROS message types for package openscenario_preprocessor Kotaro Yoshimoto Apache License 2.0 diff --git a/openscenario/openscenario_utility/CHANGELOG.rst b/openscenario/openscenario_utility/CHANGELOG.rst index 021f3c18dfb..9231435207e 100644 --- a/openscenario/openscenario_utility/CHANGELOG.rst +++ b/openscenario/openscenario_utility/CHANGELOG.rst @@ -24,6 +24,14 @@ Changelog for package openscenario_utility * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.5 (2024-08-27) +------------------ +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Contributors: Kotaro Yoshimoto + 3.5.4 (2024-08-26) ------------------ * Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build diff --git a/openscenario/openscenario_utility/package.xml b/openscenario/openscenario_utility/package.xml index 94fe00e3f49..38e808f3336 100644 --- a/openscenario/openscenario_utility/package.xml +++ b/openscenario/openscenario_utility/package.xml @@ -2,7 +2,7 @@ openscenario_utility - 3.5.4 + 3.5.5 Utility tools for ASAM OpenSCENARIO 1.2.0 Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_validator/CHANGELOG.rst b/openscenario/openscenario_validator/CHANGELOG.rst index 37bbdaeef80..f3d7e494552 100644 --- a/openscenario/openscenario_validator/CHANGELOG.rst +++ b/openscenario/openscenario_validator/CHANGELOG.rst @@ -10,6 +10,14 @@ Changelog for package openscenario_validator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.5 (2024-08-27) +------------------ +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Contributors: Kotaro Yoshimoto + 3.5.4 (2024-08-26) ------------------ * Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build diff --git a/openscenario/openscenario_validator/package.xml b/openscenario/openscenario_validator/package.xml index 804c7023e43..935ec6e7754 100644 --- a/openscenario/openscenario_validator/package.xml +++ b/openscenario/openscenario_validator/package.xml @@ -2,7 +2,7 @@ openscenario_validator - 3.5.4 + 3.5.5 Validator for OpenSCENARIO 1.3 Kotaro Yoshimoto Apache License 2.0 diff --git a/rviz_plugins/openscenario_visualization/CHANGELOG.rst b/rviz_plugins/openscenario_visualization/CHANGELOG.rst index b8cbe34be33..6ae1cf64306 100644 --- a/rviz_plugins/openscenario_visualization/CHANGELOG.rst +++ b/rviz_plugins/openscenario_visualization/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package openscenario_visualization * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.5 (2024-08-27) +------------------ +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Contributors: Kotaro Yoshimoto + 3.5.4 (2024-08-26) ------------------ * Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build diff --git a/rviz_plugins/openscenario_visualization/package.xml b/rviz_plugins/openscenario_visualization/package.xml index f8f21ccb236..169d8665dd2 100644 --- a/rviz_plugins/openscenario_visualization/package.xml +++ b/rviz_plugins/openscenario_visualization/package.xml @@ -2,7 +2,7 @@ openscenario_visualization - 3.5.4 + 3.5.5 Visualization tools for simulation results Masaya Kataoka Kyoichi Sugahara diff --git a/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst b/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst index dc7ebe4370a..7beaae2ee0b 100644 --- a/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst +++ b/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package real_time_factor_control_rviz_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.5 (2024-08-27) +------------------ +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Contributors: Kotaro Yoshimoto + 3.5.4 (2024-08-26) ------------------ * Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build diff --git a/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml b/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml index bafebc256bf..b6e1e8d7902 100644 --- a/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml +++ b/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml @@ -2,7 +2,7 @@ real_time_factor_control_rviz_plugin - 3.5.4 + 3.5.5 Slider controlling real time factor value. Paweł Lech Apache License 2.0 diff --git a/scenario_simulator_v2/CHANGELOG.rst b/scenario_simulator_v2/CHANGELOG.rst index fbde618feba..c110372ee31 100644 --- a/scenario_simulator_v2/CHANGELOG.rst +++ b/scenario_simulator_v2/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package scenario_simulator_v2 * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.5 (2024-08-27) +------------------ +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Contributors: Kotaro Yoshimoto + 3.5.4 (2024-08-26) ------------------ * Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build diff --git a/scenario_simulator_v2/package.xml b/scenario_simulator_v2/package.xml index d509f074439..1e3b0acf02c 100644 --- a/scenario_simulator_v2/package.xml +++ b/scenario_simulator_v2/package.xml @@ -2,7 +2,7 @@ scenario_simulator_v2 - 3.5.4 + 3.5.5 scenario testing framework for Autoware Masaya Kataoka Apache License 2.0 diff --git a/simulation/behavior_tree_plugin/CHANGELOG.rst b/simulation/behavior_tree_plugin/CHANGELOG.rst index 46cb9fc6eb3..201793a253b 100644 --- a/simulation/behavior_tree_plugin/CHANGELOG.rst +++ b/simulation/behavior_tree_plugin/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package behavior_tree_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.5 (2024-08-27) +------------------ +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Contributors: Kotaro Yoshimoto + 3.5.4 (2024-08-26) ------------------ * Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build diff --git a/simulation/behavior_tree_plugin/package.xml b/simulation/behavior_tree_plugin/package.xml index d8aa1397a6e..89b5ac53c57 100644 --- a/simulation/behavior_tree_plugin/package.xml +++ b/simulation/behavior_tree_plugin/package.xml @@ -2,7 +2,7 @@ behavior_tree_plugin - 3.5.4 + 3.5.5 Behavior tree plugin for traffic_simulator masaya Apache 2.0 diff --git a/simulation/do_nothing_plugin/CHANGELOG.rst b/simulation/do_nothing_plugin/CHANGELOG.rst index c69dad60f58..bce71b331ee 100644 --- a/simulation/do_nothing_plugin/CHANGELOG.rst +++ b/simulation/do_nothing_plugin/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package do_nothing_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.5 (2024-08-27) +------------------ +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Contributors: Kotaro Yoshimoto + 3.5.4 (2024-08-26) ------------------ * Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build diff --git a/simulation/do_nothing_plugin/package.xml b/simulation/do_nothing_plugin/package.xml index 8b93d7aaec0..ce8938e06e9 100644 --- a/simulation/do_nothing_plugin/package.xml +++ b/simulation/do_nothing_plugin/package.xml @@ -2,7 +2,7 @@ do_nothing_plugin - 3.5.4 + 3.5.5 Behavior plugin for do nothing Masaya Kataoka Apache 2.0 diff --git a/simulation/simple_sensor_simulator/CHANGELOG.rst b/simulation/simple_sensor_simulator/CHANGELOG.rst index 13d459b31ec..0a6bd102f62 100644 --- a/simulation/simple_sensor_simulator/CHANGELOG.rst +++ b/simulation/simple_sensor_simulator/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package simple_sensor_simulator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.5 (2024-08-27) +------------------ +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Contributors: Kotaro Yoshimoto + 3.5.4 (2024-08-26) ------------------ * Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build diff --git a/simulation/simple_sensor_simulator/package.xml b/simulation/simple_sensor_simulator/package.xml index 76c52cbb8ff..428a93898de 100644 --- a/simulation/simple_sensor_simulator/package.xml +++ b/simulation/simple_sensor_simulator/package.xml @@ -1,7 +1,7 @@ simple_sensor_simulator - 3.5.4 + 3.5.5 simple_sensor_simulator package masaya kataoka diff --git a/simulation/simulation_interface/CHANGELOG.rst b/simulation/simulation_interface/CHANGELOG.rst index aceae32f4e6..8627664b6d1 100644 --- a/simulation/simulation_interface/CHANGELOG.rst +++ b/simulation/simulation_interface/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package simulation_interface * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.5 (2024-08-27) +------------------ +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Contributors: Kotaro Yoshimoto + 3.5.4 (2024-08-26) ------------------ * Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build diff --git a/simulation/simulation_interface/package.xml b/simulation/simulation_interface/package.xml index 84aa025158e..adc700b1520 100644 --- a/simulation/simulation_interface/package.xml +++ b/simulation/simulation_interface/package.xml @@ -2,7 +2,7 @@ simulation_interface - 3.5.4 + 3.5.5 packages to define interface between simulator and scenario interpreter Masaya Kataoka Apache License 2.0 diff --git a/simulation/traffic_simulator/CHANGELOG.rst b/simulation/traffic_simulator/CHANGELOG.rst index 00755cffd6b..779539af957 100644 --- a/simulation/traffic_simulator/CHANGELOG.rst +++ b/simulation/traffic_simulator/CHANGELOG.rst @@ -21,6 +21,18 @@ Changelog for package traffic_simulator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.5 (2024-08-27) +------------------ +* Merge pull request `#1348 `_ from tier4/fix/distance-with-lane-change + Fix longitudinal dintance calculation with lane-change in `HdMapUtils::getLongitudinalDistance` +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* chore: add a test for corner case +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* fix: longitudinal calculation with lane-change +* Contributors: Kotaro Yoshimoto, Masaya Kataoka + 3.5.4 (2024-08-26) ------------------ * Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build diff --git a/simulation/traffic_simulator/package.xml b/simulation/traffic_simulator/package.xml index 68d94caf6fc..696eb1f705e 100644 --- a/simulation/traffic_simulator/package.xml +++ b/simulation/traffic_simulator/package.xml @@ -1,7 +1,7 @@ traffic_simulator - 3.5.4 + 3.5.5 control traffic flow masaya kataoka diff --git a/simulation/traffic_simulator_msgs/CHANGELOG.rst b/simulation/traffic_simulator_msgs/CHANGELOG.rst index 77cd19e3c59..61a5fd96f0e 100644 --- a/simulation/traffic_simulator_msgs/CHANGELOG.rst +++ b/simulation/traffic_simulator_msgs/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package openscenario_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.5 (2024-08-27) +------------------ +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Contributors: Kotaro Yoshimoto + 3.5.4 (2024-08-26) ------------------ * Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build diff --git a/simulation/traffic_simulator_msgs/package.xml b/simulation/traffic_simulator_msgs/package.xml index ac5e3f83550..2e37ee59a73 100644 --- a/simulation/traffic_simulator_msgs/package.xml +++ b/simulation/traffic_simulator_msgs/package.xml @@ -2,7 +2,7 @@ traffic_simulator_msgs - 3.5.4 + 3.5.5 ROS messages for openscenario Masaya Kataoka Apache License 2.0 diff --git a/test_runner/random_test_runner/CHANGELOG.rst b/test_runner/random_test_runner/CHANGELOG.rst index c1cb5787edd..a913aa6c3e4 100644 --- a/test_runner/random_test_runner/CHANGELOG.rst +++ b/test_runner/random_test_runner/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package random_test_runner * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.5 (2024-08-27) +------------------ +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Contributors: Kotaro Yoshimoto + 3.5.4 (2024-08-26) ------------------ * Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build diff --git a/test_runner/random_test_runner/package.xml b/test_runner/random_test_runner/package.xml index 88e9d090a7f..05192a782a7 100644 --- a/test_runner/random_test_runner/package.xml +++ b/test_runner/random_test_runner/package.xml @@ -2,7 +2,7 @@ random_test_runner - 3.5.4 + 3.5.5 Random behavior test runner piotr-zyskowski-rai Apache License 2.0 diff --git a/test_runner/scenario_test_runner/CHANGELOG.rst b/test_runner/scenario_test_runner/CHANGELOG.rst index 0bcaa51945b..01a260b2f93 100644 --- a/test_runner/scenario_test_runner/CHANGELOG.rst +++ b/test_runner/scenario_test_runner/CHANGELOG.rst @@ -35,6 +35,17 @@ Changelog for package scenario_test_runner * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +3.5.5 (2024-08-27) +------------------ +* Merge pull request `#1348 `_ from tier4/fix/distance-with-lane-change + Fix longitudinal dintance calculation with lane-change in `HdMapUtils::getLongitudinalDistance` +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* Merge branch 'master' into fix/distance-with-lane-change +* chore: add corner case to fix into a scenario +* Contributors: Kotaro Yoshimoto, Masaya Kataoka + 3.5.4 (2024-08-26) ------------------ * Merge branch 'master' into feature/use_workflow_dispatch_in_docker_build diff --git a/test_runner/scenario_test_runner/package.xml b/test_runner/scenario_test_runner/package.xml index 66278236c94..803393bef42 100644 --- a/test_runner/scenario_test_runner/package.xml +++ b/test_runner/scenario_test_runner/package.xml @@ -2,7 +2,7 @@ scenario_test_runner - 3.5.4 + 3.5.5 scenario test runner package Tatsuya Yamasaki Apache License 2.0 From 7fad45b19f8766a9498ade2694f0292c755233b9 Mon Sep 17 00:00:00 2001 From: Masaya Kataoka Date: Tue, 27 Aug 2024 12:18:44 +0900 Subject: [PATCH 182/304] add angular velocity / acceleration as z axis value Signed-off-by: Masaya Kataoka --- simulation/do_nothing_plugin/src/plugin.cpp | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/simulation/do_nothing_plugin/src/plugin.cpp b/simulation/do_nothing_plugin/src/plugin.cpp index 15ec1418b2d..7366a4d6c57 100644 --- a/simulation/do_nothing_plugin/src/plugin.cpp +++ b/simulation/do_nothing_plugin/src/plugin.cpp @@ -103,20 +103,21 @@ auto interpolateEntityStatusFromPolylineTrajectory( const double angular_velocity = math::geometry::convertQuaternionToEulerAngle( math::geometry::getRotation(v0.position.orientation, v1.position.orientation)) - .z; + .z / + (v1.time - v0.time); const auto angular_acceleration = (entity_status->getTwist().angular.x - angular_velocity) / (v1.time - v0.time); interpolated_entity_status.action_status.twist = geometry_msgs::build() .linear(geometry_msgs::build().x(linear_velocity).y(0).z(0)) - .angular(geometry_msgs::build().x(angular_velocity).y(0).z(0)); + .angular(geometry_msgs::build().x(0).y(0).z(angular_velocity)); interpolated_entity_status.action_status.accel = geometry_msgs::build() .linear( geometry_msgs::build().x(linear_acceleration).y(0).z(0)) .angular( - geometry_msgs::build().x(angular_acceleration).y(0).z(0)); + geometry_msgs::build().x(0).y(0).z(angular_acceleration)); interpolated_entity_status.action_status.linear_jerk = linear_jerk; return interpolated_entity_status; }; From 9c838f75089a3c1dd1e4c83babc273b01b07ba2d Mon Sep 17 00:00:00 2001 From: Release Bot Date: Tue, 27 Aug 2024 10:01:15 +0000 Subject: [PATCH 183/304] Bump version of scenario_simulator_v2 from version 3.5.5 to version 4.0.0 --- common/math/arithmetic/CHANGELOG.rst | 29 ++++++++ common/math/arithmetic/package.xml | 2 +- common/math/geometry/CHANGELOG.rst | 29 ++++++++ common/math/geometry/package.xml | 2 +- .../CHANGELOG.rst | 29 ++++++++ .../scenario_simulator_exception/package.xml | 2 +- common/simple_junit/CHANGELOG.rst | 29 ++++++++ common/simple_junit/package.xml | 2 +- common/status_monitor/CHANGELOG.rst | 29 ++++++++ common/status_monitor/package.xml | 2 +- external/concealer/CHANGELOG.rst | 29 ++++++++ external/concealer/package.xml | 2 +- external/embree_vendor/CHANGELOG.rst | 29 ++++++++ external/embree_vendor/package.xml | 2 +- map/kashiwanoha_map/CHANGELOG.rst | 29 ++++++++ map/kashiwanoha_map/package.xml | 2 +- map/simple_cross_map/CHANGELOG.rst | 17 +++++ map/simple_cross_map/package.xml | 2 +- mock/cpp_mock_scenarios/CHANGELOG.rst | 34 ++++++++++ mock/cpp_mock_scenarios/package.xml | 2 +- .../CHANGELOG.rst | 29 ++++++++ .../package.xml | 2 +- .../openscenario_interpreter/CHANGELOG.rst | 30 +++++++++ .../openscenario_interpreter/package.xml | 2 +- .../CHANGELOG.rst | 29 ++++++++ .../package.xml | 2 +- .../CHANGELOG.rst | 29 ++++++++ .../openscenario_interpreter_msgs/package.xml | 2 +- .../openscenario_preprocessor/CHANGELOG.rst | 29 ++++++++ .../openscenario_preprocessor/package.xml | 2 +- .../CHANGELOG.rst | 29 ++++++++ .../package.xml | 2 +- .../openscenario_utility/CHANGELOG.rst | 29 ++++++++ openscenario/openscenario_utility/package.xml | 2 +- .../openscenario_validator/CHANGELOG.rst | 28 ++++++++ .../openscenario_validator/package.xml | 2 +- .../openscenario_visualization/CHANGELOG.rst | 29 ++++++++ .../openscenario_visualization/package.xml | 2 +- .../CHANGELOG.rst | 29 ++++++++ .../package.xml | 2 +- scenario_simulator_v2/CHANGELOG.rst | 29 ++++++++ scenario_simulator_v2/package.xml | 2 +- simulation/behavior_tree_plugin/CHANGELOG.rst | 39 +++++++++++ simulation/behavior_tree_plugin/package.xml | 2 +- simulation/do_nothing_plugin/CHANGELOG.rst | 36 ++++++++++ simulation/do_nothing_plugin/package.xml | 2 +- .../simple_sensor_simulator/CHANGELOG.rst | 36 ++++++++++ .../simple_sensor_simulator/package.xml | 2 +- simulation/simulation_interface/CHANGELOG.rst | 33 ++++++++++ simulation/simulation_interface/package.xml | 2 +- simulation/traffic_simulator/CHANGELOG.rst | 66 +++++++++++++++++++ simulation/traffic_simulator/package.xml | 2 +- .../traffic_simulator_msgs/CHANGELOG.rst | 29 ++++++++ simulation/traffic_simulator_msgs/package.xml | 2 +- test_runner/random_test_runner/CHANGELOG.rst | 33 ++++++++++ test_runner/random_test_runner/package.xml | 2 +- .../scenario_test_runner/CHANGELOG.rst | 29 ++++++++ test_runner/scenario_test_runner/package.xml | 2 +- 58 files changed, 932 insertions(+), 29 deletions(-) diff --git a/common/math/arithmetic/CHANGELOG.rst b/common/math/arithmetic/CHANGELOG.rst index 8d95f2507bf..7ebc997dc1d 100644 --- a/common/math/arithmetic/CHANGELOG.rst +++ b/common/math/arithmetic/CHANGELOG.rst @@ -21,6 +21,35 @@ Changelog for package arithmetic * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.0 (2024-08-27) +------------------ +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' of https://github.com/tier4/scenario_simulator_v2 into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Contributors: DMoszynski, Dawid Moszynski, Dawid Moszyński, Mateusz Palczuk, Tatsuya Yamasaki + 3.5.5 (2024-08-27) ------------------ * Merge branch 'master' into fix/distance-with-lane-change diff --git a/common/math/arithmetic/package.xml b/common/math/arithmetic/package.xml index 80822986ba2..f36b46cbfda 100644 --- a/common/math/arithmetic/package.xml +++ b/common/math/arithmetic/package.xml @@ -2,7 +2,7 @@ arithmetic - 3.5.5 + 4.0.0 arithmetic library for scenario_simulator_v2 Tatsuya Yamasaki Apache License 2.0 diff --git a/common/math/geometry/CHANGELOG.rst b/common/math/geometry/CHANGELOG.rst index 8d6f6602bf9..5f3f3f94197 100644 --- a/common/math/geometry/CHANGELOG.rst +++ b/common/math/geometry/CHANGELOG.rst @@ -21,6 +21,35 @@ Changelog for package geometry * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.0 (2024-08-27) +------------------ +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' of https://github.com/tier4/scenario_simulator_v2 into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Contributors: DMoszynski, Dawid Moszynski, Dawid Moszyński, Mateusz Palczuk, Tatsuya Yamasaki + 3.5.5 (2024-08-27) ------------------ * Merge branch 'master' into fix/distance-with-lane-change diff --git a/common/math/geometry/package.xml b/common/math/geometry/package.xml index ab400ec03a7..2486fda3ffe 100644 --- a/common/math/geometry/package.xml +++ b/common/math/geometry/package.xml @@ -2,7 +2,7 @@ geometry - 3.5.5 + 4.0.0 geometry math library for scenario_simulator_v2 application Masaya Kataoka Apache License 2.0 diff --git a/common/scenario_simulator_exception/CHANGELOG.rst b/common/scenario_simulator_exception/CHANGELOG.rst index 63833bad90b..53df0993865 100644 --- a/common/scenario_simulator_exception/CHANGELOG.rst +++ b/common/scenario_simulator_exception/CHANGELOG.rst @@ -21,6 +21,35 @@ Changelog for package scenario_simulator_exception * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.0 (2024-08-27) +------------------ +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' of https://github.com/tier4/scenario_simulator_v2 into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Contributors: DMoszynski, Dawid Moszynski, Dawid Moszyński, Mateusz Palczuk, Tatsuya Yamasaki + 3.5.5 (2024-08-27) ------------------ * Merge branch 'master' into fix/distance-with-lane-change diff --git a/common/scenario_simulator_exception/package.xml b/common/scenario_simulator_exception/package.xml index 3ef06abc051..bf139e1ecd1 100644 --- a/common/scenario_simulator_exception/package.xml +++ b/common/scenario_simulator_exception/package.xml @@ -2,7 +2,7 @@ scenario_simulator_exception - 3.5.5 + 4.0.0 Exception types for scenario simulator Tatsuya Yamasaki Apache License 2.0 diff --git a/common/simple_junit/CHANGELOG.rst b/common/simple_junit/CHANGELOG.rst index 4e42bf48f5b..8ac9b966391 100644 --- a/common/simple_junit/CHANGELOG.rst +++ b/common/simple_junit/CHANGELOG.rst @@ -21,6 +21,35 @@ Changelog for package junit_exporter * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.0 (2024-08-27) +------------------ +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' of https://github.com/tier4/scenario_simulator_v2 into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Contributors: DMoszynski, Dawid Moszynski, Dawid Moszyński, Mateusz Palczuk, Tatsuya Yamasaki + 3.5.5 (2024-08-27) ------------------ * Merge branch 'master' into fix/distance-with-lane-change diff --git a/common/simple_junit/package.xml b/common/simple_junit/package.xml index 208e16e125e..abe99788581 100644 --- a/common/simple_junit/package.xml +++ b/common/simple_junit/package.xml @@ -2,7 +2,7 @@ simple_junit - 3.5.5 + 4.0.0 Lightweight JUnit library for ROS 2 Masaya Kataoka Tatsuya Yamasaki diff --git a/common/status_monitor/CHANGELOG.rst b/common/status_monitor/CHANGELOG.rst index ef178805641..d6814bcac78 100644 --- a/common/status_monitor/CHANGELOG.rst +++ b/common/status_monitor/CHANGELOG.rst @@ -21,6 +21,35 @@ Changelog for package status_monitor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.0 (2024-08-27) +------------------ +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' of https://github.com/tier4/scenario_simulator_v2 into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Contributors: DMoszynski, Dawid Moszynski, Dawid Moszyński, Mateusz Palczuk, Tatsuya Yamasaki + 3.5.5 (2024-08-27) ------------------ * Merge branch 'master' into fix/distance-with-lane-change diff --git a/common/status_monitor/package.xml b/common/status_monitor/package.xml index 1ea1e1962d5..0222a5f57c4 100644 --- a/common/status_monitor/package.xml +++ b/common/status_monitor/package.xml @@ -2,7 +2,7 @@ status_monitor - 3.5.5 + 4.0.0 none Tatsuya Yamasaki Apache License 2.0 diff --git a/external/concealer/CHANGELOG.rst b/external/concealer/CHANGELOG.rst index 496b5cc1478..159b43145f5 100644 --- a/external/concealer/CHANGELOG.rst +++ b/external/concealer/CHANGELOG.rst @@ -21,6 +21,35 @@ Changelog for package concealer * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.0 (2024-08-27) +------------------ +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' of https://github.com/tier4/scenario_simulator_v2 into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Contributors: DMoszynski, Dawid Moszynski, Dawid Moszyński, Mateusz Palczuk, Tatsuya Yamasaki + 3.5.5 (2024-08-27) ------------------ * Merge branch 'master' into fix/distance-with-lane-change diff --git a/external/concealer/package.xml b/external/concealer/package.xml index f9d1b400e66..c17301dc530 100644 --- a/external/concealer/package.xml +++ b/external/concealer/package.xml @@ -2,7 +2,7 @@ concealer - 3.5.5 + 4.0.0 Provides a class 'Autoware' to conceal miscellaneous things to simplify Autoware management of the simulator. Tatsuya Yamasaki Apache License 2.0 diff --git a/external/embree_vendor/CHANGELOG.rst b/external/embree_vendor/CHANGELOG.rst index 8500522b236..d89c788e526 100644 --- a/external/embree_vendor/CHANGELOG.rst +++ b/external/embree_vendor/CHANGELOG.rst @@ -24,6 +24,35 @@ Changelog for package embree_vendor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.0 (2024-08-27) +------------------ +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' of https://github.com/tier4/scenario_simulator_v2 into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Contributors: DMoszynski, Dawid Moszynski, Dawid Moszyński, Mateusz Palczuk, Tatsuya Yamasaki + 3.5.5 (2024-08-27) ------------------ * Merge branch 'master' into fix/distance-with-lane-change diff --git a/external/embree_vendor/package.xml b/external/embree_vendor/package.xml index c190c5d3bb9..259540e6c57 100644 --- a/external/embree_vendor/package.xml +++ b/external/embree_vendor/package.xml @@ -2,7 +2,7 @@ embree_vendor - 3.5.5 + 4.0.0 vendor packages for intel raytracing kernel library masaya Apache 2.0 diff --git a/map/kashiwanoha_map/CHANGELOG.rst b/map/kashiwanoha_map/CHANGELOG.rst index 7356e061c79..1187e9f6ed8 100644 --- a/map/kashiwanoha_map/CHANGELOG.rst +++ b/map/kashiwanoha_map/CHANGELOG.rst @@ -21,6 +21,35 @@ Changelog for package kashiwanoha_map * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.0 (2024-08-27) +------------------ +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' of https://github.com/tier4/scenario_simulator_v2 into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Contributors: DMoszynski, Dawid Moszynski, Dawid Moszyński, Mateusz Palczuk, Tatsuya Yamasaki + 3.5.5 (2024-08-27) ------------------ * Merge branch 'master' into fix/distance-with-lane-change diff --git a/map/kashiwanoha_map/package.xml b/map/kashiwanoha_map/package.xml index 6ca6d218b1b..7ba96bd7c5f 100644 --- a/map/kashiwanoha_map/package.xml +++ b/map/kashiwanoha_map/package.xml @@ -2,7 +2,7 @@ kashiwanoha_map - 3.5.5 + 4.0.0 map package for kashiwanoha Masaya Kataoka Apache License 2.0 diff --git a/map/simple_cross_map/CHANGELOG.rst b/map/simple_cross_map/CHANGELOG.rst index 506f5b401e8..421f52a5de8 100644 --- a/map/simple_cross_map/CHANGELOG.rst +++ b/map/simple_cross_map/CHANGELOG.rst @@ -9,6 +9,23 @@ Changelog for package simple_cross_map * Merge branch 'master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.0 (2024-08-27) +------------------ +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Contributors: DMoszynski, Dawid Moszynski, Dawid Moszyński, Mateusz Palczuk, Tatsuya Yamasaki + 3.5.5 (2024-08-27) ------------------ * Merge branch 'master' into fix/distance-with-lane-change diff --git a/map/simple_cross_map/package.xml b/map/simple_cross_map/package.xml index 916ccdb0f93..440ac51157e 100644 --- a/map/simple_cross_map/package.xml +++ b/map/simple_cross_map/package.xml @@ -2,7 +2,7 @@ simple_cross_map - 3.5.5 + 4.0.0 map package for simple cross Masaya Kataoka Apache License 2.0 diff --git a/mock/cpp_mock_scenarios/CHANGELOG.rst b/mock/cpp_mock_scenarios/CHANGELOG.rst index 2ad6a3324e6..7fad4612f32 100644 --- a/mock/cpp_mock_scenarios/CHANGELOG.rst +++ b/mock/cpp_mock_scenarios/CHANGELOG.rst @@ -21,6 +21,40 @@ Changelog for package cpp_mock_scenarios * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.0 (2024-08-27) +------------------ +* Merge pull request `#1320 `_ from tier4/ref/RJD-1053-set-update-canonicalized-entity-status + ref(behavior_tree, traffic_simulator): move responsibility for canonicalization to traffic_simulator, simplify +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* ref(traffic_simulator): use getCanonicalizedStatus, remove getStatus +* feat(cpp_mock_scenarios): add isPedestrain and isVehicle - use it +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* fix(cpp_mack_utils): adapt define_traffic_source scenarios to getEntity() +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' of https://github.com/tier4/scenario_simulator_v2 into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Contributors: DMoszynski, Dawid Moszynski, Dawid Moszyński, Masaya Kataoka, Mateusz Palczuk, Tatsuya Yamasaki + 3.5.5 (2024-08-27) ------------------ * Merge branch 'master' into fix/distance-with-lane-change diff --git a/mock/cpp_mock_scenarios/package.xml b/mock/cpp_mock_scenarios/package.xml index 51337dcd9d9..78ffc9d6fd4 100644 --- a/mock/cpp_mock_scenarios/package.xml +++ b/mock/cpp_mock_scenarios/package.xml @@ -2,7 +2,7 @@ cpp_mock_scenarios - 3.5.5 + 4.0.0 C++ mock scenarios masaya Apache License 2.0 diff --git a/openscenario/openscenario_experimental_catalog/CHANGELOG.rst b/openscenario/openscenario_experimental_catalog/CHANGELOG.rst index 83ddd710daf..0a9c26fab87 100644 --- a/openscenario/openscenario_experimental_catalog/CHANGELOG.rst +++ b/openscenario/openscenario_experimental_catalog/CHANGELOG.rst @@ -21,6 +21,35 @@ Changelog for package openscenario_experimental_catalog * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.0 (2024-08-27) +------------------ +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' of https://github.com/tier4/scenario_simulator_v2 into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Contributors: DMoszynski, Dawid Moszynski, Dawid Moszyński, Mateusz Palczuk, Tatsuya Yamasaki + 3.5.5 (2024-08-27) ------------------ * Merge branch 'master' into fix/distance-with-lane-change diff --git a/openscenario/openscenario_experimental_catalog/package.xml b/openscenario/openscenario_experimental_catalog/package.xml index 9d0beec7acd..ea6780a3616 100644 --- a/openscenario/openscenario_experimental_catalog/package.xml +++ b/openscenario/openscenario_experimental_catalog/package.xml @@ -2,7 +2,7 @@ openscenario_experimental_catalog - 3.5.5 + 4.0.0 TIER IV experimental catalogs for OpenSCENARIO Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter/CHANGELOG.rst b/openscenario/openscenario_interpreter/CHANGELOG.rst index 7f9d432ec0b..010cf5eda15 100644 --- a/openscenario/openscenario_interpreter/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter/CHANGELOG.rst @@ -32,6 +32,36 @@ Changelog for package openscenario_interpreter * add publish_empty_context parameter * Contributors: Masaya Kataoka +4.0.0 (2024-08-27) +------------------ +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' of https://github.com/tier4/scenario_simulator_v2 into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Contributors: DMoszynski, Dawid Moszynski, Dawid Moszyński, Mateusz Palczuk, Tatsuya Yamasaki + 3.5.5 (2024-08-27) ------------------ * Merge branch 'master' into fix/distance-with-lane-change diff --git a/openscenario/openscenario_interpreter/package.xml b/openscenario/openscenario_interpreter/package.xml index e3675d53fe6..1a3246c0132 100644 --- a/openscenario/openscenario_interpreter/package.xml +++ b/openscenario/openscenario_interpreter/package.xml @@ -2,7 +2,7 @@ openscenario_interpreter - 3.5.5 + 4.0.0 OpenSCENARIO 1.2.0 interpreter package for Autoware Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter_example/CHANGELOG.rst b/openscenario/openscenario_interpreter_example/CHANGELOG.rst index 19793ec1e0c..c106ea65721 100644 --- a/openscenario/openscenario_interpreter_example/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter_example/CHANGELOG.rst @@ -21,6 +21,35 @@ Changelog for package openscenario_interpreter_example * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.0 (2024-08-27) +------------------ +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' of https://github.com/tier4/scenario_simulator_v2 into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Contributors: DMoszynski, Dawid Moszynski, Dawid Moszyński, Mateusz Palczuk, Tatsuya Yamasaki + 3.5.5 (2024-08-27) ------------------ * Merge branch 'master' into fix/distance-with-lane-change diff --git a/openscenario/openscenario_interpreter_example/package.xml b/openscenario/openscenario_interpreter_example/package.xml index cc446b72940..8eaba7e3bea 100644 --- a/openscenario/openscenario_interpreter_example/package.xml +++ b/openscenario/openscenario_interpreter_example/package.xml @@ -3,7 +3,7 @@ openscenario_interpreter_example - 3.5.5 + 4.0.0 Examples for some TIER IV OpenSCENARIO Interpreter's features Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst b/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst index 1d18fc6d4eb..80d11b578bb 100644 --- a/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst @@ -21,6 +21,35 @@ Changelog for package openscenario_interpreter_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.0 (2024-08-27) +------------------ +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' of https://github.com/tier4/scenario_simulator_v2 into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Contributors: DMoszynski, Dawid Moszynski, Dawid Moszyński, Mateusz Palczuk, Tatsuya Yamasaki + 3.5.5 (2024-08-27) ------------------ * Merge branch 'master' into fix/distance-with-lane-change diff --git a/openscenario/openscenario_interpreter_msgs/package.xml b/openscenario/openscenario_interpreter_msgs/package.xml index 991f3c93ce0..8951c8831c9 100644 --- a/openscenario/openscenario_interpreter_msgs/package.xml +++ b/openscenario/openscenario_interpreter_msgs/package.xml @@ -2,7 +2,7 @@ openscenario_interpreter_msgs - 3.5.5 + 4.0.0 ROS message types for package openscenario_interpreter Yamasaki Tatsuya Apache License 2.0 diff --git a/openscenario/openscenario_preprocessor/CHANGELOG.rst b/openscenario/openscenario_preprocessor/CHANGELOG.rst index 3140170a4b2..652db237806 100644 --- a/openscenario/openscenario_preprocessor/CHANGELOG.rst +++ b/openscenario/openscenario_preprocessor/CHANGELOG.rst @@ -21,6 +21,35 @@ Changelog for package openscenario_preprocessor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.0 (2024-08-27) +------------------ +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' of https://github.com/tier4/scenario_simulator_v2 into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Contributors: DMoszynski, Dawid Moszynski, Dawid Moszyński, Mateusz Palczuk, Tatsuya Yamasaki + 3.5.5 (2024-08-27) ------------------ * Merge branch 'master' into fix/distance-with-lane-change diff --git a/openscenario/openscenario_preprocessor/package.xml b/openscenario/openscenario_preprocessor/package.xml index 055c3084485..73870766efe 100644 --- a/openscenario/openscenario_preprocessor/package.xml +++ b/openscenario/openscenario_preprocessor/package.xml @@ -3,7 +3,7 @@ openscenario_preprocessor - 3.5.5 + 4.0.0 Example package for TIER IV OpenSCENARIO Interpreter Kotaro Yoshimoto Apache License 2.0 diff --git a/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst b/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst index 51e7aac4ed4..f221daad775 100644 --- a/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst +++ b/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst @@ -21,6 +21,35 @@ Changelog for package openscenario_preprocessor_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.0 (2024-08-27) +------------------ +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' of https://github.com/tier4/scenario_simulator_v2 into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Contributors: DMoszynski, Dawid Moszynski, Dawid Moszyński, Mateusz Palczuk, Tatsuya Yamasaki + 3.5.5 (2024-08-27) ------------------ * Merge branch 'master' into fix/distance-with-lane-change diff --git a/openscenario/openscenario_preprocessor_msgs/package.xml b/openscenario/openscenario_preprocessor_msgs/package.xml index cc559bbb190..5c63864697d 100644 --- a/openscenario/openscenario_preprocessor_msgs/package.xml +++ b/openscenario/openscenario_preprocessor_msgs/package.xml @@ -2,7 +2,7 @@ openscenario_preprocessor_msgs - 3.5.5 + 4.0.0 ROS message types for package openscenario_preprocessor Kotaro Yoshimoto Apache License 2.0 diff --git a/openscenario/openscenario_utility/CHANGELOG.rst b/openscenario/openscenario_utility/CHANGELOG.rst index 9231435207e..acd38f5b37e 100644 --- a/openscenario/openscenario_utility/CHANGELOG.rst +++ b/openscenario/openscenario_utility/CHANGELOG.rst @@ -24,6 +24,35 @@ Changelog for package openscenario_utility * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.0 (2024-08-27) +------------------ +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' of https://github.com/tier4/scenario_simulator_v2 into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Contributors: DMoszynski, Dawid Moszynski, Dawid Moszyński, Mateusz Palczuk, Tatsuya Yamasaki + 3.5.5 (2024-08-27) ------------------ * Merge branch 'master' into fix/distance-with-lane-change diff --git a/openscenario/openscenario_utility/package.xml b/openscenario/openscenario_utility/package.xml index 38e808f3336..e1aea7aa002 100644 --- a/openscenario/openscenario_utility/package.xml +++ b/openscenario/openscenario_utility/package.xml @@ -2,7 +2,7 @@ openscenario_utility - 3.5.5 + 4.0.0 Utility tools for ASAM OpenSCENARIO 1.2.0 Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_validator/CHANGELOG.rst b/openscenario/openscenario_validator/CHANGELOG.rst index f3d7e494552..e7ae08f6807 100644 --- a/openscenario/openscenario_validator/CHANGELOG.rst +++ b/openscenario/openscenario_validator/CHANGELOG.rst @@ -10,6 +10,34 @@ Changelog for package openscenario_validator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.0 (2024-08-27) +------------------ +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' of https://github.com/tier4/scenario_simulator_v2 into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Contributors: DMoszynski, Dawid Moszynski, Dawid Moszyński, Mateusz Palczuk, Tatsuya Yamasaki + 3.5.5 (2024-08-27) ------------------ * Merge branch 'master' into fix/distance-with-lane-change diff --git a/openscenario/openscenario_validator/package.xml b/openscenario/openscenario_validator/package.xml index 935ec6e7754..2f229820981 100644 --- a/openscenario/openscenario_validator/package.xml +++ b/openscenario/openscenario_validator/package.xml @@ -2,7 +2,7 @@ openscenario_validator - 3.5.5 + 4.0.0 Validator for OpenSCENARIO 1.3 Kotaro Yoshimoto Apache License 2.0 diff --git a/rviz_plugins/openscenario_visualization/CHANGELOG.rst b/rviz_plugins/openscenario_visualization/CHANGELOG.rst index 6ae1cf64306..c6c02437fdc 100644 --- a/rviz_plugins/openscenario_visualization/CHANGELOG.rst +++ b/rviz_plugins/openscenario_visualization/CHANGELOG.rst @@ -21,6 +21,35 @@ Changelog for package openscenario_visualization * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.0 (2024-08-27) +------------------ +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' of https://github.com/tier4/scenario_simulator_v2 into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Contributors: DMoszynski, Dawid Moszynski, Dawid Moszyński, Mateusz Palczuk, Tatsuya Yamasaki + 3.5.5 (2024-08-27) ------------------ * Merge branch 'master' into fix/distance-with-lane-change diff --git a/rviz_plugins/openscenario_visualization/package.xml b/rviz_plugins/openscenario_visualization/package.xml index 169d8665dd2..791d511ac19 100644 --- a/rviz_plugins/openscenario_visualization/package.xml +++ b/rviz_plugins/openscenario_visualization/package.xml @@ -2,7 +2,7 @@ openscenario_visualization - 3.5.5 + 4.0.0 Visualization tools for simulation results Masaya Kataoka Kyoichi Sugahara diff --git a/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst b/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst index 7beaae2ee0b..baa0d2f10f5 100644 --- a/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst +++ b/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst @@ -21,6 +21,35 @@ Changelog for package real_time_factor_control_rviz_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.0 (2024-08-27) +------------------ +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' of https://github.com/tier4/scenario_simulator_v2 into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Contributors: DMoszynski, Dawid Moszynski, Dawid Moszyński, Mateusz Palczuk, Tatsuya Yamasaki + 3.5.5 (2024-08-27) ------------------ * Merge branch 'master' into fix/distance-with-lane-change diff --git a/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml b/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml index b6e1e8d7902..40b8ecaf3db 100644 --- a/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml +++ b/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml @@ -2,7 +2,7 @@ real_time_factor_control_rviz_plugin - 3.5.5 + 4.0.0 Slider controlling real time factor value. Paweł Lech Apache License 2.0 diff --git a/scenario_simulator_v2/CHANGELOG.rst b/scenario_simulator_v2/CHANGELOG.rst index c110372ee31..592d5e608b6 100644 --- a/scenario_simulator_v2/CHANGELOG.rst +++ b/scenario_simulator_v2/CHANGELOG.rst @@ -21,6 +21,35 @@ Changelog for package scenario_simulator_v2 * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.0 (2024-08-27) +------------------ +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' of https://github.com/tier4/scenario_simulator_v2 into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Contributors: DMoszynski, Dawid Moszynski, Dawid Moszyński, Mateusz Palczuk, Tatsuya Yamasaki + 3.5.5 (2024-08-27) ------------------ * Merge branch 'master' into fix/distance-with-lane-change diff --git a/scenario_simulator_v2/package.xml b/scenario_simulator_v2/package.xml index 1e3b0acf02c..c8b28412525 100644 --- a/scenario_simulator_v2/package.xml +++ b/scenario_simulator_v2/package.xml @@ -2,7 +2,7 @@ scenario_simulator_v2 - 3.5.5 + 4.0.0 scenario testing framework for Autoware Masaya Kataoka Apache License 2.0 diff --git a/simulation/behavior_tree_plugin/CHANGELOG.rst b/simulation/behavior_tree_plugin/CHANGELOG.rst index 201793a253b..8fd62dccc89 100644 --- a/simulation/behavior_tree_plugin/CHANGELOG.rst +++ b/simulation/behavior_tree_plugin/CHANGELOG.rst @@ -21,6 +21,45 @@ Changelog for package behavior_tree_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.0 (2024-08-27) +------------------ +* Merge pull request `#1320 `_ from tier4/ref/RJD-1053-set-update-canonicalized-entity-status + ref(behavior_tree, traffic_simulator): move responsibility for canonicalization to traffic_simulator, simplify +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* ref(behavior_tree): remove unused variable +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* ref(behavior_tree): use CanonicalizedEntityStatus as shared_ptr inside BT and use ::set +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' of https://github.com/tier4/scenario_simulator_v2 into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* ref(behavior_tree_plugin): rename updated_status variable +* ref(traffic_simulator, behavior_tree_plugin): revert unnecessary changes +* fix(traffic_simulator, behavior_tree_plugin): fix returned EntityStatus from bt, fix canonicalize in vehicle_entity and pedestrian_entity +* feat(behavior_tree_plugin, entity_base): move toCanonicalizedEntityPose to traffic_simulator, use EntityStatus as updated_state in BehaviorTree +* feat(traffic_simulator): use CanonicalizedEntityStatus only with single constructor +* Merge remote-tracking branch 'origin/ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* tmp +* Contributors: DMoszynski, Dawid Moszynski, Dawid Moszyński, Masaya Kataoka, Mateusz Palczuk, Tatsuya Yamasaki + 3.5.5 (2024-08-27) ------------------ * Merge branch 'master' into fix/distance-with-lane-change diff --git a/simulation/behavior_tree_plugin/package.xml b/simulation/behavior_tree_plugin/package.xml index 89b5ac53c57..453923e6f45 100644 --- a/simulation/behavior_tree_plugin/package.xml +++ b/simulation/behavior_tree_plugin/package.xml @@ -2,7 +2,7 @@ behavior_tree_plugin - 3.5.5 + 4.0.0 Behavior tree plugin for traffic_simulator masaya Apache 2.0 diff --git a/simulation/do_nothing_plugin/CHANGELOG.rst b/simulation/do_nothing_plugin/CHANGELOG.rst index bce71b331ee..6cf17db778d 100644 --- a/simulation/do_nothing_plugin/CHANGELOG.rst +++ b/simulation/do_nothing_plugin/CHANGELOG.rst @@ -21,6 +21,42 @@ Changelog for package do_nothing_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.0 (2024-08-27) +------------------ +* Merge pull request `#1320 `_ from tier4/ref/RJD-1053-set-update-canonicalized-entity-status + ref(behavior_tree, traffic_simulator): move responsibility for canonicalization to traffic_simulator, simplify +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* ref(behavior_tree): use CanonicalizedEntityStatus as shared_ptr inside BT and use ::set +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' of https://github.com/tier4/scenario_simulator_v2 into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* ref(do_notching_plugin): remove unecessary comment +* feat(behavior_tree_plugin, entity_base): move toCanonicalizedEntityPose to traffic_simulator, use EntityStatus as updated_state in BehaviorTree +* feat(traffic_simulator): use CanonicalizedEntityStatus only with single constructor +* Merge remote-tracking branch 'origin/ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* tmp +* Contributors: DMoszynski, Dawid Moszynski, Dawid Moszyński, Masaya Kataoka, Mateusz Palczuk, Tatsuya Yamasaki + 3.5.5 (2024-08-27) ------------------ * Merge branch 'master' into fix/distance-with-lane-change diff --git a/simulation/do_nothing_plugin/package.xml b/simulation/do_nothing_plugin/package.xml index ce8938e06e9..b8fc31e0732 100644 --- a/simulation/do_nothing_plugin/package.xml +++ b/simulation/do_nothing_plugin/package.xml @@ -2,7 +2,7 @@ do_nothing_plugin - 3.5.5 + 4.0.0 Behavior plugin for do nothing Masaya Kataoka Apache 2.0 diff --git a/simulation/simple_sensor_simulator/CHANGELOG.rst b/simulation/simple_sensor_simulator/CHANGELOG.rst index 0a6bd102f62..0248e9bcee9 100644 --- a/simulation/simple_sensor_simulator/CHANGELOG.rst +++ b/simulation/simple_sensor_simulator/CHANGELOG.rst @@ -21,6 +21,42 @@ Changelog for package simple_sensor_simulator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.0 (2024-08-27) +------------------ +* Merge pull request `#1320 `_ from tier4/ref/RJD-1053-set-update-canonicalized-entity-status + ref(behavior_tree, traffic_simulator): move responsibility for canonicalization to traffic_simulator, simplify +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* doc(developer_guide, traffic_simulator): update doc after review changes, add code notes +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* doc(developer_guide, pose utils): adopt lane_pose_calculation doc to canonicalization laneletpose in CanonicalizedEntityStatus +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' of https://github.com/tier4/scenario_simulator_v2 into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* ref(traffic_simulator): move toCanonicalizeLaneletPose to CanonicalizedEntityStatus::set, little tidy up +* ref(traffic_simulator): remove operator= for CanonicalizedEntityStatus, use set and assertions +* Merge remote-tracking branch 'origin/ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Contributors: DMoszynski, Dawid Moszynski, Dawid Moszyński, Masaya Kataoka, Mateusz Palczuk, Tatsuya Yamasaki + 3.5.5 (2024-08-27) ------------------ * Merge branch 'master' into fix/distance-with-lane-change diff --git a/simulation/simple_sensor_simulator/package.xml b/simulation/simple_sensor_simulator/package.xml index 428a93898de..1581fb4e23c 100644 --- a/simulation/simple_sensor_simulator/package.xml +++ b/simulation/simple_sensor_simulator/package.xml @@ -1,7 +1,7 @@ simple_sensor_simulator - 3.5.5 + 4.0.0 simple_sensor_simulator package masaya kataoka diff --git a/simulation/simulation_interface/CHANGELOG.rst b/simulation/simulation_interface/CHANGELOG.rst index 8627664b6d1..72af712e74a 100644 --- a/simulation/simulation_interface/CHANGELOG.rst +++ b/simulation/simulation_interface/CHANGELOG.rst @@ -21,6 +21,39 @@ Changelog for package simulation_interface * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.0 (2024-08-27) +------------------ +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' of https://github.com/tier4/scenario_simulator_v2 into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* fix(conversions, behavior_plugin_base): add new line at the end +* ref(traffic_simulator, behavior_tree_plugin): revert unnecessary changes +* feat(traffic_simulator): use CanonicalizedEntityStatus only with single constructor +* Merge remote-tracking branch 'origin/ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Contributors: DMoszynski, Dawid Moszynski, Dawid Moszyński, Mateusz Palczuk, Tatsuya Yamasaki + 3.5.5 (2024-08-27) ------------------ * Merge branch 'master' into fix/distance-with-lane-change diff --git a/simulation/simulation_interface/package.xml b/simulation/simulation_interface/package.xml index adc700b1520..bd51d39719f 100644 --- a/simulation/simulation_interface/package.xml +++ b/simulation/simulation_interface/package.xml @@ -2,7 +2,7 @@ simulation_interface - 3.5.5 + 4.0.0 packages to define interface between simulator and scenario interpreter Masaya Kataoka Apache License 2.0 diff --git a/simulation/traffic_simulator/CHANGELOG.rst b/simulation/traffic_simulator/CHANGELOG.rst index 779539af957..95fbb110a65 100644 --- a/simulation/traffic_simulator/CHANGELOG.rst +++ b/simulation/traffic_simulator/CHANGELOG.rst @@ -21,6 +21,72 @@ Changelog for package traffic_simulator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.0 (2024-08-27) +------------------ +* Merge pull request `#1320 `_ from tier4/ref/RJD-1053-set-update-canonicalized-entity-status + ref(behavior_tree, traffic_simulator): move responsibility for canonicalization to traffic_simulator, simplify +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* doc(distance): use doxygen format + Co-authored-by: Masaya Kataoka +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Fix EgoEntity bug where status time was incremented only when Ego was controlled by simulator + This bug lead to problems in other checks which relied on the correct status time +* Fix EgoEntity error where map pose was unable to be set after scenario start, which should be possible for Ego +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* ref(behavior_tree): use CanonicalizedEntityStatus as shared_ptr inside BT and use ::set +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* fix(ego_entity): fix setMapPose +* ref(traffic_simulator): remove souvenir +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* fix(spell): fix string in api +* feat(traffic_simulator, entity_base): improve setStatus - add passing lanelet_id - use it +* ref(traffic_simulator): use getCanonicalizedStatus, remove getStatus +* ref(traffic_simulator): remove virutla getEntityType, tidy up CanonicalizedEntityStatus getters +* feat(cpp_mock_scenarios): add isPedestrain and isVehicle - use it +* ref(utils, pose): global use pose:: namespace +* fix(traffic_simulator): apply clang reformat +* ref(traffic_simulator): improve CanonicalizedEntityStatus getters - use const ref +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* ref(entity_base): fix retuned type def, fix typo +* doc(developer_guide, traffic_simulator): update doc after review changes, add code notes +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* fix(traffic_simulator): fix helper_functions for tests and misc object tests +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* fix(follow_trajectory_action): fix after merge FTA changes +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* doc(developer_guide, pose utils): adopt lane_pose_calculation doc to canonicalization laneletpose in CanonicalizedEntityStatus +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' of https://github.com/tier4/scenario_simulator_v2 into ref/RJD-1053-set-update-canonicalized-entity-status +* fix(traffic_simulator): improve assertions in CanonicalizedEntityStatus::set +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* fix(conversions, behavior_plugin_base): add new line at the end +* ref(traffic_simulator): move toCanonicalizeLaneletPose to CanonicalizedEntityStatus::set, little tidy up +* fix(traffic_simulator): fix behavior_plugin_base +* ref(traffic_simulator, behavior_tree_plugin): revert unnecessary changes +* ref(traffic_simulator, behavior_tree_plugin): revert unnecessary changes +* ref(traffic_simulator): remove operator= for CanonicalizedEntityStatus, use set and assertions +* fix(traffic_simulator, behavior_tree_plugin): fix returned EntityStatus from bt, fix canonicalize in vehicle_entity and pedestrian_entity +* feat(behavior_tree_plugin, entity_base): move toCanonicalizedEntityPose to traffic_simulator, use EntityStatus as updated_state in BehaviorTree +* feat(traffic_simulator): use CanonicalizedEntityStatus only with single constructor +* Merge remote-tracking branch 'origin/ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* tmp +* ref(traffic_simulator): remove unnecessary cast to EnrityStatus in EntityManager and MicObjectEntity +* ref(traffic_simulator): remove unecessary casts to EntityStatus in EntityBase +* Contributors: DMoszynski, Dawid Moszynski, Dawid Moszyński, Masaya Kataoka, Mateusz Palczuk, Tatsuya Yamasaki + 3.5.5 (2024-08-27) ------------------ * Merge pull request `#1348 `_ from tier4/fix/distance-with-lane-change diff --git a/simulation/traffic_simulator/package.xml b/simulation/traffic_simulator/package.xml index 696eb1f705e..7f181b61180 100644 --- a/simulation/traffic_simulator/package.xml +++ b/simulation/traffic_simulator/package.xml @@ -1,7 +1,7 @@ traffic_simulator - 3.5.5 + 4.0.0 control traffic flow masaya kataoka diff --git a/simulation/traffic_simulator_msgs/CHANGELOG.rst b/simulation/traffic_simulator_msgs/CHANGELOG.rst index 61a5fd96f0e..2364c4edb1d 100644 --- a/simulation/traffic_simulator_msgs/CHANGELOG.rst +++ b/simulation/traffic_simulator_msgs/CHANGELOG.rst @@ -21,6 +21,35 @@ Changelog for package openscenario_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.0 (2024-08-27) +------------------ +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' of https://github.com/tier4/scenario_simulator_v2 into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Contributors: DMoszynski, Dawid Moszynski, Dawid Moszyński, Mateusz Palczuk, Tatsuya Yamasaki + 3.5.5 (2024-08-27) ------------------ * Merge branch 'master' into fix/distance-with-lane-change diff --git a/simulation/traffic_simulator_msgs/package.xml b/simulation/traffic_simulator_msgs/package.xml index 2e37ee59a73..b491f064996 100644 --- a/simulation/traffic_simulator_msgs/package.xml +++ b/simulation/traffic_simulator_msgs/package.xml @@ -2,7 +2,7 @@ traffic_simulator_msgs - 3.5.5 + 4.0.0 ROS messages for openscenario Masaya Kataoka Apache License 2.0 diff --git a/test_runner/random_test_runner/CHANGELOG.rst b/test_runner/random_test_runner/CHANGELOG.rst index a913aa6c3e4..c45dc19d818 100644 --- a/test_runner/random_test_runner/CHANGELOG.rst +++ b/test_runner/random_test_runner/CHANGELOG.rst @@ -21,6 +21,39 @@ Changelog for package random_test_runner * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.0 (2024-08-27) +------------------ +* Merge pull request `#1320 `_ from tier4/ref/RJD-1053-set-update-canonicalized-entity-status + ref(behavior_tree, traffic_simulator): move responsibility for canonicalization to traffic_simulator, simplify +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' of https://github.com/tier4/scenario_simulator_v2 into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* feat(traffic_simulator): use CanonicalizedEntityStatus only with single constructor +* Merge remote-tracking branch 'origin/ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* tmp +* Contributors: DMoszynski, Dawid Moszynski, Dawid Moszyński, Masaya Kataoka, Mateusz Palczuk, Tatsuya Yamasaki + 3.5.5 (2024-08-27) ------------------ * Merge branch 'master' into fix/distance-with-lane-change diff --git a/test_runner/random_test_runner/package.xml b/test_runner/random_test_runner/package.xml index 05192a782a7..de79b0549ea 100644 --- a/test_runner/random_test_runner/package.xml +++ b/test_runner/random_test_runner/package.xml @@ -2,7 +2,7 @@ random_test_runner - 3.5.5 + 4.0.0 Random behavior test runner piotr-zyskowski-rai Apache License 2.0 diff --git a/test_runner/scenario_test_runner/CHANGELOG.rst b/test_runner/scenario_test_runner/CHANGELOG.rst index 01a260b2f93..290a3eb17cd 100644 --- a/test_runner/scenario_test_runner/CHANGELOG.rst +++ b/test_runner/scenario_test_runner/CHANGELOG.rst @@ -35,6 +35,35 @@ Changelog for package scenario_test_runner * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.0 (2024-08-27) +------------------ +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' of https://github.com/tier4/scenario_simulator_v2 into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge branch 'ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Merge remote-tracking branch 'origin/ref/RJD-1053-implement-pose-utils' into ref/RJD-1053-set-update-canonicalized-entity-status +* Contributors: DMoszynski, Dawid Moszynski, Dawid Moszyński, Mateusz Palczuk, Tatsuya Yamasaki + 3.5.5 (2024-08-27) ------------------ * Merge pull request `#1348 `_ from tier4/fix/distance-with-lane-change diff --git a/test_runner/scenario_test_runner/package.xml b/test_runner/scenario_test_runner/package.xml index 803393bef42..0091b9e44d9 100644 --- a/test_runner/scenario_test_runner/package.xml +++ b/test_runner/scenario_test_runner/package.xml @@ -2,7 +2,7 @@ scenario_test_runner - 3.5.5 + 4.0.0 scenario test runner package Tatsuya Yamasaki Apache License 2.0 From 836540f81b2b01cae1e493e2aeecfb00836247d1 Mon Sep 17 00:00:00 2001 From: Mateusz Palczuk Date: Tue, 27 Aug 2024 18:13:57 +0200 Subject: [PATCH 184/304] Fix after using pointer to store entity status Signed-off-by: Mateusz Palczuk --- simulation/traffic_simulator/src/entity/ego_entity.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/simulation/traffic_simulator/src/entity/ego_entity.cpp b/simulation/traffic_simulator/src/entity/ego_entity.cpp index 8a3dba65a4d..02ab5ff4ef3 100644 --- a/simulation/traffic_simulator/src/entity/ego_entity.cpp +++ b/simulation/traffic_simulator/src/entity/ego_entity.cpp @@ -268,7 +268,7 @@ auto EgoEntity::setBehaviorParameter( auto EgoEntity::requestSpeedChange(double value, bool /* continuous */) -> void { - if (status_.getTime() > 0.0) { + if (status_->getTime() > 0.0) { THROW_SEMANTIC_ERROR("You cannot set target speed to the ego vehicle after starting scenario."); } else { target_speed_ = value; From 5324a6748d1538de3718be57bc5aa646048c4e4c Mon Sep 17 00:00:00 2001 From: Release Bot Date: Wed, 28 Aug 2024 05:43:03 +0000 Subject: [PATCH 185/304] Bump version of scenario_simulator_v2 from version 4.0.0 to version 4.0.1 --- common/math/arithmetic/CHANGELOG.rst | 7 +++++++ common/math/arithmetic/package.xml | 2 +- common/math/geometry/CHANGELOG.rst | 7 +++++++ common/math/geometry/package.xml | 2 +- common/scenario_simulator_exception/CHANGELOG.rst | 7 +++++++ common/scenario_simulator_exception/package.xml | 2 +- common/simple_junit/CHANGELOG.rst | 7 +++++++ common/simple_junit/package.xml | 2 +- common/status_monitor/CHANGELOG.rst | 7 +++++++ common/status_monitor/package.xml | 2 +- external/concealer/CHANGELOG.rst | 7 +++++++ external/concealer/package.xml | 2 +- external/embree_vendor/CHANGELOG.rst | 7 +++++++ external/embree_vendor/package.xml | 2 +- map/kashiwanoha_map/CHANGELOG.rst | 7 +++++++ map/kashiwanoha_map/package.xml | 2 +- map/simple_cross_map/CHANGELOG.rst | 7 +++++++ map/simple_cross_map/package.xml | 2 +- mock/cpp_mock_scenarios/CHANGELOG.rst | 7 +++++++ mock/cpp_mock_scenarios/package.xml | 2 +- .../openscenario_experimental_catalog/CHANGELOG.rst | 7 +++++++ .../openscenario_experimental_catalog/package.xml | 2 +- openscenario/openscenario_interpreter/CHANGELOG.rst | 7 +++++++ openscenario/openscenario_interpreter/package.xml | 2 +- .../openscenario_interpreter_example/CHANGELOG.rst | 7 +++++++ .../openscenario_interpreter_example/package.xml | 2 +- .../openscenario_interpreter_msgs/CHANGELOG.rst | 7 +++++++ .../openscenario_interpreter_msgs/package.xml | 2 +- openscenario/openscenario_preprocessor/CHANGELOG.rst | 7 +++++++ openscenario/openscenario_preprocessor/package.xml | 2 +- .../openscenario_preprocessor_msgs/CHANGELOG.rst | 7 +++++++ .../openscenario_preprocessor_msgs/package.xml | 2 +- openscenario/openscenario_utility/CHANGELOG.rst | 7 +++++++ openscenario/openscenario_utility/package.xml | 2 +- openscenario/openscenario_validator/CHANGELOG.rst | 7 +++++++ openscenario/openscenario_validator/package.xml | 2 +- .../openscenario_visualization/CHANGELOG.rst | 7 +++++++ rviz_plugins/openscenario_visualization/package.xml | 2 +- .../CHANGELOG.rst | 7 +++++++ .../real_time_factor_control_rviz_plugin/package.xml | 2 +- scenario_simulator_v2/CHANGELOG.rst | 7 +++++++ scenario_simulator_v2/package.xml | 2 +- simulation/behavior_tree_plugin/CHANGELOG.rst | 7 +++++++ simulation/behavior_tree_plugin/package.xml | 2 +- simulation/do_nothing_plugin/CHANGELOG.rst | 12 ++++++++++++ simulation/do_nothing_plugin/package.xml | 2 +- simulation/simple_sensor_simulator/CHANGELOG.rst | 7 +++++++ simulation/simple_sensor_simulator/package.xml | 2 +- simulation/simulation_interface/CHANGELOG.rst | 7 +++++++ simulation/simulation_interface/package.xml | 2 +- simulation/traffic_simulator/CHANGELOG.rst | 11 +++++++++++ simulation/traffic_simulator/package.xml | 2 +- simulation/traffic_simulator_msgs/CHANGELOG.rst | 7 +++++++ simulation/traffic_simulator_msgs/package.xml | 2 +- test_runner/random_test_runner/CHANGELOG.rst | 7 +++++++ test_runner/random_test_runner/package.xml | 2 +- test_runner/scenario_test_runner/CHANGELOG.rst | 7 +++++++ test_runner/scenario_test_runner/package.xml | 2 +- 58 files changed, 241 insertions(+), 29 deletions(-) diff --git a/common/math/arithmetic/CHANGELOG.rst b/common/math/arithmetic/CHANGELOG.rst index 7ebc997dc1d..f0cf2ec7855 100644 --- a/common/math/arithmetic/CHANGELOG.rst +++ b/common/math/arithmetic/CHANGELOG.rst @@ -21,6 +21,13 @@ Changelog for package arithmetic * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.1 (2024-08-28) +------------------ +* Merge branch 'master' into fix/follow_trajectory +* Merge branch 'master' into fix/follow_trajectory +* Merge remote-tracking branch 'origin' into fix/follow_trajectory +* Contributors: Masaya Kataoka + 4.0.0 (2024-08-27) ------------------ * Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status diff --git a/common/math/arithmetic/package.xml b/common/math/arithmetic/package.xml index f36b46cbfda..3625943a4d7 100644 --- a/common/math/arithmetic/package.xml +++ b/common/math/arithmetic/package.xml @@ -2,7 +2,7 @@ arithmetic - 4.0.0 + 4.0.1 arithmetic library for scenario_simulator_v2 Tatsuya Yamasaki Apache License 2.0 diff --git a/common/math/geometry/CHANGELOG.rst b/common/math/geometry/CHANGELOG.rst index 5f3f3f94197..611fb339998 100644 --- a/common/math/geometry/CHANGELOG.rst +++ b/common/math/geometry/CHANGELOG.rst @@ -21,6 +21,13 @@ Changelog for package geometry * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.1 (2024-08-28) +------------------ +* Merge branch 'master' into fix/follow_trajectory +* Merge branch 'master' into fix/follow_trajectory +* Merge remote-tracking branch 'origin' into fix/follow_trajectory +* Contributors: Masaya Kataoka + 4.0.0 (2024-08-27) ------------------ * Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status diff --git a/common/math/geometry/package.xml b/common/math/geometry/package.xml index 2486fda3ffe..87539646efd 100644 --- a/common/math/geometry/package.xml +++ b/common/math/geometry/package.xml @@ -2,7 +2,7 @@ geometry - 4.0.0 + 4.0.1 geometry math library for scenario_simulator_v2 application Masaya Kataoka Apache License 2.0 diff --git a/common/scenario_simulator_exception/CHANGELOG.rst b/common/scenario_simulator_exception/CHANGELOG.rst index 53df0993865..5b706727192 100644 --- a/common/scenario_simulator_exception/CHANGELOG.rst +++ b/common/scenario_simulator_exception/CHANGELOG.rst @@ -21,6 +21,13 @@ Changelog for package scenario_simulator_exception * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.1 (2024-08-28) +------------------ +* Merge branch 'master' into fix/follow_trajectory +* Merge branch 'master' into fix/follow_trajectory +* Merge remote-tracking branch 'origin' into fix/follow_trajectory +* Contributors: Masaya Kataoka + 4.0.0 (2024-08-27) ------------------ * Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status diff --git a/common/scenario_simulator_exception/package.xml b/common/scenario_simulator_exception/package.xml index bf139e1ecd1..8daac31a5d8 100644 --- a/common/scenario_simulator_exception/package.xml +++ b/common/scenario_simulator_exception/package.xml @@ -2,7 +2,7 @@ scenario_simulator_exception - 4.0.0 + 4.0.1 Exception types for scenario simulator Tatsuya Yamasaki Apache License 2.0 diff --git a/common/simple_junit/CHANGELOG.rst b/common/simple_junit/CHANGELOG.rst index 8ac9b966391..a1aaf142434 100644 --- a/common/simple_junit/CHANGELOG.rst +++ b/common/simple_junit/CHANGELOG.rst @@ -21,6 +21,13 @@ Changelog for package junit_exporter * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.1 (2024-08-28) +------------------ +* Merge branch 'master' into fix/follow_trajectory +* Merge branch 'master' into fix/follow_trajectory +* Merge remote-tracking branch 'origin' into fix/follow_trajectory +* Contributors: Masaya Kataoka + 4.0.0 (2024-08-27) ------------------ * Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status diff --git a/common/simple_junit/package.xml b/common/simple_junit/package.xml index abe99788581..459a77350d7 100644 --- a/common/simple_junit/package.xml +++ b/common/simple_junit/package.xml @@ -2,7 +2,7 @@ simple_junit - 4.0.0 + 4.0.1 Lightweight JUnit library for ROS 2 Masaya Kataoka Tatsuya Yamasaki diff --git a/common/status_monitor/CHANGELOG.rst b/common/status_monitor/CHANGELOG.rst index d6814bcac78..34e1cfdb571 100644 --- a/common/status_monitor/CHANGELOG.rst +++ b/common/status_monitor/CHANGELOG.rst @@ -21,6 +21,13 @@ Changelog for package status_monitor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.1 (2024-08-28) +------------------ +* Merge branch 'master' into fix/follow_trajectory +* Merge branch 'master' into fix/follow_trajectory +* Merge remote-tracking branch 'origin' into fix/follow_trajectory +* Contributors: Masaya Kataoka + 4.0.0 (2024-08-27) ------------------ * Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status diff --git a/common/status_monitor/package.xml b/common/status_monitor/package.xml index 0222a5f57c4..36e7e7bb9cc 100644 --- a/common/status_monitor/package.xml +++ b/common/status_monitor/package.xml @@ -2,7 +2,7 @@ status_monitor - 4.0.0 + 4.0.1 none Tatsuya Yamasaki Apache License 2.0 diff --git a/external/concealer/CHANGELOG.rst b/external/concealer/CHANGELOG.rst index 159b43145f5..bdb4a51fba2 100644 --- a/external/concealer/CHANGELOG.rst +++ b/external/concealer/CHANGELOG.rst @@ -21,6 +21,13 @@ Changelog for package concealer * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.1 (2024-08-28) +------------------ +* Merge branch 'master' into fix/follow_trajectory +* Merge branch 'master' into fix/follow_trajectory +* Merge remote-tracking branch 'origin' into fix/follow_trajectory +* Contributors: Masaya Kataoka + 4.0.0 (2024-08-27) ------------------ * Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status diff --git a/external/concealer/package.xml b/external/concealer/package.xml index c17301dc530..73b37aa2a0b 100644 --- a/external/concealer/package.xml +++ b/external/concealer/package.xml @@ -2,7 +2,7 @@ concealer - 4.0.0 + 4.0.1 Provides a class 'Autoware' to conceal miscellaneous things to simplify Autoware management of the simulator. Tatsuya Yamasaki Apache License 2.0 diff --git a/external/embree_vendor/CHANGELOG.rst b/external/embree_vendor/CHANGELOG.rst index d89c788e526..21b51ed81e4 100644 --- a/external/embree_vendor/CHANGELOG.rst +++ b/external/embree_vendor/CHANGELOG.rst @@ -24,6 +24,13 @@ Changelog for package embree_vendor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.1 (2024-08-28) +------------------ +* Merge branch 'master' into fix/follow_trajectory +* Merge branch 'master' into fix/follow_trajectory +* Merge remote-tracking branch 'origin' into fix/follow_trajectory +* Contributors: Masaya Kataoka + 4.0.0 (2024-08-27) ------------------ * Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status diff --git a/external/embree_vendor/package.xml b/external/embree_vendor/package.xml index 259540e6c57..58f9588ef97 100644 --- a/external/embree_vendor/package.xml +++ b/external/embree_vendor/package.xml @@ -2,7 +2,7 @@ embree_vendor - 4.0.0 + 4.0.1 vendor packages for intel raytracing kernel library masaya Apache 2.0 diff --git a/map/kashiwanoha_map/CHANGELOG.rst b/map/kashiwanoha_map/CHANGELOG.rst index 1187e9f6ed8..cfc1b88fe46 100644 --- a/map/kashiwanoha_map/CHANGELOG.rst +++ b/map/kashiwanoha_map/CHANGELOG.rst @@ -21,6 +21,13 @@ Changelog for package kashiwanoha_map * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.1 (2024-08-28) +------------------ +* Merge branch 'master' into fix/follow_trajectory +* Merge branch 'master' into fix/follow_trajectory +* Merge remote-tracking branch 'origin' into fix/follow_trajectory +* Contributors: Masaya Kataoka + 4.0.0 (2024-08-27) ------------------ * Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status diff --git a/map/kashiwanoha_map/package.xml b/map/kashiwanoha_map/package.xml index 7ba96bd7c5f..9dd1feb8811 100644 --- a/map/kashiwanoha_map/package.xml +++ b/map/kashiwanoha_map/package.xml @@ -2,7 +2,7 @@ kashiwanoha_map - 4.0.0 + 4.0.1 map package for kashiwanoha Masaya Kataoka Apache License 2.0 diff --git a/map/simple_cross_map/CHANGELOG.rst b/map/simple_cross_map/CHANGELOG.rst index 421f52a5de8..7e0c7ebe807 100644 --- a/map/simple_cross_map/CHANGELOG.rst +++ b/map/simple_cross_map/CHANGELOG.rst @@ -9,6 +9,13 @@ Changelog for package simple_cross_map * Merge branch 'master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.1 (2024-08-28) +------------------ +* Merge branch 'master' into fix/follow_trajectory +* Merge branch 'master' into fix/follow_trajectory +* Merge remote-tracking branch 'origin' into fix/follow_trajectory +* Contributors: Masaya Kataoka + 4.0.0 (2024-08-27) ------------------ * Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status diff --git a/map/simple_cross_map/package.xml b/map/simple_cross_map/package.xml index 440ac51157e..e677dc10515 100644 --- a/map/simple_cross_map/package.xml +++ b/map/simple_cross_map/package.xml @@ -2,7 +2,7 @@ simple_cross_map - 4.0.0 + 4.0.1 map package for simple cross Masaya Kataoka Apache License 2.0 diff --git a/mock/cpp_mock_scenarios/CHANGELOG.rst b/mock/cpp_mock_scenarios/CHANGELOG.rst index 7fad4612f32..04522f2e6a5 100644 --- a/mock/cpp_mock_scenarios/CHANGELOG.rst +++ b/mock/cpp_mock_scenarios/CHANGELOG.rst @@ -21,6 +21,13 @@ Changelog for package cpp_mock_scenarios * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.1 (2024-08-28) +------------------ +* Merge branch 'master' into fix/follow_trajectory +* Merge branch 'master' into fix/follow_trajectory +* Merge remote-tracking branch 'origin' into fix/follow_trajectory +* Contributors: Masaya Kataoka + 4.0.0 (2024-08-27) ------------------ * Merge pull request `#1320 `_ from tier4/ref/RJD-1053-set-update-canonicalized-entity-status diff --git a/mock/cpp_mock_scenarios/package.xml b/mock/cpp_mock_scenarios/package.xml index 78ffc9d6fd4..6b6bd72812f 100644 --- a/mock/cpp_mock_scenarios/package.xml +++ b/mock/cpp_mock_scenarios/package.xml @@ -2,7 +2,7 @@ cpp_mock_scenarios - 4.0.0 + 4.0.1 C++ mock scenarios masaya Apache License 2.0 diff --git a/openscenario/openscenario_experimental_catalog/CHANGELOG.rst b/openscenario/openscenario_experimental_catalog/CHANGELOG.rst index 0a9c26fab87..0cc316e9b5d 100644 --- a/openscenario/openscenario_experimental_catalog/CHANGELOG.rst +++ b/openscenario/openscenario_experimental_catalog/CHANGELOG.rst @@ -21,6 +21,13 @@ Changelog for package openscenario_experimental_catalog * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.1 (2024-08-28) +------------------ +* Merge branch 'master' into fix/follow_trajectory +* Merge branch 'master' into fix/follow_trajectory +* Merge remote-tracking branch 'origin' into fix/follow_trajectory +* Contributors: Masaya Kataoka + 4.0.0 (2024-08-27) ------------------ * Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status diff --git a/openscenario/openscenario_experimental_catalog/package.xml b/openscenario/openscenario_experimental_catalog/package.xml index ea6780a3616..e57ddb23587 100644 --- a/openscenario/openscenario_experimental_catalog/package.xml +++ b/openscenario/openscenario_experimental_catalog/package.xml @@ -2,7 +2,7 @@ openscenario_experimental_catalog - 4.0.0 + 4.0.1 TIER IV experimental catalogs for OpenSCENARIO Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter/CHANGELOG.rst b/openscenario/openscenario_interpreter/CHANGELOG.rst index 010cf5eda15..e241f116058 100644 --- a/openscenario/openscenario_interpreter/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter/CHANGELOG.rst @@ -32,6 +32,13 @@ Changelog for package openscenario_interpreter * add publish_empty_context parameter * Contributors: Masaya Kataoka +4.0.1 (2024-08-28) +------------------ +* Merge branch 'master' into fix/follow_trajectory +* Merge branch 'master' into fix/follow_trajectory +* Merge remote-tracking branch 'origin' into fix/follow_trajectory +* Contributors: Masaya Kataoka + 4.0.0 (2024-08-27) ------------------ * Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status diff --git a/openscenario/openscenario_interpreter/package.xml b/openscenario/openscenario_interpreter/package.xml index 1a3246c0132..a10be27cf5f 100644 --- a/openscenario/openscenario_interpreter/package.xml +++ b/openscenario/openscenario_interpreter/package.xml @@ -2,7 +2,7 @@ openscenario_interpreter - 4.0.0 + 4.0.1 OpenSCENARIO 1.2.0 interpreter package for Autoware Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter_example/CHANGELOG.rst b/openscenario/openscenario_interpreter_example/CHANGELOG.rst index c106ea65721..073fc6723e6 100644 --- a/openscenario/openscenario_interpreter_example/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter_example/CHANGELOG.rst @@ -21,6 +21,13 @@ Changelog for package openscenario_interpreter_example * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.1 (2024-08-28) +------------------ +* Merge branch 'master' into fix/follow_trajectory +* Merge branch 'master' into fix/follow_trajectory +* Merge remote-tracking branch 'origin' into fix/follow_trajectory +* Contributors: Masaya Kataoka + 4.0.0 (2024-08-27) ------------------ * Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status diff --git a/openscenario/openscenario_interpreter_example/package.xml b/openscenario/openscenario_interpreter_example/package.xml index 8eaba7e3bea..ce15c7e10e6 100644 --- a/openscenario/openscenario_interpreter_example/package.xml +++ b/openscenario/openscenario_interpreter_example/package.xml @@ -3,7 +3,7 @@ openscenario_interpreter_example - 4.0.0 + 4.0.1 Examples for some TIER IV OpenSCENARIO Interpreter's features Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst b/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst index 80d11b578bb..75b6a57ddc1 100644 --- a/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst @@ -21,6 +21,13 @@ Changelog for package openscenario_interpreter_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.1 (2024-08-28) +------------------ +* Merge branch 'master' into fix/follow_trajectory +* Merge branch 'master' into fix/follow_trajectory +* Merge remote-tracking branch 'origin' into fix/follow_trajectory +* Contributors: Masaya Kataoka + 4.0.0 (2024-08-27) ------------------ * Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status diff --git a/openscenario/openscenario_interpreter_msgs/package.xml b/openscenario/openscenario_interpreter_msgs/package.xml index 8951c8831c9..ec4cbe4de0c 100644 --- a/openscenario/openscenario_interpreter_msgs/package.xml +++ b/openscenario/openscenario_interpreter_msgs/package.xml @@ -2,7 +2,7 @@ openscenario_interpreter_msgs - 4.0.0 + 4.0.1 ROS message types for package openscenario_interpreter Yamasaki Tatsuya Apache License 2.0 diff --git a/openscenario/openscenario_preprocessor/CHANGELOG.rst b/openscenario/openscenario_preprocessor/CHANGELOG.rst index 652db237806..d432795c645 100644 --- a/openscenario/openscenario_preprocessor/CHANGELOG.rst +++ b/openscenario/openscenario_preprocessor/CHANGELOG.rst @@ -21,6 +21,13 @@ Changelog for package openscenario_preprocessor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.1 (2024-08-28) +------------------ +* Merge branch 'master' into fix/follow_trajectory +* Merge branch 'master' into fix/follow_trajectory +* Merge remote-tracking branch 'origin' into fix/follow_trajectory +* Contributors: Masaya Kataoka + 4.0.0 (2024-08-27) ------------------ * Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status diff --git a/openscenario/openscenario_preprocessor/package.xml b/openscenario/openscenario_preprocessor/package.xml index 73870766efe..b143a04b9cc 100644 --- a/openscenario/openscenario_preprocessor/package.xml +++ b/openscenario/openscenario_preprocessor/package.xml @@ -3,7 +3,7 @@ openscenario_preprocessor - 4.0.0 + 4.0.1 Example package for TIER IV OpenSCENARIO Interpreter Kotaro Yoshimoto Apache License 2.0 diff --git a/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst b/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst index f221daad775..486258b6f6e 100644 --- a/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst +++ b/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst @@ -21,6 +21,13 @@ Changelog for package openscenario_preprocessor_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.1 (2024-08-28) +------------------ +* Merge branch 'master' into fix/follow_trajectory +* Merge branch 'master' into fix/follow_trajectory +* Merge remote-tracking branch 'origin' into fix/follow_trajectory +* Contributors: Masaya Kataoka + 4.0.0 (2024-08-27) ------------------ * Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status diff --git a/openscenario/openscenario_preprocessor_msgs/package.xml b/openscenario/openscenario_preprocessor_msgs/package.xml index 5c63864697d..49c22a096e1 100644 --- a/openscenario/openscenario_preprocessor_msgs/package.xml +++ b/openscenario/openscenario_preprocessor_msgs/package.xml @@ -2,7 +2,7 @@ openscenario_preprocessor_msgs - 4.0.0 + 4.0.1 ROS message types for package openscenario_preprocessor Kotaro Yoshimoto Apache License 2.0 diff --git a/openscenario/openscenario_utility/CHANGELOG.rst b/openscenario/openscenario_utility/CHANGELOG.rst index acd38f5b37e..9e6a0cff55c 100644 --- a/openscenario/openscenario_utility/CHANGELOG.rst +++ b/openscenario/openscenario_utility/CHANGELOG.rst @@ -24,6 +24,13 @@ Changelog for package openscenario_utility * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.1 (2024-08-28) +------------------ +* Merge branch 'master' into fix/follow_trajectory +* Merge branch 'master' into fix/follow_trajectory +* Merge remote-tracking branch 'origin' into fix/follow_trajectory +* Contributors: Masaya Kataoka + 4.0.0 (2024-08-27) ------------------ * Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status diff --git a/openscenario/openscenario_utility/package.xml b/openscenario/openscenario_utility/package.xml index e1aea7aa002..bddd78b888a 100644 --- a/openscenario/openscenario_utility/package.xml +++ b/openscenario/openscenario_utility/package.xml @@ -2,7 +2,7 @@ openscenario_utility - 4.0.0 + 4.0.1 Utility tools for ASAM OpenSCENARIO 1.2.0 Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_validator/CHANGELOG.rst b/openscenario/openscenario_validator/CHANGELOG.rst index e7ae08f6807..dbc02ffa15e 100644 --- a/openscenario/openscenario_validator/CHANGELOG.rst +++ b/openscenario/openscenario_validator/CHANGELOG.rst @@ -10,6 +10,13 @@ Changelog for package openscenario_validator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.1 (2024-08-28) +------------------ +* Merge branch 'master' into fix/follow_trajectory +* Merge branch 'master' into fix/follow_trajectory +* Merge remote-tracking branch 'origin' into fix/follow_trajectory +* Contributors: Masaya Kataoka + 4.0.0 (2024-08-27) ------------------ * Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status diff --git a/openscenario/openscenario_validator/package.xml b/openscenario/openscenario_validator/package.xml index 2f229820981..727d84b215e 100644 --- a/openscenario/openscenario_validator/package.xml +++ b/openscenario/openscenario_validator/package.xml @@ -2,7 +2,7 @@ openscenario_validator - 4.0.0 + 4.0.1 Validator for OpenSCENARIO 1.3 Kotaro Yoshimoto Apache License 2.0 diff --git a/rviz_plugins/openscenario_visualization/CHANGELOG.rst b/rviz_plugins/openscenario_visualization/CHANGELOG.rst index c6c02437fdc..e9030b9e398 100644 --- a/rviz_plugins/openscenario_visualization/CHANGELOG.rst +++ b/rviz_plugins/openscenario_visualization/CHANGELOG.rst @@ -21,6 +21,13 @@ Changelog for package openscenario_visualization * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.1 (2024-08-28) +------------------ +* Merge branch 'master' into fix/follow_trajectory +* Merge branch 'master' into fix/follow_trajectory +* Merge remote-tracking branch 'origin' into fix/follow_trajectory +* Contributors: Masaya Kataoka + 4.0.0 (2024-08-27) ------------------ * Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status diff --git a/rviz_plugins/openscenario_visualization/package.xml b/rviz_plugins/openscenario_visualization/package.xml index 791d511ac19..bf087c6d752 100644 --- a/rviz_plugins/openscenario_visualization/package.xml +++ b/rviz_plugins/openscenario_visualization/package.xml @@ -2,7 +2,7 @@ openscenario_visualization - 4.0.0 + 4.0.1 Visualization tools for simulation results Masaya Kataoka Kyoichi Sugahara diff --git a/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst b/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst index baa0d2f10f5..76196479a03 100644 --- a/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst +++ b/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst @@ -21,6 +21,13 @@ Changelog for package real_time_factor_control_rviz_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.1 (2024-08-28) +------------------ +* Merge branch 'master' into fix/follow_trajectory +* Merge branch 'master' into fix/follow_trajectory +* Merge remote-tracking branch 'origin' into fix/follow_trajectory +* Contributors: Masaya Kataoka + 4.0.0 (2024-08-27) ------------------ * Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status diff --git a/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml b/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml index 40b8ecaf3db..a85e7d945cb 100644 --- a/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml +++ b/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml @@ -2,7 +2,7 @@ real_time_factor_control_rviz_plugin - 4.0.0 + 4.0.1 Slider controlling real time factor value. Paweł Lech Apache License 2.0 diff --git a/scenario_simulator_v2/CHANGELOG.rst b/scenario_simulator_v2/CHANGELOG.rst index 592d5e608b6..f4b6cded252 100644 --- a/scenario_simulator_v2/CHANGELOG.rst +++ b/scenario_simulator_v2/CHANGELOG.rst @@ -21,6 +21,13 @@ Changelog for package scenario_simulator_v2 * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.1 (2024-08-28) +------------------ +* Merge branch 'master' into fix/follow_trajectory +* Merge branch 'master' into fix/follow_trajectory +* Merge remote-tracking branch 'origin' into fix/follow_trajectory +* Contributors: Masaya Kataoka + 4.0.0 (2024-08-27) ------------------ * Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status diff --git a/scenario_simulator_v2/package.xml b/scenario_simulator_v2/package.xml index c8b28412525..341ff2f1148 100644 --- a/scenario_simulator_v2/package.xml +++ b/scenario_simulator_v2/package.xml @@ -2,7 +2,7 @@ scenario_simulator_v2 - 4.0.0 + 4.0.1 scenario testing framework for Autoware Masaya Kataoka Apache License 2.0 diff --git a/simulation/behavior_tree_plugin/CHANGELOG.rst b/simulation/behavior_tree_plugin/CHANGELOG.rst index 8fd62dccc89..d626c620326 100644 --- a/simulation/behavior_tree_plugin/CHANGELOG.rst +++ b/simulation/behavior_tree_plugin/CHANGELOG.rst @@ -21,6 +21,13 @@ Changelog for package behavior_tree_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.1 (2024-08-28) +------------------ +* Merge branch 'master' into fix/follow_trajectory +* Merge branch 'master' into fix/follow_trajectory +* Merge remote-tracking branch 'origin' into fix/follow_trajectory +* Contributors: Masaya Kataoka + 4.0.0 (2024-08-27) ------------------ * Merge pull request `#1320 `_ from tier4/ref/RJD-1053-set-update-canonicalized-entity-status diff --git a/simulation/behavior_tree_plugin/package.xml b/simulation/behavior_tree_plugin/package.xml index 453923e6f45..73653dde912 100644 --- a/simulation/behavior_tree_plugin/package.xml +++ b/simulation/behavior_tree_plugin/package.xml @@ -2,7 +2,7 @@ behavior_tree_plugin - 4.0.0 + 4.0.1 Behavior tree plugin for traffic_simulator masaya Apache 2.0 diff --git a/simulation/do_nothing_plugin/CHANGELOG.rst b/simulation/do_nothing_plugin/CHANGELOG.rst index 6cf17db778d..3887770331c 100644 --- a/simulation/do_nothing_plugin/CHANGELOG.rst +++ b/simulation/do_nothing_plugin/CHANGELOG.rst @@ -21,6 +21,18 @@ Changelog for package do_nothing_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.1 (2024-08-28) +------------------ +* Merge pull request `#1354 `_ from tier4/fix/follow_trajectory + Fix follow trajectory action and timestamp in entity status +* Merge branch 'master' into fix/follow_trajectory +* Merge branch 'master' into fix/follow_trajectory +* add angular velocity / acceleration as z axis value +* enabel calculate angular accel and jerk +* Merge remote-tracking branch 'origin' into fix/follow_trajectory +* fix interpolate ration calculation +* Contributors: Masaya Kataoka, Tatsuya Yamasaki + 4.0.0 (2024-08-27) ------------------ * Merge pull request `#1320 `_ from tier4/ref/RJD-1053-set-update-canonicalized-entity-status diff --git a/simulation/do_nothing_plugin/package.xml b/simulation/do_nothing_plugin/package.xml index b8fc31e0732..532f61a26a1 100644 --- a/simulation/do_nothing_plugin/package.xml +++ b/simulation/do_nothing_plugin/package.xml @@ -2,7 +2,7 @@ do_nothing_plugin - 4.0.0 + 4.0.1 Behavior plugin for do nothing Masaya Kataoka Apache 2.0 diff --git a/simulation/simple_sensor_simulator/CHANGELOG.rst b/simulation/simple_sensor_simulator/CHANGELOG.rst index 0248e9bcee9..ff982390614 100644 --- a/simulation/simple_sensor_simulator/CHANGELOG.rst +++ b/simulation/simple_sensor_simulator/CHANGELOG.rst @@ -21,6 +21,13 @@ Changelog for package simple_sensor_simulator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.1 (2024-08-28) +------------------ +* Merge branch 'master' into fix/follow_trajectory +* Merge branch 'master' into fix/follow_trajectory +* Merge remote-tracking branch 'origin' into fix/follow_trajectory +* Contributors: Masaya Kataoka + 4.0.0 (2024-08-27) ------------------ * Merge pull request `#1320 `_ from tier4/ref/RJD-1053-set-update-canonicalized-entity-status diff --git a/simulation/simple_sensor_simulator/package.xml b/simulation/simple_sensor_simulator/package.xml index 1581fb4e23c..ca7365c68ce 100644 --- a/simulation/simple_sensor_simulator/package.xml +++ b/simulation/simple_sensor_simulator/package.xml @@ -1,7 +1,7 @@ simple_sensor_simulator - 4.0.0 + 4.0.1 simple_sensor_simulator package masaya kataoka diff --git a/simulation/simulation_interface/CHANGELOG.rst b/simulation/simulation_interface/CHANGELOG.rst index 72af712e74a..54263df3416 100644 --- a/simulation/simulation_interface/CHANGELOG.rst +++ b/simulation/simulation_interface/CHANGELOG.rst @@ -21,6 +21,13 @@ Changelog for package simulation_interface * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.1 (2024-08-28) +------------------ +* Merge branch 'master' into fix/follow_trajectory +* Merge branch 'master' into fix/follow_trajectory +* Merge remote-tracking branch 'origin' into fix/follow_trajectory +* Contributors: Masaya Kataoka + 4.0.0 (2024-08-27) ------------------ * Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status diff --git a/simulation/simulation_interface/package.xml b/simulation/simulation_interface/package.xml index bd51d39719f..3b64b4a5d50 100644 --- a/simulation/simulation_interface/package.xml +++ b/simulation/simulation_interface/package.xml @@ -2,7 +2,7 @@ simulation_interface - 4.0.0 + 4.0.1 packages to define interface between simulator and scenario interpreter Masaya Kataoka Apache License 2.0 diff --git a/simulation/traffic_simulator/CHANGELOG.rst b/simulation/traffic_simulator/CHANGELOG.rst index 95fbb110a65..1187b626236 100644 --- a/simulation/traffic_simulator/CHANGELOG.rst +++ b/simulation/traffic_simulator/CHANGELOG.rst @@ -21,6 +21,17 @@ Changelog for package traffic_simulator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.1 (2024-08-28) +------------------ +* Merge pull request `#1354 `_ from tier4/fix/follow_trajectory + Fix follow trajectory action and timestamp in entity status +* Merge branch 'master' into fix/follow_trajectory +* Merge branch 'master' into fix/follow_trajectory +* Merge remote-tracking branch 'origin' into fix/follow_trajectory +* fix timestamp +* fix timestamp in status_with_trajectory +* Contributors: Masaya Kataoka, Tatsuya Yamasaki + 4.0.0 (2024-08-27) ------------------ * Merge pull request `#1320 `_ from tier4/ref/RJD-1053-set-update-canonicalized-entity-status diff --git a/simulation/traffic_simulator/package.xml b/simulation/traffic_simulator/package.xml index 7f181b61180..aa42fda39d0 100644 --- a/simulation/traffic_simulator/package.xml +++ b/simulation/traffic_simulator/package.xml @@ -1,7 +1,7 @@ traffic_simulator - 4.0.0 + 4.0.1 control traffic flow masaya kataoka diff --git a/simulation/traffic_simulator_msgs/CHANGELOG.rst b/simulation/traffic_simulator_msgs/CHANGELOG.rst index 2364c4edb1d..acdd6da5397 100644 --- a/simulation/traffic_simulator_msgs/CHANGELOG.rst +++ b/simulation/traffic_simulator_msgs/CHANGELOG.rst @@ -21,6 +21,13 @@ Changelog for package openscenario_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.1 (2024-08-28) +------------------ +* Merge branch 'master' into fix/follow_trajectory +* Merge branch 'master' into fix/follow_trajectory +* Merge remote-tracking branch 'origin' into fix/follow_trajectory +* Contributors: Masaya Kataoka + 4.0.0 (2024-08-27) ------------------ * Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status diff --git a/simulation/traffic_simulator_msgs/package.xml b/simulation/traffic_simulator_msgs/package.xml index b491f064996..a5c656b0110 100644 --- a/simulation/traffic_simulator_msgs/package.xml +++ b/simulation/traffic_simulator_msgs/package.xml @@ -2,7 +2,7 @@ traffic_simulator_msgs - 4.0.0 + 4.0.1 ROS messages for openscenario Masaya Kataoka Apache License 2.0 diff --git a/test_runner/random_test_runner/CHANGELOG.rst b/test_runner/random_test_runner/CHANGELOG.rst index c45dc19d818..d55240d8255 100644 --- a/test_runner/random_test_runner/CHANGELOG.rst +++ b/test_runner/random_test_runner/CHANGELOG.rst @@ -21,6 +21,13 @@ Changelog for package random_test_runner * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.1 (2024-08-28) +------------------ +* Merge branch 'master' into fix/follow_trajectory +* Merge branch 'master' into fix/follow_trajectory +* Merge remote-tracking branch 'origin' into fix/follow_trajectory +* Contributors: Masaya Kataoka + 4.0.0 (2024-08-27) ------------------ * Merge pull request `#1320 `_ from tier4/ref/RJD-1053-set-update-canonicalized-entity-status diff --git a/test_runner/random_test_runner/package.xml b/test_runner/random_test_runner/package.xml index de79b0549ea..19052431620 100644 --- a/test_runner/random_test_runner/package.xml +++ b/test_runner/random_test_runner/package.xml @@ -2,7 +2,7 @@ random_test_runner - 4.0.0 + 4.0.1 Random behavior test runner piotr-zyskowski-rai Apache License 2.0 diff --git a/test_runner/scenario_test_runner/CHANGELOG.rst b/test_runner/scenario_test_runner/CHANGELOG.rst index 290a3eb17cd..3334ed01d30 100644 --- a/test_runner/scenario_test_runner/CHANGELOG.rst +++ b/test_runner/scenario_test_runner/CHANGELOG.rst @@ -35,6 +35,13 @@ Changelog for package scenario_test_runner * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.1 (2024-08-28) +------------------ +* Merge branch 'master' into fix/follow_trajectory +* Merge branch 'master' into fix/follow_trajectory +* Merge remote-tracking branch 'origin' into fix/follow_trajectory +* Contributors: Masaya Kataoka + 4.0.0 (2024-08-27) ------------------ * Merge branch 'master' into ref/RJD-1053-set-update-canonicalized-entity-status diff --git a/test_runner/scenario_test_runner/package.xml b/test_runner/scenario_test_runner/package.xml index 0091b9e44d9..ad38e922e42 100644 --- a/test_runner/scenario_test_runner/package.xml +++ b/test_runner/scenario_test_runner/package.xml @@ -2,7 +2,7 @@ scenario_test_runner - 4.0.0 + 4.0.1 scenario test runner package Tatsuya Yamasaki Apache License 2.0 From 10fbcd9a2a91e419755d6790fe60f8bc9c94dc4d Mon Sep 17 00:00:00 2001 From: Release Bot Date: Wed, 28 Aug 2024 10:01:24 +0000 Subject: [PATCH 186/304] Bump version of scenario_simulator_v2 from version 4.0.1 to version 4.0.2 --- common/math/arithmetic/CHANGELOG.rst | 12 +++++++++ common/math/arithmetic/package.xml | 2 +- common/math/geometry/CHANGELOG.rst | 12 +++++++++ common/math/geometry/package.xml | 2 +- .../CHANGELOG.rst | 12 +++++++++ .../scenario_simulator_exception/package.xml | 2 +- common/simple_junit/CHANGELOG.rst | 12 +++++++++ common/simple_junit/package.xml | 2 +- common/status_monitor/CHANGELOG.rst | 12 +++++++++ common/status_monitor/package.xml | 2 +- external/concealer/CHANGELOG.rst | 12 +++++++++ external/concealer/package.xml | 2 +- external/embree_vendor/CHANGELOG.rst | 12 +++++++++ external/embree_vendor/package.xml | 2 +- map/kashiwanoha_map/CHANGELOG.rst | 12 +++++++++ map/kashiwanoha_map/package.xml | 2 +- map/simple_cross_map/CHANGELOG.rst | 8 ++++++ map/simple_cross_map/package.xml | 2 +- mock/cpp_mock_scenarios/CHANGELOG.rst | 12 +++++++++ mock/cpp_mock_scenarios/package.xml | 2 +- .../CHANGELOG.rst | 12 +++++++++ .../package.xml | 2 +- .../openscenario_interpreter/CHANGELOG.rst | 12 +++++++++ .../openscenario_interpreter/package.xml | 2 +- .../CHANGELOG.rst | 12 +++++++++ .../package.xml | 2 +- .../CHANGELOG.rst | 12 +++++++++ .../openscenario_interpreter_msgs/package.xml | 2 +- .../openscenario_preprocessor/CHANGELOG.rst | 12 +++++++++ .../openscenario_preprocessor/package.xml | 2 +- .../CHANGELOG.rst | 12 +++++++++ .../package.xml | 2 +- .../openscenario_utility/CHANGELOG.rst | 12 +++++++++ openscenario/openscenario_utility/package.xml | 2 +- .../openscenario_validator/CHANGELOG.rst | 12 +++++++++ .../openscenario_validator/package.xml | 2 +- .../openscenario_visualization/CHANGELOG.rst | 12 +++++++++ .../openscenario_visualization/package.xml | 2 +- .../CHANGELOG.rst | 12 +++++++++ .../package.xml | 2 +- scenario_simulator_v2/CHANGELOG.rst | 12 +++++++++ scenario_simulator_v2/package.xml | 2 +- simulation/behavior_tree_plugin/CHANGELOG.rst | 16 ++++++++++++ simulation/behavior_tree_plugin/package.xml | 2 +- simulation/do_nothing_plugin/CHANGELOG.rst | 12 +++++++++ simulation/do_nothing_plugin/package.xml | 2 +- .../simple_sensor_simulator/CHANGELOG.rst | 12 +++++++++ .../simple_sensor_simulator/package.xml | 2 +- simulation/simulation_interface/CHANGELOG.rst | 12 +++++++++ simulation/simulation_interface/package.xml | 2 +- simulation/traffic_simulator/CHANGELOG.rst | 26 +++++++++++++++++++ simulation/traffic_simulator/package.xml | 2 +- .../traffic_simulator_msgs/CHANGELOG.rst | 12 +++++++++ simulation/traffic_simulator_msgs/package.xml | 2 +- test_runner/random_test_runner/CHANGELOG.rst | 12 +++++++++ test_runner/random_test_runner/package.xml | 2 +- .../scenario_test_runner/CHANGELOG.rst | 12 +++++++++ test_runner/scenario_test_runner/package.xml | 2 +- 58 files changed, 391 insertions(+), 29 deletions(-) diff --git a/common/math/arithmetic/CHANGELOG.rst b/common/math/arithmetic/CHANGELOG.rst index f0cf2ec7855..3eea6a621bf 100644 --- a/common/math/arithmetic/CHANGELOG.rst +++ b/common/math/arithmetic/CHANGELOG.rst @@ -21,6 +21,18 @@ Changelog for package arithmetic * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.2 (2024-08-28) +------------------ +* Merge branch 'master' into RJD-1056-remove-current-time-step-time +* Merge branch 'master' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge remote-tracking branch 'origin/ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Contributors: DMoszynski, Dawid Moszynski, Dawid Moszyński, Mateusz Palczuk + 4.0.1 (2024-08-28) ------------------ * Merge branch 'master' into fix/follow_trajectory diff --git a/common/math/arithmetic/package.xml b/common/math/arithmetic/package.xml index 3625943a4d7..e1ae74a387f 100644 --- a/common/math/arithmetic/package.xml +++ b/common/math/arithmetic/package.xml @@ -2,7 +2,7 @@ arithmetic - 4.0.1 + 4.0.2 arithmetic library for scenario_simulator_v2 Tatsuya Yamasaki Apache License 2.0 diff --git a/common/math/geometry/CHANGELOG.rst b/common/math/geometry/CHANGELOG.rst index 611fb339998..cea9d9379a5 100644 --- a/common/math/geometry/CHANGELOG.rst +++ b/common/math/geometry/CHANGELOG.rst @@ -21,6 +21,18 @@ Changelog for package geometry * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.2 (2024-08-28) +------------------ +* Merge branch 'master' into RJD-1056-remove-current-time-step-time +* Merge branch 'master' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge remote-tracking branch 'origin/ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Contributors: DMoszynski, Dawid Moszynski, Dawid Moszyński, Mateusz Palczuk + 4.0.1 (2024-08-28) ------------------ * Merge branch 'master' into fix/follow_trajectory diff --git a/common/math/geometry/package.xml b/common/math/geometry/package.xml index 87539646efd..ee62a7ba900 100644 --- a/common/math/geometry/package.xml +++ b/common/math/geometry/package.xml @@ -2,7 +2,7 @@ geometry - 4.0.1 + 4.0.2 geometry math library for scenario_simulator_v2 application Masaya Kataoka Apache License 2.0 diff --git a/common/scenario_simulator_exception/CHANGELOG.rst b/common/scenario_simulator_exception/CHANGELOG.rst index 5b706727192..4de288d7dca 100644 --- a/common/scenario_simulator_exception/CHANGELOG.rst +++ b/common/scenario_simulator_exception/CHANGELOG.rst @@ -21,6 +21,18 @@ Changelog for package scenario_simulator_exception * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.2 (2024-08-28) +------------------ +* Merge branch 'master' into RJD-1056-remove-current-time-step-time +* Merge branch 'master' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge remote-tracking branch 'origin/ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Contributors: DMoszynski, Dawid Moszynski, Dawid Moszyński, Mateusz Palczuk + 4.0.1 (2024-08-28) ------------------ * Merge branch 'master' into fix/follow_trajectory diff --git a/common/scenario_simulator_exception/package.xml b/common/scenario_simulator_exception/package.xml index 8daac31a5d8..3573be7471a 100644 --- a/common/scenario_simulator_exception/package.xml +++ b/common/scenario_simulator_exception/package.xml @@ -2,7 +2,7 @@ scenario_simulator_exception - 4.0.1 + 4.0.2 Exception types for scenario simulator Tatsuya Yamasaki Apache License 2.0 diff --git a/common/simple_junit/CHANGELOG.rst b/common/simple_junit/CHANGELOG.rst index a1aaf142434..d6d8048199f 100644 --- a/common/simple_junit/CHANGELOG.rst +++ b/common/simple_junit/CHANGELOG.rst @@ -21,6 +21,18 @@ Changelog for package junit_exporter * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.2 (2024-08-28) +------------------ +* Merge branch 'master' into RJD-1056-remove-current-time-step-time +* Merge branch 'master' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge remote-tracking branch 'origin/ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Contributors: DMoszynski, Dawid Moszynski, Dawid Moszyński, Mateusz Palczuk + 4.0.1 (2024-08-28) ------------------ * Merge branch 'master' into fix/follow_trajectory diff --git a/common/simple_junit/package.xml b/common/simple_junit/package.xml index 459a77350d7..aa67db709cf 100644 --- a/common/simple_junit/package.xml +++ b/common/simple_junit/package.xml @@ -2,7 +2,7 @@ simple_junit - 4.0.1 + 4.0.2 Lightweight JUnit library for ROS 2 Masaya Kataoka Tatsuya Yamasaki diff --git a/common/status_monitor/CHANGELOG.rst b/common/status_monitor/CHANGELOG.rst index 34e1cfdb571..f784c5c6236 100644 --- a/common/status_monitor/CHANGELOG.rst +++ b/common/status_monitor/CHANGELOG.rst @@ -21,6 +21,18 @@ Changelog for package status_monitor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.2 (2024-08-28) +------------------ +* Merge branch 'master' into RJD-1056-remove-current-time-step-time +* Merge branch 'master' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge remote-tracking branch 'origin/ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Contributors: DMoszynski, Dawid Moszynski, Dawid Moszyński, Mateusz Palczuk + 4.0.1 (2024-08-28) ------------------ * Merge branch 'master' into fix/follow_trajectory diff --git a/common/status_monitor/package.xml b/common/status_monitor/package.xml index 36e7e7bb9cc..b9a66438d63 100644 --- a/common/status_monitor/package.xml +++ b/common/status_monitor/package.xml @@ -2,7 +2,7 @@ status_monitor - 4.0.1 + 4.0.2 none Tatsuya Yamasaki Apache License 2.0 diff --git a/external/concealer/CHANGELOG.rst b/external/concealer/CHANGELOG.rst index bdb4a51fba2..ed3a6c4afa3 100644 --- a/external/concealer/CHANGELOG.rst +++ b/external/concealer/CHANGELOG.rst @@ -21,6 +21,18 @@ Changelog for package concealer * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.2 (2024-08-28) +------------------ +* Merge branch 'master' into RJD-1056-remove-current-time-step-time +* Merge branch 'master' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge remote-tracking branch 'origin/ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Contributors: DMoszynski, Dawid Moszynski, Dawid Moszyński, Mateusz Palczuk + 4.0.1 (2024-08-28) ------------------ * Merge branch 'master' into fix/follow_trajectory diff --git a/external/concealer/package.xml b/external/concealer/package.xml index 73b37aa2a0b..7e314b8d3fb 100644 --- a/external/concealer/package.xml +++ b/external/concealer/package.xml @@ -2,7 +2,7 @@ concealer - 4.0.1 + 4.0.2 Provides a class 'Autoware' to conceal miscellaneous things to simplify Autoware management of the simulator. Tatsuya Yamasaki Apache License 2.0 diff --git a/external/embree_vendor/CHANGELOG.rst b/external/embree_vendor/CHANGELOG.rst index 21b51ed81e4..1a8b4a358ff 100644 --- a/external/embree_vendor/CHANGELOG.rst +++ b/external/embree_vendor/CHANGELOG.rst @@ -24,6 +24,18 @@ Changelog for package embree_vendor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.2 (2024-08-28) +------------------ +* Merge branch 'master' into RJD-1056-remove-current-time-step-time +* Merge branch 'master' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge remote-tracking branch 'origin/ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Contributors: DMoszynski, Dawid Moszynski, Dawid Moszyński, Mateusz Palczuk + 4.0.1 (2024-08-28) ------------------ * Merge branch 'master' into fix/follow_trajectory diff --git a/external/embree_vendor/package.xml b/external/embree_vendor/package.xml index 58f9588ef97..0f3175ec285 100644 --- a/external/embree_vendor/package.xml +++ b/external/embree_vendor/package.xml @@ -2,7 +2,7 @@ embree_vendor - 4.0.1 + 4.0.2 vendor packages for intel raytracing kernel library masaya Apache 2.0 diff --git a/map/kashiwanoha_map/CHANGELOG.rst b/map/kashiwanoha_map/CHANGELOG.rst index cfc1b88fe46..fca9ead920c 100644 --- a/map/kashiwanoha_map/CHANGELOG.rst +++ b/map/kashiwanoha_map/CHANGELOG.rst @@ -21,6 +21,18 @@ Changelog for package kashiwanoha_map * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.2 (2024-08-28) +------------------ +* Merge branch 'master' into RJD-1056-remove-current-time-step-time +* Merge branch 'master' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge remote-tracking branch 'origin/ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Contributors: DMoszynski, Dawid Moszynski, Dawid Moszyński, Mateusz Palczuk + 4.0.1 (2024-08-28) ------------------ * Merge branch 'master' into fix/follow_trajectory diff --git a/map/kashiwanoha_map/package.xml b/map/kashiwanoha_map/package.xml index 9dd1feb8811..ce5a22479d0 100644 --- a/map/kashiwanoha_map/package.xml +++ b/map/kashiwanoha_map/package.xml @@ -2,7 +2,7 @@ kashiwanoha_map - 4.0.1 + 4.0.2 map package for kashiwanoha Masaya Kataoka Apache License 2.0 diff --git a/map/simple_cross_map/CHANGELOG.rst b/map/simple_cross_map/CHANGELOG.rst index 7e0c7ebe807..d534602af7c 100644 --- a/map/simple_cross_map/CHANGELOG.rst +++ b/map/simple_cross_map/CHANGELOG.rst @@ -9,6 +9,14 @@ Changelog for package simple_cross_map * Merge branch 'master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.2 (2024-08-28) +------------------ +* Merge branch 'master' into RJD-1056-remove-current-time-step-time +* Merge branch 'master' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Contributors: Dawid Moszyński, Mateusz Palczuk + 4.0.1 (2024-08-28) ------------------ * Merge branch 'master' into fix/follow_trajectory diff --git a/map/simple_cross_map/package.xml b/map/simple_cross_map/package.xml index e677dc10515..7ec741ec654 100644 --- a/map/simple_cross_map/package.xml +++ b/map/simple_cross_map/package.xml @@ -2,7 +2,7 @@ simple_cross_map - 4.0.1 + 4.0.2 map package for simple cross Masaya Kataoka Apache License 2.0 diff --git a/mock/cpp_mock_scenarios/CHANGELOG.rst b/mock/cpp_mock_scenarios/CHANGELOG.rst index 04522f2e6a5..49e4d9aa494 100644 --- a/mock/cpp_mock_scenarios/CHANGELOG.rst +++ b/mock/cpp_mock_scenarios/CHANGELOG.rst @@ -21,6 +21,18 @@ Changelog for package cpp_mock_scenarios * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.2 (2024-08-28) +------------------ +* Merge branch 'master' into RJD-1056-remove-current-time-step-time +* Merge branch 'master' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge remote-tracking branch 'origin/ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Contributors: DMoszynski, Dawid Moszynski, Dawid Moszyński, Mateusz Palczuk + 4.0.1 (2024-08-28) ------------------ * Merge branch 'master' into fix/follow_trajectory diff --git a/mock/cpp_mock_scenarios/package.xml b/mock/cpp_mock_scenarios/package.xml index 6b6bd72812f..fc798c3714c 100644 --- a/mock/cpp_mock_scenarios/package.xml +++ b/mock/cpp_mock_scenarios/package.xml @@ -2,7 +2,7 @@ cpp_mock_scenarios - 4.0.1 + 4.0.2 C++ mock scenarios masaya Apache License 2.0 diff --git a/openscenario/openscenario_experimental_catalog/CHANGELOG.rst b/openscenario/openscenario_experimental_catalog/CHANGELOG.rst index 0cc316e9b5d..985452638a4 100644 --- a/openscenario/openscenario_experimental_catalog/CHANGELOG.rst +++ b/openscenario/openscenario_experimental_catalog/CHANGELOG.rst @@ -21,6 +21,18 @@ Changelog for package openscenario_experimental_catalog * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.2 (2024-08-28) +------------------ +* Merge branch 'master' into RJD-1056-remove-current-time-step-time +* Merge branch 'master' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge remote-tracking branch 'origin/ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Contributors: DMoszynski, Dawid Moszynski, Dawid Moszyński, Mateusz Palczuk + 4.0.1 (2024-08-28) ------------------ * Merge branch 'master' into fix/follow_trajectory diff --git a/openscenario/openscenario_experimental_catalog/package.xml b/openscenario/openscenario_experimental_catalog/package.xml index e57ddb23587..915d879417b 100644 --- a/openscenario/openscenario_experimental_catalog/package.xml +++ b/openscenario/openscenario_experimental_catalog/package.xml @@ -2,7 +2,7 @@ openscenario_experimental_catalog - 4.0.1 + 4.0.2 TIER IV experimental catalogs for OpenSCENARIO Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter/CHANGELOG.rst b/openscenario/openscenario_interpreter/CHANGELOG.rst index e241f116058..24bc48c0316 100644 --- a/openscenario/openscenario_interpreter/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter/CHANGELOG.rst @@ -32,6 +32,18 @@ Changelog for package openscenario_interpreter * add publish_empty_context parameter * Contributors: Masaya Kataoka +4.0.2 (2024-08-28) +------------------ +* Merge branch 'master' into RJD-1056-remove-current-time-step-time +* Merge branch 'master' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge remote-tracking branch 'origin/ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Contributors: DMoszynski, Dawid Moszynski, Dawid Moszyński, Mateusz Palczuk + 4.0.1 (2024-08-28) ------------------ * Merge branch 'master' into fix/follow_trajectory diff --git a/openscenario/openscenario_interpreter/package.xml b/openscenario/openscenario_interpreter/package.xml index a10be27cf5f..aa546ccfbf3 100644 --- a/openscenario/openscenario_interpreter/package.xml +++ b/openscenario/openscenario_interpreter/package.xml @@ -2,7 +2,7 @@ openscenario_interpreter - 4.0.1 + 4.0.2 OpenSCENARIO 1.2.0 interpreter package for Autoware Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter_example/CHANGELOG.rst b/openscenario/openscenario_interpreter_example/CHANGELOG.rst index 073fc6723e6..21ac7a73a13 100644 --- a/openscenario/openscenario_interpreter_example/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter_example/CHANGELOG.rst @@ -21,6 +21,18 @@ Changelog for package openscenario_interpreter_example * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.2 (2024-08-28) +------------------ +* Merge branch 'master' into RJD-1056-remove-current-time-step-time +* Merge branch 'master' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge remote-tracking branch 'origin/ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Contributors: DMoszynski, Dawid Moszynski, Dawid Moszyński, Mateusz Palczuk + 4.0.1 (2024-08-28) ------------------ * Merge branch 'master' into fix/follow_trajectory diff --git a/openscenario/openscenario_interpreter_example/package.xml b/openscenario/openscenario_interpreter_example/package.xml index ce15c7e10e6..9216e5aec59 100644 --- a/openscenario/openscenario_interpreter_example/package.xml +++ b/openscenario/openscenario_interpreter_example/package.xml @@ -3,7 +3,7 @@ openscenario_interpreter_example - 4.0.1 + 4.0.2 Examples for some TIER IV OpenSCENARIO Interpreter's features Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst b/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst index 75b6a57ddc1..a944ec8b220 100644 --- a/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst @@ -21,6 +21,18 @@ Changelog for package openscenario_interpreter_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.2 (2024-08-28) +------------------ +* Merge branch 'master' into RJD-1056-remove-current-time-step-time +* Merge branch 'master' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge remote-tracking branch 'origin/ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Contributors: DMoszynski, Dawid Moszynski, Dawid Moszyński, Mateusz Palczuk + 4.0.1 (2024-08-28) ------------------ * Merge branch 'master' into fix/follow_trajectory diff --git a/openscenario/openscenario_interpreter_msgs/package.xml b/openscenario/openscenario_interpreter_msgs/package.xml index ec4cbe4de0c..72051b931b5 100644 --- a/openscenario/openscenario_interpreter_msgs/package.xml +++ b/openscenario/openscenario_interpreter_msgs/package.xml @@ -2,7 +2,7 @@ openscenario_interpreter_msgs - 4.0.1 + 4.0.2 ROS message types for package openscenario_interpreter Yamasaki Tatsuya Apache License 2.0 diff --git a/openscenario/openscenario_preprocessor/CHANGELOG.rst b/openscenario/openscenario_preprocessor/CHANGELOG.rst index d432795c645..ee268d19bdf 100644 --- a/openscenario/openscenario_preprocessor/CHANGELOG.rst +++ b/openscenario/openscenario_preprocessor/CHANGELOG.rst @@ -21,6 +21,18 @@ Changelog for package openscenario_preprocessor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.2 (2024-08-28) +------------------ +* Merge branch 'master' into RJD-1056-remove-current-time-step-time +* Merge branch 'master' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge remote-tracking branch 'origin/ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Contributors: DMoszynski, Dawid Moszynski, Dawid Moszyński, Mateusz Palczuk + 4.0.1 (2024-08-28) ------------------ * Merge branch 'master' into fix/follow_trajectory diff --git a/openscenario/openscenario_preprocessor/package.xml b/openscenario/openscenario_preprocessor/package.xml index b143a04b9cc..2a1e3cca1ec 100644 --- a/openscenario/openscenario_preprocessor/package.xml +++ b/openscenario/openscenario_preprocessor/package.xml @@ -3,7 +3,7 @@ openscenario_preprocessor - 4.0.1 + 4.0.2 Example package for TIER IV OpenSCENARIO Interpreter Kotaro Yoshimoto Apache License 2.0 diff --git a/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst b/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst index 486258b6f6e..2f78e66db2d 100644 --- a/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst +++ b/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst @@ -21,6 +21,18 @@ Changelog for package openscenario_preprocessor_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.2 (2024-08-28) +------------------ +* Merge branch 'master' into RJD-1056-remove-current-time-step-time +* Merge branch 'master' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge remote-tracking branch 'origin/ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Contributors: DMoszynski, Dawid Moszynski, Dawid Moszyński, Mateusz Palczuk + 4.0.1 (2024-08-28) ------------------ * Merge branch 'master' into fix/follow_trajectory diff --git a/openscenario/openscenario_preprocessor_msgs/package.xml b/openscenario/openscenario_preprocessor_msgs/package.xml index 49c22a096e1..6d098c0525e 100644 --- a/openscenario/openscenario_preprocessor_msgs/package.xml +++ b/openscenario/openscenario_preprocessor_msgs/package.xml @@ -2,7 +2,7 @@ openscenario_preprocessor_msgs - 4.0.1 + 4.0.2 ROS message types for package openscenario_preprocessor Kotaro Yoshimoto Apache License 2.0 diff --git a/openscenario/openscenario_utility/CHANGELOG.rst b/openscenario/openscenario_utility/CHANGELOG.rst index 9e6a0cff55c..87a358bbb86 100644 --- a/openscenario/openscenario_utility/CHANGELOG.rst +++ b/openscenario/openscenario_utility/CHANGELOG.rst @@ -24,6 +24,18 @@ Changelog for package openscenario_utility * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.2 (2024-08-28) +------------------ +* Merge branch 'master' into RJD-1056-remove-current-time-step-time +* Merge branch 'master' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge remote-tracking branch 'origin/ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Contributors: DMoszynski, Dawid Moszynski, Dawid Moszyński, Mateusz Palczuk + 4.0.1 (2024-08-28) ------------------ * Merge branch 'master' into fix/follow_trajectory diff --git a/openscenario/openscenario_utility/package.xml b/openscenario/openscenario_utility/package.xml index bddd78b888a..fd2a6711791 100644 --- a/openscenario/openscenario_utility/package.xml +++ b/openscenario/openscenario_utility/package.xml @@ -2,7 +2,7 @@ openscenario_utility - 4.0.1 + 4.0.2 Utility tools for ASAM OpenSCENARIO 1.2.0 Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_validator/CHANGELOG.rst b/openscenario/openscenario_validator/CHANGELOG.rst index dbc02ffa15e..5149084599a 100644 --- a/openscenario/openscenario_validator/CHANGELOG.rst +++ b/openscenario/openscenario_validator/CHANGELOG.rst @@ -10,6 +10,18 @@ Changelog for package openscenario_validator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.2 (2024-08-28) +------------------ +* Merge branch 'master' into RJD-1056-remove-current-time-step-time +* Merge branch 'master' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge remote-tracking branch 'origin/ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Contributors: DMoszynski, Dawid Moszynski, Dawid Moszyński, Mateusz Palczuk + 4.0.1 (2024-08-28) ------------------ * Merge branch 'master' into fix/follow_trajectory diff --git a/openscenario/openscenario_validator/package.xml b/openscenario/openscenario_validator/package.xml index 727d84b215e..42b58938422 100644 --- a/openscenario/openscenario_validator/package.xml +++ b/openscenario/openscenario_validator/package.xml @@ -2,7 +2,7 @@ openscenario_validator - 4.0.1 + 4.0.2 Validator for OpenSCENARIO 1.3 Kotaro Yoshimoto Apache License 2.0 diff --git a/rviz_plugins/openscenario_visualization/CHANGELOG.rst b/rviz_plugins/openscenario_visualization/CHANGELOG.rst index e9030b9e398..f46fd32c6de 100644 --- a/rviz_plugins/openscenario_visualization/CHANGELOG.rst +++ b/rviz_plugins/openscenario_visualization/CHANGELOG.rst @@ -21,6 +21,18 @@ Changelog for package openscenario_visualization * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.2 (2024-08-28) +------------------ +* Merge branch 'master' into RJD-1056-remove-current-time-step-time +* Merge branch 'master' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge remote-tracking branch 'origin/ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Contributors: DMoszynski, Dawid Moszynski, Dawid Moszyński, Mateusz Palczuk + 4.0.1 (2024-08-28) ------------------ * Merge branch 'master' into fix/follow_trajectory diff --git a/rviz_plugins/openscenario_visualization/package.xml b/rviz_plugins/openscenario_visualization/package.xml index bf087c6d752..9964516dfe8 100644 --- a/rviz_plugins/openscenario_visualization/package.xml +++ b/rviz_plugins/openscenario_visualization/package.xml @@ -2,7 +2,7 @@ openscenario_visualization - 4.0.1 + 4.0.2 Visualization tools for simulation results Masaya Kataoka Kyoichi Sugahara diff --git a/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst b/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst index 76196479a03..14e511cde28 100644 --- a/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst +++ b/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst @@ -21,6 +21,18 @@ Changelog for package real_time_factor_control_rviz_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.2 (2024-08-28) +------------------ +* Merge branch 'master' into RJD-1056-remove-current-time-step-time +* Merge branch 'master' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge remote-tracking branch 'origin/ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Contributors: DMoszynski, Dawid Moszynski, Dawid Moszyński, Mateusz Palczuk + 4.0.1 (2024-08-28) ------------------ * Merge branch 'master' into fix/follow_trajectory diff --git a/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml b/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml index a85e7d945cb..ba5353a86a1 100644 --- a/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml +++ b/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml @@ -2,7 +2,7 @@ real_time_factor_control_rviz_plugin - 4.0.1 + 4.0.2 Slider controlling real time factor value. Paweł Lech Apache License 2.0 diff --git a/scenario_simulator_v2/CHANGELOG.rst b/scenario_simulator_v2/CHANGELOG.rst index f4b6cded252..f59f51e5e8d 100644 --- a/scenario_simulator_v2/CHANGELOG.rst +++ b/scenario_simulator_v2/CHANGELOG.rst @@ -21,6 +21,18 @@ Changelog for package scenario_simulator_v2 * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.2 (2024-08-28) +------------------ +* Merge branch 'master' into RJD-1056-remove-current-time-step-time +* Merge branch 'master' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge remote-tracking branch 'origin/ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Contributors: DMoszynski, Dawid Moszynski, Dawid Moszyński, Mateusz Palczuk + 4.0.1 (2024-08-28) ------------------ * Merge branch 'master' into fix/follow_trajectory diff --git a/scenario_simulator_v2/package.xml b/scenario_simulator_v2/package.xml index 341ff2f1148..8a5d2fbfdf0 100644 --- a/scenario_simulator_v2/package.xml +++ b/scenario_simulator_v2/package.xml @@ -2,7 +2,7 @@ scenario_simulator_v2 - 4.0.1 + 4.0.2 scenario testing framework for Autoware Masaya Kataoka Apache License 2.0 diff --git a/simulation/behavior_tree_plugin/CHANGELOG.rst b/simulation/behavior_tree_plugin/CHANGELOG.rst index d626c620326..e22038f6eb4 100644 --- a/simulation/behavior_tree_plugin/CHANGELOG.rst +++ b/simulation/behavior_tree_plugin/CHANGELOG.rst @@ -21,6 +21,22 @@ Changelog for package behavior_tree_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.2 (2024-08-28) +------------------ +* Merge pull request `#1356 `_ from tier4/RJD-1056-remove-current-time-step-time + Remove unused data members: current_time step_time +* Merge branch 'master' into RJD-1056-remove-current-time-step-time +* Merge branch 'master' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge remote-tracking branch 'origin/ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Trailing return type +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Add const to time argument in behavior +* Contributors: DMoszynski, Dawid Moszynski, Dawid Moszyński, Masaya Kataoka, Mateusz Palczuk + 4.0.1 (2024-08-28) ------------------ * Merge branch 'master' into fix/follow_trajectory diff --git a/simulation/behavior_tree_plugin/package.xml b/simulation/behavior_tree_plugin/package.xml index 73653dde912..e0cec8884ff 100644 --- a/simulation/behavior_tree_plugin/package.xml +++ b/simulation/behavior_tree_plugin/package.xml @@ -2,7 +2,7 @@ behavior_tree_plugin - 4.0.1 + 4.0.2 Behavior tree plugin for traffic_simulator masaya Apache 2.0 diff --git a/simulation/do_nothing_plugin/CHANGELOG.rst b/simulation/do_nothing_plugin/CHANGELOG.rst index 3887770331c..6b90ad05182 100644 --- a/simulation/do_nothing_plugin/CHANGELOG.rst +++ b/simulation/do_nothing_plugin/CHANGELOG.rst @@ -21,6 +21,18 @@ Changelog for package do_nothing_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.2 (2024-08-28) +------------------ +* Merge branch 'master' into RJD-1056-remove-current-time-step-time +* Merge branch 'master' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge remote-tracking branch 'origin/ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Contributors: DMoszynski, Dawid Moszynski, Dawid Moszyński, Mateusz Palczuk + 4.0.1 (2024-08-28) ------------------ * Merge pull request `#1354 `_ from tier4/fix/follow_trajectory diff --git a/simulation/do_nothing_plugin/package.xml b/simulation/do_nothing_plugin/package.xml index 532f61a26a1..bc4a3caa870 100644 --- a/simulation/do_nothing_plugin/package.xml +++ b/simulation/do_nothing_plugin/package.xml @@ -2,7 +2,7 @@ do_nothing_plugin - 4.0.1 + 4.0.2 Behavior plugin for do nothing Masaya Kataoka Apache 2.0 diff --git a/simulation/simple_sensor_simulator/CHANGELOG.rst b/simulation/simple_sensor_simulator/CHANGELOG.rst index ff982390614..ded1c84e89d 100644 --- a/simulation/simple_sensor_simulator/CHANGELOG.rst +++ b/simulation/simple_sensor_simulator/CHANGELOG.rst @@ -21,6 +21,18 @@ Changelog for package simple_sensor_simulator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.2 (2024-08-28) +------------------ +* Merge branch 'master' into RJD-1056-remove-current-time-step-time +* Merge branch 'master' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge remote-tracking branch 'origin/ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Contributors: DMoszynski, Dawid Moszynski, Dawid Moszyński, Mateusz Palczuk + 4.0.1 (2024-08-28) ------------------ * Merge branch 'master' into fix/follow_trajectory diff --git a/simulation/simple_sensor_simulator/package.xml b/simulation/simple_sensor_simulator/package.xml index ca7365c68ce..5781bd1431d 100644 --- a/simulation/simple_sensor_simulator/package.xml +++ b/simulation/simple_sensor_simulator/package.xml @@ -1,7 +1,7 @@ simple_sensor_simulator - 4.0.1 + 4.0.2 simple_sensor_simulator package masaya kataoka diff --git a/simulation/simulation_interface/CHANGELOG.rst b/simulation/simulation_interface/CHANGELOG.rst index 54263df3416..49ea5583645 100644 --- a/simulation/simulation_interface/CHANGELOG.rst +++ b/simulation/simulation_interface/CHANGELOG.rst @@ -21,6 +21,18 @@ Changelog for package simulation_interface * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.2 (2024-08-28) +------------------ +* Merge branch 'master' into RJD-1056-remove-current-time-step-time +* Merge branch 'master' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge remote-tracking branch 'origin/ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Contributors: DMoszynski, Dawid Moszynski, Dawid Moszyński, Mateusz Palczuk + 4.0.1 (2024-08-28) ------------------ * Merge branch 'master' into fix/follow_trajectory diff --git a/simulation/simulation_interface/package.xml b/simulation/simulation_interface/package.xml index 3b64b4a5d50..46a303c53ca 100644 --- a/simulation/simulation_interface/package.xml +++ b/simulation/simulation_interface/package.xml @@ -2,7 +2,7 @@ simulation_interface - 4.0.1 + 4.0.2 packages to define interface between simulator and scenario interpreter Masaya Kataoka Apache License 2.0 diff --git a/simulation/traffic_simulator/CHANGELOG.rst b/simulation/traffic_simulator/CHANGELOG.rst index 1187b626236..398fa88980a 100644 --- a/simulation/traffic_simulator/CHANGELOG.rst +++ b/simulation/traffic_simulator/CHANGELOG.rst @@ -21,6 +21,32 @@ Changelog for package traffic_simulator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.2 (2024-08-28) +------------------ +* Merge pull request `#1356 `_ from tier4/RJD-1056-remove-current-time-step-time + Remove unused data members: current_time step_time +* Merge branch 'master' into RJD-1056-remove-current-time-step-time +* Fix after using pointer to store entity status +* Merge branch 'master' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Resolve conflicts with stored time +* Merge remote-tracking branch 'origin/ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Trailing return type +* Correct style - add else +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Add const to time argument in behavior +* Add const to time argument +* Use member instead of getter +* Revert to previous macro definition +* Move requestSpeedChange time check responsibility to EgoEntity and simplify +* Correct style +* Remove step_time\_ and current_time\_ data members from EntityManager + Adjust the code so that the time is managed in API only +* Contributors: DMoszynski, Dawid Moszynski, Dawid Moszyński, Masaya Kataoka, Mateusz Palczuk + 4.0.1 (2024-08-28) ------------------ * Merge pull request `#1354 `_ from tier4/fix/follow_trajectory diff --git a/simulation/traffic_simulator/package.xml b/simulation/traffic_simulator/package.xml index aa42fda39d0..f638daa47b4 100644 --- a/simulation/traffic_simulator/package.xml +++ b/simulation/traffic_simulator/package.xml @@ -1,7 +1,7 @@ traffic_simulator - 4.0.1 + 4.0.2 control traffic flow masaya kataoka diff --git a/simulation/traffic_simulator_msgs/CHANGELOG.rst b/simulation/traffic_simulator_msgs/CHANGELOG.rst index acdd6da5397..cd135290fc0 100644 --- a/simulation/traffic_simulator_msgs/CHANGELOG.rst +++ b/simulation/traffic_simulator_msgs/CHANGELOG.rst @@ -21,6 +21,18 @@ Changelog for package openscenario_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.2 (2024-08-28) +------------------ +* Merge branch 'master' into RJD-1056-remove-current-time-step-time +* Merge branch 'master' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge remote-tracking branch 'origin/ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Contributors: DMoszynski, Dawid Moszynski, Dawid Moszyński, Mateusz Palczuk + 4.0.1 (2024-08-28) ------------------ * Merge branch 'master' into fix/follow_trajectory diff --git a/simulation/traffic_simulator_msgs/package.xml b/simulation/traffic_simulator_msgs/package.xml index a5c656b0110..308f10ff0d4 100644 --- a/simulation/traffic_simulator_msgs/package.xml +++ b/simulation/traffic_simulator_msgs/package.xml @@ -2,7 +2,7 @@ traffic_simulator_msgs - 4.0.1 + 4.0.2 ROS messages for openscenario Masaya Kataoka Apache License 2.0 diff --git a/test_runner/random_test_runner/CHANGELOG.rst b/test_runner/random_test_runner/CHANGELOG.rst index d55240d8255..ecf12a30aba 100644 --- a/test_runner/random_test_runner/CHANGELOG.rst +++ b/test_runner/random_test_runner/CHANGELOG.rst @@ -21,6 +21,18 @@ Changelog for package random_test_runner * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.2 (2024-08-28) +------------------ +* Merge branch 'master' into RJD-1056-remove-current-time-step-time +* Merge branch 'master' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge remote-tracking branch 'origin/ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Contributors: DMoszynski, Dawid Moszynski, Dawid Moszyński, Mateusz Palczuk + 4.0.1 (2024-08-28) ------------------ * Merge branch 'master' into fix/follow_trajectory diff --git a/test_runner/random_test_runner/package.xml b/test_runner/random_test_runner/package.xml index 19052431620..27cd06d1d4a 100644 --- a/test_runner/random_test_runner/package.xml +++ b/test_runner/random_test_runner/package.xml @@ -2,7 +2,7 @@ random_test_runner - 4.0.1 + 4.0.2 Random behavior test runner piotr-zyskowski-rai Apache License 2.0 diff --git a/test_runner/scenario_test_runner/CHANGELOG.rst b/test_runner/scenario_test_runner/CHANGELOG.rst index 3334ed01d30..715fda21fa8 100644 --- a/test_runner/scenario_test_runner/CHANGELOG.rst +++ b/test_runner/scenario_test_runner/CHANGELOG.rst @@ -35,6 +35,18 @@ Changelog for package scenario_test_runner * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.2 (2024-08-28) +------------------ +* Merge branch 'master' into RJD-1056-remove-current-time-step-time +* Merge branch 'master' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge remote-tracking branch 'origin/ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-current-time-step-time +* Contributors: DMoszynski, Dawid Moszynski, Dawid Moszyński, Mateusz Palczuk + 4.0.1 (2024-08-28) ------------------ * Merge branch 'master' into fix/follow_trajectory diff --git a/test_runner/scenario_test_runner/package.xml b/test_runner/scenario_test_runner/package.xml index ad38e922e42..df4572a6dab 100644 --- a/test_runner/scenario_test_runner/package.xml +++ b/test_runner/scenario_test_runner/package.xml @@ -2,7 +2,7 @@ scenario_test_runner - 4.0.1 + 4.0.2 scenario test runner package Tatsuya Yamasaki Apache License 2.0 From d6e847651d330ae4d2cc8f7a1cacc2c389e9b2fe Mon Sep 17 00:00:00 2001 From: Dawid Moszynski Date: Wed, 28 Aug 2024 15:23:18 +0200 Subject: [PATCH 187/304] feat(traffic_simulator): apply clang reforamt --- .../src/entity/pedestrian_entity.cpp | 8 +++----- .../traffic_simulator/src/entity/vehicle_entity.cpp | 11 ++++------- 2 files changed, 7 insertions(+), 12 deletions(-) diff --git a/simulation/traffic_simulator/src/entity/pedestrian_entity.cpp b/simulation/traffic_simulator/src/entity/pedestrian_entity.cpp index e73f2e101cd..e9b9572f895 100644 --- a/simulation/traffic_simulator/src/entity/pedestrian_entity.cpp +++ b/simulation/traffic_simulator/src/entity/pedestrian_entity.cpp @@ -12,12 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include -#include - #include #include #include +#include +#include #include namespace traffic_simulator @@ -254,8 +253,7 @@ auto PedestrianEntity::onUpdate(const double current_time, const double step_tim behavior_plugin_ptr_->setCanonicalizedEntityStatus(status_); behavior_plugin_ptr_->setTargetSpeed(target_speed_); behavior_plugin_ptr_->setRouteLanelets(getRouteLanelets()); - /// @note CanonicalizedEntityStatus is updated here, it is not skipped even if isAtEndOfLanelets - /// return true + /// @note CanonicalizedEntityStatus is updated here, it is not skipped even if isAtEndOfLanelets return true behavior_plugin_ptr_->update(current_time, step_time); if (const auto canonicalized_lanelet_pose = status_->getCanonicalizedLaneletPose()) { if (pose::isAtEndOfLanelets(canonicalized_lanelet_pose.value(), hdmap_utils_ptr_)) { diff --git a/simulation/traffic_simulator/src/entity/vehicle_entity.cpp b/simulation/traffic_simulator/src/entity/vehicle_entity.cpp index ac936670feb..deb2a7225cf 100644 --- a/simulation/traffic_simulator/src/entity/vehicle_entity.cpp +++ b/simulation/traffic_simulator/src/entity/vehicle_entity.cpp @@ -12,14 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include -#include - -#include - #include #include #include +#include +#include +#include #include namespace traffic_simulator @@ -147,8 +145,7 @@ auto VehicleEntity::onUpdate(const double current_time, const double step_time) } } behavior_plugin_ptr_->setReferenceTrajectory(spline_); - /// @note CanonicalizedEntityStatus is updated here, it is not skipped even if isAtEndOfLanelets - /// return true + /// @note CanonicalizedEntityStatus is updated here, it is not skipped even if isAtEndOfLanelets return true behavior_plugin_ptr_->update(current_time, step_time); if (const auto canonicalized_lanelet_pose = status_->getCanonicalizedLaneletPose()) { if (pose::isAtEndOfLanelets(canonicalized_lanelet_pose.value(), hdmap_utils_ptr_)) { From dda831d9e90246d04edffe698450c070d1dbd486 Mon Sep 17 00:00:00 2001 From: Release Bot Date: Thu, 29 Aug 2024 04:54:04 +0000 Subject: [PATCH 188/304] Bump version of scenario_simulator_v2 from version 4.0.2 to version 4.0.3 --- common/math/arithmetic/CHANGELOG.rst | 17 ++++++++ common/math/arithmetic/package.xml | 2 +- common/math/geometry/CHANGELOG.rst | 17 ++++++++ common/math/geometry/package.xml | 2 +- .../CHANGELOG.rst | 17 ++++++++ .../scenario_simulator_exception/package.xml | 2 +- common/simple_junit/CHANGELOG.rst | 17 ++++++++ common/simple_junit/package.xml | 2 +- common/status_monitor/CHANGELOG.rst | 17 ++++++++ common/status_monitor/package.xml | 2 +- external/concealer/CHANGELOG.rst | 17 ++++++++ external/concealer/package.xml | 2 +- external/embree_vendor/CHANGELOG.rst | 17 ++++++++ external/embree_vendor/package.xml | 2 +- map/kashiwanoha_map/CHANGELOG.rst | 17 ++++++++ map/kashiwanoha_map/package.xml | 2 +- map/simple_cross_map/CHANGELOG.rst | 11 ++++++ map/simple_cross_map/package.xml | 2 +- mock/cpp_mock_scenarios/CHANGELOG.rst | 17 ++++++++ mock/cpp_mock_scenarios/package.xml | 2 +- .../CHANGELOG.rst | 17 ++++++++ .../package.xml | 2 +- .../openscenario_interpreter/CHANGELOG.rst | 17 ++++++++ .../openscenario_interpreter/package.xml | 2 +- .../CHANGELOG.rst | 17 ++++++++ .../package.xml | 2 +- .../CHANGELOG.rst | 17 ++++++++ .../openscenario_interpreter_msgs/package.xml | 2 +- .../openscenario_preprocessor/CHANGELOG.rst | 17 ++++++++ .../openscenario_preprocessor/package.xml | 2 +- .../CHANGELOG.rst | 17 ++++++++ .../package.xml | 2 +- .../openscenario_utility/CHANGELOG.rst | 17 ++++++++ openscenario/openscenario_utility/package.xml | 2 +- .../openscenario_validator/CHANGELOG.rst | 17 ++++++++ .../openscenario_validator/package.xml | 2 +- .../openscenario_visualization/CHANGELOG.rst | 17 ++++++++ .../openscenario_visualization/package.xml | 2 +- .../CHANGELOG.rst | 17 ++++++++ .../package.xml | 2 +- scenario_simulator_v2/CHANGELOG.rst | 17 ++++++++ scenario_simulator_v2/package.xml | 2 +- simulation/behavior_tree_plugin/CHANGELOG.rst | 17 ++++++++ simulation/behavior_tree_plugin/package.xml | 2 +- simulation/do_nothing_plugin/CHANGELOG.rst | 17 ++++++++ simulation/do_nothing_plugin/package.xml | 2 +- .../simple_sensor_simulator/CHANGELOG.rst | 21 ++++++++++ .../simple_sensor_simulator/package.xml | 2 +- simulation/simulation_interface/CHANGELOG.rst | 17 ++++++++ simulation/simulation_interface/package.xml | 2 +- simulation/traffic_simulator/CHANGELOG.rst | 39 +++++++++++++++++++ simulation/traffic_simulator/package.xml | 2 +- .../traffic_simulator_msgs/CHANGELOG.rst | 17 ++++++++ simulation/traffic_simulator_msgs/package.xml | 2 +- test_runner/random_test_runner/CHANGELOG.rst | 23 +++++++++++ test_runner/random_test_runner/package.xml | 2 +- .../scenario_test_runner/CHANGELOG.rst | 17 ++++++++ test_runner/scenario_test_runner/package.xml | 2 +- 58 files changed, 548 insertions(+), 29 deletions(-) diff --git a/common/math/arithmetic/CHANGELOG.rst b/common/math/arithmetic/CHANGELOG.rst index 3eea6a621bf..071415b7724 100644 --- a/common/math/arithmetic/CHANGELOG.rst +++ b/common/math/arithmetic/CHANGELOG.rst @@ -21,6 +21,23 @@ Changelog for package arithmetic * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.3 (2024-08-29) +------------------ +* Merge remote-tracking branch 'origin/master' into RJD-1056-remove-npc-logic-started +* Merge branch 'RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'RJD-1056-remove-npc-logic-started' into RJD-1057-base +* Merge branch 'RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'tier4/RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'origin/RJD-1056-remove-npc-logic-started' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'origin/ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Contributors: DMoszynski, Dawid Moszynski, Mateusz Palczuk + 4.0.2 (2024-08-28) ------------------ * Merge branch 'master' into RJD-1056-remove-current-time-step-time diff --git a/common/math/arithmetic/package.xml b/common/math/arithmetic/package.xml index e1ae74a387f..1c29900b0a3 100644 --- a/common/math/arithmetic/package.xml +++ b/common/math/arithmetic/package.xml @@ -2,7 +2,7 @@ arithmetic - 4.0.2 + 4.0.3 arithmetic library for scenario_simulator_v2 Tatsuya Yamasaki Apache License 2.0 diff --git a/common/math/geometry/CHANGELOG.rst b/common/math/geometry/CHANGELOG.rst index cea9d9379a5..032cc14a7ae 100644 --- a/common/math/geometry/CHANGELOG.rst +++ b/common/math/geometry/CHANGELOG.rst @@ -21,6 +21,23 @@ Changelog for package geometry * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.3 (2024-08-29) +------------------ +* Merge remote-tracking branch 'origin/master' into RJD-1056-remove-npc-logic-started +* Merge branch 'RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'RJD-1056-remove-npc-logic-started' into RJD-1057-base +* Merge branch 'RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'tier4/RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'origin/RJD-1056-remove-npc-logic-started' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'origin/ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Contributors: DMoszynski, Dawid Moszynski, Mateusz Palczuk + 4.0.2 (2024-08-28) ------------------ * Merge branch 'master' into RJD-1056-remove-current-time-step-time diff --git a/common/math/geometry/package.xml b/common/math/geometry/package.xml index ee62a7ba900..ee5345b7bef 100644 --- a/common/math/geometry/package.xml +++ b/common/math/geometry/package.xml @@ -2,7 +2,7 @@ geometry - 4.0.2 + 4.0.3 geometry math library for scenario_simulator_v2 application Masaya Kataoka Apache License 2.0 diff --git a/common/scenario_simulator_exception/CHANGELOG.rst b/common/scenario_simulator_exception/CHANGELOG.rst index 4de288d7dca..7fb97385a33 100644 --- a/common/scenario_simulator_exception/CHANGELOG.rst +++ b/common/scenario_simulator_exception/CHANGELOG.rst @@ -21,6 +21,23 @@ Changelog for package scenario_simulator_exception * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.3 (2024-08-29) +------------------ +* Merge remote-tracking branch 'origin/master' into RJD-1056-remove-npc-logic-started +* Merge branch 'RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'RJD-1056-remove-npc-logic-started' into RJD-1057-base +* Merge branch 'RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'tier4/RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'origin/RJD-1056-remove-npc-logic-started' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'origin/ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Contributors: DMoszynski, Dawid Moszynski, Mateusz Palczuk + 4.0.2 (2024-08-28) ------------------ * Merge branch 'master' into RJD-1056-remove-current-time-step-time diff --git a/common/scenario_simulator_exception/package.xml b/common/scenario_simulator_exception/package.xml index 3573be7471a..923df025cbb 100644 --- a/common/scenario_simulator_exception/package.xml +++ b/common/scenario_simulator_exception/package.xml @@ -2,7 +2,7 @@ scenario_simulator_exception - 4.0.2 + 4.0.3 Exception types for scenario simulator Tatsuya Yamasaki Apache License 2.0 diff --git a/common/simple_junit/CHANGELOG.rst b/common/simple_junit/CHANGELOG.rst index d6d8048199f..c4995f07eaa 100644 --- a/common/simple_junit/CHANGELOG.rst +++ b/common/simple_junit/CHANGELOG.rst @@ -21,6 +21,23 @@ Changelog for package junit_exporter * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.3 (2024-08-29) +------------------ +* Merge remote-tracking branch 'origin/master' into RJD-1056-remove-npc-logic-started +* Merge branch 'RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'RJD-1056-remove-npc-logic-started' into RJD-1057-base +* Merge branch 'RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'tier4/RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'origin/RJD-1056-remove-npc-logic-started' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'origin/ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Contributors: DMoszynski, Dawid Moszynski, Mateusz Palczuk + 4.0.2 (2024-08-28) ------------------ * Merge branch 'master' into RJD-1056-remove-current-time-step-time diff --git a/common/simple_junit/package.xml b/common/simple_junit/package.xml index aa67db709cf..cda6cfd917e 100644 --- a/common/simple_junit/package.xml +++ b/common/simple_junit/package.xml @@ -2,7 +2,7 @@ simple_junit - 4.0.2 + 4.0.3 Lightweight JUnit library for ROS 2 Masaya Kataoka Tatsuya Yamasaki diff --git a/common/status_monitor/CHANGELOG.rst b/common/status_monitor/CHANGELOG.rst index f784c5c6236..e01a2cb9f43 100644 --- a/common/status_monitor/CHANGELOG.rst +++ b/common/status_monitor/CHANGELOG.rst @@ -21,6 +21,23 @@ Changelog for package status_monitor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.3 (2024-08-29) +------------------ +* Merge remote-tracking branch 'origin/master' into RJD-1056-remove-npc-logic-started +* Merge branch 'RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'RJD-1056-remove-npc-logic-started' into RJD-1057-base +* Merge branch 'RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'tier4/RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'origin/RJD-1056-remove-npc-logic-started' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'origin/ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Contributors: DMoszynski, Dawid Moszynski, Mateusz Palczuk + 4.0.2 (2024-08-28) ------------------ * Merge branch 'master' into RJD-1056-remove-current-time-step-time diff --git a/common/status_monitor/package.xml b/common/status_monitor/package.xml index b9a66438d63..5c5d5e80609 100644 --- a/common/status_monitor/package.xml +++ b/common/status_monitor/package.xml @@ -2,7 +2,7 @@ status_monitor - 4.0.2 + 4.0.3 none Tatsuya Yamasaki Apache License 2.0 diff --git a/external/concealer/CHANGELOG.rst b/external/concealer/CHANGELOG.rst index ed3a6c4afa3..5c4a05c124b 100644 --- a/external/concealer/CHANGELOG.rst +++ b/external/concealer/CHANGELOG.rst @@ -21,6 +21,23 @@ Changelog for package concealer * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.3 (2024-08-29) +------------------ +* Merge remote-tracking branch 'origin/master' into RJD-1056-remove-npc-logic-started +* Merge branch 'RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'RJD-1056-remove-npc-logic-started' into RJD-1057-base +* Merge branch 'RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'tier4/RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'origin/RJD-1056-remove-npc-logic-started' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'origin/ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Contributors: DMoszynski, Dawid Moszynski, Mateusz Palczuk + 4.0.2 (2024-08-28) ------------------ * Merge branch 'master' into RJD-1056-remove-current-time-step-time diff --git a/external/concealer/package.xml b/external/concealer/package.xml index 7e314b8d3fb..3d7adca6741 100644 --- a/external/concealer/package.xml +++ b/external/concealer/package.xml @@ -2,7 +2,7 @@ concealer - 4.0.2 + 4.0.3 Provides a class 'Autoware' to conceal miscellaneous things to simplify Autoware management of the simulator. Tatsuya Yamasaki Apache License 2.0 diff --git a/external/embree_vendor/CHANGELOG.rst b/external/embree_vendor/CHANGELOG.rst index 1a8b4a358ff..81d4fb8e5ed 100644 --- a/external/embree_vendor/CHANGELOG.rst +++ b/external/embree_vendor/CHANGELOG.rst @@ -24,6 +24,23 @@ Changelog for package embree_vendor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.3 (2024-08-29) +------------------ +* Merge remote-tracking branch 'origin/master' into RJD-1056-remove-npc-logic-started +* Merge branch 'RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'RJD-1056-remove-npc-logic-started' into RJD-1057-base +* Merge branch 'RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'tier4/RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'origin/RJD-1056-remove-npc-logic-started' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'origin/ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Contributors: DMoszynski, Dawid Moszynski, Mateusz Palczuk + 4.0.2 (2024-08-28) ------------------ * Merge branch 'master' into RJD-1056-remove-current-time-step-time diff --git a/external/embree_vendor/package.xml b/external/embree_vendor/package.xml index 0f3175ec285..9edba4646ea 100644 --- a/external/embree_vendor/package.xml +++ b/external/embree_vendor/package.xml @@ -2,7 +2,7 @@ embree_vendor - 4.0.2 + 4.0.3 vendor packages for intel raytracing kernel library masaya Apache 2.0 diff --git a/map/kashiwanoha_map/CHANGELOG.rst b/map/kashiwanoha_map/CHANGELOG.rst index fca9ead920c..529fb96066e 100644 --- a/map/kashiwanoha_map/CHANGELOG.rst +++ b/map/kashiwanoha_map/CHANGELOG.rst @@ -21,6 +21,23 @@ Changelog for package kashiwanoha_map * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.3 (2024-08-29) +------------------ +* Merge remote-tracking branch 'origin/master' into RJD-1056-remove-npc-logic-started +* Merge branch 'RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'RJD-1056-remove-npc-logic-started' into RJD-1057-base +* Merge branch 'RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'tier4/RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'origin/RJD-1056-remove-npc-logic-started' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'origin/ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Contributors: DMoszynski, Dawid Moszynski, Mateusz Palczuk + 4.0.2 (2024-08-28) ------------------ * Merge branch 'master' into RJD-1056-remove-current-time-step-time diff --git a/map/kashiwanoha_map/package.xml b/map/kashiwanoha_map/package.xml index ce5a22479d0..fedc916e65a 100644 --- a/map/kashiwanoha_map/package.xml +++ b/map/kashiwanoha_map/package.xml @@ -2,7 +2,7 @@ kashiwanoha_map - 4.0.2 + 4.0.3 map package for kashiwanoha Masaya Kataoka Apache License 2.0 diff --git a/map/simple_cross_map/CHANGELOG.rst b/map/simple_cross_map/CHANGELOG.rst index d534602af7c..a3e643fe4dd 100644 --- a/map/simple_cross_map/CHANGELOG.rst +++ b/map/simple_cross_map/CHANGELOG.rst @@ -9,6 +9,17 @@ Changelog for package simple_cross_map * Merge branch 'master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.3 (2024-08-29) +------------------ +* Merge remote-tracking branch 'origin/master' into RJD-1056-remove-npc-logic-started +* Merge branch 'RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'RJD-1056-remove-npc-logic-started' into RJD-1057-base +* Merge branch 'RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Contributors: DMoszynski, Dawid Moszynski, Mateusz Palczuk + 4.0.2 (2024-08-28) ------------------ * Merge branch 'master' into RJD-1056-remove-current-time-step-time diff --git a/map/simple_cross_map/package.xml b/map/simple_cross_map/package.xml index 7ec741ec654..b298b4db875 100644 --- a/map/simple_cross_map/package.xml +++ b/map/simple_cross_map/package.xml @@ -2,7 +2,7 @@ simple_cross_map - 4.0.2 + 4.0.3 map package for simple cross Masaya Kataoka Apache License 2.0 diff --git a/mock/cpp_mock_scenarios/CHANGELOG.rst b/mock/cpp_mock_scenarios/CHANGELOG.rst index 49e4d9aa494..a950f37148c 100644 --- a/mock/cpp_mock_scenarios/CHANGELOG.rst +++ b/mock/cpp_mock_scenarios/CHANGELOG.rst @@ -21,6 +21,23 @@ Changelog for package cpp_mock_scenarios * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.3 (2024-08-29) +------------------ +* Merge remote-tracking branch 'origin/master' into RJD-1056-remove-npc-logic-started +* Merge branch 'RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'RJD-1056-remove-npc-logic-started' into RJD-1057-base +* Merge branch 'RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'tier4/RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'origin/RJD-1056-remove-npc-logic-started' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'origin/ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Contributors: DMoszynski, Dawid Moszynski, Mateusz Palczuk + 4.0.2 (2024-08-28) ------------------ * Merge branch 'master' into RJD-1056-remove-current-time-step-time diff --git a/mock/cpp_mock_scenarios/package.xml b/mock/cpp_mock_scenarios/package.xml index fc798c3714c..ffe16eb7901 100644 --- a/mock/cpp_mock_scenarios/package.xml +++ b/mock/cpp_mock_scenarios/package.xml @@ -2,7 +2,7 @@ cpp_mock_scenarios - 4.0.2 + 4.0.3 C++ mock scenarios masaya Apache License 2.0 diff --git a/openscenario/openscenario_experimental_catalog/CHANGELOG.rst b/openscenario/openscenario_experimental_catalog/CHANGELOG.rst index 985452638a4..6792d7c61a1 100644 --- a/openscenario/openscenario_experimental_catalog/CHANGELOG.rst +++ b/openscenario/openscenario_experimental_catalog/CHANGELOG.rst @@ -21,6 +21,23 @@ Changelog for package openscenario_experimental_catalog * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.3 (2024-08-29) +------------------ +* Merge remote-tracking branch 'origin/master' into RJD-1056-remove-npc-logic-started +* Merge branch 'RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'RJD-1056-remove-npc-logic-started' into RJD-1057-base +* Merge branch 'RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'tier4/RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'origin/RJD-1056-remove-npc-logic-started' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'origin/ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Contributors: DMoszynski, Dawid Moszynski, Mateusz Palczuk + 4.0.2 (2024-08-28) ------------------ * Merge branch 'master' into RJD-1056-remove-current-time-step-time diff --git a/openscenario/openscenario_experimental_catalog/package.xml b/openscenario/openscenario_experimental_catalog/package.xml index 915d879417b..84fccf2740c 100644 --- a/openscenario/openscenario_experimental_catalog/package.xml +++ b/openscenario/openscenario_experimental_catalog/package.xml @@ -2,7 +2,7 @@ openscenario_experimental_catalog - 4.0.2 + 4.0.3 TIER IV experimental catalogs for OpenSCENARIO Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter/CHANGELOG.rst b/openscenario/openscenario_interpreter/CHANGELOG.rst index 24bc48c0316..89f41eed6ba 100644 --- a/openscenario/openscenario_interpreter/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter/CHANGELOG.rst @@ -32,6 +32,23 @@ Changelog for package openscenario_interpreter * add publish_empty_context parameter * Contributors: Masaya Kataoka +4.0.3 (2024-08-29) +------------------ +* Merge remote-tracking branch 'origin/master' into RJD-1056-remove-npc-logic-started +* Merge branch 'RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'RJD-1056-remove-npc-logic-started' into RJD-1057-base +* Merge branch 'RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'tier4/RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'origin/RJD-1056-remove-npc-logic-started' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'origin/ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Contributors: DMoszynski, Dawid Moszynski, Mateusz Palczuk + 4.0.2 (2024-08-28) ------------------ * Merge branch 'master' into RJD-1056-remove-current-time-step-time diff --git a/openscenario/openscenario_interpreter/package.xml b/openscenario/openscenario_interpreter/package.xml index aa546ccfbf3..fd0035e234c 100644 --- a/openscenario/openscenario_interpreter/package.xml +++ b/openscenario/openscenario_interpreter/package.xml @@ -2,7 +2,7 @@ openscenario_interpreter - 4.0.2 + 4.0.3 OpenSCENARIO 1.2.0 interpreter package for Autoware Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter_example/CHANGELOG.rst b/openscenario/openscenario_interpreter_example/CHANGELOG.rst index 21ac7a73a13..9ba2283cf5d 100644 --- a/openscenario/openscenario_interpreter_example/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter_example/CHANGELOG.rst @@ -21,6 +21,23 @@ Changelog for package openscenario_interpreter_example * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.3 (2024-08-29) +------------------ +* Merge remote-tracking branch 'origin/master' into RJD-1056-remove-npc-logic-started +* Merge branch 'RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'RJD-1056-remove-npc-logic-started' into RJD-1057-base +* Merge branch 'RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'tier4/RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'origin/RJD-1056-remove-npc-logic-started' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'origin/ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Contributors: DMoszynski, Dawid Moszynski, Mateusz Palczuk + 4.0.2 (2024-08-28) ------------------ * Merge branch 'master' into RJD-1056-remove-current-time-step-time diff --git a/openscenario/openscenario_interpreter_example/package.xml b/openscenario/openscenario_interpreter_example/package.xml index 9216e5aec59..27ad47d7620 100644 --- a/openscenario/openscenario_interpreter_example/package.xml +++ b/openscenario/openscenario_interpreter_example/package.xml @@ -3,7 +3,7 @@ openscenario_interpreter_example - 4.0.2 + 4.0.3 Examples for some TIER IV OpenSCENARIO Interpreter's features Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst b/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst index a944ec8b220..c8a3ac1ed5d 100644 --- a/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst @@ -21,6 +21,23 @@ Changelog for package openscenario_interpreter_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.3 (2024-08-29) +------------------ +* Merge remote-tracking branch 'origin/master' into RJD-1056-remove-npc-logic-started +* Merge branch 'RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'RJD-1056-remove-npc-logic-started' into RJD-1057-base +* Merge branch 'RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'tier4/RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'origin/RJD-1056-remove-npc-logic-started' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'origin/ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Contributors: DMoszynski, Dawid Moszynski, Mateusz Palczuk + 4.0.2 (2024-08-28) ------------------ * Merge branch 'master' into RJD-1056-remove-current-time-step-time diff --git a/openscenario/openscenario_interpreter_msgs/package.xml b/openscenario/openscenario_interpreter_msgs/package.xml index 72051b931b5..9e5e69c92ad 100644 --- a/openscenario/openscenario_interpreter_msgs/package.xml +++ b/openscenario/openscenario_interpreter_msgs/package.xml @@ -2,7 +2,7 @@ openscenario_interpreter_msgs - 4.0.2 + 4.0.3 ROS message types for package openscenario_interpreter Yamasaki Tatsuya Apache License 2.0 diff --git a/openscenario/openscenario_preprocessor/CHANGELOG.rst b/openscenario/openscenario_preprocessor/CHANGELOG.rst index ee268d19bdf..3d089f944fe 100644 --- a/openscenario/openscenario_preprocessor/CHANGELOG.rst +++ b/openscenario/openscenario_preprocessor/CHANGELOG.rst @@ -21,6 +21,23 @@ Changelog for package openscenario_preprocessor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.3 (2024-08-29) +------------------ +* Merge remote-tracking branch 'origin/master' into RJD-1056-remove-npc-logic-started +* Merge branch 'RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'RJD-1056-remove-npc-logic-started' into RJD-1057-base +* Merge branch 'RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'tier4/RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'origin/RJD-1056-remove-npc-logic-started' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'origin/ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Contributors: DMoszynski, Dawid Moszynski, Mateusz Palczuk + 4.0.2 (2024-08-28) ------------------ * Merge branch 'master' into RJD-1056-remove-current-time-step-time diff --git a/openscenario/openscenario_preprocessor/package.xml b/openscenario/openscenario_preprocessor/package.xml index 2a1e3cca1ec..7aeb238ce78 100644 --- a/openscenario/openscenario_preprocessor/package.xml +++ b/openscenario/openscenario_preprocessor/package.xml @@ -3,7 +3,7 @@ openscenario_preprocessor - 4.0.2 + 4.0.3 Example package for TIER IV OpenSCENARIO Interpreter Kotaro Yoshimoto Apache License 2.0 diff --git a/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst b/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst index 2f78e66db2d..3fb43fe4051 100644 --- a/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst +++ b/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst @@ -21,6 +21,23 @@ Changelog for package openscenario_preprocessor_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.3 (2024-08-29) +------------------ +* Merge remote-tracking branch 'origin/master' into RJD-1056-remove-npc-logic-started +* Merge branch 'RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'RJD-1056-remove-npc-logic-started' into RJD-1057-base +* Merge branch 'RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'tier4/RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'origin/RJD-1056-remove-npc-logic-started' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'origin/ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Contributors: DMoszynski, Dawid Moszynski, Mateusz Palczuk + 4.0.2 (2024-08-28) ------------------ * Merge branch 'master' into RJD-1056-remove-current-time-step-time diff --git a/openscenario/openscenario_preprocessor_msgs/package.xml b/openscenario/openscenario_preprocessor_msgs/package.xml index 6d098c0525e..2aad028ee03 100644 --- a/openscenario/openscenario_preprocessor_msgs/package.xml +++ b/openscenario/openscenario_preprocessor_msgs/package.xml @@ -2,7 +2,7 @@ openscenario_preprocessor_msgs - 4.0.2 + 4.0.3 ROS message types for package openscenario_preprocessor Kotaro Yoshimoto Apache License 2.0 diff --git a/openscenario/openscenario_utility/CHANGELOG.rst b/openscenario/openscenario_utility/CHANGELOG.rst index 87a358bbb86..47440c02ecb 100644 --- a/openscenario/openscenario_utility/CHANGELOG.rst +++ b/openscenario/openscenario_utility/CHANGELOG.rst @@ -24,6 +24,23 @@ Changelog for package openscenario_utility * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.3 (2024-08-29) +------------------ +* Merge remote-tracking branch 'origin/master' into RJD-1056-remove-npc-logic-started +* Merge branch 'RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'RJD-1056-remove-npc-logic-started' into RJD-1057-base +* Merge branch 'RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'tier4/RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'origin/RJD-1056-remove-npc-logic-started' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'origin/ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Contributors: DMoszynski, Dawid Moszynski, Mateusz Palczuk + 4.0.2 (2024-08-28) ------------------ * Merge branch 'master' into RJD-1056-remove-current-time-step-time diff --git a/openscenario/openscenario_utility/package.xml b/openscenario/openscenario_utility/package.xml index fd2a6711791..29bcf7248fd 100644 --- a/openscenario/openscenario_utility/package.xml +++ b/openscenario/openscenario_utility/package.xml @@ -2,7 +2,7 @@ openscenario_utility - 4.0.2 + 4.0.3 Utility tools for ASAM OpenSCENARIO 1.2.0 Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_validator/CHANGELOG.rst b/openscenario/openscenario_validator/CHANGELOG.rst index 5149084599a..b35540ce799 100644 --- a/openscenario/openscenario_validator/CHANGELOG.rst +++ b/openscenario/openscenario_validator/CHANGELOG.rst @@ -10,6 +10,23 @@ Changelog for package openscenario_validator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.3 (2024-08-29) +------------------ +* Merge remote-tracking branch 'origin/master' into RJD-1056-remove-npc-logic-started +* Merge branch 'RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'RJD-1056-remove-npc-logic-started' into RJD-1057-base +* Merge branch 'RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'tier4/RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'origin/RJD-1056-remove-npc-logic-started' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'origin/ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Contributors: DMoszynski, Dawid Moszynski, Mateusz Palczuk + 4.0.2 (2024-08-28) ------------------ * Merge branch 'master' into RJD-1056-remove-current-time-step-time diff --git a/openscenario/openscenario_validator/package.xml b/openscenario/openscenario_validator/package.xml index 42b58938422..ddcc5bd312f 100644 --- a/openscenario/openscenario_validator/package.xml +++ b/openscenario/openscenario_validator/package.xml @@ -2,7 +2,7 @@ openscenario_validator - 4.0.2 + 4.0.3 Validator for OpenSCENARIO 1.3 Kotaro Yoshimoto Apache License 2.0 diff --git a/rviz_plugins/openscenario_visualization/CHANGELOG.rst b/rviz_plugins/openscenario_visualization/CHANGELOG.rst index f46fd32c6de..83df7d0e31b 100644 --- a/rviz_plugins/openscenario_visualization/CHANGELOG.rst +++ b/rviz_plugins/openscenario_visualization/CHANGELOG.rst @@ -21,6 +21,23 @@ Changelog for package openscenario_visualization * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.3 (2024-08-29) +------------------ +* Merge remote-tracking branch 'origin/master' into RJD-1056-remove-npc-logic-started +* Merge branch 'RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'RJD-1056-remove-npc-logic-started' into RJD-1057-base +* Merge branch 'RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'tier4/RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'origin/RJD-1056-remove-npc-logic-started' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'origin/ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Contributors: DMoszynski, Dawid Moszynski, Mateusz Palczuk + 4.0.2 (2024-08-28) ------------------ * Merge branch 'master' into RJD-1056-remove-current-time-step-time diff --git a/rviz_plugins/openscenario_visualization/package.xml b/rviz_plugins/openscenario_visualization/package.xml index 9964516dfe8..06b03052c70 100644 --- a/rviz_plugins/openscenario_visualization/package.xml +++ b/rviz_plugins/openscenario_visualization/package.xml @@ -2,7 +2,7 @@ openscenario_visualization - 4.0.2 + 4.0.3 Visualization tools for simulation results Masaya Kataoka Kyoichi Sugahara diff --git a/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst b/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst index 14e511cde28..227f0183a4c 100644 --- a/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst +++ b/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst @@ -21,6 +21,23 @@ Changelog for package real_time_factor_control_rviz_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.3 (2024-08-29) +------------------ +* Merge remote-tracking branch 'origin/master' into RJD-1056-remove-npc-logic-started +* Merge branch 'RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'RJD-1056-remove-npc-logic-started' into RJD-1057-base +* Merge branch 'RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'tier4/RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'origin/RJD-1056-remove-npc-logic-started' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'origin/ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Contributors: DMoszynski, Dawid Moszynski, Mateusz Palczuk + 4.0.2 (2024-08-28) ------------------ * Merge branch 'master' into RJD-1056-remove-current-time-step-time diff --git a/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml b/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml index ba5353a86a1..a2cdb4f23ab 100644 --- a/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml +++ b/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml @@ -2,7 +2,7 @@ real_time_factor_control_rviz_plugin - 4.0.2 + 4.0.3 Slider controlling real time factor value. Paweł Lech Apache License 2.0 diff --git a/scenario_simulator_v2/CHANGELOG.rst b/scenario_simulator_v2/CHANGELOG.rst index f59f51e5e8d..48cc5314ef2 100644 --- a/scenario_simulator_v2/CHANGELOG.rst +++ b/scenario_simulator_v2/CHANGELOG.rst @@ -21,6 +21,23 @@ Changelog for package scenario_simulator_v2 * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.3 (2024-08-29) +------------------ +* Merge remote-tracking branch 'origin/master' into RJD-1056-remove-npc-logic-started +* Merge branch 'RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'RJD-1056-remove-npc-logic-started' into RJD-1057-base +* Merge branch 'RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'tier4/RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'origin/RJD-1056-remove-npc-logic-started' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'origin/ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Contributors: DMoszynski, Dawid Moszynski, Mateusz Palczuk + 4.0.2 (2024-08-28) ------------------ * Merge branch 'master' into RJD-1056-remove-current-time-step-time diff --git a/scenario_simulator_v2/package.xml b/scenario_simulator_v2/package.xml index 8a5d2fbfdf0..79fba664888 100644 --- a/scenario_simulator_v2/package.xml +++ b/scenario_simulator_v2/package.xml @@ -2,7 +2,7 @@ scenario_simulator_v2 - 4.0.2 + 4.0.3 scenario testing framework for Autoware Masaya Kataoka Apache License 2.0 diff --git a/simulation/behavior_tree_plugin/CHANGELOG.rst b/simulation/behavior_tree_plugin/CHANGELOG.rst index e22038f6eb4..a84d1462e3e 100644 --- a/simulation/behavior_tree_plugin/CHANGELOG.rst +++ b/simulation/behavior_tree_plugin/CHANGELOG.rst @@ -21,6 +21,23 @@ Changelog for package behavior_tree_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.3 (2024-08-29) +------------------ +* Merge remote-tracking branch 'origin/master' into RJD-1056-remove-npc-logic-started +* Merge branch 'RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'RJD-1056-remove-npc-logic-started' into RJD-1057-base +* Merge branch 'RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'tier4/RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'origin/RJD-1056-remove-npc-logic-started' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'origin/ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Contributors: DMoszynski, Dawid Moszynski, Mateusz Palczuk + 4.0.2 (2024-08-28) ------------------ * Merge pull request `#1356 `_ from tier4/RJD-1056-remove-current-time-step-time diff --git a/simulation/behavior_tree_plugin/package.xml b/simulation/behavior_tree_plugin/package.xml index e0cec8884ff..43c837d63c6 100644 --- a/simulation/behavior_tree_plugin/package.xml +++ b/simulation/behavior_tree_plugin/package.xml @@ -2,7 +2,7 @@ behavior_tree_plugin - 4.0.2 + 4.0.3 Behavior tree plugin for traffic_simulator masaya Apache 2.0 diff --git a/simulation/do_nothing_plugin/CHANGELOG.rst b/simulation/do_nothing_plugin/CHANGELOG.rst index 6b90ad05182..9389fb87965 100644 --- a/simulation/do_nothing_plugin/CHANGELOG.rst +++ b/simulation/do_nothing_plugin/CHANGELOG.rst @@ -21,6 +21,23 @@ Changelog for package do_nothing_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.3 (2024-08-29) +------------------ +* Merge remote-tracking branch 'origin/master' into RJD-1056-remove-npc-logic-started +* Merge branch 'RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'RJD-1056-remove-npc-logic-started' into RJD-1057-base +* Merge branch 'RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'tier4/RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'origin/RJD-1056-remove-npc-logic-started' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'origin/ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Contributors: DMoszynski, Dawid Moszynski, Mateusz Palczuk + 4.0.2 (2024-08-28) ------------------ * Merge branch 'master' into RJD-1056-remove-current-time-step-time diff --git a/simulation/do_nothing_plugin/package.xml b/simulation/do_nothing_plugin/package.xml index bc4a3caa870..7e00ac22e1a 100644 --- a/simulation/do_nothing_plugin/package.xml +++ b/simulation/do_nothing_plugin/package.xml @@ -2,7 +2,7 @@ do_nothing_plugin - 4.0.2 + 4.0.3 Behavior plugin for do nothing Masaya Kataoka Apache 2.0 diff --git a/simulation/simple_sensor_simulator/CHANGELOG.rst b/simulation/simple_sensor_simulator/CHANGELOG.rst index ded1c84e89d..a538f140727 100644 --- a/simulation/simple_sensor_simulator/CHANGELOG.rst +++ b/simulation/simple_sensor_simulator/CHANGELOG.rst @@ -21,6 +21,27 @@ Changelog for package simple_sensor_simulator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.3 (2024-08-29) +------------------ +* Merge pull request `#1358 `_ from tier4/RJD-1056-remove-npc-logic-started + Remove unused data members: npc_logic_started +* Merge remote-tracking branch 'origin/master' into RJD-1056-remove-npc-logic-started +* Merge branch 'RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'RJD-1056-remove-npc-logic-started' into RJD-1057-base +* Merge branch 'RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'tier4/RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'origin/RJD-1056-remove-npc-logic-started' into RJD-1057-base +* ref(ego_entity_simulation): slight improve - add const, rename current_time +* fix(ego_entity): fix autoware update when not npc_logic_started +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'origin/ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Contributors: DMoszynski, Dawid Moszynski, Masaya Kataoka, Mateusz Palczuk + 4.0.2 (2024-08-28) ------------------ * Merge branch 'master' into RJD-1056-remove-current-time-step-time diff --git a/simulation/simple_sensor_simulator/package.xml b/simulation/simple_sensor_simulator/package.xml index 5781bd1431d..9103769b115 100644 --- a/simulation/simple_sensor_simulator/package.xml +++ b/simulation/simple_sensor_simulator/package.xml @@ -1,7 +1,7 @@ simple_sensor_simulator - 4.0.2 + 4.0.3 simple_sensor_simulator package masaya kataoka diff --git a/simulation/simulation_interface/CHANGELOG.rst b/simulation/simulation_interface/CHANGELOG.rst index 49ea5583645..73448aa0c12 100644 --- a/simulation/simulation_interface/CHANGELOG.rst +++ b/simulation/simulation_interface/CHANGELOG.rst @@ -21,6 +21,23 @@ Changelog for package simulation_interface * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.3 (2024-08-29) +------------------ +* Merge remote-tracking branch 'origin/master' into RJD-1056-remove-npc-logic-started +* Merge branch 'RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'RJD-1056-remove-npc-logic-started' into RJD-1057-base +* Merge branch 'RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'tier4/RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'origin/RJD-1056-remove-npc-logic-started' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'origin/ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Contributors: DMoszynski, Dawid Moszynski, Mateusz Palczuk + 4.0.2 (2024-08-28) ------------------ * Merge branch 'master' into RJD-1056-remove-current-time-step-time diff --git a/simulation/simulation_interface/package.xml b/simulation/simulation_interface/package.xml index 46a303c53ca..325d8df7d6a 100644 --- a/simulation/simulation_interface/package.xml +++ b/simulation/simulation_interface/package.xml @@ -2,7 +2,7 @@ simulation_interface - 4.0.2 + 4.0.3 packages to define interface between simulator and scenario interpreter Masaya Kataoka Apache License 2.0 diff --git a/simulation/traffic_simulator/CHANGELOG.rst b/simulation/traffic_simulator/CHANGELOG.rst index 398fa88980a..d8c4e2bed5b 100644 --- a/simulation/traffic_simulator/CHANGELOG.rst +++ b/simulation/traffic_simulator/CHANGELOG.rst @@ -21,6 +21,45 @@ Changelog for package traffic_simulator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.3 (2024-08-29) +------------------ +* Merge pull request `#1358 `_ from tier4/RJD-1056-remove-npc-logic-started + Remove unused data members: npc_logic_started +* feat(traffic_simulator): apply clang reforamt +* Merge remote-tracking branch 'origin/master' into RJD-1056-remove-npc-logic-started +* Merge branch 'RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'RJD-1056-remove-npc-logic-started' into RJD-1057-base +* Merge branch 'RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'tier4/RJD-1056-remove-npc-logic-started' into RJD-1057-base +* Merge remote-tracking branch 'tier4/RJD-1056-remove-current-time-step-time' into RJD-1057-base +* fix(traffic_simulator): remove unnecessary misc_object tests +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'origin/RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge remote-tracking branch 'origin/RJD-1056-remove-npc-logic-started' into RJD-1057-base +* fix(ego_entity): fix autoware update when not npc_logic_started +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Corrections for adapting removed npc logic started +* Merge remote-tracking branch 'origin/ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'origin/RJD-1056-remove-npc-logic-started' into RJD-1057-base +* Correct EntityManager::getCurrentAction +* Add else +* Trailing return type +* Use member instead of getter +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Forward isNpcLogicStarted to API and restore TestExecutor +* Add else +* Move implementation to cpp file +* Remove npc_logic_started from API +* Update NPC logic only when it has been started +* Correct style +* Restore previous getCurrentAction behavior +* Remove npc_logic_started from Entities +* Contributors: DMoszynski, Dawid Moszynski, Masaya Kataoka, Mateusz Palczuk + 4.0.2 (2024-08-28) ------------------ * Merge pull request `#1356 `_ from tier4/RJD-1056-remove-current-time-step-time diff --git a/simulation/traffic_simulator/package.xml b/simulation/traffic_simulator/package.xml index f638daa47b4..0c811088089 100644 --- a/simulation/traffic_simulator/package.xml +++ b/simulation/traffic_simulator/package.xml @@ -1,7 +1,7 @@ traffic_simulator - 4.0.2 + 4.0.3 control traffic flow masaya kataoka diff --git a/simulation/traffic_simulator_msgs/CHANGELOG.rst b/simulation/traffic_simulator_msgs/CHANGELOG.rst index cd135290fc0..77ddc0bc853 100644 --- a/simulation/traffic_simulator_msgs/CHANGELOG.rst +++ b/simulation/traffic_simulator_msgs/CHANGELOG.rst @@ -21,6 +21,23 @@ Changelog for package openscenario_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.3 (2024-08-29) +------------------ +* Merge remote-tracking branch 'origin/master' into RJD-1056-remove-npc-logic-started +* Merge branch 'RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'RJD-1056-remove-npc-logic-started' into RJD-1057-base +* Merge branch 'RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'tier4/RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'origin/RJD-1056-remove-npc-logic-started' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'origin/ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Contributors: DMoszynski, Dawid Moszynski, Mateusz Palczuk + 4.0.2 (2024-08-28) ------------------ * Merge branch 'master' into RJD-1056-remove-current-time-step-time diff --git a/simulation/traffic_simulator_msgs/package.xml b/simulation/traffic_simulator_msgs/package.xml index 308f10ff0d4..2444a632eb7 100644 --- a/simulation/traffic_simulator_msgs/package.xml +++ b/simulation/traffic_simulator_msgs/package.xml @@ -2,7 +2,7 @@ traffic_simulator_msgs - 4.0.2 + 4.0.3 ROS messages for openscenario Masaya Kataoka Apache License 2.0 diff --git a/test_runner/random_test_runner/CHANGELOG.rst b/test_runner/random_test_runner/CHANGELOG.rst index ecf12a30aba..8e16a329471 100644 --- a/test_runner/random_test_runner/CHANGELOG.rst +++ b/test_runner/random_test_runner/CHANGELOG.rst @@ -21,6 +21,29 @@ Changelog for package random_test_runner * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.3 (2024-08-29) +------------------ +* Merge pull request `#1358 `_ from tier4/RJD-1056-remove-npc-logic-started + Remove unused data members: npc_logic_started +* Merge remote-tracking branch 'origin/master' into RJD-1056-remove-npc-logic-started +* Merge branch 'RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'RJD-1056-remove-npc-logic-started' into RJD-1057-base +* Merge branch 'RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'tier4/RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'origin/RJD-1056-remove-npc-logic-started' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'origin/ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'origin/RJD-1056-remove-npc-logic-started' into RJD-1057-base +* Trailing return type +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Forward isNpcLogicStarted to API and restore TestExecutor +* Remove npc_logic_started from API +* Contributors: DMoszynski, Dawid Moszynski, Masaya Kataoka, Mateusz Palczuk + 4.0.2 (2024-08-28) ------------------ * Merge branch 'master' into RJD-1056-remove-current-time-step-time diff --git a/test_runner/random_test_runner/package.xml b/test_runner/random_test_runner/package.xml index 27cd06d1d4a..e281411002d 100644 --- a/test_runner/random_test_runner/package.xml +++ b/test_runner/random_test_runner/package.xml @@ -2,7 +2,7 @@ random_test_runner - 4.0.2 + 4.0.3 Random behavior test runner piotr-zyskowski-rai Apache License 2.0 diff --git a/test_runner/scenario_test_runner/CHANGELOG.rst b/test_runner/scenario_test_runner/CHANGELOG.rst index 715fda21fa8..9d40fbc6fa4 100644 --- a/test_runner/scenario_test_runner/CHANGELOG.rst +++ b/test_runner/scenario_test_runner/CHANGELOG.rst @@ -35,6 +35,23 @@ Changelog for package scenario_test_runner * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.3 (2024-08-29) +------------------ +* Merge remote-tracking branch 'origin/master' into RJD-1056-remove-npc-logic-started +* Merge branch 'RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'RJD-1056-remove-npc-logic-started' into RJD-1057-base +* Merge branch 'RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'tier4/RJD-1056-remove-current-time-step-time' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'origin/RJD-1056-remove-npc-logic-started' into RJD-1057-base +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge remote-tracking branch 'origin/ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Merge branch 'ref/RJD-1053-set-update-canonicalized-entity-status' into RJD-1056-remove-npc-logic-started +* Contributors: DMoszynski, Dawid Moszynski, Mateusz Palczuk + 4.0.2 (2024-08-28) ------------------ * Merge branch 'master' into RJD-1056-remove-current-time-step-time diff --git a/test_runner/scenario_test_runner/package.xml b/test_runner/scenario_test_runner/package.xml index df4572a6dab..14db4ea7f12 100644 --- a/test_runner/scenario_test_runner/package.xml +++ b/test_runner/scenario_test_runner/package.xml @@ -2,7 +2,7 @@ scenario_test_runner - 4.0.2 + 4.0.3 scenario test runner package Tatsuya Yamasaki Apache License 2.0 From 66baecfd61ddaaefe993a09602ae642f4f929594 Mon Sep 17 00:00:00 2001 From: robomic Date: Thu, 29 Aug 2024 11:38:10 +0200 Subject: [PATCH 189/304] longitudinal distance tests --- .../traffic_simulator/test/CMakeLists.txt | 9 +- .../test/src/utils/CMakeLists.txt | 2 + .../test/src/utils/test_distance.cpp | 329 ++++++++++++++++++ 3 files changed, 336 insertions(+), 4 deletions(-) create mode 100644 simulation/traffic_simulator/test/src/utils/CMakeLists.txt create mode 100644 simulation/traffic_simulator/test/src/utils/test_distance.cpp diff --git a/simulation/traffic_simulator/test/CMakeLists.txt b/simulation/traffic_simulator/test/CMakeLists.txt index 713c8b40678..f60dfacda88 100644 --- a/simulation/traffic_simulator/test/CMakeLists.txt +++ b/simulation/traffic_simulator/test/CMakeLists.txt @@ -1,7 +1,8 @@ -add_subdirectory(src/traffic_lights) -add_subdirectory(src/helper) -add_subdirectory(src/entity) add_subdirectory(src/behavior) +add_subdirectory(src/entity) +add_subdirectory(src/hdmap_utils) +add_subdirectory(src/helper) add_subdirectory(src/job) add_subdirectory(src/simulation_clock) -add_subdirectory(src/hdmap_utils) +add_subdirectory(src/traffic_lights) +add_subdirectory(src/utils) diff --git a/simulation/traffic_simulator/test/src/utils/CMakeLists.txt b/simulation/traffic_simulator/test/src/utils/CMakeLists.txt new file mode 100644 index 00000000000..29fb6b608ab --- /dev/null +++ b/simulation/traffic_simulator/test/src/utils/CMakeLists.txt @@ -0,0 +1,2 @@ +ament_add_gtest(test_distance test_distance.cpp) +target_link_libraries(test_distance traffic_simulator) diff --git a/simulation/traffic_simulator/test/src/utils/test_distance.cpp b/simulation/traffic_simulator/test/src/utils/test_distance.cpp new file mode 100644 index 00000000000..7fb03b977c7 --- /dev/null +++ b/simulation/traffic_simulator/test/src/utils/test_distance.cpp @@ -0,0 +1,329 @@ +// Copyright 2015 TIER IV, Inc. All rights reserved. +// +// 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. + +#include + +#include +#include +#include +#include +#include +#include + +int main(int argc, char ** argv) +{ + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} + +/** + * @note Test if the function correctly uses getLateralDistance. Test with a scenario + * in which it is impossible to calculate the distance, e.g. not connected lanelets + * and with allow_lane_change = false. + */ +TEST(distance, lateralDistance_impossible_noChange) +{ + auto hdmap_utils_ptr = std::make_shared( + ament_index_cpp::get_package_share_directory("traffic_simulator") + + "/map/four_track_highway/lanelet2_map.osm", + geographic_msgs::build() + .latitude(35.22312494055522) + .longitude(138.8024583466017) + .altitude(0.0)); + const auto pose_from = traffic_simulator::helper::constructCanonicalizedLaneletPose( + 3002184L, 0.0, 0.0, hdmap_utils_ptr); + const auto pose_to = + traffic_simulator::helper::constructCanonicalizedLaneletPose(202L, 0.0, 0.0, hdmap_utils_ptr); + { + const auto result = traffic_simulator::distance::lateralDistance( + pose_from, pose_to, std::numeric_limits::infinity(), false, hdmap_utils_ptr); + EXPECT_FALSE(result.has_value()); + } + { + const auto result = + traffic_simulator::distance::lateralDistance(pose_from, pose_to, false, hdmap_utils_ptr); + EXPECT_FALSE(result.has_value()); + } +} + +/** + * @note Test if the function correctly uses getLateralDistance. Test with a scenario + * in which it is possible to calculate the distance + * and with allow_lane_change = false. + */ +TEST(distance, lateralDistance_possible_noChange) +{ + auto hdmap_utils_ptr = std::make_shared( + ament_index_cpp::get_package_share_directory("traffic_simulator") + + "/map/four_track_highway/lanelet2_map.osm", + geographic_msgs::build() + .latitude(35.22312494055522) + .longitude(138.8024583466017) + .altitude(0.0)); + const auto pose_from = traffic_simulator::helper::constructCanonicalizedLaneletPose( + 3002184L, 0.0, 0.0, hdmap_utils_ptr); + const auto pose_to = + traffic_simulator::helper::constructCanonicalizedLaneletPose(201L, 0.0, 0.0, hdmap_utils_ptr); + { + const auto result = traffic_simulator::distance::lateralDistance( + pose_from, pose_to, std::numeric_limits::infinity(), false, hdmap_utils_ptr); + ASSERT_TRUE(result.has_value()); + EXPECT_NEAR(result.value(), 0.0, std::numeric_limits::epsilon()); + } + { + const auto result = + traffic_simulator::distance::lateralDistance(pose_from, pose_to, false, hdmap_utils_ptr); + ASSERT_TRUE(result.has_value()); + EXPECT_NEAR(result.value(), 0.0, std::numeric_limits::epsilon()); + } +} + +/** + * @note Test if the function correctly uses getLateralDistance. Test with a scenario + * in which it is impossible to calculate the distance, e.g. not connected lanelets + * and with allow_lane_change = true. + */ +TEST(distance, lateralDistance_impossible_change) +{ + auto hdmap_utils_ptr = std::make_shared( + ament_index_cpp::get_package_share_directory("traffic_simulator") + + "/map/four_track_highway/lanelet2_map.osm", + geographic_msgs::build() + .latitude(35.22312494055522) + .longitude(138.8024583466017) + .altitude(0.0)); + const auto pose_from = + traffic_simulator::helper::constructCanonicalizedLaneletPose(202L, 0.0, 0.0, hdmap_utils_ptr); + const auto pose_to = traffic_simulator::helper::constructCanonicalizedLaneletPose( + 3002184L, 0.0, 0.0, hdmap_utils_ptr); + { + const auto result = traffic_simulator::distance::lateralDistance( + pose_from, pose_to, std::numeric_limits::infinity(), true, hdmap_utils_ptr); + EXPECT_FALSE(result.has_value()); + } + { + const auto result = + traffic_simulator::distance::lateralDistance(pose_from, pose_to, true, hdmap_utils_ptr); + EXPECT_FALSE(result.has_value()); + } +} + +/** + * @note Test if the function correctly uses getLateralDistance. Test with a scenario + * in which it is possible to calculate the distance + * and with allow_lane_change = true. + */ +TEST(distance, lateralDistance_possible_change) +{ + auto hdmap_utils_ptr = std::make_shared( + ament_index_cpp::get_package_share_directory("traffic_simulator") + + "/map/four_track_highway/lanelet2_map.osm", + geographic_msgs::build() + .latitude(35.22312494055522) + .longitude(138.8024583466017) + .altitude(0.0)); + const auto pose_from = traffic_simulator::helper::constructCanonicalizedLaneletPose( + 3002184L, 0.0, 0.0, hdmap_utils_ptr); + const auto pose_to = + traffic_simulator::helper::constructCanonicalizedLaneletPose(202L, 0.0, 0.0, hdmap_utils_ptr); + constexpr double approx_distance = -3.0; + constexpr double tolerance = 0.5; + { + const auto result = traffic_simulator::distance::lateralDistance( + pose_from, pose_to, std::numeric_limits::infinity(), true, hdmap_utils_ptr); + ASSERT_TRUE(result.has_value()); + EXPECT_NEAR(result.value(), approx_distance, tolerance); + } + { + const auto result = + traffic_simulator::distance::lateralDistance(pose_from, pose_to, true, hdmap_utils_ptr); + ASSERT_TRUE(result.has_value()); + EXPECT_NEAR(result.value(), approx_distance, tolerance); + } +} + +/** + * @note Test if the function correctly uses getLateralDistance. Test with a scenario + * in which it is possible to calculate the distance, but matching_distance is too small. + */ +TEST(distance, lateralDistance_impossible_matching) +{ + auto hdmap_utils_ptr = std::make_shared( + ament_index_cpp::get_package_share_directory("traffic_simulator") + + "/map/four_track_highway/lanelet2_map.osm", + geographic_msgs::build() + .latitude(35.22312494055522) + .longitude(138.8024583466017) + .altitude(0.0)); + const auto pose_from = + traffic_simulator::helper::constructCanonicalizedLaneletPose(202L, 0.0, 0.0, hdmap_utils_ptr); + const auto pose_to = traffic_simulator::helper::constructCanonicalizedLaneletPose( + 3002184L, 0.0, 0.0, hdmap_utils_ptr); + { + const auto result = + traffic_simulator::distance::lateralDistance(pose_from, pose_to, 2.0, true, hdmap_utils_ptr); + EXPECT_FALSE(result.has_value()); + } +} + +/** + * @note Test if the function correctly uses getLateralDistance. Test with a scenario + * in which it is possible to calculate the distance and matching_distance is large. + */ +TEST(distance, lateralDistance_possible_matching) +{ + auto hdmap_utils_ptr = std::make_shared( + ament_index_cpp::get_package_share_directory("traffic_simulator") + + "/map/four_track_highway/lanelet2_map.osm", + geographic_msgs::build() + .latitude(35.22312494055522) + .longitude(138.8024583466017) + .altitude(0.0)); + const auto pose_from = traffic_simulator::helper::constructCanonicalizedLaneletPose( + 3002184L, 0.0, 0.0, hdmap_utils_ptr); + const auto pose_to = + traffic_simulator::helper::constructCanonicalizedLaneletPose(202L, 0.0, 0.0, hdmap_utils_ptr); + constexpr double approx_distance = -3.0; + constexpr double tolerance = 0.5; + { + const auto result = + traffic_simulator::distance::lateralDistance(pose_from, pose_to, 3.0, true, hdmap_utils_ptr); + ASSERT_TRUE(result.has_value()); + EXPECT_NEAR(result.value(), approx_distance, tolerance); + } +} + +constexpr auto convertDegToRad(const double deg) -> double { return deg / 180.0 * M_PI; } +constexpr auto convertRadToDeg(const double rad) -> double { return rad * 180.0 / M_PI; } + +auto makePose(const double x, const double y, const double yaw_deg) -> geometry_msgs::msg::Pose +{ + /** + * @note +x axis is 0 degrees; +y axis is 90 degrees + */ + return geometry_msgs::build() + .position(geometry_msgs::build().x(x).y(y).z(0.0)) + .orientation(math::geometry::convertEulerAngleToQuaternion( + geometry_msgs::build().x(0.0).y(0.0).z( + convertDegToRad(yaw_deg)))); +} + +/** + * @note Test calculation correctness with include_adjacent_lanelet = false, + * include_opposite_direction = false, allow_lane_change = false + * in an impossible scenario, e.g. no path. + */ +TEST(distance, longitudinalDistance_noAdjacent_noOpposite_noChange_false) +{ + auto hdmap_utils_ptr = std::make_shared( + ament_index_cpp::get_package_share_directory("traffic_simulator") + + "/map/four_track_highway/lanelet2_map.osm", + geographic_msgs::build() + .latitude(35.22312494055522) + .longitude(138.8024583466017) + .altitude(0.0)); + + const auto pose_from = traffic_simulator::toCanonicalizedLaneletPose( + makePose(81595.44, 50006.09, 100.0), false, hdmap_utils_ptr); + const auto pose_to = traffic_simulator::toCanonicalizedLaneletPose( + makePose(81584.48, 50084.76, 100.0), false, hdmap_utils_ptr); + { + const auto result = traffic_simulator::distance::longitudinalDistance( + pose_from.value(), pose_to.value(), false, false, false, hdmap_utils_ptr); + EXPECT_FALSE(result.has_value()); + } +} + +/** + * @note Test calculation correctness with include_adjacent_lanelet = false, + * include_opposite_direction = false, allow_lane_change = false + * in a scenario that meets those criteria. + */ +TEST(distance, longitudinalDistance_noAdjacent_noOpposite_noChange) +{ + auto hdmap_utils_ptr = std::make_shared( + ament_index_cpp::get_package_share_directory("traffic_simulator") + "/map/lanelet2_map.osm", + geographic_msgs::build() + .latitude(35.61836750154) + .longitude(139.78066608243) + .altitude(0.0)); + + const auto pose_from = traffic_simulator::toCanonicalizedLaneletPose( + makePose(3800.05, 73715.77, 30.0), false, hdmap_utils_ptr); + const auto pose_to = traffic_simulator::toCanonicalizedLaneletPose( + makePose(3841.26, 73748.80, 110.0), false, hdmap_utils_ptr); + { + constexpr double approx_distance = 60.0; + constexpr double tolerance = 1.0; + const auto result = traffic_simulator::distance::longitudinalDistance( + pose_from.value(), pose_to.value(), false, false, false, hdmap_utils_ptr); + ASSERT_TRUE(result.has_value()); + EXPECT_NEAR(result.value(), approx_distance, tolerance); + } +} + +/** + * @note Test calculation correctness with include_adjacent_lanelet = true, + * include_opposite_direction = false, allow_lane_change = false + * in an impossible scenario, e.g. no path. + */ +TEST(distance, longitudinalDistance_adjacent_noOpposite_noChange_false) +{ + auto hdmap_utils_ptr = std::make_shared( + ament_index_cpp::get_package_share_directory("traffic_simulator") + + "/map/four_track_highway/lanelet2_map.osm", + geographic_msgs::build() + .latitude(35.22312494055522) + .longitude(138.8024583466017) + .altitude(0.0)); + + const auto pose_from = traffic_simulator::toCanonicalizedLaneletPose( + makePose(81585.79, 50042.62, 100.0), false, hdmap_utils_ptr); + const auto pose_to = traffic_simulator::toCanonicalizedLaneletPose( + makePose(81588.34, 50083.23, 100.0), false, hdmap_utils_ptr); + { + const auto result = traffic_simulator::distance::longitudinalDistance( + pose_from.value(), pose_to.value(), true, false, false, hdmap_utils_ptr); + EXPECT_FALSE(result.has_value()); + } +} + +/** + * @note Test calculation correctness with include_adjacent_lanelet = true, + * include_opposite_direction = false, allow_lane_change = false + * in a scenario that meets those criteria. + */ +TEST(distance, longitudinalDistance_adjacent_noOpposite_noChange) +{ + auto hdmap_utils_ptr = std::make_shared( + ament_index_cpp::get_package_share_directory("traffic_simulator") + + "/map/four_track_highway/lanelet2_map.osm", + geographic_msgs::build() + .latitude(35.22312494055522) + .longitude(138.8024583466017) + .altitude(0.0)); + + const auto pose_from = traffic_simulator::toCanonicalizedLaneletPose( + makePose(81599.02, 50065.76, 280.0), false, hdmap_utils_ptr); + const auto pose_to = traffic_simulator::toCanonicalizedLaneletPose( + makePose(81599.61, 50045.16, 280.0), false, hdmap_utils_ptr); + { + constexpr double approx_distance = 20.0; + constexpr double tolerance = 1.0; + const auto result = traffic_simulator::distance::longitudinalDistance( + pose_from.value(), pose_to.value(), true, false, false, hdmap_utils_ptr); + ASSERT_TRUE(result.has_value()); + EXPECT_NEAR(result.value(), approx_distance, tolerance); + } +} \ No newline at end of file From b734f9e7d34af7d0f50b965949440c584244d58e Mon Sep 17 00:00:00 2001 From: Dawid Moszynski Date: Fri, 30 Aug 2024 10:25:42 +0200 Subject: [PATCH 190/304] ref(doc): change ss2 to scenario_simulator_v2 --- .../scenario_test_runner/RealtimeFactor.md | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/docs/user_guide/scenario_test_runner/RealtimeFactor.md b/docs/user_guide/scenario_test_runner/RealtimeFactor.md index 61aa1c3b180..4b9e7d66d00 100644 --- a/docs/user_guide/scenario_test_runner/RealtimeFactor.md +++ b/docs/user_guide/scenario_test_runner/RealtimeFactor.md @@ -59,20 +59,20 @@ Parameter `use_sim_time` of `openscenario_interpreter` is **false** by default a However, this impacts the time published on the `/clock` topic and the time used by `Autoware`. Details are shown in the table below: -| use_sim_time launch parameter | /clock time published by SS2 | AWF Autoware Time | -| ----------------------------- | ---------------------------- | ---------------------- | -| false | walltime | walltime from /clock | -| true (default) | simulation | simulation from /clock | +| use_sim_time launch parameter | /clock time published by scenario_simulator_v2 | AWF Autoware Time | +| ----------------------------- | ---------------------------------------------- | ---------------------- | +| false | walltime | walltime from /clock | +| true (default) | simulation | simulation from /clock | -Below are also some bullet points explaining the impact of the `use_sim_time` parameter on `SS2` and `Autoware`: +Below are also some bullet points explaining the impact of the `use_sim_time` parameter on `scenario_simulator_v2` and `Autoware`: - **`use_sim_time:=True` passed using command line (default value)** - - Both Autoware and SS2 are launched with `use_sim_time=true`. + - Both Autoware and scenario_simulator_v2 are launched with `use_sim_time=true`. - Time published on `/clock` is the **simulation time** (starting from 0). - Time published on `/clock` **can be** controlled by RViz plugin. - Simulation time **can be** controlled by RViz plugin. - **`use_sim_time:=False` passed using command line** - - Both Autoware and SS2 are launched with `use_sim_time=false`. + - Both Autoware and scenario_simulator_v2 are launched with `use_sim_time=false`. - Time published on `/clock` is the **walltime**. - Time published on `/clock` **cannot be** controlled by RViz plugin. - Simulation time **can be** controlled by RViz plugin. From e474c0617e03b58628734e08599fd8dc47667aa1 Mon Sep 17 00:00:00 2001 From: Release Bot Date: Mon, 2 Sep 2024 05:04:00 +0000 Subject: [PATCH 191/304] Bump version of scenario_simulator_v2 from version 4.0.3 to version 4.0.4 --- common/math/arithmetic/CHANGELOG.rst | 7 +++++++ common/math/arithmetic/package.xml | 2 +- common/math/geometry/CHANGELOG.rst | 7 +++++++ common/math/geometry/package.xml | 2 +- .../scenario_simulator_exception/CHANGELOG.rst | 7 +++++++ .../scenario_simulator_exception/package.xml | 2 +- common/simple_junit/CHANGELOG.rst | 7 +++++++ common/simple_junit/package.xml | 2 +- common/status_monitor/CHANGELOG.rst | 7 +++++++ common/status_monitor/package.xml | 2 +- external/concealer/CHANGELOG.rst | 7 +++++++ external/concealer/package.xml | 2 +- external/embree_vendor/CHANGELOG.rst | 7 +++++++ external/embree_vendor/package.xml | 2 +- map/kashiwanoha_map/CHANGELOG.rst | 7 +++++++ map/kashiwanoha_map/package.xml | 2 +- map/simple_cross_map/CHANGELOG.rst | 7 +++++++ map/simple_cross_map/package.xml | 2 +- mock/cpp_mock_scenarios/CHANGELOG.rst | 7 +++++++ mock/cpp_mock_scenarios/package.xml | 2 +- .../CHANGELOG.rst | 7 +++++++ .../package.xml | 2 +- .../openscenario_interpreter/CHANGELOG.rst | 7 +++++++ .../openscenario_interpreter/package.xml | 2 +- .../CHANGELOG.rst | 7 +++++++ .../package.xml | 2 +- .../CHANGELOG.rst | 7 +++++++ .../openscenario_interpreter_msgs/package.xml | 2 +- .../openscenario_preprocessor/CHANGELOG.rst | 7 +++++++ .../openscenario_preprocessor/package.xml | 2 +- .../CHANGELOG.rst | 7 +++++++ .../openscenario_preprocessor_msgs/package.xml | 2 +- .../openscenario_utility/CHANGELOG.rst | 7 +++++++ openscenario/openscenario_utility/package.xml | 2 +- .../openscenario_validator/CHANGELOG.rst | 7 +++++++ .../openscenario_validator/package.xml | 2 +- .../openscenario_visualization/CHANGELOG.rst | 7 +++++++ .../openscenario_visualization/package.xml | 2 +- .../CHANGELOG.rst | 7 +++++++ .../package.xml | 2 +- scenario_simulator_v2/CHANGELOG.rst | 7 +++++++ scenario_simulator_v2/package.xml | 2 +- simulation/behavior_tree_plugin/CHANGELOG.rst | 7 +++++++ simulation/behavior_tree_plugin/package.xml | 2 +- simulation/do_nothing_plugin/CHANGELOG.rst | 7 +++++++ simulation/do_nothing_plugin/package.xml | 2 +- .../simple_sensor_simulator/CHANGELOG.rst | 18 ++++++++++++++++++ simulation/simple_sensor_simulator/package.xml | 2 +- simulation/simulation_interface/CHANGELOG.rst | 7 +++++++ simulation/simulation_interface/package.xml | 2 +- simulation/traffic_simulator/CHANGELOG.rst | 7 +++++++ simulation/traffic_simulator/package.xml | 2 +- .../traffic_simulator_msgs/CHANGELOG.rst | 7 +++++++ simulation/traffic_simulator_msgs/package.xml | 2 +- test_runner/random_test_runner/CHANGELOG.rst | 7 +++++++ test_runner/random_test_runner/package.xml | 2 +- test_runner/scenario_test_runner/CHANGELOG.rst | 7 +++++++ test_runner/scenario_test_runner/package.xml | 2 +- 58 files changed, 243 insertions(+), 29 deletions(-) diff --git a/common/math/arithmetic/CHANGELOG.rst b/common/math/arithmetic/CHANGELOG.rst index 071415b7724..bb1c186edec 100644 --- a/common/math/arithmetic/CHANGELOG.rst +++ b/common/math/arithmetic/CHANGELOG.rst @@ -21,6 +21,13 @@ Changelog for package arithmetic * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.4 (2024-09-02) +------------------ +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Contributors: Masaya Kataoka, SzymonParapura + 4.0.3 (2024-08-29) ------------------ * Merge remote-tracking branch 'origin/master' into RJD-1056-remove-npc-logic-started diff --git a/common/math/arithmetic/package.xml b/common/math/arithmetic/package.xml index 1c29900b0a3..e4350ce9d90 100644 --- a/common/math/arithmetic/package.xml +++ b/common/math/arithmetic/package.xml @@ -2,7 +2,7 @@ arithmetic - 4.0.3 + 4.0.4 arithmetic library for scenario_simulator_v2 Tatsuya Yamasaki Apache License 2.0 diff --git a/common/math/geometry/CHANGELOG.rst b/common/math/geometry/CHANGELOG.rst index 032cc14a7ae..40ae1062b6b 100644 --- a/common/math/geometry/CHANGELOG.rst +++ b/common/math/geometry/CHANGELOG.rst @@ -21,6 +21,13 @@ Changelog for package geometry * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.4 (2024-09-02) +------------------ +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Contributors: Masaya Kataoka, SzymonParapura + 4.0.3 (2024-08-29) ------------------ * Merge remote-tracking branch 'origin/master' into RJD-1056-remove-npc-logic-started diff --git a/common/math/geometry/package.xml b/common/math/geometry/package.xml index ee5345b7bef..c2752bdd76e 100644 --- a/common/math/geometry/package.xml +++ b/common/math/geometry/package.xml @@ -2,7 +2,7 @@ geometry - 4.0.3 + 4.0.4 geometry math library for scenario_simulator_v2 application Masaya Kataoka Apache License 2.0 diff --git a/common/scenario_simulator_exception/CHANGELOG.rst b/common/scenario_simulator_exception/CHANGELOG.rst index 7fb97385a33..d7435a2d0d7 100644 --- a/common/scenario_simulator_exception/CHANGELOG.rst +++ b/common/scenario_simulator_exception/CHANGELOG.rst @@ -21,6 +21,13 @@ Changelog for package scenario_simulator_exception * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.4 (2024-09-02) +------------------ +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Contributors: Masaya Kataoka, SzymonParapura + 4.0.3 (2024-08-29) ------------------ * Merge remote-tracking branch 'origin/master' into RJD-1056-remove-npc-logic-started diff --git a/common/scenario_simulator_exception/package.xml b/common/scenario_simulator_exception/package.xml index 923df025cbb..fed6fd12440 100644 --- a/common/scenario_simulator_exception/package.xml +++ b/common/scenario_simulator_exception/package.xml @@ -2,7 +2,7 @@ scenario_simulator_exception - 4.0.3 + 4.0.4 Exception types for scenario simulator Tatsuya Yamasaki Apache License 2.0 diff --git a/common/simple_junit/CHANGELOG.rst b/common/simple_junit/CHANGELOG.rst index c4995f07eaa..4eef17af56d 100644 --- a/common/simple_junit/CHANGELOG.rst +++ b/common/simple_junit/CHANGELOG.rst @@ -21,6 +21,13 @@ Changelog for package junit_exporter * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.4 (2024-09-02) +------------------ +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Contributors: Masaya Kataoka, SzymonParapura + 4.0.3 (2024-08-29) ------------------ * Merge remote-tracking branch 'origin/master' into RJD-1056-remove-npc-logic-started diff --git a/common/simple_junit/package.xml b/common/simple_junit/package.xml index cda6cfd917e..59ed067b7f3 100644 --- a/common/simple_junit/package.xml +++ b/common/simple_junit/package.xml @@ -2,7 +2,7 @@ simple_junit - 4.0.3 + 4.0.4 Lightweight JUnit library for ROS 2 Masaya Kataoka Tatsuya Yamasaki diff --git a/common/status_monitor/CHANGELOG.rst b/common/status_monitor/CHANGELOG.rst index e01a2cb9f43..774ca2bbc6f 100644 --- a/common/status_monitor/CHANGELOG.rst +++ b/common/status_monitor/CHANGELOG.rst @@ -21,6 +21,13 @@ Changelog for package status_monitor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.4 (2024-09-02) +------------------ +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Contributors: Masaya Kataoka, SzymonParapura + 4.0.3 (2024-08-29) ------------------ * Merge remote-tracking branch 'origin/master' into RJD-1056-remove-npc-logic-started diff --git a/common/status_monitor/package.xml b/common/status_monitor/package.xml index 5c5d5e80609..282d4873375 100644 --- a/common/status_monitor/package.xml +++ b/common/status_monitor/package.xml @@ -2,7 +2,7 @@ status_monitor - 4.0.3 + 4.0.4 none Tatsuya Yamasaki Apache License 2.0 diff --git a/external/concealer/CHANGELOG.rst b/external/concealer/CHANGELOG.rst index 5c4a05c124b..1de9bcc00e0 100644 --- a/external/concealer/CHANGELOG.rst +++ b/external/concealer/CHANGELOG.rst @@ -21,6 +21,13 @@ Changelog for package concealer * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.4 (2024-09-02) +------------------ +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Contributors: Masaya Kataoka, SzymonParapura + 4.0.3 (2024-08-29) ------------------ * Merge remote-tracking branch 'origin/master' into RJD-1056-remove-npc-logic-started diff --git a/external/concealer/package.xml b/external/concealer/package.xml index 3d7adca6741..e5b4f8a03f5 100644 --- a/external/concealer/package.xml +++ b/external/concealer/package.xml @@ -2,7 +2,7 @@ concealer - 4.0.3 + 4.0.4 Provides a class 'Autoware' to conceal miscellaneous things to simplify Autoware management of the simulator. Tatsuya Yamasaki Apache License 2.0 diff --git a/external/embree_vendor/CHANGELOG.rst b/external/embree_vendor/CHANGELOG.rst index 81d4fb8e5ed..39510cf8c3f 100644 --- a/external/embree_vendor/CHANGELOG.rst +++ b/external/embree_vendor/CHANGELOG.rst @@ -24,6 +24,13 @@ Changelog for package embree_vendor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.4 (2024-09-02) +------------------ +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Contributors: Masaya Kataoka, SzymonParapura + 4.0.3 (2024-08-29) ------------------ * Merge remote-tracking branch 'origin/master' into RJD-1056-remove-npc-logic-started diff --git a/external/embree_vendor/package.xml b/external/embree_vendor/package.xml index 9edba4646ea..5df0964bb76 100644 --- a/external/embree_vendor/package.xml +++ b/external/embree_vendor/package.xml @@ -2,7 +2,7 @@ embree_vendor - 4.0.3 + 4.0.4 vendor packages for intel raytracing kernel library masaya Apache 2.0 diff --git a/map/kashiwanoha_map/CHANGELOG.rst b/map/kashiwanoha_map/CHANGELOG.rst index 529fb96066e..6ea2889e2b1 100644 --- a/map/kashiwanoha_map/CHANGELOG.rst +++ b/map/kashiwanoha_map/CHANGELOG.rst @@ -21,6 +21,13 @@ Changelog for package kashiwanoha_map * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.4 (2024-09-02) +------------------ +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Contributors: Masaya Kataoka, SzymonParapura + 4.0.3 (2024-08-29) ------------------ * Merge remote-tracking branch 'origin/master' into RJD-1056-remove-npc-logic-started diff --git a/map/kashiwanoha_map/package.xml b/map/kashiwanoha_map/package.xml index fedc916e65a..473e71e7ddf 100644 --- a/map/kashiwanoha_map/package.xml +++ b/map/kashiwanoha_map/package.xml @@ -2,7 +2,7 @@ kashiwanoha_map - 4.0.3 + 4.0.4 map package for kashiwanoha Masaya Kataoka Apache License 2.0 diff --git a/map/simple_cross_map/CHANGELOG.rst b/map/simple_cross_map/CHANGELOG.rst index a3e643fe4dd..6e9c96e3ea1 100644 --- a/map/simple_cross_map/CHANGELOG.rst +++ b/map/simple_cross_map/CHANGELOG.rst @@ -9,6 +9,13 @@ Changelog for package simple_cross_map * Merge branch 'master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.4 (2024-09-02) +------------------ +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Contributors: Masaya Kataoka, SzymonParapura + 4.0.3 (2024-08-29) ------------------ * Merge remote-tracking branch 'origin/master' into RJD-1056-remove-npc-logic-started diff --git a/map/simple_cross_map/package.xml b/map/simple_cross_map/package.xml index b298b4db875..ef675481bc7 100644 --- a/map/simple_cross_map/package.xml +++ b/map/simple_cross_map/package.xml @@ -2,7 +2,7 @@ simple_cross_map - 4.0.3 + 4.0.4 map package for simple cross Masaya Kataoka Apache License 2.0 diff --git a/mock/cpp_mock_scenarios/CHANGELOG.rst b/mock/cpp_mock_scenarios/CHANGELOG.rst index a950f37148c..62d76832554 100644 --- a/mock/cpp_mock_scenarios/CHANGELOG.rst +++ b/mock/cpp_mock_scenarios/CHANGELOG.rst @@ -21,6 +21,13 @@ Changelog for package cpp_mock_scenarios * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.4 (2024-09-02) +------------------ +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Contributors: Masaya Kataoka, SzymonParapura + 4.0.3 (2024-08-29) ------------------ * Merge remote-tracking branch 'origin/master' into RJD-1056-remove-npc-logic-started diff --git a/mock/cpp_mock_scenarios/package.xml b/mock/cpp_mock_scenarios/package.xml index ffe16eb7901..5ca7a422612 100644 --- a/mock/cpp_mock_scenarios/package.xml +++ b/mock/cpp_mock_scenarios/package.xml @@ -2,7 +2,7 @@ cpp_mock_scenarios - 4.0.3 + 4.0.4 C++ mock scenarios masaya Apache License 2.0 diff --git a/openscenario/openscenario_experimental_catalog/CHANGELOG.rst b/openscenario/openscenario_experimental_catalog/CHANGELOG.rst index 6792d7c61a1..6eafad07e9d 100644 --- a/openscenario/openscenario_experimental_catalog/CHANGELOG.rst +++ b/openscenario/openscenario_experimental_catalog/CHANGELOG.rst @@ -21,6 +21,13 @@ Changelog for package openscenario_experimental_catalog * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.4 (2024-09-02) +------------------ +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Contributors: Masaya Kataoka, SzymonParapura + 4.0.3 (2024-08-29) ------------------ * Merge remote-tracking branch 'origin/master' into RJD-1056-remove-npc-logic-started diff --git a/openscenario/openscenario_experimental_catalog/package.xml b/openscenario/openscenario_experimental_catalog/package.xml index 84fccf2740c..b87f49ec52e 100644 --- a/openscenario/openscenario_experimental_catalog/package.xml +++ b/openscenario/openscenario_experimental_catalog/package.xml @@ -2,7 +2,7 @@ openscenario_experimental_catalog - 4.0.3 + 4.0.4 TIER IV experimental catalogs for OpenSCENARIO Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter/CHANGELOG.rst b/openscenario/openscenario_interpreter/CHANGELOG.rst index 89f41eed6ba..fe0296b7d82 100644 --- a/openscenario/openscenario_interpreter/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter/CHANGELOG.rst @@ -32,6 +32,13 @@ Changelog for package openscenario_interpreter * add publish_empty_context parameter * Contributors: Masaya Kataoka +4.0.4 (2024-09-02) +------------------ +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Contributors: Masaya Kataoka, SzymonParapura + 4.0.3 (2024-08-29) ------------------ * Merge remote-tracking branch 'origin/master' into RJD-1056-remove-npc-logic-started diff --git a/openscenario/openscenario_interpreter/package.xml b/openscenario/openscenario_interpreter/package.xml index fd0035e234c..b5d213d0aee 100644 --- a/openscenario/openscenario_interpreter/package.xml +++ b/openscenario/openscenario_interpreter/package.xml @@ -2,7 +2,7 @@ openscenario_interpreter - 4.0.3 + 4.0.4 OpenSCENARIO 1.2.0 interpreter package for Autoware Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter_example/CHANGELOG.rst b/openscenario/openscenario_interpreter_example/CHANGELOG.rst index 9ba2283cf5d..9b0a471dbe2 100644 --- a/openscenario/openscenario_interpreter_example/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter_example/CHANGELOG.rst @@ -21,6 +21,13 @@ Changelog for package openscenario_interpreter_example * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.4 (2024-09-02) +------------------ +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Contributors: Masaya Kataoka, SzymonParapura + 4.0.3 (2024-08-29) ------------------ * Merge remote-tracking branch 'origin/master' into RJD-1056-remove-npc-logic-started diff --git a/openscenario/openscenario_interpreter_example/package.xml b/openscenario/openscenario_interpreter_example/package.xml index 27ad47d7620..449744d17e6 100644 --- a/openscenario/openscenario_interpreter_example/package.xml +++ b/openscenario/openscenario_interpreter_example/package.xml @@ -3,7 +3,7 @@ openscenario_interpreter_example - 4.0.3 + 4.0.4 Examples for some TIER IV OpenSCENARIO Interpreter's features Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst b/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst index c8a3ac1ed5d..48502653733 100644 --- a/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst @@ -21,6 +21,13 @@ Changelog for package openscenario_interpreter_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.4 (2024-09-02) +------------------ +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Contributors: Masaya Kataoka, SzymonParapura + 4.0.3 (2024-08-29) ------------------ * Merge remote-tracking branch 'origin/master' into RJD-1056-remove-npc-logic-started diff --git a/openscenario/openscenario_interpreter_msgs/package.xml b/openscenario/openscenario_interpreter_msgs/package.xml index 9e5e69c92ad..ee364f8ca43 100644 --- a/openscenario/openscenario_interpreter_msgs/package.xml +++ b/openscenario/openscenario_interpreter_msgs/package.xml @@ -2,7 +2,7 @@ openscenario_interpreter_msgs - 4.0.3 + 4.0.4 ROS message types for package openscenario_interpreter Yamasaki Tatsuya Apache License 2.0 diff --git a/openscenario/openscenario_preprocessor/CHANGELOG.rst b/openscenario/openscenario_preprocessor/CHANGELOG.rst index 3d089f944fe..1c70a7d2f90 100644 --- a/openscenario/openscenario_preprocessor/CHANGELOG.rst +++ b/openscenario/openscenario_preprocessor/CHANGELOG.rst @@ -21,6 +21,13 @@ Changelog for package openscenario_preprocessor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.4 (2024-09-02) +------------------ +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Contributors: Masaya Kataoka, SzymonParapura + 4.0.3 (2024-08-29) ------------------ * Merge remote-tracking branch 'origin/master' into RJD-1056-remove-npc-logic-started diff --git a/openscenario/openscenario_preprocessor/package.xml b/openscenario/openscenario_preprocessor/package.xml index 7aeb238ce78..c5a9fa0ccb7 100644 --- a/openscenario/openscenario_preprocessor/package.xml +++ b/openscenario/openscenario_preprocessor/package.xml @@ -3,7 +3,7 @@ openscenario_preprocessor - 4.0.3 + 4.0.4 Example package for TIER IV OpenSCENARIO Interpreter Kotaro Yoshimoto Apache License 2.0 diff --git a/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst b/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst index 3fb43fe4051..1d094431d99 100644 --- a/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst +++ b/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst @@ -21,6 +21,13 @@ Changelog for package openscenario_preprocessor_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.4 (2024-09-02) +------------------ +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Contributors: Masaya Kataoka, SzymonParapura + 4.0.3 (2024-08-29) ------------------ * Merge remote-tracking branch 'origin/master' into RJD-1056-remove-npc-logic-started diff --git a/openscenario/openscenario_preprocessor_msgs/package.xml b/openscenario/openscenario_preprocessor_msgs/package.xml index 2aad028ee03..a1b4f436a32 100644 --- a/openscenario/openscenario_preprocessor_msgs/package.xml +++ b/openscenario/openscenario_preprocessor_msgs/package.xml @@ -2,7 +2,7 @@ openscenario_preprocessor_msgs - 4.0.3 + 4.0.4 ROS message types for package openscenario_preprocessor Kotaro Yoshimoto Apache License 2.0 diff --git a/openscenario/openscenario_utility/CHANGELOG.rst b/openscenario/openscenario_utility/CHANGELOG.rst index 47440c02ecb..b7cf67def8c 100644 --- a/openscenario/openscenario_utility/CHANGELOG.rst +++ b/openscenario/openscenario_utility/CHANGELOG.rst @@ -24,6 +24,13 @@ Changelog for package openscenario_utility * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.4 (2024-09-02) +------------------ +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Contributors: Masaya Kataoka, SzymonParapura + 4.0.3 (2024-08-29) ------------------ * Merge remote-tracking branch 'origin/master' into RJD-1056-remove-npc-logic-started diff --git a/openscenario/openscenario_utility/package.xml b/openscenario/openscenario_utility/package.xml index 29bcf7248fd..be9aa620fbe 100644 --- a/openscenario/openscenario_utility/package.xml +++ b/openscenario/openscenario_utility/package.xml @@ -2,7 +2,7 @@ openscenario_utility - 4.0.3 + 4.0.4 Utility tools for ASAM OpenSCENARIO 1.2.0 Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_validator/CHANGELOG.rst b/openscenario/openscenario_validator/CHANGELOG.rst index b35540ce799..e7373a93b65 100644 --- a/openscenario/openscenario_validator/CHANGELOG.rst +++ b/openscenario/openscenario_validator/CHANGELOG.rst @@ -10,6 +10,13 @@ Changelog for package openscenario_validator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.4 (2024-09-02) +------------------ +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Contributors: Masaya Kataoka, SzymonParapura + 4.0.3 (2024-08-29) ------------------ * Merge remote-tracking branch 'origin/master' into RJD-1056-remove-npc-logic-started diff --git a/openscenario/openscenario_validator/package.xml b/openscenario/openscenario_validator/package.xml index ddcc5bd312f..a78113eed79 100644 --- a/openscenario/openscenario_validator/package.xml +++ b/openscenario/openscenario_validator/package.xml @@ -2,7 +2,7 @@ openscenario_validator - 4.0.3 + 4.0.4 Validator for OpenSCENARIO 1.3 Kotaro Yoshimoto Apache License 2.0 diff --git a/rviz_plugins/openscenario_visualization/CHANGELOG.rst b/rviz_plugins/openscenario_visualization/CHANGELOG.rst index 83df7d0e31b..a3c990bd223 100644 --- a/rviz_plugins/openscenario_visualization/CHANGELOG.rst +++ b/rviz_plugins/openscenario_visualization/CHANGELOG.rst @@ -21,6 +21,13 @@ Changelog for package openscenario_visualization * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.4 (2024-09-02) +------------------ +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Contributors: Masaya Kataoka, SzymonParapura + 4.0.3 (2024-08-29) ------------------ * Merge remote-tracking branch 'origin/master' into RJD-1056-remove-npc-logic-started diff --git a/rviz_plugins/openscenario_visualization/package.xml b/rviz_plugins/openscenario_visualization/package.xml index 06b03052c70..02ea72c337f 100644 --- a/rviz_plugins/openscenario_visualization/package.xml +++ b/rviz_plugins/openscenario_visualization/package.xml @@ -2,7 +2,7 @@ openscenario_visualization - 4.0.3 + 4.0.4 Visualization tools for simulation results Masaya Kataoka Kyoichi Sugahara diff --git a/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst b/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst index 227f0183a4c..75e8669b2a9 100644 --- a/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst +++ b/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst @@ -21,6 +21,13 @@ Changelog for package real_time_factor_control_rviz_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.4 (2024-09-02) +------------------ +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Contributors: Masaya Kataoka, SzymonParapura + 4.0.3 (2024-08-29) ------------------ * Merge remote-tracking branch 'origin/master' into RJD-1056-remove-npc-logic-started diff --git a/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml b/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml index a2cdb4f23ab..b67a20a9508 100644 --- a/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml +++ b/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml @@ -2,7 +2,7 @@ real_time_factor_control_rviz_plugin - 4.0.3 + 4.0.4 Slider controlling real time factor value. Paweł Lech Apache License 2.0 diff --git a/scenario_simulator_v2/CHANGELOG.rst b/scenario_simulator_v2/CHANGELOG.rst index 48cc5314ef2..09219d5b536 100644 --- a/scenario_simulator_v2/CHANGELOG.rst +++ b/scenario_simulator_v2/CHANGELOG.rst @@ -21,6 +21,13 @@ Changelog for package scenario_simulator_v2 * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.4 (2024-09-02) +------------------ +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Contributors: Masaya Kataoka, SzymonParapura + 4.0.3 (2024-08-29) ------------------ * Merge remote-tracking branch 'origin/master' into RJD-1056-remove-npc-logic-started diff --git a/scenario_simulator_v2/package.xml b/scenario_simulator_v2/package.xml index 79fba664888..f4a9cbbfde4 100644 --- a/scenario_simulator_v2/package.xml +++ b/scenario_simulator_v2/package.xml @@ -2,7 +2,7 @@ scenario_simulator_v2 - 4.0.3 + 4.0.4 scenario testing framework for Autoware Masaya Kataoka Apache License 2.0 diff --git a/simulation/behavior_tree_plugin/CHANGELOG.rst b/simulation/behavior_tree_plugin/CHANGELOG.rst index a84d1462e3e..7079b435a9a 100644 --- a/simulation/behavior_tree_plugin/CHANGELOG.rst +++ b/simulation/behavior_tree_plugin/CHANGELOG.rst @@ -21,6 +21,13 @@ Changelog for package behavior_tree_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.4 (2024-09-02) +------------------ +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Contributors: Masaya Kataoka, SzymonParapura + 4.0.3 (2024-08-29) ------------------ * Merge remote-tracking branch 'origin/master' into RJD-1056-remove-npc-logic-started diff --git a/simulation/behavior_tree_plugin/package.xml b/simulation/behavior_tree_plugin/package.xml index 43c837d63c6..afa4dcbb82e 100644 --- a/simulation/behavior_tree_plugin/package.xml +++ b/simulation/behavior_tree_plugin/package.xml @@ -2,7 +2,7 @@ behavior_tree_plugin - 4.0.3 + 4.0.4 Behavior tree plugin for traffic_simulator masaya Apache 2.0 diff --git a/simulation/do_nothing_plugin/CHANGELOG.rst b/simulation/do_nothing_plugin/CHANGELOG.rst index 9389fb87965..4f6b112885d 100644 --- a/simulation/do_nothing_plugin/CHANGELOG.rst +++ b/simulation/do_nothing_plugin/CHANGELOG.rst @@ -21,6 +21,13 @@ Changelog for package do_nothing_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.4 (2024-09-02) +------------------ +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Contributors: Masaya Kataoka, SzymonParapura + 4.0.3 (2024-08-29) ------------------ * Merge remote-tracking branch 'origin/master' into RJD-1056-remove-npc-logic-started diff --git a/simulation/do_nothing_plugin/package.xml b/simulation/do_nothing_plugin/package.xml index 7e00ac22e1a..d73bfd1a99a 100644 --- a/simulation/do_nothing_plugin/package.xml +++ b/simulation/do_nothing_plugin/package.xml @@ -2,7 +2,7 @@ do_nothing_plugin - 4.0.3 + 4.0.4 Behavior plugin for do nothing Masaya Kataoka Apache 2.0 diff --git a/simulation/simple_sensor_simulator/CHANGELOG.rst b/simulation/simple_sensor_simulator/CHANGELOG.rst index a538f140727..330c7beb168 100644 --- a/simulation/simple_sensor_simulator/CHANGELOG.rst +++ b/simulation/simple_sensor_simulator/CHANGELOG.rst @@ -21,6 +21,24 @@ Changelog for package simple_sensor_simulator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.4 (2024-09-02) +------------------ +* Merge pull request `#1301 `_ from tier4/feature/simple_sensor_simulator_unit_tests_lidar + Test: [RJD-937] to Implement Unit tests on simple_sensor_simulator +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Test: [RJD-937] to Implement Unit tests on simple_sensor_simulator + - Removed dummy class + - Updated unit tests +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Test: [RJD-937] to Implement Unit tests on simple_sensor_simulator + - Added missed header file +* Test: [RJD-937] to Implement Unit tests on simple_sensor_simulator + - Added unit tests to LidarSensor + - Addede unit tests to Primitive + - Refactored Raycaster unit tests +* Contributors: Masaya Kataoka, SzymonParapura + 4.0.3 (2024-08-29) ------------------ * Merge pull request `#1358 `_ from tier4/RJD-1056-remove-npc-logic-started diff --git a/simulation/simple_sensor_simulator/package.xml b/simulation/simple_sensor_simulator/package.xml index 9103769b115..33fece8a706 100644 --- a/simulation/simple_sensor_simulator/package.xml +++ b/simulation/simple_sensor_simulator/package.xml @@ -1,7 +1,7 @@ simple_sensor_simulator - 4.0.3 + 4.0.4 simple_sensor_simulator package masaya kataoka diff --git a/simulation/simulation_interface/CHANGELOG.rst b/simulation/simulation_interface/CHANGELOG.rst index 73448aa0c12..ac992200c2e 100644 --- a/simulation/simulation_interface/CHANGELOG.rst +++ b/simulation/simulation_interface/CHANGELOG.rst @@ -21,6 +21,13 @@ Changelog for package simulation_interface * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.4 (2024-09-02) +------------------ +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Contributors: Masaya Kataoka, SzymonParapura + 4.0.3 (2024-08-29) ------------------ * Merge remote-tracking branch 'origin/master' into RJD-1056-remove-npc-logic-started diff --git a/simulation/simulation_interface/package.xml b/simulation/simulation_interface/package.xml index 325d8df7d6a..4098f2afc3a 100644 --- a/simulation/simulation_interface/package.xml +++ b/simulation/simulation_interface/package.xml @@ -2,7 +2,7 @@ simulation_interface - 4.0.3 + 4.0.4 packages to define interface between simulator and scenario interpreter Masaya Kataoka Apache License 2.0 diff --git a/simulation/traffic_simulator/CHANGELOG.rst b/simulation/traffic_simulator/CHANGELOG.rst index d8c4e2bed5b..2ae66a903af 100644 --- a/simulation/traffic_simulator/CHANGELOG.rst +++ b/simulation/traffic_simulator/CHANGELOG.rst @@ -21,6 +21,13 @@ Changelog for package traffic_simulator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.4 (2024-09-02) +------------------ +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Contributors: Masaya Kataoka, SzymonParapura + 4.0.3 (2024-08-29) ------------------ * Merge pull request `#1358 `_ from tier4/RJD-1056-remove-npc-logic-started diff --git a/simulation/traffic_simulator/package.xml b/simulation/traffic_simulator/package.xml index 0c811088089..a53007167c1 100644 --- a/simulation/traffic_simulator/package.xml +++ b/simulation/traffic_simulator/package.xml @@ -1,7 +1,7 @@ traffic_simulator - 4.0.3 + 4.0.4 control traffic flow masaya kataoka diff --git a/simulation/traffic_simulator_msgs/CHANGELOG.rst b/simulation/traffic_simulator_msgs/CHANGELOG.rst index 77ddc0bc853..f4a7b54d808 100644 --- a/simulation/traffic_simulator_msgs/CHANGELOG.rst +++ b/simulation/traffic_simulator_msgs/CHANGELOG.rst @@ -21,6 +21,13 @@ Changelog for package openscenario_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.4 (2024-09-02) +------------------ +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Contributors: Masaya Kataoka, SzymonParapura + 4.0.3 (2024-08-29) ------------------ * Merge remote-tracking branch 'origin/master' into RJD-1056-remove-npc-logic-started diff --git a/simulation/traffic_simulator_msgs/package.xml b/simulation/traffic_simulator_msgs/package.xml index 2444a632eb7..20123d7e905 100644 --- a/simulation/traffic_simulator_msgs/package.xml +++ b/simulation/traffic_simulator_msgs/package.xml @@ -2,7 +2,7 @@ traffic_simulator_msgs - 4.0.3 + 4.0.4 ROS messages for openscenario Masaya Kataoka Apache License 2.0 diff --git a/test_runner/random_test_runner/CHANGELOG.rst b/test_runner/random_test_runner/CHANGELOG.rst index 8e16a329471..c5254557c9d 100644 --- a/test_runner/random_test_runner/CHANGELOG.rst +++ b/test_runner/random_test_runner/CHANGELOG.rst @@ -21,6 +21,13 @@ Changelog for package random_test_runner * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.4 (2024-09-02) +------------------ +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Contributors: Masaya Kataoka, SzymonParapura + 4.0.3 (2024-08-29) ------------------ * Merge pull request `#1358 `_ from tier4/RJD-1056-remove-npc-logic-started diff --git a/test_runner/random_test_runner/package.xml b/test_runner/random_test_runner/package.xml index e281411002d..8e2ac0e8ac7 100644 --- a/test_runner/random_test_runner/package.xml +++ b/test_runner/random_test_runner/package.xml @@ -2,7 +2,7 @@ random_test_runner - 4.0.3 + 4.0.4 Random behavior test runner piotr-zyskowski-rai Apache License 2.0 diff --git a/test_runner/scenario_test_runner/CHANGELOG.rst b/test_runner/scenario_test_runner/CHANGELOG.rst index 9d40fbc6fa4..0169e72bf9f 100644 --- a/test_runner/scenario_test_runner/CHANGELOG.rst +++ b/test_runner/scenario_test_runner/CHANGELOG.rst @@ -35,6 +35,13 @@ Changelog for package scenario_test_runner * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.0.4 (2024-09-02) +------------------ +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar +* Contributors: Masaya Kataoka, SzymonParapura + 4.0.3 (2024-08-29) ------------------ * Merge remote-tracking branch 'origin/master' into RJD-1056-remove-npc-logic-started diff --git a/test_runner/scenario_test_runner/package.xml b/test_runner/scenario_test_runner/package.xml index 14db4ea7f12..0e9b538151e 100644 --- a/test_runner/scenario_test_runner/package.xml +++ b/test_runner/scenario_test_runner/package.xml @@ -2,7 +2,7 @@ scenario_test_runner - 4.0.3 + 4.0.4 scenario test runner package Tatsuya Yamasaki Apache License 2.0 From b07aef99182fbcbdd0a764b846c2349638f29d7c Mon Sep 17 00:00:00 2001 From: Dawid Moszynski Date: Mon, 2 Sep 2024 09:33:58 +0200 Subject: [PATCH 192/304] doc(realtimefactor): fix inconsistencies --- .../scenario_test_runner/RealtimeFactor.md | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/docs/user_guide/scenario_test_runner/RealtimeFactor.md b/docs/user_guide/scenario_test_runner/RealtimeFactor.md index 4b9e7d66d00..e8b1cbe5d66 100644 --- a/docs/user_guide/scenario_test_runner/RealtimeFactor.md +++ b/docs/user_guide/scenario_test_runner/RealtimeFactor.md @@ -11,7 +11,7 @@ It is possible to modify the speed of simulation (the speed of time published on ```bash ros2 launch scenario_test_runner scenario_test_runner.launch.py \ - architecture_type:=awf/universe \ + architecture_type:=awf/universe/20230906 \ record:=false \ scenario:='$(find-pkg-share scenario_test_runner)/scenario/sample.yaml' \ sensor_model:=sample_sensor_kit \ @@ -47,7 +47,7 @@ Parameter `use_sim_time` of `openscenario_interpreter` is **false** by default a ```bash ros2 launch scenario_test_runner scenario_test_runner.launch.py \ - architecture_type:=awf/universe \ + architecture_type:=awf/universe/20230906 \ record:=false \ scenario:='$(find-pkg-share scenario_test_runner)/scenario/sample.yaml' \ sensor_model:=sample_sensor_kit \ @@ -61,17 +61,17 @@ Details are shown in the table below: | use_sim_time launch parameter | /clock time published by scenario_simulator_v2 | AWF Autoware Time | | ----------------------------- | ---------------------------------------------- | ---------------------- | -| false | walltime | walltime from /clock | -| true (default) | simulation | simulation from /clock | +| false (default) | walltime | walltime from /clock | +| true | simulation | simulation from /clock | Below are also some bullet points explaining the impact of the `use_sim_time` parameter on `scenario_simulator_v2` and `Autoware`: - - **`use_sim_time:=True` passed using command line (default value)** + - **`use_sim_time:=True` passed using command line** - Both Autoware and scenario_simulator_v2 are launched with `use_sim_time=true`. - Time published on `/clock` is the **simulation time** (starting from 0). - Time published on `/clock` **can be** controlled by RViz plugin. - Simulation time **can be** controlled by RViz plugin. - - **`use_sim_time:=False` passed using command line** + - **`use_sim_time:=False` passed using command line (default value)** - Both Autoware and scenario_simulator_v2 are launched with `use_sim_time=false`. - Time published on `/clock` is the **walltime**. - Time published on `/clock` **cannot be** controlled by RViz plugin. From 9f1eeedf2029d5090891b0ebf3169ba8b5bb2a60 Mon Sep 17 00:00:00 2001 From: robomic Date: Mon, 2 Sep 2024 10:27:51 +0200 Subject: [PATCH 193/304] make const members public --- .../include/geometry/polygon/line_segment.hpp | 13 ++--- .../src/intersection/intersection.cpp | 8 +-- .../geometry/src/polygon/line_segment.cpp | 52 ++++++++----------- .../src/spline/catmull_rom_spline.cpp | 4 +- .../math/geometry/test/test_line_segment.cpp | 16 +++--- 5 files changed, 40 insertions(+), 53 deletions(-) diff --git a/common/math/geometry/include/geometry/polygon/line_segment.hpp b/common/math/geometry/include/geometry/polygon/line_segment.hpp index 6fb16991950..8ba0f98bc0c 100644 --- a/common/math/geometry/include/geometry/polygon/line_segment.hpp +++ b/common/math/geometry/include/geometry/polygon/line_segment.hpp @@ -31,6 +31,10 @@ class LineSegment public: const geometry_msgs::msg::Point start_point; const geometry_msgs::msg::Point end_point; + const geometry_msgs::msg::Vector3 vector; + const geometry_msgs::msg::Vector3 vector_2d; + const double length; + const double length_2d; LineSegment( const geometry_msgs::msg::Point & start_point, const geometry_msgs::msg::Point & end_point); @@ -58,11 +62,7 @@ class LineSegment auto getSValue( const geometry_msgs::msg::Pose & pose, double threshold_distance, bool denormalize_s) const -> std::optional; - auto getVector() const -> const geometry_msgs::msg::Vector3 &; auto getNormalVector() const -> geometry_msgs::msg::Vector3; - auto get2DVector() const -> const geometry_msgs::msg::Vector3 &; - auto getLength() const -> double; - auto get2DLength() const -> double; auto get2DVectorSlope() const -> double; auto getSquaredDistanceIn2D( const geometry_msgs::msg::Point & point, const double s, const bool denormalize_s = false) const @@ -73,11 +73,6 @@ class LineSegment auto relativePointPosition2D(const geometry_msgs::msg::Point & point) const -> int; private: - const double length; - const double length_2d; - const geometry_msgs::msg::Vector3 vector; - const geometry_msgs::msg::Vector3 vector_2d; - auto denormalize(const std::optional & s, const bool throw_error_on_out_of_range = true) const -> std::optional; auto denormalize(const double s) const -> double; diff --git a/common/math/geometry/src/intersection/intersection.cpp b/common/math/geometry/src/intersection/intersection.cpp index 013efbb4cbe..85f0b691809 100644 --- a/common/math/geometry/src/intersection/intersection.cpp +++ b/common/math/geometry/src/intersection/intersection.cpp @@ -61,13 +61,13 @@ std::optional getIntersection2D( return std::nullopt; } else { // 'line0' represented as a0x + b0y = c0 - const double a0 = line0.get2DVector().y; - const double b0 = -line0.get2DVector().x; + const double a0 = line0.vector_2d.y; + const double b0 = -line0.vector_2d.x; const double c0 = a0 * line0.start_point.x + b0 * line0.start_point.y; // 'line1' represented as a1x + b1y = c1 - const double a1 = line1.get2DVector().y; - const double b1 = -line1.get2DVector().x; + const double a1 = line1.vector_2d.y; + const double b1 = -line1.vector_2d.x; const double c1 = a1 * line1.start_point.x + b1 * line1.start_point.y; const double determinant = a0 * b1 - a1 * b0; diff --git a/common/math/geometry/src/polygon/line_segment.cpp b/common/math/geometry/src/polygon/line_segment.cpp index 47ade55b944..b3b71a13b13 100644 --- a/common/math/geometry/src/polygon/line_segment.cpp +++ b/common/math/geometry/src/polygon/line_segment.cpp @@ -31,8 +31,6 @@ LineSegment::LineSegment( const geometry_msgs::msg::Point & start_point, const geometry_msgs::msg::Point & end_point) : start_point(start_point), end_point(end_point), - length(hypot(end_point, start_point)), - length_2d(std::hypot(end_point.x - start_point.x, end_point.y - start_point.y)), vector(geometry_msgs::build() .x(end_point.x - start_point.x) .y(end_point.y - start_point.y) @@ -40,7 +38,9 @@ LineSegment::LineSegment( vector_2d(geometry_msgs::build() .x(end_point.x - start_point.x) .y(end_point.y - start_point.y) - .z(0.0)) + .z(0.0)), + length(hypot(end_point, start_point)), + length_2d(std::hypot(end_point.x - start_point.x, end_point.y - start_point.y)) { } @@ -75,24 +75,24 @@ LineSegment::~LineSegment() {} auto LineSegment::getPoint(const double s, const bool denormalize_s) const -> geometry_msgs::msg::Point { - const double s_normalized = denormalize_s ? s / getLength() : s; + const double s_normalized = denormalize_s ? s / length : s; if (0.0 <= s_normalized && s_normalized <= 1.0) { return geometry_msgs::build() - .x(start_point.x + getVector().x * s_normalized) - .y(start_point.y + getVector().y * s_normalized) - .z(start_point.z + getVector().z * s_normalized); + .x(start_point.x + vector.x * s_normalized) + .y(start_point.y + vector.y * s_normalized) + .z(start_point.z + vector.z * s_normalized); } else if (denormalize_s) { THROW_SIMULATION_ERROR( "Invalid S value is specified, while getting point on a line segment.", - "The range of s_normalized value should be in range [0,", getLength(), "].", - "But, your values are = ", s, " and length = ", getLength(), + "The range of s_normalized value should be in range [0,", length, "].", + "But, your values are = ", s, " and length = ", length, " This message is not originally intended to be displayed, if you see it, please " "contact the developer of traffic_simulator."); } else { THROW_SIMULATION_ERROR( "Invalid S value is specified, while getting point on a line segment.", "The range of s_normalized value should be in range [0,1].", "But, your values are = ", s, - " and length = ", getLength(), + " and length = ", length, " This message is not originally intended to be displayed, if you see it, please " "contact the developer of traffic_simulator."); } @@ -114,8 +114,8 @@ auto LineSegment::getPose(const double s, const bool denormalize_s, const bool f .orientation(math::geometry::convertEulerAngleToQuaternion( geometry_msgs::build() .x(0.0) - .y(fill_pitch ? std::atan2(-getVector().z, std::hypot(getVector().x, getVector().y)) : 0.0) - .z(std::atan2(getVector().y, getVector().x)))); + .y(fill_pitch ? std::atan2(-vector.z, std::hypot(vector.x, vector.y)) : 0.0) + .z(std::atan2(vector.y, vector.x)))); } /** @@ -128,9 +128,9 @@ auto LineSegment::isIntersect2D(const geometry_msgs::msg::Point & point) const - { if (isInBounds2D(point)) { const double cross_product = - (point.y - start_point.y) * get2DVector().x - (point.x - start_point.x) * get2DVector().y; + (point.y - start_point.y) * vector_2d.x - (point.x - start_point.x) * vector_2d.y; constexpr double tolerance = std::numeric_limits::epsilon(); - return std::abs(cross_product) <= get2DLength() * tolerance; + return std::abs(cross_product) <= length_2d * tolerance; } else { return false; } @@ -177,8 +177,8 @@ auto LineSegment::get2DIntersectionSValue( /// Finally, we multiply this proportion by the actual 3D length to obtain the total SValue. if (isIntersect2D(point)) { const double proportion_2d = - std::hypot(point.x - start_point.x, point.y - start_point.y) / get2DLength(); - return denormalize_s ? std::make_optional(proportion_2d * getLength()) + std::hypot(point.x - start_point.x, point.y - start_point.y) / length_2d; + return denormalize_s ? std::make_optional(proportion_2d * length) : std::make_optional(proportion_2d); } else { return std::nullopt; @@ -212,8 +212,6 @@ auto LineSegment::getIntersection2D(const LineSegment & line) const return math::geometry::getIntersection2D(*this, line); } -auto LineSegment::getVector() const -> const geometry_msgs::msg::Vector3 & { return vector; } - /** * @brief Get normal vector of the line segment. * @return geometry_msgs::msg::Vector3 @@ -222,23 +220,17 @@ auto LineSegment::getNormalVector() const -> geometry_msgs::msg::Vector3 { const double theta = M_PI / 2.0; return geometry_msgs::build() - .x(getVector().x * std::cos(theta) - getVector().y * std::sin(theta)) - .y(getVector().x * std::sin(theta) + getVector().y * std::cos(theta)) + .x(vector.x * std::cos(theta) - vector.y * std::sin(theta)) + .y(vector.x * std::sin(theta) + vector.y * std::cos(theta)) .z(0.0); } -auto LineSegment::get2DVector() const -> const geometry_msgs::msg::Vector3 & { return vector_2d; } - -auto LineSegment::get2DLength() const -> double { return length_2d; } - -auto LineSegment::getLength() const -> double { return length; } - auto LineSegment::get2DVectorSlope() const -> double { - if (get2DVector().x <= std::numeric_limits::epsilon()) { + if (vector_2d.x <= std::numeric_limits::epsilon()) { THROW_SIMULATION_ERROR("Slope of a vertical line is undefined"); } else { - return get2DVector().y / get2DVector().x; + return vector_2d.y / vector_2d.x; } } @@ -300,7 +292,7 @@ auto LineSegment::denormalize( auto LineSegment::denormalize(const double s) const -> double { if (0.0 <= s && s <= 1.0) { - return s * getLength(); + return s * length; } else { THROW_SIMULATION_ERROR( "Invalid normalized s value, s = ", s, ", S value should be in range [0,1].", @@ -370,7 +362,7 @@ auto LineSegment::relativePointPosition2D(const geometry_msgs::msg::Point & poin { constexpr double tolerance = std::numeric_limits::epsilon(); const double determinant = - get2DVector().y * (point.x - end_point.x) - get2DVector().x * (point.y - end_point.y); + vector_2d.y * (point.x - end_point.x) - vector_2d.x * (point.y - end_point.y); return static_cast(determinant > tolerance) - static_cast(determinant < -tolerance); } diff --git a/common/math/geometry/src/spline/catmull_rom_spline.cpp b/common/math/geometry/src/spline/catmull_rom_spline.cpp index 0c5b6830cce..01dafbf7594 100644 --- a/common/math/geometry/src/spline/catmull_rom_spline.cpp +++ b/common/math/geometry/src/spline/catmull_rom_spline.cpp @@ -139,7 +139,7 @@ CatmullRomSpline::CatmullRomSpline(const std::vector break; /// @note In this case, spline is interpreted as line segment. case 2: - total_length_ = line_segments_[0].getLength(); + total_length_ = line_segments_[0].length; break; /// @note In this case, spline is interpreted as curve. default: @@ -628,7 +628,7 @@ auto CatmullRomSpline::getTangentVector(const double s) const -> geometry_msgs:: "contact the developer of traffic_simulator."); } if (0 <= s && s <= getLength()) { - return line_segments_[0].getVector(); + return line_segments_[0].vector; } THROW_SIMULATION_ERROR( "Invalid S value is specified, while getting tangent vector.", diff --git a/common/math/geometry/test/test_line_segment.cpp b/common/math/geometry/test/test_line_segment.cpp index 01011d528b6..c7f6aeb6067 100644 --- a/common/math/geometry/test/test_line_segment.cpp +++ b/common/math/geometry/test/test_line_segment.cpp @@ -99,13 +99,13 @@ TEST(LineSegment, getIntersection2DDisjoint) TEST(LineSegment, getVector) { const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(2.0, 3.0, 4.0)); - EXPECT_VECTOR3_EQ(line.getVector(), makeVector(1.0, 1.0, 1.0)); + EXPECT_VECTOR3_EQ(line.vector, makeVector(1.0, 1.0, 1.0)); } TEST(LineSegment, getVectorZeroLength) { const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(1.0, 2.0, 3.0)); - EXPECT_VECTOR3_EQ(line.getVector(), makeVector(0.0, 0.0, 0.0)); + EXPECT_VECTOR3_EQ(line.vector, makeVector(0.0, 0.0, 0.0)); } TEST(LineSegment, getNormalVector) @@ -123,37 +123,37 @@ TEST(LineSegment, getNormalVector_zeroLength) TEST(LineSegment, get2DVector) { const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(2.0, 3.0, 4.0)); - EXPECT_VECTOR3_EQ(line.get2DVector(), makeVector(1.0, 1.0, 0.0)); + EXPECT_VECTOR3_EQ(line.vector_2d, makeVector(1.0, 1.0, 0.0)); } TEST(LineSegment, get2DVectorZeroLength) { const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(1.0, 2.0, 3.0)); - EXPECT_VECTOR3_EQ(line.get2DVector(), makeVector(0.0, 0.0, 0.0)); + EXPECT_VECTOR3_EQ(line.vector_2d, makeVector(0.0, 0.0, 0.0)); } TEST(LineSegment, getLength) { const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(2.0, 3.0, 4.0)); - EXPECT_DOUBLE_EQ(line.getLength(), std::sqrt(3.0)); + EXPECT_DOUBLE_EQ(line.length, std::sqrt(3.0)); } TEST(LineSegment, getLengthZeroLength) { const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(1.0, 2.0, 3.0)); - EXPECT_DOUBLE_EQ(line.getLength(), 0.0); + EXPECT_DOUBLE_EQ(line.length, 0.0); } TEST(LineSegment, get2DLength) { const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(2.0, 3.0, 4.0)); - EXPECT_DOUBLE_EQ(line.get2DLength(), std::sqrt(2.0)); + EXPECT_DOUBLE_EQ(line.length_2d, std::sqrt(2.0)); } TEST(LineSegment, get2DLengthZeroLength) { const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(1.0, 2.0, 3.0)); - EXPECT_DOUBLE_EQ(line.get2DLength(), 0.0); + EXPECT_DOUBLE_EQ(line.length_2d, 0.0); } TEST(LineSegment, get2DVectorSlope) From 9fa855f0c7bbdefb174e21bb3591b425b8e3f4b6 Mon Sep 17 00:00:00 2001 From: Release Bot Date: Tue, 3 Sep 2024 00:30:59 +0000 Subject: [PATCH 194/304] Bump version of scenario_simulator_v2 from version 4.0.4 to version 4.1.0 --- common/math/arithmetic/CHANGELOG.rst | 9 ++++++ common/math/arithmetic/package.xml | 2 +- common/math/geometry/CHANGELOG.rst | 29 +++++++++++++++++++ common/math/geometry/package.xml | 2 +- .../CHANGELOG.rst | 9 ++++++ .../scenario_simulator_exception/package.xml | 2 +- common/simple_junit/CHANGELOG.rst | 9 ++++++ common/simple_junit/package.xml | 2 +- common/status_monitor/CHANGELOG.rst | 9 ++++++ common/status_monitor/package.xml | 2 +- external/concealer/CHANGELOG.rst | 9 ++++++ external/concealer/package.xml | 2 +- external/embree_vendor/CHANGELOG.rst | 9 ++++++ external/embree_vendor/package.xml | 2 +- map/kashiwanoha_map/CHANGELOG.rst | 9 ++++++ map/kashiwanoha_map/package.xml | 2 +- map/simple_cross_map/CHANGELOG.rst | 9 ++++++ map/simple_cross_map/package.xml | 2 +- mock/cpp_mock_scenarios/CHANGELOG.rst | 9 ++++++ mock/cpp_mock_scenarios/package.xml | 2 +- .../CHANGELOG.rst | 9 ++++++ .../package.xml | 2 +- .../openscenario_interpreter/CHANGELOG.rst | 9 ++++++ .../openscenario_interpreter/package.xml | 2 +- .../CHANGELOG.rst | 9 ++++++ .../package.xml | 2 +- .../CHANGELOG.rst | 9 ++++++ .../openscenario_interpreter_msgs/package.xml | 2 +- .../openscenario_preprocessor/CHANGELOG.rst | 9 ++++++ .../openscenario_preprocessor/package.xml | 2 +- .../CHANGELOG.rst | 9 ++++++ .../package.xml | 2 +- .../openscenario_utility/CHANGELOG.rst | 9 ++++++ openscenario/openscenario_utility/package.xml | 2 +- .../openscenario_validator/CHANGELOG.rst | 9 ++++++ .../openscenario_validator/package.xml | 2 +- .../openscenario_visualization/CHANGELOG.rst | 9 ++++++ .../openscenario_visualization/package.xml | 2 +- .../CHANGELOG.rst | 9 ++++++ .../package.xml | 2 +- scenario_simulator_v2/CHANGELOG.rst | 9 ++++++ scenario_simulator_v2/package.xml | 2 +- simulation/behavior_tree_plugin/CHANGELOG.rst | 9 ++++++ simulation/behavior_tree_plugin/package.xml | 2 +- simulation/do_nothing_plugin/CHANGELOG.rst | 9 ++++++ simulation/do_nothing_plugin/package.xml | 2 +- .../simple_sensor_simulator/CHANGELOG.rst | 9 ++++++ .../simple_sensor_simulator/package.xml | 2 +- simulation/simulation_interface/CHANGELOG.rst | 9 ++++++ simulation/simulation_interface/package.xml | 2 +- simulation/traffic_simulator/CHANGELOG.rst | 9 ++++++ simulation/traffic_simulator/package.xml | 2 +- .../traffic_simulator_msgs/CHANGELOG.rst | 9 ++++++ simulation/traffic_simulator_msgs/package.xml | 2 +- test_runner/random_test_runner/CHANGELOG.rst | 9 ++++++ test_runner/random_test_runner/package.xml | 2 +- .../scenario_test_runner/CHANGELOG.rst | 9 ++++++ test_runner/scenario_test_runner/package.xml | 2 +- 58 files changed, 310 insertions(+), 29 deletions(-) diff --git a/common/math/arithmetic/CHANGELOG.rst b/common/math/arithmetic/CHANGELOG.rst index bb1c186edec..798240c5750 100644 --- a/common/math/arithmetic/CHANGELOG.rst +++ b/common/math/arithmetic/CHANGELOG.rst @@ -21,6 +21,15 @@ Changelog for package arithmetic * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.1.0 (2024-09-03) +------------------ +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-1344-getIntersection2DSValue +* Merge branch 'master' into RJD-1278/fix-1343-isIntersect2D +* Contributors: Michał Ciasnocha + 4.0.4 (2024-09-02) ------------------ * Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar diff --git a/common/math/arithmetic/package.xml b/common/math/arithmetic/package.xml index e4350ce9d90..e43e4b119fa 100644 --- a/common/math/arithmetic/package.xml +++ b/common/math/arithmetic/package.xml @@ -2,7 +2,7 @@ arithmetic - 4.0.4 + 4.1.0 arithmetic library for scenario_simulator_v2 Tatsuya Yamasaki Apache License 2.0 diff --git a/common/math/geometry/CHANGELOG.rst b/common/math/geometry/CHANGELOG.rst index 40ae1062b6b..78f5dfec7f3 100644 --- a/common/math/geometry/CHANGELOG.rst +++ b/common/math/geometry/CHANGELOG.rst @@ -21,6 +21,35 @@ Changelog for package geometry * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.1.0 (2024-09-03) +------------------ +* Merge pull request `#1353 `_ from tier4/RJD-1278/fix-line-segment + Rjd 1278/fix line segment +* Merge branch 'master' into RJD-1278/fix-line-segment +* make const members public +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-line-segment +* remove{} +* expand on the note, add else to if-stmts +* note +* add else to if statements +* rename getSlope, add consts +* remove unnecessary lambda +* simplify denormalize logic +* use has_value +* rename getIntersection2DSValue, minor logical fixes regarding 2D vs 3D +* LineSegment 2D vs 3D indistinction fixes +* return const& and remove implicit conversions +* vector fields for LineSegment class, cleanup +* use isInBounds function +* combine 2 PR, apply review requests +* Merge branch 'RJD-1278/fix-1344-getIntersection2DSValue' of github.com:tier4/scenario_simulator_v2 into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-1344-getIntersection2DSValue +* Merge branch 'master' into RJD-1278/fix-1343-isIntersect2D +* isIntesect2D initial solution +* 1344 fix initial solution +* Contributors: Masaya Kataoka, Michał Ciasnocha, robomic + 4.0.4 (2024-09-02) ------------------ * Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar diff --git a/common/math/geometry/package.xml b/common/math/geometry/package.xml index c2752bdd76e..f1d4f4b1346 100644 --- a/common/math/geometry/package.xml +++ b/common/math/geometry/package.xml @@ -2,7 +2,7 @@ geometry - 4.0.4 + 4.1.0 geometry math library for scenario_simulator_v2 application Masaya Kataoka Apache License 2.0 diff --git a/common/scenario_simulator_exception/CHANGELOG.rst b/common/scenario_simulator_exception/CHANGELOG.rst index d7435a2d0d7..3f3aba9d0e0 100644 --- a/common/scenario_simulator_exception/CHANGELOG.rst +++ b/common/scenario_simulator_exception/CHANGELOG.rst @@ -21,6 +21,15 @@ Changelog for package scenario_simulator_exception * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.1.0 (2024-09-03) +------------------ +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-1344-getIntersection2DSValue +* Merge branch 'master' into RJD-1278/fix-1343-isIntersect2D +* Contributors: Michał Ciasnocha + 4.0.4 (2024-09-02) ------------------ * Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar diff --git a/common/scenario_simulator_exception/package.xml b/common/scenario_simulator_exception/package.xml index fed6fd12440..73b6c401da2 100644 --- a/common/scenario_simulator_exception/package.xml +++ b/common/scenario_simulator_exception/package.xml @@ -2,7 +2,7 @@ scenario_simulator_exception - 4.0.4 + 4.1.0 Exception types for scenario simulator Tatsuya Yamasaki Apache License 2.0 diff --git a/common/simple_junit/CHANGELOG.rst b/common/simple_junit/CHANGELOG.rst index 4eef17af56d..33220c8e35b 100644 --- a/common/simple_junit/CHANGELOG.rst +++ b/common/simple_junit/CHANGELOG.rst @@ -21,6 +21,15 @@ Changelog for package junit_exporter * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.1.0 (2024-09-03) +------------------ +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-1344-getIntersection2DSValue +* Merge branch 'master' into RJD-1278/fix-1343-isIntersect2D +* Contributors: Michał Ciasnocha + 4.0.4 (2024-09-02) ------------------ * Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar diff --git a/common/simple_junit/package.xml b/common/simple_junit/package.xml index 59ed067b7f3..29cb3c22b1c 100644 --- a/common/simple_junit/package.xml +++ b/common/simple_junit/package.xml @@ -2,7 +2,7 @@ simple_junit - 4.0.4 + 4.1.0 Lightweight JUnit library for ROS 2 Masaya Kataoka Tatsuya Yamasaki diff --git a/common/status_monitor/CHANGELOG.rst b/common/status_monitor/CHANGELOG.rst index 774ca2bbc6f..71e4bd326fb 100644 --- a/common/status_monitor/CHANGELOG.rst +++ b/common/status_monitor/CHANGELOG.rst @@ -21,6 +21,15 @@ Changelog for package status_monitor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.1.0 (2024-09-03) +------------------ +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-1344-getIntersection2DSValue +* Merge branch 'master' into RJD-1278/fix-1343-isIntersect2D +* Contributors: Michał Ciasnocha + 4.0.4 (2024-09-02) ------------------ * Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar diff --git a/common/status_monitor/package.xml b/common/status_monitor/package.xml index 282d4873375..e335459d58e 100644 --- a/common/status_monitor/package.xml +++ b/common/status_monitor/package.xml @@ -2,7 +2,7 @@ status_monitor - 4.0.4 + 4.1.0 none Tatsuya Yamasaki Apache License 2.0 diff --git a/external/concealer/CHANGELOG.rst b/external/concealer/CHANGELOG.rst index 1de9bcc00e0..b68296f8743 100644 --- a/external/concealer/CHANGELOG.rst +++ b/external/concealer/CHANGELOG.rst @@ -21,6 +21,15 @@ Changelog for package concealer * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.1.0 (2024-09-03) +------------------ +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-1344-getIntersection2DSValue +* Merge branch 'master' into RJD-1278/fix-1343-isIntersect2D +* Contributors: Michał Ciasnocha + 4.0.4 (2024-09-02) ------------------ * Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar diff --git a/external/concealer/package.xml b/external/concealer/package.xml index e5b4f8a03f5..e8bc60a7cfd 100644 --- a/external/concealer/package.xml +++ b/external/concealer/package.xml @@ -2,7 +2,7 @@ concealer - 4.0.4 + 4.1.0 Provides a class 'Autoware' to conceal miscellaneous things to simplify Autoware management of the simulator. Tatsuya Yamasaki Apache License 2.0 diff --git a/external/embree_vendor/CHANGELOG.rst b/external/embree_vendor/CHANGELOG.rst index 39510cf8c3f..c99809ca1eb 100644 --- a/external/embree_vendor/CHANGELOG.rst +++ b/external/embree_vendor/CHANGELOG.rst @@ -24,6 +24,15 @@ Changelog for package embree_vendor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.1.0 (2024-09-03) +------------------ +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-1344-getIntersection2DSValue +* Merge branch 'master' into RJD-1278/fix-1343-isIntersect2D +* Contributors: Michał Ciasnocha + 4.0.4 (2024-09-02) ------------------ * Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar diff --git a/external/embree_vendor/package.xml b/external/embree_vendor/package.xml index 5df0964bb76..d132c246a38 100644 --- a/external/embree_vendor/package.xml +++ b/external/embree_vendor/package.xml @@ -2,7 +2,7 @@ embree_vendor - 4.0.4 + 4.1.0 vendor packages for intel raytracing kernel library masaya Apache 2.0 diff --git a/map/kashiwanoha_map/CHANGELOG.rst b/map/kashiwanoha_map/CHANGELOG.rst index 6ea2889e2b1..0861c50126d 100644 --- a/map/kashiwanoha_map/CHANGELOG.rst +++ b/map/kashiwanoha_map/CHANGELOG.rst @@ -21,6 +21,15 @@ Changelog for package kashiwanoha_map * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.1.0 (2024-09-03) +------------------ +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-1344-getIntersection2DSValue +* Merge branch 'master' into RJD-1278/fix-1343-isIntersect2D +* Contributors: Michał Ciasnocha + 4.0.4 (2024-09-02) ------------------ * Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar diff --git a/map/kashiwanoha_map/package.xml b/map/kashiwanoha_map/package.xml index 473e71e7ddf..394167d04fa 100644 --- a/map/kashiwanoha_map/package.xml +++ b/map/kashiwanoha_map/package.xml @@ -2,7 +2,7 @@ kashiwanoha_map - 4.0.4 + 4.1.0 map package for kashiwanoha Masaya Kataoka Apache License 2.0 diff --git a/map/simple_cross_map/CHANGELOG.rst b/map/simple_cross_map/CHANGELOG.rst index 6e9c96e3ea1..ad95ad7ab75 100644 --- a/map/simple_cross_map/CHANGELOG.rst +++ b/map/simple_cross_map/CHANGELOG.rst @@ -9,6 +9,15 @@ Changelog for package simple_cross_map * Merge branch 'master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.1.0 (2024-09-03) +------------------ +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-1344-getIntersection2DSValue +* Merge branch 'master' into RJD-1278/fix-1343-isIntersect2D +* Contributors: Michał Ciasnocha + 4.0.4 (2024-09-02) ------------------ * Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar diff --git a/map/simple_cross_map/package.xml b/map/simple_cross_map/package.xml index ef675481bc7..1ccfc858fdf 100644 --- a/map/simple_cross_map/package.xml +++ b/map/simple_cross_map/package.xml @@ -2,7 +2,7 @@ simple_cross_map - 4.0.4 + 4.1.0 map package for simple cross Masaya Kataoka Apache License 2.0 diff --git a/mock/cpp_mock_scenarios/CHANGELOG.rst b/mock/cpp_mock_scenarios/CHANGELOG.rst index 62d76832554..dc2498e6200 100644 --- a/mock/cpp_mock_scenarios/CHANGELOG.rst +++ b/mock/cpp_mock_scenarios/CHANGELOG.rst @@ -21,6 +21,15 @@ Changelog for package cpp_mock_scenarios * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.1.0 (2024-09-03) +------------------ +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-1344-getIntersection2DSValue +* Merge branch 'master' into RJD-1278/fix-1343-isIntersect2D +* Contributors: Michał Ciasnocha + 4.0.4 (2024-09-02) ------------------ * Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar diff --git a/mock/cpp_mock_scenarios/package.xml b/mock/cpp_mock_scenarios/package.xml index 5ca7a422612..bdfce4bf3f6 100644 --- a/mock/cpp_mock_scenarios/package.xml +++ b/mock/cpp_mock_scenarios/package.xml @@ -2,7 +2,7 @@ cpp_mock_scenarios - 4.0.4 + 4.1.0 C++ mock scenarios masaya Apache License 2.0 diff --git a/openscenario/openscenario_experimental_catalog/CHANGELOG.rst b/openscenario/openscenario_experimental_catalog/CHANGELOG.rst index 6eafad07e9d..45f16c7f224 100644 --- a/openscenario/openscenario_experimental_catalog/CHANGELOG.rst +++ b/openscenario/openscenario_experimental_catalog/CHANGELOG.rst @@ -21,6 +21,15 @@ Changelog for package openscenario_experimental_catalog * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.1.0 (2024-09-03) +------------------ +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-1344-getIntersection2DSValue +* Merge branch 'master' into RJD-1278/fix-1343-isIntersect2D +* Contributors: Michał Ciasnocha + 4.0.4 (2024-09-02) ------------------ * Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar diff --git a/openscenario/openscenario_experimental_catalog/package.xml b/openscenario/openscenario_experimental_catalog/package.xml index b87f49ec52e..bff30fd153a 100644 --- a/openscenario/openscenario_experimental_catalog/package.xml +++ b/openscenario/openscenario_experimental_catalog/package.xml @@ -2,7 +2,7 @@ openscenario_experimental_catalog - 4.0.4 + 4.1.0 TIER IV experimental catalogs for OpenSCENARIO Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter/CHANGELOG.rst b/openscenario/openscenario_interpreter/CHANGELOG.rst index fe0296b7d82..4d18a9ce2d1 100644 --- a/openscenario/openscenario_interpreter/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter/CHANGELOG.rst @@ -32,6 +32,15 @@ Changelog for package openscenario_interpreter * add publish_empty_context parameter * Contributors: Masaya Kataoka +4.1.0 (2024-09-03) +------------------ +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-1344-getIntersection2DSValue +* Merge branch 'master' into RJD-1278/fix-1343-isIntersect2D +* Contributors: Michał Ciasnocha + 4.0.4 (2024-09-02) ------------------ * Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar diff --git a/openscenario/openscenario_interpreter/package.xml b/openscenario/openscenario_interpreter/package.xml index b5d213d0aee..de5a6d9ce11 100644 --- a/openscenario/openscenario_interpreter/package.xml +++ b/openscenario/openscenario_interpreter/package.xml @@ -2,7 +2,7 @@ openscenario_interpreter - 4.0.4 + 4.1.0 OpenSCENARIO 1.2.0 interpreter package for Autoware Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter_example/CHANGELOG.rst b/openscenario/openscenario_interpreter_example/CHANGELOG.rst index 9b0a471dbe2..eab5fcfc343 100644 --- a/openscenario/openscenario_interpreter_example/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter_example/CHANGELOG.rst @@ -21,6 +21,15 @@ Changelog for package openscenario_interpreter_example * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.1.0 (2024-09-03) +------------------ +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-1344-getIntersection2DSValue +* Merge branch 'master' into RJD-1278/fix-1343-isIntersect2D +* Contributors: Michał Ciasnocha + 4.0.4 (2024-09-02) ------------------ * Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar diff --git a/openscenario/openscenario_interpreter_example/package.xml b/openscenario/openscenario_interpreter_example/package.xml index 449744d17e6..dcb5d70431d 100644 --- a/openscenario/openscenario_interpreter_example/package.xml +++ b/openscenario/openscenario_interpreter_example/package.xml @@ -3,7 +3,7 @@ openscenario_interpreter_example - 4.0.4 + 4.1.0 Examples for some TIER IV OpenSCENARIO Interpreter's features Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst b/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst index 48502653733..0979b4b8d63 100644 --- a/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst @@ -21,6 +21,15 @@ Changelog for package openscenario_interpreter_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.1.0 (2024-09-03) +------------------ +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-1344-getIntersection2DSValue +* Merge branch 'master' into RJD-1278/fix-1343-isIntersect2D +* Contributors: Michał Ciasnocha + 4.0.4 (2024-09-02) ------------------ * Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar diff --git a/openscenario/openscenario_interpreter_msgs/package.xml b/openscenario/openscenario_interpreter_msgs/package.xml index ee364f8ca43..d30064c23bf 100644 --- a/openscenario/openscenario_interpreter_msgs/package.xml +++ b/openscenario/openscenario_interpreter_msgs/package.xml @@ -2,7 +2,7 @@ openscenario_interpreter_msgs - 4.0.4 + 4.1.0 ROS message types for package openscenario_interpreter Yamasaki Tatsuya Apache License 2.0 diff --git a/openscenario/openscenario_preprocessor/CHANGELOG.rst b/openscenario/openscenario_preprocessor/CHANGELOG.rst index 1c70a7d2f90..e1ffb99c452 100644 --- a/openscenario/openscenario_preprocessor/CHANGELOG.rst +++ b/openscenario/openscenario_preprocessor/CHANGELOG.rst @@ -21,6 +21,15 @@ Changelog for package openscenario_preprocessor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.1.0 (2024-09-03) +------------------ +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-1344-getIntersection2DSValue +* Merge branch 'master' into RJD-1278/fix-1343-isIntersect2D +* Contributors: Michał Ciasnocha + 4.0.4 (2024-09-02) ------------------ * Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar diff --git a/openscenario/openscenario_preprocessor/package.xml b/openscenario/openscenario_preprocessor/package.xml index c5a9fa0ccb7..727976cfc2e 100644 --- a/openscenario/openscenario_preprocessor/package.xml +++ b/openscenario/openscenario_preprocessor/package.xml @@ -3,7 +3,7 @@ openscenario_preprocessor - 4.0.4 + 4.1.0 Example package for TIER IV OpenSCENARIO Interpreter Kotaro Yoshimoto Apache License 2.0 diff --git a/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst b/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst index 1d094431d99..9be6223f578 100644 --- a/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst +++ b/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst @@ -21,6 +21,15 @@ Changelog for package openscenario_preprocessor_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.1.0 (2024-09-03) +------------------ +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-1344-getIntersection2DSValue +* Merge branch 'master' into RJD-1278/fix-1343-isIntersect2D +* Contributors: Michał Ciasnocha + 4.0.4 (2024-09-02) ------------------ * Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar diff --git a/openscenario/openscenario_preprocessor_msgs/package.xml b/openscenario/openscenario_preprocessor_msgs/package.xml index a1b4f436a32..9c0bdac10b5 100644 --- a/openscenario/openscenario_preprocessor_msgs/package.xml +++ b/openscenario/openscenario_preprocessor_msgs/package.xml @@ -2,7 +2,7 @@ openscenario_preprocessor_msgs - 4.0.4 + 4.1.0 ROS message types for package openscenario_preprocessor Kotaro Yoshimoto Apache License 2.0 diff --git a/openscenario/openscenario_utility/CHANGELOG.rst b/openscenario/openscenario_utility/CHANGELOG.rst index b7cf67def8c..7c359c8bb51 100644 --- a/openscenario/openscenario_utility/CHANGELOG.rst +++ b/openscenario/openscenario_utility/CHANGELOG.rst @@ -24,6 +24,15 @@ Changelog for package openscenario_utility * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.1.0 (2024-09-03) +------------------ +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-1344-getIntersection2DSValue +* Merge branch 'master' into RJD-1278/fix-1343-isIntersect2D +* Contributors: Michał Ciasnocha + 4.0.4 (2024-09-02) ------------------ * Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar diff --git a/openscenario/openscenario_utility/package.xml b/openscenario/openscenario_utility/package.xml index be9aa620fbe..d65a371ab39 100644 --- a/openscenario/openscenario_utility/package.xml +++ b/openscenario/openscenario_utility/package.xml @@ -2,7 +2,7 @@ openscenario_utility - 4.0.4 + 4.1.0 Utility tools for ASAM OpenSCENARIO 1.2.0 Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_validator/CHANGELOG.rst b/openscenario/openscenario_validator/CHANGELOG.rst index e7373a93b65..07b5937398d 100644 --- a/openscenario/openscenario_validator/CHANGELOG.rst +++ b/openscenario/openscenario_validator/CHANGELOG.rst @@ -10,6 +10,15 @@ Changelog for package openscenario_validator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.1.0 (2024-09-03) +------------------ +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-1344-getIntersection2DSValue +* Merge branch 'master' into RJD-1278/fix-1343-isIntersect2D +* Contributors: Michał Ciasnocha + 4.0.4 (2024-09-02) ------------------ * Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar diff --git a/openscenario/openscenario_validator/package.xml b/openscenario/openscenario_validator/package.xml index a78113eed79..7bfe192367b 100644 --- a/openscenario/openscenario_validator/package.xml +++ b/openscenario/openscenario_validator/package.xml @@ -2,7 +2,7 @@ openscenario_validator - 4.0.4 + 4.1.0 Validator for OpenSCENARIO 1.3 Kotaro Yoshimoto Apache License 2.0 diff --git a/rviz_plugins/openscenario_visualization/CHANGELOG.rst b/rviz_plugins/openscenario_visualization/CHANGELOG.rst index a3c990bd223..f4e0684997a 100644 --- a/rviz_plugins/openscenario_visualization/CHANGELOG.rst +++ b/rviz_plugins/openscenario_visualization/CHANGELOG.rst @@ -21,6 +21,15 @@ Changelog for package openscenario_visualization * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.1.0 (2024-09-03) +------------------ +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-1344-getIntersection2DSValue +* Merge branch 'master' into RJD-1278/fix-1343-isIntersect2D +* Contributors: Michał Ciasnocha + 4.0.4 (2024-09-02) ------------------ * Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar diff --git a/rviz_plugins/openscenario_visualization/package.xml b/rviz_plugins/openscenario_visualization/package.xml index 02ea72c337f..7d4ab9d638f 100644 --- a/rviz_plugins/openscenario_visualization/package.xml +++ b/rviz_plugins/openscenario_visualization/package.xml @@ -2,7 +2,7 @@ openscenario_visualization - 4.0.4 + 4.1.0 Visualization tools for simulation results Masaya Kataoka Kyoichi Sugahara diff --git a/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst b/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst index 75e8669b2a9..45b50390972 100644 --- a/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst +++ b/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst @@ -21,6 +21,15 @@ Changelog for package real_time_factor_control_rviz_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.1.0 (2024-09-03) +------------------ +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-1344-getIntersection2DSValue +* Merge branch 'master' into RJD-1278/fix-1343-isIntersect2D +* Contributors: Michał Ciasnocha + 4.0.4 (2024-09-02) ------------------ * Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar diff --git a/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml b/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml index b67a20a9508..95bb05b9e6d 100644 --- a/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml +++ b/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml @@ -2,7 +2,7 @@ real_time_factor_control_rviz_plugin - 4.0.4 + 4.1.0 Slider controlling real time factor value. Paweł Lech Apache License 2.0 diff --git a/scenario_simulator_v2/CHANGELOG.rst b/scenario_simulator_v2/CHANGELOG.rst index 09219d5b536..45ad48f52ae 100644 --- a/scenario_simulator_v2/CHANGELOG.rst +++ b/scenario_simulator_v2/CHANGELOG.rst @@ -21,6 +21,15 @@ Changelog for package scenario_simulator_v2 * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.1.0 (2024-09-03) +------------------ +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-1344-getIntersection2DSValue +* Merge branch 'master' into RJD-1278/fix-1343-isIntersect2D +* Contributors: Michał Ciasnocha + 4.0.4 (2024-09-02) ------------------ * Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar diff --git a/scenario_simulator_v2/package.xml b/scenario_simulator_v2/package.xml index f4a9cbbfde4..d8ffcaefbd1 100644 --- a/scenario_simulator_v2/package.xml +++ b/scenario_simulator_v2/package.xml @@ -2,7 +2,7 @@ scenario_simulator_v2 - 4.0.4 + 4.1.0 scenario testing framework for Autoware Masaya Kataoka Apache License 2.0 diff --git a/simulation/behavior_tree_plugin/CHANGELOG.rst b/simulation/behavior_tree_plugin/CHANGELOG.rst index 7079b435a9a..6d8bcd80543 100644 --- a/simulation/behavior_tree_plugin/CHANGELOG.rst +++ b/simulation/behavior_tree_plugin/CHANGELOG.rst @@ -21,6 +21,15 @@ Changelog for package behavior_tree_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.1.0 (2024-09-03) +------------------ +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-1344-getIntersection2DSValue +* Merge branch 'master' into RJD-1278/fix-1343-isIntersect2D +* Contributors: Michał Ciasnocha + 4.0.4 (2024-09-02) ------------------ * Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar diff --git a/simulation/behavior_tree_plugin/package.xml b/simulation/behavior_tree_plugin/package.xml index afa4dcbb82e..f63468266a5 100644 --- a/simulation/behavior_tree_plugin/package.xml +++ b/simulation/behavior_tree_plugin/package.xml @@ -2,7 +2,7 @@ behavior_tree_plugin - 4.0.4 + 4.1.0 Behavior tree plugin for traffic_simulator masaya Apache 2.0 diff --git a/simulation/do_nothing_plugin/CHANGELOG.rst b/simulation/do_nothing_plugin/CHANGELOG.rst index 4f6b112885d..c8c5c7d59a3 100644 --- a/simulation/do_nothing_plugin/CHANGELOG.rst +++ b/simulation/do_nothing_plugin/CHANGELOG.rst @@ -21,6 +21,15 @@ Changelog for package do_nothing_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.1.0 (2024-09-03) +------------------ +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-1344-getIntersection2DSValue +* Merge branch 'master' into RJD-1278/fix-1343-isIntersect2D +* Contributors: Michał Ciasnocha + 4.0.4 (2024-09-02) ------------------ * Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar diff --git a/simulation/do_nothing_plugin/package.xml b/simulation/do_nothing_plugin/package.xml index d73bfd1a99a..0cefa0af367 100644 --- a/simulation/do_nothing_plugin/package.xml +++ b/simulation/do_nothing_plugin/package.xml @@ -2,7 +2,7 @@ do_nothing_plugin - 4.0.4 + 4.1.0 Behavior plugin for do nothing Masaya Kataoka Apache 2.0 diff --git a/simulation/simple_sensor_simulator/CHANGELOG.rst b/simulation/simple_sensor_simulator/CHANGELOG.rst index 330c7beb168..b1bb91e0a45 100644 --- a/simulation/simple_sensor_simulator/CHANGELOG.rst +++ b/simulation/simple_sensor_simulator/CHANGELOG.rst @@ -21,6 +21,15 @@ Changelog for package simple_sensor_simulator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.1.0 (2024-09-03) +------------------ +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-1344-getIntersection2DSValue +* Merge branch 'master' into RJD-1278/fix-1343-isIntersect2D +* Contributors: Michał Ciasnocha + 4.0.4 (2024-09-02) ------------------ * Merge pull request `#1301 `_ from tier4/feature/simple_sensor_simulator_unit_tests_lidar diff --git a/simulation/simple_sensor_simulator/package.xml b/simulation/simple_sensor_simulator/package.xml index 33fece8a706..f8540ec94f0 100644 --- a/simulation/simple_sensor_simulator/package.xml +++ b/simulation/simple_sensor_simulator/package.xml @@ -1,7 +1,7 @@ simple_sensor_simulator - 4.0.4 + 4.1.0 simple_sensor_simulator package masaya kataoka diff --git a/simulation/simulation_interface/CHANGELOG.rst b/simulation/simulation_interface/CHANGELOG.rst index ac992200c2e..042d163f8bb 100644 --- a/simulation/simulation_interface/CHANGELOG.rst +++ b/simulation/simulation_interface/CHANGELOG.rst @@ -21,6 +21,15 @@ Changelog for package simulation_interface * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.1.0 (2024-09-03) +------------------ +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-1344-getIntersection2DSValue +* Merge branch 'master' into RJD-1278/fix-1343-isIntersect2D +* Contributors: Michał Ciasnocha + 4.0.4 (2024-09-02) ------------------ * Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar diff --git a/simulation/simulation_interface/package.xml b/simulation/simulation_interface/package.xml index 4098f2afc3a..519a95c2094 100644 --- a/simulation/simulation_interface/package.xml +++ b/simulation/simulation_interface/package.xml @@ -2,7 +2,7 @@ simulation_interface - 4.0.4 + 4.1.0 packages to define interface between simulator and scenario interpreter Masaya Kataoka Apache License 2.0 diff --git a/simulation/traffic_simulator/CHANGELOG.rst b/simulation/traffic_simulator/CHANGELOG.rst index 2ae66a903af..1198df922fa 100644 --- a/simulation/traffic_simulator/CHANGELOG.rst +++ b/simulation/traffic_simulator/CHANGELOG.rst @@ -21,6 +21,15 @@ Changelog for package traffic_simulator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.1.0 (2024-09-03) +------------------ +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-1344-getIntersection2DSValue +* Merge branch 'master' into RJD-1278/fix-1343-isIntersect2D +* Contributors: Michał Ciasnocha + 4.0.4 (2024-09-02) ------------------ * Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar diff --git a/simulation/traffic_simulator/package.xml b/simulation/traffic_simulator/package.xml index a53007167c1..0c23831f034 100644 --- a/simulation/traffic_simulator/package.xml +++ b/simulation/traffic_simulator/package.xml @@ -1,7 +1,7 @@ traffic_simulator - 4.0.4 + 4.1.0 control traffic flow masaya kataoka diff --git a/simulation/traffic_simulator_msgs/CHANGELOG.rst b/simulation/traffic_simulator_msgs/CHANGELOG.rst index f4a7b54d808..32b8498248c 100644 --- a/simulation/traffic_simulator_msgs/CHANGELOG.rst +++ b/simulation/traffic_simulator_msgs/CHANGELOG.rst @@ -21,6 +21,15 @@ Changelog for package openscenario_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.1.0 (2024-09-03) +------------------ +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-1344-getIntersection2DSValue +* Merge branch 'master' into RJD-1278/fix-1343-isIntersect2D +* Contributors: Michał Ciasnocha + 4.0.4 (2024-09-02) ------------------ * Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar diff --git a/simulation/traffic_simulator_msgs/package.xml b/simulation/traffic_simulator_msgs/package.xml index 20123d7e905..09a9de877df 100644 --- a/simulation/traffic_simulator_msgs/package.xml +++ b/simulation/traffic_simulator_msgs/package.xml @@ -2,7 +2,7 @@ traffic_simulator_msgs - 4.0.4 + 4.1.0 ROS messages for openscenario Masaya Kataoka Apache License 2.0 diff --git a/test_runner/random_test_runner/CHANGELOG.rst b/test_runner/random_test_runner/CHANGELOG.rst index c5254557c9d..97aa4d0b437 100644 --- a/test_runner/random_test_runner/CHANGELOG.rst +++ b/test_runner/random_test_runner/CHANGELOG.rst @@ -21,6 +21,15 @@ Changelog for package random_test_runner * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.1.0 (2024-09-03) +------------------ +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-1344-getIntersection2DSValue +* Merge branch 'master' into RJD-1278/fix-1343-isIntersect2D +* Contributors: Michał Ciasnocha + 4.0.4 (2024-09-02) ------------------ * Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar diff --git a/test_runner/random_test_runner/package.xml b/test_runner/random_test_runner/package.xml index 8e2ac0e8ac7..661360ef9e4 100644 --- a/test_runner/random_test_runner/package.xml +++ b/test_runner/random_test_runner/package.xml @@ -2,7 +2,7 @@ random_test_runner - 4.0.4 + 4.1.0 Random behavior test runner piotr-zyskowski-rai Apache License 2.0 diff --git a/test_runner/scenario_test_runner/CHANGELOG.rst b/test_runner/scenario_test_runner/CHANGELOG.rst index 0169e72bf9f..6ded1b349c5 100644 --- a/test_runner/scenario_test_runner/CHANGELOG.rst +++ b/test_runner/scenario_test_runner/CHANGELOG.rst @@ -35,6 +35,15 @@ Changelog for package scenario_test_runner * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.1.0 (2024-09-03) +------------------ +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-line-segment +* Merge branch 'master' into RJD-1278/fix-1344-getIntersection2DSValue +* Merge branch 'master' into RJD-1278/fix-1343-isIntersect2D +* Contributors: Michał Ciasnocha + 4.0.4 (2024-09-02) ------------------ * Merge branch 'master' into feature/simple_sensor_simulator_unit_tests_lidar diff --git a/test_runner/scenario_test_runner/package.xml b/test_runner/scenario_test_runner/package.xml index 0e9b538151e..c8cd38804e6 100644 --- a/test_runner/scenario_test_runner/package.xml +++ b/test_runner/scenario_test_runner/package.xml @@ -2,7 +2,7 @@ scenario_test_runner - 4.0.4 + 4.1.0 scenario test runner package Tatsuya Yamasaki Apache License 2.0 From a3e59a7051400776473288eceb2e4198082b4215 Mon Sep 17 00:00:00 2001 From: Release Bot Date: Tue, 3 Sep 2024 03:50:00 +0000 Subject: [PATCH 195/304] Bump version of scenario_simulator_v2 from version 4.1.0 to version 4.1.1 --- common/math/arithmetic/CHANGELOG.rst | 14 ++++++++++++++ common/math/arithmetic/package.xml | 2 +- common/math/geometry/CHANGELOG.rst | 14 ++++++++++++++ common/math/geometry/package.xml | 2 +- .../CHANGELOG.rst | 14 ++++++++++++++ .../scenario_simulator_exception/package.xml | 2 +- common/simple_junit/CHANGELOG.rst | 14 ++++++++++++++ common/simple_junit/package.xml | 2 +- common/status_monitor/CHANGELOG.rst | 14 ++++++++++++++ common/status_monitor/package.xml | 2 +- external/concealer/CHANGELOG.rst | 14 ++++++++++++++ external/concealer/package.xml | 2 +- external/embree_vendor/CHANGELOG.rst | 14 ++++++++++++++ external/embree_vendor/package.xml | 2 +- map/kashiwanoha_map/CHANGELOG.rst | 14 ++++++++++++++ map/kashiwanoha_map/package.xml | 2 +- map/simple_cross_map/CHANGELOG.rst | 14 ++++++++++++++ map/simple_cross_map/package.xml | 2 +- mock/cpp_mock_scenarios/CHANGELOG.rst | 14 ++++++++++++++ mock/cpp_mock_scenarios/package.xml | 2 +- .../CHANGELOG.rst | 14 ++++++++++++++ .../package.xml | 2 +- .../openscenario_interpreter/CHANGELOG.rst | 15 +++++++++++++++ .../openscenario_interpreter/package.xml | 2 +- .../CHANGELOG.rst | 14 ++++++++++++++ .../package.xml | 2 +- .../CHANGELOG.rst | 14 ++++++++++++++ .../openscenario_interpreter_msgs/package.xml | 2 +- .../openscenario_preprocessor/CHANGELOG.rst | 14 ++++++++++++++ .../openscenario_preprocessor/package.xml | 2 +- .../CHANGELOG.rst | 14 ++++++++++++++ .../package.xml | 2 +- .../openscenario_utility/CHANGELOG.rst | 14 ++++++++++++++ openscenario/openscenario_utility/package.xml | 2 +- .../openscenario_validator/CHANGELOG.rst | 14 ++++++++++++++ .../openscenario_validator/package.xml | 2 +- .../openscenario_visualization/CHANGELOG.rst | 14 ++++++++++++++ .../openscenario_visualization/package.xml | 2 +- .../CHANGELOG.rst | 14 ++++++++++++++ .../package.xml | 2 +- scenario_simulator_v2/CHANGELOG.rst | 14 ++++++++++++++ scenario_simulator_v2/package.xml | 2 +- simulation/behavior_tree_plugin/CHANGELOG.rst | 14 ++++++++++++++ simulation/behavior_tree_plugin/package.xml | 2 +- simulation/do_nothing_plugin/CHANGELOG.rst | 14 ++++++++++++++ simulation/do_nothing_plugin/package.xml | 2 +- .../simple_sensor_simulator/CHANGELOG.rst | 18 ++++++++++++++++++ .../simple_sensor_simulator/package.xml | 2 +- simulation/simulation_interface/CHANGELOG.rst | 15 +++++++++++++++ simulation/simulation_interface/package.xml | 2 +- simulation/traffic_simulator/CHANGELOG.rst | 18 ++++++++++++++++++ simulation/traffic_simulator/package.xml | 2 +- .../traffic_simulator_msgs/CHANGELOG.rst | 14 ++++++++++++++ simulation/traffic_simulator_msgs/package.xml | 2 +- test_runner/random_test_runner/CHANGELOG.rst | 14 ++++++++++++++ test_runner/random_test_runner/package.xml | 2 +- .../scenario_test_runner/CHANGELOG.rst | 19 +++++++++++++++++++ test_runner/scenario_test_runner/package.xml | 2 +- 58 files changed, 450 insertions(+), 29 deletions(-) diff --git a/common/math/arithmetic/CHANGELOG.rst b/common/math/arithmetic/CHANGELOG.rst index 798240c5750..330d9aa24aa 100644 --- a/common/math/arithmetic/CHANGELOG.rst +++ b/common/math/arithmetic/CHANGELOG.rst @@ -21,6 +21,20 @@ Changelog for package arithmetic * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.1.1 (2024-09-03) +------------------ +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge remote-tracking branch 'origin/master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into doc/RJD-1273-add-realtime-factor-doc +* Contributors: Dawid Moszynski, Dawid Moszyński, Kotaro Yoshimoto + 4.1.0 (2024-09-03) ------------------ * Merge branch 'master' into RJD-1278/fix-line-segment diff --git a/common/math/arithmetic/package.xml b/common/math/arithmetic/package.xml index e43e4b119fa..6e6b99eecc8 100644 --- a/common/math/arithmetic/package.xml +++ b/common/math/arithmetic/package.xml @@ -2,7 +2,7 @@ arithmetic - 4.1.0 + 4.1.1 arithmetic library for scenario_simulator_v2 Tatsuya Yamasaki Apache License 2.0 diff --git a/common/math/geometry/CHANGELOG.rst b/common/math/geometry/CHANGELOG.rst index 78f5dfec7f3..bb6fe0f336a 100644 --- a/common/math/geometry/CHANGELOG.rst +++ b/common/math/geometry/CHANGELOG.rst @@ -21,6 +21,20 @@ Changelog for package geometry * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.1.1 (2024-09-03) +------------------ +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge remote-tracking branch 'origin/master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into doc/RJD-1273-add-realtime-factor-doc +* Contributors: Dawid Moszynski, Dawid Moszyński, Kotaro Yoshimoto + 4.1.0 (2024-09-03) ------------------ * Merge pull request `#1353 `_ from tier4/RJD-1278/fix-line-segment diff --git a/common/math/geometry/package.xml b/common/math/geometry/package.xml index f1d4f4b1346..4efabccc4ab 100644 --- a/common/math/geometry/package.xml +++ b/common/math/geometry/package.xml @@ -2,7 +2,7 @@ geometry - 4.1.0 + 4.1.1 geometry math library for scenario_simulator_v2 application Masaya Kataoka Apache License 2.0 diff --git a/common/scenario_simulator_exception/CHANGELOG.rst b/common/scenario_simulator_exception/CHANGELOG.rst index 3f3aba9d0e0..751669f5645 100644 --- a/common/scenario_simulator_exception/CHANGELOG.rst +++ b/common/scenario_simulator_exception/CHANGELOG.rst @@ -21,6 +21,20 @@ Changelog for package scenario_simulator_exception * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.1.1 (2024-09-03) +------------------ +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge remote-tracking branch 'origin/master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into doc/RJD-1273-add-realtime-factor-doc +* Contributors: Dawid Moszynski, Dawid Moszyński, Kotaro Yoshimoto + 4.1.0 (2024-09-03) ------------------ * Merge branch 'master' into RJD-1278/fix-line-segment diff --git a/common/scenario_simulator_exception/package.xml b/common/scenario_simulator_exception/package.xml index 73b6c401da2..f8044694277 100644 --- a/common/scenario_simulator_exception/package.xml +++ b/common/scenario_simulator_exception/package.xml @@ -2,7 +2,7 @@ scenario_simulator_exception - 4.1.0 + 4.1.1 Exception types for scenario simulator Tatsuya Yamasaki Apache License 2.0 diff --git a/common/simple_junit/CHANGELOG.rst b/common/simple_junit/CHANGELOG.rst index 33220c8e35b..e8c04a9b3da 100644 --- a/common/simple_junit/CHANGELOG.rst +++ b/common/simple_junit/CHANGELOG.rst @@ -21,6 +21,20 @@ Changelog for package junit_exporter * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.1.1 (2024-09-03) +------------------ +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge remote-tracking branch 'origin/master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into doc/RJD-1273-add-realtime-factor-doc +* Contributors: Dawid Moszynski, Dawid Moszyński, Kotaro Yoshimoto + 4.1.0 (2024-09-03) ------------------ * Merge branch 'master' into RJD-1278/fix-line-segment diff --git a/common/simple_junit/package.xml b/common/simple_junit/package.xml index 29cb3c22b1c..94acfc23b4f 100644 --- a/common/simple_junit/package.xml +++ b/common/simple_junit/package.xml @@ -2,7 +2,7 @@ simple_junit - 4.1.0 + 4.1.1 Lightweight JUnit library for ROS 2 Masaya Kataoka Tatsuya Yamasaki diff --git a/common/status_monitor/CHANGELOG.rst b/common/status_monitor/CHANGELOG.rst index 71e4bd326fb..93bd7dae8e2 100644 --- a/common/status_monitor/CHANGELOG.rst +++ b/common/status_monitor/CHANGELOG.rst @@ -21,6 +21,20 @@ Changelog for package status_monitor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.1.1 (2024-09-03) +------------------ +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge remote-tracking branch 'origin/master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into doc/RJD-1273-add-realtime-factor-doc +* Contributors: Dawid Moszynski, Dawid Moszyński, Kotaro Yoshimoto + 4.1.0 (2024-09-03) ------------------ * Merge branch 'master' into RJD-1278/fix-line-segment diff --git a/common/status_monitor/package.xml b/common/status_monitor/package.xml index e335459d58e..8581f52357e 100644 --- a/common/status_monitor/package.xml +++ b/common/status_monitor/package.xml @@ -2,7 +2,7 @@ status_monitor - 4.1.0 + 4.1.1 none Tatsuya Yamasaki Apache License 2.0 diff --git a/external/concealer/CHANGELOG.rst b/external/concealer/CHANGELOG.rst index b68296f8743..a65070a5b3a 100644 --- a/external/concealer/CHANGELOG.rst +++ b/external/concealer/CHANGELOG.rst @@ -21,6 +21,20 @@ Changelog for package concealer * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.1.1 (2024-09-03) +------------------ +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge remote-tracking branch 'origin/master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into doc/RJD-1273-add-realtime-factor-doc +* Contributors: Dawid Moszynski, Dawid Moszyński, Kotaro Yoshimoto + 4.1.0 (2024-09-03) ------------------ * Merge branch 'master' into RJD-1278/fix-line-segment diff --git a/external/concealer/package.xml b/external/concealer/package.xml index e8bc60a7cfd..43e7da9c9cb 100644 --- a/external/concealer/package.xml +++ b/external/concealer/package.xml @@ -2,7 +2,7 @@ concealer - 4.1.0 + 4.1.1 Provides a class 'Autoware' to conceal miscellaneous things to simplify Autoware management of the simulator. Tatsuya Yamasaki Apache License 2.0 diff --git a/external/embree_vendor/CHANGELOG.rst b/external/embree_vendor/CHANGELOG.rst index c99809ca1eb..f43f59683ed 100644 --- a/external/embree_vendor/CHANGELOG.rst +++ b/external/embree_vendor/CHANGELOG.rst @@ -24,6 +24,20 @@ Changelog for package embree_vendor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.1.1 (2024-09-03) +------------------ +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge remote-tracking branch 'origin/master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into doc/RJD-1273-add-realtime-factor-doc +* Contributors: Dawid Moszynski, Dawid Moszyński, Kotaro Yoshimoto + 4.1.0 (2024-09-03) ------------------ * Merge branch 'master' into RJD-1278/fix-line-segment diff --git a/external/embree_vendor/package.xml b/external/embree_vendor/package.xml index d132c246a38..5eb7b996777 100644 --- a/external/embree_vendor/package.xml +++ b/external/embree_vendor/package.xml @@ -2,7 +2,7 @@ embree_vendor - 4.1.0 + 4.1.1 vendor packages for intel raytracing kernel library masaya Apache 2.0 diff --git a/map/kashiwanoha_map/CHANGELOG.rst b/map/kashiwanoha_map/CHANGELOG.rst index 0861c50126d..22bf4853964 100644 --- a/map/kashiwanoha_map/CHANGELOG.rst +++ b/map/kashiwanoha_map/CHANGELOG.rst @@ -21,6 +21,20 @@ Changelog for package kashiwanoha_map * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.1.1 (2024-09-03) +------------------ +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge remote-tracking branch 'origin/master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into doc/RJD-1273-add-realtime-factor-doc +* Contributors: Dawid Moszynski, Dawid Moszyński, Kotaro Yoshimoto + 4.1.0 (2024-09-03) ------------------ * Merge branch 'master' into RJD-1278/fix-line-segment diff --git a/map/kashiwanoha_map/package.xml b/map/kashiwanoha_map/package.xml index 394167d04fa..8dc789e7ad9 100644 --- a/map/kashiwanoha_map/package.xml +++ b/map/kashiwanoha_map/package.xml @@ -2,7 +2,7 @@ kashiwanoha_map - 4.1.0 + 4.1.1 map package for kashiwanoha Masaya Kataoka Apache License 2.0 diff --git a/map/simple_cross_map/CHANGELOG.rst b/map/simple_cross_map/CHANGELOG.rst index ad95ad7ab75..df422fbee7e 100644 --- a/map/simple_cross_map/CHANGELOG.rst +++ b/map/simple_cross_map/CHANGELOG.rst @@ -9,6 +9,20 @@ Changelog for package simple_cross_map * Merge branch 'master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.1.1 (2024-09-03) +------------------ +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge remote-tracking branch 'origin/master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into doc/RJD-1273-add-realtime-factor-doc +* Contributors: Dawid Moszynski, Dawid Moszyński, Kotaro Yoshimoto + 4.1.0 (2024-09-03) ------------------ * Merge branch 'master' into RJD-1278/fix-line-segment diff --git a/map/simple_cross_map/package.xml b/map/simple_cross_map/package.xml index 1ccfc858fdf..5844a6ddd6e 100644 --- a/map/simple_cross_map/package.xml +++ b/map/simple_cross_map/package.xml @@ -2,7 +2,7 @@ simple_cross_map - 4.1.0 + 4.1.1 map package for simple cross Masaya Kataoka Apache License 2.0 diff --git a/mock/cpp_mock_scenarios/CHANGELOG.rst b/mock/cpp_mock_scenarios/CHANGELOG.rst index dc2498e6200..5104c7ac09b 100644 --- a/mock/cpp_mock_scenarios/CHANGELOG.rst +++ b/mock/cpp_mock_scenarios/CHANGELOG.rst @@ -21,6 +21,20 @@ Changelog for package cpp_mock_scenarios * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.1.1 (2024-09-03) +------------------ +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge remote-tracking branch 'origin/master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into doc/RJD-1273-add-realtime-factor-doc +* Contributors: Dawid Moszynski, Dawid Moszyński, Kotaro Yoshimoto + 4.1.0 (2024-09-03) ------------------ * Merge branch 'master' into RJD-1278/fix-line-segment diff --git a/mock/cpp_mock_scenarios/package.xml b/mock/cpp_mock_scenarios/package.xml index bdfce4bf3f6..f595e5f10dc 100644 --- a/mock/cpp_mock_scenarios/package.xml +++ b/mock/cpp_mock_scenarios/package.xml @@ -2,7 +2,7 @@ cpp_mock_scenarios - 4.1.0 + 4.1.1 C++ mock scenarios masaya Apache License 2.0 diff --git a/openscenario/openscenario_experimental_catalog/CHANGELOG.rst b/openscenario/openscenario_experimental_catalog/CHANGELOG.rst index 45f16c7f224..4bc7d1e3f3e 100644 --- a/openscenario/openscenario_experimental_catalog/CHANGELOG.rst +++ b/openscenario/openscenario_experimental_catalog/CHANGELOG.rst @@ -21,6 +21,20 @@ Changelog for package openscenario_experimental_catalog * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.1.1 (2024-09-03) +------------------ +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge remote-tracking branch 'origin/master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into doc/RJD-1273-add-realtime-factor-doc +* Contributors: Dawid Moszynski, Dawid Moszyński, Kotaro Yoshimoto + 4.1.0 (2024-09-03) ------------------ * Merge branch 'master' into RJD-1278/fix-line-segment diff --git a/openscenario/openscenario_experimental_catalog/package.xml b/openscenario/openscenario_experimental_catalog/package.xml index bff30fd153a..45f27892af7 100644 --- a/openscenario/openscenario_experimental_catalog/package.xml +++ b/openscenario/openscenario_experimental_catalog/package.xml @@ -2,7 +2,7 @@ openscenario_experimental_catalog - 4.1.0 + 4.1.1 TIER IV experimental catalogs for OpenSCENARIO Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter/CHANGELOG.rst b/openscenario/openscenario_interpreter/CHANGELOG.rst index 4d18a9ce2d1..71666b59396 100644 --- a/openscenario/openscenario_interpreter/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter/CHANGELOG.rst @@ -32,6 +32,21 @@ Changelog for package openscenario_interpreter * add publish_empty_context parameter * Contributors: Masaya Kataoka +4.1.1 (2024-09-03) +------------------ +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge remote-tracking branch 'origin/master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into doc/RJD-1273-add-realtime-factor-doc +* Contributors: Dawid Moszynski, Dawid Moszyński, Kotaro Yoshimoto + 4.1.0 (2024-09-03) ------------------ * Merge branch 'master' into RJD-1278/fix-line-segment diff --git a/openscenario/openscenario_interpreter/package.xml b/openscenario/openscenario_interpreter/package.xml index de5a6d9ce11..3d070c90e78 100644 --- a/openscenario/openscenario_interpreter/package.xml +++ b/openscenario/openscenario_interpreter/package.xml @@ -2,7 +2,7 @@ openscenario_interpreter - 4.1.0 + 4.1.1 OpenSCENARIO 1.2.0 interpreter package for Autoware Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter_example/CHANGELOG.rst b/openscenario/openscenario_interpreter_example/CHANGELOG.rst index eab5fcfc343..284f8b712ce 100644 --- a/openscenario/openscenario_interpreter_example/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter_example/CHANGELOG.rst @@ -21,6 +21,20 @@ Changelog for package openscenario_interpreter_example * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.1.1 (2024-09-03) +------------------ +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge remote-tracking branch 'origin/master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into doc/RJD-1273-add-realtime-factor-doc +* Contributors: Dawid Moszynski, Dawid Moszyński, Kotaro Yoshimoto + 4.1.0 (2024-09-03) ------------------ * Merge branch 'master' into RJD-1278/fix-line-segment diff --git a/openscenario/openscenario_interpreter_example/package.xml b/openscenario/openscenario_interpreter_example/package.xml index dcb5d70431d..0eddc9f2065 100644 --- a/openscenario/openscenario_interpreter_example/package.xml +++ b/openscenario/openscenario_interpreter_example/package.xml @@ -3,7 +3,7 @@ openscenario_interpreter_example - 4.1.0 + 4.1.1 Examples for some TIER IV OpenSCENARIO Interpreter's features Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst b/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst index 0979b4b8d63..2ff6a3ad396 100644 --- a/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst @@ -21,6 +21,20 @@ Changelog for package openscenario_interpreter_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.1.1 (2024-09-03) +------------------ +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge remote-tracking branch 'origin/master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into doc/RJD-1273-add-realtime-factor-doc +* Contributors: Dawid Moszynski, Dawid Moszyński, Kotaro Yoshimoto + 4.1.0 (2024-09-03) ------------------ * Merge branch 'master' into RJD-1278/fix-line-segment diff --git a/openscenario/openscenario_interpreter_msgs/package.xml b/openscenario/openscenario_interpreter_msgs/package.xml index d30064c23bf..c0c44be4bcf 100644 --- a/openscenario/openscenario_interpreter_msgs/package.xml +++ b/openscenario/openscenario_interpreter_msgs/package.xml @@ -2,7 +2,7 @@ openscenario_interpreter_msgs - 4.1.0 + 4.1.1 ROS message types for package openscenario_interpreter Yamasaki Tatsuya Apache License 2.0 diff --git a/openscenario/openscenario_preprocessor/CHANGELOG.rst b/openscenario/openscenario_preprocessor/CHANGELOG.rst index e1ffb99c452..2c679019060 100644 --- a/openscenario/openscenario_preprocessor/CHANGELOG.rst +++ b/openscenario/openscenario_preprocessor/CHANGELOG.rst @@ -21,6 +21,20 @@ Changelog for package openscenario_preprocessor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.1.1 (2024-09-03) +------------------ +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge remote-tracking branch 'origin/master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into doc/RJD-1273-add-realtime-factor-doc +* Contributors: Dawid Moszynski, Dawid Moszyński, Kotaro Yoshimoto + 4.1.0 (2024-09-03) ------------------ * Merge branch 'master' into RJD-1278/fix-line-segment diff --git a/openscenario/openscenario_preprocessor/package.xml b/openscenario/openscenario_preprocessor/package.xml index 727976cfc2e..2806381635c 100644 --- a/openscenario/openscenario_preprocessor/package.xml +++ b/openscenario/openscenario_preprocessor/package.xml @@ -3,7 +3,7 @@ openscenario_preprocessor - 4.1.0 + 4.1.1 Example package for TIER IV OpenSCENARIO Interpreter Kotaro Yoshimoto Apache License 2.0 diff --git a/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst b/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst index 9be6223f578..4f6847559fc 100644 --- a/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst +++ b/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst @@ -21,6 +21,20 @@ Changelog for package openscenario_preprocessor_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.1.1 (2024-09-03) +------------------ +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge remote-tracking branch 'origin/master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into doc/RJD-1273-add-realtime-factor-doc +* Contributors: Dawid Moszynski, Dawid Moszyński, Kotaro Yoshimoto + 4.1.0 (2024-09-03) ------------------ * Merge branch 'master' into RJD-1278/fix-line-segment diff --git a/openscenario/openscenario_preprocessor_msgs/package.xml b/openscenario/openscenario_preprocessor_msgs/package.xml index 9c0bdac10b5..af39b90a017 100644 --- a/openscenario/openscenario_preprocessor_msgs/package.xml +++ b/openscenario/openscenario_preprocessor_msgs/package.xml @@ -2,7 +2,7 @@ openscenario_preprocessor_msgs - 4.1.0 + 4.1.1 ROS message types for package openscenario_preprocessor Kotaro Yoshimoto Apache License 2.0 diff --git a/openscenario/openscenario_utility/CHANGELOG.rst b/openscenario/openscenario_utility/CHANGELOG.rst index 7c359c8bb51..7303319e8d7 100644 --- a/openscenario/openscenario_utility/CHANGELOG.rst +++ b/openscenario/openscenario_utility/CHANGELOG.rst @@ -24,6 +24,20 @@ Changelog for package openscenario_utility * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.1.1 (2024-09-03) +------------------ +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge remote-tracking branch 'origin/master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into doc/RJD-1273-add-realtime-factor-doc +* Contributors: Dawid Moszynski, Dawid Moszyński, Kotaro Yoshimoto + 4.1.0 (2024-09-03) ------------------ * Merge branch 'master' into RJD-1278/fix-line-segment diff --git a/openscenario/openscenario_utility/package.xml b/openscenario/openscenario_utility/package.xml index d65a371ab39..17130a022c3 100644 --- a/openscenario/openscenario_utility/package.xml +++ b/openscenario/openscenario_utility/package.xml @@ -2,7 +2,7 @@ openscenario_utility - 4.1.0 + 4.1.1 Utility tools for ASAM OpenSCENARIO 1.2.0 Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_validator/CHANGELOG.rst b/openscenario/openscenario_validator/CHANGELOG.rst index 07b5937398d..edae34b089e 100644 --- a/openscenario/openscenario_validator/CHANGELOG.rst +++ b/openscenario/openscenario_validator/CHANGELOG.rst @@ -10,6 +10,20 @@ Changelog for package openscenario_validator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.1.1 (2024-09-03) +------------------ +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge remote-tracking branch 'origin/master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into doc/RJD-1273-add-realtime-factor-doc +* Contributors: Dawid Moszynski, Dawid Moszyński, Kotaro Yoshimoto + 4.1.0 (2024-09-03) ------------------ * Merge branch 'master' into RJD-1278/fix-line-segment diff --git a/openscenario/openscenario_validator/package.xml b/openscenario/openscenario_validator/package.xml index 7bfe192367b..da541f624f9 100644 --- a/openscenario/openscenario_validator/package.xml +++ b/openscenario/openscenario_validator/package.xml @@ -2,7 +2,7 @@ openscenario_validator - 4.1.0 + 4.1.1 Validator for OpenSCENARIO 1.3 Kotaro Yoshimoto Apache License 2.0 diff --git a/rviz_plugins/openscenario_visualization/CHANGELOG.rst b/rviz_plugins/openscenario_visualization/CHANGELOG.rst index f4e0684997a..d69f5f28b9c 100644 --- a/rviz_plugins/openscenario_visualization/CHANGELOG.rst +++ b/rviz_plugins/openscenario_visualization/CHANGELOG.rst @@ -21,6 +21,20 @@ Changelog for package openscenario_visualization * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.1.1 (2024-09-03) +------------------ +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge remote-tracking branch 'origin/master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into doc/RJD-1273-add-realtime-factor-doc +* Contributors: Dawid Moszynski, Dawid Moszyński, Kotaro Yoshimoto + 4.1.0 (2024-09-03) ------------------ * Merge branch 'master' into RJD-1278/fix-line-segment diff --git a/rviz_plugins/openscenario_visualization/package.xml b/rviz_plugins/openscenario_visualization/package.xml index 7d4ab9d638f..e76f23b4545 100644 --- a/rviz_plugins/openscenario_visualization/package.xml +++ b/rviz_plugins/openscenario_visualization/package.xml @@ -2,7 +2,7 @@ openscenario_visualization - 4.1.0 + 4.1.1 Visualization tools for simulation results Masaya Kataoka Kyoichi Sugahara diff --git a/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst b/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst index 45b50390972..89dc9d79e52 100644 --- a/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst +++ b/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst @@ -21,6 +21,20 @@ Changelog for package real_time_factor_control_rviz_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.1.1 (2024-09-03) +------------------ +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge remote-tracking branch 'origin/master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into doc/RJD-1273-add-realtime-factor-doc +* Contributors: Dawid Moszynski, Dawid Moszyński, Kotaro Yoshimoto + 4.1.0 (2024-09-03) ------------------ * Merge branch 'master' into RJD-1278/fix-line-segment diff --git a/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml b/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml index 95bb05b9e6d..7e40fec1330 100644 --- a/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml +++ b/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml @@ -2,7 +2,7 @@ real_time_factor_control_rviz_plugin - 4.1.0 + 4.1.1 Slider controlling real time factor value. Paweł Lech Apache License 2.0 diff --git a/scenario_simulator_v2/CHANGELOG.rst b/scenario_simulator_v2/CHANGELOG.rst index 45ad48f52ae..d75490f9061 100644 --- a/scenario_simulator_v2/CHANGELOG.rst +++ b/scenario_simulator_v2/CHANGELOG.rst @@ -21,6 +21,20 @@ Changelog for package scenario_simulator_v2 * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.1.1 (2024-09-03) +------------------ +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge remote-tracking branch 'origin/master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into doc/RJD-1273-add-realtime-factor-doc +* Contributors: Dawid Moszynski, Dawid Moszyński, Kotaro Yoshimoto + 4.1.0 (2024-09-03) ------------------ * Merge branch 'master' into RJD-1278/fix-line-segment diff --git a/scenario_simulator_v2/package.xml b/scenario_simulator_v2/package.xml index d8ffcaefbd1..75a3120d806 100644 --- a/scenario_simulator_v2/package.xml +++ b/scenario_simulator_v2/package.xml @@ -2,7 +2,7 @@ scenario_simulator_v2 - 4.1.0 + 4.1.1 scenario testing framework for Autoware Masaya Kataoka Apache License 2.0 diff --git a/simulation/behavior_tree_plugin/CHANGELOG.rst b/simulation/behavior_tree_plugin/CHANGELOG.rst index 6d8bcd80543..a1827aa4290 100644 --- a/simulation/behavior_tree_plugin/CHANGELOG.rst +++ b/simulation/behavior_tree_plugin/CHANGELOG.rst @@ -21,6 +21,20 @@ Changelog for package behavior_tree_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.1.1 (2024-09-03) +------------------ +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge remote-tracking branch 'origin/master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into doc/RJD-1273-add-realtime-factor-doc +* Contributors: Dawid Moszynski, Dawid Moszyński, Kotaro Yoshimoto + 4.1.0 (2024-09-03) ------------------ * Merge branch 'master' into RJD-1278/fix-line-segment diff --git a/simulation/behavior_tree_plugin/package.xml b/simulation/behavior_tree_plugin/package.xml index f63468266a5..b049b75aecf 100644 --- a/simulation/behavior_tree_plugin/package.xml +++ b/simulation/behavior_tree_plugin/package.xml @@ -2,7 +2,7 @@ behavior_tree_plugin - 4.1.0 + 4.1.1 Behavior tree plugin for traffic_simulator masaya Apache 2.0 diff --git a/simulation/do_nothing_plugin/CHANGELOG.rst b/simulation/do_nothing_plugin/CHANGELOG.rst index c8c5c7d59a3..333a17a14ce 100644 --- a/simulation/do_nothing_plugin/CHANGELOG.rst +++ b/simulation/do_nothing_plugin/CHANGELOG.rst @@ -21,6 +21,20 @@ Changelog for package do_nothing_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.1.1 (2024-09-03) +------------------ +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge remote-tracking branch 'origin/master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into doc/RJD-1273-add-realtime-factor-doc +* Contributors: Dawid Moszynski, Dawid Moszyński, Kotaro Yoshimoto + 4.1.0 (2024-09-03) ------------------ * Merge branch 'master' into RJD-1278/fix-line-segment diff --git a/simulation/do_nothing_plugin/package.xml b/simulation/do_nothing_plugin/package.xml index 0cefa0af367..04e674bafbe 100644 --- a/simulation/do_nothing_plugin/package.xml +++ b/simulation/do_nothing_plugin/package.xml @@ -2,7 +2,7 @@ do_nothing_plugin - 4.1.0 + 4.1.1 Behavior plugin for do nothing Masaya Kataoka Apache 2.0 diff --git a/simulation/simple_sensor_simulator/CHANGELOG.rst b/simulation/simple_sensor_simulator/CHANGELOG.rst index b1bb91e0a45..589423df12d 100644 --- a/simulation/simple_sensor_simulator/CHANGELOG.rst +++ b/simulation/simple_sensor_simulator/CHANGELOG.rst @@ -21,6 +21,24 @@ Changelog for package simple_sensor_simulator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.1.1 (2024-09-03) +------------------ +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Revert "feat(params): set use_sim_time default as True" + This reverts commit da85edf4956083563715daa3d60f0da1f94a423d. +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* feat(params): set use_sim_time default as True +* Merge remote-tracking branch 'origin/master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into doc/RJD-1273-add-realtime-factor-doc +* Contributors: Dawid Moszynski, Dawid Moszyński, Kotaro Yoshimoto + 4.1.0 (2024-09-03) ------------------ * Merge branch 'master' into RJD-1278/fix-line-segment diff --git a/simulation/simple_sensor_simulator/package.xml b/simulation/simple_sensor_simulator/package.xml index f8540ec94f0..bd84da7888a 100644 --- a/simulation/simple_sensor_simulator/package.xml +++ b/simulation/simple_sensor_simulator/package.xml @@ -1,7 +1,7 @@ simple_sensor_simulator - 4.1.0 + 4.1.1 simple_sensor_simulator package masaya kataoka diff --git a/simulation/simulation_interface/CHANGELOG.rst b/simulation/simulation_interface/CHANGELOG.rst index 042d163f8bb..808b578281b 100644 --- a/simulation/simulation_interface/CHANGELOG.rst +++ b/simulation/simulation_interface/CHANGELOG.rst @@ -21,6 +21,21 @@ Changelog for package simulation_interface * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.1.1 (2024-09-03) +------------------ +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge remote-tracking branch 'origin/master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into doc/RJD-1273-add-realtime-factor-doc +* Contributors: Dawid Moszynski, Dawid Moszyński, Kotaro Yoshimoto + 4.1.0 (2024-09-03) ------------------ * Merge branch 'master' into RJD-1278/fix-line-segment diff --git a/simulation/simulation_interface/package.xml b/simulation/simulation_interface/package.xml index 519a95c2094..7900025ff2e 100644 --- a/simulation/simulation_interface/package.xml +++ b/simulation/simulation_interface/package.xml @@ -2,7 +2,7 @@ simulation_interface - 4.1.0 + 4.1.1 packages to define interface between simulator and scenario interpreter Masaya Kataoka Apache License 2.0 diff --git a/simulation/traffic_simulator/CHANGELOG.rst b/simulation/traffic_simulator/CHANGELOG.rst index 1198df922fa..8e67976fb9e 100644 --- a/simulation/traffic_simulator/CHANGELOG.rst +++ b/simulation/traffic_simulator/CHANGELOG.rst @@ -21,6 +21,24 @@ Changelog for package traffic_simulator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.1.1 (2024-09-03) +------------------ +* Merge pull request `#1207 `_ from tier4/fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* feat(use_sim_time): set default as false +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge remote-tracking branch 'origin/master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into doc/RJD-1273-add-realtime-factor-doc +* use_sim_time used in concealer initialization +* Contributors: Dawid Moszynski, Dawid Moszyński, Kotaro Yoshimoto, Paweł Lech + 4.1.0 (2024-09-03) ------------------ * Merge branch 'master' into RJD-1278/fix-line-segment diff --git a/simulation/traffic_simulator/package.xml b/simulation/traffic_simulator/package.xml index 0c23831f034..24c4c007e01 100644 --- a/simulation/traffic_simulator/package.xml +++ b/simulation/traffic_simulator/package.xml @@ -1,7 +1,7 @@ traffic_simulator - 4.1.0 + 4.1.1 control traffic flow masaya kataoka diff --git a/simulation/traffic_simulator_msgs/CHANGELOG.rst b/simulation/traffic_simulator_msgs/CHANGELOG.rst index 32b8498248c..5db5f440c2e 100644 --- a/simulation/traffic_simulator_msgs/CHANGELOG.rst +++ b/simulation/traffic_simulator_msgs/CHANGELOG.rst @@ -21,6 +21,20 @@ Changelog for package openscenario_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.1.1 (2024-09-03) +------------------ +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge remote-tracking branch 'origin/master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into doc/RJD-1273-add-realtime-factor-doc +* Contributors: Dawid Moszynski, Dawid Moszyński, Kotaro Yoshimoto + 4.1.0 (2024-09-03) ------------------ * Merge branch 'master' into RJD-1278/fix-line-segment diff --git a/simulation/traffic_simulator_msgs/package.xml b/simulation/traffic_simulator_msgs/package.xml index 09a9de877df..8050ee25c17 100644 --- a/simulation/traffic_simulator_msgs/package.xml +++ b/simulation/traffic_simulator_msgs/package.xml @@ -2,7 +2,7 @@ traffic_simulator_msgs - 4.1.0 + 4.1.1 ROS messages for openscenario Masaya Kataoka Apache License 2.0 diff --git a/test_runner/random_test_runner/CHANGELOG.rst b/test_runner/random_test_runner/CHANGELOG.rst index 97aa4d0b437..6fefac553c0 100644 --- a/test_runner/random_test_runner/CHANGELOG.rst +++ b/test_runner/random_test_runner/CHANGELOG.rst @@ -21,6 +21,20 @@ Changelog for package random_test_runner * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.1.1 (2024-09-03) +------------------ +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge remote-tracking branch 'origin/master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into doc/RJD-1273-add-realtime-factor-doc +* Contributors: Dawid Moszynski, Dawid Moszyński, Kotaro Yoshimoto + 4.1.0 (2024-09-03) ------------------ * Merge branch 'master' into RJD-1278/fix-line-segment diff --git a/test_runner/random_test_runner/package.xml b/test_runner/random_test_runner/package.xml index 661360ef9e4..84b08a721a1 100644 --- a/test_runner/random_test_runner/package.xml +++ b/test_runner/random_test_runner/package.xml @@ -2,7 +2,7 @@ random_test_runner - 4.1.0 + 4.1.1 Random behavior test runner piotr-zyskowski-rai Apache License 2.0 diff --git a/test_runner/scenario_test_runner/CHANGELOG.rst b/test_runner/scenario_test_runner/CHANGELOG.rst index 6ded1b349c5..afa619d2d51 100644 --- a/test_runner/scenario_test_runner/CHANGELOG.rst +++ b/test_runner/scenario_test_runner/CHANGELOG.rst @@ -35,6 +35,25 @@ Changelog for package scenario_test_runner * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.1.1 (2024-09-03) +------------------ +* Merge pull request `#1207 `_ from tier4/fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* feat(use_sim_time): set default as false +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* Revert "feat(params): set use_sim_time default as True" + This reverts commit da85edf4956083563715daa3d60f0da1f94a423d. +* Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control +* feat(params): set use_sim_time default as True +* Merge remote-tracking branch 'origin/master' into fix/use-sim-time-for-real-time-factor-control +* Merge branch 'master' into doc/RJD-1273-add-realtime-factor-doc +* Contributors: Dawid Moszynski, Dawid Moszyński, Kotaro Yoshimoto + 4.1.0 (2024-09-03) ------------------ * Merge branch 'master' into RJD-1278/fix-line-segment diff --git a/test_runner/scenario_test_runner/package.xml b/test_runner/scenario_test_runner/package.xml index c8cd38804e6..8ae5e7817c6 100644 --- a/test_runner/scenario_test_runner/package.xml +++ b/test_runner/scenario_test_runner/package.xml @@ -2,7 +2,7 @@ scenario_test_runner - 4.1.0 + 4.1.1 scenario test runner package Tatsuya Yamasaki Apache License 2.0 From 50bcb748bbb35741788a8a7d9c0e3aca179747a9 Mon Sep 17 00:00:00 2001 From: robomic Date: Mon, 5 Aug 2024 11:24:24 +0200 Subject: [PATCH 196/304] add a proper structure to the test files --- common/math/geometry/test/CMakeLists.txt | 35 +++++++------------ .../test/{ => src}/expect_eq_macros.hpp | 0 .../test/src/intersection/CMakeLists.txt | 5 +++ .../{ => src/intersection}/test_collision.cpp | 2 +- .../intersection}/test_intersection.cpp | 4 +-- .../geometry/test/src/polygon/CMakeLists.txt | 5 +++ .../{ => src/polygon}/test_line_segment.cpp | 4 +-- .../test/{ => src/polygon}/test_polygon.cpp | 4 +-- .../test/src/quaternion/CMakeLists.txt | 2 ++ .../{ => src/quaternion}/test_quaternion.cpp | 4 +-- .../geometry/test/src/solver/CMakeLists.txt | 2 ++ .../solver}/test_polynomial_solver.cpp | 0 .../geometry/test/src/spline/CMakeLists.txt | 8 +++++ .../spline}/test_catmull_rom_spline.cpp | 4 +-- .../spline}/test_catmull_rom_subspline.cpp | 4 +-- .../{ => src/spline}/test_hermite_curve.cpp | 4 +-- .../test/{ => src}/test_bounding_box.cpp | 0 .../geometry/test/{ => src}/test_distance.cpp | 0 .../test/{ => src}/test_transform.cpp | 0 .../geometry/test/{ => src}/test_utils.hpp | 0 .../test/{ => src}/vector3/CMakeLists.txt | 0 .../vector3/test_truncate_custom.cpp | 0 .../{ => src}/vector3/test_truncate_msg.cpp | 0 .../test/{ => src}/vector3/test_vector3.cpp | 0 24 files changed, 49 insertions(+), 38 deletions(-) rename common/math/geometry/test/{ => src}/expect_eq_macros.hpp (100%) create mode 100644 common/math/geometry/test/src/intersection/CMakeLists.txt rename common/math/geometry/test/{ => src/intersection}/test_collision.cpp (99%) rename common/math/geometry/test/{ => src/intersection}/test_intersection.cpp (98%) create mode 100644 common/math/geometry/test/src/polygon/CMakeLists.txt rename common/math/geometry/test/{ => src/polygon}/test_line_segment.cpp (99%) rename common/math/geometry/test/{ => src/polygon}/test_polygon.cpp (98%) create mode 100644 common/math/geometry/test/src/quaternion/CMakeLists.txt rename common/math/geometry/test/{ => src/quaternion}/test_quaternion.cpp (96%) create mode 100644 common/math/geometry/test/src/solver/CMakeLists.txt rename common/math/geometry/test/{ => src/solver}/test_polynomial_solver.cpp (100%) create mode 100644 common/math/geometry/test/src/spline/CMakeLists.txt rename common/math/geometry/test/{ => src/spline}/test_catmull_rom_spline.cpp (99%) rename common/math/geometry/test/{ => src/spline}/test_catmull_rom_subspline.cpp (98%) rename common/math/geometry/test/{ => src/spline}/test_hermite_curve.cpp (99%) rename common/math/geometry/test/{ => src}/test_bounding_box.cpp (100%) rename common/math/geometry/test/{ => src}/test_distance.cpp (100%) rename common/math/geometry/test/{ => src}/test_transform.cpp (100%) rename common/math/geometry/test/{ => src}/test_utils.hpp (100%) rename common/math/geometry/test/{ => src}/vector3/CMakeLists.txt (100%) rename common/math/geometry/test/{ => src}/vector3/test_truncate_custom.cpp (100%) rename common/math/geometry/test/{ => src}/vector3/test_truncate_msg.cpp (100%) rename common/math/geometry/test/{ => src}/vector3/test_vector3.cpp (100%) diff --git a/common/math/geometry/test/CMakeLists.txt b/common/math/geometry/test/CMakeLists.txt index dfd0a09460b..eed4ab3431c 100644 --- a/common/math/geometry/test/CMakeLists.txt +++ b/common/math/geometry/test/CMakeLists.txt @@ -1,26 +1,15 @@ -add_subdirectory(vector3) +add_subdirectory(src/intersection) +add_subdirectory(src/polygon) +add_subdirectory(src/quaternion) +add_subdirectory(src/solver) +add_subdirectory(src/spline) +add_subdirectory(src/vector3) -ament_add_gtest(test_bounding_box test_bounding_box.cpp) -ament_add_gtest(test_catmull_rom_spline test_catmull_rom_spline.cpp) -ament_add_gtest(test_catmull_rom_subspline test_catmull_rom_subspline.cpp) -ament_add_gtest(test_collision test_collision.cpp) -ament_add_gtest(test_distance test_distance.cpp) -ament_add_gtest(test_hermite_curve test_hermite_curve.cpp) -ament_add_gtest(test_polygon test_polygon.cpp) -ament_add_gtest(test_polynomial_solver test_polynomial_solver.cpp) -ament_add_gtest(test_transform test_transform.cpp) -ament_add_gtest(test_intersection test_intersection.cpp) -ament_add_gtest(test_line_segment test_line_segment.cpp) -ament_add_gtest(test_quaternion test_quaternion.cpp) -target_link_libraries(test_bounding_box geometry) -target_link_libraries(test_catmull_rom_spline geometry) -target_link_libraries(test_catmull_rom_subspline geometry) -target_link_libraries(test_collision geometry) +ament_add_gtest(test_distance src/test_distance.cpp) target_link_libraries(test_distance geometry) -target_link_libraries(test_hermite_curve geometry) -target_link_libraries(test_polygon geometry) -target_link_libraries(test_polynomial_solver geometry) + +ament_add_gtest(test_bounding_box src/test_bounding_box.cpp) +target_link_libraries(test_bounding_box geometry) + +ament_add_gtest(test_transform src/test_transform.cpp) target_link_libraries(test_transform geometry) -target_link_libraries(test_intersection geometry) -target_link_libraries(test_line_segment geometry) -target_link_libraries(test_quaternion geometry) diff --git a/common/math/geometry/test/expect_eq_macros.hpp b/common/math/geometry/test/src/expect_eq_macros.hpp similarity index 100% rename from common/math/geometry/test/expect_eq_macros.hpp rename to common/math/geometry/test/src/expect_eq_macros.hpp diff --git a/common/math/geometry/test/src/intersection/CMakeLists.txt b/common/math/geometry/test/src/intersection/CMakeLists.txt new file mode 100644 index 00000000000..ea171973a2c --- /dev/null +++ b/common/math/geometry/test/src/intersection/CMakeLists.txt @@ -0,0 +1,5 @@ +ament_add_gtest(test_collision test_collision.cpp) +target_link_libraries(test_collision geometry) + +ament_add_gtest(test_intersection test_intersection.cpp) +target_link_libraries(test_intersection geometry) diff --git a/common/math/geometry/test/test_collision.cpp b/common/math/geometry/test/src/intersection/test_collision.cpp similarity index 99% rename from common/math/geometry/test/test_collision.cpp rename to common/math/geometry/test/src/intersection/test_collision.cpp index cf60a70eba2..a32622d4f0c 100644 --- a/common/math/geometry/test/test_collision.cpp +++ b/common/math/geometry/test/src/intersection/test_collision.cpp @@ -17,7 +17,7 @@ #include #include -#include "test_utils.hpp" +#include "../test_utils.hpp" TEST(Collision, DifferentHeight) { diff --git a/common/math/geometry/test/test_intersection.cpp b/common/math/geometry/test/src/intersection/test_intersection.cpp similarity index 98% rename from common/math/geometry/test/test_intersection.cpp rename to common/math/geometry/test/src/intersection/test_intersection.cpp index 06b8925bbca..f21879f6555 100644 --- a/common/math/geometry/test/test_intersection.cpp +++ b/common/math/geometry/test/src/intersection/test_intersection.cpp @@ -18,8 +18,8 @@ #include #include -#include "expect_eq_macros.hpp" -#include "test_utils.hpp" +#include "../expect_eq_macros.hpp" +#include "../test_utils.hpp" TEST(Intersection, isIntersect2DDisjoint) { diff --git a/common/math/geometry/test/src/polygon/CMakeLists.txt b/common/math/geometry/test/src/polygon/CMakeLists.txt new file mode 100644 index 00000000000..8a2eae13418 --- /dev/null +++ b/common/math/geometry/test/src/polygon/CMakeLists.txt @@ -0,0 +1,5 @@ +ament_add_gtest(test_line_segment test_line_segment.cpp) +target_link_libraries(test_line_segment geometry) + +ament_add_gtest(test_polygon test_polygon.cpp) +target_link_libraries(test_polygon geometry) diff --git a/common/math/geometry/test/test_line_segment.cpp b/common/math/geometry/test/src/polygon/test_line_segment.cpp similarity index 99% rename from common/math/geometry/test/test_line_segment.cpp rename to common/math/geometry/test/src/polygon/test_line_segment.cpp index c7f6aeb6067..f927e9ba1f0 100644 --- a/common/math/geometry/test/test_line_segment.cpp +++ b/common/math/geometry/test/src/polygon/test_line_segment.cpp @@ -19,8 +19,8 @@ #include #include -#include "expect_eq_macros.hpp" -#include "test_utils.hpp" +#include "../expect_eq_macros.hpp" +#include "../test_utils.hpp" TEST(LineSegment, initializeDifferentPoints) { diff --git a/common/math/geometry/test/test_polygon.cpp b/common/math/geometry/test/src/polygon/test_polygon.cpp similarity index 98% rename from common/math/geometry/test/test_polygon.cpp rename to common/math/geometry/test/src/polygon/test_polygon.cpp index 8ec0ea97ad9..e7278fa6566 100644 --- a/common/math/geometry/test/test_polygon.cpp +++ b/common/math/geometry/test/src/polygon/test_polygon.cpp @@ -17,8 +17,8 @@ #include #include -#include "expect_eq_macros.hpp" -#include "test_utils.hpp" +#include "../expect_eq_macros.hpp" +#include "../test_utils.hpp" TEST(Polygon, filterByAxis) { diff --git a/common/math/geometry/test/src/quaternion/CMakeLists.txt b/common/math/geometry/test/src/quaternion/CMakeLists.txt new file mode 100644 index 00000000000..2ea2aaf3d91 --- /dev/null +++ b/common/math/geometry/test/src/quaternion/CMakeLists.txt @@ -0,0 +1,2 @@ +ament_add_gtest(test_quaternion test_quaternion.cpp) +target_link_libraries(test_quaternion geometry) diff --git a/common/math/geometry/test/test_quaternion.cpp b/common/math/geometry/test/src/quaternion/test_quaternion.cpp similarity index 96% rename from common/math/geometry/test/test_quaternion.cpp rename to common/math/geometry/test/src/quaternion/test_quaternion.cpp index 7dfd1285664..14c7f3a82ba 100644 --- a/common/math/geometry/test/test_quaternion.cpp +++ b/common/math/geometry/test/src/quaternion/test_quaternion.cpp @@ -18,8 +18,8 @@ #include #include -#include "expect_eq_macros.hpp" -#include "test_utils.hpp" +#include "../expect_eq_macros.hpp" +#include "../test_utils.hpp" constexpr double EPS = 1e-6; diff --git a/common/math/geometry/test/src/solver/CMakeLists.txt b/common/math/geometry/test/src/solver/CMakeLists.txt new file mode 100644 index 00000000000..0716910f184 --- /dev/null +++ b/common/math/geometry/test/src/solver/CMakeLists.txt @@ -0,0 +1,2 @@ +ament_add_gtest(test_polynomial_solver test_polynomial_solver.cpp) +target_link_libraries(test_polynomial_solver geometry) diff --git a/common/math/geometry/test/test_polynomial_solver.cpp b/common/math/geometry/test/src/solver/test_polynomial_solver.cpp similarity index 100% rename from common/math/geometry/test/test_polynomial_solver.cpp rename to common/math/geometry/test/src/solver/test_polynomial_solver.cpp diff --git a/common/math/geometry/test/src/spline/CMakeLists.txt b/common/math/geometry/test/src/spline/CMakeLists.txt new file mode 100644 index 00000000000..d6a2793f80d --- /dev/null +++ b/common/math/geometry/test/src/spline/CMakeLists.txt @@ -0,0 +1,8 @@ +ament_add_gtest(test_catmull_rom_spline test_catmull_rom_spline.cpp) +target_link_libraries(test_catmull_rom_spline geometry) + +ament_add_gtest(test_catmull_rom_subspline test_catmull_rom_subspline.cpp) +target_link_libraries(test_catmull_rom_subspline geometry) + +ament_add_gtest(test_hermite_curve test_hermite_curve.cpp) +target_link_libraries(test_hermite_curve geometry) diff --git a/common/math/geometry/test/test_catmull_rom_spline.cpp b/common/math/geometry/test/src/spline/test_catmull_rom_spline.cpp similarity index 99% rename from common/math/geometry/test/test_catmull_rom_spline.cpp rename to common/math/geometry/test/src/spline/test_catmull_rom_spline.cpp index b29aba00130..b224e7d0d45 100644 --- a/common/math/geometry/test/test_catmull_rom_spline.cpp +++ b/common/math/geometry/test/src/spline/test_catmull_rom_spline.cpp @@ -18,8 +18,8 @@ #include #include -#include "expect_eq_macros.hpp" -#include "test_utils.hpp" +#include "../expect_eq_macros.hpp" +#include "../test_utils.hpp" constexpr double EPS = 1e-6; diff --git a/common/math/geometry/test/test_catmull_rom_subspline.cpp b/common/math/geometry/test/src/spline/test_catmull_rom_subspline.cpp similarity index 98% rename from common/math/geometry/test/test_catmull_rom_subspline.cpp rename to common/math/geometry/test/src/spline/test_catmull_rom_subspline.cpp index 567d1bf089e..10b2b56124c 100644 --- a/common/math/geometry/test/test_catmull_rom_subspline.cpp +++ b/common/math/geometry/test/src/spline/test_catmull_rom_subspline.cpp @@ -17,8 +17,8 @@ #include #include -#include "expect_eq_macros.hpp" -#include "test_utils.hpp" +#include "../expect_eq_macros.hpp" +#include "../test_utils.hpp" constexpr double EPS = 1e-6; diff --git a/common/math/geometry/test/test_hermite_curve.cpp b/common/math/geometry/test/src/spline/test_hermite_curve.cpp similarity index 99% rename from common/math/geometry/test/test_hermite_curve.cpp rename to common/math/geometry/test/src/spline/test_hermite_curve.cpp index 9efbccef633..08ab6c3c4a0 100644 --- a/common/math/geometry/test/test_hermite_curve.cpp +++ b/common/math/geometry/test/src/spline/test_hermite_curve.cpp @@ -16,8 +16,8 @@ #include -#include "expect_eq_macros.hpp" -#include "test_utils.hpp" +#include "../expect_eq_macros.hpp" +#include "../test_utils.hpp" constexpr double EPS = 1e-3; diff --git a/common/math/geometry/test/test_bounding_box.cpp b/common/math/geometry/test/src/test_bounding_box.cpp similarity index 100% rename from common/math/geometry/test/test_bounding_box.cpp rename to common/math/geometry/test/src/test_bounding_box.cpp diff --git a/common/math/geometry/test/test_distance.cpp b/common/math/geometry/test/src/test_distance.cpp similarity index 100% rename from common/math/geometry/test/test_distance.cpp rename to common/math/geometry/test/src/test_distance.cpp diff --git a/common/math/geometry/test/test_transform.cpp b/common/math/geometry/test/src/test_transform.cpp similarity index 100% rename from common/math/geometry/test/test_transform.cpp rename to common/math/geometry/test/src/test_transform.cpp diff --git a/common/math/geometry/test/test_utils.hpp b/common/math/geometry/test/src/test_utils.hpp similarity index 100% rename from common/math/geometry/test/test_utils.hpp rename to common/math/geometry/test/src/test_utils.hpp diff --git a/common/math/geometry/test/vector3/CMakeLists.txt b/common/math/geometry/test/src/vector3/CMakeLists.txt similarity index 100% rename from common/math/geometry/test/vector3/CMakeLists.txt rename to common/math/geometry/test/src/vector3/CMakeLists.txt diff --git a/common/math/geometry/test/vector3/test_truncate_custom.cpp b/common/math/geometry/test/src/vector3/test_truncate_custom.cpp similarity index 100% rename from common/math/geometry/test/vector3/test_truncate_custom.cpp rename to common/math/geometry/test/src/vector3/test_truncate_custom.cpp diff --git a/common/math/geometry/test/vector3/test_truncate_msg.cpp b/common/math/geometry/test/src/vector3/test_truncate_msg.cpp similarity index 100% rename from common/math/geometry/test/vector3/test_truncate_msg.cpp rename to common/math/geometry/test/src/vector3/test_truncate_msg.cpp diff --git a/common/math/geometry/test/vector3/test_vector3.cpp b/common/math/geometry/test/src/vector3/test_vector3.cpp similarity index 100% rename from common/math/geometry/test/vector3/test_vector3.cpp rename to common/math/geometry/test/src/vector3/test_vector3.cpp From 069e3b4f283bfd2fb0ffbba3314e98e5a508a7f1 Mon Sep 17 00:00:00 2001 From: robomic Date: Mon, 5 Aug 2024 14:37:48 +0200 Subject: [PATCH 197/304] getPose, getPoint refactor --- .../test/src/polygon/test_line_segment.cpp | 198 ++++++++++-------- 1 file changed, 111 insertions(+), 87 deletions(-) diff --git a/common/math/geometry/test/src/polygon/test_line_segment.cpp b/common/math/geometry/test/src/polygon/test_line_segment.cpp index f927e9ba1f0..4eac94644ab 100644 --- a/common/math/geometry/test/src/polygon/test_line_segment.cpp +++ b/common/math/geometry/test/src/polygon/test_line_segment.cpp @@ -17,6 +17,7 @@ #include #include #include +#include #include #include "../expect_eq_macros.hpp" @@ -326,97 +327,120 @@ TEST(LineSegment, getSValue_parallelDenormalize) EXPECT_FALSE(s); } -/// @brief In this test case, testing the `LineSegment::getPoint` function can find the point on the line segment with start point (x,y,z) = (0,0,0) and end point (x,y,z) = (1,1,1) in the cartesian coordinate system. (variable name `line`). -TEST(LineSegment, GetPoint) +TEST(LineSegment, GetPoint_outOfBounds_denormalized) { - { - math::geometry::LineSegment line( - geometry_msgs::build().x(0).y(0).z(0), - geometry_msgs::build().x(1).y(1).z(1)); - /// @note If s = 0 and denormalize_s = false, the return value of the `getPoint` function should be a start point of the `line`. - /// If the `denormalize_s = false`, the return value `s` of the function is normalized and in range `s = [0,1]`. - // [Snippet_getPoint_with_s_0] - EXPECT_POINT_EQ( - line.getPoint(0, false), geometry_msgs::build().x(0).y(0).z(0)); - // [Snippet_getPoint_with_s_0] - /// @snippet test/test_line_segment.cpp Snippet_getPoint_with_s_0 - - /// @note If s = 0 and denormalize_s = false, the return value of the `LineSegment::getPoint` function should be a end point of the `line`. - /// If the `denormalize_s = false`, the return value `s` of the function is normalized and in range `s = [0,1]`. - // [Snippet_getPoint_with_s_1] - EXPECT_POINT_EQ( - line.getPoint(1, false), geometry_msgs::build().x(1).y(1).z(1)); - // [Snippet_getPoint_with_s_1] - /// @snippet test/test_line_segment.cpp Snippet_getPoint_with_s_1 - - /// @note If s = sqrt(3) and denormalize_s = true, the return value of the `LineSegment::getPoint` function should be a end point of the `line`. - /// If the `denormalize_s = true`, the return value `s` is denormalized and it returns the value `s` times the length of the curve. - // [Snippet_getPoint_with_sqrt_3_denormalized] - EXPECT_POINT_EQ( - line.getPoint(std::sqrt(3), true), - geometry_msgs::build().x(1).y(1).z(1)); - // [Snippet_getPoint_with_sqrt_3_denormalized] - /// @snippet test/test_line_segment.cpp Snippet_getPoint_with_sqrt_3_denormalized - - /// @note If s is not in range s = [0,1], testing the `LineSegment::getPoint` function can throw error. If s is not in range s = [0,1], it means the point is not on the line. - // [Snippet_getPoint_out_of_range] - EXPECT_THROW(line.getPoint(2, false), common::SimulationError); - EXPECT_THROW(line.getPoint(-1, false), common::SimulationError); - // [Snippet_getPoint_out_of_range] - /// @snippet test/test_line_segment.cpp Snippet_getPoint_out_of_range - - /// @note If s is not in range s = [0,sqrt(3)] and denormalize, testing the `LineSegment::getPoint` function can throw error. If s is not in range s = [0,sqrt(3)], it means the point is not on the line. - // [Snippet_getPoint_out_of_range_with_denormalize] - EXPECT_THROW(line.getPoint(2, true), common::SimulationError); - EXPECT_THROW(line.getPoint(-1, true), common::SimulationError); - EXPECT_NO_THROW(line.getPoint(0, true)); - EXPECT_NO_THROW(line.getPoint(std::sqrt(3.0), true)); - // [Snippet_getPoint_out_of_range_with_denormalize] - /// @snippet test/test_line_segment.cpp Snippet_getPoint_out_of_range_with_denormalize - } + const auto line = + math::geometry::LineSegment(makePoint(-1.0, -2.0, 1.0), makePoint(3.0, 2.0, -1.0)); + ASSERT_DOUBLE_EQ(line.getLength(), 6.0); + + EXPECT_THROW(line.getPoint(7.0, true), common::SimulationError); + EXPECT_THROW(line.getPoint(-1.0, true), common::SimulationError); } -/// @brief In this test case, testing the `LineSegment::getPose` function can find the pose on the line segment with start point (x,y,z) = (0,0,0) and end point (x,y,z) = (0,0,1) in the cartesian coordinate system. (variable name `line`). -TEST(LineSegment, GetPose) +TEST(LineSegment, GetPoint_outOfBounds_normalized) { - { - math::geometry::LineSegment line( - geometry_msgs::build().x(0).y(0).z(0), - geometry_msgs::build().x(0).y(0).z(1)); - /// @note When the `s = 0`(1st argument of the `LineSegment::getPose` function), the return value of the `LineSegment::getPose` function should be a start point of the `line`. - /// Orientation should be defined by the direction of the `line`, so the orientation should be parallel to the z axis. - // [Snippet_getPose_with_s_0] - EXPECT_POSE_EQ( - line.getPose(0, false, false), - geometry_msgs::build() - .position(geometry_msgs::build().x(0).y(0).z(0)) - .orientation(geometry_msgs::build().x(0).y(0).z(0).w(1))); - EXPECT_POSE_EQ( - line.getPose(0, false, true), - geometry_msgs::build() - .position(geometry_msgs::build().x(0).y(0).z(0)) - .orientation(math::geometry::convertEulerAngleToQuaternion( - geometry_msgs::build().x(0).y(-M_PI * 0.5).z(0)))); - // [Snippet_getPose_with_s_0] - /// @snippet test/test_line_segment.cpp Snippet_getPose_with_s_0 - - /// @note When the `s = 1`(1st argument of the `LineSegment::getPose` function), the return value of the `LineSegment::getPose` function should be an end point of the `line`. - /// Orientation should be defined by the direction of the `line`, so the orientation should be parallel to the z axis. - // [Snippet_getPose_with_s_1] - EXPECT_POSE_EQ( - line.getPose(1, false, false), - geometry_msgs::build() - .position(geometry_msgs::build().x(0).y(0).z(1)) - .orientation(geometry_msgs::build().x(0).y(0).z(0).w(1))); - EXPECT_POSE_EQ( - line.getPose(1, false, true), - geometry_msgs::build() - .position(geometry_msgs::build().x(0).y(0).z(1)) - .orientation(math::geometry::convertEulerAngleToQuaternion( - geometry_msgs::build().x(0).y(-M_PI * 0.5).z(0)))); - // [Snippet_getPose_with_s_1] - /// @snippet test/test_line_segment.cpp Snippet_getPose_with_s_1 - } + const auto line = + math::geometry::LineSegment(makePoint(-1.0, -2.0, 1.0), makePoint(3.0, 2.0, -1.0)); + ASSERT_DOUBLE_EQ(line.getLength(), 6.0); + + EXPECT_THROW(line.getPoint(1.1, false), common::SimulationError); + EXPECT_THROW(line.getPoint(-0.1, false), common::SimulationError); +} + +TEST(LineSegment, GetPoint_inside_denormalized) +{ + const auto line = + math::geometry::LineSegment(makePoint(-1.0, -2.0, 1.0), makePoint(3.0, 2.0, -1.0)); + ASSERT_DOUBLE_EQ(line.getLength(), 6.0); + + EXPECT_POINT_EQ(line.getPoint(0.0, true), makePoint(-1.0, -2.0, 1.0)); + EXPECT_POINT_EQ(line.getPoint(3.0, true), makePoint(1.0, 0.0, 0.0)); + EXPECT_POINT_EQ(line.getPoint(6.0, true), makePoint(3.0, 2.0, -1.0)); +} + +TEST(LineSegment, GetPoint_inside_normalized) +{ + const auto line = + math::geometry::LineSegment(makePoint(-1.0, -2.0, 1.0), makePoint(3.0, 2.0, -1.0)); + ASSERT_DOUBLE_EQ(line.getLength(), 6.0); + + EXPECT_POINT_EQ(line.getPoint(0.0, false), makePoint(-1.0, -2.0, 1.0)); + EXPECT_POINT_EQ(line.getPoint(0.5, false), makePoint(1.0, 0.0, 0.0)); + EXPECT_POINT_EQ(line.getPoint(1.0, false), makePoint(3.0, 2.0, -1.0)); +} + +TEST(LineSegment, getPose_denormalized) +{ + const auto line = + math::geometry::LineSegment(makePoint(-1.0, -2.0, 0.0), makePoint(3.0, 2.0, 4.0)); + const double length = 4.0 * std::sqrt(3.0); + ASSERT_DOUBLE_EQ(line.getLength(), length); + + EXPECT_POSE_EQ( + line.getPose(0.0 * length, true, false), + makePose( + -1.0, -2.0, 0.0, + math::geometry::convertEulerAngleToQuaternion(makeVector(0.0, 0.0, M_PI_4)))); + + EXPECT_POSE_EQ( + line.getPose(0.5 * length, true, false), + makePose( + 1.0, 0.0, 2.0, math::geometry::convertEulerAngleToQuaternion(makeVector(0.0, 0.0, M_PI_4)))); + + EXPECT_POSE_EQ( + line.getPose(1.0 * length, true, false), + makePose( + 3.0, 2.0, 4.0, math::geometry::convertEulerAngleToQuaternion(makeVector(0.0, 0.0, M_PI_4)))); +} + +TEST(LineSegment, getPose_normalized) +{ + const auto line = + math::geometry::LineSegment(makePoint(-1.0, -2.0, 0.0), makePoint(3.0, 2.0, 4.0)); + const double length = 4.0 * std::sqrt(3.0); + ASSERT_DOUBLE_EQ(line.getLength(), length); + + EXPECT_POSE_EQ( + line.getPose(0.0, false, false), + makePose( + -1.0, -2.0, 0.0, + math::geometry::convertEulerAngleToQuaternion(makeVector(0.0, 0.0, M_PI_4)))); + + EXPECT_POSE_EQ( + line.getPose(0.5, false, false), + makePose( + 1.0, 0.0, 2.0, math::geometry::convertEulerAngleToQuaternion(makeVector(0.0, 0.0, M_PI_4)))); + + EXPECT_POSE_EQ( + line.getPose(1.0, false, false), + makePose( + 3.0, 2.0, 4.0, math::geometry::convertEulerAngleToQuaternion(makeVector(0.0, 0.0, M_PI_4)))); +} + +TEST(LineSegment, getPose_pitch) +{ + const auto line = math::geometry::LineSegment( + makePoint(-1.0, -2.0, 0.0 * std::sqrt(2.0)), makePoint(3.0, 2.0, 4.0 * std::sqrt(2.0))); + const double length = 8.0; + ASSERT_DOUBLE_EQ(line.getLength(), length); + + EXPECT_POSE_EQ( + line.getPose(0.0 * length, true, true), + makePose( + -1.0, -2.0, 0.0 * std::sqrt(2.0), + math::geometry::convertEulerAngleToQuaternion(makeVector(0.0, -M_PI_4, M_PI_4)))); + + EXPECT_POSE_EQ( + line.getPose(0.5 * length, true, true), + makePose( + 1.0, 0.0, 2.0 * std::sqrt(2.0), + math::geometry::convertEulerAngleToQuaternion(makeVector(0.0, -M_PI_4, M_PI_4)))); + + EXPECT_POSE_EQ( + line.getPose(1.0 * length, true, true), + makePose( + 3.0, 2.0, 4.0 * std::sqrt(2.0), + math::geometry::convertEulerAngleToQuaternion(makeVector(0.0, -M_PI_4, M_PI_4)))); } /// @brief In this test case, we check collision with the point and the line segment with start point (x,y,z) = (0,-1,0) and end point (x,y,z) = (0,1,0) in the cartesian coordinate system. (variable name `line`). From dc92033bf9ff8dc1d0d69d50d9d26e1759c8cb27 Mon Sep 17 00:00:00 2001 From: robomic Date: Mon, 5 Aug 2024 18:08:32 +0200 Subject: [PATCH 198/304] getIntersection2DSValue and isIntersect2D functions --- .../test/src/polygon/test_line_segment.cpp | 390 +++++++++++------- 1 file changed, 230 insertions(+), 160 deletions(-) diff --git a/common/math/geometry/test/src/polygon/test_line_segment.cpp b/common/math/geometry/test/src/polygon/test_line_segment.cpp index 4eac94644ab..0fcaeed94f3 100644 --- a/common/math/geometry/test/src/polygon/test_line_segment.cpp +++ b/common/math/geometry/test/src/polygon/test_line_segment.cpp @@ -443,178 +443,248 @@ TEST(LineSegment, getPose_pitch) math::geometry::convertEulerAngleToQuaternion(makeVector(0.0, -M_PI_4, M_PI_4)))); } -/// @brief In this test case, we check collision with the point and the line segment with start point (x,y,z) = (0,-1,0) and end point (x,y,z) = (0,1,0) in the cartesian coordinate system. (variable name `line`). -TEST(LineSegment, isIntersect2D) +TEST(LineSegment, isIntersect2D_pointInside) { + const auto line = + math::geometry::LineSegment(makePoint(-1.0, -2.0, 0.0), makePoint(3.0, 2.0, 4.0)); + + EXPECT_TRUE(line.isIntersect2D(makePoint(0.0, -1.0, 1.0))); + EXPECT_TRUE(line.isIntersect2D(makePoint(0.0, -1.0, 0.0))); +} + +TEST(LineSegment, isIntersect2D_pointOutside) +{ + const auto line = + math::geometry::LineSegment(makePoint(-1.0, -2.0, 0.0), makePoint(3.0, 2.0, 4.0)); + + EXPECT_FALSE(line.isIntersect2D(makePoint(-1.0, -1.0, 1.0))); + EXPECT_FALSE(line.isIntersect2D( + makePoint(0.0, std::numeric_limits::max(), std::numeric_limits::max()))); + + EXPECT_FALSE(line.isIntersect2D(makePoint(-3.0, 0.0, 0.0))); + EXPECT_FALSE(line.isIntersect2D(makePoint(4.0, 0.0, 0.0))); +} + +TEST(LineSegment, isIntersect2D_pointCollinear) +{ + const auto line = + math::geometry::LineSegment(makePoint(-1.0, -2.0, 0.0), makePoint(3.0, 2.0, 4.0)); + + EXPECT_FALSE(line.isIntersect2D(makePoint(-2.0, -3.0, -1.0))); + EXPECT_FALSE(line.isIntersect2D(makePoint(-2.0, -3.0, 0.0))); + + EXPECT_FALSE(line.isIntersect2D(makePoint(4.0, 3.0, 5.0))); + EXPECT_FALSE(line.isIntersect2D(makePoint(4.0, 3.0, 0.0))); +} + +TEST(LineSegment, isIntersect2D_pointOnEnd) +{ + const auto line = + math::geometry::LineSegment(makePoint(-1.0, -2.0, 0.0), makePoint(3.0, 2.0, 4.0)); + + EXPECT_TRUE(line.isIntersect2D(makePoint(-1.0, -2.0, 0.0))); + EXPECT_TRUE(line.isIntersect2D(makePoint(-1.0, -2.0, 7.0))); + + EXPECT_TRUE(line.isIntersect2D(makePoint(3.0, 2.0, 4.0))); + EXPECT_TRUE(line.isIntersect2D(makePoint(3.0, 2.0, -5.0))); +} + +TEST(LineSegment, getIntersection2DSValue_line_vertical) +{ + const auto line = + math::geometry::LineSegment(makePoint(-1.0, -2.0, 0.0), makePoint(-1.0, 2.0, 0.0)); { - math::geometry::LineSegment line( - geometry_msgs::build().x(0).y(-1).z(0), - geometry_msgs::build().x(0).y(1).z(0)); - /// @note Testing the `LineSegment::isIntersect2D` function can find intersection with point (0,0,0) and `line`. - // [Snippet_isIntersect2D_with_point_0_0_0] - EXPECT_TRUE( - line.isIntersect2D(geometry_msgs::build().x(0).y(0).z(0))); - // [Snippet_isIntersect2D_with_point_0_0_0] - /// @snippet test/test_line_segment.cpp Snippet_isIntersect2D_with_point_0_0_0 - - /// @note Testing the `LineSegment::isIntersect2D` function can find intersection with point (0,0,-1) - // [Snippet_isIntersect2D_with_point_0_0_-1] - EXPECT_TRUE( - line.isIntersect2D(geometry_msgs::build().x(0).y(0).z(-1))); - // [Snippet_isIntersect2D_with_point_0_0_-1] - /// @snippet test/test_line_segment.cpp Snippet_isIntersect2D_with_point_0_0_-1 - - /// @note Testing the `LineSegment::isIntersect2D` function can find intersection with point (0,1,0) and `line`. - // [Snippet_isIntersect2D_with_point_0_1_0] - EXPECT_TRUE( - line.isIntersect2D(geometry_msgs::build().x(0).y(1).z(0))); - // [Snippet_isIntersect2D_with_point_0_1_0] - /// @snippet test/test_line_segment.cpp Snippet_isIntersect2D_with_point_0_1_0 - - /// @note Testing the `LineSegment::isIntersect2D` function can find that there is no intersection with point (0,2,0) and `line`. - // [Snippet_isIntersect2D_with_point_0_2_0] - EXPECT_FALSE( - line.isIntersect2D(geometry_msgs::build().x(0).y(2).z(0))); - // [Snippet_isIntersect2D_with_point_0_2_0] - /// @snippet test/test_line_segment.cpp Snippet_isIntersect2D_with_point_0_2_0 - - /// @note Testing the `LineSegment::isIntersect2D` function can find that there is no intersection with point (0,-2,0) and `line`. - // [Snippet_isIntersect2D_with_point_0_-2_0] - EXPECT_FALSE( - line.isIntersect2D(geometry_msgs::build().x(0).y(-2).z(0))); - // [Snippet_isIntersect2D_with_point_0_-2_0] - /// @snippet test/test_line_segment.cpp Snippet_isIntersect2D_with_point_0_-2_0 + const auto s_value = line.getIntersection2DSValue( + math::geometry::LineSegment(makePoint(-2.0, -2.0, 0.0), makePoint(1.0, 1.0, 0.0)), true); + ASSERT_TRUE(s_value.has_value()); + EXPECT_DOUBLE_EQ(s_value.value(), 1.0); + } + { + const auto s_value = line.getIntersection2DSValue( + math::geometry::LineSegment(makePoint(-2.0, -2.0, 0.0), makePoint(1.0, 1.0, 0.0)), false); + ASSERT_TRUE(s_value.has_value()); + EXPECT_DOUBLE_EQ(s_value.value(), 0.25); } } -/// @brief In this test case, we check collision with the line segment with start point (x,y,z) = (0,-1,0) and end point (x,y,z) = (0,1,0) in the cartesian coordinate system. (variable name `line`). -TEST(LineSegment, get2DIntersectionSValue) +TEST(LineSegment, getIntersection2DSValue_line_horizontal) { + const auto line = + math::geometry::LineSegment(makePoint(-1.0, 2.0, 0.0), makePoint(1.0, 2.0, 0.0)); { - math::geometry::LineSegment line( - geometry_msgs::build().x(0).y(-1).z(0), - geometry_msgs::build().x(0).y(1).z(0)); - /** - * @note Testing the `LineSegment::get2DIntersectionSValue` function can find a collision with the point with (x,y,z) = (0,0,0) in the cartesian coordinate system. - * In the frenet coordinate system along the `line`, the s value should be 0.5. - * If so, the variable `collision_s` should be `std::optional(0.5)`. - */ - // [Snippet_get2DIntersectionSValue_with_point_0_0_0] - { - const auto collision_s = line.get2DIntersectionSValue( - geometry_msgs::build().x(0).y(0).z(0), false); - EXPECT_TRUE(collision_s); - if (collision_s) { - EXPECT_DOUBLE_EQ(collision_s.value(), 0.5); - } - } - // [Snippet_get2DIntersectionSValue_with_point_0_0_0] - /// @snippet test/test_line_segment.cpp Snippet_get2DIntersectionSValue_with_point_0_0_0 + const auto s_value = line.getIntersection2DSValue( + math::geometry::LineSegment(makePoint(-1.0, 0.0, 0.0), makePoint(1.0, 4.0, 0.0)), true); + ASSERT_TRUE(s_value.has_value()); + EXPECT_DOUBLE_EQ(s_value.value(), 1.0); + } + { + const auto s_value = line.getIntersection2DSValue( + math::geometry::LineSegment(makePoint(-1.0, 0.0, 0.0), makePoint(1.0, 4.0, 0.0)), false); + ASSERT_TRUE(s_value.has_value()); + EXPECT_DOUBLE_EQ(s_value.value(), 0.5); + } +} - /** - * @note Testing the `LineSegment::get2DIntersectionSValue` function can find a collision with the point with (x,y,z) = (0,1,0) in the cartesian coordinate system. - * In the frenet coordinate system along the `line`, the s value should be 1.0. - * If so, the variable `collision_s` should be `std::optional(1.0)`. - */ - // [Snippet_get2DIntersectionSValue_with_point_0_1_0] - { - const auto collision_s = line.get2DIntersectionSValue( - geometry_msgs::build().x(0).y(1).z(0), false); - EXPECT_TRUE(collision_s); - if (collision_s) { - EXPECT_DOUBLE_EQ(collision_s.value(), 1.0); - } - } - // [Snippet_get2DIntersectionSValue_with_point_0_1_0] - /// @snippet test/test_line_segment.cpp Snippet_get2DIntersectionSValue_with_point_0_1_0 +TEST(LineSegment, getIntersection2DSValue_line_bounds) +{ + const auto line = + math::geometry::LineSegment(makePoint(-1.0, 1.0, 0.0), makePoint(1.0, 3.0, 0.0)); + { + const auto s_value = line.getIntersection2DSValue( + math::geometry::LineSegment(makePoint(-2.0, 2.0, 0.0), makePoint(0.0, 0.0, 0.0)), false); + ASSERT_TRUE(s_value.has_value()); + EXPECT_DOUBLE_EQ(s_value.value(), 0.0); + } + { + const auto s_value = line.getIntersection2DSValue( + math::geometry::LineSegment(makePoint(1.0, 3.0, 0.0), makePoint(2.0, 2.0, 0.0)), false); + ASSERT_TRUE(s_value.has_value()); + EXPECT_DOUBLE_EQ(s_value.value(), 1.0); + } +} - /** - * @note Testing the `LineSegment::get2DIntersectionSValue` function can find a collision with the point with (x,y,z) = (0,1,0) in the cartesian coordinate system. - * In the frenet coordinate system along the `line`, the s value should be 1.0. - * And, the 2nd argument of the `LineSegment::get2DIntersectionSValue` (denormalized_s) is true, so the return value should be 1.0 (normalized s value.) * 2.0 (length of the `line`) = 2.0. - * If so, the variable `collision_s` should be `std::optional(2.0)`. - */ - // [Snippet_get2DIntersectionSValue_with_point_0_1_0_denormalized] - { - const auto collision_s = line.get2DIntersectionSValue( - geometry_msgs::build().x(0).y(1).z(0), true); - EXPECT_TRUE(collision_s); - if (collision_s) { - EXPECT_DOUBLE_EQ(collision_s.value(), 2.0); - } - } - // [Snippet_get2DIntersectionSValue_with_point_0_1_0_denormalized] - /// @snippet test/test_line_segment.cpp Snippet_get2DIntersectionSValue_with_point_0_1_0_denormalized +TEST(LineSegment, getIntersection2DSValue_line_outside) +{ + const auto line = + math::geometry::LineSegment(makePoint(-1.0, 1.0, 0.0), makePoint(1.0, 3.0, 0.0)); - /** - * @note Testing the `LineSegment::get2DIntersectionSValue` function can find a collision with the point with (x,y,z) = (0,0,0) in the cartesian coordinate system. - * In the frenet coordinate system along the `line`, the s value should be 0.5. - * And, the 2nd argument of the `LineSegment::get2DIntersectionSValue` (denormalized_s) is true, so the return value should be 0.5 (normalized s value.) * 2.0 (length of the `line`) = 1.0. - * If so, the variable `collision_s` should be `std::optional(1.0)`. - */ - // [Snippet_get2DIntersectionSValue_with_point_0_0_0_denormalized] - { - const auto collision_s = line.get2DIntersectionSValue( - geometry_msgs::build().x(0).y(0).z(0), true); - EXPECT_TRUE(collision_s); - if (collision_s) { - EXPECT_DOUBLE_EQ(collision_s.value(), 1.0); - } - } - // [Snippet_get2DIntersectionSValue_with_point_0_0_0_denormalized] - /// @snippet test/test_line_segment.cpp Snippet_get2DIntersectionSValue_with_point_0_0_0_denormalized + EXPECT_FALSE( + line + .getIntersection2DSValue( + math::geometry::LineSegment(makePoint(-2.0, 1.0, 0.0), makePoint(0.0, 0.0, 0.0)), false) + .has_value()); - /** - * @note Testing the `LineSegment::get2DIntersectionSValue` function can find that the point with (x,y,z) = (1,0,0) in the cartesian coordinate system does not collide to `line.`. - * If the function works valid, the variable `collision_s` should be `std::nullopt`. - */ - // [Snippet_get2DIntersectionSValue_with_point_1_0_0] - { - const auto collision_s = line.get2DIntersectionSValue( - geometry_msgs::build().x(1).y(0).z(0), false); - EXPECT_FALSE(collision_s); - } - // [Snippet_get2DIntersectionSValue_with_point_1_0_0] - /// @snippet test/test_line_segment.cpp Snippet_get2DIntersectionSValue_with_point_1_0_0 + EXPECT_FALSE( + line + .getIntersection2DSValue( + math::geometry::LineSegment(makePoint(1.0, 4.0, 0.0), makePoint(2.0, 2.0, 0.0)), false) + .has_value()); +} - { // parallel no denormalize - EXPECT_THROW( - line.get2DIntersectionSValue( - math::geometry::LineSegment(makePoint(0.0, -1.0), makePoint(0.0, 1.0)), false), - common::SimulationError); - } - { // parallel denormalize - EXPECT_THROW( - line.get2DIntersectionSValue( - math::geometry::LineSegment(makePoint(0.0, -1.0), makePoint(0.0, 1.0)), true), - common::SimulationError); - } - { // intersect no denormalize - const auto collision_s = line.get2DIntersectionSValue( - math::geometry::LineSegment(makePoint(-1.0, 0.5), makePoint(1.0, 0.5)), false); - EXPECT_TRUE(collision_s); - if (collision_s) { - EXPECT_DOUBLE_EQ(collision_s.value(), 0.75); - } - } - { // intersect denormalize - const auto collision_s = line.get2DIntersectionSValue( - math::geometry::LineSegment(makePoint(-1.0, 0.5), makePoint(1.0, 0.5)), true); - EXPECT_TRUE(collision_s); - if (collision_s) { - EXPECT_DOUBLE_EQ(collision_s.value(), 1.5); - } - } - { // no intersect no denormalize - const auto collision_s = line.get2DIntersectionSValue( - math::geometry::LineSegment(makePoint(-1.0, 1.5), makePoint(1.0, 1.5)), false); - EXPECT_FALSE(collision_s); - } - { // no intersect denormalize - const auto collision_s = line.get2DIntersectionSValue( - math::geometry::LineSegment(makePoint(-1.0, 1.5), makePoint(1.0, 1.5)), true); - EXPECT_FALSE(collision_s); - } +TEST(LineSegment, getIntersection2DSValue_line_collinear) +{ + const auto line = + math::geometry::LineSegment(makePoint(-1.0, 1.0, 0.0), makePoint(1.0, 3.0, 0.0)); + + EXPECT_THROW(line.getIntersection2DSValue(line, false), common::SimulationError); + + EXPECT_FALSE( + line + .getIntersection2DSValue( + math::geometry::LineSegment(makePoint(3.0, 5.0, 0.0), makePoint(5.0, 7.0, 0.0)), false) + .has_value()); +} + +TEST(LineSegment, getIntersection2DSValue_point_vertical) +{ + const auto line = + math::geometry::LineSegment(makePoint(-1.0, -2.0, 0.0), makePoint(-1.0, 2.0, 0.0)); + + { + const auto s_value = line.getIntersection2DSValue(makePoint(-1.0, 0.0, 0.0), true); + ASSERT_TRUE(s_value.has_value()); + EXPECT_DOUBLE_EQ(s_value.value(), 2.0); + } + { + const auto s_value = line.getIntersection2DSValue(makePoint(-1.0, 0.0, 0.0), false); + ASSERT_TRUE(s_value.has_value()); + EXPECT_DOUBLE_EQ(s_value.value(), 0.5); + } + { + EXPECT_FALSE(line.getIntersection2DSValue(makePoint(-101.0, 0.0, 0.0), true).has_value()); + EXPECT_FALSE(line.getIntersection2DSValue(makePoint(103.0, 0.0, 0.0), false).has_value()); + EXPECT_FALSE(line.getIntersection2DSValue(makePoint(-1.0, -107.0, 0.0), true).has_value()); + EXPECT_FALSE(line.getIntersection2DSValue(makePoint(-1.0, 109.0, 0.0), false).has_value()); + } +} + +TEST(LineSegment, getIntersection2DSValue_point_horizontal) +{ + const auto line = + math::geometry::LineSegment(makePoint(-1.0, 2.0, 0.0), makePoint(1.0, 2.0, 0.0)); + + { + const auto s_value = line.getIntersection2DSValue(makePoint(0.0, 2.0, 0.0), true); + ASSERT_TRUE(s_value.has_value()); + EXPECT_DOUBLE_EQ(s_value.value(), 1.0); + } + { + const auto s_value = line.getIntersection2DSValue(makePoint(0.0, 2.0, 0.0), false); + ASSERT_TRUE(s_value.has_value()); + EXPECT_DOUBLE_EQ(s_value.value(), 0.5); + } + { + EXPECT_FALSE(line.getIntersection2DSValue(makePoint(-113.0, 2.0, 0.0), true).has_value()); + EXPECT_FALSE(line.getIntersection2DSValue(makePoint(127.0, 2.0, 0.0), false).has_value()); + EXPECT_FALSE(line.getIntersection2DSValue(makePoint(0.0, -131.0, 0.0), true).has_value()); + EXPECT_FALSE(line.getIntersection2DSValue(makePoint(0.0, 137.0, 0.0), false).has_value()); + } +} + +TEST(LineSegment, getIntersection2DSValue_point_bounds) +{ + const auto line = + math::geometry::LineSegment(makePoint(-2.0, -2.0, 0.0), makePoint(1.0, 4.0, 0.0)); + + { + const auto s_value = line.getIntersection2DSValue(makePoint(-2.0, -2.0, 0.0), true); + ASSERT_TRUE(s_value.has_value()); + EXPECT_DOUBLE_EQ(s_value.value(), 0.0); + } + { + const auto s_value = line.getIntersection2DSValue(makePoint(-2.0, -2.0, 0.0), false); + ASSERT_TRUE(s_value.has_value()); + EXPECT_DOUBLE_EQ(s_value.value(), 0.0); + } + { + EXPECT_FALSE(line.getIntersection2DSValue(makePoint(-139.0, -2.0, 0.0), true).has_value()); + EXPECT_FALSE(line.getIntersection2DSValue(makePoint(149.0, -2.0, 0.0), false).has_value()); + } + + { + const auto s_value = line.getIntersection2DSValue(makePoint(1.0, 4.0, 0.0), true); + ASSERT_TRUE(s_value.has_value()); + EXPECT_DOUBLE_EQ(s_value.value(), 3.0 * std::sqrt(5)); + } + { + const auto s_value = line.getIntersection2DSValue(makePoint(1.0, 4.0, 0.0), false); + ASSERT_TRUE(s_value.has_value()); + EXPECT_DOUBLE_EQ(s_value.value(), 1.0); + } + { + EXPECT_FALSE(line.getIntersection2DSValue(makePoint(-151.0, 4.0, 0.0), true).has_value()); + EXPECT_FALSE(line.getIntersection2DSValue(makePoint(157.0, 4.0, 0.0), false).has_value()); + } +} + +TEST(LineSegment, getIntersection2DSValue_point_outside) +{ + const auto line = + math::geometry::LineSegment(makePoint(-2.0, -2.0, 0.0), makePoint(1.0, 4.0, 0.0)); + + EXPECT_FALSE(line.getIntersection2DSValue(makePoint(-3.0, 1.0, 0.0), true).has_value()); + EXPECT_FALSE(line.getIntersection2DSValue(makePoint(-1.0, 1.0, 0.0), true).has_value()); + EXPECT_FALSE(line.getIntersection2DSValue(makePoint(0.0, 1.0, 0.0), true).has_value()); + EXPECT_FALSE(line.getIntersection2DSValue(makePoint(2.0, 1.0, 0.0), true).has_value()); + + EXPECT_FALSE(line.getIntersection2DSValue(makePoint(-0.5, -5.0, 0.0), true).has_value()); + EXPECT_FALSE(line.getIntersection2DSValue(makePoint(-0.5, -1.0, 0.0), true).has_value()); + EXPECT_FALSE(line.getIntersection2DSValue(makePoint(-0.5, 3.0, 0.0), true).has_value()); + EXPECT_FALSE(line.getIntersection2DSValue(makePoint(-0.5, 7.0, 0.0), true).has_value()); + + EXPECT_FALSE(line.getIntersection2DSValue(makePoint(7.0, 7.0, 0.0), true).has_value()); + EXPECT_FALSE(line.getIntersection2DSValue(makePoint(7.0, -7.0, 0.0), true).has_value()); + EXPECT_FALSE(line.getIntersection2DSValue(makePoint(-7.0, 7.0, 0.0), true).has_value()); + EXPECT_FALSE(line.getIntersection2DSValue(makePoint(-7.0, -7.0, 0.0), true).has_value()); +} + +/// @brief In this test case, we check collision with the line segment with start point (x,y,z) = (0,-1,0) and end point (x,y,z) = (0,1,0) in the cartesian coordinate system. (variable name `line`). +TEST(LineSegment, get2DIntersectionSValue) +{ + { + math::geometry::LineSegment line( + geometry_msgs::build().x(0).y(-1).z(0), + geometry_msgs::build().x(0).y(1).z(0)); /** * @note Testing the `LineSegment::getIntersection2D` function can throw error getting intersection with exact same line segment. From c6d11cd6825d5eaeb624013b68377e809d054477 Mon Sep 17 00:00:00 2001 From: robomic Date: Tue, 6 Aug 2024 08:44:18 +0200 Subject: [PATCH 199/304] getIntersection2D function --- .../test/src/polygon/test_line_segment.cpp | 21 +++++++++++++++++++ 1 file changed, 21 insertions(+) diff --git a/common/math/geometry/test/src/polygon/test_line_segment.cpp b/common/math/geometry/test/src/polygon/test_line_segment.cpp index 0fcaeed94f3..c780402540d 100644 --- a/common/math/geometry/test/src/polygon/test_line_segment.cpp +++ b/common/math/geometry/test/src/polygon/test_line_segment.cpp @@ -97,6 +97,27 @@ TEST(LineSegment, getIntersection2DDisjoint) EXPECT_FALSE(line0.getIntersection2D(line1)); } +TEST(LineSegment, getIntersection2DIntersect) +{ + const auto line0 = math::geometry::LineSegment(makePoint(0.0, 0.0), makePoint(1.0, 1.0)); + const auto line1 = math::geometry::LineSegment(makePoint(1.0, 0.0), makePoint(0.0, 1.0)); + + const auto p0 = line0.getIntersection2D(line1); + const auto p1 = line1.getIntersection2D(line0); + + ASSERT_TRUE(p0.has_value()); + ASSERT_TRUE(p1.has_value()); + EXPECT_POINT_EQ(p0.value(), makePoint(0.5, 0.5)); + EXPECT_POINT_EQ(p1.value(), makePoint(0.5, 0.5)); +} + +TEST(LineSegment, getIntersection2DIdentical) +{ + const auto line = math::geometry::LineSegment(makePoint(0.0, 0.0), makePoint(1.0, 1.0)); + + EXPECT_THROW(line.getIntersection2D(line), common::SimulationError); +} + TEST(LineSegment, getVector) { const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(2.0, 3.0, 4.0)); From 0fbdba03b87baf9cae231576e6fe2f9ebaf8b3b4 Mon Sep 17 00:00:00 2001 From: robomic Date: Tue, 6 Aug 2024 08:51:56 +0200 Subject: [PATCH 200/304] sort tests, rm old duplicate --- .../test/src/polygon/test_line_segment.cpp | 327 +++++++++++++++--- 1 file changed, 277 insertions(+), 50 deletions(-) diff --git a/common/math/geometry/test/src/polygon/test_line_segment.cpp b/common/math/geometry/test/src/polygon/test_line_segment.cpp index c780402540d..28f3a6991fa 100644 --- a/common/math/geometry/test/src/polygon/test_line_segment.cpp +++ b/common/math/geometry/test/src/polygon/test_line_segment.cpp @@ -358,7 +358,7 @@ TEST(LineSegment, GetPoint_outOfBounds_denormalized) EXPECT_THROW(line.getPoint(-1.0, true), common::SimulationError); } -TEST(LineSegment, GetPoint_outOfBounds_normalized) +TEST(LineSegment, getPoint_outOfBounds_normalized) { const auto line = math::geometry::LineSegment(makePoint(-1.0, -2.0, 1.0), makePoint(3.0, 2.0, -1.0)); @@ -368,7 +368,7 @@ TEST(LineSegment, GetPoint_outOfBounds_normalized) EXPECT_THROW(line.getPoint(-0.1, false), common::SimulationError); } -TEST(LineSegment, GetPoint_inside_denormalized) +TEST(LineSegment, getPoint_inside_denormalized) { const auto line = math::geometry::LineSegment(makePoint(-1.0, -2.0, 1.0), makePoint(3.0, 2.0, -1.0)); @@ -379,7 +379,7 @@ TEST(LineSegment, GetPoint_inside_denormalized) EXPECT_POINT_EQ(line.getPoint(6.0, true), makePoint(3.0, 2.0, -1.0)); } -TEST(LineSegment, GetPoint_inside_normalized) +TEST(LineSegment, getPoint_inside_normalized) { const auto line = math::geometry::LineSegment(makePoint(-1.0, -2.0, 1.0), makePoint(3.0, 2.0, -1.0)); @@ -464,6 +464,26 @@ TEST(LineSegment, getPose_pitch) math::geometry::convertEulerAngleToQuaternion(makeVector(0.0, -M_PI_4, M_PI_4)))); } +TEST(LineSegment, isIntersect2DDisjoint) +{ + const math::geometry::LineSegment line0(makePoint(0.0, 0.0), makePoint(1.0, 1.0)); + const math::geometry::LineSegment line1(makePoint(1.0, 0.0), makePoint(2.0, 1.0)); + EXPECT_FALSE(line0.isIntersect2D(line1)); +} + +TEST(LineSegment, isIntersect2DIntersect) +{ + const math::geometry::LineSegment line0(makePoint(1.0, 1.0), makePoint(2.0, 1.0)); + const math::geometry::LineSegment line1(makePoint(1.0, 0.0), makeVector(1.0, 1.0), 3.0); + EXPECT_TRUE(line0.isIntersect2D(line1)); +} + +TEST(LineSegment, isIntersect2DIdentical) +{ + const math::geometry::LineSegment line(makePoint(0.0, 0.0), makePoint(1.0, 1.0)); + EXPECT_TRUE(line.isIntersect2D(line)); +} + TEST(LineSegment, isIntersect2D_pointInside) { const auto line = @@ -699,57 +719,264 @@ TEST(LineSegment, getIntersection2DSValue_point_outside) EXPECT_FALSE(line.getIntersection2DSValue(makePoint(-7.0, -7.0, 0.0), true).has_value()); } -/// @brief In this test case, we check collision with the line segment with start point (x,y,z) = (0,-1,0) and end point (x,y,z) = (0,1,0) in the cartesian coordinate system. (variable name `line`). -TEST(LineSegment, get2DIntersectionSValue) +TEST(LineSegment, getIntersection2DDisjoint) { - { - math::geometry::LineSegment line( - geometry_msgs::build().x(0).y(-1).z(0), - geometry_msgs::build().x(0).y(1).z(0)); - - /** - * @note Testing the `LineSegment::getIntersection2D` function can throw error getting intersection with exact same line segment. - * In this case, any s value can be a intersection point, so we cannot return single value. - */ - // [Snippet_getIntersection2D_with_line] - { - EXPECT_THROW(line.getIntersection2D(line), common::SimulationError); - } - // [Snippet_getIntersection2D_with_line] - /// @snippet test/test_line_segment.cpp Snippet_getIntersection2D_with_line - - /** - * @note Testing the `LineSegment::getIntersection2D` function can throw error getting intersection with part of the line segment `line`. - * In this case, any s value can be a intersection point, so we cannot return single value. - */ - // [Snippet_getIntersection2D_with_part_of_line] - { - EXPECT_THROW( - line.getIntersection2D(math::geometry::LineSegment( - geometry_msgs::build().x(0).y(-1).z(0), - geometry_msgs::build().x(0).y(0).z(0))), - common::SimulationError); - } - // [Snippet_getIntersection2D_with_part_of_line] - /// @snippet test/test_line_segment.cpp Snippet_getIntersection2D_with_part_of_line - - /// @note @note Testing the `LineSegment::getIntersection2D` function can find collision with the line segment with start point (x,y,z) = (1,0,0) and end point (x,y,z) = (-1,0,0) in the cartesian coordinate system and `line`. - // [Snippet_getIntersection2D_line_1_0_0_-1_0_0] - { - const auto point = line.getIntersection2D(math::geometry::LineSegment( - geometry_msgs::build().x(1).y(0).z(0), - geometry_msgs::build().x(-1).y(0).z(0))); - EXPECT_TRUE(point); - if (point) { - EXPECT_POINT_EQ( - point.value(), geometry_msgs::build().x(0).y(0).z(0)); - } - } - // [Snippet_getIntersection2D_line_1_0_0_-1_0_0] - /// @snippet test/test_line_segment.cpp Snippet_getIntersection2D_line_1_0_0_-1_0_0 + const math::geometry::LineSegment line0(makePoint(0.0, 0.0), makePoint(1.0, 1.0)); + const math::geometry::LineSegment line1(makePoint(1.0, 0.0), makePoint(2.0, 1.0)); + EXPECT_FALSE(line0.getIntersection2D(line1)); +} + +TEST(LineSegment, getIntersection2DIntersect) +{ + const auto line0 = math::geometry::LineSegment(makePoint(0.0, 0.0), makePoint(1.0, 1.0)); + const auto line1 = math::geometry::LineSegment(makePoint(1.0, 0.0), makePoint(0.0, 1.0)); + + const auto p0 = line0.getIntersection2D(line1); + const auto p1 = line1.getIntersection2D(line0); + + ASSERT_TRUE(p0.has_value()); + ASSERT_TRUE(p1.has_value()); + EXPECT_POINT_EQ(p0.value(), makePoint(0.5, 0.5)); + EXPECT_POINT_EQ(p1.value(), makePoint(0.5, 0.5)); +} + +TEST(LineSegment, getIntersection2DIdentical) +{ + const auto line = math::geometry::LineSegment(makePoint(0.0, 0.0), makePoint(1.0, 1.0)); + + EXPECT_THROW(line.getIntersection2D(line), common::SimulationError); +} + +TEST(LineSegment, getSValue) +{ + math::geometry::LineSegment line(makePoint(0.0, 0.0, 0.0), makePoint(3.0, 3.0, 3.0)); + const auto s = line.getSValue(makePose(2.0, 2.0, 2.0), 1.0, false); + EXPECT_TRUE(s); + if (s) { + EXPECT_DOUBLE_EQ(s.value(), 2.0 / 3.0); + } +} + +TEST(LineSegment, getSValue_denormalize) +{ + math::geometry::LineSegment line(makePoint(0.0, 0.0, 0.0), makePoint(3.0, 3.0, 3.0)); + const auto s = line.getSValue(makePose(2.0, 2.0, 2.0), 1.0, true); + EXPECT_TRUE(s); + if (s) { + EXPECT_DOUBLE_EQ(s.value(), std::hypot(2.0, 2.0, 2.0)); } } +TEST(LineSegment, getSValue_outOfRange) +{ + math::geometry::LineSegment line(makePoint(0.0, 0.0, 0.0), makePoint(3.0, 3.0, 3.0)); + const auto s = line.getSValue(makePose(4.0, 4.0, 4.0), 1.0, false); + EXPECT_FALSE(s); +} + +TEST(LineSegment, getSValue_outOfRangeDenormalize) +{ + math::geometry::LineSegment line(makePoint(0.0, 0.0, 0.0), makePoint(3.0, 3.0, 3.0)); + const auto s = line.getSValue(makePose(4.0, 4.0, 4.0), 1.0, true); + EXPECT_FALSE(s); +} + +TEST(LineSegment, getSValue_parallel) +{ + math::geometry::LineSegment line(makePoint(0.0, 0.0, 0.0), makePoint(3.0, 3.0, 0.0)); + const auto s = line.getSValue( + makePose( + 1.0, 0.0, 0.0, + math::geometry::convertEulerAngleToQuaternion(makeVector(0.0, 0.0, M_PI_4 * 3.0))), + 1000.0, false); + EXPECT_FALSE(s); +} + +TEST(LineSegment, getSValue_parallelDenormalize) +{ + math::geometry::LineSegment line(makePoint(0.0, 0.0, 0.0), makePoint(3.0, 3.0, 0.0)); + const auto s = line.getSValue( + makePose( + 1.0, 0.0, 0.0, + math::geometry::convertEulerAngleToQuaternion(makeVector(0.0, 0.0, M_PI_4 * 3.0))), + 1000.0, true); + EXPECT_FALSE(s); +} + +TEST(LineSegment, getVector) +{ + const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(2.0, 3.0, 4.0)); + EXPECT_VECTOR3_EQ(line.getVector(), makeVector(1.0, 1.0, 1.0)); +} + +TEST(LineSegment, getVectorZeroLength) +{ + const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(1.0, 2.0, 3.0)); + EXPECT_VECTOR3_EQ(line.getVector(), makeVector(0.0, 0.0, 0.0)); +} + +TEST(LineSegment, getNormalVector) +{ + const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(2.0, 3.0, 4.0)); + EXPECT_VECTOR3_EQ(line.getNormalVector(), makeVector(-1.0, 1.0, 0.0)); +} + +TEST(LineSegment, getNormalVector_zeroLength) +{ + const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(1.0, 2.0, 3.0)); + EXPECT_VECTOR3_EQ(line.getNormalVector(), makeVector(0.0, 0.0, 0.0)); +} + +TEST(LineSegment, get2DVector) +{ + const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(2.0, 3.0, 4.0)); + EXPECT_VECTOR3_EQ(line.get2DVector(), makeVector(1.0, 1.0, 0.0)); +} + +TEST(LineSegment, get2DVectorZeroLength) +{ + const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(1.0, 2.0, 3.0)); + EXPECT_VECTOR3_EQ(line.get2DVector(), makeVector(0.0, 0.0, 0.0)); +} + +TEST(LineSegment, getLength) +{ + const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(2.0, 3.0, 4.0)); + EXPECT_DOUBLE_EQ(line.getLength(), std::sqrt(3.0)); +} + +TEST(LineSegment, getLengthZeroLength) +{ + const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(1.0, 2.0, 3.0)); + EXPECT_DOUBLE_EQ(line.getLength(), 0.0); +} + +TEST(LineSegment, get2DLength) +{ + const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(2.0, 3.0, 4.0)); + EXPECT_DOUBLE_EQ(line.get2DLength(), std::sqrt(2.0)); +} + +TEST(LineSegment, get2DLengthZeroLength) +{ + const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(1.0, 2.0, 3.0)); + EXPECT_DOUBLE_EQ(line.get2DLength(), 0.0); +} + +TEST(LineSegment, getSlope) +{ + const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(3.0, 3.0, 4.0)); + EXPECT_DOUBLE_EQ(line.getSlope(), 0.5); +} + +TEST(LineSegment, getSlopeZeroLength) +{ + const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(1.0, 2.0, 3.0)); + EXPECT_TRUE(std::isnan(line.getSlope())); +} + +TEST(LineSegment, getSquaredDistanceIn2D) +{ + const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(3.0, 4.0, 5.0)); + EXPECT_DOUBLE_EQ(line.getSquaredDistanceIn2D(makePoint(0.0, 1.0, 2.0), 0.5, false), 8.0); +} + +TEST(LineSegment, getSquaredDistanceIn2D_denormalize) +{ + const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(3.0, 4.0, 5.0)); + EXPECT_DOUBLE_EQ( + line.getSquaredDistanceIn2D(makePoint(0.0, 1.0, 2.0), std::sqrt(3.0), true), 8.0); +} + +TEST(LineSegment, getSquaredDistanceVector) +{ + const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(3.0, 4.0, 5.0)); + EXPECT_VECTOR3_EQ( + line.getSquaredDistanceVector(makePoint(0.0, 1.0, 2.0), 0.5, false), + makeVector(-2.0, -2.0, -2.0)); +} + +TEST(LineSegment, getSquaredDistanceVector_denormalize) +{ + const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(3.0, 4.0, 5.0)); + EXPECT_VECTOR3_EQ( + line.getSquaredDistanceVector(makePoint(0.0, 1.0, 2.0), std::sqrt(3.0), true), + makeVector(-2.0, -2.0, -2.0)); +} + +TEST(LineSegment, getLineSegments) +{ + const std::vector points{ + makePoint(1.0, 2.0, 3.0), makePoint(2.0, 3.0, 4.0), makePoint(3.0, 4.0, 5.0), + makePoint(4.0, 5.0, 6.0)}; + const std::vector lines = + math::geometry::getLineSegments(points, false); + EXPECT_EQ(lines.size(), size_t(3)); + EXPECT_POINT_EQ(lines[0].start_point, points[0]); + EXPECT_POINT_EQ(lines[0].end_point, points[1]); + EXPECT_POINT_EQ(lines[1].start_point, points[1]); + EXPECT_POINT_EQ(lines[1].end_point, points[2]); + EXPECT_POINT_EQ(lines[2].start_point, points[2]); + EXPECT_POINT_EQ(lines[2].end_point, points[3]); +} + +TEST(LineSegment, getLineSegments_closeStartEnd) +{ + const std::vector points{ + makePoint(1.0, 2.0, 3.0), makePoint(2.0, 3.0, 4.0), makePoint(3.0, 4.0, 5.0), + makePoint(4.0, 5.0, 6.0)}; + const std::vector lines = + math::geometry::getLineSegments(points, true); + EXPECT_EQ(lines.size(), size_t(4)); + EXPECT_POINT_EQ(lines[0].start_point, points[0]); + EXPECT_POINT_EQ(lines[0].end_point, points[1]); + EXPECT_POINT_EQ(lines[1].start_point, points[1]); + EXPECT_POINT_EQ(lines[1].end_point, points[2]); + EXPECT_POINT_EQ(lines[2].start_point, points[2]); + EXPECT_POINT_EQ(lines[2].end_point, points[3]); + EXPECT_POINT_EQ(lines[3].start_point, points[3]); + EXPECT_POINT_EQ(lines[3].end_point, points[0]); +} + +TEST(LineSegment, getLineSegmentsVectorEmpty) +{ + const std::vector points; + const std::vector lines = math::geometry::getLineSegments(points); + EXPECT_EQ(lines.size(), size_t(0)); +} + +TEST(LineSegment, getLineSegmentsVectorIdentical) +{ + geometry_msgs::msg::Point point = makePoint(1.0, 2.0, 3.0); + const std::vector points{point, point, point, point}; + const std::vector lines = + math::geometry::getLineSegments(points, false); + EXPECT_EQ(lines.size(), size_t(3)); + EXPECT_POINT_EQ(lines[0].start_point, point); + EXPECT_POINT_EQ(lines[0].end_point, point); + EXPECT_POINT_EQ(lines[1].start_point, point); + EXPECT_POINT_EQ(lines[1].end_point, point); + EXPECT_POINT_EQ(lines[2].start_point, point); + EXPECT_POINT_EQ(lines[2].end_point, point); +} + +TEST(LineSegment, getLineSegmentsVectorIdentical_closeStartEnd) +{ + geometry_msgs::msg::Point point = makePoint(1.0, 2.0, 3.0); + const std::vector points{point, point, point, point}; + const std::vector lines = + math::geometry::getLineSegments(points, true); + EXPECT_EQ(lines.size(), size_t(4)); + EXPECT_POINT_EQ(lines[0].start_point, point); + EXPECT_POINT_EQ(lines[0].end_point, point); + EXPECT_POINT_EQ(lines[1].start_point, point); + EXPECT_POINT_EQ(lines[1].end_point, point); + EXPECT_POINT_EQ(lines[2].start_point, point); + EXPECT_POINT_EQ(lines[2].end_point, point); + EXPECT_POINT_EQ(lines[3].start_point, point); + EXPECT_POINT_EQ(lines[3].end_point, point); +} + int main(int argc, char ** argv) { testing::InitGoogleTest(&argc, argv); From 378b26afa7f7e7e1ebcec8fd8e4f302c8a3e6dcf Mon Sep 17 00:00:00 2001 From: robomic Date: Tue, 6 Aug 2024 08:55:25 +0200 Subject: [PATCH 201/304] tune down numbers --- common/math/geometry/test/src/polygon/test_line_segment.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/common/math/geometry/test/src/polygon/test_line_segment.cpp b/common/math/geometry/test/src/polygon/test_line_segment.cpp index 28f3a6991fa..4de7f9c7c41 100644 --- a/common/math/geometry/test/src/polygon/test_line_segment.cpp +++ b/common/math/geometry/test/src/polygon/test_line_segment.cpp @@ -499,8 +499,7 @@ TEST(LineSegment, isIntersect2D_pointOutside) math::geometry::LineSegment(makePoint(-1.0, -2.0, 0.0), makePoint(3.0, 2.0, 4.0)); EXPECT_FALSE(line.isIntersect2D(makePoint(-1.0, -1.0, 1.0))); - EXPECT_FALSE(line.isIntersect2D( - makePoint(0.0, std::numeric_limits::max(), std::numeric_limits::max()))); + EXPECT_FALSE(line.isIntersect2D(makePoint(0.0, 89.0, 97.0))); EXPECT_FALSE(line.isIntersect2D(makePoint(-3.0, 0.0, 0.0))); EXPECT_FALSE(line.isIntersect2D(makePoint(4.0, 0.0, 0.0))); From db799fbc39fbc65cb324a1fd0e221ee1ebe7ca6a Mon Sep 17 00:00:00 2001 From: robomic Date: Tue, 6 Aug 2024 09:47:57 +0200 Subject: [PATCH 202/304] quaternion operators --- .../test/src/quaternion/test_quaternion.cpp | 30 +++++++++---------- 1 file changed, 15 insertions(+), 15 deletions(-) diff --git a/common/math/geometry/test/src/quaternion/test_quaternion.cpp b/common/math/geometry/test/src/quaternion/test_quaternion.cpp index 14c7f3a82ba..0b15b1b777b 100644 --- a/common/math/geometry/test/src/quaternion/test_quaternion.cpp +++ b/common/math/geometry/test/src/quaternion/test_quaternion.cpp @@ -23,42 +23,42 @@ constexpr double EPS = 1e-6; -TEST(Quaternion, testCase1) +TEST(Quaternion, operator_addition) { using math::geometry::operator+; - auto q1 = math::geometry::makeQuaternion(0, 1, 0, 1); - auto q2 = math::geometry::makeQuaternion(0, 1, 0, 1); - auto ans = q1 + q2; + const auto q1 = math::geometry::makeQuaternion(0, 1, 0, 1); + const auto q2 = math::geometry::makeQuaternion(0, 1, 0, 1); + const auto ans = q1 + q2; EXPECT_QUATERNION_EQ(ans, math::geometry::makeQuaternion(0, 2, 0, 2)) } -TEST(Quaternion, testCase2) +TEST(Quaternion, operator_subtraction) { using math::geometry::operator-; - auto q1 = math::geometry::makeQuaternion(0, 1, 0, 1); - auto q2 = math::geometry::makeQuaternion(0, 1, 0, 1); - auto ans = q1 - q2; + const auto q1 = math::geometry::makeQuaternion(0, 1, 0, 1); + const auto q2 = math::geometry::makeQuaternion(0, 1, 0, 1); + const auto ans = q1 - q2; EXPECT_QUATERNION_EQ(ans, math::geometry::makeQuaternion(0, 0, 0, 0)) } -TEST(Quaternion, testCase3) +TEST(Quaternion, operator_multiplication) { using math::geometry::operator*; - auto q1 = math::geometry::makeQuaternion(0, 1, 0, 1); - auto q2 = math::geometry::makeQuaternion(0, 1, 0, 1); - auto ans = q1 * q2; + const auto q1 = math::geometry::makeQuaternion(0, 1, 0, 1); + const auto q2 = math::geometry::makeQuaternion(0, 1, 0, 1); + const auto ans = q1 * q2; EXPECT_QUATERNION_EQ(ans, math::geometry::makeQuaternion(0, 2, 0, 0)) } -TEST(Quaternion, testCase4) +TEST(Quaternion, operator_additionAssignment) { using math::geometry::operator+=; - auto q1 = math::geometry::makeQuaternion(0, 1, 0, 1); - auto q2 = math::geometry::makeQuaternion(0, 1, 0, 1); + const auto q1 = math::geometry::makeQuaternion(0, 1, 0, 1); + const auto q2 = math::geometry::makeQuaternion(0, 1, 0, 1); q1 += q2; EXPECT_QUATERNION_EQ(q1, math::geometry::makeQuaternion(0, 2, 0, 2)) } From 407598fc9d0a8cef5fda344f4c204a9654161f4b Mon Sep 17 00:00:00 2001 From: robomic Date: Tue, 6 Aug 2024 09:57:54 +0200 Subject: [PATCH 203/304] rename tests in CatmullRomSpline --- common/math/geometry/test/src/quaternion/test_quaternion.cpp | 2 +- .../math/geometry/test/src/spline/test_catmull_rom_spline.cpp | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/common/math/geometry/test/src/quaternion/test_quaternion.cpp b/common/math/geometry/test/src/quaternion/test_quaternion.cpp index 0b15b1b777b..d2b7aa857c8 100644 --- a/common/math/geometry/test/src/quaternion/test_quaternion.cpp +++ b/common/math/geometry/test/src/quaternion/test_quaternion.cpp @@ -57,7 +57,7 @@ TEST(Quaternion, operator_additionAssignment) { using math::geometry::operator+=; - const auto q1 = math::geometry::makeQuaternion(0, 1, 0, 1); + auto q1 = math::geometry::makeQuaternion(0, 1, 0, 1); const auto q2 = math::geometry::makeQuaternion(0, 1, 0, 1); q1 += q2; EXPECT_QUATERNION_EQ(q1, math::geometry::makeQuaternion(0, 2, 0, 2)) diff --git a/common/math/geometry/test/src/spline/test_catmull_rom_spline.cpp b/common/math/geometry/test/src/spline/test_catmull_rom_spline.cpp index b224e7d0d45..68ad3855eca 100644 --- a/common/math/geometry/test/src/spline/test_catmull_rom_spline.cpp +++ b/common/math/geometry/test/src/spline/test_catmull_rom_spline.cpp @@ -70,7 +70,7 @@ void addOffset(geometry_msgs::msg::Point & point, const double offset, const dou /// @brief Testing the `CatmullRomSpline::getCollisionPointIn2D` function works valid. /// In this test case, number of the control points of the catmull-rom spline (variable name `spline`) is 2, so the shape of the value `spline` is line segment. -TEST(CatmullRomSpline, GetCollisionWith2ControlPoints) +TEST(CatmullRomSpline, getCollisionPointIn2D_2ControlPoints) { /// @note The `spline` has control points p0 and p1. Control point p0 is point (x,y,z) = (0,0,0) and control point p1 is point (x,y,z) = (1,0,0) in the cartesian coordinate system. // [Snippet_construct_spline] @@ -149,7 +149,7 @@ TEST(CatmullRomSpline, GetCollisionWith2ControlPoints) /// @brief Testing the `CatmullRomSpline::getCollisionPointIn2D` function works valid /// In this test case, number of the control points of the catmull-rom spline (variable name `spline`) is 1, so the shape of the value `spline` is single point. -TEST(CatmullRomSpline, GetCollisionWith1ControlPoint) +TEST(CatmullRomSpline, getCollisionPointIn2D_1ControlPoint) { /// @note The variable `spline` has control point with point (x,y,z) = (0,1,0) in the cartesian coordinate system. So, `spline` is same as point (x,y,z) = (0,1,0). auto spline = math::geometry::CatmullRomSpline( From cb150e9d782e2350e5bfbea8ded993bad622f7d4 Mon Sep 17 00:00:00 2001 From: robomic Date: Tue, 6 Aug 2024 10:20:31 +0200 Subject: [PATCH 204/304] rename tests in HermiteCurve --- .../test/src/spline/test_hermite_curve.cpp | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/common/math/geometry/test/src/spline/test_hermite_curve.cpp b/common/math/geometry/test/src/spline/test_hermite_curve.cpp index 08ab6c3c4a0..833a2079322 100644 --- a/common/math/geometry/test/src/spline/test_hermite_curve.cpp +++ b/common/math/geometry/test/src/spline/test_hermite_curve.cpp @@ -503,7 +503,7 @@ TEST(HermiteCurveTest, getTangentVector4) EXPECT_DOUBLE_EQ(curve.getTangentVector(0.5, false).y / norm, 1.0 / std::sqrt(2.0)); } -TEST(HermiteCurveTest, getTangentVectorAutoscale1) +TEST(HermiteCurveTest, getTangentVectorDenormalized1) { //p(0,0) v(1,0)-> p(1,1) v(0,1) const auto curve = makeCurve1(); constexpr double eps = 0.1; @@ -513,7 +513,7 @@ TEST(HermiteCurveTest, getTangentVectorAutoscale1) EXPECT_NEAR(curve.getTangentVector(0.75, true).y / norm, 1.0 / std::sqrt(2.0), eps); } -TEST(HermiteCurveTest, getTangentVectorAutoscale2) +TEST(HermiteCurveTest, getTangentVectorDenormalized2) { //p(0,0) v(1,0)-> p(1,-1) v(0,-1) const auto curve = makeCurve2(); constexpr double eps = 0.1; @@ -523,7 +523,7 @@ TEST(HermiteCurveTest, getTangentVectorAutoscale2) EXPECT_NEAR(curve.getTangentVector(0.75, true).y / norm, -1.0 / std::sqrt(2.0), eps); } -TEST(HermiteCurveTest, getTangentVectorAutoscale3) +TEST(HermiteCurveTest, getTangentVectorDenormalized3) { //p(1,1) v(0,-1)-> p(0,0) v(-1,0) const auto curve = makeCurve3(); constexpr double eps = 0.1; @@ -533,7 +533,7 @@ TEST(HermiteCurveTest, getTangentVectorAutoscale3) EXPECT_NEAR(curve.getTangentVector(0.75, true).y / norm, -1.0 / std::sqrt(2.0), eps); } -TEST(HermiteCurveTest, getTangentVectorAutoscale4) +TEST(HermiteCurveTest, getTangentVectorDenormalized4) { //p(1,-1) v(0,1)-> p(0,0) v(-1,0) const auto curve = makeCurve4(); constexpr double eps = 0.1; @@ -579,7 +579,7 @@ TEST(HermiteCurveTest, getNormalVector4) EXPECT_DOUBLE_EQ(curve.getNormalVector(0.5, false).y / norm, -1.0 / std::sqrt(2.0)); } -TEST(HermiteCurveTest, getNormalVectorAutoscale1) +TEST(HermiteCurveTest, getNormalVectorDenormalized1) { //p(0,0) v(1,0)-> p(1,1) v(0,1) const auto curve = makeCurve1(); constexpr double eps = 0.1; @@ -589,7 +589,7 @@ TEST(HermiteCurveTest, getNormalVectorAutoscale1) EXPECT_NEAR(curve.getNormalVector(0.75, true).y / norm, 1.0 / std::sqrt(2.0), eps); } -TEST(HermiteCurveTest, getNormalVectorAutoscale2) +TEST(HermiteCurveTest, getNormalVectorDenormalized2) { //p(0,0) v(1,0)-> p(1,-1) v(0,-1) const auto curve = makeCurve2(); constexpr double eps = 0.1; @@ -599,7 +599,7 @@ TEST(HermiteCurveTest, getNormalVectorAutoscale2) EXPECT_NEAR(curve.getNormalVector(0.75, true).y / norm, 1.0 / std::sqrt(2.0), eps); } -TEST(HermiteCurveTest, getNormalVectorAutoscale3) +TEST(HermiteCurveTest, getNormalVectorDenormalized3) { //p(1,1) v(0,-1)-> p(0,0) v(-1,0) const auto curve = makeCurve3(); constexpr double eps = 0.1; @@ -609,7 +609,7 @@ TEST(HermiteCurveTest, getNormalVectorAutoscale3) EXPECT_NEAR(curve.getNormalVector(0.75, true).y / norm, -1.0 / std::sqrt(2.0), eps); } -TEST(HermiteCurveTest, getNormalVectorAutoscale4) +TEST(HermiteCurveTest, getNormalVectorDenormalized4) { //p(1,-1) v(0,1)-> p(0,0) v(-1,0) const auto curve = makeCurve4(); constexpr double eps = 0.1; From 80dea0de24a68ac8923b377c04fcc6c9d2e3603a Mon Sep 17 00:00:00 2001 From: robomic Date: Tue, 6 Aug 2024 10:28:13 +0200 Subject: [PATCH 205/304] clean up vector3 --- .../test/src/spline/test_hermite_curve.cpp | 2 +- .../test/src/vector3/test_vector3.cpp | 22 +++++++------------ 2 files changed, 9 insertions(+), 15 deletions(-) diff --git a/common/math/geometry/test/src/spline/test_hermite_curve.cpp b/common/math/geometry/test/src/spline/test_hermite_curve.cpp index 833a2079322..0ea5f153526 100644 --- a/common/math/geometry/test/src/spline/test_hermite_curve.cpp +++ b/common/math/geometry/test/src/spline/test_hermite_curve.cpp @@ -320,7 +320,7 @@ TEST(HermiteCurveTest, getSValue) EXPECT_NEAR(s2.value(), 1.0, EPS); } -TEST(HermiteCurveTest, getSValueAutoscale) +TEST(HermiteCurveTest, getSValueDenormalized) { const auto curve = makeLine2(); diff --git a/common/math/geometry/test/src/vector3/test_vector3.cpp b/common/math/geometry/test/src/vector3/test_vector3.cpp index b07cfede363..45f24c3b726 100644 --- a/common/math/geometry/test/src/vector3/test_vector3.cpp +++ b/common/math/geometry/test/src/vector3/test_vector3.cpp @@ -75,6 +75,12 @@ TEST(Vector3, normalize_msgVector) const double norm = std::sqrt(14.0); EXPECT_VECTOR3_EQ( math::geometry::normalize(vec0), makeVector(1.0 / norm, 2.0 / norm, 3.0 / norm)); + + geometry_msgs::msg::Vector3 vec1; + EXPECT_DOUBLE_EQ(math::geometry::norm(vec1), 0.0); + + geometry_msgs::msg::Vector3 vec2 = makeVector(1.0, 0.0, 3.0); + EXPECT_DOUBLE_EQ(math::geometry::norm(vec2), std::sqrt(10.0)); } TEST(Vector3, normalize_customVector) @@ -184,25 +190,13 @@ TEST(Vector3, additionAssignment_customVector) EXPECT_VECTOR3_EQ(vec0, makeVector(0.0, 0.0, 2.0)); } -TEST(Vector3, vector3_getSizeZero) -{ - geometry_msgs::msg::Vector3 vec; - EXPECT_DOUBLE_EQ(math::geometry::norm(vec), 0.0); -} - -TEST(Vector3, vector3_getSize) -{ - geometry_msgs::msg::Vector3 vec = makeVector(1.0, 0.0, 3.0); - EXPECT_DOUBLE_EQ(math::geometry::norm(vec), std::sqrt(10.0)); -} - -TEST(Vector3, vector3_normalizeZero) +TEST(Vector3, normalize_zeroLength) { geometry_msgs::msg::Vector3 vec; EXPECT_THROW(math::geometry::normalize(vec), common::SimulationError); } -TEST(Vector3, vector3_normalize) +TEST(Vector3, normalize) { geometry_msgs::msg::Vector3 vec = makeVector(1.0, 0.0, 3.0); vec = math::geometry::normalize(vec); From 7249ae68cb1031fb9ca66d0e31dc3e6c3ae0a6f2 Mon Sep 17 00:00:00 2001 From: robomic Date: Tue, 6 Aug 2024 10:29:37 +0200 Subject: [PATCH 206/304] bounding_box clean up --- common/math/geometry/test/src/test_bounding_box.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/common/math/geometry/test/src/test_bounding_box.cpp b/common/math/geometry/test/src/test_bounding_box.cpp index c6df82911d0..36abed690c3 100644 --- a/common/math/geometry/test/src/test_bounding_box.cpp +++ b/common/math/geometry/test/src/test_bounding_box.cpp @@ -46,7 +46,7 @@ TEST(BoundingBox, getPointsFromBboxCustom) EXPECT_POINT_EQ(points[3], makePoint(6.5, -2.0, 1.0)); } -TEST(BoundingBox, get2DPolygonZeroPose) +TEST(BoundingBox, toPolygon2D_zeroPose) { geometry_msgs::msg::Pose pose; traffic_simulator_msgs::msg::BoundingBox bounding_box = makeBbox(2.0, 2.0, 2.0); @@ -61,7 +61,7 @@ TEST(BoundingBox, get2DPolygonZeroPose) EXPECT_BOOST_POINT_2D_AND_POINT_EQ(poly.outer()[4], makePoint(1.0, 1.0)); } -TEST(BoundingBox, get2DPolygonOnlyTranslation) +TEST(BoundingBox, toPolygon2D_onlyTranslation) { geometry_msgs::msg::Pose pose = makePose(1.0, 2.0); traffic_simulator_msgs::msg::BoundingBox bounding_box = makeBbox(2.0, 2.0, 2.0); @@ -76,7 +76,7 @@ TEST(BoundingBox, get2DPolygonOnlyTranslation) EXPECT_BOOST_POINT_2D_AND_POINT_EQ(poly.outer()[4], makePoint(2.0, 3.0)); } -TEST(BoundingBox, get2DPolygonFullPose) +TEST(BoundingBox, toPolygon2D_fullPose) { geometry_msgs::msg::Pose pose = makePose(1.0, 2.0); pose.orientation = math::geometry::convertEulerAngleToQuaternion( From 473585ed8b9805d7b67427bc53bd2e356afd87b9 Mon Sep 17 00:00:00 2001 From: robomic Date: Tue, 6 Aug 2024 11:49:28 +0200 Subject: [PATCH 207/304] add comments --- .../test/src/polygon/test_line_segment.cpp | 346 ++++-------------- .../test/src/quaternion/test_quaternion.cpp | 12 + .../test/src/spline/test_hermite_curve.cpp | 27 ++ .../geometry/test/src/test_bounding_box.cpp | 9 + .../test/src/vector3/test_vector3.cpp | 6 + 5 files changed, 121 insertions(+), 279 deletions(-) diff --git a/common/math/geometry/test/src/polygon/test_line_segment.cpp b/common/math/geometry/test/src/polygon/test_line_segment.cpp index 4de7f9c7c41..9ab3829d121 100644 --- a/common/math/geometry/test/src/polygon/test_line_segment.cpp +++ b/common/math/geometry/test/src/polygon/test_line_segment.cpp @@ -70,285 +70,10 @@ TEST(LineSegment, initializeVectorZeroLength) EXPECT_POINT_EQ(line_segment.end_point, point); } -TEST(LineSegment, isIntersect2DDisjoint) -{ - const math::geometry::LineSegment line0(makePoint(0.0, 0.0), makePoint(1.0, 1.0)); - const math::geometry::LineSegment line1(makePoint(1.0, 0.0), makePoint(2.0, 1.0)); - EXPECT_FALSE(line0.isIntersect2D(line1)); -} - -TEST(LineSegment, isIntersect2DIntersect) -{ - const math::geometry::LineSegment line0(makePoint(1.0, 1.0), makePoint(2.0, 1.0)); - const math::geometry::LineSegment line1(makePoint(1.0, 0.0), makeVector(1.0, 1.0), 3.0); - EXPECT_TRUE(line0.isIntersect2D(line1)); -} - -TEST(LineSegment, isIntersect2DIdentical) -{ - const math::geometry::LineSegment line(makePoint(0.0, 0.0), makePoint(1.0, 1.0)); - EXPECT_TRUE(line.isIntersect2D(line)); -} - -TEST(LineSegment, getIntersection2DDisjoint) -{ - const math::geometry::LineSegment line0(makePoint(0.0, 0.0), makePoint(1.0, 1.0)); - const math::geometry::LineSegment line1(makePoint(1.0, 0.0), makePoint(2.0, 1.0)); - EXPECT_FALSE(line0.getIntersection2D(line1)); -} - -TEST(LineSegment, getIntersection2DIntersect) -{ - const auto line0 = math::geometry::LineSegment(makePoint(0.0, 0.0), makePoint(1.0, 1.0)); - const auto line1 = math::geometry::LineSegment(makePoint(1.0, 0.0), makePoint(0.0, 1.0)); - - const auto p0 = line0.getIntersection2D(line1); - const auto p1 = line1.getIntersection2D(line0); - - ASSERT_TRUE(p0.has_value()); - ASSERT_TRUE(p1.has_value()); - EXPECT_POINT_EQ(p0.value(), makePoint(0.5, 0.5)); - EXPECT_POINT_EQ(p1.value(), makePoint(0.5, 0.5)); -} - -TEST(LineSegment, getIntersection2DIdentical) -{ - const auto line = math::geometry::LineSegment(makePoint(0.0, 0.0), makePoint(1.0, 1.0)); - - EXPECT_THROW(line.getIntersection2D(line), common::SimulationError); -} - -TEST(LineSegment, getVector) -{ - const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(2.0, 3.0, 4.0)); - EXPECT_VECTOR3_EQ(line.vector, makeVector(1.0, 1.0, 1.0)); -} - -TEST(LineSegment, getVectorZeroLength) -{ - const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(1.0, 2.0, 3.0)); - EXPECT_VECTOR3_EQ(line.vector, makeVector(0.0, 0.0, 0.0)); -} - -TEST(LineSegment, getNormalVector) -{ - const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(2.0, 3.0, 4.0)); - EXPECT_VECTOR3_EQ(line.getNormalVector(), makeVector(-1.0, 1.0, 0.0)); -} - -TEST(LineSegment, getNormalVector_zeroLength) -{ - const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(1.0, 2.0, 3.0)); - EXPECT_VECTOR3_EQ(line.getNormalVector(), makeVector(0.0, 0.0, 0.0)); -} - -TEST(LineSegment, get2DVector) -{ - const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(2.0, 3.0, 4.0)); - EXPECT_VECTOR3_EQ(line.vector_2d, makeVector(1.0, 1.0, 0.0)); -} - -TEST(LineSegment, get2DVectorZeroLength) -{ - const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(1.0, 2.0, 3.0)); - EXPECT_VECTOR3_EQ(line.vector_2d, makeVector(0.0, 0.0, 0.0)); -} - -TEST(LineSegment, getLength) -{ - const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(2.0, 3.0, 4.0)); - EXPECT_DOUBLE_EQ(line.length, std::sqrt(3.0)); -} - -TEST(LineSegment, getLengthZeroLength) -{ - const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(1.0, 2.0, 3.0)); - EXPECT_DOUBLE_EQ(line.length, 0.0); -} - -TEST(LineSegment, get2DLength) -{ - const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(2.0, 3.0, 4.0)); - EXPECT_DOUBLE_EQ(line.length_2d, std::sqrt(2.0)); -} - -TEST(LineSegment, get2DLengthZeroLength) -{ - const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(1.0, 2.0, 3.0)); - EXPECT_DOUBLE_EQ(line.length_2d, 0.0); -} - -TEST(LineSegment, get2DVectorSlope) -{ - const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(3.0, 3.0, 4.0)); - EXPECT_DOUBLE_EQ(line.get2DVectorSlope(), 0.5); -} - -TEST(LineSegment, get2DVectorSlopeZeroLength) -{ - const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(1.0, 2.0, 3.0)); - EXPECT_THROW(line.get2DVectorSlope(), common::SimulationError); -} - -TEST(LineSegment, getSquaredDistanceIn2D) -{ - const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(3.0, 4.0, 5.0)); - EXPECT_DOUBLE_EQ(line.getSquaredDistanceIn2D(makePoint(0.0, 1.0, 2.0), 0.5, false), 8.0); -} - -TEST(LineSegment, getSquaredDistanceIn2D_denormalize) -{ - const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(3.0, 4.0, 5.0)); - EXPECT_DOUBLE_EQ( - line.getSquaredDistanceIn2D(makePoint(0.0, 1.0, 2.0), std::sqrt(3.0), true), 8.0); -} - -TEST(LineSegment, getSquaredDistanceVector) -{ - const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(3.0, 4.0, 5.0)); - EXPECT_VECTOR3_EQ( - line.getSquaredDistanceVector(makePoint(0.0, 1.0, 2.0), 0.5, false), - makeVector(-2.0, -2.0, -2.0)); -} - -TEST(LineSegment, getSquaredDistanceVector_denormalize) -{ - const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(3.0, 4.0, 5.0)); - EXPECT_VECTOR3_EQ( - line.getSquaredDistanceVector(makePoint(0.0, 1.0, 2.0), std::sqrt(3.0), true), - makeVector(-2.0, -2.0, -2.0)); -} - -TEST(LineSegment, getLineSegments) -{ - const std::vector points{ - makePoint(1.0, 2.0, 3.0), makePoint(2.0, 3.0, 4.0), makePoint(3.0, 4.0, 5.0), - makePoint(4.0, 5.0, 6.0)}; - const std::vector lines = - math::geometry::getLineSegments(points, false); - EXPECT_EQ(lines.size(), size_t(3)); - EXPECT_POINT_EQ(lines[0].start_point, points[0]); - EXPECT_POINT_EQ(lines[0].end_point, points[1]); - EXPECT_POINT_EQ(lines[1].start_point, points[1]); - EXPECT_POINT_EQ(lines[1].end_point, points[2]); - EXPECT_POINT_EQ(lines[2].start_point, points[2]); - EXPECT_POINT_EQ(lines[2].end_point, points[3]); -} - -TEST(LineSegment, getLineSegments_closeStartEnd) -{ - const std::vector points{ - makePoint(1.0, 2.0, 3.0), makePoint(2.0, 3.0, 4.0), makePoint(3.0, 4.0, 5.0), - makePoint(4.0, 5.0, 6.0)}; - const std::vector lines = - math::geometry::getLineSegments(points, true); - EXPECT_EQ(lines.size(), size_t(4)); - EXPECT_POINT_EQ(lines[0].start_point, points[0]); - EXPECT_POINT_EQ(lines[0].end_point, points[1]); - EXPECT_POINT_EQ(lines[1].start_point, points[1]); - EXPECT_POINT_EQ(lines[1].end_point, points[2]); - EXPECT_POINT_EQ(lines[2].start_point, points[2]); - EXPECT_POINT_EQ(lines[2].end_point, points[3]); - EXPECT_POINT_EQ(lines[3].start_point, points[3]); - EXPECT_POINT_EQ(lines[3].end_point, points[0]); -} - -TEST(LineSegment, getLineSegmentsVectorEmpty) -{ - const std::vector points; - const std::vector lines = math::geometry::getLineSegments(points); - EXPECT_EQ(lines.size(), size_t(0)); -} - -TEST(LineSegment, getLineSegmentsVectorIdentical) -{ - geometry_msgs::msg::Point point = makePoint(1.0, 2.0, 3.0); - const std::vector points{point, point, point, point}; - const std::vector lines = - math::geometry::getLineSegments(points, false); - EXPECT_EQ(lines.size(), size_t(3)); - EXPECT_POINT_EQ(lines[0].start_point, point); - EXPECT_POINT_EQ(lines[0].end_point, point); - EXPECT_POINT_EQ(lines[1].start_point, point); - EXPECT_POINT_EQ(lines[1].end_point, point); - EXPECT_POINT_EQ(lines[2].start_point, point); - EXPECT_POINT_EQ(lines[2].end_point, point); -} - -TEST(LineSegment, getLineSegmentsVectorIdentical_closeStartEnd) -{ - geometry_msgs::msg::Point point = makePoint(1.0, 2.0, 3.0); - const std::vector points{point, point, point, point}; - const std::vector lines = - math::geometry::getLineSegments(points, true); - EXPECT_EQ(lines.size(), size_t(4)); - EXPECT_POINT_EQ(lines[0].start_point, point); - EXPECT_POINT_EQ(lines[0].end_point, point); - EXPECT_POINT_EQ(lines[1].start_point, point); - EXPECT_POINT_EQ(lines[1].end_point, point); - EXPECT_POINT_EQ(lines[2].start_point, point); - EXPECT_POINT_EQ(lines[2].end_point, point); - EXPECT_POINT_EQ(lines[3].start_point, point); - EXPECT_POINT_EQ(lines[3].end_point, point); -} - -TEST(LineSegment, getSValue) -{ - math::geometry::LineSegment line(makePoint(0.0, 0.0, 0.0), makePoint(3.0, 3.0, 3.0)); - const auto s = line.getSValue(makePose(2.0, 2.0, 2.0), 1.0, false); - EXPECT_TRUE(s); - if (s) { - EXPECT_DOUBLE_EQ(s.value(), 2.0 / 3.0); - } -} - -TEST(LineSegment, getSValue_denormalize) -{ - math::geometry::LineSegment line(makePoint(0.0, 0.0, 0.0), makePoint(3.0, 3.0, 3.0)); - const auto s = line.getSValue(makePose(2.0, 2.0, 2.0), 1.0, true); - EXPECT_TRUE(s); - if (s) { - EXPECT_DOUBLE_EQ(s.value(), std::hypot(2.0, 2.0, 2.0)); - } -} - -TEST(LineSegment, getSValue_outOfRange) -{ - math::geometry::LineSegment line(makePoint(0.0, 0.0, 0.0), makePoint(3.0, 3.0, 3.0)); - const auto s = line.getSValue(makePose(4.0, 4.0, 4.0), 1.0, false); - EXPECT_FALSE(s); -} - -TEST(LineSegment, getSValue_outOfRangeDenormalize) -{ - math::geometry::LineSegment line(makePoint(0.0, 0.0, 0.0), makePoint(3.0, 3.0, 3.0)); - const auto s = line.getSValue(makePose(4.0, 4.0, 4.0), 1.0, true); - EXPECT_FALSE(s); -} - -TEST(LineSegment, getSValue_parallel) -{ - math::geometry::LineSegment line(makePoint(0.0, 0.0, 0.0), makePoint(3.0, 3.0, 0.0)); - const auto s = line.getSValue( - makePose( - 1.0, 0.0, 0.0, - math::geometry::convertEulerAngleToQuaternion(makeVector(0.0, 0.0, M_PI_4 * 3.0))), - 1000.0, false); - EXPECT_FALSE(s); -} - -TEST(LineSegment, getSValue_parallelDenormalize) -{ - math::geometry::LineSegment line(makePoint(0.0, 0.0, 0.0), makePoint(3.0, 3.0, 0.0)); - const auto s = line.getSValue( - makePose( - 1.0, 0.0, 0.0, - math::geometry::convertEulerAngleToQuaternion(makeVector(0.0, 0.0, M_PI_4 * 3.0))), - 1000.0, true); - EXPECT_FALSE(s); -} - -TEST(LineSegment, GetPoint_outOfBounds_denormalized) +/** + * @note Test error throwing when s is out of bounds. + */ +TEST(LineSegment, getPoint_outOfBounds_denormalized) { const auto line = math::geometry::LineSegment(makePoint(-1.0, -2.0, 1.0), makePoint(3.0, 2.0, -1.0)); @@ -358,6 +83,9 @@ TEST(LineSegment, GetPoint_outOfBounds_denormalized) EXPECT_THROW(line.getPoint(-1.0, true), common::SimulationError); } +/** + * @note Test error throwing when normalized s is out of bounds. + */ TEST(LineSegment, getPoint_outOfBounds_normalized) { const auto line = @@ -368,6 +96,9 @@ TEST(LineSegment, getPoint_outOfBounds_normalized) EXPECT_THROW(line.getPoint(-0.1, false), common::SimulationError); } +/** + * @note Test calculation correctness when s is out of bounds. + */ TEST(LineSegment, getPoint_inside_denormalized) { const auto line = @@ -379,6 +110,9 @@ TEST(LineSegment, getPoint_inside_denormalized) EXPECT_POINT_EQ(line.getPoint(6.0, true), makePoint(3.0, 2.0, -1.0)); } +/** + * @note Test calculation correctness when normalized s is out of bounds. + */ TEST(LineSegment, getPoint_inside_normalized) { const auto line = @@ -390,6 +124,9 @@ TEST(LineSegment, getPoint_inside_normalized) EXPECT_POINT_EQ(line.getPoint(1.0, false), makePoint(3.0, 2.0, -1.0)); } +/** + * @note Test calculation correctness with denormalized s. + */ TEST(LineSegment, getPose_denormalized) { const auto line = @@ -414,6 +151,9 @@ TEST(LineSegment, getPose_denormalized) 3.0, 2.0, 4.0, math::geometry::convertEulerAngleToQuaternion(makeVector(0.0, 0.0, M_PI_4)))); } +/** + * @note Test calculation correctness with normalized s. + */ TEST(LineSegment, getPose_normalized) { const auto line = @@ -438,6 +178,9 @@ TEST(LineSegment, getPose_normalized) 3.0, 2.0, 4.0, math::geometry::convertEulerAngleToQuaternion(makeVector(0.0, 0.0, M_PI_4)))); } +/** + * @note Test pitch calculation correctness with fill_pitch = true. + */ TEST(LineSegment, getPose_pitch) { const auto line = math::geometry::LineSegment( @@ -484,6 +227,9 @@ TEST(LineSegment, isIntersect2DIdentical) EXPECT_TRUE(line.isIntersect2D(line)); } +/** + * @note Test function behavior with a point on the line. + */ TEST(LineSegment, isIntersect2D_pointInside) { const auto line = @@ -493,6 +239,9 @@ TEST(LineSegment, isIntersect2D_pointInside) EXPECT_TRUE(line.isIntersect2D(makePoint(0.0, -1.0, 0.0))); } +/** + * @note Test function behavior with a point outside of the line. + */ TEST(LineSegment, isIntersect2D_pointOutside) { const auto line = @@ -505,6 +254,9 @@ TEST(LineSegment, isIntersect2D_pointOutside) EXPECT_FALSE(line.isIntersect2D(makePoint(4.0, 0.0, 0.0))); } +/** + * @note Test function behavior with a point that is collinear and external to the line. + */ TEST(LineSegment, isIntersect2D_pointCollinear) { const auto line = @@ -517,6 +269,9 @@ TEST(LineSegment, isIntersect2D_pointCollinear) EXPECT_FALSE(line.isIntersect2D(makePoint(4.0, 3.0, 0.0))); } +/** + * @note Test function behavior with a point on an end of the line. + */ TEST(LineSegment, isIntersect2D_pointOnEnd) { const auto line = @@ -529,6 +284,9 @@ TEST(LineSegment, isIntersect2D_pointOnEnd) EXPECT_TRUE(line.isIntersect2D(makePoint(3.0, 2.0, -5.0))); } +/** + * @note Test result correctness with a line intersecting with a vertical line. + */ TEST(LineSegment, getIntersection2DSValue_line_vertical) { const auto line = @@ -547,6 +305,9 @@ TEST(LineSegment, getIntersection2DSValue_line_vertical) } } +/** + * @note Test result correctness with a line intersecting with a horizontal line. + */ TEST(LineSegment, getIntersection2DSValue_line_horizontal) { const auto line = @@ -565,6 +326,9 @@ TEST(LineSegment, getIntersection2DSValue_line_horizontal) } } +/** + * @note Test result correctness with lines intersecting at the start and end of a line. + */ TEST(LineSegment, getIntersection2DSValue_line_bounds) { const auto line = @@ -583,6 +347,9 @@ TEST(LineSegment, getIntersection2DSValue_line_bounds) } } +/** + * @note Test result correctness with a line outside of the line. + */ TEST(LineSegment, getIntersection2DSValue_line_outside) { const auto line = @@ -601,6 +368,9 @@ TEST(LineSegment, getIntersection2DSValue_line_outside) .has_value()); } +/** + * @note Test result correctness when lines are collinear. + */ TEST(LineSegment, getIntersection2DSValue_line_collinear) { const auto line = @@ -615,6 +385,9 @@ TEST(LineSegment, getIntersection2DSValue_line_collinear) .has_value()); } +/** + * @note Test result correctness with a point inside a vertical line. + */ TEST(LineSegment, getIntersection2DSValue_point_vertical) { const auto line = @@ -638,6 +411,9 @@ TEST(LineSegment, getIntersection2DSValue_point_vertical) } } +/** + * @note Test result correctness with a point inside a horizontal line. + */ TEST(LineSegment, getIntersection2DSValue_point_horizontal) { const auto line = @@ -661,6 +437,9 @@ TEST(LineSegment, getIntersection2DSValue_point_horizontal) } } +/** + * @note Test result correctness with points at the start and end of a line. + */ TEST(LineSegment, getIntersection2DSValue_point_bounds) { const auto line = @@ -697,6 +476,9 @@ TEST(LineSegment, getIntersection2DSValue_point_bounds) } } +/** + * @note Test result correctness with a point outside of the line. + */ TEST(LineSegment, getIntersection2DSValue_point_outside) { const auto line = @@ -725,6 +507,9 @@ TEST(LineSegment, getIntersection2DDisjoint) EXPECT_FALSE(line0.getIntersection2D(line1)); } +/** + * @note Test function behavior with two intersecting lines. + */ TEST(LineSegment, getIntersection2DIntersect) { const auto line0 = math::geometry::LineSegment(makePoint(0.0, 0.0), makePoint(1.0, 1.0)); @@ -739,6 +524,9 @@ TEST(LineSegment, getIntersection2DIntersect) EXPECT_POINT_EQ(p1.value(), makePoint(0.5, 0.5)); } +/** + * @note Test function behavior with two identical lines. + */ TEST(LineSegment, getIntersection2DIdentical) { const auto line = math::geometry::LineSegment(makePoint(0.0, 0.0), makePoint(1.0, 1.0)); diff --git a/common/math/geometry/test/src/quaternion/test_quaternion.cpp b/common/math/geometry/test/src/quaternion/test_quaternion.cpp index d2b7aa857c8..0b31df60805 100644 --- a/common/math/geometry/test/src/quaternion/test_quaternion.cpp +++ b/common/math/geometry/test/src/quaternion/test_quaternion.cpp @@ -23,6 +23,9 @@ constexpr double EPS = 1e-6; +/** + * @note Test result correctness with a basic example. + */ TEST(Quaternion, operator_addition) { using math::geometry::operator+; @@ -33,6 +36,9 @@ TEST(Quaternion, operator_addition) EXPECT_QUATERNION_EQ(ans, math::geometry::makeQuaternion(0, 2, 0, 2)) } +/** + * @note Test result correctness with a basic example. + */ TEST(Quaternion, operator_subtraction) { using math::geometry::operator-; @@ -43,6 +49,9 @@ TEST(Quaternion, operator_subtraction) EXPECT_QUATERNION_EQ(ans, math::geometry::makeQuaternion(0, 0, 0, 0)) } +/** + * @note Test result correctness with a basic example. + */ TEST(Quaternion, operator_multiplication) { using math::geometry::operator*; @@ -53,6 +62,9 @@ TEST(Quaternion, operator_multiplication) EXPECT_QUATERNION_EQ(ans, math::geometry::makeQuaternion(0, 2, 0, 0)) } +/** + * @note Test result correctness with a basic example. + */ TEST(Quaternion, operator_additionAssignment) { using math::geometry::operator+=; diff --git a/common/math/geometry/test/src/spline/test_hermite_curve.cpp b/common/math/geometry/test/src/spline/test_hermite_curve.cpp index 0ea5f153526..96eb39fd2ec 100644 --- a/common/math/geometry/test/src/spline/test_hermite_curve.cpp +++ b/common/math/geometry/test/src/spline/test_hermite_curve.cpp @@ -320,6 +320,9 @@ TEST(HermiteCurveTest, getSValue) EXPECT_NEAR(s2.value(), 1.0, EPS); } +/** + * @note Test function correctness with parameter denormalize_s = true. + */ TEST(HermiteCurveTest, getSValueDenormalized) { const auto curve = makeLine2(); @@ -503,6 +506,9 @@ TEST(HermiteCurveTest, getTangentVector4) EXPECT_DOUBLE_EQ(curve.getTangentVector(0.5, false).y / norm, 1.0 / std::sqrt(2.0)); } +/** + * @note Test function correctness with parameter denormalize_s = true with different curves. + */ TEST(HermiteCurveTest, getTangentVectorDenormalized1) { //p(0,0) v(1,0)-> p(1,1) v(0,1) const auto curve = makeCurve1(); @@ -513,6 +519,9 @@ TEST(HermiteCurveTest, getTangentVectorDenormalized1) EXPECT_NEAR(curve.getTangentVector(0.75, true).y / norm, 1.0 / std::sqrt(2.0), eps); } +/** + * @note Test function correctness with parameter denormalize_s = true with different curves. + */ TEST(HermiteCurveTest, getTangentVectorDenormalized2) { //p(0,0) v(1,0)-> p(1,-1) v(0,-1) const auto curve = makeCurve2(); @@ -523,6 +532,9 @@ TEST(HermiteCurveTest, getTangentVectorDenormalized2) EXPECT_NEAR(curve.getTangentVector(0.75, true).y / norm, -1.0 / std::sqrt(2.0), eps); } +/** + * @note Test function correctness with parameter denormalize_s = true with different curves. + */ TEST(HermiteCurveTest, getTangentVectorDenormalized3) { //p(1,1) v(0,-1)-> p(0,0) v(-1,0) const auto curve = makeCurve3(); @@ -533,6 +545,9 @@ TEST(HermiteCurveTest, getTangentVectorDenormalized3) EXPECT_NEAR(curve.getTangentVector(0.75, true).y / norm, -1.0 / std::sqrt(2.0), eps); } +/** + * @note Test function correctness with parameter denormalize_s = true with different curves. + */ TEST(HermiteCurveTest, getTangentVectorDenormalized4) { //p(1,-1) v(0,1)-> p(0,0) v(-1,0) const auto curve = makeCurve4(); @@ -579,6 +594,9 @@ TEST(HermiteCurveTest, getNormalVector4) EXPECT_DOUBLE_EQ(curve.getNormalVector(0.5, false).y / norm, -1.0 / std::sqrt(2.0)); } +/** + * @note Test function correctness with parameter denormalize_s = true with different curves. + */ TEST(HermiteCurveTest, getNormalVectorDenormalized1) { //p(0,0) v(1,0)-> p(1,1) v(0,1) const auto curve = makeCurve1(); @@ -589,6 +607,9 @@ TEST(HermiteCurveTest, getNormalVectorDenormalized1) EXPECT_NEAR(curve.getNormalVector(0.75, true).y / norm, 1.0 / std::sqrt(2.0), eps); } +/** + * @note Test function correctness with parameter denormalize_s = true with different curves. + */ TEST(HermiteCurveTest, getNormalVectorDenormalized2) { //p(0,0) v(1,0)-> p(1,-1) v(0,-1) const auto curve = makeCurve2(); @@ -599,6 +620,9 @@ TEST(HermiteCurveTest, getNormalVectorDenormalized2) EXPECT_NEAR(curve.getNormalVector(0.75, true).y / norm, 1.0 / std::sqrt(2.0), eps); } +/** + * @note Test function correctness with parameter denormalize_s = true with different curves. + */ TEST(HermiteCurveTest, getNormalVectorDenormalized3) { //p(1,1) v(0,-1)-> p(0,0) v(-1,0) const auto curve = makeCurve3(); @@ -609,6 +633,9 @@ TEST(HermiteCurveTest, getNormalVectorDenormalized3) EXPECT_NEAR(curve.getNormalVector(0.75, true).y / norm, -1.0 / std::sqrt(2.0), eps); } +/** + * @note Test function correctness with parameter denormalize_s = true with different curves. + */ TEST(HermiteCurveTest, getNormalVectorDenormalized4) { //p(1,-1) v(0,1)-> p(0,0) v(-1,0) const auto curve = makeCurve4(); diff --git a/common/math/geometry/test/src/test_bounding_box.cpp b/common/math/geometry/test/src/test_bounding_box.cpp index 36abed690c3..7ee06e9cfa3 100644 --- a/common/math/geometry/test/src/test_bounding_box.cpp +++ b/common/math/geometry/test/src/test_bounding_box.cpp @@ -46,6 +46,9 @@ TEST(BoundingBox, getPointsFromBboxCustom) EXPECT_POINT_EQ(points[3], makePoint(6.5, -2.0, 1.0)); } +/** + * @note Test obtaining polygon from bounding box with no transformation applied. + */ TEST(BoundingBox, toPolygon2D_zeroPose) { geometry_msgs::msg::Pose pose; @@ -61,6 +64,9 @@ TEST(BoundingBox, toPolygon2D_zeroPose) EXPECT_BOOST_POINT_2D_AND_POINT_EQ(poly.outer()[4], makePoint(1.0, 1.0)); } +/** + * @note Test obtaining polygon from bounding box with only translation applied. + */ TEST(BoundingBox, toPolygon2D_onlyTranslation) { geometry_msgs::msg::Pose pose = makePose(1.0, 2.0); @@ -76,6 +82,9 @@ TEST(BoundingBox, toPolygon2D_onlyTranslation) EXPECT_BOOST_POINT_2D_AND_POINT_EQ(poly.outer()[4], makePoint(2.0, 3.0)); } +/** + * @note Test obtaining polygon from bounding box with full transformation applied (translation + rotation). + */ TEST(BoundingBox, toPolygon2D_fullPose) { geometry_msgs::msg::Pose pose = makePose(1.0, 2.0); diff --git a/common/math/geometry/test/src/vector3/test_vector3.cpp b/common/math/geometry/test/src/vector3/test_vector3.cpp index 45f24c3b726..c75f7177d3e 100644 --- a/common/math/geometry/test/src/vector3/test_vector3.cpp +++ b/common/math/geometry/test/src/vector3/test_vector3.cpp @@ -54,6 +54,9 @@ TEST(Vector3, hypot_customVector) EXPECT_DOUBLE_EQ(math::geometry::hypot(vec0, vec1), 6.0); } +/** + * @note Test function correctness with parameter that is ros message vector. + */ TEST(Vector3, norm_msgVector) { geometry_msgs::msg::Vector3 vec0 = makeVector(1.0, 2.0, 3.0); @@ -190,6 +193,9 @@ TEST(Vector3, additionAssignment_customVector) EXPECT_VECTOR3_EQ(vec0, makeVector(0.0, 0.0, 2.0)); } +/** + * @note Test function correctness when one of the vectors has length of 0. + */ TEST(Vector3, normalize_zeroLength) { geometry_msgs::msg::Vector3 vec; From e811a2650b7389f0235d21751b62f63805565052 Mon Sep 17 00:00:00 2001 From: robomic Date: Tue, 6 Aug 2024 14:13:19 +0200 Subject: [PATCH 208/304] refactor toPolygon2D tests --- .../geometry/test/src/test_bounding_box.cpp | 72 ++++++++++--------- 1 file changed, 37 insertions(+), 35 deletions(-) diff --git a/common/math/geometry/test/src/test_bounding_box.cpp b/common/math/geometry/test/src/test_bounding_box.cpp index 7ee06e9cfa3..b3449f994e4 100644 --- a/common/math/geometry/test/src/test_bounding_box.cpp +++ b/common/math/geometry/test/src/test_bounding_box.cpp @@ -51,17 +51,17 @@ TEST(BoundingBox, getPointsFromBboxCustom) */ TEST(BoundingBox, toPolygon2D_zeroPose) { - geometry_msgs::msg::Pose pose; - traffic_simulator_msgs::msg::BoundingBox bounding_box = makeBbox(2.0, 2.0, 2.0); - boost::geometry::model::polygon> poly = - math::geometry::toPolygon2D(pose, bounding_box); - EXPECT_EQ(poly.inners().size(), size_t(0)); - EXPECT_EQ(poly.outer().size(), size_t(5)); - EXPECT_BOOST_POINT_2D_AND_POINT_EQ(poly.outer()[0], makePoint(1.0, 1.0)); - EXPECT_BOOST_POINT_2D_AND_POINT_EQ(poly.outer()[1], makePoint(-1.0, 1.0)); - EXPECT_BOOST_POINT_2D_AND_POINT_EQ(poly.outer()[2], makePoint(-1.0, -1.0)); - EXPECT_BOOST_POINT_2D_AND_POINT_EQ(poly.outer()[3], makePoint(1.0, -1.0)); - EXPECT_BOOST_POINT_2D_AND_POINT_EQ(poly.outer()[4], makePoint(1.0, 1.0)); + const auto pose = geometry_msgs::msg::Pose(); + const auto bounding_box = makeBbox(2.0, 2.0, 2.0); + const auto polygon = math::geometry::toPolygon2D(pose, bounding_box); + + ASSERT_EQ(polygon.inners().size(), static_cast(0)); + ASSERT_EQ(polygon.outer().size(), static_cast(5)); + EXPECT_BOOST_POINT_2D_AND_POINT_EQ(polygon.outer()[0], makePoint(1.0, 1.0)); + EXPECT_BOOST_POINT_2D_AND_POINT_EQ(polygon.outer()[1], makePoint(-1.0, 1.0)); + EXPECT_BOOST_POINT_2D_AND_POINT_EQ(polygon.outer()[2], makePoint(-1.0, -1.0)); + EXPECT_BOOST_POINT_2D_AND_POINT_EQ(polygon.outer()[3], makePoint(1.0, -1.0)); + EXPECT_BOOST_POINT_2D_AND_POINT_EQ(polygon.outer()[4], makePoint(1.0, 1.0)); } /** @@ -69,17 +69,17 @@ TEST(BoundingBox, toPolygon2D_zeroPose) */ TEST(BoundingBox, toPolygon2D_onlyTranslation) { - geometry_msgs::msg::Pose pose = makePose(1.0, 2.0); - traffic_simulator_msgs::msg::BoundingBox bounding_box = makeBbox(2.0, 2.0, 2.0); - boost::geometry::model::polygon> poly = - math::geometry::toPolygon2D(pose, bounding_box); - EXPECT_EQ(poly.inners().size(), size_t(0)); - EXPECT_EQ(poly.outer().size(), size_t(5)); - EXPECT_BOOST_POINT_2D_AND_POINT_EQ(poly.outer()[0], makePoint(2.0, 3.0)); - EXPECT_BOOST_POINT_2D_AND_POINT_EQ(poly.outer()[1], makePoint(0.0, 3.0)); - EXPECT_BOOST_POINT_2D_AND_POINT_EQ(poly.outer()[2], makePoint(0.0, 1.0)); - EXPECT_BOOST_POINT_2D_AND_POINT_EQ(poly.outer()[3], makePoint(2.0, 1.0)); - EXPECT_BOOST_POINT_2D_AND_POINT_EQ(poly.outer()[4], makePoint(2.0, 3.0)); + const auto pose = makePose(1.0, 2.0); + const auto bounding_box = makeBbox(2.0, 2.0, 2.0); + const auto polygon = math::geometry::toPolygon2D(pose, bounding_box); + + ASSERT_EQ(polygon.inners().size(), static_cast(0)); + ASSERT_EQ(polygon.outer().size(), static_cast(5)); + EXPECT_BOOST_POINT_2D_AND_POINT_EQ(polygon.outer()[0], makePoint(2.0, 3.0)); + EXPECT_BOOST_POINT_2D_AND_POINT_EQ(polygon.outer()[1], makePoint(0.0, 3.0)); + EXPECT_BOOST_POINT_2D_AND_POINT_EQ(polygon.outer()[2], makePoint(0.0, 1.0)); + EXPECT_BOOST_POINT_2D_AND_POINT_EQ(polygon.outer()[3], makePoint(2.0, 1.0)); + EXPECT_BOOST_POINT_2D_AND_POINT_EQ(polygon.outer()[4], makePoint(2.0, 3.0)); } /** @@ -87,21 +87,23 @@ TEST(BoundingBox, toPolygon2D_onlyTranslation) */ TEST(BoundingBox, toPolygon2D_fullPose) { - geometry_msgs::msg::Pose pose = makePose(1.0, 2.0); - pose.orientation = math::geometry::convertEulerAngleToQuaternion( - geometry_msgs::build().x(0.0).y(0.0).z(30.0 * M_PI / 180.0)); - traffic_simulator_msgs::msg::BoundingBox bounding_box = makeBbox(2.0, 2.0, 2.0); - boost::geometry::model::polygon> poly = - math::geometry::toPolygon2D(pose, bounding_box); - EXPECT_EQ(poly.inners().size(), size_t(0)); - EXPECT_EQ(poly.outer().size(), size_t(5)); + const auto pose = makePose( + 1.0, 2.0, 0.0, + math::geometry::convertEulerAngleToQuaternion( + geometry_msgs::build().x(0.0).y(0.0).z(30.0 * M_PI / 180.0))); + + const auto bounding_box = makeBbox(2.0, 2.0, 2.0); + const auto polygon = math::geometry::toPolygon2D(pose, bounding_box); + ASSERT_EQ(polygon.inners().size(), static_cast(0)); + ASSERT_EQ(polygon.outer().size(), static_cast(5)); + const double x = std::sqrt(2.0) * std::cos((30.0 + 45.0) * M_PI / 180.0); const double y = std::sqrt(2.0) * std::sin((30.0 + 45.0) * M_PI / 180.0); - EXPECT_BOOST_POINT_2D_AND_POINT_EQ(poly.outer()[0], makePoint(x + 1.0, y + 2.0)); - EXPECT_BOOST_POINT_2D_AND_POINT_EQ(poly.outer()[1], makePoint(-y + 1.0, x + 2.0)); - EXPECT_BOOST_POINT_2D_AND_POINT_EQ(poly.outer()[2], makePoint(-x + 1.0, -y + 2.0)); - EXPECT_BOOST_POINT_2D_AND_POINT_EQ(poly.outer()[3], makePoint(y + 1.0, -x + 2.0)); - EXPECT_BOOST_POINT_2D_AND_POINT_EQ(poly.outer()[4], makePoint(x + 1.0, y + 2.0)); + EXPECT_BOOST_POINT_2D_AND_POINT_EQ(polygon.outer()[0], makePoint(x + 1.0, y + 2.0)); + EXPECT_BOOST_POINT_2D_AND_POINT_EQ(polygon.outer()[1], makePoint(-y + 1.0, x + 2.0)); + EXPECT_BOOST_POINT_2D_AND_POINT_EQ(polygon.outer()[2], makePoint(-x + 1.0, -y + 2.0)); + EXPECT_BOOST_POINT_2D_AND_POINT_EQ(polygon.outer()[3], makePoint(y + 1.0, -x + 2.0)); + EXPECT_BOOST_POINT_2D_AND_POINT_EQ(polygon.outer()[4], makePoint(x + 1.0, y + 2.0)); } TEST(BoundingBox, getPolygonDistanceWithCollision) From fbef66f40c4f06aae69217d3040369285660f931 Mon Sep 17 00:00:00 2001 From: robomic Date: Mon, 19 Aug 2024 11:52:04 +0200 Subject: [PATCH 209/304] isIntersect2D_collinear --- .../test/src/polygon/test_line_segment.cpp | 15 +++++++++++++++ 1 file changed, 15 insertions(+) diff --git a/common/math/geometry/test/src/polygon/test_line_segment.cpp b/common/math/geometry/test/src/polygon/test_line_segment.cpp index 9ab3829d121..0cddb807aa7 100644 --- a/common/math/geometry/test/src/polygon/test_line_segment.cpp +++ b/common/math/geometry/test/src/polygon/test_line_segment.cpp @@ -227,6 +227,21 @@ TEST(LineSegment, isIntersect2DIdentical) EXPECT_TRUE(line.isIntersect2D(line)); } +/** + * @note Test function behavior with two disjoint, collinear lines. + */ + +TEST(LineSegment, isIntersect2D_collinear) +{ + const auto line = + math::geometry::LineSegment(makePoint(-1.0, 1.0, 0.0), makePoint(1.0, 3.0, 0.0)); + + EXPECT_FALSE(line.isIntersect2D( + math::geometry::LineSegment(makePoint(3.0, 5.0, 0.0), makePoint(5.0, 7.0, 0.0)))); + EXPECT_FALSE(line.isIntersect2D( + math::geometry::LineSegment(makePoint(-3.0, -1.0, 0.0), makePoint(-1.0, 1.0, 0.0)))); +} + /** * @note Test function behavior with a point on the line. */ From 240ef334443a034461f9e66c5412d8161d14a93b Mon Sep 17 00:00:00 2001 From: robomic Date: Mon, 19 Aug 2024 15:16:55 +0200 Subject: [PATCH 210/304] remove empty line --- common/math/geometry/test/src/polygon/test_line_segment.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/common/math/geometry/test/src/polygon/test_line_segment.cpp b/common/math/geometry/test/src/polygon/test_line_segment.cpp index 0cddb807aa7..b6e7bec4f0a 100644 --- a/common/math/geometry/test/src/polygon/test_line_segment.cpp +++ b/common/math/geometry/test/src/polygon/test_line_segment.cpp @@ -230,7 +230,6 @@ TEST(LineSegment, isIntersect2DIdentical) /** * @note Test function behavior with two disjoint, collinear lines. */ - TEST(LineSegment, isIntersect2D_collinear) { const auto line = From f9dd0e317092363a0e693701bb39ea6d6ef07bc0 Mon Sep 17 00:00:00 2001 From: robomic Date: Mon, 19 Aug 2024 15:22:17 +0200 Subject: [PATCH 211/304] update testcase --- common/math/geometry/test/src/polygon/test_line_segment.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/common/math/geometry/test/src/polygon/test_line_segment.cpp b/common/math/geometry/test/src/polygon/test_line_segment.cpp index b6e7bec4f0a..eac5222db07 100644 --- a/common/math/geometry/test/src/polygon/test_line_segment.cpp +++ b/common/math/geometry/test/src/polygon/test_line_segment.cpp @@ -238,7 +238,7 @@ TEST(LineSegment, isIntersect2D_collinear) EXPECT_FALSE(line.isIntersect2D( math::geometry::LineSegment(makePoint(3.0, 5.0, 0.0), makePoint(5.0, 7.0, 0.0)))); EXPECT_FALSE(line.isIntersect2D( - math::geometry::LineSegment(makePoint(-3.0, -1.0, 0.0), makePoint(-1.0, 1.0, 0.0)))); + math::geometry::LineSegment(makePoint(-3.0, -1.0, 0.0), makePoint(-2.0, 0.0, 0.0)))); } /** From a954b89f3874f56eeddcce4c10c2282731e17245 Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Tue, 3 Sep 2024 17:05:52 +0900 Subject: [PATCH 212/304] Add feature to forward parameters prefixed with `autoware.` to Autoware Signed-off-by: yamacir-kit --- .../concealer/include/concealer/launch.hpp | 29 ++++++++++------ .../src/entity/ego_entity.cpp | 34 ++++++++++--------- .../launch/scenario_test_runner.launch.py | 16 +++++++++ 3 files changed, 52 insertions(+), 27 deletions(-) diff --git a/external/concealer/include/concealer/launch.hpp b/external/concealer/include/concealer/launch.hpp index 99ba2556654..54f1459f1b3 100644 --- a/external/concealer/include/concealer/launch.hpp +++ b/external/concealer/include/concealer/launch.hpp @@ -33,8 +33,9 @@ namespace concealer { -template -auto ros2_launch(const std::string & package, const std::string & file, Ts &&... xs) +template +auto ros2_launch( + const std::string & package, const std::string & file, const Parameters & parameters) { #ifdef CONCEALER_ISOLATE_STANDARD_OUTPUT const std::string log_filename = "/tmp/scenario_test_runner/autoware-output.txt"; @@ -44,17 +45,23 @@ auto ros2_launch(const std::string & package, const std::string & file, Ts &&... ::close(fd); #endif - const auto process_id = fork(); + const auto argv = [&]() { + auto argv = std::vector(); - const std::vector argv{ - "python3", - boost::algorithm::replace_all_copy(dollar("which ros2"), "\n", ""), - "launch", // NOTE: The command 'ros2' is a Python script. - package, - file, - std::forward(xs)...}; + argv.push_back("python3"); + argv.push_back(boost::algorithm::replace_all_copy(dollar("which ros2"), "\n", "")); + argv.push_back("launch"); + argv.push_back(package); + argv.push_back(file); - if (process_id < 0) { + for (const auto & parameter : parameters) { + argv.push_back(parameter); + } + + return argv; + }(); + + if (const auto process_id = fork(); process_id < 0) { throw std::system_error(errno, std::system_category()); } else if (process_id == 0 and execute(argv) < 0) { std::cout << std::system_error(errno, std::system_category()).what() << std::endl; diff --git a/simulation/traffic_simulator/src/entity/ego_entity.cpp b/simulation/traffic_simulator/src/entity/ego_entity.cpp index 6e29abdeb2d..d58f31ae94e 100644 --- a/simulation/traffic_simulator/src/entity/ego_entity.cpp +++ b/simulation/traffic_simulator/src/entity/ego_entity.cpp @@ -41,26 +41,28 @@ auto EgoEntity::makeFieldOperatorApplication( if (const auto architecture_type = getParameter(node_parameters, "architecture_type", "awf/universe"); architecture_type.find("awf/universe") != std::string::npos) { - std::string rviz_config = getParameter(node_parameters, "rviz_config", ""); + const auto rviz_config = getParameter(node_parameters, "rviz_config", ""); + + auto parameters = getParameter>(node_parameters, "autoware.", {}); + + // clang-format off + parameters.push_back("map_path:=" + configuration.map_path.string()); + parameters.push_back("lanelet2_map_file:=" + configuration.getLanelet2MapFile()); + parameters.push_back("pointcloud_map_file:=" + configuration.getPointCloudMapFile()); + parameters.push_back("sensor_model:=" + getParameter(node_parameters, "sensor_model")); + parameters.push_back("vehicle_model:=" + getParameter(node_parameters, "vehicle_model")); + parameters.push_back("rviz_config:=" + (rviz_config.empty() ? configuration.rviz_config_path.string() : rviz_config)); + parameters.push_back("scenario_simulation:=true"); + parameters.push_back("use_foa:=false"); + parameters.push_back("perception/enable_traffic_light:=" + std::string((architecture_type >= "awf/universe/20230906") ? "true" : "false")); + parameters.push_back("use_sim_time:=" + std::string(getParameter(node_parameters, "use_sim_time", false) ? "true" : "false")); + // clang-format on + return getParameter(node_parameters, "launch_autoware", true) ? std::make_unique< concealer::FieldOperatorApplicationFor>( getParameter(node_parameters, "autoware_launch_package"), - getParameter(node_parameters, "autoware_launch_file"), - "map_path:=" + configuration.map_path.string(), - "lanelet2_map_file:=" + configuration.getLanelet2MapFile(), - "pointcloud_map_file:=" + configuration.getPointCloudMapFile(), - "sensor_model:=" + getParameter(node_parameters, "sensor_model"), - "vehicle_model:=" + getParameter(node_parameters, "vehicle_model"), - "rviz_config:=" + ((rviz_config == "") - ? configuration.rviz_config_path.string() - : Configuration::Pathname(rviz_config).string()), - "scenario_simulation:=true", "use_foa:=false", - "perception/enable_traffic_light:=" + - std::string((architecture_type >= "awf/universe/20230906") ? "true" : "false"), - "use_sim_time:=" + - std::string( - getParameter(node_parameters, "use_sim_time", false) ? "true" : "false")) + getParameter(node_parameters, "autoware_launch_file"), parameters) : std::make_unique< concealer::FieldOperatorApplicationFor>(); } else { diff --git a/test_runner/scenario_test_runner/launch/scenario_test_runner.launch.py b/test_runner/scenario_test_runner/launch/scenario_test_runner.launch.py index 33c5161e927..edcda777f00 100755 --- a/test_runner/scenario_test_runner/launch/scenario_test_runner.launch.py +++ b/test_runner/scenario_test_runner/launch/scenario_test_runner.launch.py @@ -31,6 +31,8 @@ from scenario_test_runner.shutdown_once import ShutdownOnce +import re + def architecture_types(): return ["awf/universe", "awf/universe/20230906"] @@ -131,7 +133,21 @@ def make_parameters(): {"sigterm_timeout": sigterm_timeout}, {"vehicle_model": vehicle_model}, ] + parameters += make_vehicle_parameters() + + list_of_string = [] + + pattern = re.compile("[Aa]utoware\..*") + + for each in context.launch_configurations.items(): + if (pattern.match(each[0])): + list_of_string.append(each[0][9:] + ":=" + each[1]) + + parameters += [ + {"autoware.": list_of_string} + ] + return parameters def make_vehicle_parameters(): From 9b180d2ee4cbb6df4c0dbab91153b819f7f3d885 Mon Sep 17 00:00:00 2001 From: robomic Date: Tue, 3 Sep 2024 10:51:07 +0200 Subject: [PATCH 213/304] updates after merge --- .../test/src/polygon/test_line_segment.cpp | 140 +++++++++--------- 1 file changed, 70 insertions(+), 70 deletions(-) diff --git a/common/math/geometry/test/src/polygon/test_line_segment.cpp b/common/math/geometry/test/src/polygon/test_line_segment.cpp index eac5222db07..354e9d71584 100644 --- a/common/math/geometry/test/src/polygon/test_line_segment.cpp +++ b/common/math/geometry/test/src/polygon/test_line_segment.cpp @@ -77,7 +77,7 @@ TEST(LineSegment, getPoint_outOfBounds_denormalized) { const auto line = math::geometry::LineSegment(makePoint(-1.0, -2.0, 1.0), makePoint(3.0, 2.0, -1.0)); - ASSERT_DOUBLE_EQ(line.getLength(), 6.0); + ASSERT_DOUBLE_EQ(line.length, 6.0); EXPECT_THROW(line.getPoint(7.0, true), common::SimulationError); EXPECT_THROW(line.getPoint(-1.0, true), common::SimulationError); @@ -90,7 +90,7 @@ TEST(LineSegment, getPoint_outOfBounds_normalized) { const auto line = math::geometry::LineSegment(makePoint(-1.0, -2.0, 1.0), makePoint(3.0, 2.0, -1.0)); - ASSERT_DOUBLE_EQ(line.getLength(), 6.0); + ASSERT_DOUBLE_EQ(line.length, 6.0); EXPECT_THROW(line.getPoint(1.1, false), common::SimulationError); EXPECT_THROW(line.getPoint(-0.1, false), common::SimulationError); @@ -103,7 +103,7 @@ TEST(LineSegment, getPoint_inside_denormalized) { const auto line = math::geometry::LineSegment(makePoint(-1.0, -2.0, 1.0), makePoint(3.0, 2.0, -1.0)); - ASSERT_DOUBLE_EQ(line.getLength(), 6.0); + ASSERT_DOUBLE_EQ(line.length, 6.0); EXPECT_POINT_EQ(line.getPoint(0.0, true), makePoint(-1.0, -2.0, 1.0)); EXPECT_POINT_EQ(line.getPoint(3.0, true), makePoint(1.0, 0.0, 0.0)); @@ -117,7 +117,7 @@ TEST(LineSegment, getPoint_inside_normalized) { const auto line = math::geometry::LineSegment(makePoint(-1.0, -2.0, 1.0), makePoint(3.0, 2.0, -1.0)); - ASSERT_DOUBLE_EQ(line.getLength(), 6.0); + ASSERT_DOUBLE_EQ(line.length, 6.0); EXPECT_POINT_EQ(line.getPoint(0.0, false), makePoint(-1.0, -2.0, 1.0)); EXPECT_POINT_EQ(line.getPoint(0.5, false), makePoint(1.0, 0.0, 0.0)); @@ -132,7 +132,7 @@ TEST(LineSegment, getPose_denormalized) const auto line = math::geometry::LineSegment(makePoint(-1.0, -2.0, 0.0), makePoint(3.0, 2.0, 4.0)); const double length = 4.0 * std::sqrt(3.0); - ASSERT_DOUBLE_EQ(line.getLength(), length); + ASSERT_DOUBLE_EQ(line.length, length); EXPECT_POSE_EQ( line.getPose(0.0 * length, true, false), @@ -159,7 +159,7 @@ TEST(LineSegment, getPose_normalized) const auto line = math::geometry::LineSegment(makePoint(-1.0, -2.0, 0.0), makePoint(3.0, 2.0, 4.0)); const double length = 4.0 * std::sqrt(3.0); - ASSERT_DOUBLE_EQ(line.getLength(), length); + ASSERT_DOUBLE_EQ(line.length, length); EXPECT_POSE_EQ( line.getPose(0.0, false, false), @@ -186,7 +186,7 @@ TEST(LineSegment, getPose_pitch) const auto line = math::geometry::LineSegment( makePoint(-1.0, -2.0, 0.0 * std::sqrt(2.0)), makePoint(3.0, 2.0, 4.0 * std::sqrt(2.0))); const double length = 8.0; - ASSERT_DOUBLE_EQ(line.getLength(), length); + ASSERT_DOUBLE_EQ(line.length, length); EXPECT_POSE_EQ( line.getPose(0.0 * length, true, true), @@ -301,18 +301,18 @@ TEST(LineSegment, isIntersect2D_pointOnEnd) /** * @note Test result correctness with a line intersecting with a vertical line. */ -TEST(LineSegment, getIntersection2DSValue_line_vertical) +TEST(LineSegment, get2DIntersectionSValue_line_vertical) { const auto line = math::geometry::LineSegment(makePoint(-1.0, -2.0, 0.0), makePoint(-1.0, 2.0, 0.0)); { - const auto s_value = line.getIntersection2DSValue( + const auto s_value = line.get2DIntersectionSValue( math::geometry::LineSegment(makePoint(-2.0, -2.0, 0.0), makePoint(1.0, 1.0, 0.0)), true); ASSERT_TRUE(s_value.has_value()); EXPECT_DOUBLE_EQ(s_value.value(), 1.0); } { - const auto s_value = line.getIntersection2DSValue( + const auto s_value = line.get2DIntersectionSValue( math::geometry::LineSegment(makePoint(-2.0, -2.0, 0.0), makePoint(1.0, 1.0, 0.0)), false); ASSERT_TRUE(s_value.has_value()); EXPECT_DOUBLE_EQ(s_value.value(), 0.25); @@ -322,18 +322,18 @@ TEST(LineSegment, getIntersection2DSValue_line_vertical) /** * @note Test result correctness with a line intersecting with a horizontal line. */ -TEST(LineSegment, getIntersection2DSValue_line_horizontal) +TEST(LineSegment, get2DIntersectionSValue_line_horizontal) { const auto line = math::geometry::LineSegment(makePoint(-1.0, 2.0, 0.0), makePoint(1.0, 2.0, 0.0)); { - const auto s_value = line.getIntersection2DSValue( + const auto s_value = line.get2DIntersectionSValue( math::geometry::LineSegment(makePoint(-1.0, 0.0, 0.0), makePoint(1.0, 4.0, 0.0)), true); ASSERT_TRUE(s_value.has_value()); EXPECT_DOUBLE_EQ(s_value.value(), 1.0); } { - const auto s_value = line.getIntersection2DSValue( + const auto s_value = line.get2DIntersectionSValue( math::geometry::LineSegment(makePoint(-1.0, 0.0, 0.0), makePoint(1.0, 4.0, 0.0)), false); ASSERT_TRUE(s_value.has_value()); EXPECT_DOUBLE_EQ(s_value.value(), 0.5); @@ -343,18 +343,18 @@ TEST(LineSegment, getIntersection2DSValue_line_horizontal) /** * @note Test result correctness with lines intersecting at the start and end of a line. */ -TEST(LineSegment, getIntersection2DSValue_line_bounds) +TEST(LineSegment, get2DIntersectionSValue_line_bounds) { const auto line = math::geometry::LineSegment(makePoint(-1.0, 1.0, 0.0), makePoint(1.0, 3.0, 0.0)); { - const auto s_value = line.getIntersection2DSValue( + const auto s_value = line.get2DIntersectionSValue( math::geometry::LineSegment(makePoint(-2.0, 2.0, 0.0), makePoint(0.0, 0.0, 0.0)), false); ASSERT_TRUE(s_value.has_value()); EXPECT_DOUBLE_EQ(s_value.value(), 0.0); } { - const auto s_value = line.getIntersection2DSValue( + const auto s_value = line.get2DIntersectionSValue( math::geometry::LineSegment(makePoint(1.0, 3.0, 0.0), makePoint(2.0, 2.0, 0.0)), false); ASSERT_TRUE(s_value.has_value()); EXPECT_DOUBLE_EQ(s_value.value(), 1.0); @@ -364,20 +364,20 @@ TEST(LineSegment, getIntersection2DSValue_line_bounds) /** * @note Test result correctness with a line outside of the line. */ -TEST(LineSegment, getIntersection2DSValue_line_outside) +TEST(LineSegment, get2DIntersectionSValue_line_outside) { const auto line = math::geometry::LineSegment(makePoint(-1.0, 1.0, 0.0), makePoint(1.0, 3.0, 0.0)); EXPECT_FALSE( line - .getIntersection2DSValue( + .get2DIntersectionSValue( math::geometry::LineSegment(makePoint(-2.0, 1.0, 0.0), makePoint(0.0, 0.0, 0.0)), false) .has_value()); EXPECT_FALSE( line - .getIntersection2DSValue( + .get2DIntersectionSValue( math::geometry::LineSegment(makePoint(1.0, 4.0, 0.0), makePoint(2.0, 2.0, 0.0)), false) .has_value()); } @@ -385,16 +385,16 @@ TEST(LineSegment, getIntersection2DSValue_line_outside) /** * @note Test result correctness when lines are collinear. */ -TEST(LineSegment, getIntersection2DSValue_line_collinear) +TEST(LineSegment, get2DIntersectionSValue_line_collinear) { const auto line = math::geometry::LineSegment(makePoint(-1.0, 1.0, 0.0), makePoint(1.0, 3.0, 0.0)); - EXPECT_THROW(line.getIntersection2DSValue(line, false), common::SimulationError); + EXPECT_THROW(line.get2DIntersectionSValue(line, false), common::SimulationError); EXPECT_FALSE( line - .getIntersection2DSValue( + .get2DIntersectionSValue( math::geometry::LineSegment(makePoint(3.0, 5.0, 0.0), makePoint(5.0, 7.0, 0.0)), false) .has_value()); } @@ -402,116 +402,116 @@ TEST(LineSegment, getIntersection2DSValue_line_collinear) /** * @note Test result correctness with a point inside a vertical line. */ -TEST(LineSegment, getIntersection2DSValue_point_vertical) +TEST(LineSegment, get2DIntersectionSValue_point_vertical) { const auto line = math::geometry::LineSegment(makePoint(-1.0, -2.0, 0.0), makePoint(-1.0, 2.0, 0.0)); { - const auto s_value = line.getIntersection2DSValue(makePoint(-1.0, 0.0, 0.0), true); + const auto s_value = line.get2DIntersectionSValue(makePoint(-1.0, 0.0, 0.0), true); ASSERT_TRUE(s_value.has_value()); EXPECT_DOUBLE_EQ(s_value.value(), 2.0); } { - const auto s_value = line.getIntersection2DSValue(makePoint(-1.0, 0.0, 0.0), false); + const auto s_value = line.get2DIntersectionSValue(makePoint(-1.0, 0.0, 0.0), false); ASSERT_TRUE(s_value.has_value()); EXPECT_DOUBLE_EQ(s_value.value(), 0.5); } { - EXPECT_FALSE(line.getIntersection2DSValue(makePoint(-101.0, 0.0, 0.0), true).has_value()); - EXPECT_FALSE(line.getIntersection2DSValue(makePoint(103.0, 0.0, 0.0), false).has_value()); - EXPECT_FALSE(line.getIntersection2DSValue(makePoint(-1.0, -107.0, 0.0), true).has_value()); - EXPECT_FALSE(line.getIntersection2DSValue(makePoint(-1.0, 109.0, 0.0), false).has_value()); + EXPECT_FALSE(line.get2DIntersectionSValue(makePoint(-101.0, 0.0, 0.0), true).has_value()); + EXPECT_FALSE(line.get2DIntersectionSValue(makePoint(103.0, 0.0, 0.0), false).has_value()); + EXPECT_FALSE(line.get2DIntersectionSValue(makePoint(-1.0, -107.0, 0.0), true).has_value()); + EXPECT_FALSE(line.get2DIntersectionSValue(makePoint(-1.0, 109.0, 0.0), false).has_value()); } } /** * @note Test result correctness with a point inside a horizontal line. */ -TEST(LineSegment, getIntersection2DSValue_point_horizontal) +TEST(LineSegment, get2DIntersectionSValue_point_horizontal) { const auto line = math::geometry::LineSegment(makePoint(-1.0, 2.0, 0.0), makePoint(1.0, 2.0, 0.0)); { - const auto s_value = line.getIntersection2DSValue(makePoint(0.0, 2.0, 0.0), true); + const auto s_value = line.get2DIntersectionSValue(makePoint(0.0, 2.0, 0.0), true); ASSERT_TRUE(s_value.has_value()); EXPECT_DOUBLE_EQ(s_value.value(), 1.0); } { - const auto s_value = line.getIntersection2DSValue(makePoint(0.0, 2.0, 0.0), false); + const auto s_value = line.get2DIntersectionSValue(makePoint(0.0, 2.0, 0.0), false); ASSERT_TRUE(s_value.has_value()); EXPECT_DOUBLE_EQ(s_value.value(), 0.5); } { - EXPECT_FALSE(line.getIntersection2DSValue(makePoint(-113.0, 2.0, 0.0), true).has_value()); - EXPECT_FALSE(line.getIntersection2DSValue(makePoint(127.0, 2.0, 0.0), false).has_value()); - EXPECT_FALSE(line.getIntersection2DSValue(makePoint(0.0, -131.0, 0.0), true).has_value()); - EXPECT_FALSE(line.getIntersection2DSValue(makePoint(0.0, 137.0, 0.0), false).has_value()); + EXPECT_FALSE(line.get2DIntersectionSValue(makePoint(-113.0, 2.0, 0.0), true).has_value()); + EXPECT_FALSE(line.get2DIntersectionSValue(makePoint(127.0, 2.0, 0.0), false).has_value()); + EXPECT_FALSE(line.get2DIntersectionSValue(makePoint(0.0, -131.0, 0.0), true).has_value()); + EXPECT_FALSE(line.get2DIntersectionSValue(makePoint(0.0, 137.0, 0.0), false).has_value()); } } /** * @note Test result correctness with points at the start and end of a line. */ -TEST(LineSegment, getIntersection2DSValue_point_bounds) +TEST(LineSegment, get2DIntersectionSValue_point_bounds) { const auto line = math::geometry::LineSegment(makePoint(-2.0, -2.0, 0.0), makePoint(1.0, 4.0, 0.0)); { - const auto s_value = line.getIntersection2DSValue(makePoint(-2.0, -2.0, 0.0), true); + const auto s_value = line.get2DIntersectionSValue(makePoint(-2.0, -2.0, 0.0), true); ASSERT_TRUE(s_value.has_value()); EXPECT_DOUBLE_EQ(s_value.value(), 0.0); } { - const auto s_value = line.getIntersection2DSValue(makePoint(-2.0, -2.0, 0.0), false); + const auto s_value = line.get2DIntersectionSValue(makePoint(-2.0, -2.0, 0.0), false); ASSERT_TRUE(s_value.has_value()); EXPECT_DOUBLE_EQ(s_value.value(), 0.0); } { - EXPECT_FALSE(line.getIntersection2DSValue(makePoint(-139.0, -2.0, 0.0), true).has_value()); - EXPECT_FALSE(line.getIntersection2DSValue(makePoint(149.0, -2.0, 0.0), false).has_value()); + EXPECT_FALSE(line.get2DIntersectionSValue(makePoint(-139.0, -2.0, 0.0), true).has_value()); + EXPECT_FALSE(line.get2DIntersectionSValue(makePoint(149.0, -2.0, 0.0), false).has_value()); } { - const auto s_value = line.getIntersection2DSValue(makePoint(1.0, 4.0, 0.0), true); + const auto s_value = line.get2DIntersectionSValue(makePoint(1.0, 4.0, 0.0), true); ASSERT_TRUE(s_value.has_value()); EXPECT_DOUBLE_EQ(s_value.value(), 3.0 * std::sqrt(5)); } { - const auto s_value = line.getIntersection2DSValue(makePoint(1.0, 4.0, 0.0), false); + const auto s_value = line.get2DIntersectionSValue(makePoint(1.0, 4.0, 0.0), false); ASSERT_TRUE(s_value.has_value()); EXPECT_DOUBLE_EQ(s_value.value(), 1.0); } { - EXPECT_FALSE(line.getIntersection2DSValue(makePoint(-151.0, 4.0, 0.0), true).has_value()); - EXPECT_FALSE(line.getIntersection2DSValue(makePoint(157.0, 4.0, 0.0), false).has_value()); + EXPECT_FALSE(line.get2DIntersectionSValue(makePoint(-151.0, 4.0, 0.0), true).has_value()); + EXPECT_FALSE(line.get2DIntersectionSValue(makePoint(157.0, 4.0, 0.0), false).has_value()); } } /** * @note Test result correctness with a point outside of the line. */ -TEST(LineSegment, getIntersection2DSValue_point_outside) +TEST(LineSegment, get2DIntersectionSValue_point_outside) { const auto line = math::geometry::LineSegment(makePoint(-2.0, -2.0, 0.0), makePoint(1.0, 4.0, 0.0)); - EXPECT_FALSE(line.getIntersection2DSValue(makePoint(-3.0, 1.0, 0.0), true).has_value()); - EXPECT_FALSE(line.getIntersection2DSValue(makePoint(-1.0, 1.0, 0.0), true).has_value()); - EXPECT_FALSE(line.getIntersection2DSValue(makePoint(0.0, 1.0, 0.0), true).has_value()); - EXPECT_FALSE(line.getIntersection2DSValue(makePoint(2.0, 1.0, 0.0), true).has_value()); + EXPECT_FALSE(line.get2DIntersectionSValue(makePoint(-3.0, 1.0, 0.0), true).has_value()); + EXPECT_FALSE(line.get2DIntersectionSValue(makePoint(-1.0, 1.0, 0.0), true).has_value()); + EXPECT_FALSE(line.get2DIntersectionSValue(makePoint(0.0, 1.0, 0.0), true).has_value()); + EXPECT_FALSE(line.get2DIntersectionSValue(makePoint(2.0, 1.0, 0.0), true).has_value()); - EXPECT_FALSE(line.getIntersection2DSValue(makePoint(-0.5, -5.0, 0.0), true).has_value()); - EXPECT_FALSE(line.getIntersection2DSValue(makePoint(-0.5, -1.0, 0.0), true).has_value()); - EXPECT_FALSE(line.getIntersection2DSValue(makePoint(-0.5, 3.0, 0.0), true).has_value()); - EXPECT_FALSE(line.getIntersection2DSValue(makePoint(-0.5, 7.0, 0.0), true).has_value()); + EXPECT_FALSE(line.get2DIntersectionSValue(makePoint(-0.5, -5.0, 0.0), true).has_value()); + EXPECT_FALSE(line.get2DIntersectionSValue(makePoint(-0.5, -1.0, 0.0), true).has_value()); + EXPECT_FALSE(line.get2DIntersectionSValue(makePoint(-0.5, 3.0, 0.0), true).has_value()); + EXPECT_FALSE(line.get2DIntersectionSValue(makePoint(-0.5, 7.0, 0.0), true).has_value()); - EXPECT_FALSE(line.getIntersection2DSValue(makePoint(7.0, 7.0, 0.0), true).has_value()); - EXPECT_FALSE(line.getIntersection2DSValue(makePoint(7.0, -7.0, 0.0), true).has_value()); - EXPECT_FALSE(line.getIntersection2DSValue(makePoint(-7.0, 7.0, 0.0), true).has_value()); - EXPECT_FALSE(line.getIntersection2DSValue(makePoint(-7.0, -7.0, 0.0), true).has_value()); + EXPECT_FALSE(line.get2DIntersectionSValue(makePoint(7.0, 7.0, 0.0), true).has_value()); + EXPECT_FALSE(line.get2DIntersectionSValue(makePoint(7.0, -7.0, 0.0), true).has_value()); + EXPECT_FALSE(line.get2DIntersectionSValue(makePoint(-7.0, 7.0, 0.0), true).has_value()); + EXPECT_FALSE(line.get2DIntersectionSValue(makePoint(-7.0, -7.0, 0.0), true).has_value()); } TEST(LineSegment, getIntersection2DDisjoint) @@ -607,13 +607,13 @@ TEST(LineSegment, getSValue_parallelDenormalize) TEST(LineSegment, getVector) { const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(2.0, 3.0, 4.0)); - EXPECT_VECTOR3_EQ(line.getVector(), makeVector(1.0, 1.0, 1.0)); + EXPECT_VECTOR3_EQ(line.vector, makeVector(1.0, 1.0, 1.0)); } TEST(LineSegment, getVectorZeroLength) { const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(1.0, 2.0, 3.0)); - EXPECT_VECTOR3_EQ(line.getVector(), makeVector(0.0, 0.0, 0.0)); + EXPECT_VECTOR3_EQ(line.vector, makeVector(0.0, 0.0, 0.0)); } TEST(LineSegment, getNormalVector) @@ -631,49 +631,49 @@ TEST(LineSegment, getNormalVector_zeroLength) TEST(LineSegment, get2DVector) { const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(2.0, 3.0, 4.0)); - EXPECT_VECTOR3_EQ(line.get2DVector(), makeVector(1.0, 1.0, 0.0)); + EXPECT_VECTOR3_EQ(line.vector_2d, makeVector(1.0, 1.0, 0.0)); } TEST(LineSegment, get2DVectorZeroLength) { const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(1.0, 2.0, 3.0)); - EXPECT_VECTOR3_EQ(line.get2DVector(), makeVector(0.0, 0.0, 0.0)); + EXPECT_VECTOR3_EQ(line.vector_2d, makeVector(0.0, 0.0, 0.0)); } TEST(LineSegment, getLength) { const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(2.0, 3.0, 4.0)); - EXPECT_DOUBLE_EQ(line.getLength(), std::sqrt(3.0)); + EXPECT_DOUBLE_EQ(line.length, std::sqrt(3.0)); } TEST(LineSegment, getLengthZeroLength) { const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(1.0, 2.0, 3.0)); - EXPECT_DOUBLE_EQ(line.getLength(), 0.0); + EXPECT_DOUBLE_EQ(line.length, 0.0); } TEST(LineSegment, get2DLength) { const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(2.0, 3.0, 4.0)); - EXPECT_DOUBLE_EQ(line.get2DLength(), std::sqrt(2.0)); + EXPECT_DOUBLE_EQ(line.length_2d, std::sqrt(2.0)); } TEST(LineSegment, get2DLengthZeroLength) { const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(1.0, 2.0, 3.0)); - EXPECT_DOUBLE_EQ(line.get2DLength(), 0.0); + EXPECT_DOUBLE_EQ(line.length_2d, 0.0); } -TEST(LineSegment, getSlope) +TEST(LineSegment, get2DVectorSlope) { const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(3.0, 3.0, 4.0)); - EXPECT_DOUBLE_EQ(line.getSlope(), 0.5); + EXPECT_DOUBLE_EQ(line.get2DVectorSlope(), 0.5); } -TEST(LineSegment, getSlopeZeroLength) +TEST(LineSegment, get2DVectorSlopeZeroLength) { const math::geometry::LineSegment line(makePoint(1.0, 2.0, 3.0), makePoint(1.0, 2.0, 3.0)); - EXPECT_TRUE(std::isnan(line.getSlope())); + EXPECT_THROW(line.get2DVectorSlope(), common::SimulationError); } TEST(LineSegment, getSquaredDistanceIn2D) From 4f7fa88e5d4ea45c44277a1de8b6feed85d73dbb Mon Sep 17 00:00:00 2001 From: robomic Date: Thu, 29 Aug 2024 11:38:10 +0200 Subject: [PATCH 214/304] longitudinal distance tests --- .../traffic_simulator/test/CMakeLists.txt | 9 +- .../test/src/utils/CMakeLists.txt | 2 + .../test/src/utils/test_distance.cpp | 329 ++++++++++++++++++ 3 files changed, 336 insertions(+), 4 deletions(-) create mode 100644 simulation/traffic_simulator/test/src/utils/CMakeLists.txt create mode 100644 simulation/traffic_simulator/test/src/utils/test_distance.cpp diff --git a/simulation/traffic_simulator/test/CMakeLists.txt b/simulation/traffic_simulator/test/CMakeLists.txt index 713c8b40678..f60dfacda88 100644 --- a/simulation/traffic_simulator/test/CMakeLists.txt +++ b/simulation/traffic_simulator/test/CMakeLists.txt @@ -1,7 +1,8 @@ -add_subdirectory(src/traffic_lights) -add_subdirectory(src/helper) -add_subdirectory(src/entity) add_subdirectory(src/behavior) +add_subdirectory(src/entity) +add_subdirectory(src/hdmap_utils) +add_subdirectory(src/helper) add_subdirectory(src/job) add_subdirectory(src/simulation_clock) -add_subdirectory(src/hdmap_utils) +add_subdirectory(src/traffic_lights) +add_subdirectory(src/utils) diff --git a/simulation/traffic_simulator/test/src/utils/CMakeLists.txt b/simulation/traffic_simulator/test/src/utils/CMakeLists.txt new file mode 100644 index 00000000000..29fb6b608ab --- /dev/null +++ b/simulation/traffic_simulator/test/src/utils/CMakeLists.txt @@ -0,0 +1,2 @@ +ament_add_gtest(test_distance test_distance.cpp) +target_link_libraries(test_distance traffic_simulator) diff --git a/simulation/traffic_simulator/test/src/utils/test_distance.cpp b/simulation/traffic_simulator/test/src/utils/test_distance.cpp new file mode 100644 index 00000000000..7fb03b977c7 --- /dev/null +++ b/simulation/traffic_simulator/test/src/utils/test_distance.cpp @@ -0,0 +1,329 @@ +// Copyright 2015 TIER IV, Inc. All rights reserved. +// +// 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. + +#include + +#include +#include +#include +#include +#include +#include + +int main(int argc, char ** argv) +{ + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} + +/** + * @note Test if the function correctly uses getLateralDistance. Test with a scenario + * in which it is impossible to calculate the distance, e.g. not connected lanelets + * and with allow_lane_change = false. + */ +TEST(distance, lateralDistance_impossible_noChange) +{ + auto hdmap_utils_ptr = std::make_shared( + ament_index_cpp::get_package_share_directory("traffic_simulator") + + "/map/four_track_highway/lanelet2_map.osm", + geographic_msgs::build() + .latitude(35.22312494055522) + .longitude(138.8024583466017) + .altitude(0.0)); + const auto pose_from = traffic_simulator::helper::constructCanonicalizedLaneletPose( + 3002184L, 0.0, 0.0, hdmap_utils_ptr); + const auto pose_to = + traffic_simulator::helper::constructCanonicalizedLaneletPose(202L, 0.0, 0.0, hdmap_utils_ptr); + { + const auto result = traffic_simulator::distance::lateralDistance( + pose_from, pose_to, std::numeric_limits::infinity(), false, hdmap_utils_ptr); + EXPECT_FALSE(result.has_value()); + } + { + const auto result = + traffic_simulator::distance::lateralDistance(pose_from, pose_to, false, hdmap_utils_ptr); + EXPECT_FALSE(result.has_value()); + } +} + +/** + * @note Test if the function correctly uses getLateralDistance. Test with a scenario + * in which it is possible to calculate the distance + * and with allow_lane_change = false. + */ +TEST(distance, lateralDistance_possible_noChange) +{ + auto hdmap_utils_ptr = std::make_shared( + ament_index_cpp::get_package_share_directory("traffic_simulator") + + "/map/four_track_highway/lanelet2_map.osm", + geographic_msgs::build() + .latitude(35.22312494055522) + .longitude(138.8024583466017) + .altitude(0.0)); + const auto pose_from = traffic_simulator::helper::constructCanonicalizedLaneletPose( + 3002184L, 0.0, 0.0, hdmap_utils_ptr); + const auto pose_to = + traffic_simulator::helper::constructCanonicalizedLaneletPose(201L, 0.0, 0.0, hdmap_utils_ptr); + { + const auto result = traffic_simulator::distance::lateralDistance( + pose_from, pose_to, std::numeric_limits::infinity(), false, hdmap_utils_ptr); + ASSERT_TRUE(result.has_value()); + EXPECT_NEAR(result.value(), 0.0, std::numeric_limits::epsilon()); + } + { + const auto result = + traffic_simulator::distance::lateralDistance(pose_from, pose_to, false, hdmap_utils_ptr); + ASSERT_TRUE(result.has_value()); + EXPECT_NEAR(result.value(), 0.0, std::numeric_limits::epsilon()); + } +} + +/** + * @note Test if the function correctly uses getLateralDistance. Test with a scenario + * in which it is impossible to calculate the distance, e.g. not connected lanelets + * and with allow_lane_change = true. + */ +TEST(distance, lateralDistance_impossible_change) +{ + auto hdmap_utils_ptr = std::make_shared( + ament_index_cpp::get_package_share_directory("traffic_simulator") + + "/map/four_track_highway/lanelet2_map.osm", + geographic_msgs::build() + .latitude(35.22312494055522) + .longitude(138.8024583466017) + .altitude(0.0)); + const auto pose_from = + traffic_simulator::helper::constructCanonicalizedLaneletPose(202L, 0.0, 0.0, hdmap_utils_ptr); + const auto pose_to = traffic_simulator::helper::constructCanonicalizedLaneletPose( + 3002184L, 0.0, 0.0, hdmap_utils_ptr); + { + const auto result = traffic_simulator::distance::lateralDistance( + pose_from, pose_to, std::numeric_limits::infinity(), true, hdmap_utils_ptr); + EXPECT_FALSE(result.has_value()); + } + { + const auto result = + traffic_simulator::distance::lateralDistance(pose_from, pose_to, true, hdmap_utils_ptr); + EXPECT_FALSE(result.has_value()); + } +} + +/** + * @note Test if the function correctly uses getLateralDistance. Test with a scenario + * in which it is possible to calculate the distance + * and with allow_lane_change = true. + */ +TEST(distance, lateralDistance_possible_change) +{ + auto hdmap_utils_ptr = std::make_shared( + ament_index_cpp::get_package_share_directory("traffic_simulator") + + "/map/four_track_highway/lanelet2_map.osm", + geographic_msgs::build() + .latitude(35.22312494055522) + .longitude(138.8024583466017) + .altitude(0.0)); + const auto pose_from = traffic_simulator::helper::constructCanonicalizedLaneletPose( + 3002184L, 0.0, 0.0, hdmap_utils_ptr); + const auto pose_to = + traffic_simulator::helper::constructCanonicalizedLaneletPose(202L, 0.0, 0.0, hdmap_utils_ptr); + constexpr double approx_distance = -3.0; + constexpr double tolerance = 0.5; + { + const auto result = traffic_simulator::distance::lateralDistance( + pose_from, pose_to, std::numeric_limits::infinity(), true, hdmap_utils_ptr); + ASSERT_TRUE(result.has_value()); + EXPECT_NEAR(result.value(), approx_distance, tolerance); + } + { + const auto result = + traffic_simulator::distance::lateralDistance(pose_from, pose_to, true, hdmap_utils_ptr); + ASSERT_TRUE(result.has_value()); + EXPECT_NEAR(result.value(), approx_distance, tolerance); + } +} + +/** + * @note Test if the function correctly uses getLateralDistance. Test with a scenario + * in which it is possible to calculate the distance, but matching_distance is too small. + */ +TEST(distance, lateralDistance_impossible_matching) +{ + auto hdmap_utils_ptr = std::make_shared( + ament_index_cpp::get_package_share_directory("traffic_simulator") + + "/map/four_track_highway/lanelet2_map.osm", + geographic_msgs::build() + .latitude(35.22312494055522) + .longitude(138.8024583466017) + .altitude(0.0)); + const auto pose_from = + traffic_simulator::helper::constructCanonicalizedLaneletPose(202L, 0.0, 0.0, hdmap_utils_ptr); + const auto pose_to = traffic_simulator::helper::constructCanonicalizedLaneletPose( + 3002184L, 0.0, 0.0, hdmap_utils_ptr); + { + const auto result = + traffic_simulator::distance::lateralDistance(pose_from, pose_to, 2.0, true, hdmap_utils_ptr); + EXPECT_FALSE(result.has_value()); + } +} + +/** + * @note Test if the function correctly uses getLateralDistance. Test with a scenario + * in which it is possible to calculate the distance and matching_distance is large. + */ +TEST(distance, lateralDistance_possible_matching) +{ + auto hdmap_utils_ptr = std::make_shared( + ament_index_cpp::get_package_share_directory("traffic_simulator") + + "/map/four_track_highway/lanelet2_map.osm", + geographic_msgs::build() + .latitude(35.22312494055522) + .longitude(138.8024583466017) + .altitude(0.0)); + const auto pose_from = traffic_simulator::helper::constructCanonicalizedLaneletPose( + 3002184L, 0.0, 0.0, hdmap_utils_ptr); + const auto pose_to = + traffic_simulator::helper::constructCanonicalizedLaneletPose(202L, 0.0, 0.0, hdmap_utils_ptr); + constexpr double approx_distance = -3.0; + constexpr double tolerance = 0.5; + { + const auto result = + traffic_simulator::distance::lateralDistance(pose_from, pose_to, 3.0, true, hdmap_utils_ptr); + ASSERT_TRUE(result.has_value()); + EXPECT_NEAR(result.value(), approx_distance, tolerance); + } +} + +constexpr auto convertDegToRad(const double deg) -> double { return deg / 180.0 * M_PI; } +constexpr auto convertRadToDeg(const double rad) -> double { return rad * 180.0 / M_PI; } + +auto makePose(const double x, const double y, const double yaw_deg) -> geometry_msgs::msg::Pose +{ + /** + * @note +x axis is 0 degrees; +y axis is 90 degrees + */ + return geometry_msgs::build() + .position(geometry_msgs::build().x(x).y(y).z(0.0)) + .orientation(math::geometry::convertEulerAngleToQuaternion( + geometry_msgs::build().x(0.0).y(0.0).z( + convertDegToRad(yaw_deg)))); +} + +/** + * @note Test calculation correctness with include_adjacent_lanelet = false, + * include_opposite_direction = false, allow_lane_change = false + * in an impossible scenario, e.g. no path. + */ +TEST(distance, longitudinalDistance_noAdjacent_noOpposite_noChange_false) +{ + auto hdmap_utils_ptr = std::make_shared( + ament_index_cpp::get_package_share_directory("traffic_simulator") + + "/map/four_track_highway/lanelet2_map.osm", + geographic_msgs::build() + .latitude(35.22312494055522) + .longitude(138.8024583466017) + .altitude(0.0)); + + const auto pose_from = traffic_simulator::toCanonicalizedLaneletPose( + makePose(81595.44, 50006.09, 100.0), false, hdmap_utils_ptr); + const auto pose_to = traffic_simulator::toCanonicalizedLaneletPose( + makePose(81584.48, 50084.76, 100.0), false, hdmap_utils_ptr); + { + const auto result = traffic_simulator::distance::longitudinalDistance( + pose_from.value(), pose_to.value(), false, false, false, hdmap_utils_ptr); + EXPECT_FALSE(result.has_value()); + } +} + +/** + * @note Test calculation correctness with include_adjacent_lanelet = false, + * include_opposite_direction = false, allow_lane_change = false + * in a scenario that meets those criteria. + */ +TEST(distance, longitudinalDistance_noAdjacent_noOpposite_noChange) +{ + auto hdmap_utils_ptr = std::make_shared( + ament_index_cpp::get_package_share_directory("traffic_simulator") + "/map/lanelet2_map.osm", + geographic_msgs::build() + .latitude(35.61836750154) + .longitude(139.78066608243) + .altitude(0.0)); + + const auto pose_from = traffic_simulator::toCanonicalizedLaneletPose( + makePose(3800.05, 73715.77, 30.0), false, hdmap_utils_ptr); + const auto pose_to = traffic_simulator::toCanonicalizedLaneletPose( + makePose(3841.26, 73748.80, 110.0), false, hdmap_utils_ptr); + { + constexpr double approx_distance = 60.0; + constexpr double tolerance = 1.0; + const auto result = traffic_simulator::distance::longitudinalDistance( + pose_from.value(), pose_to.value(), false, false, false, hdmap_utils_ptr); + ASSERT_TRUE(result.has_value()); + EXPECT_NEAR(result.value(), approx_distance, tolerance); + } +} + +/** + * @note Test calculation correctness with include_adjacent_lanelet = true, + * include_opposite_direction = false, allow_lane_change = false + * in an impossible scenario, e.g. no path. + */ +TEST(distance, longitudinalDistance_adjacent_noOpposite_noChange_false) +{ + auto hdmap_utils_ptr = std::make_shared( + ament_index_cpp::get_package_share_directory("traffic_simulator") + + "/map/four_track_highway/lanelet2_map.osm", + geographic_msgs::build() + .latitude(35.22312494055522) + .longitude(138.8024583466017) + .altitude(0.0)); + + const auto pose_from = traffic_simulator::toCanonicalizedLaneletPose( + makePose(81585.79, 50042.62, 100.0), false, hdmap_utils_ptr); + const auto pose_to = traffic_simulator::toCanonicalizedLaneletPose( + makePose(81588.34, 50083.23, 100.0), false, hdmap_utils_ptr); + { + const auto result = traffic_simulator::distance::longitudinalDistance( + pose_from.value(), pose_to.value(), true, false, false, hdmap_utils_ptr); + EXPECT_FALSE(result.has_value()); + } +} + +/** + * @note Test calculation correctness with include_adjacent_lanelet = true, + * include_opposite_direction = false, allow_lane_change = false + * in a scenario that meets those criteria. + */ +TEST(distance, longitudinalDistance_adjacent_noOpposite_noChange) +{ + auto hdmap_utils_ptr = std::make_shared( + ament_index_cpp::get_package_share_directory("traffic_simulator") + + "/map/four_track_highway/lanelet2_map.osm", + geographic_msgs::build() + .latitude(35.22312494055522) + .longitude(138.8024583466017) + .altitude(0.0)); + + const auto pose_from = traffic_simulator::toCanonicalizedLaneletPose( + makePose(81599.02, 50065.76, 280.0), false, hdmap_utils_ptr); + const auto pose_to = traffic_simulator::toCanonicalizedLaneletPose( + makePose(81599.61, 50045.16, 280.0), false, hdmap_utils_ptr); + { + constexpr double approx_distance = 20.0; + constexpr double tolerance = 1.0; + const auto result = traffic_simulator::distance::longitudinalDistance( + pose_from.value(), pose_to.value(), true, false, false, hdmap_utils_ptr); + ASSERT_TRUE(result.has_value()); + EXPECT_NEAR(result.value(), approx_distance, tolerance); + } +} \ No newline at end of file From 8864e27c105c27a067126eb91c4c55d8517f9266 Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Tue, 3 Sep 2024 18:40:10 +0900 Subject: [PATCH 215/304] Remove data member `traffic_simulator::Configuration::rviz_config_path` Signed-off-by: yamacir-kit --- .../traffic_simulator/api/configuration.hpp | 4 ---- .../src/entity/ego_entity.cpp | 4 +--- .../launch/scenario_test_runner.launch.py | 21 +++++++++---------- 3 files changed, 11 insertions(+), 18 deletions(-) diff --git a/simulation/traffic_simulator/include/traffic_simulator/api/configuration.hpp b/simulation/traffic_simulator/include/traffic_simulator/api/configuration.hpp index 3e17d2f5873..47577f79cea 100644 --- a/simulation/traffic_simulator/include/traffic_simulator/api/configuration.hpp +++ b/simulation/traffic_simulator/include/traffic_simulator/api/configuration.hpp @@ -65,10 +65,6 @@ struct Configuration Pathname scenario_path = ""; - Pathname rviz_config_path = // - ament_index_cpp::get_package_share_directory("traffic_simulator") + - "/config/scenario_simulator_v2.rviz"; - explicit Configuration(const Pathname & map_path) // : map_path(assertMapPath(map_path)), lanelet2_map_file(findLexicographicallyFirstFilenameOf(map_path, ".osm")), diff --git a/simulation/traffic_simulator/src/entity/ego_entity.cpp b/simulation/traffic_simulator/src/entity/ego_entity.cpp index d58f31ae94e..91ebc94c2fd 100644 --- a/simulation/traffic_simulator/src/entity/ego_entity.cpp +++ b/simulation/traffic_simulator/src/entity/ego_entity.cpp @@ -41,8 +41,6 @@ auto EgoEntity::makeFieldOperatorApplication( if (const auto architecture_type = getParameter(node_parameters, "architecture_type", "awf/universe"); architecture_type.find("awf/universe") != std::string::npos) { - const auto rviz_config = getParameter(node_parameters, "rviz_config", ""); - auto parameters = getParameter>(node_parameters, "autoware.", {}); // clang-format off @@ -51,7 +49,7 @@ auto EgoEntity::makeFieldOperatorApplication( parameters.push_back("pointcloud_map_file:=" + configuration.getPointCloudMapFile()); parameters.push_back("sensor_model:=" + getParameter(node_parameters, "sensor_model")); parameters.push_back("vehicle_model:=" + getParameter(node_parameters, "vehicle_model")); - parameters.push_back("rviz_config:=" + (rviz_config.empty() ? configuration.rviz_config_path.string() : rviz_config)); + parameters.push_back("rviz_config:=" + getParameter(node_parameters, "rviz_config")); parameters.push_back("scenario_simulation:=true"); parameters.push_back("use_foa:=false"); parameters.push_back("perception/enable_traffic_light:=" + std::string((architecture_type >= "awf/universe/20230906") ? "true" : "false")); diff --git a/test_runner/scenario_test_runner/launch/scenario_test_runner.launch.py b/test_runner/scenario_test_runner/launch/scenario_test_runner.launch.py index edcda777f00..009a8d4d5d5 100755 --- a/test_runner/scenario_test_runner/launch/scenario_test_runner.launch.py +++ b/test_runner/scenario_test_runner/launch/scenario_test_runner.launch.py @@ -60,6 +60,10 @@ def default_autoware_launch_file_of(architecture_type): }[architecture_type] +def default_rviz_config_file(): + return Path(get_package_share_directory("traffic_simulator")) / "config/scenario_simulator_v2.rviz" + + def launch_setup(context, *args, **kwargs): # fmt: off architecture_type = LaunchConfiguration("architecture_type", default="awf/universe/20230906") @@ -79,7 +83,7 @@ def launch_setup(context, *args, **kwargs): port = LaunchConfiguration("port", default=5555) publish_empty_context = LaunchConfiguration("publish_empty_context", default=False) record = LaunchConfiguration("record", default=True) - rviz_config = LaunchConfiguration("rviz_config", default="") + rviz_config = LaunchConfiguration("rviz_config", default=default_rviz_config_file()) scenario = LaunchConfiguration("scenario", default=Path("/dev/null")) sensor_model = LaunchConfiguration("sensor_model", default="") sigterm_timeout = LaunchConfiguration("sigterm_timeout", default=8) @@ -144,9 +148,10 @@ def make_parameters(): if (pattern.match(each[0])): list_of_string.append(each[0][9:] + ":=" + each[1]) - parameters += [ - {"autoware.": list_of_string} - ] + if list_of_string != []: + parameters += [ + {"autoware.": list_of_string} + ] return parameters @@ -245,13 +250,7 @@ def description(): name="rviz2", output={"stderr": "log", "stdout": "log"}, condition=IfCondition(launch_rviz), - arguments=[ - "-d", - str( - Path(get_package_share_directory("traffic_simulator")) - / "config/scenario_simulator_v2.rviz" - ), - ], + arguments=["-d", str(default_rviz_config_file())], ), ] From 6971ebdf08a9d3380261e75259e620378fc05cc5 Mon Sep 17 00:00:00 2001 From: robomic Date: Tue, 3 Sep 2024 16:14:35 +0200 Subject: [PATCH 216/304] distance tests skeleton, add intersection map and move standard map to its folder --- .../test/map/inctersection/lanelet2_map.osm | 15432 ++++++++++++++++ .../map/{ => standard_map}/lanelet2_map.osm | 0 .../test/src/hdmap_utils/test_hdmap_utils.cpp | 6 +- .../test/src/helper_functions.hpp | 3 +- .../src/traffic_lights/test_traffic_light.cpp | 3 +- .../test_traffic_light_manager.cpp | 3 +- .../test/src/utils/test_distance.cpp | 122 +- 7 files changed, 15562 insertions(+), 7 deletions(-) create mode 100644 simulation/traffic_simulator/test/map/inctersection/lanelet2_map.osm rename simulation/traffic_simulator/test/map/{ => standard_map}/lanelet2_map.osm (100%) diff --git a/simulation/traffic_simulator/test/map/inctersection/lanelet2_map.osm b/simulation/traffic_simulator/test/map/inctersection/lanelet2_map.osm new file mode 100644 index 00000000000..3a239c64159 --- /dev/null +++ b/simulation/traffic_simulator/test/map/inctersection/lanelet2_map.osm @@ -0,0 +1,15432 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/simulation/traffic_simulator/test/map/lanelet2_map.osm b/simulation/traffic_simulator/test/map/standard_map/lanelet2_map.osm similarity index 100% rename from simulation/traffic_simulator/test/map/lanelet2_map.osm rename to simulation/traffic_simulator/test/map/standard_map/lanelet2_map.osm diff --git a/simulation/traffic_simulator/test/src/hdmap_utils/test_hdmap_utils.cpp b/simulation/traffic_simulator/test/src/hdmap_utils/test_hdmap_utils.cpp index 93512bda08d..b0bd92f0569 100644 --- a/simulation/traffic_simulator/test/src/hdmap_utils/test_hdmap_utils.cpp +++ b/simulation/traffic_simulator/test/src/hdmap_utils/test_hdmap_utils.cpp @@ -35,7 +35,8 @@ class HdMapUtilsTest_StandardMap : public testing::Test protected: HdMapUtilsTest_StandardMap() : hdmap_utils(hdmap_utils::HdMapUtils( - ament_index_cpp::get_package_share_directory("traffic_simulator") + "/map/lanelet2_map.osm", + ament_index_cpp::get_package_share_directory("traffic_simulator") + + "/map/standard_map/lanelet2_map.osm", geographic_msgs::build() .latitude(35.61836750154) .longitude(139.78066608243) @@ -132,7 +133,8 @@ TEST(HdMapUtils, Construct) { ASSERT_NO_THROW( auto hdmap_utils = hdmap_utils::HdMapUtils( - ament_index_cpp::get_package_share_directory("traffic_simulator") + "/map/lanelet2_map.osm", + ament_index_cpp::get_package_share_directory("traffic_simulator") + + "/map/standard_map/lanelet2_map.osm", geographic_msgs::build() .latitude(35.61836750154) .longitude(139.78066608243) diff --git a/simulation/traffic_simulator/test/src/helper_functions.hpp b/simulation/traffic_simulator/test/src/helper_functions.hpp index ba5f24b86c6..ff0cb7248cc 100644 --- a/simulation/traffic_simulator/test/src/helper_functions.hpp +++ b/simulation/traffic_simulator/test/src/helper_functions.hpp @@ -63,7 +63,8 @@ auto makePose( auto makeHdMapUtilsSharedPointer() -> std::shared_ptr { return std::make_shared( - ament_index_cpp::get_package_share_directory("traffic_simulator") + "/map/lanelet2_map.osm", + ament_index_cpp::get_package_share_directory("traffic_simulator") + + "/map/standard_map/lanelet2_map.osm", geographic_msgs::build() .latitude(35.9037067912303) .longitude(139.9337945139059) diff --git a/simulation/traffic_simulator/test/src/traffic_lights/test_traffic_light.cpp b/simulation/traffic_simulator/test/src/traffic_lights/test_traffic_light.cpp index 6ab5ba9c6f9..55ac100b94f 100644 --- a/simulation/traffic_simulator/test/src/traffic_lights/test_traffic_light.cpp +++ b/simulation/traffic_simulator/test/src/traffic_lights/test_traffic_light.cpp @@ -714,7 +714,8 @@ class TrafficLightTest : public testing::Test protected: TrafficLightTest() : map_manager( - ament_index_cpp::get_package_share_directory("traffic_simulator") + "/map/lanelet2_map.osm", + ament_index_cpp::get_package_share_directory("traffic_simulator") + + "/map/standard_map/lanelet2_map.osm", geographic_msgs::build() .latitude(35.61836750154) .longitude(139.78066608243) diff --git a/simulation/traffic_simulator/test/src/traffic_lights/test_traffic_light_manager.cpp b/simulation/traffic_simulator/test/src/traffic_lights/test_traffic_light_manager.cpp index f5b58616f44..3593b18f50b 100644 --- a/simulation/traffic_simulator/test/src/traffic_lights/test_traffic_light_manager.cpp +++ b/simulation/traffic_simulator/test/src/traffic_lights/test_traffic_light_manager.cpp @@ -23,7 +23,8 @@ class TrafficLightManagerTest : public testing::Test protected: TrafficLightManagerTest() : manager(std::make_shared( - ament_index_cpp::get_package_share_directory("traffic_simulator") + "/map/lanelet2_map.osm", + ament_index_cpp::get_package_share_directory("traffic_simulator") + + "/map/standard_map/lanelet2_map.osm", geographic_msgs::build() .latitude(35.61836750154) .longitude(139.78066608243) diff --git a/simulation/traffic_simulator/test/src/utils/test_distance.cpp b/simulation/traffic_simulator/test/src/utils/test_distance.cpp index 7fb03b977c7..249e556be03 100644 --- a/simulation/traffic_simulator/test/src/utils/test_distance.cpp +++ b/simulation/traffic_simulator/test/src/utils/test_distance.cpp @@ -253,7 +253,8 @@ TEST(distance, longitudinalDistance_noAdjacent_noOpposite_noChange_false) TEST(distance, longitudinalDistance_noAdjacent_noOpposite_noChange) { auto hdmap_utils_ptr = std::make_shared( - ament_index_cpp::get_package_share_directory("traffic_simulator") + "/map/lanelet2_map.osm", + ament_index_cpp::get_package_share_directory("traffic_simulator") + + "/map/standard_map/lanelet2_map.osm", geographic_msgs::build() .latitude(35.61836750154) .longitude(139.78066608243) @@ -326,4 +327,121 @@ TEST(distance, longitudinalDistance_adjacent_noOpposite_noChange) ASSERT_TRUE(result.has_value()); EXPECT_NEAR(result.value(), approx_distance, tolerance); } -} \ No newline at end of file +} + +/** + * @note Test calculation correctness with include_adjacent_lanelet = false, + * include_opposite_direction = false, allow_lane_change = true + * in an impossible scenario, e.g. no path. + */ +TEST(distance, longitudinalDistance_noAdjacent_noOpposite_change_false) +{ + auto hdmap_utils_ptr = std::make_shared( + ament_index_cpp::get_package_share_directory("traffic_simulator") + + "/map/four_track_highway/lanelet2_map.osm", + geographic_msgs::build() + .latitude(35.22312494055522) + .longitude(138.8024583466017) + .altitude(0.0)); + + { + const auto pose_from = traffic_simulator::toCanonicalizedLaneletPose( + makePose(81595.47, 49982.80, 100.0), false, hdmap_utils_ptr); + const auto pose_to = traffic_simulator::toCanonicalizedLaneletPose( + makePose(81599.34, 50022.34, 100.0), false, hdmap_utils_ptr); + const auto result = traffic_simulator::distance::longitudinalDistance( + pose_from.value(), pose_to.value(), false, false, true, hdmap_utils_ptr); + EXPECT_FALSE(result.has_value()); + } + { + const auto pose_from = traffic_simulator::toCanonicalizedLaneletPose( + makePose(81612.35, 50015.63, 280.0), false, hdmap_utils_ptr); + const auto pose_to = traffic_simulator::toCanonicalizedLaneletPose( + makePose(81612.95, 49991.30, 280.0), false, hdmap_utils_ptr); + const auto result = traffic_simulator::distance::longitudinalDistance( + pose_from.value(), pose_to.value(), false, false, true, hdmap_utils_ptr); + EXPECT_FALSE(result.has_value()); + } +} + +/** + * @note Test calculation correctness with include_adjacent_lanelet = false, + * include_opposite_direction = false, allow_lane_change = true + * in a scenario that meets those criteria. + */ +TEST(distance, longitudinalDistance_noAdjacent_noOpposite_change) +{ + auto hdmap_utils_ptr = std::make_shared( + ament_index_cpp::get_package_share_directory("traffic_simulator") + + "/map/four_track_highway/lanelet2_map.osm", + geographic_msgs::build() + .latitude(35.22312494055522) + .longitude(138.8024583466017) + .altitude(0.0)); + { + const auto pose_from = traffic_simulator::toCanonicalizedLaneletPose( + makePose(81592.96, 49997.94, 100.0), false, hdmap_utils_ptr); + const auto pose_to = traffic_simulator::toCanonicalizedLaneletPose( + makePose(81570.56, 50141.75, 100.0), false, hdmap_utils_ptr); + constexpr double approx_distance = 145.0; + constexpr double tolerance = 1.0; + const auto result = traffic_simulator::distance::longitudinalDistance( + pose_from.value(), pose_to.value(), false, false, true, hdmap_utils_ptr); + ASSERT_TRUE(result.has_value()); + EXPECT_NEAR(result.value(), approx_distance, tolerance); + } + { + const auto pose_from = traffic_simulator::toCanonicalizedLaneletPose( + makePose(81587.31, 50165.57, 100.0), false, hdmap_utils_ptr); + const auto pose_to = traffic_simulator::toCanonicalizedLaneletPose( + makePose(81610.25, 49988.59, 100.0), false, hdmap_utils_ptr); + constexpr double approx_distance = 178.0; + constexpr double tolerance = 1.0; + const auto result = traffic_simulator::distance::longitudinalDistance( + pose_from.value(), pose_to.value(), false, false, true, hdmap_utils_ptr); + ASSERT_TRUE(result.has_value()); + EXPECT_NEAR(result.value(), approx_distance, tolerance); + } +} + +/** + * @note Test calculation correctness with include_adjacent_lanelet = true, + * include_opposite_direction = false, allow_lane_change = true + * in an impossible scenario, e.g. no path. + */ +TEST(distance, longitudinalDistance_adjacent_noOpposite_change_false) {} + +/** + * @note Test calculation correctness with include_adjacent_lanelet = true, + * include_opposite_direction = false, allow_lane_change = true + * in a scenario that meets those criteria. + */ +TEST(distance, longitudinalDistance_adjacent_noOpposite_change) {} + +/** + * @note Test calculation correctness with include_adjacent_lanelet = true, + * include_opposite_direction = true, allow_lane_change = false + * in an impossible scenario, e.g. no path. + */ +TEST(distance, longitudinalDistance_adjacent_opposite_noChange_false) {} + +/** + * @note Test calculation correctness with include_adjacent_lanelet = true, + * include_opposite_direction = true, allow_lane_change = false + * in a scenario that meets those criteria. + */ +TEST(distance, longitudinalDistance_adjacent_opposite_noChange) {} + +/** + * @note Test calculation correctness with include_adjacent_lanelet = true, + * include_opposite_direction = true, allow_lane_change = true + * in an impossible scenario, e.g. no path. + */ +TEST(distance, longitudinalDistance_adjacent_opposite_change_false) {} + +/** + * @note Test calculation correctness with include_adjacent_lanelet = true, + * include_opposite_direction = true, allow_lane_change = true + * in a scenario that meets those criteria. + */ +TEST(distance, longitudinalDistance_adjacent_opposite_change) {} From 04373bd451c00ff6a8468ae486dec5423fb5e890 Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Wed, 4 Sep 2024 13:16:51 +0900 Subject: [PATCH 217/304] Simplify collection of `autoware.` prefixed parameters Signed-off-by: yamacir-kit --- .../launch/scenario_test_runner.launch.py | 16 ++-------------- 1 file changed, 2 insertions(+), 14 deletions(-) diff --git a/test_runner/scenario_test_runner/launch/scenario_test_runner.launch.py b/test_runner/scenario_test_runner/launch/scenario_test_runner.launch.py index 009a8d4d5d5..af3702a0d9b 100755 --- a/test_runner/scenario_test_runner/launch/scenario_test_runner.launch.py +++ b/test_runner/scenario_test_runner/launch/scenario_test_runner.launch.py @@ -31,8 +31,6 @@ from scenario_test_runner.shutdown_once import ShutdownOnce -import re - def architecture_types(): return ["awf/universe", "awf/universe/20230906"] @@ -140,18 +138,8 @@ def make_parameters(): parameters += make_vehicle_parameters() - list_of_string = [] - - pattern = re.compile("[Aa]utoware\..*") - - for each in context.launch_configurations.items(): - if (pattern.match(each[0])): - list_of_string.append(each[0][9:] + ":=" + each[1]) - - if list_of_string != []: - parameters += [ - {"autoware.": list_of_string} - ] + if (it := [item[0][9:] + ':=' + item[1] for item in context.launch_configurations.items() if item[0][:9] == 'autoware.']) != []: + parameters += [{"autoware.": it}] return parameters From fb3ba4b61d075078716cdb521ef333900d776772 Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Wed, 4 Sep 2024 16:32:59 +0900 Subject: [PATCH 218/304] Move parameter `use_sim_time` into function `make_parameters` Signed-off-by: yamacir-kit --- simulation/traffic_simulator/src/entity/ego_entity.cpp | 6 ++++-- .../launch/scenario_test_runner.launch.py | 10 +++++++--- 2 files changed, 11 insertions(+), 5 deletions(-) diff --git a/simulation/traffic_simulator/src/entity/ego_entity.cpp b/simulation/traffic_simulator/src/entity/ego_entity.cpp index 91ebc94c2fd..4deb4f97110 100644 --- a/simulation/traffic_simulator/src/entity/ego_entity.cpp +++ b/simulation/traffic_simulator/src/entity/ego_entity.cpp @@ -41,6 +41,8 @@ auto EgoEntity::makeFieldOperatorApplication( if (const auto architecture_type = getParameter(node_parameters, "architecture_type", "awf/universe"); architecture_type.find("awf/universe") != std::string::npos) { + auto boolalpha = [](bool value) { return std::string(value ? "true" : "false"); }; + auto parameters = getParameter>(node_parameters, "autoware.", {}); // clang-format off @@ -52,8 +54,8 @@ auto EgoEntity::makeFieldOperatorApplication( parameters.push_back("rviz_config:=" + getParameter(node_parameters, "rviz_config")); parameters.push_back("scenario_simulation:=true"); parameters.push_back("use_foa:=false"); - parameters.push_back("perception/enable_traffic_light:=" + std::string((architecture_type >= "awf/universe/20230906") ? "true" : "false")); - parameters.push_back("use_sim_time:=" + std::string(getParameter(node_parameters, "use_sim_time", false) ? "true" : "false")); + parameters.push_back("perception/enable_traffic_light:=" + boolalpha(architecture_type >= "awf/universe/20230906")); + parameters.push_back("use_sim_time:=" + boolalpha(getParameter(node_parameters, "use_sim_time", false))); // clang-format on return getParameter(node_parameters, "launch_autoware", true) diff --git a/test_runner/scenario_test_runner/launch/scenario_test_runner.launch.py b/test_runner/scenario_test_runner/launch/scenario_test_runner.launch.py index af3702a0d9b..8513fab9b1e 100755 --- a/test_runner/scenario_test_runner/launch/scenario_test_runner.launch.py +++ b/test_runner/scenario_test_runner/launch/scenario_test_runner.launch.py @@ -133,12 +133,16 @@ def make_parameters(): {"rviz_config": rviz_config}, {"sensor_model": sensor_model}, {"sigterm_timeout": sigterm_timeout}, + {"use_sim_time": use_sim_time}, {"vehicle_model": vehicle_model}, ] parameters += make_vehicle_parameters() - if (it := [item[0][9:] + ':=' + item[1] for item in context.launch_configurations.items() if item[0][:9] == 'autoware.']) != []: + def make_prefixed_parameters(): + return [item[0][9:] + ':=' + item[1] for item in context.launch_configurations.items() if item[0][:9] == 'autoware.'] + + if (it := make_prefixed_parameters()) != []: parameters += [{"autoware.": it}] return parameters @@ -201,7 +205,7 @@ def description(): namespace="simulation", output="screen", on_exit=ShutdownOnce(), - parameters=make_parameters() + [{"use_sim_time": use_sim_time}], + parameters=make_parameters(), condition=IfCondition(launch_simple_sensor_simulator), ), # The `name` keyword overrides the name for all created nodes, so duplicated nodes appear. @@ -214,7 +218,7 @@ def description(): executable="openscenario_interpreter_node", namespace="simulation", output="screen", - parameters=[{"use_sim_time": use_sim_time}]+make_parameters(), + parameters=make_parameters(), prefix=make_launch_prefix(), on_exit=ShutdownOnce(), ), From 640b00a85aaeb1ea017e93a1750bcdcd38e798d4 Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Wed, 4 Sep 2024 17:28:59 +0900 Subject: [PATCH 219/304] Move function `make_vehicle_parameters` into function `make_parameters` Signed-off-by: yamacir-kit --- .../launch/scenario_test_runner.launch.py | 32 +++++++++---------- 1 file changed, 15 insertions(+), 17 deletions(-) diff --git a/test_runner/scenario_test_runner/launch/scenario_test_runner.launch.py b/test_runner/scenario_test_runner/launch/scenario_test_runner.launch.py index 8513fab9b1e..6ebccaa9c89 100755 --- a/test_runner/scenario_test_runner/launch/scenario_test_runner.launch.py +++ b/test_runner/scenario_test_runner/launch/scenario_test_runner.launch.py @@ -137,29 +137,27 @@ def make_parameters(): {"vehicle_model": vehicle_model}, ] - parameters += make_vehicle_parameters() - - def make_prefixed_parameters(): + def collect_vehicle_parameters(): + if vehicle_model_name := vehicle_model.perform(context): + description = get_package_share_directory(vehicle_model_name + "_description") + return [ + description + "/config/vehicle_info.param.yaml", + description + "/config/simulator_model.param.yaml", + ] + else: + return [] + + if (it := collect_vehicle_parameters()) != []: + parameters += it + + def collect_prefixed_parameters(): return [item[0][9:] + ':=' + item[1] for item in context.launch_configurations.items() if item[0][:9] == 'autoware.'] - if (it := make_prefixed_parameters()) != []: + if (it := collect_prefixed_parameters()) != []: parameters += [{"autoware.": it}] return parameters - def make_vehicle_parameters(): - parameters = [] - - def description(): - return get_package_share_directory( - vehicle_model.perform(context) + "_description" - ) - - if vehicle_model.perform(context): - parameters.append(description() + "/config/vehicle_info.param.yaml") - parameters.append(description() + "/config/simulator_model.param.yaml") - return parameters - return [ # fmt: off DeclareLaunchArgument("architecture_type", default_value=architecture_type ), From 3caf5303159dc1ee2b906b79f45ed40a928d28b1 Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Wed, 4 Sep 2024 18:04:46 +0900 Subject: [PATCH 220/304] Cleanup Signed-off-by: yamacir-kit --- .../include/traffic_simulator/api/configuration.hpp | 1 - simulation/traffic_simulator/src/entity/ego_entity.cpp | 6 ++---- 2 files changed, 2 insertions(+), 5 deletions(-) diff --git a/simulation/traffic_simulator/include/traffic_simulator/api/configuration.hpp b/simulation/traffic_simulator/include/traffic_simulator/api/configuration.hpp index 47577f79cea..155fab255b9 100644 --- a/simulation/traffic_simulator/include/traffic_simulator/api/configuration.hpp +++ b/simulation/traffic_simulator/include/traffic_simulator/api/configuration.hpp @@ -16,7 +16,6 @@ #define TRAFFIC_SIMULATOR__API__CONFIGURATION_HPP_ #include -#include #include #include #include diff --git a/simulation/traffic_simulator/src/entity/ego_entity.cpp b/simulation/traffic_simulator/src/entity/ego_entity.cpp index 4deb4f97110..7ba999c60b1 100644 --- a/simulation/traffic_simulator/src/entity/ego_entity.cpp +++ b/simulation/traffic_simulator/src/entity/ego_entity.cpp @@ -41,8 +41,6 @@ auto EgoEntity::makeFieldOperatorApplication( if (const auto architecture_type = getParameter(node_parameters, "architecture_type", "awf/universe"); architecture_type.find("awf/universe") != std::string::npos) { - auto boolalpha = [](bool value) { return std::string(value ? "true" : "false"); }; - auto parameters = getParameter>(node_parameters, "autoware.", {}); // clang-format off @@ -54,8 +52,8 @@ auto EgoEntity::makeFieldOperatorApplication( parameters.push_back("rviz_config:=" + getParameter(node_parameters, "rviz_config")); parameters.push_back("scenario_simulation:=true"); parameters.push_back("use_foa:=false"); - parameters.push_back("perception/enable_traffic_light:=" + boolalpha(architecture_type >= "awf/universe/20230906")); - parameters.push_back("use_sim_time:=" + boolalpha(getParameter(node_parameters, "use_sim_time", false))); + parameters.push_back("perception/enable_traffic_light:=" + std::string(architecture_type >= "awf/universe/20230906" ? "true" : "false")); + parameters.push_back("use_sim_time:=" + std::string(getParameter(node_parameters, "use_sim_time", false) ? "true" : "false")); // clang-format on return getParameter(node_parameters, "launch_autoware", true) From 851a696e7551e68e86802d70d9ad2060d8ebf9a2 Mon Sep 17 00:00:00 2001 From: robomic Date: Thu, 5 Sep 2024 11:34:02 +0200 Subject: [PATCH 221/304] clean-up; test_fixture --- .../lanelet2_map.osm | 0 .../test/src/utils/test_distance.cpp | 369 ++++++++++-------- 2 files changed, 212 insertions(+), 157 deletions(-) rename simulation/traffic_simulator/test/map/{inctersection => intersection}/lanelet2_map.osm (100%) diff --git a/simulation/traffic_simulator/test/map/inctersection/lanelet2_map.osm b/simulation/traffic_simulator/test/map/intersection/lanelet2_map.osm similarity index 100% rename from simulation/traffic_simulator/test/map/inctersection/lanelet2_map.osm rename to simulation/traffic_simulator/test/map/intersection/lanelet2_map.osm diff --git a/simulation/traffic_simulator/test/src/utils/test_distance.cpp b/simulation/traffic_simulator/test/src/utils/test_distance.cpp index 249e556be03..3295392590b 100644 --- a/simulation/traffic_simulator/test/src/utils/test_distance.cpp +++ b/simulation/traffic_simulator/test/src/utils/test_distance.cpp @@ -27,20 +27,61 @@ int main(int argc, char ** argv) return RUN_ALL_TESTS(); } +class distanceTest_FourTrackHighway : public testing::Test +{ +protected: + distanceTest_FourTrackHighway() + : hdmap_utils_ptr(std::make_shared( + ament_index_cpp::get_package_share_directory("traffic_simulator") + + "/map/four_track_highway/lanelet2_map.osm", + geographic_msgs::build() + .latitude(35.22312494055522) + .longitude(138.8024583466017) + .altitude(0.0))) + { + } + std::shared_ptr hdmap_utils_ptr; +}; + +class distanceTest_StandardMap : public testing::Test +{ +protected: + distanceTest_StandardMap() + : hdmap_utils_ptr(std::make_shared( + ament_index_cpp::get_package_share_directory("traffic_simulator") + + "/map/standard_map/lanelet2_map.osm", + geographic_msgs::build() + .latitude(35.61836750154) + .longitude(139.78066608243) + .altitude(0.0))) + { + } + std::shared_ptr hdmap_utils_ptr; +}; + +class distanceTest_Intersection : public testing::Test +{ +protected: + distanceTest_Intersection() + : hdmap_utils_ptr(std::make_shared( + ament_index_cpp::get_package_share_directory("traffic_simulator") + + "/map/intersection/lanelet2_map.osm", + geographic_msgs::build() + .latitude(35.64200728302) + .longitude(139.74821144562) + .altitude(0.0))) + { + } + std::shared_ptr hdmap_utils_ptr; +}; + /** * @note Test if the function correctly uses getLateralDistance. Test with a scenario * in which it is impossible to calculate the distance, e.g. not connected lanelets * and with allow_lane_change = false. */ -TEST(distance, lateralDistance_impossible_noChange) +TEST_F(distanceTest_FourTrackHighway, lateralDistance_impossible_noChange) { - auto hdmap_utils_ptr = std::make_shared( - ament_index_cpp::get_package_share_directory("traffic_simulator") + - "/map/four_track_highway/lanelet2_map.osm", - geographic_msgs::build() - .latitude(35.22312494055522) - .longitude(138.8024583466017) - .altitude(0.0)); const auto pose_from = traffic_simulator::helper::constructCanonicalizedLaneletPose( 3002184L, 0.0, 0.0, hdmap_utils_ptr); const auto pose_to = @@ -62,15 +103,8 @@ TEST(distance, lateralDistance_impossible_noChange) * in which it is possible to calculate the distance * and with allow_lane_change = false. */ -TEST(distance, lateralDistance_possible_noChange) +TEST_F(distanceTest_FourTrackHighway, lateralDistance_possible_noChange) { - auto hdmap_utils_ptr = std::make_shared( - ament_index_cpp::get_package_share_directory("traffic_simulator") + - "/map/four_track_highway/lanelet2_map.osm", - geographic_msgs::build() - .latitude(35.22312494055522) - .longitude(138.8024583466017) - .altitude(0.0)); const auto pose_from = traffic_simulator::helper::constructCanonicalizedLaneletPose( 3002184L, 0.0, 0.0, hdmap_utils_ptr); const auto pose_to = @@ -94,15 +128,8 @@ TEST(distance, lateralDistance_possible_noChange) * in which it is impossible to calculate the distance, e.g. not connected lanelets * and with allow_lane_change = true. */ -TEST(distance, lateralDistance_impossible_change) +TEST_F(distanceTest_FourTrackHighway, lateralDistance_impossible_change) { - auto hdmap_utils_ptr = std::make_shared( - ament_index_cpp::get_package_share_directory("traffic_simulator") + - "/map/four_track_highway/lanelet2_map.osm", - geographic_msgs::build() - .latitude(35.22312494055522) - .longitude(138.8024583466017) - .altitude(0.0)); const auto pose_from = traffic_simulator::helper::constructCanonicalizedLaneletPose(202L, 0.0, 0.0, hdmap_utils_ptr); const auto pose_to = traffic_simulator::helper::constructCanonicalizedLaneletPose( @@ -124,15 +151,8 @@ TEST(distance, lateralDistance_impossible_change) * in which it is possible to calculate the distance * and with allow_lane_change = true. */ -TEST(distance, lateralDistance_possible_change) +TEST_F(distanceTest_FourTrackHighway, lateralDistance_possible_change) { - auto hdmap_utils_ptr = std::make_shared( - ament_index_cpp::get_package_share_directory("traffic_simulator") + - "/map/four_track_highway/lanelet2_map.osm", - geographic_msgs::build() - .latitude(35.22312494055522) - .longitude(138.8024583466017) - .altitude(0.0)); const auto pose_from = traffic_simulator::helper::constructCanonicalizedLaneletPose( 3002184L, 0.0, 0.0, hdmap_utils_ptr); const auto pose_to = @@ -157,15 +177,8 @@ TEST(distance, lateralDistance_possible_change) * @note Test if the function correctly uses getLateralDistance. Test with a scenario * in which it is possible to calculate the distance, but matching_distance is too small. */ -TEST(distance, lateralDistance_impossible_matching) +TEST_F(distanceTest_FourTrackHighway, lateralDistance_impossible_matching) { - auto hdmap_utils_ptr = std::make_shared( - ament_index_cpp::get_package_share_directory("traffic_simulator") + - "/map/four_track_highway/lanelet2_map.osm", - geographic_msgs::build() - .latitude(35.22312494055522) - .longitude(138.8024583466017) - .altitude(0.0)); const auto pose_from = traffic_simulator::helper::constructCanonicalizedLaneletPose(202L, 0.0, 0.0, hdmap_utils_ptr); const auto pose_to = traffic_simulator::helper::constructCanonicalizedLaneletPose( @@ -181,26 +194,18 @@ TEST(distance, lateralDistance_impossible_matching) * @note Test if the function correctly uses getLateralDistance. Test with a scenario * in which it is possible to calculate the distance and matching_distance is large. */ -TEST(distance, lateralDistance_possible_matching) +TEST_F(distanceTest_FourTrackHighway, lateralDistance_possible_matching) { - auto hdmap_utils_ptr = std::make_shared( - ament_index_cpp::get_package_share_directory("traffic_simulator") + - "/map/four_track_highway/lanelet2_map.osm", - geographic_msgs::build() - .latitude(35.22312494055522) - .longitude(138.8024583466017) - .altitude(0.0)); const auto pose_from = traffic_simulator::helper::constructCanonicalizedLaneletPose( 3002184L, 0.0, 0.0, hdmap_utils_ptr); const auto pose_to = traffic_simulator::helper::constructCanonicalizedLaneletPose(202L, 0.0, 0.0, hdmap_utils_ptr); - constexpr double approx_distance = -3.0; - constexpr double tolerance = 0.5; + { const auto result = traffic_simulator::distance::lateralDistance(pose_from, pose_to, 3.0, true, hdmap_utils_ptr); ASSERT_TRUE(result.has_value()); - EXPECT_NEAR(result.value(), approx_distance, tolerance); + EXPECT_NEAR(result.value(), -3.0, 0.5); } } @@ -224,21 +229,16 @@ auto makePose(const double x, const double y, const double yaw_deg) -> geometry_ * include_opposite_direction = false, allow_lane_change = false * in an impossible scenario, e.g. no path. */ -TEST(distance, longitudinalDistance_noAdjacent_noOpposite_noChange_false) +TEST_F(distanceTest_FourTrackHighway, longitudinalDistance_noAdjacent_noOpposite_noChange_false) { - auto hdmap_utils_ptr = std::make_shared( - ament_index_cpp::get_package_share_directory("traffic_simulator") + - "/map/four_track_highway/lanelet2_map.osm", - geographic_msgs::build() - .latitude(35.22312494055522) - .longitude(138.8024583466017) - .altitude(0.0)); - - const auto pose_from = traffic_simulator::toCanonicalizedLaneletPose( - makePose(81595.44, 50006.09, 100.0), false, hdmap_utils_ptr); - const auto pose_to = traffic_simulator::toCanonicalizedLaneletPose( - makePose(81584.48, 50084.76, 100.0), false, hdmap_utils_ptr); { + const auto pose_from = traffic_simulator::toCanonicalizedLaneletPose( + makePose(81595.44, 50006.09, 100.0), false, hdmap_utils_ptr); + ASSERT_TRUE(pose_from.has_value()); + const auto pose_to = traffic_simulator::toCanonicalizedLaneletPose( + makePose(81584.48, 50084.76, 100.0), false, hdmap_utils_ptr); + ASSERT_TRUE(pose_from.has_value()); + const auto result = traffic_simulator::distance::longitudinalDistance( pose_from.value(), pose_to.value(), false, false, false, hdmap_utils_ptr); EXPECT_FALSE(result.has_value()); @@ -250,27 +250,20 @@ TEST(distance, longitudinalDistance_noAdjacent_noOpposite_noChange_false) * include_opposite_direction = false, allow_lane_change = false * in a scenario that meets those criteria. */ -TEST(distance, longitudinalDistance_noAdjacent_noOpposite_noChange) +TEST_F(distanceTest_StandardMap, longitudinalDistance_noAdjacent_noOpposite_noChange) { - auto hdmap_utils_ptr = std::make_shared( - ament_index_cpp::get_package_share_directory("traffic_simulator") + - "/map/standard_map/lanelet2_map.osm", - geographic_msgs::build() - .latitude(35.61836750154) - .longitude(139.78066608243) - .altitude(0.0)); - - const auto pose_from = traffic_simulator::toCanonicalizedLaneletPose( - makePose(3800.05, 73715.77, 30.0), false, hdmap_utils_ptr); - const auto pose_to = traffic_simulator::toCanonicalizedLaneletPose( - makePose(3841.26, 73748.80, 110.0), false, hdmap_utils_ptr); { - constexpr double approx_distance = 60.0; - constexpr double tolerance = 1.0; + const auto pose_from = traffic_simulator::toCanonicalizedLaneletPose( + makePose(3800.05, 73715.77, 30.0), false, hdmap_utils_ptr); + ASSERT_TRUE(pose_from.has_value()); + const auto pose_to = traffic_simulator::toCanonicalizedLaneletPose( + makePose(3841.26, 73748.80, 110.0), false, hdmap_utils_ptr); + ASSERT_TRUE(pose_from.has_value()); + const auto result = traffic_simulator::distance::longitudinalDistance( pose_from.value(), pose_to.value(), false, false, false, hdmap_utils_ptr); ASSERT_TRUE(result.has_value()); - EXPECT_NEAR(result.value(), approx_distance, tolerance); + EXPECT_NEAR(result.value(), 60.0, 1.0); } } @@ -279,21 +272,16 @@ TEST(distance, longitudinalDistance_noAdjacent_noOpposite_noChange) * include_opposite_direction = false, allow_lane_change = false * in an impossible scenario, e.g. no path. */ -TEST(distance, longitudinalDistance_adjacent_noOpposite_noChange_false) +TEST_F(distanceTest_FourTrackHighway, longitudinalDistance_adjacent_noOpposite_noChange_false) { - auto hdmap_utils_ptr = std::make_shared( - ament_index_cpp::get_package_share_directory("traffic_simulator") + - "/map/four_track_highway/lanelet2_map.osm", - geographic_msgs::build() - .latitude(35.22312494055522) - .longitude(138.8024583466017) - .altitude(0.0)); - - const auto pose_from = traffic_simulator::toCanonicalizedLaneletPose( - makePose(81585.79, 50042.62, 100.0), false, hdmap_utils_ptr); - const auto pose_to = traffic_simulator::toCanonicalizedLaneletPose( - makePose(81588.34, 50083.23, 100.0), false, hdmap_utils_ptr); { + const auto pose_from = traffic_simulator::toCanonicalizedLaneletPose( + makePose(81585.79, 50042.62, 100.0), false, hdmap_utils_ptr); + ASSERT_TRUE(pose_from.has_value()); + const auto pose_to = traffic_simulator::toCanonicalizedLaneletPose( + makePose(81588.34, 50083.23, 100.0), false, hdmap_utils_ptr); + ASSERT_TRUE(pose_from.has_value()); + const auto result = traffic_simulator::distance::longitudinalDistance( pose_from.value(), pose_to.value(), true, false, false, hdmap_utils_ptr); EXPECT_FALSE(result.has_value()); @@ -305,27 +293,20 @@ TEST(distance, longitudinalDistance_adjacent_noOpposite_noChange_false) * include_opposite_direction = false, allow_lane_change = false * in a scenario that meets those criteria. */ -TEST(distance, longitudinalDistance_adjacent_noOpposite_noChange) +TEST_F(distanceTest_FourTrackHighway, longitudinalDistance_adjacent_noOpposite_noChange) { - auto hdmap_utils_ptr = std::make_shared( - ament_index_cpp::get_package_share_directory("traffic_simulator") + - "/map/four_track_highway/lanelet2_map.osm", - geographic_msgs::build() - .latitude(35.22312494055522) - .longitude(138.8024583466017) - .altitude(0.0)); - - const auto pose_from = traffic_simulator::toCanonicalizedLaneletPose( - makePose(81599.02, 50065.76, 280.0), false, hdmap_utils_ptr); - const auto pose_to = traffic_simulator::toCanonicalizedLaneletPose( - makePose(81599.61, 50045.16, 280.0), false, hdmap_utils_ptr); { - constexpr double approx_distance = 20.0; - constexpr double tolerance = 1.0; + const auto pose_from = traffic_simulator::toCanonicalizedLaneletPose( + makePose(81599.02, 50065.76, 280.0), false, hdmap_utils_ptr); + ASSERT_TRUE(pose_from.has_value()); + const auto pose_to = traffic_simulator::toCanonicalizedLaneletPose( + makePose(81599.61, 50045.16, 280.0), false, hdmap_utils_ptr); + ASSERT_TRUE(pose_from.has_value()); + const auto result = traffic_simulator::distance::longitudinalDistance( pose_from.value(), pose_to.value(), true, false, false, hdmap_utils_ptr); ASSERT_TRUE(result.has_value()); - EXPECT_NEAR(result.value(), approx_distance, tolerance); + EXPECT_NEAR(result.value(), 20.0, 1.0); } } @@ -334,21 +315,16 @@ TEST(distance, longitudinalDistance_adjacent_noOpposite_noChange) * include_opposite_direction = false, allow_lane_change = true * in an impossible scenario, e.g. no path. */ -TEST(distance, longitudinalDistance_noAdjacent_noOpposite_change_false) +TEST_F(distanceTest_FourTrackHighway, longitudinalDistance_noAdjacent_noOpposite_change_false) { - auto hdmap_utils_ptr = std::make_shared( - ament_index_cpp::get_package_share_directory("traffic_simulator") + - "/map/four_track_highway/lanelet2_map.osm", - geographic_msgs::build() - .latitude(35.22312494055522) - .longitude(138.8024583466017) - .altitude(0.0)); - { const auto pose_from = traffic_simulator::toCanonicalizedLaneletPose( makePose(81595.47, 49982.80, 100.0), false, hdmap_utils_ptr); + ASSERT_TRUE(pose_from.has_value()); const auto pose_to = traffic_simulator::toCanonicalizedLaneletPose( makePose(81599.34, 50022.34, 100.0), false, hdmap_utils_ptr); + ASSERT_TRUE(pose_from.has_value()); + const auto result = traffic_simulator::distance::longitudinalDistance( pose_from.value(), pose_to.value(), false, false, true, hdmap_utils_ptr); EXPECT_FALSE(result.has_value()); @@ -356,8 +332,11 @@ TEST(distance, longitudinalDistance_noAdjacent_noOpposite_change_false) { const auto pose_from = traffic_simulator::toCanonicalizedLaneletPose( makePose(81612.35, 50015.63, 280.0), false, hdmap_utils_ptr); + ASSERT_TRUE(pose_from.has_value()); const auto pose_to = traffic_simulator::toCanonicalizedLaneletPose( makePose(81612.95, 49991.30, 280.0), false, hdmap_utils_ptr); + ASSERT_TRUE(pose_from.has_value()); + const auto result = traffic_simulator::distance::longitudinalDistance( pose_from.value(), pose_to.value(), false, false, true, hdmap_utils_ptr); EXPECT_FALSE(result.has_value()); @@ -369,79 +348,155 @@ TEST(distance, longitudinalDistance_noAdjacent_noOpposite_change_false) * include_opposite_direction = false, allow_lane_change = true * in a scenario that meets those criteria. */ -TEST(distance, longitudinalDistance_noAdjacent_noOpposite_change) +TEST_F(distanceTest_FourTrackHighway, longitudinalDistance_noAdjacent_noOpposite_change_case0) { - auto hdmap_utils_ptr = std::make_shared( - ament_index_cpp::get_package_share_directory("traffic_simulator") + - "/map/four_track_highway/lanelet2_map.osm", - geographic_msgs::build() - .latitude(35.22312494055522) - .longitude(138.8024583466017) - .altitude(0.0)); { const auto pose_from = traffic_simulator::toCanonicalizedLaneletPose( makePose(81592.96, 49997.94, 100.0), false, hdmap_utils_ptr); + ASSERT_TRUE(pose_from.has_value()); const auto pose_to = traffic_simulator::toCanonicalizedLaneletPose( makePose(81570.56, 50141.75, 100.0), false, hdmap_utils_ptr); - constexpr double approx_distance = 145.0; - constexpr double tolerance = 1.0; + ASSERT_TRUE(pose_from.has_value()); + const auto result = traffic_simulator::distance::longitudinalDistance( pose_from.value(), pose_to.value(), false, false, true, hdmap_utils_ptr); ASSERT_TRUE(result.has_value()); - EXPECT_NEAR(result.value(), approx_distance, tolerance); + EXPECT_NEAR(result.value(), 145.0, 1.0); } { const auto pose_from = traffic_simulator::toCanonicalizedLaneletPose( makePose(81587.31, 50165.57, 100.0), false, hdmap_utils_ptr); + ASSERT_TRUE(pose_from.has_value()); const auto pose_to = traffic_simulator::toCanonicalizedLaneletPose( makePose(81610.25, 49988.59, 100.0), false, hdmap_utils_ptr); - constexpr double approx_distance = 178.0; - constexpr double tolerance = 1.0; + ASSERT_TRUE(pose_from.has_value()); + const auto result = traffic_simulator::distance::longitudinalDistance( pose_from.value(), pose_to.value(), false, false, true, hdmap_utils_ptr); ASSERT_TRUE(result.has_value()); - EXPECT_NEAR(result.value(), approx_distance, tolerance); + EXPECT_NEAR(result.value(), 178.0, 1.0); } } /** - * @note Test calculation correctness with include_adjacent_lanelet = true, - * include_opposite_direction = false, allow_lane_change = true - * in an impossible scenario, e.g. no path. - */ -TEST(distance, longitudinalDistance_adjacent_noOpposite_change_false) {} - -/** - * @note Test calculation correctness with include_adjacent_lanelet = true, + * @note Test calculation correctness with include_adjacent_lanelet = false, * include_opposite_direction = false, allow_lane_change = true * in a scenario that meets those criteria. */ -TEST(distance, longitudinalDistance_adjacent_noOpposite_change) {} +TEST_F(distanceTest_Intersection, longitudinalDistance_noAdjacent_noOpposite_change_case1) +{ + { + const auto pose_from = traffic_simulator::toCanonicalizedLaneletPose( + makePose(86627.71, 44972.06, 340.0), false, hdmap_utils_ptr); + ASSERT_TRUE(pose_from.has_value()); + const auto pose_to = traffic_simulator::toCanonicalizedLaneletPose( + makePose(86647.23, 44882.51, 240.0), false, hdmap_utils_ptr); + ASSERT_TRUE(pose_from.has_value()); -/** - * @note Test calculation correctness with include_adjacent_lanelet = true, - * include_opposite_direction = true, allow_lane_change = false - * in an impossible scenario, e.g. no path. - */ -TEST(distance, longitudinalDistance_adjacent_opposite_noChange_false) {} + const auto result = traffic_simulator::distance::longitudinalDistance( + pose_from.value(), pose_to.value(), false, false, true, hdmap_utils_ptr); + EXPECT_TRUE(result.has_value()); + } + { + const auto pose_from = traffic_simulator::toCanonicalizedLaneletPose( + makePose(86555.38, 45000.88, 340.0), false, hdmap_utils_ptr); + ASSERT_TRUE(pose_from.has_value()); + const auto pose_to = traffic_simulator::toCanonicalizedLaneletPose( + makePose(86647.23, 44882.51, 240.0), false, hdmap_utils_ptr); + ASSERT_TRUE(pose_from.has_value()); -/** - * @note Test calculation correctness with include_adjacent_lanelet = true, - * include_opposite_direction = true, allow_lane_change = false - * in a scenario that meets those criteria. - */ -TEST(distance, longitudinalDistance_adjacent_opposite_noChange) {} + const auto result = traffic_simulator::distance::longitudinalDistance( + pose_from.value(), pose_to.value(), false, false, true, hdmap_utils_ptr); + EXPECT_TRUE(result.has_value()); + } + { + const auto pose_from = traffic_simulator::toCanonicalizedLaneletPose( + makePose(86788.82, 44993.77, 210.0), false, hdmap_utils_ptr); + ASSERT_TRUE(pose_from.has_value()); + const auto pose_to = traffic_simulator::toCanonicalizedLaneletPose( + makePose(86553.48, 44990.56, 150.0), false, hdmap_utils_ptr); + ASSERT_TRUE(pose_from.has_value()); + + const auto result = traffic_simulator::distance::longitudinalDistance( + pose_from.value(), pose_to.value(), false, false, true, hdmap_utils_ptr); + EXPECT_TRUE(result.has_value()); + } + { + const auto pose_from = traffic_simulator::toCanonicalizedLaneletPose( + makePose(86787.85, 44998.44, 210.0), false, hdmap_utils_ptr); + ASSERT_TRUE(pose_from.has_value()); + const auto pose_to = traffic_simulator::toCanonicalizedLaneletPose( + makePose(86648.95, 44884.04, 240.0), false, hdmap_utils_ptr); + ASSERT_TRUE(pose_from.has_value()); + + const auto result = traffic_simulator::distance::longitudinalDistance( + pose_from.value(), pose_to.value(), false, false, true, hdmap_utils_ptr); + EXPECT_TRUE(result.has_value()); + } +} /** * @note Test calculation correctness with include_adjacent_lanelet = true, - * include_opposite_direction = true, allow_lane_change = true + * include_opposite_direction = false, allow_lane_change = true * in an impossible scenario, e.g. no path. */ -TEST(distance, longitudinalDistance_adjacent_opposite_change_false) {} +TEST_F(distanceTest_Intersection, longitudinalDistance_adjacent_noOpposite_change_false) +{ + { + const auto pose_from = traffic_simulator::toCanonicalizedLaneletPose( + makePose(86736.13, 44969.63, 210.0), false, hdmap_utils_ptr); + ASSERT_TRUE(pose_from.has_value()); + const auto pose_to = traffic_simulator::toCanonicalizedLaneletPose( + makePose(86642.95, 44958.78, 340.0), false, hdmap_utils_ptr); + ASSERT_TRUE(pose_from.has_value()); + + const auto result = traffic_simulator::distance::longitudinalDistance( + pose_from.value(), pose_to.value(), true, false, true, hdmap_utils_ptr); + EXPECT_FALSE(result.has_value()); + } + { + const auto pose_from = traffic_simulator::toCanonicalizedLaneletPose( + makePose(86732.06, 44976.58, 210.0), false, hdmap_utils_ptr); + ASSERT_TRUE(pose_from.has_value()); + const auto pose_to = traffic_simulator::toCanonicalizedLaneletPose( + makePose(86704.59, 44927.32, 340.0), false, hdmap_utils_ptr); + ASSERT_TRUE(pose_from.has_value()); + + const auto result = traffic_simulator::distance::longitudinalDistance( + pose_from.value(), pose_to.value(), true, false, true, hdmap_utils_ptr); + EXPECT_FALSE(result.has_value()); + } +} /** * @note Test calculation correctness with include_adjacent_lanelet = true, - * include_opposite_direction = true, allow_lane_change = true + * include_opposite_direction = false, allow_lane_change = true * in a scenario that meets those criteria. */ -TEST(distance, longitudinalDistance_adjacent_opposite_change) {} +TEST_F(distanceTest_Intersection, longitudinalDistance_adjacent_noOpposite_change) +{ + { + const auto pose_from = traffic_simulator::toCanonicalizedLaneletPose( + makePose(86637.19, 44967.35, 340.0), false, hdmap_utils_ptr); + const auto pose_to = traffic_simulator::toCanonicalizedLaneletPose( + makePose(86648.82, 44886.19, 240.0), false, hdmap_utils_ptr); + + const auto result = traffic_simulator::distance::longitudinalDistance( + pose_from.value(), pose_to.value(), true, false, true, hdmap_utils_ptr); + ASSERT_TRUE(result.has_value()); + EXPECT_NEAR(result.value(), 103.0, 1.0); + } + { + const auto pose_from = traffic_simulator::toCanonicalizedLaneletPose( + makePose(86719.94, 44957.20, 210.0), false, hdmap_utils_ptr); + ASSERT_TRUE(pose_from.has_value()); + const auto pose_to = traffic_simulator::toCanonicalizedLaneletPose( + makePose(86599.32, 44975.01, 180.0), false, hdmap_utils_ptr); + ASSERT_TRUE(pose_from.has_value()); + + const auto result = traffic_simulator::distance::longitudinalDistance( + pose_from.value(), pose_to.value(), true, false, true, hdmap_utils_ptr); + ASSERT_TRUE(result.has_value()); + EXPECT_NEAR(result.value(), 131.0, 1.0); + } +} From 059a7c1758afd6ef95217a868bfc69da4d10ef11 Mon Sep 17 00:00:00 2001 From: robomic Date: Thu, 5 Sep 2024 11:36:46 +0200 Subject: [PATCH 222/304] remove redundant constructor call --- .../test/src/hdmap_utils/test_hdmap_utils.cpp | 25 ++++++++++--------- 1 file changed, 13 insertions(+), 12 deletions(-) diff --git a/simulation/traffic_simulator/test/src/hdmap_utils/test_hdmap_utils.cpp b/simulation/traffic_simulator/test/src/hdmap_utils/test_hdmap_utils.cpp index b0bd92f0569..26b5efaa132 100644 --- a/simulation/traffic_simulator/test/src/hdmap_utils/test_hdmap_utils.cpp +++ b/simulation/traffic_simulator/test/src/hdmap_utils/test_hdmap_utils.cpp @@ -34,13 +34,13 @@ class HdMapUtilsTest_StandardMap : public testing::Test { protected: HdMapUtilsTest_StandardMap() - : hdmap_utils(hdmap_utils::HdMapUtils( + : hdmap_utils( ament_index_cpp::get_package_share_directory("traffic_simulator") + "/map/standard_map/lanelet2_map.osm", geographic_msgs::build() .latitude(35.61836750154) .longitude(139.78066608243) - .altitude(0.0))) + .altitude(0.0)) { } @@ -50,13 +50,13 @@ class HdMapUtilsTest_WithRoadShoulderMap : public testing::Test { protected: HdMapUtilsTest_WithRoadShoulderMap() - : hdmap_utils(hdmap_utils::HdMapUtils( + : hdmap_utils( ament_index_cpp::get_package_share_directory("traffic_simulator") + "/map/with_road_shoulder/lanelet2_map.osm", geographic_msgs::build() .latitude(35.61836750154) .longitude(139.78066608243) - .altitude(0.0))) + .altitude(0.0)) { } @@ -66,13 +66,13 @@ class HdMapUtilsTest_EmptyMap : public testing::Test { protected: HdMapUtilsTest_EmptyMap() - : hdmap_utils(hdmap_utils::HdMapUtils( + : hdmap_utils( ament_index_cpp::get_package_share_directory("traffic_simulator") + "/map/empty/lanelet2_map.osm", geographic_msgs::build() .latitude(0.0) .longitude(0.0) - .altitude(0.0))) + .altitude(0.0)) { } @@ -82,13 +82,13 @@ class HdMapUtilsTest_FourTrackHighwayMap : public testing::Test { protected: HdMapUtilsTest_FourTrackHighwayMap() - : hdmap_utils(hdmap_utils::HdMapUtils( + : hdmap_utils( ament_index_cpp::get_package_share_directory("traffic_simulator") + "/map/four_track_highway/lanelet2_map.osm", geographic_msgs::build() .latitude(35.22312494055522) .longitude(138.8024583466017) - .altitude(0.0))) + .altitude(0.0)) { } @@ -98,13 +98,13 @@ class HdMapUtilsTest_CrossroadsWithStoplinesMap : public testing::Test { protected: HdMapUtilsTest_CrossroadsWithStoplinesMap() - : hdmap_utils(hdmap_utils::HdMapUtils( + : hdmap_utils( ament_index_cpp::get_package_share_directory("traffic_simulator") + "/map/crossroads_with_stoplines/lanelet2_map.osm", geographic_msgs::build() .latitude(35.23808753540768) .longitude(139.9009591876285) - .altitude(0.0))) + .altitude(0.0)) { } @@ -114,17 +114,18 @@ class HdMapUtilsTest_KashiwanohaMap : public testing::Test { protected: HdMapUtilsTest_KashiwanohaMap() - : hdmap_utils(hdmap_utils::HdMapUtils( + : hdmap_utils( ament_index_cpp::get_package_share_directory("kashiwanoha_map") + "/map/lanelet2_map.osm", geographic_msgs::build() .latitude(0.0) .longitude(0.0) - .altitude(0.0))) + .altitude(0.0)) { } hdmap_utils::HdMapUtils hdmap_utils; }; + /** * @note Test basic functionality. * Test initialization correctness with a correct path to a lanelet map. From 1f6cf08cdb30bc070857221374c7cd1c30e5e06e Mon Sep 17 00:00:00 2001 From: robomic Date: Thu, 5 Sep 2024 16:27:07 +0200 Subject: [PATCH 223/304] distance.cpp bug fixes, distanceToRightLaneBound tests --- .../traffic_simulator/src/utils/distance.cpp | 8 +- .../test/src/utils/test_distance.cpp | 167 ++++++++++++++++++ 2 files changed, 174 insertions(+), 1 deletion(-) diff --git a/simulation/traffic_simulator/src/utils/distance.cpp b/simulation/traffic_simulator/src/utils/distance.cpp index b6e8e8a9ff8..af12722401e 100644 --- a/simulation/traffic_simulator/src/utils/distance.cpp +++ b/simulation/traffic_simulator/src/utils/distance.cpp @@ -214,6 +214,9 @@ auto distanceToLeftLaneBound( const traffic_simulator_msgs::msg::BoundingBox & bounding_box, const lanelet::Ids & lanelet_ids, const std::shared_ptr & hdmap_utils_ptr) -> double { + if (lanelet_ids.empty()) { + THROW_SEMANTIC_ERROR("Failing to calculate distanceToLeftLaneBound given an empty vector."); + } std::vector distances; std::transform( lanelet_ids.begin(), lanelet_ids.end(), std::back_inserter(distances), [&](auto lanelet_id) { @@ -245,10 +248,13 @@ auto distanceToRightLaneBound( const traffic_simulator_msgs::msg::BoundingBox & bounding_box, const lanelet::Ids & lanelet_ids, const std::shared_ptr & hdmap_utils_ptr) -> double { + if (lanelet_ids.empty()) { + THROW_SEMANTIC_ERROR("Failing to calculate distanceToRightLaneBound for given empty vector."); + } std::vector distances; std::transform( lanelet_ids.begin(), lanelet_ids.end(), std::back_inserter(distances), [&](auto lanelet_id) { - return distanceToLeftLaneBound(map_pose, bounding_box, lanelet_id, hdmap_utils_ptr); + return distanceToRightLaneBound(map_pose, bounding_box, lanelet_id, hdmap_utils_ptr); }); return *std::min_element(distances.begin(), distances.end()); } diff --git a/simulation/traffic_simulator/test/src/utils/test_distance.cpp b/simulation/traffic_simulator/test/src/utils/test_distance.cpp index 3295392590b..31cfb0614c2 100644 --- a/simulation/traffic_simulator/test/src/utils/test_distance.cpp +++ b/simulation/traffic_simulator/test/src/utils/test_distance.cpp @@ -15,7 +15,9 @@ #include #include +#include #include +#include #include #include #include @@ -500,3 +502,168 @@ TEST_F(distanceTest_Intersection, longitudinalDistance_adjacent_noOpposite_chang EXPECT_NEAR(result.value(), 131.0, 1.0); } } + +auto makeBoundingBox( + const double x, const double y, const double x_offset = 0.0, const double y_offset = 0.0) + -> traffic_simulator_msgs::msg::BoundingBox +{ + return traffic_simulator_msgs::build() + .center(geometry_msgs::build().x(x_offset).y(y_offset).z(0.0)) + .dimensions(geometry_msgs::build().x(x).y(y).z(0.0)); +} + +/** + * @note Test equality with math::geometry::getPolygonDistance + * function result on intersecting bounding boxes. + */ +TEST(distance, boundingBoxDistance_intersection) +{ + const auto pose_from = makePose(100.0, 100.0, 0.0); + const auto pose_to = makePose(120.0, 100.0, 90.0); + const auto bounding_box_from = makeBoundingBox(30.0, 1.0); + const auto bounding_box_to = makeBoundingBox(1.0, 30.0); + + const auto result = traffic_simulator::distance::boundingBoxDistance( + pose_from, bounding_box_from, pose_to, bounding_box_to); + const auto actual = + math::geometry::getPolygonDistance(pose_from, bounding_box_from, pose_to, bounding_box_to); + EXPECT_FALSE(result.has_value()); + EXPECT_FALSE(actual.has_value()); +} + +/** + * @note Test equality with math::geometry::getPolygonDistance + * function result on disjoint bounding boxes. + */ +TEST(distance, boundingBoxDistance_disjoint) +{ + const auto pose_from = makePose(100.0, 100.0, 0.0); + const auto pose_to = makePose(120.0, 100.0, 90.0); + const auto bounding_box_from = makeBoundingBox(1.0, 30.0); + const auto bounding_box_to = makeBoundingBox(30.0, 1.0); + + const auto result = traffic_simulator::distance::boundingBoxDistance( + pose_from, bounding_box_from, pose_to, bounding_box_to); + const auto actual = + math::geometry::getPolygonDistance(pose_from, bounding_box_from, pose_to, bounding_box_to); + ASSERT_TRUE(result.has_value()); + ASSERT_TRUE(actual.has_value()); + EXPECT_NEAR(actual.value(), result.value(), std::numeric_limits::epsilon()); +} + +/** + * @note Test calculation correctness with lanelet::Id. + */ +TEST_F(distanceTest_StandardMap, distanceToLeftLaneBound_single) +{ + constexpr lanelet::Id lanelet_id = 34741L; + constexpr double tolerance = 0.1; + { + const auto pose = makePose(3818.33, 73726.18, 30.0); + const auto bounding_box = makeBoundingBox(0.1, 0.1, 0.0, 0.0); + const auto result = traffic_simulator::distance::distanceToLeftLaneBound( + pose, bounding_box, lanelet_id, hdmap_utils_ptr); + EXPECT_NEAR(result, 0.5, tolerance); + } + { + const auto pose = makePose(3816.89, 73723.09, 30.0); + const auto bounding_box = makeBoundingBox(0.1, 0.1, 0.0, 0.0); + const auto result = traffic_simulator::distance::distanceToLeftLaneBound( + pose, bounding_box, lanelet_id, hdmap_utils_ptr); + EXPECT_NEAR(result, 2.6, tolerance); + } + { + const auto pose = makePose(3813.42, 73721.11, 30.0); + const auto bounding_box = makeBoundingBox(3.0, 0.1, 0.0, 0.0); + const auto result = traffic_simulator::distance::distanceToLeftLaneBound( + pose, bounding_box, lanelet_id, hdmap_utils_ptr); + EXPECT_NEAR(result, 2.7, tolerance); + } + { + const auto pose = makePose(3813.42, 73721.11, 120.0); + const auto bounding_box = makeBoundingBox(3.0, 0.1, 0.0, 0.0); + const auto result = traffic_simulator::distance::distanceToLeftLaneBound( + pose, bounding_box, lanelet_id, hdmap_utils_ptr); + EXPECT_NEAR(result, 1.3, tolerance); + } + { + const auto pose = makePose(3810.99, 73721.40, 30.0); + const auto bounding_box = makeBoundingBox(0.1, 0.1, 1.0, 0.0); + const auto result = traffic_simulator::distance::distanceToLeftLaneBound( + pose, bounding_box, lanelet_id, hdmap_utils_ptr); + EXPECT_NEAR(result, 1.4, tolerance); + } + { + const auto pose = makePose(3810.99, 73721.40, 30.0); + const auto bounding_box = makeBoundingBox(0.1, 0.1, 0.0, -1.0); + const auto result = traffic_simulator::distance::distanceToLeftLaneBound( + pose, bounding_box, lanelet_id, hdmap_utils_ptr); + EXPECT_NEAR(result, 2.4, tolerance); + } + { + const auto pose = makePose(3680.81, 73757.27, 30.0); + const auto bounding_box = makeBoundingBox(0.1, 0.1, 0.0, 0.0); + const auto result = traffic_simulator::distance::distanceToLeftLaneBound( + pose, bounding_box, 34684L, hdmap_utils_ptr); + EXPECT_NEAR(result, 5.1, tolerance); + } + { + const auto pose = makePose(3692.79, 73753.00, 30.0); + const auto bounding_box = makeBoundingBox(0.1, 0.1, 0.0, 0.0); + const auto result = traffic_simulator::distance::distanceToLeftLaneBound( + pose, bounding_box, 34684L, hdmap_utils_ptr); + EXPECT_NEAR(result, 7.2, tolerance); + } +} + +/** + * @note Test calculation correctness with a vector containing multiple lanelets. + * Test equality with the minimum of distanceToLeftLaneBound results (lanelet::Id overload). + */ +TEST_F(distanceTest_StandardMap, distanceToLeftLaneBound_multipleVector) +{ + const auto lanelet_ids = lanelet::Ids{34603L, 34600L, 34621L, 34741L}; + const auto pose = makePose(3836.16, 73757.99, 120.0); + const auto bounding_box = makeBoundingBox(0.1, 0.1, 0.0, 0.0); + const auto actual_distance = std::transform_reduce( + lanelet_ids.cbegin(), lanelet_ids.cend(), std::numeric_limits::max(), + [](const double lhs, const double rhs) { return std::min(lhs, rhs); }, + [&pose, &bounding_box, this](lanelet::Id lanelet_id) { + return traffic_simulator::distance::distanceToLeftLaneBound( + pose, bounding_box, lanelet_id, hdmap_utils_ptr); + }); + const auto result_distance = traffic_simulator::distance::distanceToLeftLaneBound( + pose, bounding_box, lanelet_ids, hdmap_utils_ptr); + EXPECT_NEAR(actual_distance, result_distance, std::numeric_limits::epsilon()); + EXPECT_NEAR(result_distance, 1.4, 0.1); +} + +/** + * @note Test calculation correctness with a vector containing a single lanelet. + * Test equality with the distanceToLeftLaneBound results (lanelet::Id overload). + */ +TEST_F(distanceTest_StandardMap, distanceToLeftLaneBound_singleVector) +{ + constexpr lanelet::Id lanelet_id = 34426L; + const auto pose = makePose(3693.34, 73738.37, 300.0); + const auto bounding_box = makeBoundingBox(0.1, 0.1, 0.0, 0.0); + const auto actual_distance = traffic_simulator::distance::distanceToLeftLaneBound( + pose, bounding_box, lanelet_id, hdmap_utils_ptr); + const auto result_distance = traffic_simulator::distance::distanceToLeftLaneBound( + pose, bounding_box, {lanelet_id}, hdmap_utils_ptr); + EXPECT_NEAR(actual_distance, result_distance, std::numeric_limits::epsilon()); + EXPECT_NEAR(result_distance, 1.8, 0.1); +} + +/** + * @note Test function behavior with an empty vector. + */ +TEST_F(distanceTest_StandardMap, distanceToRightLaneBound_emptyVector) +{ + const auto pose = makePose(3825.87, 73773.08, 135.0); + const auto bounding_box = makeBoundingBox(0.1, 0.1, 0.0, 0.0); + EXPECT_THROW( + traffic_simulator::distance::distanceToLeftLaneBound( + pose, bounding_box, lanelet::Ids{}, hdmap_utils_ptr), + common::SemanticError); +} From 545dec6da89910d5c36fbea323adb0b92c7dd06e Mon Sep 17 00:00:00 2001 From: robomic Date: Fri, 6 Sep 2024 10:18:41 +0200 Subject: [PATCH 224/304] distanceToRightLaneBound tests, cleanup --- .../test/src/utils/test_distance.cpp | 164 +++++++++++++++--- 1 file changed, 141 insertions(+), 23 deletions(-) diff --git a/simulation/traffic_simulator/test/src/utils/test_distance.cpp b/simulation/traffic_simulator/test/src/utils/test_distance.cpp index 31cfb0614c2..2a05446490b 100644 --- a/simulation/traffic_simulator/test/src/utils/test_distance.cpp +++ b/simulation/traffic_simulator/test/src/utils/test_distance.cpp @@ -523,12 +523,12 @@ TEST(distance, boundingBoxDistance_intersection) const auto bounding_box_from = makeBoundingBox(30.0, 1.0); const auto bounding_box_to = makeBoundingBox(1.0, 30.0); - const auto result = traffic_simulator::distance::boundingBoxDistance( + const auto result_distance = traffic_simulator::distance::boundingBoxDistance( pose_from, bounding_box_from, pose_to, bounding_box_to); - const auto actual = + const auto actual_distance = math::geometry::getPolygonDistance(pose_from, bounding_box_from, pose_to, bounding_box_to); - EXPECT_FALSE(result.has_value()); - EXPECT_FALSE(actual.has_value()); + EXPECT_FALSE(result_distance.has_value()); + EXPECT_FALSE(actual_distance.has_value()); } /** @@ -542,13 +542,14 @@ TEST(distance, boundingBoxDistance_disjoint) const auto bounding_box_from = makeBoundingBox(1.0, 30.0); const auto bounding_box_to = makeBoundingBox(30.0, 1.0); - const auto result = traffic_simulator::distance::boundingBoxDistance( + const auto result_distance = traffic_simulator::distance::boundingBoxDistance( pose_from, bounding_box_from, pose_to, bounding_box_to); - const auto actual = + const auto actual_distance = math::geometry::getPolygonDistance(pose_from, bounding_box_from, pose_to, bounding_box_to); - ASSERT_TRUE(result.has_value()); - ASSERT_TRUE(actual.has_value()); - EXPECT_NEAR(actual.value(), result.value(), std::numeric_limits::epsilon()); + ASSERT_TRUE(result_distance.has_value()); + ASSERT_TRUE(actual_distance.has_value()); + EXPECT_NEAR( + actual_distance.value(), result_distance.value(), std::numeric_limits::epsilon()); } /** @@ -561,56 +562,56 @@ TEST_F(distanceTest_StandardMap, distanceToLeftLaneBound_single) { const auto pose = makePose(3818.33, 73726.18, 30.0); const auto bounding_box = makeBoundingBox(0.1, 0.1, 0.0, 0.0); - const auto result = traffic_simulator::distance::distanceToLeftLaneBound( + const double result = traffic_simulator::distance::distanceToLeftLaneBound( pose, bounding_box, lanelet_id, hdmap_utils_ptr); EXPECT_NEAR(result, 0.5, tolerance); } { const auto pose = makePose(3816.89, 73723.09, 30.0); const auto bounding_box = makeBoundingBox(0.1, 0.1, 0.0, 0.0); - const auto result = traffic_simulator::distance::distanceToLeftLaneBound( + const double result = traffic_simulator::distance::distanceToLeftLaneBound( pose, bounding_box, lanelet_id, hdmap_utils_ptr); EXPECT_NEAR(result, 2.6, tolerance); } { const auto pose = makePose(3813.42, 73721.11, 30.0); const auto bounding_box = makeBoundingBox(3.0, 0.1, 0.0, 0.0); - const auto result = traffic_simulator::distance::distanceToLeftLaneBound( + const double result = traffic_simulator::distance::distanceToLeftLaneBound( pose, bounding_box, lanelet_id, hdmap_utils_ptr); EXPECT_NEAR(result, 2.7, tolerance); } { const auto pose = makePose(3813.42, 73721.11, 120.0); const auto bounding_box = makeBoundingBox(3.0, 0.1, 0.0, 0.0); - const auto result = traffic_simulator::distance::distanceToLeftLaneBound( + const double result = traffic_simulator::distance::distanceToLeftLaneBound( pose, bounding_box, lanelet_id, hdmap_utils_ptr); EXPECT_NEAR(result, 1.3, tolerance); } { const auto pose = makePose(3810.99, 73721.40, 30.0); const auto bounding_box = makeBoundingBox(0.1, 0.1, 1.0, 0.0); - const auto result = traffic_simulator::distance::distanceToLeftLaneBound( + const double result = traffic_simulator::distance::distanceToLeftLaneBound( pose, bounding_box, lanelet_id, hdmap_utils_ptr); EXPECT_NEAR(result, 1.4, tolerance); } { const auto pose = makePose(3810.99, 73721.40, 30.0); const auto bounding_box = makeBoundingBox(0.1, 0.1, 0.0, -1.0); - const auto result = traffic_simulator::distance::distanceToLeftLaneBound( + const double result = traffic_simulator::distance::distanceToLeftLaneBound( pose, bounding_box, lanelet_id, hdmap_utils_ptr); EXPECT_NEAR(result, 2.4, tolerance); } { const auto pose = makePose(3680.81, 73757.27, 30.0); const auto bounding_box = makeBoundingBox(0.1, 0.1, 0.0, 0.0); - const auto result = traffic_simulator::distance::distanceToLeftLaneBound( + const double result = traffic_simulator::distance::distanceToLeftLaneBound( pose, bounding_box, 34684L, hdmap_utils_ptr); EXPECT_NEAR(result, 5.1, tolerance); } { const auto pose = makePose(3692.79, 73753.00, 30.0); const auto bounding_box = makeBoundingBox(0.1, 0.1, 0.0, 0.0); - const auto result = traffic_simulator::distance::distanceToLeftLaneBound( + const double result = traffic_simulator::distance::distanceToLeftLaneBound( pose, bounding_box, 34684L, hdmap_utils_ptr); EXPECT_NEAR(result, 7.2, tolerance); } @@ -625,14 +626,14 @@ TEST_F(distanceTest_StandardMap, distanceToLeftLaneBound_multipleVector) const auto lanelet_ids = lanelet::Ids{34603L, 34600L, 34621L, 34741L}; const auto pose = makePose(3836.16, 73757.99, 120.0); const auto bounding_box = makeBoundingBox(0.1, 0.1, 0.0, 0.0); - const auto actual_distance = std::transform_reduce( + const double actual_distance = std::transform_reduce( lanelet_ids.cbegin(), lanelet_ids.cend(), std::numeric_limits::max(), [](const double lhs, const double rhs) { return std::min(lhs, rhs); }, - [&pose, &bounding_box, this](lanelet::Id lanelet_id) { + [&pose, &bounding_box, this](const lanelet::Id lanelet_id) { return traffic_simulator::distance::distanceToLeftLaneBound( pose, bounding_box, lanelet_id, hdmap_utils_ptr); }); - const auto result_distance = traffic_simulator::distance::distanceToLeftLaneBound( + const double result_distance = traffic_simulator::distance::distanceToLeftLaneBound( pose, bounding_box, lanelet_ids, hdmap_utils_ptr); EXPECT_NEAR(actual_distance, result_distance, std::numeric_limits::epsilon()); EXPECT_NEAR(result_distance, 1.4, 0.1); @@ -647,9 +648,9 @@ TEST_F(distanceTest_StandardMap, distanceToLeftLaneBound_singleVector) constexpr lanelet::Id lanelet_id = 34426L; const auto pose = makePose(3693.34, 73738.37, 300.0); const auto bounding_box = makeBoundingBox(0.1, 0.1, 0.0, 0.0); - const auto actual_distance = traffic_simulator::distance::distanceToLeftLaneBound( + const double actual_distance = traffic_simulator::distance::distanceToLeftLaneBound( pose, bounding_box, lanelet_id, hdmap_utils_ptr); - const auto result_distance = traffic_simulator::distance::distanceToLeftLaneBound( + const double result_distance = traffic_simulator::distance::distanceToLeftLaneBound( pose, bounding_box, {lanelet_id}, hdmap_utils_ptr); EXPECT_NEAR(actual_distance, result_distance, std::numeric_limits::epsilon()); EXPECT_NEAR(result_distance, 1.8, 0.1); @@ -658,7 +659,7 @@ TEST_F(distanceTest_StandardMap, distanceToLeftLaneBound_singleVector) /** * @note Test function behavior with an empty vector. */ -TEST_F(distanceTest_StandardMap, distanceToRightLaneBound_emptyVector) +TEST_F(distanceTest_StandardMap, distanceToLeftLaneBound_emptyVector) { const auto pose = makePose(3825.87, 73773.08, 135.0); const auto bounding_box = makeBoundingBox(0.1, 0.1, 0.0, 0.0); @@ -667,3 +668,120 @@ TEST_F(distanceTest_StandardMap, distanceToRightLaneBound_emptyVector) pose, bounding_box, lanelet::Ids{}, hdmap_utils_ptr), common::SemanticError); } + +/** + * @note Test calculation correctness with lanelet::Id. + */ +TEST_F(distanceTest_Intersection, distanceToRightLaneBound_single) +{ + constexpr lanelet::Id lanelet_id = 660L; + constexpr double tolerance = 0.1; + { + const auto pose = makePose(86651.84, 44941.47, 135.0); + const auto bounding_box = makeBoundingBox(0.1, 0.1, 0.0, 0.0); + const double result = traffic_simulator::distance::distanceToRightLaneBound( + pose, bounding_box, lanelet_id, hdmap_utils_ptr); + EXPECT_NEAR(result, 4.1, tolerance); + } + { + const auto pose = makePose(86653.05, 44946.74, 135.0); + const auto bounding_box = makeBoundingBox(0.1, 0.1, 0.0, 0.0); + const double result = traffic_simulator::distance::distanceToRightLaneBound( + pose, bounding_box, lanelet_id, hdmap_utils_ptr); + EXPECT_NEAR(result, 0.6, tolerance); + } + { + const auto pose = makePose(86651.47, 44941.07, 120.0); + const auto bounding_box = makeBoundingBox(3.0, 0.1, 0.0, 0.0); + const double result = traffic_simulator::distance::distanceToRightLaneBound( + pose, bounding_box, lanelet_id, hdmap_utils_ptr); + EXPECT_NEAR(result, 4.3, tolerance); + } + { + const auto pose = makePose(86651.47, 44941.07, 210.0); + const auto bounding_box = makeBoundingBox(3.0, 0.1, 0.0, 0.0); + const double result = traffic_simulator::distance::distanceToRightLaneBound( + pose, bounding_box, lanelet_id, hdmap_utils_ptr); + EXPECT_NEAR(result, 3.1, tolerance); + } + { + const auto pose = makePose(86644.10, 44951.86, 150.0); + const auto bounding_box = makeBoundingBox(0.1, 0.1, 1.0, 0.0); + const double result = traffic_simulator::distance::distanceToRightLaneBound( + pose, bounding_box, lanelet_id, hdmap_utils_ptr); + EXPECT_NEAR(result, 2.0, tolerance); + } + { + const auto pose = makePose(86644.10, 44951.86, 150.0); + const auto bounding_box = makeBoundingBox(0.1, 0.1, 0.0, -1.0); + const double result = traffic_simulator::distance::distanceToRightLaneBound( + pose, bounding_box, lanelet_id, hdmap_utils_ptr); + EXPECT_NEAR(result, 1.1, tolerance); + } + { + const auto pose = makePose(86644.11, 44941.21, 0.0); + const auto bounding_box = makeBoundingBox(0.1, 0.1, 0.0, 0.0); + const double result = traffic_simulator::distance::distanceToRightLaneBound( + pose, bounding_box, lanelet_id, hdmap_utils_ptr); + EXPECT_NEAR(result, 11.2, tolerance); + } + { + const auto pose = makePose(86656.83, 44946.96, 0.0); + const auto bounding_box = makeBoundingBox(0.1, 0.1, 0.0, 0.0); + const double result = traffic_simulator::distance::distanceToRightLaneBound( + pose, bounding_box, lanelet_id, hdmap_utils_ptr); + EXPECT_NEAR(result, 2.6, tolerance); + } +} + +/** + * @note Test calculation correctness with a vector containing multiple lanelets. + * Test equality with the minimum of distanceToRightLaneBound results (lanelet::Id overload). + */ +TEST_F(distanceTest_Intersection, distanceToRightLaneBound_multipleVector) +{ + const auto lanelet_ids = lanelet::Ids{660L, 663L, 684L, 654L, 686L}; + const auto pose = makePose(86642.05, 44902.61, 60.0); + const auto bounding_box = makeBoundingBox(0.1, 0.1, 0.0, 0.0); + const double actual_distance = std::transform_reduce( + lanelet_ids.cbegin(), lanelet_ids.cend(), std::numeric_limits::max(), + [](const double lhs, const double rhs) { return std::min(lhs, rhs); }, + [&pose, &bounding_box, this](const lanelet::Id lanelet_id) { + return traffic_simulator::distance::distanceToRightLaneBound( + pose, bounding_box, lanelet_id, hdmap_utils_ptr); + }); + const double result_distance = traffic_simulator::distance::distanceToRightLaneBound( + pose, bounding_box, lanelet_ids, hdmap_utils_ptr); + EXPECT_NEAR(actual_distance, result_distance, std::numeric_limits::epsilon()); + EXPECT_NEAR(result_distance, 2.7, 0.1); +} + +/** + * @note Test calculation correctness with a vector containing a single lanelet. + * Test equality with the distanceToRightLaneBound result (lanelet::Id overload). + */ +TEST_F(distanceTest_Intersection, distanceToRightLaneBound_singleVector) +{ + constexpr lanelet::Id lanelet_id = 654L; + const auto pose = makePose(86702.79, 44929.05, 150.0); + const auto bounding_box = makeBoundingBox(0.1, 0.1, 0.0, 0.0); + const double actual_distance = traffic_simulator::distance::distanceToRightLaneBound( + pose, bounding_box, lanelet_id, hdmap_utils_ptr); + const double result_distance = traffic_simulator::distance::distanceToRightLaneBound( + pose, bounding_box, {lanelet_id}, hdmap_utils_ptr); + EXPECT_NEAR(actual_distance, result_distance, std::numeric_limits::epsilon()); + EXPECT_NEAR(result_distance, 2.4, 0.1); +} + +/** + * @note Test function behavior with an empty vector. + */ +TEST_F(distanceTest_Intersection, distanceToRightLaneBound_emptyVector) +{ + const auto pose = makePose(3825.87, 73773.08, 135.0); + const auto bounding_box = makeBoundingBox(0.1, 0.1, 0.0, 0.0); + EXPECT_THROW( + traffic_simulator::distance::distanceToRightLaneBound( + pose, bounding_box, lanelet::Ids{}, hdmap_utils_ptr), + common::SemanticError); +} From 724a87c7ee16ad3d26693ad2968ba30380e5507f Mon Sep 17 00:00:00 2001 From: robomic Date: Fri, 6 Sep 2024 10:19:50 +0200 Subject: [PATCH 225/304] remove the failing case --- .../test/src/utils/test_distance.cpp | 59 +------------------ 1 file changed, 1 insertion(+), 58 deletions(-) diff --git a/simulation/traffic_simulator/test/src/utils/test_distance.cpp b/simulation/traffic_simulator/test/src/utils/test_distance.cpp index 2a05446490b..f312ce3184e 100644 --- a/simulation/traffic_simulator/test/src/utils/test_distance.cpp +++ b/simulation/traffic_simulator/test/src/utils/test_distance.cpp @@ -350,7 +350,7 @@ TEST_F(distanceTest_FourTrackHighway, longitudinalDistance_noAdjacent_noOpposite * include_opposite_direction = false, allow_lane_change = true * in a scenario that meets those criteria. */ -TEST_F(distanceTest_FourTrackHighway, longitudinalDistance_noAdjacent_noOpposite_change_case0) +TEST_F(distanceTest_FourTrackHighway, longitudinalDistance_noAdjacent_noOpposite_change) { { const auto pose_from = traffic_simulator::toCanonicalizedLaneletPose( @@ -380,63 +380,6 @@ TEST_F(distanceTest_FourTrackHighway, longitudinalDistance_noAdjacent_noOpposite } } -/** - * @note Test calculation correctness with include_adjacent_lanelet = false, - * include_opposite_direction = false, allow_lane_change = true - * in a scenario that meets those criteria. - */ -TEST_F(distanceTest_Intersection, longitudinalDistance_noAdjacent_noOpposite_change_case1) -{ - { - const auto pose_from = traffic_simulator::toCanonicalizedLaneletPose( - makePose(86627.71, 44972.06, 340.0), false, hdmap_utils_ptr); - ASSERT_TRUE(pose_from.has_value()); - const auto pose_to = traffic_simulator::toCanonicalizedLaneletPose( - makePose(86647.23, 44882.51, 240.0), false, hdmap_utils_ptr); - ASSERT_TRUE(pose_from.has_value()); - - const auto result = traffic_simulator::distance::longitudinalDistance( - pose_from.value(), pose_to.value(), false, false, true, hdmap_utils_ptr); - EXPECT_TRUE(result.has_value()); - } - { - const auto pose_from = traffic_simulator::toCanonicalizedLaneletPose( - makePose(86555.38, 45000.88, 340.0), false, hdmap_utils_ptr); - ASSERT_TRUE(pose_from.has_value()); - const auto pose_to = traffic_simulator::toCanonicalizedLaneletPose( - makePose(86647.23, 44882.51, 240.0), false, hdmap_utils_ptr); - ASSERT_TRUE(pose_from.has_value()); - - const auto result = traffic_simulator::distance::longitudinalDistance( - pose_from.value(), pose_to.value(), false, false, true, hdmap_utils_ptr); - EXPECT_TRUE(result.has_value()); - } - { - const auto pose_from = traffic_simulator::toCanonicalizedLaneletPose( - makePose(86788.82, 44993.77, 210.0), false, hdmap_utils_ptr); - ASSERT_TRUE(pose_from.has_value()); - const auto pose_to = traffic_simulator::toCanonicalizedLaneletPose( - makePose(86553.48, 44990.56, 150.0), false, hdmap_utils_ptr); - ASSERT_TRUE(pose_from.has_value()); - - const auto result = traffic_simulator::distance::longitudinalDistance( - pose_from.value(), pose_to.value(), false, false, true, hdmap_utils_ptr); - EXPECT_TRUE(result.has_value()); - } - { - const auto pose_from = traffic_simulator::toCanonicalizedLaneletPose( - makePose(86787.85, 44998.44, 210.0), false, hdmap_utils_ptr); - ASSERT_TRUE(pose_from.has_value()); - const auto pose_to = traffic_simulator::toCanonicalizedLaneletPose( - makePose(86648.95, 44884.04, 240.0), false, hdmap_utils_ptr); - ASSERT_TRUE(pose_from.has_value()); - - const auto result = traffic_simulator::distance::longitudinalDistance( - pose_from.value(), pose_to.value(), false, false, true, hdmap_utils_ptr); - EXPECT_TRUE(result.has_value()); - } -} - /** * @note Test calculation correctness with include_adjacent_lanelet = true, * include_opposite_direction = false, allow_lane_change = true From 808a4b93ea883d247c7565870ab1c98627d284af Mon Sep 17 00:00:00 2001 From: Grzegorz Maj Date: Wed, 4 Sep 2024 14:25:01 +0200 Subject: [PATCH 226/304] Pose module unit tests --- .../traffic_simulator/test/CMakeLists.txt | 1 + .../test/src/utils/CMakeLists.txt | 2 + .../test/src/utils/test_pose.cpp | 669 ++++++++++++++++++ 3 files changed, 672 insertions(+) create mode 100644 simulation/traffic_simulator/test/src/utils/CMakeLists.txt create mode 100644 simulation/traffic_simulator/test/src/utils/test_pose.cpp diff --git a/simulation/traffic_simulator/test/CMakeLists.txt b/simulation/traffic_simulator/test/CMakeLists.txt index 713c8b40678..eb539f6e7df 100644 --- a/simulation/traffic_simulator/test/CMakeLists.txt +++ b/simulation/traffic_simulator/test/CMakeLists.txt @@ -5,3 +5,4 @@ add_subdirectory(src/behavior) add_subdirectory(src/job) add_subdirectory(src/simulation_clock) add_subdirectory(src/hdmap_utils) +add_subdirectory(src/utils) diff --git a/simulation/traffic_simulator/test/src/utils/CMakeLists.txt b/simulation/traffic_simulator/test/src/utils/CMakeLists.txt new file mode 100644 index 00000000000..8c96fcb2eaa --- /dev/null +++ b/simulation/traffic_simulator/test/src/utils/CMakeLists.txt @@ -0,0 +1,2 @@ +ament_add_gtest(test_pose test_pose.cpp) +target_link_libraries(test_pose traffic_simulator) diff --git a/simulation/traffic_simulator/test/src/utils/test_pose.cpp b/simulation/traffic_simulator/test/src/utils/test_pose.cpp new file mode 100644 index 00000000000..b8182b2617a --- /dev/null +++ b/simulation/traffic_simulator/test/src/utils/test_pose.cpp @@ -0,0 +1,669 @@ +// Copyright 2015 TIER IV, Inc. All rights reserved. +// +// 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. + +#include + +#include + +#include "../helper_functions.hpp" + +int main(int argc, char ** argv) +{ + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} + +class PoseTest : public testing::Test +{ +protected: + PoseTest() + : hdmap_utils(std::make_shared( + ament_index_cpp::get_package_share_directory("traffic_simulator") + + "/map/four_track_highway/lanelet2_map.osm", + geographic_msgs::build() + .latitude(35.22312494055522) + .longitude(138.8024583466017) + .altitude(0.0))) + { + } + + std::shared_ptr hdmap_utils; +}; + +/** + * @note test created object values + */ +TEST(pose, quietNaNPose) +{ + const auto pose = traffic_simulator::pose::quietNaNPose(); + + EXPECT_TRUE(isnan(pose.position.x)); + EXPECT_TRUE(isnan(pose.position.y)); + EXPECT_TRUE(isnan(pose.position.z)); + + EXPECT_EQ(pose.orientation.x, 0); + EXPECT_EQ(pose.orientation.y, 0); + EXPECT_EQ(pose.orientation.z, 0); + EXPECT_EQ(pose.orientation.w, 1); +} + +/** + * @note test created object values + */ +TEST(pose, quietNaNLaneletPose) +{ + const auto pose = traffic_simulator::pose::quietNaNLaneletPose(); + + EXPECT_EQ(pose.lanelet_id, std::numeric_limits::max()); + EXPECT_TRUE(isnan(pose.s)); + EXPECT_TRUE(isnan(pose.offset)); + EXPECT_TRUE(isnan(pose.rpy.x)); + EXPECT_TRUE(isnan(pose.rpy.y)); + EXPECT_TRUE(isnan(pose.rpy.z)); +} + +/** + * @note test canonicalization with a default constructed LaneletPose + */ +TEST_F(PoseTest, canonicalize_default) +{ + const auto pose = + traffic_simulator::pose::canonicalize(traffic_simulator_msgs::msg::LaneletPose(), hdmap_utils); + + EXPECT_FALSE(pose.has_value()); +} + +/** + * @note test canonicalization with an invalid LaneletPose + */ +TEST_F(PoseTest, canonicalize_invalid) +{ + EXPECT_THROW( + traffic_simulator::pose::canonicalize( + traffic_simulator::pose::quietNaNLaneletPose(), hdmap_utils), + std::runtime_error); +} + +/** + * @note test canonicalization with a valid constructed LaneletPose + */ +TEST_F(PoseTest, canonicalize_valid) +{ + const auto pose = traffic_simulator::helper::constructLaneletPose(195, 0.0, 0.0); + std::optional canonicalized_pose; + + EXPECT_NO_THROW(canonicalized_pose = traffic_simulator::pose::canonicalize(pose, hdmap_utils)); + ASSERT_TRUE(canonicalized_pose.has_value()); + EXPECT_LANELET_POSE_EQ( + static_cast(canonicalized_pose.value()), pose); +} + +/** + * @note test conversion to geometry_msgs::msg::Pose from CanonicalizedLaneletPose + */ +TEST_F(PoseTest, toMapPose_CanonicalizedLaneletPose) +{ + const traffic_simulator::lanelet_pose::CanonicalizedLaneletPose canonicalized_pose( + traffic_simulator::helper::constructLaneletPose(195, 0.0, 0.0), hdmap_utils); + + const geometry_msgs::msg::Pose pose = makePose( + makePoint(81585.1622, 50176.9202, 34.2595), + geometry_msgs::build().x(0).y(0).z(-0.6397).w(0.7686)); + + EXPECT_POSE_NEAR(traffic_simulator::pose::toMapPose(canonicalized_pose), pose, 0.01); +} + +/** + * @note test conversion to geometry_msgs::msg::Pose from LaneletPose with HdMapUtils pointer + */ +TEST_F(PoseTest, toMapPose_LaneletPose) +{ + const auto lanelet_pose = traffic_simulator::helper::constructLaneletPose(195, 0.0, 0.0); + + const geometry_msgs::msg::Pose pose = makePose( + makePoint(81585.1622, 50176.9202, 34.2595), + geometry_msgs::build().x(0).y(0).z(-0.6397).w(0.7686)); + + EXPECT_POSE_NEAR(traffic_simulator::pose::toMapPose(lanelet_pose, hdmap_utils), pose, 0.01); +} + +/** + * @note test function behavior with a pose that can be canonicalized + */ +TEST_F(PoseTest, toCanonicalizedLaneletPose_noBoundingBox_noRoute_valid) +{ + const auto lanelet_pose = + traffic_simulator::helper::constructCanonicalizedLaneletPose(195, 0.0, 0.0, hdmap_utils); + + const geometry_msgs::msg::Pose pose = static_cast(lanelet_pose); + + const auto canonicalized_pose = + traffic_simulator::pose::toCanonicalizedLaneletPose(pose, true, hdmap_utils); + + ASSERT_TRUE(canonicalized_pose.has_value()); + EXPECT_POSE_NEAR(pose, static_cast(canonicalized_pose.value()), 0.01); + EXPECT_LANELET_POSE_NEAR( + static_cast(canonicalized_pose.value()), + static_cast(lanelet_pose), 0.01); +} + +/** + * @note test function behavior with a pose that can not be canonicalized + */ +TEST_F(PoseTest, toCanonicalizedLaneletPose_noBoundingBox_noRoute_invalid) +{ + const geometry_msgs::msg::Pose pose = makePose(makePoint(0, 0, 0)); + + EXPECT_EQ( + traffic_simulator::pose::toCanonicalizedLaneletPose(pose, true, hdmap_utils), std::nullopt); +} + +/** + * @note test function behavior with a pose that can be canonicalized + */ +TEST_F(PoseTest, toCanonicalizedLaneletPose_BoundingBox_noRoute_valid) +{ + const auto lanelet_pose = + traffic_simulator::helper::constructCanonicalizedLaneletPose(195, 0.0, 0.0, hdmap_utils); + + const geometry_msgs::msg::Pose pose = static_cast(lanelet_pose); + + const auto canonicalized_pose = traffic_simulator::pose::toCanonicalizedLaneletPose( + pose, makeBoundingBox(), true, 1.0, hdmap_utils); + + ASSERT_TRUE(canonicalized_pose.has_value()); + EXPECT_POSE_NEAR(pose, static_cast(canonicalized_pose.value()), 0.01); + EXPECT_LANELET_POSE_NEAR( + static_cast(canonicalized_pose.value()), + static_cast(lanelet_pose), 0.01); +} + +/** + * @note test function behavior with a pose that can not be canonicalized, matching distance too large + */ +TEST_F(PoseTest, toCanonicalizedLaneletPose_BoundingBox_noRoute_invalid) +{ + const auto lanelet_pose = + traffic_simulator::helper::constructCanonicalizedLaneletPose(195, 10.0, 0.0, hdmap_utils); + + const geometry_msgs::msg::Pose pose = static_cast(lanelet_pose); + + EXPECT_EQ( + traffic_simulator::pose::toCanonicalizedLaneletPose( + pose, makeSmallBoundingBox(), true, 0.0, hdmap_utils), + std::nullopt); +} + +/** + * @note test function behavior with an empty unique_route_lanelets vector and a pose that can not be canonicalized + */ +TEST_F(PoseTest, toCanonicalizedLaneletPose_BoundingBox_route_emptyInvalid) +{ + const geometry_msgs::msg::Pose pose = makePose(makePoint(0, 0, 0)); + + EXPECT_EQ( + traffic_simulator::pose::toCanonicalizedLaneletPose( + pose, makeBoundingBox(), {}, true, 1.0, hdmap_utils), + std::nullopt); +} + +/** + * @note test function behavior with an empty unique_route_lanelets vector and a pose that can be canonicalized + */ +TEST_F(PoseTest, toCanonicalizedLaneletPose_BoundingBox_route_emptyValid) +{ + const auto lanelet_pose = + traffic_simulator::helper::constructCanonicalizedLaneletPose(195, 0.0, 0.0, hdmap_utils); + + const geometry_msgs::msg::Pose pose = static_cast(lanelet_pose); + + const auto canonicalized_pose = traffic_simulator::pose::toCanonicalizedLaneletPose( + pose, makeBoundingBox(), {}, true, 1.0, hdmap_utils); + + ASSERT_TRUE(canonicalized_pose.has_value()); + EXPECT_POSE_NEAR(pose, static_cast(canonicalized_pose.value()), 0.01); + EXPECT_LANELET_POSE_NEAR( + static_cast(canonicalized_pose.value()), + static_cast(lanelet_pose), 0.01); +} + +/** + * @note test function behavior with a non empty unique_route_lanelets vector and a pose that can not be canonicalized + */ +TEST_F(PoseTest, toCanonicalizedLaneletPose_BoundingBox_route_nonEmptyInvalid) +{ + const geometry_msgs::msg::Pose pose = makePose(makePoint(0, 0, 0)); + + EXPECT_EQ( + traffic_simulator::pose::toCanonicalizedLaneletPose( + pose, makeBoundingBox(), {195}, true, 1.0, hdmap_utils), + std::nullopt); +} + +/** + * @note test function behavior with a non empty unique_route_lanelets vector and a pose that can be canonicalized + */ +TEST_F(PoseTest, toCanonicalizedLaneletPose_BoundingBox_route_nonEmptyValid) +{ + const auto lanelet_pose = + traffic_simulator::helper::constructCanonicalizedLaneletPose(195, 0.0, 0.0, hdmap_utils); + + const geometry_msgs::msg::Pose pose = static_cast(lanelet_pose); + + const auto canonicalized_pose = traffic_simulator::pose::toCanonicalizedLaneletPose( + pose, makeBoundingBox(), {195}, true, 1.0, hdmap_utils); + + ASSERT_TRUE(canonicalized_pose.has_value()); + EXPECT_POSE_NEAR(pose, static_cast(canonicalized_pose.value()), 0.01); + EXPECT_LANELET_POSE_NEAR( + static_cast(canonicalized_pose.value()), + static_cast(lanelet_pose), 0.01); +} + +/** + * @note test calculation correctness with a non trivial example + */ +TEST(pose, transformRelativePoseToGlobal) +{ + const geometry_msgs::msg::Pose pose_relative = makePose(makePoint(4.9969, -28.1026, 0.214)); + const geometry_msgs::msg::Pose pose_global = makePose(makePoint(81601.0571, 50099.0981, 34.595)); + const geometry_msgs::msg::Pose pose_rel_global = + makePose(makePoint(81606.054, 50070.9955, 34.809)); + + EXPECT_POSE_EQ( + traffic_simulator::pose::transformRelativePoseToGlobal(pose_global, pose_relative), + pose_rel_global); +} + +/** + * @note test calculation correctness when only one pose is zeroed, the goal is to obtain a pose equal to the second argument + */ +TEST(pose, relativePose_poses_zeros) +{ + const auto from = makePose(makePoint(0, 0, 0)); + const auto to = makePose(makePoint(10, 51, 2)); + const auto relative = traffic_simulator::pose::relativePose(from, to); + + ASSERT_TRUE(relative.has_value()); + EXPECT_POSE_EQ(relative.value(), to); +} + +/** + * @note test calculation correctness when both poses are zeroed + */ +TEST(pose, relativePose_poses_zero) +{ + const auto from = makePose(makePoint(0, 0, 0)); + const auto to = makePose(makePoint(0, 0, 0)); + const auto relative = traffic_simulator::pose::relativePose(from, to); + + ASSERT_TRUE(relative.has_value()); + EXPECT_POSE_EQ(relative.value(), to); +} + +/** + * @note ttest calculation correctness with a non trivial example + */ +TEST(pose, relativePose_poses_complex) +{ + const auto pose_relative = makePose(makePoint(4.9969, -28.1026, 0.214)); + const auto from = makePose(makePoint(81601.0571, 50099.0981, 34.595)); + const auto to = makePose(makePoint(81606.054, 50070.9955, 34.809)); + + const auto relative = traffic_simulator::pose::relativePose(from, to); + + ASSERT_TRUE(relative.has_value()); + EXPECT_POSE_NEAR(pose_relative, relative.value(), 0.01); +} + +/** + * @note test calculation correctness with the overload + */ +TEST_F(PoseTest, relativePose_first) +{ + const auto pose_relative = makePose( + makePoint(9.9999, -0.0009, 0.0126), + geometry_msgs::build().x(0).y(0).z(0).w(1)); + const auto from = makePose( + makePoint(81585.1622, 50176.9202, 34.2595), + geometry_msgs::build().x(0).y(0).z(-0.6397).w(0.7686)); + const auto to = + traffic_simulator::helper::constructCanonicalizedLaneletPose(195, 10.0, 0.0, hdmap_utils); + + const auto relative = traffic_simulator::pose::relativePose(from, to); + + ASSERT_TRUE(relative.has_value()); + EXPECT_POSE_NEAR(pose_relative, relative.value(), 0.01); +} + +/** + * @note test calculation correctness with the overload + */ +TEST_F(PoseTest, relativePose_second) +{ + const auto pose_relative = makePose( + makePoint(145244.7916, 786706.3326, 0.0127), + geometry_msgs::build().x(0).y(0).z(0).w(1)); + const auto from = + traffic_simulator::helper::constructCanonicalizedLaneletPose(195, 0.0, 0.0, hdmap_utils); + const auto to = makePose( + makePoint(881586.9767, 50167.0862, 34.2722), + geometry_msgs::build().x(0).y(0).z(-0.6397).w(0.7686)); + const auto relative = traffic_simulator::pose::relativePose(from, to); + + ASSERT_TRUE(relative.has_value()); + EXPECT_POSE_NEAR(pose_relative, relative.value(), 0.01); +} + +/** + * @note test calculation correctness when bounding boxes are disjoint + */ +TEST_F(PoseTest, boundingBoxRelativePose_disjoint) +{ + const auto pose_relative = makePose(makePoint(0.1108, -20.5955, 0.0)); + const auto from = makePose(makePoint(81600.3967, 50094.4298, 34.6759)); + const auto to = makePose(makePoint(81604.5076, 50071.8343, 40.8482)); + const auto boundingBox = makeBoundingBox(); + + const auto relative = + traffic_simulator::pose::boundingBoxRelativePose(from, boundingBox, to, boundingBox); + + ASSERT_TRUE(relative.has_value()); + EXPECT_POSE_NEAR(pose_relative, relative.value(), 0.01); +} + +/** + * @note test calculation correctness when bounding boxes share an edge + */ +TEST_F(PoseTest, boundingBoxRelativePose_commonEdge) +{ + const auto from = makePose(makePoint(81600, 50094, 34)); + const auto to = makePose(makePoint(81601, 50094, 34)); + const auto boundingBox = makeSmallBoundingBox(); + + const auto relative = + traffic_simulator::pose::boundingBoxRelativePose(from, boundingBox, to, boundingBox); + + EXPECT_FALSE(relative.has_value()); +} + +/** + * @note test calculation correctness when bounding boxes intersect + */ +TEST_F(PoseTest, boundingBoxRelativePose_intersect) +{ + const auto from = makePose(makePoint(81600, 50094, 34)); + const auto to = makePose(makePoint(81600.5, 50094, 34)); + const auto boundingBox = makeSmallBoundingBox(); + + const auto relative = + traffic_simulator::pose::boundingBoxRelativePose(from, boundingBox, to, boundingBox); + + EXPECT_FALSE(relative.has_value()); +} + +/** + * @note test s-value calculation correctness when longitudinal distance between the poses can not be calculated + */ +TEST_F(PoseTest, relativeLaneletPose_s_invalid) +{ + const auto from = + traffic_simulator::helper::constructCanonicalizedLaneletPose(195, 0.0, 0.0, hdmap_utils); + const auto to = + traffic_simulator::helper::constructCanonicalizedLaneletPose(196, 0.0, 0.0, hdmap_utils); + + const auto relative = traffic_simulator::pose::relativeLaneletPose(from, to, false, hdmap_utils); + + EXPECT_TRUE(isnan(relative.s)); +} + +/** + * @note test s-value calculation correctness when longitudinal distance between the poses can be calculated + */ +TEST_F(PoseTest, relativeLaneletPose_s_valid) +{ + const auto from = + traffic_simulator::helper::constructCanonicalizedLaneletPose(195, 0.0, 0.0, hdmap_utils); + const auto to = + traffic_simulator::helper::constructCanonicalizedLaneletPose(3002163, 0.0, 0.0, hdmap_utils); + + const auto relative = traffic_simulator::pose::relativeLaneletPose(from, to, false, hdmap_utils); + + EXPECT_NEAR(relative.s, 107.74, 0.001); +} + +/** + * @note test offset-value calculation correctness when lateral distance between the poses can not be calculated + */ +TEST_F(PoseTest, relativeLaneletPose_offset_invalid) +{ + const auto from = + traffic_simulator::helper::constructCanonicalizedLaneletPose(195, 0.0, 0.0, hdmap_utils); + const auto to = + traffic_simulator::helper::constructCanonicalizedLaneletPose(196, 0.0, 0.0, hdmap_utils); + + const auto relative = traffic_simulator::pose::relativeLaneletPose(from, to, false, hdmap_utils); + + EXPECT_TRUE(isnan(relative.offset)); +} + +/** + * @note test offset-value calculation correctness when lateral distance between the poses can be calculated + */ +TEST_F(PoseTest, relativeLaneletPose_offset_valid) +{ + const auto from = + traffic_simulator::helper::constructCanonicalizedLaneletPose(195, 0.0, 0.0, hdmap_utils); + const auto to = + traffic_simulator::helper::constructCanonicalizedLaneletPose(3002163, 0.0, 1.0, hdmap_utils); + + const auto relative = traffic_simulator::pose::relativeLaneletPose(from, to, true, hdmap_utils); + + EXPECT_EQ(relative.offset, 1.0); +} + +/** + * @note test s-value calculation correctness when longitudinal distance between the poses can not be calculated + */ +TEST_F(PoseTest, boundingBoxRelativeLaneletPose_s_invalid) +{ + const auto from = + traffic_simulator::helper::constructCanonicalizedLaneletPose(195, 0.0, 0.0, hdmap_utils); + const auto to = + traffic_simulator::helper::constructCanonicalizedLaneletPose(196, 0.0, 1.0, hdmap_utils); + const auto boundingBox = makeBoundingBox(); + + const auto relative = traffic_simulator::pose::boundingBoxRelativeLaneletPose( + from, boundingBox, to, boundingBox, false, hdmap_utils); + + EXPECT_TRUE(isnan(relative.s)); +} + +/** + * @note test s-value calculation correctness when longitudinal distance between the poses can be calculated + */ +TEST_F(PoseTest, boundingBoxRelativeLaneletPose_s_valid) +{ + const auto from = + traffic_simulator::helper::constructCanonicalizedLaneletPose(195, 0.0, 0.0, hdmap_utils); + const auto to = + traffic_simulator::helper::constructCanonicalizedLaneletPose(3002163, 0.0, 0.0, hdmap_utils); + const auto boundingBox = makeBoundingBox(); + + const auto relative = traffic_simulator::pose::boundingBoxRelativeLaneletPose( + from, boundingBox, to, boundingBox, false, hdmap_utils); + + EXPECT_NEAR(relative.s, 103.74, 0.01); +} + +/** + * @note test offset-value calculation correctness when lateral distance between the poses can not be calculated + */ +TEST_F(PoseTest, boundingBoxRelativeLaneletPose_offset_invalid) +{ + const auto from = + traffic_simulator::helper::constructCanonicalizedLaneletPose(195, 0.0, 0.0, hdmap_utils); + const auto to = + traffic_simulator::helper::constructCanonicalizedLaneletPose(196, 0.0, 1.0, hdmap_utils); + const auto boundingBox = makeBoundingBox(); + + const auto relative = traffic_simulator::pose::boundingBoxRelativeLaneletPose( + from, boundingBox, to, boundingBox, false, hdmap_utils); + + EXPECT_TRUE(isnan(relative.s)); +} + +/** + * @note test offset-value calculation correctness when lateral distance between the poses can be calculated + */ +TEST_F(PoseTest, boundingBoxRelativeLaneletPose_offset_valid) +{ + const auto from = + traffic_simulator::helper::constructCanonicalizedLaneletPose(195, 0.0, -1.0, hdmap_utils); + const auto to = + traffic_simulator::helper::constructCanonicalizedLaneletPose(3002163, 0.0, 1.0, hdmap_utils); + const auto boundingBox = makeBoundingBox(); + + const auto relative = traffic_simulator::pose::boundingBoxRelativeLaneletPose( + from, boundingBox, to, boundingBox, false, hdmap_utils); + + EXPECT_EQ(relative.offset, 0.0); +} + +/** + * @note test calculation correctness when the pose lies within the lanelet + */ +TEST_F(PoseTest, isInLanelet_inside) +{ + const auto pose = + traffic_simulator::helper::constructCanonicalizedLaneletPose(195, 0.0, 0.0, hdmap_utils); + + EXPECT_TRUE(traffic_simulator::pose::isInLanelet(pose, 195, 0, hdmap_utils)); +} + +/** + * @note test calculation correctness when the pose lies outside the front of the llanelet, distance greater than the tolerance + */ +TEST_F(PoseTest, isInLanelet_outsideFrontFar) +{ + const auto pose = + traffic_simulator::helper::constructCanonicalizedLaneletPose(3002163, -10.0, 0.0, hdmap_utils); + + EXPECT_FALSE(traffic_simulator::pose::isInLanelet(pose, 3002163, 1, hdmap_utils)); +} + +/** + * @note test calculation correctness when the pose lies outside the front of the llanelet, distance smaller than the tolerance + */ +TEST_F(PoseTest, isInLanelet_outsideFrontClose) +{ + const auto pose = + traffic_simulator::helper::constructCanonicalizedLaneletPose(3002163, -1.0, 0.0, hdmap_utils); + + EXPECT_TRUE(traffic_simulator::pose::isInLanelet(pose, 3002163, 2, hdmap_utils)); +} + +/** + * @note test calculation correctness when the pose lies outside the back of the llanelet, distance greater than the tolerance + */ +TEST_F(PoseTest, isInLanelet_outsideBackFar) +{ + const auto pose = + traffic_simulator::helper::constructCanonicalizedLaneletPose(195, 120.0, 0.0, hdmap_utils); + + EXPECT_FALSE(traffic_simulator::pose::isInLanelet(pose, 195, 2, hdmap_utils)); +} + +/** + * @note test calculation correctness when the pose lies outside the back of the lanelet, distance smaller than the tolerance + */ +TEST_F(PoseTest, isInLanelet_outsideBackClose) +{ + const auto pose = + traffic_simulator::helper::constructCanonicalizedLaneletPose(195, 110.0, 0.0, hdmap_utils); + + EXPECT_TRUE(traffic_simulator::pose::isInLanelet(pose, 195, 10, hdmap_utils)); +} + +/** + * @note test calculation correctness when there are no following lanelets and the pose lies within the lanelet + */ +TEST_F(PoseTest, isAtEndOfLanelets_noFollowing_within) +{ + const auto pose = + traffic_simulator::helper::constructCanonicalizedLaneletPose(3002171, 31.0, 0.0, hdmap_utils); + + EXPECT_FALSE(traffic_simulator::pose::isAtEndOfLanelets(pose, hdmap_utils)); +} + +/** + * @note test calculation correctness when there is a single following lanelet and the pose lies within the lanelet + */ +TEST_F(PoseTest, isAtEndOfLanelets_singleFollowing_within) +{ + const auto pose = + traffic_simulator::helper::constructCanonicalizedLaneletPose(3002167, 5.0, 0.0, hdmap_utils); + + EXPECT_FALSE(traffic_simulator::pose::isAtEndOfLanelets(pose, hdmap_utils)); +} + +/** + * @note test calculation correctness when there is a signle following lanelet and the pose lies after the end of the lanelet + */ +TEST_F(PoseTest, isAtEndOfLanelets_singleFollowing_outside) +{ + const auto pose = + traffic_simulator::helper::constructCanonicalizedLaneletPose(3002167, 20.0, 0.0, hdmap_utils); + + EXPECT_FALSE(traffic_simulator::pose::isAtEndOfLanelets(pose, hdmap_utils)); +} + +/** + * @note test calculation correctness when there are multiple following lanelets and the pose lies within the lanelet + */ +TEST_F(PoseTest, isAtEndOfLanelets_multipleFollowing_within) +{ + const auto pose = + traffic_simulator::helper::constructCanonicalizedLaneletPose(195, 5.0, 0.0, hdmap_utils); + + EXPECT_FALSE(traffic_simulator::pose::isAtEndOfLanelets(pose, hdmap_utils)); +} + +/** + * @note test calculation correctness when there are multiple following lanelets and the pose lies after the end of the lanelet + */ +TEST_F(PoseTest, isAtEndOfLanelets_multipleFollowing_outside) +{ + const auto pose = + traffic_simulator::helper::constructCanonicalizedLaneletPose(195, 120.0, 0.0, hdmap_utils); + + EXPECT_FALSE(traffic_simulator::pose::isAtEndOfLanelets(pose, hdmap_utils)); +} + +/** + * @note test function behavior when non existent lanelet::Id has been passed + */ +TEST_F(PoseTest, laneletLength_invalid) +{ + EXPECT_THROW( + traffic_simulator::pose::laneletLength(10000000000000000, hdmap_utils), std::runtime_error); +} + +/** + * @note test calculation correctness when a correct lanelet::Id has been passed + */ +TEST_F(PoseTest, laneletLength_valid) +{ + EXPECT_NEAR(traffic_simulator::pose::laneletLength(195, hdmap_utils), 107.74, 0.01); +} From 6269ea83cde5e94a602b1df19258cb085352f059 Mon Sep 17 00:00:00 2001 From: Release Bot Date: Mon, 9 Sep 2024 04:44:38 +0000 Subject: [PATCH 227/304] Bump version of scenario_simulator_v2 from version 4.1.1 to version 4.2.0 --- common/math/arithmetic/CHANGELOG.rst | 3 +++ common/math/arithmetic/package.xml | 2 +- common/math/geometry/CHANGELOG.rst | 3 +++ common/math/geometry/package.xml | 2 +- common/scenario_simulator_exception/CHANGELOG.rst | 3 +++ common/scenario_simulator_exception/package.xml | 2 +- common/simple_junit/CHANGELOG.rst | 3 +++ common/simple_junit/package.xml | 2 +- common/status_monitor/CHANGELOG.rst | 3 +++ common/status_monitor/package.xml | 2 +- external/concealer/CHANGELOG.rst | 6 ++++++ external/concealer/package.xml | 2 +- external/embree_vendor/CHANGELOG.rst | 3 +++ external/embree_vendor/package.xml | 2 +- map/kashiwanoha_map/CHANGELOG.rst | 3 +++ map/kashiwanoha_map/package.xml | 2 +- map/simple_cross_map/CHANGELOG.rst | 3 +++ map/simple_cross_map/package.xml | 2 +- mock/cpp_mock_scenarios/CHANGELOG.rst | 3 +++ mock/cpp_mock_scenarios/package.xml | 2 +- .../openscenario_experimental_catalog/CHANGELOG.rst | 3 +++ .../openscenario_experimental_catalog/package.xml | 2 +- openscenario/openscenario_interpreter/CHANGELOG.rst | 3 +++ openscenario/openscenario_interpreter/package.xml | 2 +- .../openscenario_interpreter_example/CHANGELOG.rst | 3 +++ .../openscenario_interpreter_example/package.xml | 2 +- .../openscenario_interpreter_msgs/CHANGELOG.rst | 3 +++ openscenario/openscenario_interpreter_msgs/package.xml | 2 +- openscenario/openscenario_preprocessor/CHANGELOG.rst | 3 +++ openscenario/openscenario_preprocessor/package.xml | 2 +- .../openscenario_preprocessor_msgs/CHANGELOG.rst | 3 +++ .../openscenario_preprocessor_msgs/package.xml | 2 +- openscenario/openscenario_utility/CHANGELOG.rst | 3 +++ openscenario/openscenario_utility/package.xml | 2 +- openscenario/openscenario_validator/CHANGELOG.rst | 3 +++ openscenario/openscenario_validator/package.xml | 2 +- rviz_plugins/openscenario_visualization/CHANGELOG.rst | 3 +++ rviz_plugins/openscenario_visualization/package.xml | 2 +- .../real_time_factor_control_rviz_plugin/CHANGELOG.rst | 3 +++ .../real_time_factor_control_rviz_plugin/package.xml | 2 +- scenario_simulator_v2/CHANGELOG.rst | 3 +++ scenario_simulator_v2/package.xml | 2 +- simulation/behavior_tree_plugin/CHANGELOG.rst | 3 +++ simulation/behavior_tree_plugin/package.xml | 2 +- simulation/do_nothing_plugin/CHANGELOG.rst | 3 +++ simulation/do_nothing_plugin/package.xml | 2 +- simulation/simple_sensor_simulator/CHANGELOG.rst | 3 +++ simulation/simple_sensor_simulator/package.xml | 2 +- simulation/simulation_interface/CHANGELOG.rst | 3 +++ simulation/simulation_interface/package.xml | 2 +- simulation/traffic_simulator/CHANGELOG.rst | 9 +++++++++ simulation/traffic_simulator/package.xml | 2 +- simulation/traffic_simulator_msgs/CHANGELOG.rst | 3 +++ simulation/traffic_simulator_msgs/package.xml | 2 +- test_runner/random_test_runner/CHANGELOG.rst | 3 +++ test_runner/random_test_runner/package.xml | 2 +- test_runner/scenario_test_runner/CHANGELOG.rst | 10 ++++++++++ test_runner/scenario_test_runner/package.xml | 2 +- 58 files changed, 132 insertions(+), 29 deletions(-) diff --git a/common/math/arithmetic/CHANGELOG.rst b/common/math/arithmetic/CHANGELOG.rst index 330d9aa24aa..f93617fd14f 100644 --- a/common/math/arithmetic/CHANGELOG.rst +++ b/common/math/arithmetic/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package arithmetic * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.0 (2024-09-09) +------------------ + 4.1.1 (2024-09-03) ------------------ * Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control diff --git a/common/math/arithmetic/package.xml b/common/math/arithmetic/package.xml index 6e6b99eecc8..39519d462a0 100644 --- a/common/math/arithmetic/package.xml +++ b/common/math/arithmetic/package.xml @@ -2,7 +2,7 @@ arithmetic - 4.1.1 + 4.2.0 arithmetic library for scenario_simulator_v2 Tatsuya Yamasaki Apache License 2.0 diff --git a/common/math/geometry/CHANGELOG.rst b/common/math/geometry/CHANGELOG.rst index bb6fe0f336a..40505bb1888 100644 --- a/common/math/geometry/CHANGELOG.rst +++ b/common/math/geometry/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package geometry * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.0 (2024-09-09) +------------------ + 4.1.1 (2024-09-03) ------------------ * Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control diff --git a/common/math/geometry/package.xml b/common/math/geometry/package.xml index 4efabccc4ab..aebfc75ff48 100644 --- a/common/math/geometry/package.xml +++ b/common/math/geometry/package.xml @@ -2,7 +2,7 @@ geometry - 4.1.1 + 4.2.0 geometry math library for scenario_simulator_v2 application Masaya Kataoka Apache License 2.0 diff --git a/common/scenario_simulator_exception/CHANGELOG.rst b/common/scenario_simulator_exception/CHANGELOG.rst index 751669f5645..38462336a04 100644 --- a/common/scenario_simulator_exception/CHANGELOG.rst +++ b/common/scenario_simulator_exception/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package scenario_simulator_exception * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.0 (2024-09-09) +------------------ + 4.1.1 (2024-09-03) ------------------ * Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control diff --git a/common/scenario_simulator_exception/package.xml b/common/scenario_simulator_exception/package.xml index f8044694277..edd7e147791 100644 --- a/common/scenario_simulator_exception/package.xml +++ b/common/scenario_simulator_exception/package.xml @@ -2,7 +2,7 @@ scenario_simulator_exception - 4.1.1 + 4.2.0 Exception types for scenario simulator Tatsuya Yamasaki Apache License 2.0 diff --git a/common/simple_junit/CHANGELOG.rst b/common/simple_junit/CHANGELOG.rst index e8c04a9b3da..e7311df3b5c 100644 --- a/common/simple_junit/CHANGELOG.rst +++ b/common/simple_junit/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package junit_exporter * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.0 (2024-09-09) +------------------ + 4.1.1 (2024-09-03) ------------------ * Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control diff --git a/common/simple_junit/package.xml b/common/simple_junit/package.xml index 94acfc23b4f..06585618cec 100644 --- a/common/simple_junit/package.xml +++ b/common/simple_junit/package.xml @@ -2,7 +2,7 @@ simple_junit - 4.1.1 + 4.2.0 Lightweight JUnit library for ROS 2 Masaya Kataoka Tatsuya Yamasaki diff --git a/common/status_monitor/CHANGELOG.rst b/common/status_monitor/CHANGELOG.rst index 93bd7dae8e2..bdfd65dcb5f 100644 --- a/common/status_monitor/CHANGELOG.rst +++ b/common/status_monitor/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package status_monitor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.0 (2024-09-09) +------------------ + 4.1.1 (2024-09-03) ------------------ * Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control diff --git a/common/status_monitor/package.xml b/common/status_monitor/package.xml index 8581f52357e..98585d9bea1 100644 --- a/common/status_monitor/package.xml +++ b/common/status_monitor/package.xml @@ -2,7 +2,7 @@ status_monitor - 4.1.1 + 4.2.0 none Tatsuya Yamasaki Apache License 2.0 diff --git a/external/concealer/CHANGELOG.rst b/external/concealer/CHANGELOG.rst index a65070a5b3a..d59a67dfa40 100644 --- a/external/concealer/CHANGELOG.rst +++ b/external/concealer/CHANGELOG.rst @@ -21,6 +21,12 @@ Changelog for package concealer * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.0 (2024-09-09) +------------------ +* Merge pull request `#1362 `_ from tier4/feature/ros2-parameter-forwarding +* Add feature to forward parameters prefixed with `autoware.` to Autoware +* Contributors: Kotaro Yoshimoto, yamacir-kit + 4.1.1 (2024-09-03) ------------------ * Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control diff --git a/external/concealer/package.xml b/external/concealer/package.xml index 43e7da9c9cb..cfcaf051652 100644 --- a/external/concealer/package.xml +++ b/external/concealer/package.xml @@ -2,7 +2,7 @@ concealer - 4.1.1 + 4.2.0 Provides a class 'Autoware' to conceal miscellaneous things to simplify Autoware management of the simulator. Tatsuya Yamasaki Apache License 2.0 diff --git a/external/embree_vendor/CHANGELOG.rst b/external/embree_vendor/CHANGELOG.rst index f43f59683ed..cdb962aeb46 100644 --- a/external/embree_vendor/CHANGELOG.rst +++ b/external/embree_vendor/CHANGELOG.rst @@ -24,6 +24,9 @@ Changelog for package embree_vendor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.0 (2024-09-09) +------------------ + 4.1.1 (2024-09-03) ------------------ * Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control diff --git a/external/embree_vendor/package.xml b/external/embree_vendor/package.xml index 5eb7b996777..d2d07f80f0b 100644 --- a/external/embree_vendor/package.xml +++ b/external/embree_vendor/package.xml @@ -2,7 +2,7 @@ embree_vendor - 4.1.1 + 4.2.0 vendor packages for intel raytracing kernel library masaya Apache 2.0 diff --git a/map/kashiwanoha_map/CHANGELOG.rst b/map/kashiwanoha_map/CHANGELOG.rst index 22bf4853964..e784fe07292 100644 --- a/map/kashiwanoha_map/CHANGELOG.rst +++ b/map/kashiwanoha_map/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package kashiwanoha_map * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.0 (2024-09-09) +------------------ + 4.1.1 (2024-09-03) ------------------ * Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control diff --git a/map/kashiwanoha_map/package.xml b/map/kashiwanoha_map/package.xml index 8dc789e7ad9..60835697fe0 100644 --- a/map/kashiwanoha_map/package.xml +++ b/map/kashiwanoha_map/package.xml @@ -2,7 +2,7 @@ kashiwanoha_map - 4.1.1 + 4.2.0 map package for kashiwanoha Masaya Kataoka Apache License 2.0 diff --git a/map/simple_cross_map/CHANGELOG.rst b/map/simple_cross_map/CHANGELOG.rst index df422fbee7e..c494e9d2080 100644 --- a/map/simple_cross_map/CHANGELOG.rst +++ b/map/simple_cross_map/CHANGELOG.rst @@ -9,6 +9,9 @@ Changelog for package simple_cross_map * Merge branch 'master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.0 (2024-09-09) +------------------ + 4.1.1 (2024-09-03) ------------------ * Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control diff --git a/map/simple_cross_map/package.xml b/map/simple_cross_map/package.xml index 5844a6ddd6e..0f54737183a 100644 --- a/map/simple_cross_map/package.xml +++ b/map/simple_cross_map/package.xml @@ -2,7 +2,7 @@ simple_cross_map - 4.1.1 + 4.2.0 map package for simple cross Masaya Kataoka Apache License 2.0 diff --git a/mock/cpp_mock_scenarios/CHANGELOG.rst b/mock/cpp_mock_scenarios/CHANGELOG.rst index 5104c7ac09b..98c71a7a5f8 100644 --- a/mock/cpp_mock_scenarios/CHANGELOG.rst +++ b/mock/cpp_mock_scenarios/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package cpp_mock_scenarios * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.0 (2024-09-09) +------------------ + 4.1.1 (2024-09-03) ------------------ * Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control diff --git a/mock/cpp_mock_scenarios/package.xml b/mock/cpp_mock_scenarios/package.xml index f595e5f10dc..ff478f05e7f 100644 --- a/mock/cpp_mock_scenarios/package.xml +++ b/mock/cpp_mock_scenarios/package.xml @@ -2,7 +2,7 @@ cpp_mock_scenarios - 4.1.1 + 4.2.0 C++ mock scenarios masaya Apache License 2.0 diff --git a/openscenario/openscenario_experimental_catalog/CHANGELOG.rst b/openscenario/openscenario_experimental_catalog/CHANGELOG.rst index 4bc7d1e3f3e..8cdb221e4e9 100644 --- a/openscenario/openscenario_experimental_catalog/CHANGELOG.rst +++ b/openscenario/openscenario_experimental_catalog/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package openscenario_experimental_catalog * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.0 (2024-09-09) +------------------ + 4.1.1 (2024-09-03) ------------------ * Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control diff --git a/openscenario/openscenario_experimental_catalog/package.xml b/openscenario/openscenario_experimental_catalog/package.xml index 45f27892af7..98afcc38fa2 100644 --- a/openscenario/openscenario_experimental_catalog/package.xml +++ b/openscenario/openscenario_experimental_catalog/package.xml @@ -2,7 +2,7 @@ openscenario_experimental_catalog - 4.1.1 + 4.2.0 TIER IV experimental catalogs for OpenSCENARIO Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter/CHANGELOG.rst b/openscenario/openscenario_interpreter/CHANGELOG.rst index 71666b59396..b9c5aafe459 100644 --- a/openscenario/openscenario_interpreter/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter/CHANGELOG.rst @@ -32,6 +32,9 @@ Changelog for package openscenario_interpreter * add publish_empty_context parameter * Contributors: Masaya Kataoka +4.2.0 (2024-09-09) +------------------ + 4.1.1 (2024-09-03) ------------------ * Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control diff --git a/openscenario/openscenario_interpreter/package.xml b/openscenario/openscenario_interpreter/package.xml index 3d070c90e78..5a1379176d5 100644 --- a/openscenario/openscenario_interpreter/package.xml +++ b/openscenario/openscenario_interpreter/package.xml @@ -2,7 +2,7 @@ openscenario_interpreter - 4.1.1 + 4.2.0 OpenSCENARIO 1.2.0 interpreter package for Autoware Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter_example/CHANGELOG.rst b/openscenario/openscenario_interpreter_example/CHANGELOG.rst index 284f8b712ce..525d22ee2a8 100644 --- a/openscenario/openscenario_interpreter_example/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter_example/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package openscenario_interpreter_example * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.0 (2024-09-09) +------------------ + 4.1.1 (2024-09-03) ------------------ * Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control diff --git a/openscenario/openscenario_interpreter_example/package.xml b/openscenario/openscenario_interpreter_example/package.xml index 0eddc9f2065..813cfc0bda9 100644 --- a/openscenario/openscenario_interpreter_example/package.xml +++ b/openscenario/openscenario_interpreter_example/package.xml @@ -3,7 +3,7 @@ openscenario_interpreter_example - 4.1.1 + 4.2.0 Examples for some TIER IV OpenSCENARIO Interpreter's features Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst b/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst index 2ff6a3ad396..55c6684f8db 100644 --- a/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package openscenario_interpreter_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.0 (2024-09-09) +------------------ + 4.1.1 (2024-09-03) ------------------ * Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control diff --git a/openscenario/openscenario_interpreter_msgs/package.xml b/openscenario/openscenario_interpreter_msgs/package.xml index c0c44be4bcf..813d66ec4e7 100644 --- a/openscenario/openscenario_interpreter_msgs/package.xml +++ b/openscenario/openscenario_interpreter_msgs/package.xml @@ -2,7 +2,7 @@ openscenario_interpreter_msgs - 4.1.1 + 4.2.0 ROS message types for package openscenario_interpreter Yamasaki Tatsuya Apache License 2.0 diff --git a/openscenario/openscenario_preprocessor/CHANGELOG.rst b/openscenario/openscenario_preprocessor/CHANGELOG.rst index 2c679019060..e96fd8fcf07 100644 --- a/openscenario/openscenario_preprocessor/CHANGELOG.rst +++ b/openscenario/openscenario_preprocessor/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package openscenario_preprocessor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.0 (2024-09-09) +------------------ + 4.1.1 (2024-09-03) ------------------ * Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control diff --git a/openscenario/openscenario_preprocessor/package.xml b/openscenario/openscenario_preprocessor/package.xml index 2806381635c..f44e74303d3 100644 --- a/openscenario/openscenario_preprocessor/package.xml +++ b/openscenario/openscenario_preprocessor/package.xml @@ -3,7 +3,7 @@ openscenario_preprocessor - 4.1.1 + 4.2.0 Example package for TIER IV OpenSCENARIO Interpreter Kotaro Yoshimoto Apache License 2.0 diff --git a/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst b/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst index 4f6847559fc..33356a19cf0 100644 --- a/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst +++ b/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package openscenario_preprocessor_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.0 (2024-09-09) +------------------ + 4.1.1 (2024-09-03) ------------------ * Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control diff --git a/openscenario/openscenario_preprocessor_msgs/package.xml b/openscenario/openscenario_preprocessor_msgs/package.xml index af39b90a017..51db6a0bb77 100644 --- a/openscenario/openscenario_preprocessor_msgs/package.xml +++ b/openscenario/openscenario_preprocessor_msgs/package.xml @@ -2,7 +2,7 @@ openscenario_preprocessor_msgs - 4.1.1 + 4.2.0 ROS message types for package openscenario_preprocessor Kotaro Yoshimoto Apache License 2.0 diff --git a/openscenario/openscenario_utility/CHANGELOG.rst b/openscenario/openscenario_utility/CHANGELOG.rst index 7303319e8d7..3af8959cc64 100644 --- a/openscenario/openscenario_utility/CHANGELOG.rst +++ b/openscenario/openscenario_utility/CHANGELOG.rst @@ -24,6 +24,9 @@ Changelog for package openscenario_utility * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.0 (2024-09-09) +------------------ + 4.1.1 (2024-09-03) ------------------ * Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control diff --git a/openscenario/openscenario_utility/package.xml b/openscenario/openscenario_utility/package.xml index 17130a022c3..2c9309a5a49 100644 --- a/openscenario/openscenario_utility/package.xml +++ b/openscenario/openscenario_utility/package.xml @@ -2,7 +2,7 @@ openscenario_utility - 4.1.1 + 4.2.0 Utility tools for ASAM OpenSCENARIO 1.2.0 Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_validator/CHANGELOG.rst b/openscenario/openscenario_validator/CHANGELOG.rst index edae34b089e..c8771876622 100644 --- a/openscenario/openscenario_validator/CHANGELOG.rst +++ b/openscenario/openscenario_validator/CHANGELOG.rst @@ -10,6 +10,9 @@ Changelog for package openscenario_validator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.0 (2024-09-09) +------------------ + 4.1.1 (2024-09-03) ------------------ * Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control diff --git a/openscenario/openscenario_validator/package.xml b/openscenario/openscenario_validator/package.xml index da541f624f9..46f34489fd5 100644 --- a/openscenario/openscenario_validator/package.xml +++ b/openscenario/openscenario_validator/package.xml @@ -2,7 +2,7 @@ openscenario_validator - 4.1.1 + 4.2.0 Validator for OpenSCENARIO 1.3 Kotaro Yoshimoto Apache License 2.0 diff --git a/rviz_plugins/openscenario_visualization/CHANGELOG.rst b/rviz_plugins/openscenario_visualization/CHANGELOG.rst index d69f5f28b9c..bd02b1875ab 100644 --- a/rviz_plugins/openscenario_visualization/CHANGELOG.rst +++ b/rviz_plugins/openscenario_visualization/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package openscenario_visualization * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.0 (2024-09-09) +------------------ + 4.1.1 (2024-09-03) ------------------ * Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control diff --git a/rviz_plugins/openscenario_visualization/package.xml b/rviz_plugins/openscenario_visualization/package.xml index e76f23b4545..fde305cd15b 100644 --- a/rviz_plugins/openscenario_visualization/package.xml +++ b/rviz_plugins/openscenario_visualization/package.xml @@ -2,7 +2,7 @@ openscenario_visualization - 4.1.1 + 4.2.0 Visualization tools for simulation results Masaya Kataoka Kyoichi Sugahara diff --git a/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst b/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst index 89dc9d79e52..ba6cca5ae93 100644 --- a/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst +++ b/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package real_time_factor_control_rviz_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.0 (2024-09-09) +------------------ + 4.1.1 (2024-09-03) ------------------ * Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control diff --git a/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml b/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml index 7e40fec1330..2201e871651 100644 --- a/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml +++ b/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml @@ -2,7 +2,7 @@ real_time_factor_control_rviz_plugin - 4.1.1 + 4.2.0 Slider controlling real time factor value. Paweł Lech Apache License 2.0 diff --git a/scenario_simulator_v2/CHANGELOG.rst b/scenario_simulator_v2/CHANGELOG.rst index d75490f9061..bf0064df433 100644 --- a/scenario_simulator_v2/CHANGELOG.rst +++ b/scenario_simulator_v2/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package scenario_simulator_v2 * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.0 (2024-09-09) +------------------ + 4.1.1 (2024-09-03) ------------------ * Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control diff --git a/scenario_simulator_v2/package.xml b/scenario_simulator_v2/package.xml index 75a3120d806..005b42bc240 100644 --- a/scenario_simulator_v2/package.xml +++ b/scenario_simulator_v2/package.xml @@ -2,7 +2,7 @@ scenario_simulator_v2 - 4.1.1 + 4.2.0 scenario testing framework for Autoware Masaya Kataoka Apache License 2.0 diff --git a/simulation/behavior_tree_plugin/CHANGELOG.rst b/simulation/behavior_tree_plugin/CHANGELOG.rst index a1827aa4290..884cd2681dd 100644 --- a/simulation/behavior_tree_plugin/CHANGELOG.rst +++ b/simulation/behavior_tree_plugin/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package behavior_tree_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.0 (2024-09-09) +------------------ + 4.1.1 (2024-09-03) ------------------ * Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control diff --git a/simulation/behavior_tree_plugin/package.xml b/simulation/behavior_tree_plugin/package.xml index b049b75aecf..0280fa610b5 100644 --- a/simulation/behavior_tree_plugin/package.xml +++ b/simulation/behavior_tree_plugin/package.xml @@ -2,7 +2,7 @@ behavior_tree_plugin - 4.1.1 + 4.2.0 Behavior tree plugin for traffic_simulator masaya Apache 2.0 diff --git a/simulation/do_nothing_plugin/CHANGELOG.rst b/simulation/do_nothing_plugin/CHANGELOG.rst index 333a17a14ce..ffac7c9ebd4 100644 --- a/simulation/do_nothing_plugin/CHANGELOG.rst +++ b/simulation/do_nothing_plugin/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package do_nothing_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.0 (2024-09-09) +------------------ + 4.1.1 (2024-09-03) ------------------ * Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control diff --git a/simulation/do_nothing_plugin/package.xml b/simulation/do_nothing_plugin/package.xml index 04e674bafbe..22eda8d1269 100644 --- a/simulation/do_nothing_plugin/package.xml +++ b/simulation/do_nothing_plugin/package.xml @@ -2,7 +2,7 @@ do_nothing_plugin - 4.1.1 + 4.2.0 Behavior plugin for do nothing Masaya Kataoka Apache 2.0 diff --git a/simulation/simple_sensor_simulator/CHANGELOG.rst b/simulation/simple_sensor_simulator/CHANGELOG.rst index 589423df12d..a967312719b 100644 --- a/simulation/simple_sensor_simulator/CHANGELOG.rst +++ b/simulation/simple_sensor_simulator/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package simple_sensor_simulator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.0 (2024-09-09) +------------------ + 4.1.1 (2024-09-03) ------------------ * Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control diff --git a/simulation/simple_sensor_simulator/package.xml b/simulation/simple_sensor_simulator/package.xml index bd84da7888a..fba1b6b8bf2 100644 --- a/simulation/simple_sensor_simulator/package.xml +++ b/simulation/simple_sensor_simulator/package.xml @@ -1,7 +1,7 @@ simple_sensor_simulator - 4.1.1 + 4.2.0 simple_sensor_simulator package masaya kataoka diff --git a/simulation/simulation_interface/CHANGELOG.rst b/simulation/simulation_interface/CHANGELOG.rst index 808b578281b..e77441ef241 100644 --- a/simulation/simulation_interface/CHANGELOG.rst +++ b/simulation/simulation_interface/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package simulation_interface * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.0 (2024-09-09) +------------------ + 4.1.1 (2024-09-03) ------------------ * Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control diff --git a/simulation/simulation_interface/package.xml b/simulation/simulation_interface/package.xml index 7900025ff2e..996dd089d0b 100644 --- a/simulation/simulation_interface/package.xml +++ b/simulation/simulation_interface/package.xml @@ -2,7 +2,7 @@ simulation_interface - 4.1.1 + 4.2.0 packages to define interface between simulator and scenario interpreter Masaya Kataoka Apache License 2.0 diff --git a/simulation/traffic_simulator/CHANGELOG.rst b/simulation/traffic_simulator/CHANGELOG.rst index 8e67976fb9e..1a61d823f75 100644 --- a/simulation/traffic_simulator/CHANGELOG.rst +++ b/simulation/traffic_simulator/CHANGELOG.rst @@ -21,6 +21,15 @@ Changelog for package traffic_simulator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.0 (2024-09-09) +------------------ +* Merge pull request `#1362 `_ from tier4/feature/ros2-parameter-forwarding +* Cleanup +* Move parameter `use_sim_time` into function `make_parameters` +* Remove data member `traffic_simulator::Configuration::rviz_config_path` +* Add feature to forward parameters prefixed with `autoware.` to Autoware +* Contributors: Kotaro Yoshimoto, yamacir-kit + 4.1.1 (2024-09-03) ------------------ * Merge pull request `#1207 `_ from tier4/fix/use-sim-time-for-real-time-factor-control diff --git a/simulation/traffic_simulator/package.xml b/simulation/traffic_simulator/package.xml index 24c4c007e01..c08ba92d91d 100644 --- a/simulation/traffic_simulator/package.xml +++ b/simulation/traffic_simulator/package.xml @@ -1,7 +1,7 @@ traffic_simulator - 4.1.1 + 4.2.0 control traffic flow masaya kataoka diff --git a/simulation/traffic_simulator_msgs/CHANGELOG.rst b/simulation/traffic_simulator_msgs/CHANGELOG.rst index 5db5f440c2e..b615cb5b853 100644 --- a/simulation/traffic_simulator_msgs/CHANGELOG.rst +++ b/simulation/traffic_simulator_msgs/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package openscenario_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.0 (2024-09-09) +------------------ + 4.1.1 (2024-09-03) ------------------ * Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control diff --git a/simulation/traffic_simulator_msgs/package.xml b/simulation/traffic_simulator_msgs/package.xml index 8050ee25c17..e70bf444879 100644 --- a/simulation/traffic_simulator_msgs/package.xml +++ b/simulation/traffic_simulator_msgs/package.xml @@ -2,7 +2,7 @@ traffic_simulator_msgs - 4.1.1 + 4.2.0 ROS messages for openscenario Masaya Kataoka Apache License 2.0 diff --git a/test_runner/random_test_runner/CHANGELOG.rst b/test_runner/random_test_runner/CHANGELOG.rst index 6fefac553c0..c02728d68e2 100644 --- a/test_runner/random_test_runner/CHANGELOG.rst +++ b/test_runner/random_test_runner/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package random_test_runner * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.0 (2024-09-09) +------------------ + 4.1.1 (2024-09-03) ------------------ * Merge branch 'master' into fix/use-sim-time-for-real-time-factor-control diff --git a/test_runner/random_test_runner/package.xml b/test_runner/random_test_runner/package.xml index 84b08a721a1..d7cc7c7ca4c 100644 --- a/test_runner/random_test_runner/package.xml +++ b/test_runner/random_test_runner/package.xml @@ -2,7 +2,7 @@ random_test_runner - 4.1.1 + 4.2.0 Random behavior test runner piotr-zyskowski-rai Apache License 2.0 diff --git a/test_runner/scenario_test_runner/CHANGELOG.rst b/test_runner/scenario_test_runner/CHANGELOG.rst index afa619d2d51..0e9d8b7395a 100644 --- a/test_runner/scenario_test_runner/CHANGELOG.rst +++ b/test_runner/scenario_test_runner/CHANGELOG.rst @@ -35,6 +35,16 @@ Changelog for package scenario_test_runner * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.0 (2024-09-09) +------------------ +* Merge pull request `#1362 `_ from tier4/feature/ros2-parameter-forwarding +* Move function `make_vehicle_parameters` into function `make_parameters` +* Move parameter `use_sim_time` into function `make_parameters` +* Simplify collection of `autoware.` prefixed parameters +* Remove data member `traffic_simulator::Configuration::rviz_config_path` +* Add feature to forward parameters prefixed with `autoware.` to Autoware +* Contributors: Kotaro Yoshimoto, yamacir-kit + 4.1.1 (2024-09-03) ------------------ * Merge pull request `#1207 `_ from tier4/fix/use-sim-time-for-real-time-factor-control diff --git a/test_runner/scenario_test_runner/package.xml b/test_runner/scenario_test_runner/package.xml index 8ae5e7817c6..f4146f760a5 100644 --- a/test_runner/scenario_test_runner/package.xml +++ b/test_runner/scenario_test_runner/package.xml @@ -2,7 +2,7 @@ scenario_test_runner - 4.1.1 + 4.2.0 scenario test runner package Tatsuya Yamasaki Apache License 2.0 From cc971b451b16a4cda7e5eb5c147963a786815e80 Mon Sep 17 00:00:00 2001 From: robomic Date: Mon, 9 Sep 2024 11:54:39 +0200 Subject: [PATCH 228/304] BUG EXAMPLE --- .../src/hdmap_utils/hdmap_utils.cpp | 4 ++ .../test/src/utils/test_distance.cpp | 60 +++++++++++++++++++ 2 files changed, 64 insertions(+) diff --git a/simulation/traffic_simulator/src/hdmap_utils/hdmap_utils.cpp b/simulation/traffic_simulator/src/hdmap_utils/hdmap_utils.cpp index 821a2fd0acd..5ff4c58009d 100644 --- a/simulation/traffic_simulator/src/hdmap_utils/hdmap_utils.cpp +++ b/simulation/traffic_simulator/src/hdmap_utils/hdmap_utils.cpp @@ -1547,6 +1547,10 @@ auto HdMapUtils::getLongitudinalDistance( if (route.empty()) { return std::nullopt; } + for (const auto & id : route) { + printf("%ld ", id); + } + printf("\n"); double distance = 0; auto with_lane_change = [this]( diff --git a/simulation/traffic_simulator/test/src/utils/test_distance.cpp b/simulation/traffic_simulator/test/src/utils/test_distance.cpp index f312ce3184e..80aa5ba10b1 100644 --- a/simulation/traffic_simulator/test/src/utils/test_distance.cpp +++ b/simulation/traffic_simulator/test/src/utils/test_distance.cpp @@ -728,3 +728,63 @@ TEST_F(distanceTest_Intersection, distanceToRightLaneBound_emptyVector) pose, bounding_box, lanelet::Ids{}, hdmap_utils_ptr), common::SemanticError); } + +TEST(distance, longitudinalDistance_noAdjacent_noOpposite_change_case1) +{ + std::shared_ptr hdmap_utils_ptr = + std::make_shared( + ament_index_cpp::get_package_share_directory("traffic_simulator") + + "/map/intersection/lanelet2_map.osm", + geographic_msgs::build() + .latitude(35.64200728302) + .longitude(139.74821144562) + .altitude(0.0)); + { + const auto pose_from = traffic_simulator::toCanonicalizedLaneletPose( + makePose(86627.71, 44972.06, 340.0), false, hdmap_utils_ptr); + ASSERT_TRUE(pose_from.has_value()); + const auto pose_to = traffic_simulator::toCanonicalizedLaneletPose( + makePose(86647.23, 44882.51, 240.0), false, hdmap_utils_ptr); + ASSERT_TRUE(pose_from.has_value()); + + const auto result = traffic_simulator::distance::longitudinalDistance( + pose_from.value(), pose_to.value(), false, false, true, hdmap_utils_ptr); + EXPECT_TRUE(result.has_value()); + } + { + const auto pose_from = traffic_simulator::toCanonicalizedLaneletPose( + makePose(86555.38, 45000.88, 340.0), false, hdmap_utils_ptr); + ASSERT_TRUE(pose_from.has_value()); + const auto pose_to = traffic_simulator::toCanonicalizedLaneletPose( + makePose(86647.23, 44882.51, 240.0), false, hdmap_utils_ptr); + ASSERT_TRUE(pose_from.has_value()); + + const auto result = traffic_simulator::distance::longitudinalDistance( + pose_from.value(), pose_to.value(), false, false, true, hdmap_utils_ptr); + EXPECT_TRUE(result.has_value()); + } + { + const auto pose_from = traffic_simulator::toCanonicalizedLaneletPose( + makePose(86788.82, 44993.77, 210.0), false, hdmap_utils_ptr); + ASSERT_TRUE(pose_from.has_value()); + const auto pose_to = traffic_simulator::toCanonicalizedLaneletPose( + makePose(86553.48, 44990.56, 150.0), false, hdmap_utils_ptr); + ASSERT_TRUE(pose_from.has_value()); + + const auto result = traffic_simulator::distance::longitudinalDistance( + pose_from.value(), pose_to.value(), false, false, true, hdmap_utils_ptr); + EXPECT_TRUE(result.has_value()); + } + { + const auto pose_from = traffic_simulator::toCanonicalizedLaneletPose( + makePose(86788.82, 44993.77, 210.0), false, hdmap_utils_ptr); + ASSERT_TRUE(pose_from.has_value()); + const auto pose_to = traffic_simulator::toCanonicalizedLaneletPose( + makePose(86579.91, 44979.00, 150.0), false, hdmap_utils_ptr); + ASSERT_TRUE(pose_from.has_value()); + + const auto result = traffic_simulator::distance::longitudinalDistance( + pose_from.value(), pose_to.value(), false, false, true, hdmap_utils_ptr); + EXPECT_TRUE(result.has_value()); + } +} From 145246797f2d853b1df19402d9890275520b7741 Mon Sep 17 00:00:00 2001 From: robomic Date: Mon, 9 Sep 2024 11:57:12 +0200 Subject: [PATCH 229/304] rm bug example --- .../src/hdmap_utils/hdmap_utils.cpp | 4 -- .../test/src/utils/test_distance.cpp | 60 ------------------- 2 files changed, 64 deletions(-) diff --git a/simulation/traffic_simulator/src/hdmap_utils/hdmap_utils.cpp b/simulation/traffic_simulator/src/hdmap_utils/hdmap_utils.cpp index 5ff4c58009d..821a2fd0acd 100644 --- a/simulation/traffic_simulator/src/hdmap_utils/hdmap_utils.cpp +++ b/simulation/traffic_simulator/src/hdmap_utils/hdmap_utils.cpp @@ -1547,10 +1547,6 @@ auto HdMapUtils::getLongitudinalDistance( if (route.empty()) { return std::nullopt; } - for (const auto & id : route) { - printf("%ld ", id); - } - printf("\n"); double distance = 0; auto with_lane_change = [this]( diff --git a/simulation/traffic_simulator/test/src/utils/test_distance.cpp b/simulation/traffic_simulator/test/src/utils/test_distance.cpp index 80aa5ba10b1..f312ce3184e 100644 --- a/simulation/traffic_simulator/test/src/utils/test_distance.cpp +++ b/simulation/traffic_simulator/test/src/utils/test_distance.cpp @@ -728,63 +728,3 @@ TEST_F(distanceTest_Intersection, distanceToRightLaneBound_emptyVector) pose, bounding_box, lanelet::Ids{}, hdmap_utils_ptr), common::SemanticError); } - -TEST(distance, longitudinalDistance_noAdjacent_noOpposite_change_case1) -{ - std::shared_ptr hdmap_utils_ptr = - std::make_shared( - ament_index_cpp::get_package_share_directory("traffic_simulator") + - "/map/intersection/lanelet2_map.osm", - geographic_msgs::build() - .latitude(35.64200728302) - .longitude(139.74821144562) - .altitude(0.0)); - { - const auto pose_from = traffic_simulator::toCanonicalizedLaneletPose( - makePose(86627.71, 44972.06, 340.0), false, hdmap_utils_ptr); - ASSERT_TRUE(pose_from.has_value()); - const auto pose_to = traffic_simulator::toCanonicalizedLaneletPose( - makePose(86647.23, 44882.51, 240.0), false, hdmap_utils_ptr); - ASSERT_TRUE(pose_from.has_value()); - - const auto result = traffic_simulator::distance::longitudinalDistance( - pose_from.value(), pose_to.value(), false, false, true, hdmap_utils_ptr); - EXPECT_TRUE(result.has_value()); - } - { - const auto pose_from = traffic_simulator::toCanonicalizedLaneletPose( - makePose(86555.38, 45000.88, 340.0), false, hdmap_utils_ptr); - ASSERT_TRUE(pose_from.has_value()); - const auto pose_to = traffic_simulator::toCanonicalizedLaneletPose( - makePose(86647.23, 44882.51, 240.0), false, hdmap_utils_ptr); - ASSERT_TRUE(pose_from.has_value()); - - const auto result = traffic_simulator::distance::longitudinalDistance( - pose_from.value(), pose_to.value(), false, false, true, hdmap_utils_ptr); - EXPECT_TRUE(result.has_value()); - } - { - const auto pose_from = traffic_simulator::toCanonicalizedLaneletPose( - makePose(86788.82, 44993.77, 210.0), false, hdmap_utils_ptr); - ASSERT_TRUE(pose_from.has_value()); - const auto pose_to = traffic_simulator::toCanonicalizedLaneletPose( - makePose(86553.48, 44990.56, 150.0), false, hdmap_utils_ptr); - ASSERT_TRUE(pose_from.has_value()); - - const auto result = traffic_simulator::distance::longitudinalDistance( - pose_from.value(), pose_to.value(), false, false, true, hdmap_utils_ptr); - EXPECT_TRUE(result.has_value()); - } - { - const auto pose_from = traffic_simulator::toCanonicalizedLaneletPose( - makePose(86788.82, 44993.77, 210.0), false, hdmap_utils_ptr); - ASSERT_TRUE(pose_from.has_value()); - const auto pose_to = traffic_simulator::toCanonicalizedLaneletPose( - makePose(86579.91, 44979.00, 150.0), false, hdmap_utils_ptr); - ASSERT_TRUE(pose_from.has_value()); - - const auto result = traffic_simulator::distance::longitudinalDistance( - pose_from.value(), pose_to.value(), false, false, true, hdmap_utils_ptr); - EXPECT_TRUE(result.has_value()); - } -} From ddd827a2186e7620843fde3751e9dd04e50fca2c Mon Sep 17 00:00:00 2001 From: robomic Date: Mon, 9 Sep 2024 12:07:21 +0200 Subject: [PATCH 230/304] move helper functions to the helper file --- .../test/src/helper_functions.hpp | 24 ++++++ .../test/src/utils/test_distance.cpp | 78 +++++++------------ 2 files changed, 52 insertions(+), 50 deletions(-) diff --git a/simulation/traffic_simulator/test/src/helper_functions.hpp b/simulation/traffic_simulator/test/src/helper_functions.hpp index ff0cb7248cc..a12b5e33328 100644 --- a/simulation/traffic_simulator/test/src/helper_functions.hpp +++ b/simulation/traffic_simulator/test/src/helper_functions.hpp @@ -26,6 +26,9 @@ #include "catalogs.hpp" #include "expect_eq_macros.hpp" +constexpr auto convertDegToRad(const double deg) -> double { return deg / 180.0 * M_PI; } +constexpr auto convertRadToDeg(const double rad) -> double { return rad * 180.0 / M_PI; } + auto makePoint(const double x, const double y, const double z = 0.0) -> geometry_msgs::msg::Point { return geometry_msgs::build().x(x).y(y).z(z); @@ -38,6 +41,15 @@ auto makeBoundingBox(const double center_y = 0.0) -> traffic_simulator_msgs::msg .dimensions(geometry_msgs::build().x(4.0).y(2.0).z(1.5)); } +auto makeCustom2DBoundingBox( + const double x, const double y, const double x_offset = 0.0, const double y_offset = 0.0) + -> traffic_simulator_msgs::msg::BoundingBox +{ + return traffic_simulator_msgs::build() + .center(geometry_msgs::build().x(x_offset).y(y_offset).z(0.0)) + .dimensions(geometry_msgs::build().x(x).y(y).z(0.0)); +} + auto makeSmallBoundingBox(const double center_y = 0.0) -> traffic_simulator_msgs::msg::BoundingBox { return traffic_simulator_msgs::build() @@ -51,6 +63,18 @@ auto makeQuaternionFromYaw(const double yaw) -> geometry_msgs::msg::Quaternion geometry_msgs::build().x(0.0).y(0.0).z(yaw)); } +auto makePose(const double x, const double y, const double yaw_deg) -> geometry_msgs::msg::Pose +{ + /** + * @note +x axis is 0 degrees; +y axis is 90 degrees + */ + return geometry_msgs::build() + .position(geometry_msgs::build().x(x).y(y).z(0.0)) + .orientation(math::geometry::convertEulerAngleToQuaternion( + geometry_msgs::build().x(0.0).y(0.0).z( + convertDegToRad(yaw_deg)))); +} + auto makePose( geometry_msgs::msg::Point position, geometry_msgs::msg::Quaternion orientation = geometry_msgs::msg::Quaternion()) diff --git a/simulation/traffic_simulator/test/src/utils/test_distance.cpp b/simulation/traffic_simulator/test/src/utils/test_distance.cpp index f312ce3184e..7d59aba49b5 100644 --- a/simulation/traffic_simulator/test/src/utils/test_distance.cpp +++ b/simulation/traffic_simulator/test/src/utils/test_distance.cpp @@ -23,6 +23,8 @@ #include #include +#include "../helper_functions.hpp" + int main(int argc, char ** argv) { testing::InitGoogleTest(&argc, argv); @@ -211,21 +213,6 @@ TEST_F(distanceTest_FourTrackHighway, lateralDistance_possible_matching) } } -constexpr auto convertDegToRad(const double deg) -> double { return deg / 180.0 * M_PI; } -constexpr auto convertRadToDeg(const double rad) -> double { return rad * 180.0 / M_PI; } - -auto makePose(const double x, const double y, const double yaw_deg) -> geometry_msgs::msg::Pose -{ - /** - * @note +x axis is 0 degrees; +y axis is 90 degrees - */ - return geometry_msgs::build() - .position(geometry_msgs::build().x(x).y(y).z(0.0)) - .orientation(math::geometry::convertEulerAngleToQuaternion( - geometry_msgs::build().x(0.0).y(0.0).z( - convertDegToRad(yaw_deg)))); -} - /** * @note Test calculation correctness with include_adjacent_lanelet = false, * include_opposite_direction = false, allow_lane_change = false @@ -446,15 +433,6 @@ TEST_F(distanceTest_Intersection, longitudinalDistance_adjacent_noOpposite_chang } } -auto makeBoundingBox( - const double x, const double y, const double x_offset = 0.0, const double y_offset = 0.0) - -> traffic_simulator_msgs::msg::BoundingBox -{ - return traffic_simulator_msgs::build() - .center(geometry_msgs::build().x(x_offset).y(y_offset).z(0.0)) - .dimensions(geometry_msgs::build().x(x).y(y).z(0.0)); -} - /** * @note Test equality with math::geometry::getPolygonDistance * function result on intersecting bounding boxes. @@ -463,8 +441,8 @@ TEST(distance, boundingBoxDistance_intersection) { const auto pose_from = makePose(100.0, 100.0, 0.0); const auto pose_to = makePose(120.0, 100.0, 90.0); - const auto bounding_box_from = makeBoundingBox(30.0, 1.0); - const auto bounding_box_to = makeBoundingBox(1.0, 30.0); + const auto bounding_box_from = makeCustom2DBoundingBox(30.0, 1.0); + const auto bounding_box_to = makeCustom2DBoundingBox(1.0, 30.0); const auto result_distance = traffic_simulator::distance::boundingBoxDistance( pose_from, bounding_box_from, pose_to, bounding_box_to); @@ -482,8 +460,8 @@ TEST(distance, boundingBoxDistance_disjoint) { const auto pose_from = makePose(100.0, 100.0, 0.0); const auto pose_to = makePose(120.0, 100.0, 90.0); - const auto bounding_box_from = makeBoundingBox(1.0, 30.0); - const auto bounding_box_to = makeBoundingBox(30.0, 1.0); + const auto bounding_box_from = makeCustom2DBoundingBox(1.0, 30.0); + const auto bounding_box_to = makeCustom2DBoundingBox(30.0, 1.0); const auto result_distance = traffic_simulator::distance::boundingBoxDistance( pose_from, bounding_box_from, pose_to, bounding_box_to); @@ -504,56 +482,56 @@ TEST_F(distanceTest_StandardMap, distanceToLeftLaneBound_single) constexpr double tolerance = 0.1; { const auto pose = makePose(3818.33, 73726.18, 30.0); - const auto bounding_box = makeBoundingBox(0.1, 0.1, 0.0, 0.0); + const auto bounding_box = makeCustom2DBoundingBox(0.1, 0.1, 0.0, 0.0); const double result = traffic_simulator::distance::distanceToLeftLaneBound( pose, bounding_box, lanelet_id, hdmap_utils_ptr); EXPECT_NEAR(result, 0.5, tolerance); } { const auto pose = makePose(3816.89, 73723.09, 30.0); - const auto bounding_box = makeBoundingBox(0.1, 0.1, 0.0, 0.0); + const auto bounding_box = makeCustom2DBoundingBox(0.1, 0.1, 0.0, 0.0); const double result = traffic_simulator::distance::distanceToLeftLaneBound( pose, bounding_box, lanelet_id, hdmap_utils_ptr); EXPECT_NEAR(result, 2.6, tolerance); } { const auto pose = makePose(3813.42, 73721.11, 30.0); - const auto bounding_box = makeBoundingBox(3.0, 0.1, 0.0, 0.0); + const auto bounding_box = makeCustom2DBoundingBox(3.0, 0.1, 0.0, 0.0); const double result = traffic_simulator::distance::distanceToLeftLaneBound( pose, bounding_box, lanelet_id, hdmap_utils_ptr); EXPECT_NEAR(result, 2.7, tolerance); } { const auto pose = makePose(3813.42, 73721.11, 120.0); - const auto bounding_box = makeBoundingBox(3.0, 0.1, 0.0, 0.0); + const auto bounding_box = makeCustom2DBoundingBox(3.0, 0.1, 0.0, 0.0); const double result = traffic_simulator::distance::distanceToLeftLaneBound( pose, bounding_box, lanelet_id, hdmap_utils_ptr); EXPECT_NEAR(result, 1.3, tolerance); } { const auto pose = makePose(3810.99, 73721.40, 30.0); - const auto bounding_box = makeBoundingBox(0.1, 0.1, 1.0, 0.0); + const auto bounding_box = makeCustom2DBoundingBox(0.1, 0.1, 1.0, 0.0); const double result = traffic_simulator::distance::distanceToLeftLaneBound( pose, bounding_box, lanelet_id, hdmap_utils_ptr); EXPECT_NEAR(result, 1.4, tolerance); } { const auto pose = makePose(3810.99, 73721.40, 30.0); - const auto bounding_box = makeBoundingBox(0.1, 0.1, 0.0, -1.0); + const auto bounding_box = makeCustom2DBoundingBox(0.1, 0.1, 0.0, -1.0); const double result = traffic_simulator::distance::distanceToLeftLaneBound( pose, bounding_box, lanelet_id, hdmap_utils_ptr); EXPECT_NEAR(result, 2.4, tolerance); } { const auto pose = makePose(3680.81, 73757.27, 30.0); - const auto bounding_box = makeBoundingBox(0.1, 0.1, 0.0, 0.0); + const auto bounding_box = makeCustom2DBoundingBox(0.1, 0.1, 0.0, 0.0); const double result = traffic_simulator::distance::distanceToLeftLaneBound( pose, bounding_box, 34684L, hdmap_utils_ptr); EXPECT_NEAR(result, 5.1, tolerance); } { const auto pose = makePose(3692.79, 73753.00, 30.0); - const auto bounding_box = makeBoundingBox(0.1, 0.1, 0.0, 0.0); + const auto bounding_box = makeCustom2DBoundingBox(0.1, 0.1, 0.0, 0.0); const double result = traffic_simulator::distance::distanceToLeftLaneBound( pose, bounding_box, 34684L, hdmap_utils_ptr); EXPECT_NEAR(result, 7.2, tolerance); @@ -568,7 +546,7 @@ TEST_F(distanceTest_StandardMap, distanceToLeftLaneBound_multipleVector) { const auto lanelet_ids = lanelet::Ids{34603L, 34600L, 34621L, 34741L}; const auto pose = makePose(3836.16, 73757.99, 120.0); - const auto bounding_box = makeBoundingBox(0.1, 0.1, 0.0, 0.0); + const auto bounding_box = makeCustom2DBoundingBox(0.1, 0.1, 0.0, 0.0); const double actual_distance = std::transform_reduce( lanelet_ids.cbegin(), lanelet_ids.cend(), std::numeric_limits::max(), [](const double lhs, const double rhs) { return std::min(lhs, rhs); }, @@ -590,7 +568,7 @@ TEST_F(distanceTest_StandardMap, distanceToLeftLaneBound_singleVector) { constexpr lanelet::Id lanelet_id = 34426L; const auto pose = makePose(3693.34, 73738.37, 300.0); - const auto bounding_box = makeBoundingBox(0.1, 0.1, 0.0, 0.0); + const auto bounding_box = makeCustom2DBoundingBox(0.1, 0.1, 0.0, 0.0); const double actual_distance = traffic_simulator::distance::distanceToLeftLaneBound( pose, bounding_box, lanelet_id, hdmap_utils_ptr); const double result_distance = traffic_simulator::distance::distanceToLeftLaneBound( @@ -605,7 +583,7 @@ TEST_F(distanceTest_StandardMap, distanceToLeftLaneBound_singleVector) TEST_F(distanceTest_StandardMap, distanceToLeftLaneBound_emptyVector) { const auto pose = makePose(3825.87, 73773.08, 135.0); - const auto bounding_box = makeBoundingBox(0.1, 0.1, 0.0, 0.0); + const auto bounding_box = makeCustom2DBoundingBox(0.1, 0.1, 0.0, 0.0); EXPECT_THROW( traffic_simulator::distance::distanceToLeftLaneBound( pose, bounding_box, lanelet::Ids{}, hdmap_utils_ptr), @@ -621,56 +599,56 @@ TEST_F(distanceTest_Intersection, distanceToRightLaneBound_single) constexpr double tolerance = 0.1; { const auto pose = makePose(86651.84, 44941.47, 135.0); - const auto bounding_box = makeBoundingBox(0.1, 0.1, 0.0, 0.0); + const auto bounding_box = makeCustom2DBoundingBox(0.1, 0.1, 0.0, 0.0); const double result = traffic_simulator::distance::distanceToRightLaneBound( pose, bounding_box, lanelet_id, hdmap_utils_ptr); EXPECT_NEAR(result, 4.1, tolerance); } { const auto pose = makePose(86653.05, 44946.74, 135.0); - const auto bounding_box = makeBoundingBox(0.1, 0.1, 0.0, 0.0); + const auto bounding_box = makeCustom2DBoundingBox(0.1, 0.1, 0.0, 0.0); const double result = traffic_simulator::distance::distanceToRightLaneBound( pose, bounding_box, lanelet_id, hdmap_utils_ptr); EXPECT_NEAR(result, 0.6, tolerance); } { const auto pose = makePose(86651.47, 44941.07, 120.0); - const auto bounding_box = makeBoundingBox(3.0, 0.1, 0.0, 0.0); + const auto bounding_box = makeCustom2DBoundingBox(3.0, 0.1, 0.0, 0.0); const double result = traffic_simulator::distance::distanceToRightLaneBound( pose, bounding_box, lanelet_id, hdmap_utils_ptr); EXPECT_NEAR(result, 4.3, tolerance); } { const auto pose = makePose(86651.47, 44941.07, 210.0); - const auto bounding_box = makeBoundingBox(3.0, 0.1, 0.0, 0.0); + const auto bounding_box = makeCustom2DBoundingBox(3.0, 0.1, 0.0, 0.0); const double result = traffic_simulator::distance::distanceToRightLaneBound( pose, bounding_box, lanelet_id, hdmap_utils_ptr); EXPECT_NEAR(result, 3.1, tolerance); } { const auto pose = makePose(86644.10, 44951.86, 150.0); - const auto bounding_box = makeBoundingBox(0.1, 0.1, 1.0, 0.0); + const auto bounding_box = makeCustom2DBoundingBox(0.1, 0.1, 1.0, 0.0); const double result = traffic_simulator::distance::distanceToRightLaneBound( pose, bounding_box, lanelet_id, hdmap_utils_ptr); EXPECT_NEAR(result, 2.0, tolerance); } { const auto pose = makePose(86644.10, 44951.86, 150.0); - const auto bounding_box = makeBoundingBox(0.1, 0.1, 0.0, -1.0); + const auto bounding_box = makeCustom2DBoundingBox(0.1, 0.1, 0.0, -1.0); const double result = traffic_simulator::distance::distanceToRightLaneBound( pose, bounding_box, lanelet_id, hdmap_utils_ptr); EXPECT_NEAR(result, 1.1, tolerance); } { const auto pose = makePose(86644.11, 44941.21, 0.0); - const auto bounding_box = makeBoundingBox(0.1, 0.1, 0.0, 0.0); + const auto bounding_box = makeCustom2DBoundingBox(0.1, 0.1, 0.0, 0.0); const double result = traffic_simulator::distance::distanceToRightLaneBound( pose, bounding_box, lanelet_id, hdmap_utils_ptr); EXPECT_NEAR(result, 11.2, tolerance); } { const auto pose = makePose(86656.83, 44946.96, 0.0); - const auto bounding_box = makeBoundingBox(0.1, 0.1, 0.0, 0.0); + const auto bounding_box = makeCustom2DBoundingBox(0.1, 0.1, 0.0, 0.0); const double result = traffic_simulator::distance::distanceToRightLaneBound( pose, bounding_box, lanelet_id, hdmap_utils_ptr); EXPECT_NEAR(result, 2.6, tolerance); @@ -685,7 +663,7 @@ TEST_F(distanceTest_Intersection, distanceToRightLaneBound_multipleVector) { const auto lanelet_ids = lanelet::Ids{660L, 663L, 684L, 654L, 686L}; const auto pose = makePose(86642.05, 44902.61, 60.0); - const auto bounding_box = makeBoundingBox(0.1, 0.1, 0.0, 0.0); + const auto bounding_box = makeCustom2DBoundingBox(0.1, 0.1, 0.0, 0.0); const double actual_distance = std::transform_reduce( lanelet_ids.cbegin(), lanelet_ids.cend(), std::numeric_limits::max(), [](const double lhs, const double rhs) { return std::min(lhs, rhs); }, @@ -707,7 +685,7 @@ TEST_F(distanceTest_Intersection, distanceToRightLaneBound_singleVector) { constexpr lanelet::Id lanelet_id = 654L; const auto pose = makePose(86702.79, 44929.05, 150.0); - const auto bounding_box = makeBoundingBox(0.1, 0.1, 0.0, 0.0); + const auto bounding_box = makeCustom2DBoundingBox(0.1, 0.1, 0.0, 0.0); const double actual_distance = traffic_simulator::distance::distanceToRightLaneBound( pose, bounding_box, lanelet_id, hdmap_utils_ptr); const double result_distance = traffic_simulator::distance::distanceToRightLaneBound( @@ -722,7 +700,7 @@ TEST_F(distanceTest_Intersection, distanceToRightLaneBound_singleVector) TEST_F(distanceTest_Intersection, distanceToRightLaneBound_emptyVector) { const auto pose = makePose(3825.87, 73773.08, 135.0); - const auto bounding_box = makeBoundingBox(0.1, 0.1, 0.0, 0.0); + const auto bounding_box = makeCustom2DBoundingBox(0.1, 0.1, 0.0, 0.0); EXPECT_THROW( traffic_simulator::distance::distanceToRightLaneBound( pose, bounding_box, lanelet::Ids{}, hdmap_utils_ptr), From 98ef430d21c6e280141dae62d744bec65a897b43 Mon Sep 17 00:00:00 2001 From: Grzegorz Maj Date: Mon, 12 Aug 2024 14:50:16 +0200 Subject: [PATCH 231/304] CanonicalizedLaneletPose unit tests --- .../behavior/behavior_plugin_base.hpp | 14 +- .../traffic_simulator/test/CMakeLists.txt | 1 + .../test/src/data_type/CMakeLists.txt | 3 + .../test/src/data_type/test_lanelet_pose.cpp | 390 ++++++++++++++++++ 4 files changed, 401 insertions(+), 7 deletions(-) create mode 100644 simulation/traffic_simulator/test/src/data_type/CMakeLists.txt create mode 100644 simulation/traffic_simulator/test/src/data_type/test_lanelet_pose.cpp diff --git a/simulation/traffic_simulator/include/traffic_simulator/behavior/behavior_plugin_base.hpp b/simulation/traffic_simulator/include/traffic_simulator/behavior/behavior_plugin_base.hpp index 0d4847f7d5c..ddb8d118055 100644 --- a/simulation/traffic_simulator/include/traffic_simulator/behavior/behavior_plugin_base.hpp +++ b/simulation/traffic_simulator/include/traffic_simulator/behavior/behavior_plugin_base.hpp @@ -44,13 +44,13 @@ class BehaviorPluginBase virtual auto update(const double current_time, const double step_time) -> void = 0; virtual const std::string & getCurrentAction() const = 0; -#define DEFINE_GETTER_SETTER(NAME, KEY, TYPE) \ - virtual TYPE get##NAME() = 0; \ - virtual void set##NAME(const TYPE & value) = 0; \ - auto get##NAME##Key() const->const std::string & \ - { \ - static const std::string key = KEY; \ - return key; \ +#define DEFINE_GETTER_SETTER(NAME, KEY, TYPE) \ + virtual TYPE get##NAME() = 0; \ + virtual void set##NAME(const TYPE & value) = 0; \ + auto get##NAME##Key() const -> const std::string & \ + { \ + static const std::string key = KEY; \ + return key; \ } // clang-format off diff --git a/simulation/traffic_simulator/test/CMakeLists.txt b/simulation/traffic_simulator/test/CMakeLists.txt index 713c8b40678..32f62d79252 100644 --- a/simulation/traffic_simulator/test/CMakeLists.txt +++ b/simulation/traffic_simulator/test/CMakeLists.txt @@ -5,3 +5,4 @@ add_subdirectory(src/behavior) add_subdirectory(src/job) add_subdirectory(src/simulation_clock) add_subdirectory(src/hdmap_utils) +add_subdirectory(src/data_type) diff --git a/simulation/traffic_simulator/test/src/data_type/CMakeLists.txt b/simulation/traffic_simulator/test/src/data_type/CMakeLists.txt new file mode 100644 index 00000000000..50bc1214813 --- /dev/null +++ b/simulation/traffic_simulator/test/src/data_type/CMakeLists.txt @@ -0,0 +1,3 @@ +ament_add_gtest(test_lanelet_pose test_lanelet_pose.cpp) +target_link_libraries(test_lanelet_pose traffic_simulator) + diff --git a/simulation/traffic_simulator/test/src/data_type/test_lanelet_pose.cpp b/simulation/traffic_simulator/test/src/data_type/test_lanelet_pose.cpp new file mode 100644 index 00000000000..9c8cbe27c20 --- /dev/null +++ b/simulation/traffic_simulator/test/src/data_type/test_lanelet_pose.cpp @@ -0,0 +1,390 @@ +// Copyright 2015 TIER IV, Inc. All rights reserved. +// +// 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. + +#include + +#include +#include + +#include "../helper_functions.hpp" + +using CanonicalizedLaneletPose = traffic_simulator::lanelet_pose::CanonicalizedLaneletPose; + +int main(int argc, char ** argv) +{ + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} + +/** + * @note Test constructor behavior with route_lanelets argument present when canonicalization function fails. + */ +TEST(CanonicalizedLaneletPose, CanonicalizedLaneletPose_withRoute_invalid) +{ + auto hdmap_utils = makeHdMapUtilsSharedPointer(); + EXPECT_THROW( + CanonicalizedLaneletPose( + traffic_simulator::helper::constructLaneletPose(120576, 14.6356, 0.0), lanelet::Ids{}, + hdmap_utils), + std::runtime_error); +} + +/** + * @note Test constructor behavior with route_lanelets argument present when canonicalization function succeeds + */ +TEST(CanonicalizedLaneletPose, CanonicalizedLaneletPose_withRoute) +{ + auto hdmap_utils = makeHdMapUtilsSharedPointer(); + std::shared_ptr pose; + EXPECT_NO_THROW( + pose = std::make_shared( + traffic_simulator::helper::constructLaneletPose(120659, 0.0, 0.0), lanelet::Ids{120659}, + hdmap_utils)); + EXPECT_LANELET_POSE_EQ( + static_cast(*pose), + traffic_simulator::helper::constructLaneletPose(120659, 0.0, 0.0)); +} + +/** + * @note Test constructor behavior with route_lanelets argument absent when canonicalization function fails + */ +TEST(CanonicalizedLaneletPose, CanonicalizedLaneletPose_withoutRoute_invalid) +{ + auto hdmap_utils = makeHdMapUtilsSharedPointer(); + EXPECT_THROW( + CanonicalizedLaneletPose( + traffic_simulator::helper::constructLaneletPose(120576, 0.0, 0.0), hdmap_utils), + std::runtime_error); +} + +/** + * @note Test constructor behavior with route_lanelets argument absent when canonicalization function succeeds + */ +TEST(CanonicalizedLaneletPose, CanonicalizedLaneletPose_withoutRoute) +{ + auto hdmap_utils = makeHdMapUtilsSharedPointer(); + std::shared_ptr pose; + EXPECT_NO_THROW( + pose = std::make_shared( + traffic_simulator::helper::constructLaneletPose(120659, 0.0, 0.0), hdmap_utils)); + EXPECT_LANELET_POSE_EQ( + static_cast(*pose), + traffic_simulator::helper::constructLaneletPose(120659, 0.0, 0.0)); +} + +/** + * @note Test copy constructor behavior + */ +TEST(CanonicalizedLaneletPose, CanonicalizedLaneletPose_copyConstructor) +{ + auto hdmap_utils = makeHdMapUtilsSharedPointer(); + CanonicalizedLaneletPose pose( + traffic_simulator::helper::constructLaneletPose(120659, 0.0, 0.0), hdmap_utils); + CanonicalizedLaneletPose pose_copy(pose); + EXPECT_LANELET_POSE_EQ( + static_cast(pose), + static_cast(CanonicalizedLaneletPose(pose))); +} + +/** + * @note Test move constructor behavior + */ +TEST(CanonicalizedLaneletPose, CanonicalizedLaneletPose_moveConstructor) +{ + auto hdmap_utils = makeHdMapUtilsSharedPointer(); + CanonicalizedLaneletPose pose( + traffic_simulator::helper::constructLaneletPose(120659, 0.0, 0.0), hdmap_utils); + CanonicalizedLaneletPose pose2(pose); + CanonicalizedLaneletPose pose_move = std::move(pose2); + EXPECT_LANELET_POSE_EQ( + static_cast(pose), + static_cast(pose_move)); +} + +/** + * @note Test copy assignment operator behavior + */ +TEST(CanonicalizedLaneletPose, copyAssignment) +{ + auto hdmap_utils = makeHdMapUtilsSharedPointer(); + CanonicalizedLaneletPose pose( + traffic_simulator::helper::constructLaneletPose(120659, 0.0, 0.0), hdmap_utils); + CanonicalizedLaneletPose pose_assign( + traffic_simulator::helper::constructLaneletPose(34468, 0.0, 0.0), hdmap_utils); + + pose_assign = pose; + + EXPECT_LANELET_POSE_EQ( + static_cast(pose), + static_cast(pose_assign)); +} + +/** + * @note Test conversion operator behavior using static_cast + */ +TEST(CanonicalizedLaneletPose, conversionLaneletPose) +{ + auto hdmap_utils = makeHdMapUtilsSharedPointer(); + CanonicalizedLaneletPose pose( + traffic_simulator::helper::constructLaneletPose(120659, 0.0, 0.0), hdmap_utils); + traffic_simulator::LaneletPose pose_casted = static_cast(pose); + + EXPECT_EQ(pose_casted.lanelet_id, 120659); + EXPECT_DOUBLE_EQ(pose_casted.s, 0.0); + EXPECT_DOUBLE_EQ(pose_casted.offset, 0.0); + EXPECT_VECTOR3_EQ(pose_casted.rpy, geometry_msgs::msg::Vector3()); +} + +/** + * @note Test conversion operator behavior using static_cast + */ +TEST(CanonicalizedLaneletPose, conversionPose) +{ + auto hdmap_utils = makeHdMapUtilsSharedPointer(); + CanonicalizedLaneletPose pose( + traffic_simulator::helper::constructLaneletPose(120659, 0.0, 0.0), hdmap_utils); + + geometry_msgs::msg::Pose pose1 = + makePose(makePoint(3822.3815, 73784.9618, -1.761), makeQuaternionFromYaw(2.060578777273)); + + EXPECT_POSE_NEAR(static_cast(pose), pose1, 0.01); +} + +/** + * @note Test function behavior when alternative poses are present + */ +TEST(CanonicalizedLaneletPose, hasAlternativeLaneletPose_true) +{ + auto hdmap_utils = makeHdMapUtilsSharedPointer(); + CanonicalizedLaneletPose pose( + traffic_simulator::helper::constructLaneletPose(120659, -10.0, 0.0), hdmap_utils); + + EXPECT_TRUE(pose.hasAlternativeLaneletPose()); +} + +/** + * @note Test function behavior when alternative poses are absent + */ +TEST(CanonicalizedLaneletPose, hasAlternativeLaneletPose_false) +{ + auto hdmap_utils = makeHdMapUtilsSharedPointer(); + CanonicalizedLaneletPose pose( + traffic_simulator::helper::constructLaneletPose(120659, 10.0, 0.0), hdmap_utils); + + EXPECT_FALSE(pose.hasAlternativeLaneletPose()); +} + +/** + * @note Test function behavior when there are no lanelet_poses + */ +TEST(CanonicalizedLaneletPose, getAlternativeLaneletPoseBaseOnShortestRouteFrom_empty) +{ + auto hdmap_utils = makeHdMapUtilsSharedPointer(); + CanonicalizedLaneletPose pose( + traffic_simulator::helper::constructLaneletPose(120659, 20.0, 0.0), hdmap_utils); + const auto from1 = traffic_simulator::helper::constructLaneletPose(34603, 10.0, 0.0); + const auto from2 = traffic_simulator::helper::constructLaneletPose(34579, 10.0, 0.0); + + const auto result1 = pose.getAlternativeLaneletPoseBaseOnShortestRouteFrom(from1, hdmap_utils); + const auto result2 = pose.getAlternativeLaneletPoseBaseOnShortestRouteFrom(from2, hdmap_utils); + + EXPECT_EQ(result1.value().lanelet_id, 120659); + EXPECT_EQ(result2.value().lanelet_id, 120659); +} + +/** + * @note Test function behavior when there is only one lanelet_pose + */ +TEST(CanonicalizedLaneletPose, getAlternativeLaneletPoseBaseOnShortestRouteFrom_single) +{ + auto hdmap_utils = makeHdMapUtilsSharedPointer(); + CanonicalizedLaneletPose pose( + traffic_simulator::helper::constructLaneletPose(34666, -20.0, 0.0), hdmap_utils); + const auto from1 = traffic_simulator::helper::constructLaneletPose(34603, 10.0, 0.0); + const auto from2 = traffic_simulator::helper::constructLaneletPose(34579, 10.0, 0.0); + + const auto result1 = pose.getAlternativeLaneletPoseBaseOnShortestRouteFrom(from1, hdmap_utils); + const auto result2 = pose.getAlternativeLaneletPoseBaseOnShortestRouteFrom(from2, hdmap_utils); + + EXPECT_EQ(result1.value().lanelet_id, 34603); + EXPECT_EQ(result2.value().lanelet_id, 34603); +} + +/** + * @note Test function behavior when there are multiple lanelet_poses + */ +TEST(CanonicalizedLaneletPose, getAlternativeLaneletPoseBaseOnShortestRouteFrom_multiple) +{ + auto hdmap_utils = makeHdMapUtilsSharedPointer(); + CanonicalizedLaneletPose pose( + traffic_simulator::helper::constructLaneletPose(120659, -20.0, 0.0), hdmap_utils); + const auto from1 = traffic_simulator::helper::constructLaneletPose(34603, 10.0, 0.0); + const auto from2 = traffic_simulator::helper::constructLaneletPose(34579, 10.0, 0.0); + + const auto result1 = pose.getAlternativeLaneletPoseBaseOnShortestRouteFrom(from1, hdmap_utils); + const auto result2 = pose.getAlternativeLaneletPoseBaseOnShortestRouteFrom(from2, hdmap_utils); + + EXPECT_EQ(result1.value().lanelet_id, 34603); + EXPECT_EQ(result2.value().lanelet_id, 34579); +} + +/** + * @note Test accessor function + */ +TEST(CanonicalizedLaneletPose, getConsiderPoseByRoadSlope) +{ + EXPECT_EQ(CanonicalizedLaneletPose::getConsiderPoseByRoadSlope(), false); +} + +/** + * @note Test accessor function + */ +TEST(CanonicalizedLaneletPose, setConsiderPoseByRoadSlope) +{ + EXPECT_EQ(CanonicalizedLaneletPose::getConsiderPoseByRoadSlope(), false); + CanonicalizedLaneletPose::setConsiderPoseByRoadSlope(true); + EXPECT_EQ(CanonicalizedLaneletPose::getConsiderPoseByRoadSlope(), true); +} + +/** + * @note Test operator calculation correctness with CanonicalizedLaneletPose of lesser, equal and greater lanelet_id + */ +TEST(CanonicalizedLaneletPose, operatorLessEqual) +{ + auto hdmap_utils = makeHdMapUtilsSharedPointer(); + CanonicalizedLaneletPose pose( + traffic_simulator::helper::constructLaneletPose(120659, 5.0, 0.0), hdmap_utils); + CanonicalizedLaneletPose pose_equal( + traffic_simulator::helper::constructLaneletPose(120659, 5.0, 0.0), hdmap_utils); + CanonicalizedLaneletPose pose_less( + traffic_simulator::helper::constructLaneletPose(120659, 0.0, 0.0), hdmap_utils); + CanonicalizedLaneletPose pose_greater( + traffic_simulator::helper::constructLaneletPose(120659, 6.0, 0.0), hdmap_utils); + + EXPECT_TRUE(pose_less <= pose); + EXPECT_TRUE(pose_equal <= pose); + EXPECT_FALSE(pose_greater <= pose); +} + +/** + * @note Test operator calculation correctness with CanonicalizedLaneletPose of lesser, equal and greater lanelet_id + */ +TEST(CanonicalizedLaneletPose, operatorLess) +{ + auto hdmap_utils = makeHdMapUtilsSharedPointer(); + CanonicalizedLaneletPose pose( + traffic_simulator::helper::constructLaneletPose(120659, 5.0, 0.0), hdmap_utils); + CanonicalizedLaneletPose pose_equal( + traffic_simulator::helper::constructLaneletPose(120659, 5.0, 0.0), hdmap_utils); + CanonicalizedLaneletPose pose_less( + traffic_simulator::helper::constructLaneletPose(120659, 0.0, 0.0), hdmap_utils); + CanonicalizedLaneletPose pose_greater( + traffic_simulator::helper::constructLaneletPose(120659, 6.0, 0.0), hdmap_utils); + + EXPECT_TRUE(pose_less < pose); + EXPECT_FALSE(pose_equal < pose); + EXPECT_FALSE(pose_greater < pose); +} + +/** + * @note Test operator calculation correctness with CanonicalizedLaneletPose of lesser, equal and greater lanelet_id + */ +TEST(CanonicalizedLaneletPose, operatorGreaterEqual) +{ + auto hdmap_utils = makeHdMapUtilsSharedPointer(); + CanonicalizedLaneletPose pose( + traffic_simulator::helper::constructLaneletPose(120659, 5.0, 0.0), hdmap_utils); + CanonicalizedLaneletPose pose_equal( + traffic_simulator::helper::constructLaneletPose(120659, 5.0, 0.0), hdmap_utils); + CanonicalizedLaneletPose pose_less( + traffic_simulator::helper::constructLaneletPose(120659, 0.0, 0.0), hdmap_utils); + CanonicalizedLaneletPose pose_greater( + traffic_simulator::helper::constructLaneletPose(120659, 6.0, 0.0), hdmap_utils); + + EXPECT_FALSE(pose_less >= pose); + EXPECT_TRUE(pose_equal >= pose); + EXPECT_TRUE(pose_greater >= pose); +} + +/** + * @note Test operator calculation correctness with CanonicalizedLaneletPose of lesser, equal and greater lanelet_id + */ +TEST(CanonicalizedLaneletPose, operatorGreater) +{ + auto hdmap_utils = makeHdMapUtilsSharedPointer(); + CanonicalizedLaneletPose pose( + traffic_simulator::helper::constructLaneletPose(120659, 5.0, 0.0), hdmap_utils); + CanonicalizedLaneletPose pose_equal( + traffic_simulator::helper::constructLaneletPose(120659, 5.0, 0.0), hdmap_utils); + CanonicalizedLaneletPose pose_less( + traffic_simulator::helper::constructLaneletPose(120659, 0.0, 0.0), hdmap_utils); + CanonicalizedLaneletPose pose_greater( + traffic_simulator::helper::constructLaneletPose(120659, 6.0, 0.0), hdmap_utils); + + EXPECT_FALSE(pose_less > pose); + EXPECT_FALSE(pose_equal > pose); + EXPECT_TRUE(pose_greater > pose); +} + +/** + * @note Test function behavior when provided two poses occupying the same lanelet_id + */ +TEST(CanonicalizedLaneletPose, isSameLaneletId_withPose_same) +{ + auto hdmap_utils = makeHdMapUtilsSharedPointer(); + CanonicalizedLaneletPose pose1( + traffic_simulator::helper::constructLaneletPose(120659, 0.0, 0.0), hdmap_utils); + CanonicalizedLaneletPose pose2( + traffic_simulator::helper::constructLaneletPose(120659, 1.0, 0.0), hdmap_utils); + + EXPECT_TRUE(traffic_simulator::isSameLaneletId(pose1, pose2)); +} + +/** + * @note Test function behavior when provided two poses occupying different lanelet_ids + */ +TEST(CanonicalizedLaneletPose, isSameLaneletId_withPose_different) +{ + auto hdmap_utils = makeHdMapUtilsSharedPointer(); + CanonicalizedLaneletPose pose1( + traffic_simulator::helper::constructLaneletPose(120659, 0.0, 0.0), hdmap_utils); + CanonicalizedLaneletPose pose2( + traffic_simulator::helper::constructLaneletPose(34606, 1.0, 0.0), hdmap_utils); + + EXPECT_FALSE(traffic_simulator::isSameLaneletId(pose1, pose2)); +} + +/** + * @note Test function behavior when provided with a pose having lanelt_id equal to the lanelet_id argument + */ +TEST(CanonicalizedLaneletPose, isSameLaneletId_withLanelet_same) +{ + auto hdmap_utils = makeHdMapUtilsSharedPointer(); + CanonicalizedLaneletPose pose( + traffic_simulator::helper::constructLaneletPose(120659, 0.0, 0.0), hdmap_utils); + + EXPECT_TRUE(traffic_simulator::isSameLaneletId(pose, 120659)); +} + +/** + * @note Test function behavior when provided with a pose having lanelet_id different to the lanelet_id argument + */ +TEST(CanonicalizedLaneletPose, isSameLaneletId_withLanelet_different) +{ + auto hdmap_utils = makeHdMapUtilsSharedPointer(); + CanonicalizedLaneletPose pose( + traffic_simulator::helper::constructLaneletPose(120659, 0.0, 0.0), hdmap_utils); + + EXPECT_FALSE(traffic_simulator::isSameLaneletId(pose, 34606)); +} \ No newline at end of file From 1175efdd9a22686c182f736aa56aef29b32516cd Mon Sep 17 00:00:00 2001 From: Grzegorz Maj Date: Fri, 16 Aug 2024 14:54:35 +0200 Subject: [PATCH 232/304] Unit tests review changes --- .../behavior/behavior_plugin_base.hpp | 14 +- .../test/src/data_type/test_lanelet_pose.cpp | 154 +++++++++--------- 2 files changed, 81 insertions(+), 87 deletions(-) diff --git a/simulation/traffic_simulator/include/traffic_simulator/behavior/behavior_plugin_base.hpp b/simulation/traffic_simulator/include/traffic_simulator/behavior/behavior_plugin_base.hpp index ddb8d118055..0d4847f7d5c 100644 --- a/simulation/traffic_simulator/include/traffic_simulator/behavior/behavior_plugin_base.hpp +++ b/simulation/traffic_simulator/include/traffic_simulator/behavior/behavior_plugin_base.hpp @@ -44,13 +44,13 @@ class BehaviorPluginBase virtual auto update(const double current_time, const double step_time) -> void = 0; virtual const std::string & getCurrentAction() const = 0; -#define DEFINE_GETTER_SETTER(NAME, KEY, TYPE) \ - virtual TYPE get##NAME() = 0; \ - virtual void set##NAME(const TYPE & value) = 0; \ - auto get##NAME##Key() const -> const std::string & \ - { \ - static const std::string key = KEY; \ - return key; \ +#define DEFINE_GETTER_SETTER(NAME, KEY, TYPE) \ + virtual TYPE get##NAME() = 0; \ + virtual void set##NAME(const TYPE & value) = 0; \ + auto get##NAME##Key() const->const std::string & \ + { \ + static const std::string key = KEY; \ + return key; \ } // clang-format off diff --git a/simulation/traffic_simulator/test/src/data_type/test_lanelet_pose.cpp b/simulation/traffic_simulator/test/src/data_type/test_lanelet_pose.cpp index 9c8cbe27c20..635957dcf1a 100644 --- a/simulation/traffic_simulator/test/src/data_type/test_lanelet_pose.cpp +++ b/simulation/traffic_simulator/test/src/data_type/test_lanelet_pose.cpp @@ -14,7 +14,6 @@ #include -#include #include #include "../helper_functions.hpp" @@ -26,13 +25,19 @@ int main(int argc, char ** argv) testing::InitGoogleTest(&argc, argv); return RUN_ALL_TESTS(); } +class CanonicalizedLaneletPoseTest : public testing::Test +{ +protected: + CanonicalizedLaneletPoseTest() : hdmap_utils(makeHdMapUtilsSharedPointer()) {} + + std::shared_ptr hdmap_utils; +}; /** * @note Test constructor behavior with route_lanelets argument present when canonicalization function fails. */ -TEST(CanonicalizedLaneletPose, CanonicalizedLaneletPose_withRoute_invalid) +TEST_F(CanonicalizedLaneletPoseTest, CanonicalizedLaneletPose_withRoute_invalid) { - auto hdmap_utils = makeHdMapUtilsSharedPointer(); EXPECT_THROW( CanonicalizedLaneletPose( traffic_simulator::helper::constructLaneletPose(120576, 14.6356, 0.0), lanelet::Ids{}, @@ -43,9 +48,8 @@ TEST(CanonicalizedLaneletPose, CanonicalizedLaneletPose_withRoute_invalid) /** * @note Test constructor behavior with route_lanelets argument present when canonicalization function succeeds */ -TEST(CanonicalizedLaneletPose, CanonicalizedLaneletPose_withRoute) +TEST_F(CanonicalizedLaneletPoseTest, CanonicalizedLaneletPose_withRoute) { - auto hdmap_utils = makeHdMapUtilsSharedPointer(); std::shared_ptr pose; EXPECT_NO_THROW( pose = std::make_shared( @@ -59,9 +63,8 @@ TEST(CanonicalizedLaneletPose, CanonicalizedLaneletPose_withRoute) /** * @note Test constructor behavior with route_lanelets argument absent when canonicalization function fails */ -TEST(CanonicalizedLaneletPose, CanonicalizedLaneletPose_withoutRoute_invalid) +TEST_F(CanonicalizedLaneletPoseTest, CanonicalizedLaneletPose_withoutRoute_invalid) { - auto hdmap_utils = makeHdMapUtilsSharedPointer(); EXPECT_THROW( CanonicalizedLaneletPose( traffic_simulator::helper::constructLaneletPose(120576, 0.0, 0.0), hdmap_utils), @@ -71,9 +74,8 @@ TEST(CanonicalizedLaneletPose, CanonicalizedLaneletPose_withoutRoute_invalid) /** * @note Test constructor behavior with route_lanelets argument absent when canonicalization function succeeds */ -TEST(CanonicalizedLaneletPose, CanonicalizedLaneletPose_withoutRoute) +TEST_F(CanonicalizedLaneletPoseTest, CanonicalizedLaneletPose_withoutRoute) { - auto hdmap_utils = makeHdMapUtilsSharedPointer(); std::shared_ptr pose; EXPECT_NO_THROW( pose = std::make_shared( @@ -86,12 +88,11 @@ TEST(CanonicalizedLaneletPose, CanonicalizedLaneletPose_withoutRoute) /** * @note Test copy constructor behavior */ -TEST(CanonicalizedLaneletPose, CanonicalizedLaneletPose_copyConstructor) +TEST_F(CanonicalizedLaneletPoseTest, CanonicalizedLaneletPose_copyConstructor) { - auto hdmap_utils = makeHdMapUtilsSharedPointer(); - CanonicalizedLaneletPose pose( + const CanonicalizedLaneletPose pose( traffic_simulator::helper::constructLaneletPose(120659, 0.0, 0.0), hdmap_utils); - CanonicalizedLaneletPose pose_copy(pose); + const CanonicalizedLaneletPose pose_copy(pose); EXPECT_LANELET_POSE_EQ( static_cast(pose), static_cast(CanonicalizedLaneletPose(pose))); @@ -100,13 +101,12 @@ TEST(CanonicalizedLaneletPose, CanonicalizedLaneletPose_copyConstructor) /** * @note Test move constructor behavior */ -TEST(CanonicalizedLaneletPose, CanonicalizedLaneletPose_moveConstructor) +TEST_F(CanonicalizedLaneletPoseTest, CanonicalizedLaneletPose_moveConstructor) { - auto hdmap_utils = makeHdMapUtilsSharedPointer(); - CanonicalizedLaneletPose pose( + const CanonicalizedLaneletPose pose( traffic_simulator::helper::constructLaneletPose(120659, 0.0, 0.0), hdmap_utils); - CanonicalizedLaneletPose pose2(pose); - CanonicalizedLaneletPose pose_move = std::move(pose2); + const CanonicalizedLaneletPose pose2(pose); + const CanonicalizedLaneletPose pose_move = std::move(pose2); EXPECT_LANELET_POSE_EQ( static_cast(pose), static_cast(pose_move)); @@ -115,10 +115,9 @@ TEST(CanonicalizedLaneletPose, CanonicalizedLaneletPose_moveConstructor) /** * @note Test copy assignment operator behavior */ -TEST(CanonicalizedLaneletPose, copyAssignment) +TEST_F(CanonicalizedLaneletPoseTest, copyAssignment) { - auto hdmap_utils = makeHdMapUtilsSharedPointer(); - CanonicalizedLaneletPose pose( + const CanonicalizedLaneletPose pose( traffic_simulator::helper::constructLaneletPose(120659, 0.0, 0.0), hdmap_utils); CanonicalizedLaneletPose pose_assign( traffic_simulator::helper::constructLaneletPose(34468, 0.0, 0.0), hdmap_utils); @@ -133,12 +132,12 @@ TEST(CanonicalizedLaneletPose, copyAssignment) /** * @note Test conversion operator behavior using static_cast */ -TEST(CanonicalizedLaneletPose, conversionLaneletPose) +TEST_F(CanonicalizedLaneletPoseTest, conversionLaneletPose) { - auto hdmap_utils = makeHdMapUtilsSharedPointer(); - CanonicalizedLaneletPose pose( + const CanonicalizedLaneletPose pose( traffic_simulator::helper::constructLaneletPose(120659, 0.0, 0.0), hdmap_utils); - traffic_simulator::LaneletPose pose_casted = static_cast(pose); + const traffic_simulator::LaneletPose pose_casted = + static_cast(pose); EXPECT_EQ(pose_casted.lanelet_id, 120659); EXPECT_DOUBLE_EQ(pose_casted.s, 0.0); @@ -149,13 +148,12 @@ TEST(CanonicalizedLaneletPose, conversionLaneletPose) /** * @note Test conversion operator behavior using static_cast */ -TEST(CanonicalizedLaneletPose, conversionPose) +TEST_F(CanonicalizedLaneletPoseTest, conversionPose) { - auto hdmap_utils = makeHdMapUtilsSharedPointer(); - CanonicalizedLaneletPose pose( + const CanonicalizedLaneletPose pose( traffic_simulator::helper::constructLaneletPose(120659, 0.0, 0.0), hdmap_utils); - geometry_msgs::msg::Pose pose1 = + const geometry_msgs::msg::Pose pose1 = makePose(makePoint(3822.3815, 73784.9618, -1.761), makeQuaternionFromYaw(2.060578777273)); EXPECT_POSE_NEAR(static_cast(pose), pose1, 0.01); @@ -164,10 +162,9 @@ TEST(CanonicalizedLaneletPose, conversionPose) /** * @note Test function behavior when alternative poses are present */ -TEST(CanonicalizedLaneletPose, hasAlternativeLaneletPose_true) +TEST_F(CanonicalizedLaneletPoseTest, hasAlternativeLaneletPose_true) { - auto hdmap_utils = makeHdMapUtilsSharedPointer(); - CanonicalizedLaneletPose pose( + const CanonicalizedLaneletPose pose( traffic_simulator::helper::constructLaneletPose(120659, -10.0, 0.0), hdmap_utils); EXPECT_TRUE(pose.hasAlternativeLaneletPose()); @@ -176,10 +173,9 @@ TEST(CanonicalizedLaneletPose, hasAlternativeLaneletPose_true) /** * @note Test function behavior when alternative poses are absent */ -TEST(CanonicalizedLaneletPose, hasAlternativeLaneletPose_false) +TEST_F(CanonicalizedLaneletPoseTest, hasAlternativeLaneletPose_false) { - auto hdmap_utils = makeHdMapUtilsSharedPointer(); - CanonicalizedLaneletPose pose( + const CanonicalizedLaneletPose pose( traffic_simulator::helper::constructLaneletPose(120659, 10.0, 0.0), hdmap_utils); EXPECT_FALSE(pose.hasAlternativeLaneletPose()); @@ -188,10 +184,9 @@ TEST(CanonicalizedLaneletPose, hasAlternativeLaneletPose_false) /** * @note Test function behavior when there are no lanelet_poses */ -TEST(CanonicalizedLaneletPose, getAlternativeLaneletPoseBaseOnShortestRouteFrom_empty) +TEST_F(CanonicalizedLaneletPoseTest, getAlternativeLaneletPoseBaseOnShortestRouteFrom_empty) { - auto hdmap_utils = makeHdMapUtilsSharedPointer(); - CanonicalizedLaneletPose pose( + const CanonicalizedLaneletPose pose( traffic_simulator::helper::constructLaneletPose(120659, 20.0, 0.0), hdmap_utils); const auto from1 = traffic_simulator::helper::constructLaneletPose(34603, 10.0, 0.0); const auto from2 = traffic_simulator::helper::constructLaneletPose(34579, 10.0, 0.0); @@ -199,6 +194,9 @@ TEST(CanonicalizedLaneletPose, getAlternativeLaneletPoseBaseOnShortestRouteFrom_ const auto result1 = pose.getAlternativeLaneletPoseBaseOnShortestRouteFrom(from1, hdmap_utils); const auto result2 = pose.getAlternativeLaneletPoseBaseOnShortestRouteFrom(from2, hdmap_utils); + ASSERT_TRUE(result1); + ASSERT_TRUE(result2); + EXPECT_EQ(result1.value().lanelet_id, 120659); EXPECT_EQ(result2.value().lanelet_id, 120659); } @@ -206,9 +204,8 @@ TEST(CanonicalizedLaneletPose, getAlternativeLaneletPoseBaseOnShortestRouteFrom_ /** * @note Test function behavior when there is only one lanelet_pose */ -TEST(CanonicalizedLaneletPose, getAlternativeLaneletPoseBaseOnShortestRouteFrom_single) +TEST_F(CanonicalizedLaneletPoseTest, getAlternativeLaneletPoseBaseOnShortestRouteFrom_single) { - auto hdmap_utils = makeHdMapUtilsSharedPointer(); CanonicalizedLaneletPose pose( traffic_simulator::helper::constructLaneletPose(34666, -20.0, 0.0), hdmap_utils); const auto from1 = traffic_simulator::helper::constructLaneletPose(34603, 10.0, 0.0); @@ -217,6 +214,9 @@ TEST(CanonicalizedLaneletPose, getAlternativeLaneletPoseBaseOnShortestRouteFrom_ const auto result1 = pose.getAlternativeLaneletPoseBaseOnShortestRouteFrom(from1, hdmap_utils); const auto result2 = pose.getAlternativeLaneletPoseBaseOnShortestRouteFrom(from2, hdmap_utils); + ASSERT_TRUE(result1); + ASSERT_TRUE(result2); + EXPECT_EQ(result1.value().lanelet_id, 34603); EXPECT_EQ(result2.value().lanelet_id, 34603); } @@ -224,9 +224,8 @@ TEST(CanonicalizedLaneletPose, getAlternativeLaneletPoseBaseOnShortestRouteFrom_ /** * @note Test function behavior when there are multiple lanelet_poses */ -TEST(CanonicalizedLaneletPose, getAlternativeLaneletPoseBaseOnShortestRouteFrom_multiple) +TEST_F(CanonicalizedLaneletPoseTest, getAlternativeLaneletPoseBaseOnShortestRouteFrom_multiple) { - auto hdmap_utils = makeHdMapUtilsSharedPointer(); CanonicalizedLaneletPose pose( traffic_simulator::helper::constructLaneletPose(120659, -20.0, 0.0), hdmap_utils); const auto from1 = traffic_simulator::helper::constructLaneletPose(34603, 10.0, 0.0); @@ -235,6 +234,9 @@ TEST(CanonicalizedLaneletPose, getAlternativeLaneletPoseBaseOnShortestRouteFrom_ const auto result1 = pose.getAlternativeLaneletPoseBaseOnShortestRouteFrom(from1, hdmap_utils); const auto result2 = pose.getAlternativeLaneletPoseBaseOnShortestRouteFrom(from2, hdmap_utils); + ASSERT_TRUE(result1); + ASSERT_TRUE(result2); + EXPECT_EQ(result1.value().lanelet_id, 34603); EXPECT_EQ(result2.value().lanelet_id, 34579); } @@ -260,16 +262,15 @@ TEST(CanonicalizedLaneletPose, setConsiderPoseByRoadSlope) /** * @note Test operator calculation correctness with CanonicalizedLaneletPose of lesser, equal and greater lanelet_id */ -TEST(CanonicalizedLaneletPose, operatorLessEqual) +TEST_F(CanonicalizedLaneletPoseTest, operatorLessEqual) { - auto hdmap_utils = makeHdMapUtilsSharedPointer(); - CanonicalizedLaneletPose pose( + const CanonicalizedLaneletPose pose( traffic_simulator::helper::constructLaneletPose(120659, 5.0, 0.0), hdmap_utils); - CanonicalizedLaneletPose pose_equal( + const CanonicalizedLaneletPose pose_equal( traffic_simulator::helper::constructLaneletPose(120659, 5.0, 0.0), hdmap_utils); - CanonicalizedLaneletPose pose_less( + const CanonicalizedLaneletPose pose_less( traffic_simulator::helper::constructLaneletPose(120659, 0.0, 0.0), hdmap_utils); - CanonicalizedLaneletPose pose_greater( + const CanonicalizedLaneletPose pose_greater( traffic_simulator::helper::constructLaneletPose(120659, 6.0, 0.0), hdmap_utils); EXPECT_TRUE(pose_less <= pose); @@ -280,16 +281,15 @@ TEST(CanonicalizedLaneletPose, operatorLessEqual) /** * @note Test operator calculation correctness with CanonicalizedLaneletPose of lesser, equal and greater lanelet_id */ -TEST(CanonicalizedLaneletPose, operatorLess) +TEST_F(CanonicalizedLaneletPoseTest, operatorLess) { - auto hdmap_utils = makeHdMapUtilsSharedPointer(); - CanonicalizedLaneletPose pose( + const CanonicalizedLaneletPose pose( traffic_simulator::helper::constructLaneletPose(120659, 5.0, 0.0), hdmap_utils); - CanonicalizedLaneletPose pose_equal( + const CanonicalizedLaneletPose pose_equal( traffic_simulator::helper::constructLaneletPose(120659, 5.0, 0.0), hdmap_utils); - CanonicalizedLaneletPose pose_less( + const CanonicalizedLaneletPose pose_less( traffic_simulator::helper::constructLaneletPose(120659, 0.0, 0.0), hdmap_utils); - CanonicalizedLaneletPose pose_greater( + const CanonicalizedLaneletPose pose_greater( traffic_simulator::helper::constructLaneletPose(120659, 6.0, 0.0), hdmap_utils); EXPECT_TRUE(pose_less < pose); @@ -300,16 +300,15 @@ TEST(CanonicalizedLaneletPose, operatorLess) /** * @note Test operator calculation correctness with CanonicalizedLaneletPose of lesser, equal and greater lanelet_id */ -TEST(CanonicalizedLaneletPose, operatorGreaterEqual) +TEST_F(CanonicalizedLaneletPoseTest, operatorGreaterEqual) { - auto hdmap_utils = makeHdMapUtilsSharedPointer(); - CanonicalizedLaneletPose pose( + const CanonicalizedLaneletPose pose( traffic_simulator::helper::constructLaneletPose(120659, 5.0, 0.0), hdmap_utils); - CanonicalizedLaneletPose pose_equal( + const CanonicalizedLaneletPose pose_equal( traffic_simulator::helper::constructLaneletPose(120659, 5.0, 0.0), hdmap_utils); - CanonicalizedLaneletPose pose_less( + const CanonicalizedLaneletPose pose_less( traffic_simulator::helper::constructLaneletPose(120659, 0.0, 0.0), hdmap_utils); - CanonicalizedLaneletPose pose_greater( + const CanonicalizedLaneletPose pose_greater( traffic_simulator::helper::constructLaneletPose(120659, 6.0, 0.0), hdmap_utils); EXPECT_FALSE(pose_less >= pose); @@ -320,16 +319,15 @@ TEST(CanonicalizedLaneletPose, operatorGreaterEqual) /** * @note Test operator calculation correctness with CanonicalizedLaneletPose of lesser, equal and greater lanelet_id */ -TEST(CanonicalizedLaneletPose, operatorGreater) +TEST_F(CanonicalizedLaneletPoseTest, operatorGreater) { - auto hdmap_utils = makeHdMapUtilsSharedPointer(); - CanonicalizedLaneletPose pose( + const CanonicalizedLaneletPose pose( traffic_simulator::helper::constructLaneletPose(120659, 5.0, 0.0), hdmap_utils); - CanonicalizedLaneletPose pose_equal( + const CanonicalizedLaneletPose pose_equal( traffic_simulator::helper::constructLaneletPose(120659, 5.0, 0.0), hdmap_utils); - CanonicalizedLaneletPose pose_less( + const CanonicalizedLaneletPose pose_less( traffic_simulator::helper::constructLaneletPose(120659, 0.0, 0.0), hdmap_utils); - CanonicalizedLaneletPose pose_greater( + const CanonicalizedLaneletPose pose_greater( traffic_simulator::helper::constructLaneletPose(120659, 6.0, 0.0), hdmap_utils); EXPECT_FALSE(pose_less > pose); @@ -340,12 +338,11 @@ TEST(CanonicalizedLaneletPose, operatorGreater) /** * @note Test function behavior when provided two poses occupying the same lanelet_id */ -TEST(CanonicalizedLaneletPose, isSameLaneletId_withPose_same) +TEST_F(CanonicalizedLaneletPoseTest, isSameLaneletId_withPose_same) { - auto hdmap_utils = makeHdMapUtilsSharedPointer(); - CanonicalizedLaneletPose pose1( + const CanonicalizedLaneletPose pose1( traffic_simulator::helper::constructLaneletPose(120659, 0.0, 0.0), hdmap_utils); - CanonicalizedLaneletPose pose2( + const CanonicalizedLaneletPose pose2( traffic_simulator::helper::constructLaneletPose(120659, 1.0, 0.0), hdmap_utils); EXPECT_TRUE(traffic_simulator::isSameLaneletId(pose1, pose2)); @@ -354,10 +351,9 @@ TEST(CanonicalizedLaneletPose, isSameLaneletId_withPose_same) /** * @note Test function behavior when provided two poses occupying different lanelet_ids */ -TEST(CanonicalizedLaneletPose, isSameLaneletId_withPose_different) +TEST_F(CanonicalizedLaneletPoseTest, isSameLaneletId_withPose_different) { - auto hdmap_utils = makeHdMapUtilsSharedPointer(); - CanonicalizedLaneletPose pose1( + const CanonicalizedLaneletPose pose1( traffic_simulator::helper::constructLaneletPose(120659, 0.0, 0.0), hdmap_utils); CanonicalizedLaneletPose pose2( traffic_simulator::helper::constructLaneletPose(34606, 1.0, 0.0), hdmap_utils); @@ -368,10 +364,9 @@ TEST(CanonicalizedLaneletPose, isSameLaneletId_withPose_different) /** * @note Test function behavior when provided with a pose having lanelt_id equal to the lanelet_id argument */ -TEST(CanonicalizedLaneletPose, isSameLaneletId_withLanelet_same) +TEST_F(CanonicalizedLaneletPoseTest, isSameLaneletId_withLanelet_same) { - auto hdmap_utils = makeHdMapUtilsSharedPointer(); - CanonicalizedLaneletPose pose( + const CanonicalizedLaneletPose pose( traffic_simulator::helper::constructLaneletPose(120659, 0.0, 0.0), hdmap_utils); EXPECT_TRUE(traffic_simulator::isSameLaneletId(pose, 120659)); @@ -380,11 +375,10 @@ TEST(CanonicalizedLaneletPose, isSameLaneletId_withLanelet_same) /** * @note Test function behavior when provided with a pose having lanelet_id different to the lanelet_id argument */ -TEST(CanonicalizedLaneletPose, isSameLaneletId_withLanelet_different) +TEST_F(CanonicalizedLaneletPoseTest, isSameLaneletId_withLanelet_different) { - auto hdmap_utils = makeHdMapUtilsSharedPointer(); - CanonicalizedLaneletPose pose( + const CanonicalizedLaneletPose pose( traffic_simulator::helper::constructLaneletPose(120659, 0.0, 0.0), hdmap_utils); EXPECT_FALSE(traffic_simulator::isSameLaneletId(pose, 34606)); -} \ No newline at end of file +} From ca7705316e7896637aa34af3b2fdb212d3484be2 Mon Sep 17 00:00:00 2001 From: Grzegorz Maj Date: Mon, 2 Sep 2024 09:05:43 +0200 Subject: [PATCH 233/304] Change invalid test cases to more obvious values --- .../test/src/data_type/test_lanelet_pose.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/simulation/traffic_simulator/test/src/data_type/test_lanelet_pose.cpp b/simulation/traffic_simulator/test/src/data_type/test_lanelet_pose.cpp index 635957dcf1a..b12a0d25e2c 100644 --- a/simulation/traffic_simulator/test/src/data_type/test_lanelet_pose.cpp +++ b/simulation/traffic_simulator/test/src/data_type/test_lanelet_pose.cpp @@ -40,7 +40,7 @@ TEST_F(CanonicalizedLaneletPoseTest, CanonicalizedLaneletPose_withRoute_invalid) { EXPECT_THROW( CanonicalizedLaneletPose( - traffic_simulator::helper::constructLaneletPose(120576, 14.6356, 0.0), lanelet::Ids{}, + traffic_simulator::helper::constructLaneletPose(100000000000, 0.0, 0.0), lanelet::Ids{}, hdmap_utils), std::runtime_error); } @@ -67,7 +67,7 @@ TEST_F(CanonicalizedLaneletPoseTest, CanonicalizedLaneletPose_withoutRoute_inval { EXPECT_THROW( CanonicalizedLaneletPose( - traffic_simulator::helper::constructLaneletPose(120576, 0.0, 0.0), hdmap_utils), + traffic_simulator::helper::constructLaneletPose(100000000000, 0.0, 0.0), hdmap_utils), std::runtime_error); } From e5068998bc36a720b422b90e1071d7e9d6abe7e0 Mon Sep 17 00:00:00 2001 From: Grzegorz Maj Date: Fri, 6 Sep 2024 12:48:29 +0200 Subject: [PATCH 234/304] Change assert check from bool to has_value --- .../test/src/data_type/test_lanelet_pose.cpp | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/simulation/traffic_simulator/test/src/data_type/test_lanelet_pose.cpp b/simulation/traffic_simulator/test/src/data_type/test_lanelet_pose.cpp index b12a0d25e2c..60414b7e91d 100644 --- a/simulation/traffic_simulator/test/src/data_type/test_lanelet_pose.cpp +++ b/simulation/traffic_simulator/test/src/data_type/test_lanelet_pose.cpp @@ -194,8 +194,8 @@ TEST_F(CanonicalizedLaneletPoseTest, getAlternativeLaneletPoseBaseOnShortestRout const auto result1 = pose.getAlternativeLaneletPoseBaseOnShortestRouteFrom(from1, hdmap_utils); const auto result2 = pose.getAlternativeLaneletPoseBaseOnShortestRouteFrom(from2, hdmap_utils); - ASSERT_TRUE(result1); - ASSERT_TRUE(result2); + ASSERT_TRUE(result1.has_value()); + ASSERT_TRUE(result2.has_value()); EXPECT_EQ(result1.value().lanelet_id, 120659); EXPECT_EQ(result2.value().lanelet_id, 120659); @@ -214,8 +214,8 @@ TEST_F(CanonicalizedLaneletPoseTest, getAlternativeLaneletPoseBaseOnShortestRout const auto result1 = pose.getAlternativeLaneletPoseBaseOnShortestRouteFrom(from1, hdmap_utils); const auto result2 = pose.getAlternativeLaneletPoseBaseOnShortestRouteFrom(from2, hdmap_utils); - ASSERT_TRUE(result1); - ASSERT_TRUE(result2); + ASSERT_TRUE(result1.has_value()); + ASSERT_TRUE(result2.has_value()); EXPECT_EQ(result1.value().lanelet_id, 34603); EXPECT_EQ(result2.value().lanelet_id, 34603); @@ -234,8 +234,8 @@ TEST_F(CanonicalizedLaneletPoseTest, getAlternativeLaneletPoseBaseOnShortestRout const auto result1 = pose.getAlternativeLaneletPoseBaseOnShortestRouteFrom(from1, hdmap_utils); const auto result2 = pose.getAlternativeLaneletPoseBaseOnShortestRouteFrom(from2, hdmap_utils); - ASSERT_TRUE(result1); - ASSERT_TRUE(result2); + ASSERT_TRUE(result1.has_value()); + ASSERT_TRUE(result2.has_value()); EXPECT_EQ(result1.value().lanelet_id, 34603); EXPECT_EQ(result2.value().lanelet_id, 34579); From 0ab6703c110d42afa067864229ee5d9d98bd3eb1 Mon Sep 17 00:00:00 2001 From: Grzegorz Maj Date: Mon, 9 Sep 2024 13:06:53 +0200 Subject: [PATCH 235/304] Lint changes --- scenario_simulator_v2/CMakeLists.txt.user | 201 ++++++++++++++++++ .../test/src/data_type/CMakeLists.txt | 1 - 2 files changed, 201 insertions(+), 1 deletion(-) create mode 100644 scenario_simulator_v2/CMakeLists.txt.user diff --git a/scenario_simulator_v2/CMakeLists.txt.user b/scenario_simulator_v2/CMakeLists.txt.user new file mode 100644 index 00000000000..d55c9cc4285 --- /dev/null +++ b/scenario_simulator_v2/CMakeLists.txt.user @@ -0,0 +1,201 @@ + + + + + + EnvironmentId + {2d447ef6-df7d-4f95-afdb-b10ca9bf9414} + + + ProjectExplorer.Project.ActiveTarget + 0 + + + ProjectExplorer.Project.EditorSettings + + true + false + true + + Cpp + + CppGlobal + + + + QmlJS + + QmlJSGlobal + + + 2 + UTF-8 + false + 4 + false + 80 + true + true + 1 + 0 + false + true + false + 2 + true + true + 0 + 8 + true + false + 1 + true + true + true + *.md, *.MD, Makefile + false + true + true + + + + ProjectExplorer.Project.PluginSettings + + + true + false + true + true + true + true + + + 0 + true + + true + true + Builtin.DefaultTidyAndClazy + 14 + true + + + + true + + + + + ProjectExplorer.Project.Target.0 + + Desktop + Desktop 6.2.4 + Desktop 6.2.4 + {6445e3be-3f86-41bb-bbc3-ceb8f69cbaf8} + 0 + 0 + 0 + + Debug + 2 + false + + -DCMAKE_GENERATOR:STRING=Ninja +-DCMAKE_BUILD_TYPE:STRING=Debug +-DCMAKE_PROJECT_INCLUDE_BEFORE:FILEPATH=%{BuildConfig:BuildDirectory:NativeFilePath}/.qtc/package-manager/auto-setup.cmake +-DQT_QMAKE_EXECUTABLE:FILEPATH=%{Qt:qmakeExecutable} +-DCMAKE_PREFIX_PATH:PATH=%{Qt:QT_INSTALL_PREFIX} +-DCMAKE_C_COMPILER:FILEPATH=%{Compiler:Executable:C} +-DCMAKE_CXX_COMPILER:FILEPATH=%{Compiler:Executable:Cxx} +-DCMAKE_CXX_FLAGS_INIT:STRING=%{Qt:QML_DEBUG_FLAG} + 0 + /home/gmaj/repos/robotec/scenario_simulator_ws/src/scenario_simulator_v2/scenario_simulator_v2/build/Desktop_6_2_4-Debug + + + + + all + + false + + true + Build + CMakeProjectManager.MakeStep + + 1 + Build + Build + ProjectExplorer.BuildSteps.Build + + + + + + clean + + false + + true + Build + CMakeProjectManager.MakeStep + + 1 + Clean + Clean + ProjectExplorer.BuildSteps.Clean + + 2 + false + + false + + Debug + CMakeProjectManager.CMakeBuildConfiguration + + 1 + + + 0 + Deploy + Deploy + ProjectExplorer.BuildSteps.Deploy + + 1 + + false + ProjectExplorer.DefaultDeployConfiguration + + 1 + + true + true + 0 + true + + 2 + + false + -e cpu-cycles --call-graph dwarf,4096 -F 250 + + ProjectExplorer.CustomExecutableRunConfiguration + + false + true + true + + 1 + + + + ProjectExplorer.Project.TargetCount + 1 + + + ProjectExplorer.Project.Updater.FileVersion + 22 + + + Version + 22 + + diff --git a/simulation/traffic_simulator/test/src/data_type/CMakeLists.txt b/simulation/traffic_simulator/test/src/data_type/CMakeLists.txt index 50bc1214813..6bbebabc879 100644 --- a/simulation/traffic_simulator/test/src/data_type/CMakeLists.txt +++ b/simulation/traffic_simulator/test/src/data_type/CMakeLists.txt @@ -1,3 +1,2 @@ ament_add_gtest(test_lanelet_pose test_lanelet_pose.cpp) target_link_libraries(test_lanelet_pose traffic_simulator) - From 7c0186f6a2b82e286b0658d3b70fe9c97301e034 Mon Sep 17 00:00:00 2001 From: Grzegorz Maj Date: Mon, 9 Sep 2024 13:18:35 +0200 Subject: [PATCH 236/304] Spelling changes --- scenario_simulator_v2/CMakeLists.txt.user | 201 ------------------ .../test/src/data_type/test_lanelet_pose.cpp | 2 +- 2 files changed, 1 insertion(+), 202 deletions(-) delete mode 100644 scenario_simulator_v2/CMakeLists.txt.user diff --git a/scenario_simulator_v2/CMakeLists.txt.user b/scenario_simulator_v2/CMakeLists.txt.user deleted file mode 100644 index d55c9cc4285..00000000000 --- a/scenario_simulator_v2/CMakeLists.txt.user +++ /dev/null @@ -1,201 +0,0 @@ - - - - - - EnvironmentId - {2d447ef6-df7d-4f95-afdb-b10ca9bf9414} - - - ProjectExplorer.Project.ActiveTarget - 0 - - - ProjectExplorer.Project.EditorSettings - - true - false - true - - Cpp - - CppGlobal - - - - QmlJS - - QmlJSGlobal - - - 2 - UTF-8 - false - 4 - false - 80 - true - true - 1 - 0 - false - true - false - 2 - true - true - 0 - 8 - true - false - 1 - true - true - true - *.md, *.MD, Makefile - false - true - true - - - - ProjectExplorer.Project.PluginSettings - - - true - false - true - true - true - true - - - 0 - true - - true - true - Builtin.DefaultTidyAndClazy - 14 - true - - - - true - - - - - ProjectExplorer.Project.Target.0 - - Desktop - Desktop 6.2.4 - Desktop 6.2.4 - {6445e3be-3f86-41bb-bbc3-ceb8f69cbaf8} - 0 - 0 - 0 - - Debug - 2 - false - - -DCMAKE_GENERATOR:STRING=Ninja --DCMAKE_BUILD_TYPE:STRING=Debug --DCMAKE_PROJECT_INCLUDE_BEFORE:FILEPATH=%{BuildConfig:BuildDirectory:NativeFilePath}/.qtc/package-manager/auto-setup.cmake --DQT_QMAKE_EXECUTABLE:FILEPATH=%{Qt:qmakeExecutable} --DCMAKE_PREFIX_PATH:PATH=%{Qt:QT_INSTALL_PREFIX} --DCMAKE_C_COMPILER:FILEPATH=%{Compiler:Executable:C} --DCMAKE_CXX_COMPILER:FILEPATH=%{Compiler:Executable:Cxx} --DCMAKE_CXX_FLAGS_INIT:STRING=%{Qt:QML_DEBUG_FLAG} - 0 - /home/gmaj/repos/robotec/scenario_simulator_ws/src/scenario_simulator_v2/scenario_simulator_v2/build/Desktop_6_2_4-Debug - - - - - all - - false - - true - Build - CMakeProjectManager.MakeStep - - 1 - Build - Build - ProjectExplorer.BuildSteps.Build - - - - - - clean - - false - - true - Build - CMakeProjectManager.MakeStep - - 1 - Clean - Clean - ProjectExplorer.BuildSteps.Clean - - 2 - false - - false - - Debug - CMakeProjectManager.CMakeBuildConfiguration - - 1 - - - 0 - Deploy - Deploy - ProjectExplorer.BuildSteps.Deploy - - 1 - - false - ProjectExplorer.DefaultDeployConfiguration - - 1 - - true - true - 0 - true - - 2 - - false - -e cpu-cycles --call-graph dwarf,4096 -F 250 - - ProjectExplorer.CustomExecutableRunConfiguration - - false - true - true - - 1 - - - - ProjectExplorer.Project.TargetCount - 1 - - - ProjectExplorer.Project.Updater.FileVersion - 22 - - - Version - 22 - - diff --git a/simulation/traffic_simulator/test/src/data_type/test_lanelet_pose.cpp b/simulation/traffic_simulator/test/src/data_type/test_lanelet_pose.cpp index 60414b7e91d..24d74f063ce 100644 --- a/simulation/traffic_simulator/test/src/data_type/test_lanelet_pose.cpp +++ b/simulation/traffic_simulator/test/src/data_type/test_lanelet_pose.cpp @@ -362,7 +362,7 @@ TEST_F(CanonicalizedLaneletPoseTest, isSameLaneletId_withPose_different) } /** - * @note Test function behavior when provided with a pose having lanelt_id equal to the lanelet_id argument + * @note Test function behavior when provided with a pose having lanelet_id equal to the lanelet_id argument */ TEST_F(CanonicalizedLaneletPoseTest, isSameLaneletId_withLanelet_same) { From 18bfc25ae2cdefd84bce37750db5536eaf0e10b0 Mon Sep 17 00:00:00 2001 From: Grzegorz Maj Date: Mon, 9 Sep 2024 14:50:45 +0200 Subject: [PATCH 237/304] CR requested changes --- .../test/src/utils/test_pose.cpp | 160 +++++++++--------- 1 file changed, 80 insertions(+), 80 deletions(-) diff --git a/simulation/traffic_simulator/test/src/utils/test_pose.cpp b/simulation/traffic_simulator/test/src/utils/test_pose.cpp index b8182b2617a..5834df083b6 100644 --- a/simulation/traffic_simulator/test/src/utils/test_pose.cpp +++ b/simulation/traffic_simulator/test/src/utils/test_pose.cpp @@ -42,39 +42,39 @@ class PoseTest : public testing::Test }; /** - * @note test created object values + * @note Test created object values. */ TEST(pose, quietNaNPose) { const auto pose = traffic_simulator::pose::quietNaNPose(); - EXPECT_TRUE(isnan(pose.position.x)); - EXPECT_TRUE(isnan(pose.position.y)); - EXPECT_TRUE(isnan(pose.position.z)); + EXPECT_TRUE(std::isnan(pose.position.x)); + EXPECT_TRUE(std::isnan(pose.position.y)); + EXPECT_TRUE(std::isnan(pose.position.z)); - EXPECT_EQ(pose.orientation.x, 0); - EXPECT_EQ(pose.orientation.y, 0); - EXPECT_EQ(pose.orientation.z, 0); - EXPECT_EQ(pose.orientation.w, 1); + EXPECT_DOUBLE_EQ(pose.orientation.x, 0.0); + EXPECT_DOUBLE_EQ(pose.orientation.y, 0.0); + EXPECT_DOUBLE_EQ(pose.orientation.z, 0.0); + EXPECT_DOUBLE_EQ(pose.orientation.w, 1.0); } /** - * @note test created object values + * @note Test created object values. */ TEST(pose, quietNaNLaneletPose) { const auto pose = traffic_simulator::pose::quietNaNLaneletPose(); EXPECT_EQ(pose.lanelet_id, std::numeric_limits::max()); - EXPECT_TRUE(isnan(pose.s)); - EXPECT_TRUE(isnan(pose.offset)); - EXPECT_TRUE(isnan(pose.rpy.x)); - EXPECT_TRUE(isnan(pose.rpy.y)); - EXPECT_TRUE(isnan(pose.rpy.z)); + EXPECT_TRUE(std::isnan(pose.s)); + EXPECT_TRUE(std::isnan(pose.offset)); + EXPECT_TRUE(std::isnan(pose.rpy.x)); + EXPECT_TRUE(std::isnan(pose.rpy.y)); + EXPECT_TRUE(std::isnan(pose.rpy.z)); } /** - * @note test canonicalization with a default constructed LaneletPose + * @note Test canonicalization with a default constructed LaneletPose. */ TEST_F(PoseTest, canonicalize_default) { @@ -85,7 +85,7 @@ TEST_F(PoseTest, canonicalize_default) } /** - * @note test canonicalization with an invalid LaneletPose + * @note Test canonicalization with an invalid LaneletPose. */ TEST_F(PoseTest, canonicalize_invalid) { @@ -96,7 +96,7 @@ TEST_F(PoseTest, canonicalize_invalid) } /** - * @note test canonicalization with a valid constructed LaneletPose + * @note Test canonicalization with a valid constructed LaneletPose. */ TEST_F(PoseTest, canonicalize_valid) { @@ -110,7 +110,7 @@ TEST_F(PoseTest, canonicalize_valid) } /** - * @note test conversion to geometry_msgs::msg::Pose from CanonicalizedLaneletPose + * @note Test conversion to geometry_msgs::msg::Pose from CanonicalizedLaneletPose. */ TEST_F(PoseTest, toMapPose_CanonicalizedLaneletPose) { @@ -119,13 +119,13 @@ TEST_F(PoseTest, toMapPose_CanonicalizedLaneletPose) const geometry_msgs::msg::Pose pose = makePose( makePoint(81585.1622, 50176.9202, 34.2595), - geometry_msgs::build().x(0).y(0).z(-0.6397).w(0.7686)); + geometry_msgs::build().x(0.0).y(0.0).z(-0.6397).w(0.7686)); EXPECT_POSE_NEAR(traffic_simulator::pose::toMapPose(canonicalized_pose), pose, 0.01); } /** - * @note test conversion to geometry_msgs::msg::Pose from LaneletPose with HdMapUtils pointer + * @note Test conversion to geometry_msgs::msg::Pose from LaneletPose with HdMapUtils pointer. */ TEST_F(PoseTest, toMapPose_LaneletPose) { @@ -139,7 +139,7 @@ TEST_F(PoseTest, toMapPose_LaneletPose) } /** - * @note test function behavior with a pose that can be canonicalized + * @note Test function behavior with a pose that can be canonicalized. */ TEST_F(PoseTest, toCanonicalizedLaneletPose_noBoundingBox_noRoute_valid) { @@ -159,7 +159,7 @@ TEST_F(PoseTest, toCanonicalizedLaneletPose_noBoundingBox_noRoute_valid) } /** - * @note test function behavior with a pose that can not be canonicalized + * @note Test function behavior with a pose that can not be canonicalized. */ TEST_F(PoseTest, toCanonicalizedLaneletPose_noBoundingBox_noRoute_invalid) { @@ -170,7 +170,7 @@ TEST_F(PoseTest, toCanonicalizedLaneletPose_noBoundingBox_noRoute_invalid) } /** - * @note test function behavior with a pose that can be canonicalized + * @note Test function behavior with a pose that can be canonicalized. */ TEST_F(PoseTest, toCanonicalizedLaneletPose_BoundingBox_noRoute_valid) { @@ -190,7 +190,7 @@ TEST_F(PoseTest, toCanonicalizedLaneletPose_BoundingBox_noRoute_valid) } /** - * @note test function behavior with a pose that can not be canonicalized, matching distance too large + * @note Test function behavior with a pose that can not be canonicalized, matching distance too large. */ TEST_F(PoseTest, toCanonicalizedLaneletPose_BoundingBox_noRoute_invalid) { @@ -206,7 +206,7 @@ TEST_F(PoseTest, toCanonicalizedLaneletPose_BoundingBox_noRoute_invalid) } /** - * @note test function behavior with an empty unique_route_lanelets vector and a pose that can not be canonicalized + * @note Test function behavior with an empty unique_route_lanelets vector and a pose that can not be canonicalized. */ TEST_F(PoseTest, toCanonicalizedLaneletPose_BoundingBox_route_emptyInvalid) { @@ -214,12 +214,12 @@ TEST_F(PoseTest, toCanonicalizedLaneletPose_BoundingBox_route_emptyInvalid) EXPECT_EQ( traffic_simulator::pose::toCanonicalizedLaneletPose( - pose, makeBoundingBox(), {}, true, 1.0, hdmap_utils), + pose, makeBoundingBox(), lanelet::Ids{}, true, 1.0, hdmap_utils), std::nullopt); } /** - * @note test function behavior with an empty unique_route_lanelets vector and a pose that can be canonicalized + * @note Test function behavior with an empty unique_route_lanelets vector and a pose that can be canonicalized. */ TEST_F(PoseTest, toCanonicalizedLaneletPose_BoundingBox_route_emptyValid) { @@ -239,7 +239,7 @@ TEST_F(PoseTest, toCanonicalizedLaneletPose_BoundingBox_route_emptyValid) } /** - * @note test function behavior with a non empty unique_route_lanelets vector and a pose that can not be canonicalized + * @note Test function behavior with a non empty unique_route_lanelets vector and a pose that can not be canonicalized. */ TEST_F(PoseTest, toCanonicalizedLaneletPose_BoundingBox_route_nonEmptyInvalid) { @@ -252,7 +252,7 @@ TEST_F(PoseTest, toCanonicalizedLaneletPose_BoundingBox_route_nonEmptyInvalid) } /** - * @note test function behavior with a non empty unique_route_lanelets vector and a pose that can be canonicalized + * @note Test function behavior with a non empty unique_route_lanelets vector and a pose that can be canonicalized. */ TEST_F(PoseTest, toCanonicalizedLaneletPose_BoundingBox_route_nonEmptyValid) { @@ -272,7 +272,7 @@ TEST_F(PoseTest, toCanonicalizedLaneletPose_BoundingBox_route_nonEmptyValid) } /** - * @note test calculation correctness with a non trivial example + * @note Test calculation correctness with a non trivial example. */ TEST(pose, transformRelativePoseToGlobal) { @@ -287,12 +287,12 @@ TEST(pose, transformRelativePoseToGlobal) } /** - * @note test calculation correctness when only one pose is zeroed, the goal is to obtain a pose equal to the second argument + * @note Test calculation correctness when only one pose is zeroed, the goal is to obtain a pose equal to the second argument. */ TEST(pose, relativePose_poses_zeros) { - const auto from = makePose(makePoint(0, 0, 0)); - const auto to = makePose(makePoint(10, 51, 2)); + const auto from = makePose(makePoint(0.0, 0.0, 0.0)); + const auto to = makePose(makePoint(10.0, 51.0, 2.0)); const auto relative = traffic_simulator::pose::relativePose(from, to); ASSERT_TRUE(relative.has_value()); @@ -300,12 +300,12 @@ TEST(pose, relativePose_poses_zeros) } /** - * @note test calculation correctness when both poses are zeroed + * @note Test calculation correctness when both poses are zeroed. */ TEST(pose, relativePose_poses_zero) { - const auto from = makePose(makePoint(0, 0, 0)); - const auto to = makePose(makePoint(0, 0, 0)); + const auto from = makePose(makePoint(0.0, 0.0, 0.0)); + const auto to = makePose(makePoint(0.0, 0.0, 0.0)); const auto relative = traffic_simulator::pose::relativePose(from, to); ASSERT_TRUE(relative.has_value()); @@ -313,7 +313,7 @@ TEST(pose, relativePose_poses_zero) } /** - * @note ttest calculation correctness with a non trivial example + * @note ttest calculation correctness with a non trivial example. */ TEST(pose, relativePose_poses_complex) { @@ -328,7 +328,7 @@ TEST(pose, relativePose_poses_complex) } /** - * @note test calculation correctness with the overload + * @note Test calculation correctness with the overload. */ TEST_F(PoseTest, relativePose_first) { @@ -348,7 +348,7 @@ TEST_F(PoseTest, relativePose_first) } /** - * @note test calculation correctness with the overload + * @note Test calculation correctness with the overload. */ TEST_F(PoseTest, relativePose_second) { @@ -367,54 +367,54 @@ TEST_F(PoseTest, relativePose_second) } /** - * @note test calculation correctness when bounding boxes are disjoint + * @note Test calculation correctness when bounding boxes are disjoint. */ TEST_F(PoseTest, boundingBoxRelativePose_disjoint) { const auto pose_relative = makePose(makePoint(0.1108, -20.5955, 0.0)); const auto from = makePose(makePoint(81600.3967, 50094.4298, 34.6759)); const auto to = makePose(makePoint(81604.5076, 50071.8343, 40.8482)); - const auto boundingBox = makeBoundingBox(); + const auto bounding_box = makeBoundingBox(); const auto relative = - traffic_simulator::pose::boundingBoxRelativePose(from, boundingBox, to, boundingBox); + traffic_simulator::pose::boundingBoxRelativePose(from, bounding_box, to, bounding_box); ASSERT_TRUE(relative.has_value()); EXPECT_POSE_NEAR(pose_relative, relative.value(), 0.01); } /** - * @note test calculation correctness when bounding boxes share an edge + * @note Test calculation correctness when bounding boxes share an edge. */ TEST_F(PoseTest, boundingBoxRelativePose_commonEdge) { const auto from = makePose(makePoint(81600, 50094, 34)); const auto to = makePose(makePoint(81601, 50094, 34)); - const auto boundingBox = makeSmallBoundingBox(); + const auto bounding_box = makeSmallBoundingBox(); const auto relative = - traffic_simulator::pose::boundingBoxRelativePose(from, boundingBox, to, boundingBox); + traffic_simulator::pose::boundingBoxRelativePose(from, bounding_box, to, bounding_box); EXPECT_FALSE(relative.has_value()); } /** - * @note test calculation correctness when bounding boxes intersect + * @note Test calculation correctness when bounding boxes intersect. */ TEST_F(PoseTest, boundingBoxRelativePose_intersect) { const auto from = makePose(makePoint(81600, 50094, 34)); const auto to = makePose(makePoint(81600.5, 50094, 34)); - const auto boundingBox = makeSmallBoundingBox(); + const auto bounding_box = makeSmallBoundingBox(); const auto relative = - traffic_simulator::pose::boundingBoxRelativePose(from, boundingBox, to, boundingBox); + traffic_simulator::pose::boundingBoxRelativePose(from, bounding_box, to, bounding_box); EXPECT_FALSE(relative.has_value()); } /** - * @note test s-value calculation correctness when longitudinal distance between the poses can not be calculated + * @note Test s-value calculation correctness when longitudinal distance between the poses can not be calculated. */ TEST_F(PoseTest, relativeLaneletPose_s_invalid) { @@ -425,11 +425,11 @@ TEST_F(PoseTest, relativeLaneletPose_s_invalid) const auto relative = traffic_simulator::pose::relativeLaneletPose(from, to, false, hdmap_utils); - EXPECT_TRUE(isnan(relative.s)); + EXPECT_TRUE(std::isnan(relative.s)); } /** - * @note test s-value calculation correctness when longitudinal distance between the poses can be calculated + * @note Test s-value calculation correctness when longitudinal distance between the poses can be calculated. */ TEST_F(PoseTest, relativeLaneletPose_s_valid) { @@ -444,7 +444,7 @@ TEST_F(PoseTest, relativeLaneletPose_s_valid) } /** - * @note test offset-value calculation correctness when lateral distance between the poses can not be calculated + * @note Test offset-value calculation correctness when lateral distance between the poses can not be calculated. */ TEST_F(PoseTest, relativeLaneletPose_offset_invalid) { @@ -455,11 +455,11 @@ TEST_F(PoseTest, relativeLaneletPose_offset_invalid) const auto relative = traffic_simulator::pose::relativeLaneletPose(from, to, false, hdmap_utils); - EXPECT_TRUE(isnan(relative.offset)); + EXPECT_TRUE(std::isnan(relative.offset)); } /** - * @note test offset-value calculation correctness when lateral distance between the poses can be calculated + * @note Test offset-value calculation correctness when lateral distance between the poses can be calculated. */ TEST_F(PoseTest, relativeLaneletPose_offset_valid) { @@ -474,7 +474,7 @@ TEST_F(PoseTest, relativeLaneletPose_offset_valid) } /** - * @note test s-value calculation correctness when longitudinal distance between the poses can not be calculated + * @note Test s-value calculation correctness when longitudinal distance between the poses can not be calculated. */ TEST_F(PoseTest, boundingBoxRelativeLaneletPose_s_invalid) { @@ -482,16 +482,16 @@ TEST_F(PoseTest, boundingBoxRelativeLaneletPose_s_invalid) traffic_simulator::helper::constructCanonicalizedLaneletPose(195, 0.0, 0.0, hdmap_utils); const auto to = traffic_simulator::helper::constructCanonicalizedLaneletPose(196, 0.0, 1.0, hdmap_utils); - const auto boundingBox = makeBoundingBox(); + const auto bounding_box = makeBoundingBox(); const auto relative = traffic_simulator::pose::boundingBoxRelativeLaneletPose( - from, boundingBox, to, boundingBox, false, hdmap_utils); + from, bounding_box, to, bounding_box, false, hdmap_utils); - EXPECT_TRUE(isnan(relative.s)); + EXPECT_TRUE(std::isnan(relative.s)); } /** - * @note test s-value calculation correctness when longitudinal distance between the poses can be calculated + * @note Test s-value calculation correctness when longitudinal distance between the poses can be calculated. */ TEST_F(PoseTest, boundingBoxRelativeLaneletPose_s_valid) { @@ -499,16 +499,16 @@ TEST_F(PoseTest, boundingBoxRelativeLaneletPose_s_valid) traffic_simulator::helper::constructCanonicalizedLaneletPose(195, 0.0, 0.0, hdmap_utils); const auto to = traffic_simulator::helper::constructCanonicalizedLaneletPose(3002163, 0.0, 0.0, hdmap_utils); - const auto boundingBox = makeBoundingBox(); + const auto bounding_box = makeBoundingBox(); const auto relative = traffic_simulator::pose::boundingBoxRelativeLaneletPose( - from, boundingBox, to, boundingBox, false, hdmap_utils); + from, bounding_box, to, bounding_box, false, hdmap_utils); EXPECT_NEAR(relative.s, 103.74, 0.01); } /** - * @note test offset-value calculation correctness when lateral distance between the poses can not be calculated + * @note Test offset-value calculation correctness when lateral distance between the poses can not be calculated. */ TEST_F(PoseTest, boundingBoxRelativeLaneletPose_offset_invalid) { @@ -516,16 +516,16 @@ TEST_F(PoseTest, boundingBoxRelativeLaneletPose_offset_invalid) traffic_simulator::helper::constructCanonicalizedLaneletPose(195, 0.0, 0.0, hdmap_utils); const auto to = traffic_simulator::helper::constructCanonicalizedLaneletPose(196, 0.0, 1.0, hdmap_utils); - const auto boundingBox = makeBoundingBox(); + const auto bounding_box = makeBoundingBox(); const auto relative = traffic_simulator::pose::boundingBoxRelativeLaneletPose( - from, boundingBox, to, boundingBox, false, hdmap_utils); + from, bounding_box, to, bounding_box, false, hdmap_utils); - EXPECT_TRUE(isnan(relative.s)); + EXPECT_TRUE(std::isnan(relative.s)); } /** - * @note test offset-value calculation correctness when lateral distance between the poses can be calculated + * @note Test offset-value calculation correctness when lateral distance between the poses can be calculated. */ TEST_F(PoseTest, boundingBoxRelativeLaneletPose_offset_valid) { @@ -533,16 +533,16 @@ TEST_F(PoseTest, boundingBoxRelativeLaneletPose_offset_valid) traffic_simulator::helper::constructCanonicalizedLaneletPose(195, 0.0, -1.0, hdmap_utils); const auto to = traffic_simulator::helper::constructCanonicalizedLaneletPose(3002163, 0.0, 1.0, hdmap_utils); - const auto boundingBox = makeBoundingBox(); + const auto bounding_box = makeBoundingBox(); const auto relative = traffic_simulator::pose::boundingBoxRelativeLaneletPose( - from, boundingBox, to, boundingBox, false, hdmap_utils); + from, bounding_box, to, bounding_box, false, hdmap_utils); EXPECT_EQ(relative.offset, 0.0); } /** - * @note test calculation correctness when the pose lies within the lanelet + * @note Test calculation correctness when the pose lies within the lanelet. */ TEST_F(PoseTest, isInLanelet_inside) { @@ -553,7 +553,7 @@ TEST_F(PoseTest, isInLanelet_inside) } /** - * @note test calculation correctness when the pose lies outside the front of the llanelet, distance greater than the tolerance + * @note Test calculation correctness when the pose lies outside the front of the lanelet, distance greater than the tolerance. */ TEST_F(PoseTest, isInLanelet_outsideFrontFar) { @@ -564,7 +564,7 @@ TEST_F(PoseTest, isInLanelet_outsideFrontFar) } /** - * @note test calculation correctness when the pose lies outside the front of the llanelet, distance smaller than the tolerance + * @note Test calculation correctness when the pose lies outside the front of the lanelet, distance smaller than the tolerance. */ TEST_F(PoseTest, isInLanelet_outsideFrontClose) { @@ -575,7 +575,7 @@ TEST_F(PoseTest, isInLanelet_outsideFrontClose) } /** - * @note test calculation correctness when the pose lies outside the back of the llanelet, distance greater than the tolerance + * @note Test calculation correctness when the pose lies outside the back of the lanelet, distance greater than the tolerance. */ TEST_F(PoseTest, isInLanelet_outsideBackFar) { @@ -586,7 +586,7 @@ TEST_F(PoseTest, isInLanelet_outsideBackFar) } /** - * @note test calculation correctness when the pose lies outside the back of the lanelet, distance smaller than the tolerance + * @note Test calculation correctness when the pose lies outside the back of the lanelet, distance smaller than the tolerance. */ TEST_F(PoseTest, isInLanelet_outsideBackClose) { @@ -597,7 +597,7 @@ TEST_F(PoseTest, isInLanelet_outsideBackClose) } /** - * @note test calculation correctness when there are no following lanelets and the pose lies within the lanelet + * @note Test calculation correctness when there are no following lanelets and the pose lies within the lanelet. */ TEST_F(PoseTest, isAtEndOfLanelets_noFollowing_within) { @@ -608,7 +608,7 @@ TEST_F(PoseTest, isAtEndOfLanelets_noFollowing_within) } /** - * @note test calculation correctness when there is a single following lanelet and the pose lies within the lanelet + * @note Test calculation correctness when there is a single following lanelet and the pose lies within the lanelet. */ TEST_F(PoseTest, isAtEndOfLanelets_singleFollowing_within) { @@ -619,7 +619,7 @@ TEST_F(PoseTest, isAtEndOfLanelets_singleFollowing_within) } /** - * @note test calculation correctness when there is a signle following lanelet and the pose lies after the end of the lanelet + * @note Test calculation correctness when there is a signle following lanelet and the pose lies after the end of the lanelet. */ TEST_F(PoseTest, isAtEndOfLanelets_singleFollowing_outside) { @@ -630,7 +630,7 @@ TEST_F(PoseTest, isAtEndOfLanelets_singleFollowing_outside) } /** - * @note test calculation correctness when there are multiple following lanelets and the pose lies within the lanelet + * @note Test calculation correctness when there are multiple following lanelets and the pose lies within the lanelet. */ TEST_F(PoseTest, isAtEndOfLanelets_multipleFollowing_within) { @@ -641,7 +641,7 @@ TEST_F(PoseTest, isAtEndOfLanelets_multipleFollowing_within) } /** - * @note test calculation correctness when there are multiple following lanelets and the pose lies after the end of the lanelet + * @note Test calculation correctness when there are multiple following lanelets and the pose lies after the end of the lanelet. */ TEST_F(PoseTest, isAtEndOfLanelets_multipleFollowing_outside) { @@ -652,7 +652,7 @@ TEST_F(PoseTest, isAtEndOfLanelets_multipleFollowing_outside) } /** - * @note test function behavior when non existent lanelet::Id has been passed + * @note Test function behavior when non existent lanelet::Id has been passed. */ TEST_F(PoseTest, laneletLength_invalid) { @@ -661,7 +661,7 @@ TEST_F(PoseTest, laneletLength_invalid) } /** - * @note test calculation correctness when a correct lanelet::Id has been passed + * @note Test calculation correctness when a correct lanelet::Id has been passed. */ TEST_F(PoseTest, laneletLength_valid) { From 7d8cdc1f0aa0083d9aa361728237d272b801d0ca Mon Sep 17 00:00:00 2001 From: Release Bot Date: Tue, 10 Sep 2024 04:29:03 +0000 Subject: [PATCH 238/304] Bump version of scenario_simulator_v2 from version 4.2.0 to version 4.2.1 --- common/math/arithmetic/CHANGELOG.rst | 3 +++ common/math/arithmetic/package.xml | 2 +- common/math/geometry/CHANGELOG.rst | 3 +++ common/math/geometry/package.xml | 2 +- common/scenario_simulator_exception/CHANGELOG.rst | 3 +++ common/scenario_simulator_exception/package.xml | 2 +- common/simple_junit/CHANGELOG.rst | 3 +++ common/simple_junit/package.xml | 2 +- common/status_monitor/CHANGELOG.rst | 3 +++ common/status_monitor/package.xml | 2 +- external/concealer/CHANGELOG.rst | 3 +++ external/concealer/package.xml | 2 +- external/embree_vendor/CHANGELOG.rst | 3 +++ external/embree_vendor/package.xml | 2 +- map/kashiwanoha_map/CHANGELOG.rst | 3 +++ map/kashiwanoha_map/package.xml | 2 +- map/simple_cross_map/CHANGELOG.rst | 3 +++ map/simple_cross_map/package.xml | 2 +- mock/cpp_mock_scenarios/CHANGELOG.rst | 3 +++ mock/cpp_mock_scenarios/package.xml | 2 +- .../openscenario_experimental_catalog/CHANGELOG.rst | 3 +++ .../openscenario_experimental_catalog/package.xml | 2 +- openscenario/openscenario_interpreter/CHANGELOG.rst | 3 +++ openscenario/openscenario_interpreter/package.xml | 2 +- .../openscenario_interpreter_example/CHANGELOG.rst | 3 +++ .../openscenario_interpreter_example/package.xml | 2 +- .../openscenario_interpreter_msgs/CHANGELOG.rst | 3 +++ .../openscenario_interpreter_msgs/package.xml | 2 +- openscenario/openscenario_preprocessor/CHANGELOG.rst | 3 +++ openscenario/openscenario_preprocessor/package.xml | 2 +- .../openscenario_preprocessor_msgs/CHANGELOG.rst | 3 +++ .../openscenario_preprocessor_msgs/package.xml | 2 +- openscenario/openscenario_utility/CHANGELOG.rst | 3 +++ openscenario/openscenario_utility/package.xml | 2 +- openscenario/openscenario_validator/CHANGELOG.rst | 3 +++ openscenario/openscenario_validator/package.xml | 2 +- .../openscenario_visualization/CHANGELOG.rst | 3 +++ rviz_plugins/openscenario_visualization/package.xml | 2 +- .../CHANGELOG.rst | 3 +++ .../real_time_factor_control_rviz_plugin/package.xml | 2 +- scenario_simulator_v2/CHANGELOG.rst | 6 ++++++ scenario_simulator_v2/package.xml | 2 +- simulation/behavior_tree_plugin/CHANGELOG.rst | 3 +++ simulation/behavior_tree_plugin/package.xml | 2 +- simulation/do_nothing_plugin/CHANGELOG.rst | 3 +++ simulation/do_nothing_plugin/package.xml | 2 +- simulation/simple_sensor_simulator/CHANGELOG.rst | 3 +++ simulation/simple_sensor_simulator/package.xml | 2 +- simulation/simulation_interface/CHANGELOG.rst | 3 +++ simulation/simulation_interface/package.xml | 2 +- simulation/traffic_simulator/CHANGELOG.rst | 12 ++++++++++++ simulation/traffic_simulator/package.xml | 2 +- simulation/traffic_simulator_msgs/CHANGELOG.rst | 3 +++ simulation/traffic_simulator_msgs/package.xml | 2 +- test_runner/random_test_runner/CHANGELOG.rst | 3 +++ test_runner/random_test_runner/package.xml | 2 +- test_runner/scenario_test_runner/CHANGELOG.rst | 3 +++ test_runner/scenario_test_runner/package.xml | 2 +- 58 files changed, 128 insertions(+), 29 deletions(-) diff --git a/common/math/arithmetic/CHANGELOG.rst b/common/math/arithmetic/CHANGELOG.rst index f93617fd14f..ada96ba019d 100644 --- a/common/math/arithmetic/CHANGELOG.rst +++ b/common/math/arithmetic/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package arithmetic * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.1 (2024-09-10) +------------------ + 4.2.0 (2024-09-09) ------------------ diff --git a/common/math/arithmetic/package.xml b/common/math/arithmetic/package.xml index 39519d462a0..ecc5b159eda 100644 --- a/common/math/arithmetic/package.xml +++ b/common/math/arithmetic/package.xml @@ -2,7 +2,7 @@ arithmetic - 4.2.0 + 4.2.1 arithmetic library for scenario_simulator_v2 Tatsuya Yamasaki Apache License 2.0 diff --git a/common/math/geometry/CHANGELOG.rst b/common/math/geometry/CHANGELOG.rst index 40505bb1888..cfb4e74f618 100644 --- a/common/math/geometry/CHANGELOG.rst +++ b/common/math/geometry/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package geometry * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.1 (2024-09-10) +------------------ + 4.2.0 (2024-09-09) ------------------ diff --git a/common/math/geometry/package.xml b/common/math/geometry/package.xml index aebfc75ff48..2e4d8903e86 100644 --- a/common/math/geometry/package.xml +++ b/common/math/geometry/package.xml @@ -2,7 +2,7 @@ geometry - 4.2.0 + 4.2.1 geometry math library for scenario_simulator_v2 application Masaya Kataoka Apache License 2.0 diff --git a/common/scenario_simulator_exception/CHANGELOG.rst b/common/scenario_simulator_exception/CHANGELOG.rst index 38462336a04..9a73bcf2d37 100644 --- a/common/scenario_simulator_exception/CHANGELOG.rst +++ b/common/scenario_simulator_exception/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package scenario_simulator_exception * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.1 (2024-09-10) +------------------ + 4.2.0 (2024-09-09) ------------------ diff --git a/common/scenario_simulator_exception/package.xml b/common/scenario_simulator_exception/package.xml index edd7e147791..10e83d35f6d 100644 --- a/common/scenario_simulator_exception/package.xml +++ b/common/scenario_simulator_exception/package.xml @@ -2,7 +2,7 @@ scenario_simulator_exception - 4.2.0 + 4.2.1 Exception types for scenario simulator Tatsuya Yamasaki Apache License 2.0 diff --git a/common/simple_junit/CHANGELOG.rst b/common/simple_junit/CHANGELOG.rst index e7311df3b5c..d6bb515de90 100644 --- a/common/simple_junit/CHANGELOG.rst +++ b/common/simple_junit/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package junit_exporter * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.1 (2024-09-10) +------------------ + 4.2.0 (2024-09-09) ------------------ diff --git a/common/simple_junit/package.xml b/common/simple_junit/package.xml index 06585618cec..698f4663cdf 100644 --- a/common/simple_junit/package.xml +++ b/common/simple_junit/package.xml @@ -2,7 +2,7 @@ simple_junit - 4.2.0 + 4.2.1 Lightweight JUnit library for ROS 2 Masaya Kataoka Tatsuya Yamasaki diff --git a/common/status_monitor/CHANGELOG.rst b/common/status_monitor/CHANGELOG.rst index bdfd65dcb5f..890e0cf6554 100644 --- a/common/status_monitor/CHANGELOG.rst +++ b/common/status_monitor/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package status_monitor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.1 (2024-09-10) +------------------ + 4.2.0 (2024-09-09) ------------------ diff --git a/common/status_monitor/package.xml b/common/status_monitor/package.xml index 98585d9bea1..9ba065144fa 100644 --- a/common/status_monitor/package.xml +++ b/common/status_monitor/package.xml @@ -2,7 +2,7 @@ status_monitor - 4.2.0 + 4.2.1 none Tatsuya Yamasaki Apache License 2.0 diff --git a/external/concealer/CHANGELOG.rst b/external/concealer/CHANGELOG.rst index d59a67dfa40..5e9d240adb3 100644 --- a/external/concealer/CHANGELOG.rst +++ b/external/concealer/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package concealer * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.1 (2024-09-10) +------------------ + 4.2.0 (2024-09-09) ------------------ * Merge pull request `#1362 `_ from tier4/feature/ros2-parameter-forwarding diff --git a/external/concealer/package.xml b/external/concealer/package.xml index cfcaf051652..62a6fca68cc 100644 --- a/external/concealer/package.xml +++ b/external/concealer/package.xml @@ -2,7 +2,7 @@ concealer - 4.2.0 + 4.2.1 Provides a class 'Autoware' to conceal miscellaneous things to simplify Autoware management of the simulator. Tatsuya Yamasaki Apache License 2.0 diff --git a/external/embree_vendor/CHANGELOG.rst b/external/embree_vendor/CHANGELOG.rst index cdb962aeb46..79db7206c7f 100644 --- a/external/embree_vendor/CHANGELOG.rst +++ b/external/embree_vendor/CHANGELOG.rst @@ -24,6 +24,9 @@ Changelog for package embree_vendor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.1 (2024-09-10) +------------------ + 4.2.0 (2024-09-09) ------------------ diff --git a/external/embree_vendor/package.xml b/external/embree_vendor/package.xml index d2d07f80f0b..399446daa27 100644 --- a/external/embree_vendor/package.xml +++ b/external/embree_vendor/package.xml @@ -2,7 +2,7 @@ embree_vendor - 4.2.0 + 4.2.1 vendor packages for intel raytracing kernel library masaya Apache 2.0 diff --git a/map/kashiwanoha_map/CHANGELOG.rst b/map/kashiwanoha_map/CHANGELOG.rst index e784fe07292..cd6f5f3fa00 100644 --- a/map/kashiwanoha_map/CHANGELOG.rst +++ b/map/kashiwanoha_map/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package kashiwanoha_map * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.1 (2024-09-10) +------------------ + 4.2.0 (2024-09-09) ------------------ diff --git a/map/kashiwanoha_map/package.xml b/map/kashiwanoha_map/package.xml index 60835697fe0..02af3dfe663 100644 --- a/map/kashiwanoha_map/package.xml +++ b/map/kashiwanoha_map/package.xml @@ -2,7 +2,7 @@ kashiwanoha_map - 4.2.0 + 4.2.1 map package for kashiwanoha Masaya Kataoka Apache License 2.0 diff --git a/map/simple_cross_map/CHANGELOG.rst b/map/simple_cross_map/CHANGELOG.rst index c494e9d2080..1517df254c6 100644 --- a/map/simple_cross_map/CHANGELOG.rst +++ b/map/simple_cross_map/CHANGELOG.rst @@ -9,6 +9,9 @@ Changelog for package simple_cross_map * Merge branch 'master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.1 (2024-09-10) +------------------ + 4.2.0 (2024-09-09) ------------------ diff --git a/map/simple_cross_map/package.xml b/map/simple_cross_map/package.xml index 0f54737183a..c009da3e6d6 100644 --- a/map/simple_cross_map/package.xml +++ b/map/simple_cross_map/package.xml @@ -2,7 +2,7 @@ simple_cross_map - 4.2.0 + 4.2.1 map package for simple cross Masaya Kataoka Apache License 2.0 diff --git a/mock/cpp_mock_scenarios/CHANGELOG.rst b/mock/cpp_mock_scenarios/CHANGELOG.rst index 98c71a7a5f8..75b73636c61 100644 --- a/mock/cpp_mock_scenarios/CHANGELOG.rst +++ b/mock/cpp_mock_scenarios/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package cpp_mock_scenarios * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.1 (2024-09-10) +------------------ + 4.2.0 (2024-09-09) ------------------ diff --git a/mock/cpp_mock_scenarios/package.xml b/mock/cpp_mock_scenarios/package.xml index ff478f05e7f..86a60b4d94a 100644 --- a/mock/cpp_mock_scenarios/package.xml +++ b/mock/cpp_mock_scenarios/package.xml @@ -2,7 +2,7 @@ cpp_mock_scenarios - 4.2.0 + 4.2.1 C++ mock scenarios masaya Apache License 2.0 diff --git a/openscenario/openscenario_experimental_catalog/CHANGELOG.rst b/openscenario/openscenario_experimental_catalog/CHANGELOG.rst index 8cdb221e4e9..bc6b5d4874f 100644 --- a/openscenario/openscenario_experimental_catalog/CHANGELOG.rst +++ b/openscenario/openscenario_experimental_catalog/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package openscenario_experimental_catalog * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.1 (2024-09-10) +------------------ + 4.2.0 (2024-09-09) ------------------ diff --git a/openscenario/openscenario_experimental_catalog/package.xml b/openscenario/openscenario_experimental_catalog/package.xml index 98afcc38fa2..d773d677134 100644 --- a/openscenario/openscenario_experimental_catalog/package.xml +++ b/openscenario/openscenario_experimental_catalog/package.xml @@ -2,7 +2,7 @@ openscenario_experimental_catalog - 4.2.0 + 4.2.1 TIER IV experimental catalogs for OpenSCENARIO Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter/CHANGELOG.rst b/openscenario/openscenario_interpreter/CHANGELOG.rst index b9c5aafe459..c5bfb1048a7 100644 --- a/openscenario/openscenario_interpreter/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter/CHANGELOG.rst @@ -32,6 +32,9 @@ Changelog for package openscenario_interpreter * add publish_empty_context parameter * Contributors: Masaya Kataoka +4.2.1 (2024-09-10) +------------------ + 4.2.0 (2024-09-09) ------------------ diff --git a/openscenario/openscenario_interpreter/package.xml b/openscenario/openscenario_interpreter/package.xml index 5a1379176d5..539783042b5 100644 --- a/openscenario/openscenario_interpreter/package.xml +++ b/openscenario/openscenario_interpreter/package.xml @@ -2,7 +2,7 @@ openscenario_interpreter - 4.2.0 + 4.2.1 OpenSCENARIO 1.2.0 interpreter package for Autoware Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter_example/CHANGELOG.rst b/openscenario/openscenario_interpreter_example/CHANGELOG.rst index 525d22ee2a8..dd25ebdd35a 100644 --- a/openscenario/openscenario_interpreter_example/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter_example/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package openscenario_interpreter_example * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.1 (2024-09-10) +------------------ + 4.2.0 (2024-09-09) ------------------ diff --git a/openscenario/openscenario_interpreter_example/package.xml b/openscenario/openscenario_interpreter_example/package.xml index 813cfc0bda9..7c373b60b86 100644 --- a/openscenario/openscenario_interpreter_example/package.xml +++ b/openscenario/openscenario_interpreter_example/package.xml @@ -3,7 +3,7 @@ openscenario_interpreter_example - 4.2.0 + 4.2.1 Examples for some TIER IV OpenSCENARIO Interpreter's features Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst b/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst index 55c6684f8db..95e5fc5b575 100644 --- a/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package openscenario_interpreter_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.1 (2024-09-10) +------------------ + 4.2.0 (2024-09-09) ------------------ diff --git a/openscenario/openscenario_interpreter_msgs/package.xml b/openscenario/openscenario_interpreter_msgs/package.xml index 813d66ec4e7..c1025e473c9 100644 --- a/openscenario/openscenario_interpreter_msgs/package.xml +++ b/openscenario/openscenario_interpreter_msgs/package.xml @@ -2,7 +2,7 @@ openscenario_interpreter_msgs - 4.2.0 + 4.2.1 ROS message types for package openscenario_interpreter Yamasaki Tatsuya Apache License 2.0 diff --git a/openscenario/openscenario_preprocessor/CHANGELOG.rst b/openscenario/openscenario_preprocessor/CHANGELOG.rst index e96fd8fcf07..73b87ba08c6 100644 --- a/openscenario/openscenario_preprocessor/CHANGELOG.rst +++ b/openscenario/openscenario_preprocessor/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package openscenario_preprocessor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.1 (2024-09-10) +------------------ + 4.2.0 (2024-09-09) ------------------ diff --git a/openscenario/openscenario_preprocessor/package.xml b/openscenario/openscenario_preprocessor/package.xml index f44e74303d3..07427ad9ebd 100644 --- a/openscenario/openscenario_preprocessor/package.xml +++ b/openscenario/openscenario_preprocessor/package.xml @@ -3,7 +3,7 @@ openscenario_preprocessor - 4.2.0 + 4.2.1 Example package for TIER IV OpenSCENARIO Interpreter Kotaro Yoshimoto Apache License 2.0 diff --git a/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst b/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst index 33356a19cf0..e17db512c53 100644 --- a/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst +++ b/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package openscenario_preprocessor_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.1 (2024-09-10) +------------------ + 4.2.0 (2024-09-09) ------------------ diff --git a/openscenario/openscenario_preprocessor_msgs/package.xml b/openscenario/openscenario_preprocessor_msgs/package.xml index 51db6a0bb77..81ef27144ac 100644 --- a/openscenario/openscenario_preprocessor_msgs/package.xml +++ b/openscenario/openscenario_preprocessor_msgs/package.xml @@ -2,7 +2,7 @@ openscenario_preprocessor_msgs - 4.2.0 + 4.2.1 ROS message types for package openscenario_preprocessor Kotaro Yoshimoto Apache License 2.0 diff --git a/openscenario/openscenario_utility/CHANGELOG.rst b/openscenario/openscenario_utility/CHANGELOG.rst index 3af8959cc64..64418d56389 100644 --- a/openscenario/openscenario_utility/CHANGELOG.rst +++ b/openscenario/openscenario_utility/CHANGELOG.rst @@ -24,6 +24,9 @@ Changelog for package openscenario_utility * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.1 (2024-09-10) +------------------ + 4.2.0 (2024-09-09) ------------------ diff --git a/openscenario/openscenario_utility/package.xml b/openscenario/openscenario_utility/package.xml index 2c9309a5a49..0452c65e4bc 100644 --- a/openscenario/openscenario_utility/package.xml +++ b/openscenario/openscenario_utility/package.xml @@ -2,7 +2,7 @@ openscenario_utility - 4.2.0 + 4.2.1 Utility tools for ASAM OpenSCENARIO 1.2.0 Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_validator/CHANGELOG.rst b/openscenario/openscenario_validator/CHANGELOG.rst index c8771876622..4974c949cd8 100644 --- a/openscenario/openscenario_validator/CHANGELOG.rst +++ b/openscenario/openscenario_validator/CHANGELOG.rst @@ -10,6 +10,9 @@ Changelog for package openscenario_validator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.1 (2024-09-10) +------------------ + 4.2.0 (2024-09-09) ------------------ diff --git a/openscenario/openscenario_validator/package.xml b/openscenario/openscenario_validator/package.xml index 46f34489fd5..fcac94a008d 100644 --- a/openscenario/openscenario_validator/package.xml +++ b/openscenario/openscenario_validator/package.xml @@ -2,7 +2,7 @@ openscenario_validator - 4.2.0 + 4.2.1 Validator for OpenSCENARIO 1.3 Kotaro Yoshimoto Apache License 2.0 diff --git a/rviz_plugins/openscenario_visualization/CHANGELOG.rst b/rviz_plugins/openscenario_visualization/CHANGELOG.rst index bd02b1875ab..bb7e779a749 100644 --- a/rviz_plugins/openscenario_visualization/CHANGELOG.rst +++ b/rviz_plugins/openscenario_visualization/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package openscenario_visualization * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.1 (2024-09-10) +------------------ + 4.2.0 (2024-09-09) ------------------ diff --git a/rviz_plugins/openscenario_visualization/package.xml b/rviz_plugins/openscenario_visualization/package.xml index fde305cd15b..e0017d0932a 100644 --- a/rviz_plugins/openscenario_visualization/package.xml +++ b/rviz_plugins/openscenario_visualization/package.xml @@ -2,7 +2,7 @@ openscenario_visualization - 4.2.0 + 4.2.1 Visualization tools for simulation results Masaya Kataoka Kyoichi Sugahara diff --git a/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst b/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst index ba6cca5ae93..1a6ab678121 100644 --- a/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst +++ b/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package real_time_factor_control_rviz_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.1 (2024-09-10) +------------------ + 4.2.0 (2024-09-09) ------------------ diff --git a/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml b/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml index 2201e871651..0e20f10e230 100644 --- a/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml +++ b/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml @@ -2,7 +2,7 @@ real_time_factor_control_rviz_plugin - 4.2.0 + 4.2.1 Slider controlling real time factor value. Paweł Lech Apache License 2.0 diff --git a/scenario_simulator_v2/CHANGELOG.rst b/scenario_simulator_v2/CHANGELOG.rst index bf0064df433..fb4b6a60a67 100644 --- a/scenario_simulator_v2/CHANGELOG.rst +++ b/scenario_simulator_v2/CHANGELOG.rst @@ -21,6 +21,12 @@ Changelog for package scenario_simulator_v2 * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.1 (2024-09-10) +------------------ +* Spelling changes +* Lint changes +* Contributors: Grzegorz Maj + 4.2.0 (2024-09-09) ------------------ diff --git a/scenario_simulator_v2/package.xml b/scenario_simulator_v2/package.xml index 005b42bc240..49d9a805b00 100644 --- a/scenario_simulator_v2/package.xml +++ b/scenario_simulator_v2/package.xml @@ -2,7 +2,7 @@ scenario_simulator_v2 - 4.2.0 + 4.2.1 scenario testing framework for Autoware Masaya Kataoka Apache License 2.0 diff --git a/simulation/behavior_tree_plugin/CHANGELOG.rst b/simulation/behavior_tree_plugin/CHANGELOG.rst index 884cd2681dd..7ef537a12f5 100644 --- a/simulation/behavior_tree_plugin/CHANGELOG.rst +++ b/simulation/behavior_tree_plugin/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package behavior_tree_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.1 (2024-09-10) +------------------ + 4.2.0 (2024-09-09) ------------------ diff --git a/simulation/behavior_tree_plugin/package.xml b/simulation/behavior_tree_plugin/package.xml index 0280fa610b5..efc1477f574 100644 --- a/simulation/behavior_tree_plugin/package.xml +++ b/simulation/behavior_tree_plugin/package.xml @@ -2,7 +2,7 @@ behavior_tree_plugin - 4.2.0 + 4.2.1 Behavior tree plugin for traffic_simulator masaya Apache 2.0 diff --git a/simulation/do_nothing_plugin/CHANGELOG.rst b/simulation/do_nothing_plugin/CHANGELOG.rst index ffac7c9ebd4..cf2746a65ae 100644 --- a/simulation/do_nothing_plugin/CHANGELOG.rst +++ b/simulation/do_nothing_plugin/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package do_nothing_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.1 (2024-09-10) +------------------ + 4.2.0 (2024-09-09) ------------------ diff --git a/simulation/do_nothing_plugin/package.xml b/simulation/do_nothing_plugin/package.xml index 22eda8d1269..af96fccbee9 100644 --- a/simulation/do_nothing_plugin/package.xml +++ b/simulation/do_nothing_plugin/package.xml @@ -2,7 +2,7 @@ do_nothing_plugin - 4.2.0 + 4.2.1 Behavior plugin for do nothing Masaya Kataoka Apache 2.0 diff --git a/simulation/simple_sensor_simulator/CHANGELOG.rst b/simulation/simple_sensor_simulator/CHANGELOG.rst index a967312719b..46f0089d1ce 100644 --- a/simulation/simple_sensor_simulator/CHANGELOG.rst +++ b/simulation/simple_sensor_simulator/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package simple_sensor_simulator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.1 (2024-09-10) +------------------ + 4.2.0 (2024-09-09) ------------------ diff --git a/simulation/simple_sensor_simulator/package.xml b/simulation/simple_sensor_simulator/package.xml index fba1b6b8bf2..d343fdf9bca 100644 --- a/simulation/simple_sensor_simulator/package.xml +++ b/simulation/simple_sensor_simulator/package.xml @@ -1,7 +1,7 @@ simple_sensor_simulator - 4.2.0 + 4.2.1 simple_sensor_simulator package masaya kataoka diff --git a/simulation/simulation_interface/CHANGELOG.rst b/simulation/simulation_interface/CHANGELOG.rst index e77441ef241..edd30f08fc8 100644 --- a/simulation/simulation_interface/CHANGELOG.rst +++ b/simulation/simulation_interface/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package simulation_interface * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.1 (2024-09-10) +------------------ + 4.2.0 (2024-09-09) ------------------ diff --git a/simulation/simulation_interface/package.xml b/simulation/simulation_interface/package.xml index 996dd089d0b..400517c47f5 100644 --- a/simulation/simulation_interface/package.xml +++ b/simulation/simulation_interface/package.xml @@ -2,7 +2,7 @@ simulation_interface - 4.2.0 + 4.2.1 packages to define interface between simulator and scenario interpreter Masaya Kataoka Apache License 2.0 diff --git a/simulation/traffic_simulator/CHANGELOG.rst b/simulation/traffic_simulator/CHANGELOG.rst index 1a61d823f75..21f22614cfc 100644 --- a/simulation/traffic_simulator/CHANGELOG.rst +++ b/simulation/traffic_simulator/CHANGELOG.rst @@ -21,6 +21,18 @@ Changelog for package traffic_simulator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.1 (2024-09-10) +------------------ +* Merge pull request `#1367 `_ from tier4/RJD-1197/canonicalized_lanelet_pose + Rjd 1197/canonicalized lanelet pose +* Spelling changes +* Lint changes +* Change assert check from bool to has_value +* Change invalid test cases to more obvious values +* Unit tests review changes +* CanonicalizedLaneletPose unit tests +* Contributors: Grzegorz Maj, Masaya Kataoka + 4.2.0 (2024-09-09) ------------------ * Merge pull request `#1362 `_ from tier4/feature/ros2-parameter-forwarding diff --git a/simulation/traffic_simulator/package.xml b/simulation/traffic_simulator/package.xml index c08ba92d91d..5dd00456acb 100644 --- a/simulation/traffic_simulator/package.xml +++ b/simulation/traffic_simulator/package.xml @@ -1,7 +1,7 @@ traffic_simulator - 4.2.0 + 4.2.1 control traffic flow masaya kataoka diff --git a/simulation/traffic_simulator_msgs/CHANGELOG.rst b/simulation/traffic_simulator_msgs/CHANGELOG.rst index b615cb5b853..803f9924925 100644 --- a/simulation/traffic_simulator_msgs/CHANGELOG.rst +++ b/simulation/traffic_simulator_msgs/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package openscenario_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.1 (2024-09-10) +------------------ + 4.2.0 (2024-09-09) ------------------ diff --git a/simulation/traffic_simulator_msgs/package.xml b/simulation/traffic_simulator_msgs/package.xml index e70bf444879..ae8c2b46276 100644 --- a/simulation/traffic_simulator_msgs/package.xml +++ b/simulation/traffic_simulator_msgs/package.xml @@ -2,7 +2,7 @@ traffic_simulator_msgs - 4.2.0 + 4.2.1 ROS messages for openscenario Masaya Kataoka Apache License 2.0 diff --git a/test_runner/random_test_runner/CHANGELOG.rst b/test_runner/random_test_runner/CHANGELOG.rst index c02728d68e2..b37aebab5e6 100644 --- a/test_runner/random_test_runner/CHANGELOG.rst +++ b/test_runner/random_test_runner/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package random_test_runner * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.1 (2024-09-10) +------------------ + 4.2.0 (2024-09-09) ------------------ diff --git a/test_runner/random_test_runner/package.xml b/test_runner/random_test_runner/package.xml index d7cc7c7ca4c..8366b28e337 100644 --- a/test_runner/random_test_runner/package.xml +++ b/test_runner/random_test_runner/package.xml @@ -2,7 +2,7 @@ random_test_runner - 4.2.0 + 4.2.1 Random behavior test runner piotr-zyskowski-rai Apache License 2.0 diff --git a/test_runner/scenario_test_runner/CHANGELOG.rst b/test_runner/scenario_test_runner/CHANGELOG.rst index 0e9d8b7395a..056c894558c 100644 --- a/test_runner/scenario_test_runner/CHANGELOG.rst +++ b/test_runner/scenario_test_runner/CHANGELOG.rst @@ -35,6 +35,9 @@ Changelog for package scenario_test_runner * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.1 (2024-09-10) +------------------ + 4.2.0 (2024-09-09) ------------------ * Merge pull request `#1362 `_ from tier4/feature/ros2-parameter-forwarding diff --git a/test_runner/scenario_test_runner/package.xml b/test_runner/scenario_test_runner/package.xml index f4146f760a5..f62735450fa 100644 --- a/test_runner/scenario_test_runner/package.xml +++ b/test_runner/scenario_test_runner/package.xml @@ -2,7 +2,7 @@ scenario_test_runner - 4.2.0 + 4.2.1 scenario test runner package Tatsuya Yamasaki Apache License 2.0 From 846960fdfddb37d3df2963b0c7fd96e25e11cbf2 Mon Sep 17 00:00:00 2001 From: satoshi-ota Date: Tue, 10 Sep 2024 12:55:46 +0900 Subject: [PATCH 239/304] fix: load necessary parameters Signed-off-by: satoshi-ota --- .../launch/mock_test.launch.py | 289 +++++++++++------- 1 file changed, 184 insertions(+), 105 deletions(-) diff --git a/mock/cpp_mock_scenarios/launch/mock_test.launch.py b/mock/cpp_mock_scenarios/launch/mock_test.launch.py index d976cf696ac..ee9f40194ef 100644 --- a/mock/cpp_mock_scenarios/launch/mock_test.launch.py +++ b/mock/cpp_mock_scenarios/launch/mock_test.launch.py @@ -30,7 +30,7 @@ from launch.events import Shutdown from launch.event_handlers import OnProcessExit, OnProcessIO -from launch.actions import EmitEvent, RegisterEventHandler, LogInfo, TimerAction +from launch.actions import EmitEvent, RegisterEventHandler, LogInfo, TimerAction, OpaqueFunction from launch.actions.declare_launch_argument import DeclareLaunchArgument from launch.substitutions.launch_configuration import LaunchConfiguration @@ -40,7 +40,6 @@ from pathlib import Path - class Color: BLACK = "\033[30m" RED = "\033[31m" @@ -70,113 +69,193 @@ def on_stdout_output(event: launch.Event) -> None: if lines[0] == "cpp_scenario:success": print(Color.GREEN + "Scenario Succeed" + Color.END) +def architecture_types(): + return ["awf/universe", "awf/universe/20230906"] -def generate_launch_description(): - timeout = LaunchConfiguration("timeout", default=10.0) - scenario = LaunchConfiguration("scenario", default="") - scenario_package = LaunchConfiguration("package", default="cpp_mock_scenarios") - junit_path = LaunchConfiguration("junit_path", default="/tmp/output.xunit.xml") - launch_rviz = LaunchConfiguration("launch_rviz", default=False) - vehicle_model = LaunchConfiguration("vehicle_model", default="sample_vehicle") - sensor_model = LaunchConfiguration("sensor_model", default="sample_sensor_kit") - consider_pose_by_road_slope = LaunchConfiguration("consider_pose_by_road_slope", default=True) - scenario_node = Node( - package=scenario_package, - executable=scenario, - name="scenario_node", - output="screen", - arguments=[("__log_level:=info")], - parameters=[ - { - "junit_path": junit_path, - "timeout": timeout, - "architecture_type": "awf/universe", - "autoware_launch_file": "planning_simulator.launch.xml", - "autoware_launch_package": "autoware_launch", - "launch_autoware": True, - "vehicle_model": vehicle_model, - "sensor_model": sensor_model, - "initialize_duration": 900, - "consider_pose_by_road_slope": consider_pose_by_road_slope - } - ], - ) + +def default_autoware_launch_package_of(architecture_type): + if architecture_type not in architecture_types(): + raise KeyError( + f"architecture_type := {architecture_type} is not supported. Choose one of {architecture_types()}." + ) + return { + "awf/universe": "autoware_launch", + "awf/universe/20230906": "autoware_launch", + }[architecture_type] + + +def default_autoware_launch_file_of(architecture_type): + if architecture_type not in architecture_types(): + raise KeyError( + f"architecture_type := {architecture_type} is not supported. Choose one of {architecture_types()}." + ) + return { + "awf/universe": "planning_simulator.launch.xml", + "awf/universe/20230906": "planning_simulator.launch.xml", + }[architecture_type] + + +def launch_setup(context, *args, **kwargs): + # fmt: off + architecture_type = LaunchConfiguration("architecture_type", default="awf/universe/20230906") + autoware_launch_file = LaunchConfiguration("autoware_launch_file", default=default_autoware_launch_file_of(architecture_type.perform(context))) + autoware_launch_package = LaunchConfiguration("autoware_launch_package", default=default_autoware_launch_package_of(architecture_type.perform(context))) + consider_acceleration_by_road_slope = LaunchConfiguration("consider_acceleration_by_road_slope", default=False) + consider_pose_by_road_slope = LaunchConfiguration("consider_pose_by_road_slope", default=True) + global_frame_rate = LaunchConfiguration("global_frame_rate", default=30.0) + global_real_time_factor = LaunchConfiguration("global_real_time_factor", default=1.0) + global_timeout = LaunchConfiguration("global_timeout", default=180) + initialize_duration = LaunchConfiguration("initialize_duration", default=300) + launch_autoware = LaunchConfiguration("launch_autoware", default=True) + launch_rviz = LaunchConfiguration("launch_rviz", default=False) + launch_simple_sensor_simulator = LaunchConfiguration("launch_simple_sensor_simulator", default=True) + output_directory = LaunchConfiguration("output_directory", default=Path("/tmp")) + port = LaunchConfiguration("port", default=5555) + publish_empty_context = LaunchConfiguration("publish_empty_context", default=False) + record = LaunchConfiguration("record", default=False) + rviz_config = LaunchConfiguration("rviz_config", default="") + scenario = LaunchConfiguration("scenario", default=Path("/dev/null")) + sensor_model = LaunchConfiguration("sensor_model", default="") + sigterm_timeout = LaunchConfiguration("sigterm_timeout", default=8) + use_sim_time = LaunchConfiguration("use_sim_time", default=False) + vehicle_model = LaunchConfiguration("vehicle_model", default="") + scenario_package = LaunchConfiguration("package", default="cpp_mock_scenarios") + junit_path = LaunchConfiguration("junit_path", default="/tmp/output.xunit.xml") + # fmt: on + + print(f"architecture_type := {architecture_type.perform(context)}") + print(f"autoware_launch_file := {autoware_launch_file.perform(context)}") + print(f"autoware_launch_package := {autoware_launch_package.perform(context)}") + print(f"consider_acceleration_by_road_slope := {consider_acceleration_by_road_slope.perform(context)}") + print(f"consider_pose_by_road_slope := {consider_pose_by_road_slope.perform(context)}") + print(f"global_frame_rate := {global_frame_rate.perform(context)}") + print(f"global_real_time_factor := {global_real_time_factor.perform(context)}") + print(f"global_timeout := {global_timeout.perform(context)}") + print(f"initialize_duration := {initialize_duration.perform(context)}") + print(f"launch_autoware := {launch_autoware.perform(context)}") + print(f"launch_rviz := {launch_rviz.perform(context)}") + print(f"output_directory := {output_directory.perform(context)}") + print(f"port := {port.perform(context)}") + print(f"publish_empty_context := {publish_empty_context.perform(context)}") + print(f"record := {record.perform(context)}") + print(f"rviz_config := {rviz_config.perform(context)}") + print(f"scenario := {scenario.perform(context)}") + print(f"sensor_model := {sensor_model.perform(context)}") + print(f"sigterm_timeout := {sigterm_timeout.perform(context)}") + print(f"use_sim_time := {use_sim_time.perform(context)}") + print(f"vehicle_model := {vehicle_model.perform(context)}") + print(f"scenario_package := {scenario_package.perform(context)}") + print(f"junit_path := {junit_path.perform(context)}") + + def make_parameters(): + parameters = [ + {"architecture_type": architecture_type}, + {"autoware_launch_file": autoware_launch_file}, + {"autoware_launch_package": autoware_launch_package}, + {"consider_acceleration_by_road_slope": consider_acceleration_by_road_slope}, + {"consider_pose_by_road_slope": consider_pose_by_road_slope}, + {"initialize_duration": initialize_duration}, + {"launch_autoware": launch_autoware}, + {"port": port}, + {"publish_empty_context" : publish_empty_context}, + {"record": record}, + {"rviz_config": rviz_config}, + {"sensor_model": sensor_model}, + {"sigterm_timeout": sigterm_timeout}, + {"vehicle_model": vehicle_model}, + {"global_real_time_factor": global_real_time_factor}, + {"global_frame_rate": global_frame_rate}, + {"global_timeout": global_timeout}, + ] + parameters += make_vehicle_parameters() + return parameters + + def make_vehicle_parameters(): + parameters = [] + + def description(): + return get_package_share_directory( + vehicle_model.perform(context) + "_description" + ) + + if vehicle_model.perform(context): + parameters.append(description() + "/config/vehicle_info.param.yaml") + parameters.append(description() + "/config/simulator_model.param.yaml") + return parameters + + cpp_scenario_node = Node( + package=scenario_package, + executable=scenario, + name="scenario_node", + output="screen", + arguments=[("__log_level:=info")], + parameters=make_parameters() + [{"use_sim_time": use_sim_time}], + ) io_handler = OnProcessIO( - target_action=scenario_node, + target_action=cpp_scenario_node, on_stderr=on_stderr_output, on_stdout=on_stdout_output, ) shutdown_handler = OnProcessExit( - target_action=scenario_node, on_exit=[EmitEvent(event=Shutdown())] + target_action=cpp_scenario_node, on_exit=[EmitEvent(event=Shutdown())] ) - description = LaunchDescription( - [ - DeclareLaunchArgument( - "scenario", default_value=scenario, description="Name of the scenario." - ), - DeclareLaunchArgument( - "package", - default_value=scenario_package, - description="Name of package your scenario exists", - ), - DeclareLaunchArgument( - "timeout", default_value=timeout, description="Timeout in seconds." - ), - DeclareLaunchArgument( - "junit_path", - default_value=junit_path, - description="Path of the junit output.", - ), - DeclareLaunchArgument( - "launch_rviz", - default_value=launch_rviz, - description="If true, launch with rviz.", - ), - DeclareLaunchArgument( - "vehicle_model", - default_value=vehicle_model, - description="Vehicle model of the Autoware", - ), - DeclareLaunchArgument( - "sensor_model", - default_value=sensor_model, - description="Sensor model of the Autoware", - ), - DeclareLaunchArgument( - "consider_pose_by_road_slope", - default_value=consider_pose_by_road_slope , - description="Consideration of lanelet slope in matching position", - ), - scenario_node, - RegisterEventHandler(event_handler=io_handler), - RegisterEventHandler(event_handler=shutdown_handler), - Node( - package="simple_sensor_simulator", - executable="simple_sensor_simulator_node", - name="simple_sensor_simulator_node", - output="log", - arguments=[("__log_level:=warn")], - ), - Node( - package="traffic_simulator", - executable="visualization_node", - name="visualizer", - output="screen", - ), - Node( - package="rviz2", - executable="rviz2", - name="rviz2", - output={"stderr": "log", "stdout": "log"}, - condition=IfCondition(launch_rviz), - arguments=[ - "-d", - str( - Path(get_package_share_directory("cpp_mock_scenarios")) - / "rviz/mock_test.rviz" - ), - ], - ), - ] - ) - return description + + return [ + # fmt: off + DeclareLaunchArgument("architecture_type", default_value=architecture_type ), + DeclareLaunchArgument("autoware_launch_file", default_value=autoware_launch_file ), + DeclareLaunchArgument("autoware_launch_package", default_value=autoware_launch_package ), + DeclareLaunchArgument("consider_acceleration_by_road_slope", default_value=consider_acceleration_by_road_slope), + DeclareLaunchArgument("consider_pose_by_road_slope", default_value=consider_pose_by_road_slope ), + DeclareLaunchArgument("global_frame_rate", default_value=global_frame_rate ), + DeclareLaunchArgument("global_real_time_factor", default_value=global_real_time_factor ), + DeclareLaunchArgument("global_timeout", default_value=global_timeout ), + DeclareLaunchArgument("launch_autoware", default_value=launch_autoware ), + DeclareLaunchArgument("launch_rviz", default_value=launch_rviz ), + DeclareLaunchArgument("publish_empty_context", default_value=publish_empty_context ), + DeclareLaunchArgument("output_directory", default_value=output_directory ), + DeclareLaunchArgument("rviz_config", default_value=rviz_config ), + DeclareLaunchArgument("scenario", default_value=scenario ), + DeclareLaunchArgument("sensor_model", default_value=sensor_model ), + DeclareLaunchArgument("sigterm_timeout", default_value=sigterm_timeout ), + DeclareLaunchArgument("use_sim_time", default_value=use_sim_time ), + DeclareLaunchArgument("vehicle_model", default_value=vehicle_model ), + DeclareLaunchArgument("scenario_package", default_value=scenario_package ), + DeclareLaunchArgument("junit_path", default_value=junit_path ), + # fmt: on + cpp_scenario_node, + Node( + package="simple_sensor_simulator", + executable="simple_sensor_simulator_node", + namespace="simulation", + output="screen", + parameters=make_parameters() + [{"use_sim_time": use_sim_time}], + condition=IfCondition(launch_simple_sensor_simulator), + ), + Node( + package="traffic_simulator", + executable="visualization_node", + namespace="simulation", + name="visualizer", + output="screen", + ), + Node( + package="rviz2", + executable="rviz2", + name="rviz2", + output={"stderr": "log", "stdout": "log"}, + condition=IfCondition(launch_rviz), + arguments=[ + "-d", + str( + Path(get_package_share_directory("traffic_simulator")) + / "config/scenario_simulator_v2.rviz" + ), + ], + ), + RegisterEventHandler(event_handler=io_handler), + RegisterEventHandler(event_handler=shutdown_handler), + ] + +def generate_launch_description(): + return LaunchDescription([OpaqueFunction(function=launch_setup)]) From 2e3adec88d6b51cd2b94565d26ce1759276b963f Mon Sep 17 00:00:00 2001 From: satoshi-ota Date: Tue, 10 Sep 2024 12:50:19 +0900 Subject: [PATCH 240/304] fix: make it possible to change hard-coded parameters Signed-off-by: satoshi-ota --- mock/cpp_mock_scenarios/src/cpp_scenario_node.cpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/mock/cpp_mock_scenarios/src/cpp_scenario_node.cpp b/mock/cpp_mock_scenarios/src/cpp_scenario_node.cpp index 47ca8c25d98..7335d528091 100644 --- a/mock/cpp_mock_scenarios/src/cpp_scenario_node.cpp +++ b/mock/cpp_mock_scenarios/src/cpp_scenario_node.cpp @@ -22,7 +22,10 @@ CppScenarioNode::CppScenarioNode( const std::string & lanelet2_map_file, const std::string & scenario_filename, const bool verbose, const rclcpp::NodeOptions & option) : Node(node_name, option), - api_(this, configure(map_path, lanelet2_map_file, scenario_filename, verbose), 1.0, 20), + api_( + this, configure(map_path, lanelet2_map_file, scenario_filename, verbose), + declare_parameter("global_real_time_factor", 1.0), + declare_parameter("global_frame_rate", 20.0)), scenario_filename_(scenario_filename), exception_expect_(false) { From a8b8a602b9a919f95ca3c20711405af6d3bef8d8 Mon Sep 17 00:00:00 2001 From: satoshi-ota Date: Tue, 10 Sep 2024 13:16:27 +0900 Subject: [PATCH 241/304] fix: use global timeout Signed-off-by: satoshi-ota --- .../include/cpp_mock_scenarios/cpp_scenario_node.hpp | 2 +- mock/cpp_mock_scenarios/src/cpp_scenario_node.cpp | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/mock/cpp_mock_scenarios/include/cpp_mock_scenarios/cpp_scenario_node.hpp b/mock/cpp_mock_scenarios/include/cpp_mock_scenarios/cpp_scenario_node.hpp index aa7df2b5dea..4d1141c8fc7 100644 --- a/mock/cpp_mock_scenarios/include/cpp_mock_scenarios/cpp_scenario_node.hpp +++ b/mock/cpp_mock_scenarios/include/cpp_mock_scenarios/cpp_scenario_node.hpp @@ -68,7 +68,7 @@ class CppScenarioNode : public rclcpp::Node virtual void onUpdate() = 0; virtual void onInitialize() = 0; rclcpp::TimerBase::SharedPtr update_timer_; - double timeout_; + int timeout_; auto configure( const std::string & map_path, const std::string & lanelet2_map_file, const std::string & scenario_filename, const bool verbose) -> traffic_simulator::Configuration diff --git a/mock/cpp_mock_scenarios/src/cpp_scenario_node.cpp b/mock/cpp_mock_scenarios/src/cpp_scenario_node.cpp index 7335d528091..70559cab61e 100644 --- a/mock/cpp_mock_scenarios/src/cpp_scenario_node.cpp +++ b/mock/cpp_mock_scenarios/src/cpp_scenario_node.cpp @@ -31,8 +31,8 @@ CppScenarioNode::CppScenarioNode( { declare_parameter("junit_path", "/tmp"); get_parameter("junit_path", junit_path_); - declare_parameter("timeout", 10.0); - get_parameter("timeout", timeout_); + declare_parameter("global_timeout", 10.0); + get_parameter("global_timeout", timeout_); traffic_simulator::lanelet_pose::CanonicalizedLaneletPose::setConsiderPoseByRoadSlope([&]() { if (not has_parameter("consider_pose_by_road_slope")) { From 33a329d1bdf669b0ae07200eb0a2ce5618b7b686 Mon Sep 17 00:00:00 2001 From: Release Bot Date: Tue, 10 Sep 2024 04:32:36 +0000 Subject: [PATCH 242/304] Bump version of scenario_simulator_v2 from version 4.2.1 to version 4.2.2 --- common/math/arithmetic/CHANGELOG.rst | 8 ++++ common/math/arithmetic/package.xml | 2 +- common/math/geometry/CHANGELOG.rst | 43 +++++++++++++++++++ common/math/geometry/package.xml | 2 +- .../CHANGELOG.rst | 8 ++++ .../scenario_simulator_exception/package.xml | 2 +- common/simple_junit/CHANGELOG.rst | 8 ++++ common/simple_junit/package.xml | 2 +- common/status_monitor/CHANGELOG.rst | 8 ++++ common/status_monitor/package.xml | 2 +- external/concealer/CHANGELOG.rst | 8 ++++ external/concealer/package.xml | 2 +- external/embree_vendor/CHANGELOG.rst | 8 ++++ external/embree_vendor/package.xml | 2 +- map/kashiwanoha_map/CHANGELOG.rst | 8 ++++ map/kashiwanoha_map/package.xml | 2 +- map/simple_cross_map/CHANGELOG.rst | 8 ++++ map/simple_cross_map/package.xml | 2 +- mock/cpp_mock_scenarios/CHANGELOG.rst | 8 ++++ mock/cpp_mock_scenarios/package.xml | 2 +- .../CHANGELOG.rst | 8 ++++ .../package.xml | 2 +- .../openscenario_interpreter/CHANGELOG.rst | 8 ++++ .../openscenario_interpreter/package.xml | 2 +- .../CHANGELOG.rst | 8 ++++ .../package.xml | 2 +- .../CHANGELOG.rst | 8 ++++ .../openscenario_interpreter_msgs/package.xml | 2 +- .../openscenario_preprocessor/CHANGELOG.rst | 8 ++++ .../openscenario_preprocessor/package.xml | 2 +- .../CHANGELOG.rst | 8 ++++ .../package.xml | 2 +- .../openscenario_utility/CHANGELOG.rst | 8 ++++ openscenario/openscenario_utility/package.xml | 2 +- .../openscenario_validator/CHANGELOG.rst | 8 ++++ .../openscenario_validator/package.xml | 2 +- .../openscenario_visualization/CHANGELOG.rst | 8 ++++ .../openscenario_visualization/package.xml | 2 +- .../CHANGELOG.rst | 8 ++++ .../package.xml | 2 +- scenario_simulator_v2/CHANGELOG.rst | 8 ++++ scenario_simulator_v2/package.xml | 2 +- simulation/behavior_tree_plugin/CHANGELOG.rst | 8 ++++ simulation/behavior_tree_plugin/package.xml | 2 +- simulation/do_nothing_plugin/CHANGELOG.rst | 8 ++++ simulation/do_nothing_plugin/package.xml | 2 +- .../simple_sensor_simulator/CHANGELOG.rst | 8 ++++ .../simple_sensor_simulator/package.xml | 2 +- simulation/simulation_interface/CHANGELOG.rst | 8 ++++ simulation/simulation_interface/package.xml | 2 +- simulation/traffic_simulator/CHANGELOG.rst | 8 ++++ simulation/traffic_simulator/package.xml | 2 +- .../traffic_simulator_msgs/CHANGELOG.rst | 8 ++++ simulation/traffic_simulator_msgs/package.xml | 2 +- test_runner/random_test_runner/CHANGELOG.rst | 8 ++++ test_runner/random_test_runner/package.xml | 2 +- .../scenario_test_runner/CHANGELOG.rst | 8 ++++ test_runner/scenario_test_runner/package.xml | 2 +- 58 files changed, 296 insertions(+), 29 deletions(-) diff --git a/common/math/arithmetic/CHANGELOG.rst b/common/math/arithmetic/CHANGELOG.rst index ada96ba019d..7c95d4238bb 100644 --- a/common/math/arithmetic/CHANGELOG.rst +++ b/common/math/arithmetic/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package arithmetic * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.2 (2024-09-10) +------------------ +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Contributors: Masaya Kataoka, Michał Ciasnocha + 4.2.1 (2024-09-10) ------------------ diff --git a/common/math/arithmetic/package.xml b/common/math/arithmetic/package.xml index ecc5b159eda..225fcd9dfe5 100644 --- a/common/math/arithmetic/package.xml +++ b/common/math/arithmetic/package.xml @@ -2,7 +2,7 @@ arithmetic - 4.2.1 + 4.2.2 arithmetic library for scenario_simulator_v2 Tatsuya Yamasaki Apache License 2.0 diff --git a/common/math/geometry/CHANGELOG.rst b/common/math/geometry/CHANGELOG.rst index cfb4e74f618..ed87df592b4 100644 --- a/common/math/geometry/CHANGELOG.rst +++ b/common/math/geometry/CHANGELOG.rst @@ -21,6 +21,49 @@ Changelog for package geometry * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.2 (2024-09-10) +------------------ +* Merge pull request `#1341 `_ from tier4/RJD-1278/geometry-update + Rjd 1278/geometry update +* Merge branch 'master' into RJD-1278/geometry-update +* updates after merge +* update testcase +* remove empty line +* isIntersect2D_collinear +* refactor toPolygon2D tests +* add comments +* bounding_box clean up +* clean up vector3 +* rename tests in HermiteCurve +* rename tests in CatmullRomSpline +* quaternion operators +* tune down numbers +* sort tests, rm old duplicate +* getIntersection2D function +* getIntersection2DSValue and isIntersect2D functions +* getPose, getPoint refactor +* add a proper structure to the test files +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* update testcase +* remove empty line +* isIntersect2D_collinear +* Merge branch 'master' into RJD-1278/geometry-update +* refactor toPolygon2D tests +* add comments +* bounding_box clean up +* clean up vector3 +* rename tests in HermiteCurve +* rename tests in CatmullRomSpline +* quaternion operators +* tune down numbers +* sort tests, rm old duplicate +* getIntersection2D function +* getIntersection2DSValue and isIntersect2D functions +* getPose, getPoint refactor +* add a proper structure to the test files +* Contributors: Masaya Kataoka, Michał Ciasnocha, robomic + 4.2.1 (2024-09-10) ------------------ diff --git a/common/math/geometry/package.xml b/common/math/geometry/package.xml index 2e4d8903e86..2d29d6f85f1 100644 --- a/common/math/geometry/package.xml +++ b/common/math/geometry/package.xml @@ -2,7 +2,7 @@ geometry - 4.2.1 + 4.2.2 geometry math library for scenario_simulator_v2 application Masaya Kataoka Apache License 2.0 diff --git a/common/scenario_simulator_exception/CHANGELOG.rst b/common/scenario_simulator_exception/CHANGELOG.rst index 9a73bcf2d37..554de126098 100644 --- a/common/scenario_simulator_exception/CHANGELOG.rst +++ b/common/scenario_simulator_exception/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package scenario_simulator_exception * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.2 (2024-09-10) +------------------ +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Contributors: Masaya Kataoka, Michał Ciasnocha + 4.2.1 (2024-09-10) ------------------ diff --git a/common/scenario_simulator_exception/package.xml b/common/scenario_simulator_exception/package.xml index 10e83d35f6d..ef3fd96b1eb 100644 --- a/common/scenario_simulator_exception/package.xml +++ b/common/scenario_simulator_exception/package.xml @@ -2,7 +2,7 @@ scenario_simulator_exception - 4.2.1 + 4.2.2 Exception types for scenario simulator Tatsuya Yamasaki Apache License 2.0 diff --git a/common/simple_junit/CHANGELOG.rst b/common/simple_junit/CHANGELOG.rst index d6bb515de90..3ae5e0e607e 100644 --- a/common/simple_junit/CHANGELOG.rst +++ b/common/simple_junit/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package junit_exporter * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.2 (2024-09-10) +------------------ +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Contributors: Masaya Kataoka, Michał Ciasnocha + 4.2.1 (2024-09-10) ------------------ diff --git a/common/simple_junit/package.xml b/common/simple_junit/package.xml index 698f4663cdf..52b345ecc29 100644 --- a/common/simple_junit/package.xml +++ b/common/simple_junit/package.xml @@ -2,7 +2,7 @@ simple_junit - 4.2.1 + 4.2.2 Lightweight JUnit library for ROS 2 Masaya Kataoka Tatsuya Yamasaki diff --git a/common/status_monitor/CHANGELOG.rst b/common/status_monitor/CHANGELOG.rst index 890e0cf6554..977da120e29 100644 --- a/common/status_monitor/CHANGELOG.rst +++ b/common/status_monitor/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package status_monitor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.2 (2024-09-10) +------------------ +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Contributors: Masaya Kataoka, Michał Ciasnocha + 4.2.1 (2024-09-10) ------------------ diff --git a/common/status_monitor/package.xml b/common/status_monitor/package.xml index 9ba065144fa..6e9f7ddfe55 100644 --- a/common/status_monitor/package.xml +++ b/common/status_monitor/package.xml @@ -2,7 +2,7 @@ status_monitor - 4.2.1 + 4.2.2 none Tatsuya Yamasaki Apache License 2.0 diff --git a/external/concealer/CHANGELOG.rst b/external/concealer/CHANGELOG.rst index 5e9d240adb3..182b8a56937 100644 --- a/external/concealer/CHANGELOG.rst +++ b/external/concealer/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package concealer * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.2 (2024-09-10) +------------------ +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Contributors: Masaya Kataoka, Michał Ciasnocha + 4.2.1 (2024-09-10) ------------------ diff --git a/external/concealer/package.xml b/external/concealer/package.xml index 62a6fca68cc..ff2fb906b99 100644 --- a/external/concealer/package.xml +++ b/external/concealer/package.xml @@ -2,7 +2,7 @@ concealer - 4.2.1 + 4.2.2 Provides a class 'Autoware' to conceal miscellaneous things to simplify Autoware management of the simulator. Tatsuya Yamasaki Apache License 2.0 diff --git a/external/embree_vendor/CHANGELOG.rst b/external/embree_vendor/CHANGELOG.rst index 79db7206c7f..fac779b36c5 100644 --- a/external/embree_vendor/CHANGELOG.rst +++ b/external/embree_vendor/CHANGELOG.rst @@ -24,6 +24,14 @@ Changelog for package embree_vendor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.2 (2024-09-10) +------------------ +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Contributors: Masaya Kataoka, Michał Ciasnocha + 4.2.1 (2024-09-10) ------------------ diff --git a/external/embree_vendor/package.xml b/external/embree_vendor/package.xml index 399446daa27..009829846a5 100644 --- a/external/embree_vendor/package.xml +++ b/external/embree_vendor/package.xml @@ -2,7 +2,7 @@ embree_vendor - 4.2.1 + 4.2.2 vendor packages for intel raytracing kernel library masaya Apache 2.0 diff --git a/map/kashiwanoha_map/CHANGELOG.rst b/map/kashiwanoha_map/CHANGELOG.rst index cd6f5f3fa00..ba56daf1487 100644 --- a/map/kashiwanoha_map/CHANGELOG.rst +++ b/map/kashiwanoha_map/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package kashiwanoha_map * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.2 (2024-09-10) +------------------ +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Contributors: Masaya Kataoka, Michał Ciasnocha + 4.2.1 (2024-09-10) ------------------ diff --git a/map/kashiwanoha_map/package.xml b/map/kashiwanoha_map/package.xml index 02af3dfe663..69327d2912f 100644 --- a/map/kashiwanoha_map/package.xml +++ b/map/kashiwanoha_map/package.xml @@ -2,7 +2,7 @@ kashiwanoha_map - 4.2.1 + 4.2.2 map package for kashiwanoha Masaya Kataoka Apache License 2.0 diff --git a/map/simple_cross_map/CHANGELOG.rst b/map/simple_cross_map/CHANGELOG.rst index 1517df254c6..34c60095023 100644 --- a/map/simple_cross_map/CHANGELOG.rst +++ b/map/simple_cross_map/CHANGELOG.rst @@ -9,6 +9,14 @@ Changelog for package simple_cross_map * Merge branch 'master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.2 (2024-09-10) +------------------ +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Contributors: Masaya Kataoka, Michał Ciasnocha + 4.2.1 (2024-09-10) ------------------ diff --git a/map/simple_cross_map/package.xml b/map/simple_cross_map/package.xml index c009da3e6d6..e0702113e58 100644 --- a/map/simple_cross_map/package.xml +++ b/map/simple_cross_map/package.xml @@ -2,7 +2,7 @@ simple_cross_map - 4.2.1 + 4.2.2 map package for simple cross Masaya Kataoka Apache License 2.0 diff --git a/mock/cpp_mock_scenarios/CHANGELOG.rst b/mock/cpp_mock_scenarios/CHANGELOG.rst index 75b73636c61..5cf1013e47f 100644 --- a/mock/cpp_mock_scenarios/CHANGELOG.rst +++ b/mock/cpp_mock_scenarios/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package cpp_mock_scenarios * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.2 (2024-09-10) +------------------ +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Contributors: Masaya Kataoka, Michał Ciasnocha + 4.2.1 (2024-09-10) ------------------ diff --git a/mock/cpp_mock_scenarios/package.xml b/mock/cpp_mock_scenarios/package.xml index 86a60b4d94a..0fea79cf6ed 100644 --- a/mock/cpp_mock_scenarios/package.xml +++ b/mock/cpp_mock_scenarios/package.xml @@ -2,7 +2,7 @@ cpp_mock_scenarios - 4.2.1 + 4.2.2 C++ mock scenarios masaya Apache License 2.0 diff --git a/openscenario/openscenario_experimental_catalog/CHANGELOG.rst b/openscenario/openscenario_experimental_catalog/CHANGELOG.rst index bc6b5d4874f..94d30305999 100644 --- a/openscenario/openscenario_experimental_catalog/CHANGELOG.rst +++ b/openscenario/openscenario_experimental_catalog/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package openscenario_experimental_catalog * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.2 (2024-09-10) +------------------ +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Contributors: Masaya Kataoka, Michał Ciasnocha + 4.2.1 (2024-09-10) ------------------ diff --git a/openscenario/openscenario_experimental_catalog/package.xml b/openscenario/openscenario_experimental_catalog/package.xml index d773d677134..14926ad4413 100644 --- a/openscenario/openscenario_experimental_catalog/package.xml +++ b/openscenario/openscenario_experimental_catalog/package.xml @@ -2,7 +2,7 @@ openscenario_experimental_catalog - 4.2.1 + 4.2.2 TIER IV experimental catalogs for OpenSCENARIO Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter/CHANGELOG.rst b/openscenario/openscenario_interpreter/CHANGELOG.rst index c5bfb1048a7..0d6f45fa1d2 100644 --- a/openscenario/openscenario_interpreter/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter/CHANGELOG.rst @@ -32,6 +32,14 @@ Changelog for package openscenario_interpreter * add publish_empty_context parameter * Contributors: Masaya Kataoka +4.2.2 (2024-09-10) +------------------ +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Contributors: Masaya Kataoka, Michał Ciasnocha + 4.2.1 (2024-09-10) ------------------ diff --git a/openscenario/openscenario_interpreter/package.xml b/openscenario/openscenario_interpreter/package.xml index 539783042b5..22f7cb5e429 100644 --- a/openscenario/openscenario_interpreter/package.xml +++ b/openscenario/openscenario_interpreter/package.xml @@ -2,7 +2,7 @@ openscenario_interpreter - 4.2.1 + 4.2.2 OpenSCENARIO 1.2.0 interpreter package for Autoware Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter_example/CHANGELOG.rst b/openscenario/openscenario_interpreter_example/CHANGELOG.rst index dd25ebdd35a..bdcf97388e2 100644 --- a/openscenario/openscenario_interpreter_example/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter_example/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package openscenario_interpreter_example * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.2 (2024-09-10) +------------------ +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Contributors: Masaya Kataoka, Michał Ciasnocha + 4.2.1 (2024-09-10) ------------------ diff --git a/openscenario/openscenario_interpreter_example/package.xml b/openscenario/openscenario_interpreter_example/package.xml index 7c373b60b86..6ada7470f7b 100644 --- a/openscenario/openscenario_interpreter_example/package.xml +++ b/openscenario/openscenario_interpreter_example/package.xml @@ -3,7 +3,7 @@ openscenario_interpreter_example - 4.2.1 + 4.2.2 Examples for some TIER IV OpenSCENARIO Interpreter's features Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst b/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst index 95e5fc5b575..d59b9fa3a77 100644 --- a/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package openscenario_interpreter_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.2 (2024-09-10) +------------------ +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Contributors: Masaya Kataoka, Michał Ciasnocha + 4.2.1 (2024-09-10) ------------------ diff --git a/openscenario/openscenario_interpreter_msgs/package.xml b/openscenario/openscenario_interpreter_msgs/package.xml index c1025e473c9..d3e550e165e 100644 --- a/openscenario/openscenario_interpreter_msgs/package.xml +++ b/openscenario/openscenario_interpreter_msgs/package.xml @@ -2,7 +2,7 @@ openscenario_interpreter_msgs - 4.2.1 + 4.2.2 ROS message types for package openscenario_interpreter Yamasaki Tatsuya Apache License 2.0 diff --git a/openscenario/openscenario_preprocessor/CHANGELOG.rst b/openscenario/openscenario_preprocessor/CHANGELOG.rst index 73b87ba08c6..41fb89b0237 100644 --- a/openscenario/openscenario_preprocessor/CHANGELOG.rst +++ b/openscenario/openscenario_preprocessor/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package openscenario_preprocessor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.2 (2024-09-10) +------------------ +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Contributors: Masaya Kataoka, Michał Ciasnocha + 4.2.1 (2024-09-10) ------------------ diff --git a/openscenario/openscenario_preprocessor/package.xml b/openscenario/openscenario_preprocessor/package.xml index 07427ad9ebd..068ed93f7cb 100644 --- a/openscenario/openscenario_preprocessor/package.xml +++ b/openscenario/openscenario_preprocessor/package.xml @@ -3,7 +3,7 @@ openscenario_preprocessor - 4.2.1 + 4.2.2 Example package for TIER IV OpenSCENARIO Interpreter Kotaro Yoshimoto Apache License 2.0 diff --git a/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst b/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst index e17db512c53..09161cd0b25 100644 --- a/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst +++ b/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package openscenario_preprocessor_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.2 (2024-09-10) +------------------ +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Contributors: Masaya Kataoka, Michał Ciasnocha + 4.2.1 (2024-09-10) ------------------ diff --git a/openscenario/openscenario_preprocessor_msgs/package.xml b/openscenario/openscenario_preprocessor_msgs/package.xml index 81ef27144ac..47c97df09ee 100644 --- a/openscenario/openscenario_preprocessor_msgs/package.xml +++ b/openscenario/openscenario_preprocessor_msgs/package.xml @@ -2,7 +2,7 @@ openscenario_preprocessor_msgs - 4.2.1 + 4.2.2 ROS message types for package openscenario_preprocessor Kotaro Yoshimoto Apache License 2.0 diff --git a/openscenario/openscenario_utility/CHANGELOG.rst b/openscenario/openscenario_utility/CHANGELOG.rst index 64418d56389..56fddf8f088 100644 --- a/openscenario/openscenario_utility/CHANGELOG.rst +++ b/openscenario/openscenario_utility/CHANGELOG.rst @@ -24,6 +24,14 @@ Changelog for package openscenario_utility * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.2 (2024-09-10) +------------------ +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Contributors: Masaya Kataoka, Michał Ciasnocha + 4.2.1 (2024-09-10) ------------------ diff --git a/openscenario/openscenario_utility/package.xml b/openscenario/openscenario_utility/package.xml index 0452c65e4bc..e8cb1ec2f27 100644 --- a/openscenario/openscenario_utility/package.xml +++ b/openscenario/openscenario_utility/package.xml @@ -2,7 +2,7 @@ openscenario_utility - 4.2.1 + 4.2.2 Utility tools for ASAM OpenSCENARIO 1.2.0 Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_validator/CHANGELOG.rst b/openscenario/openscenario_validator/CHANGELOG.rst index 4974c949cd8..c30c56dc4f7 100644 --- a/openscenario/openscenario_validator/CHANGELOG.rst +++ b/openscenario/openscenario_validator/CHANGELOG.rst @@ -10,6 +10,14 @@ Changelog for package openscenario_validator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.2 (2024-09-10) +------------------ +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Contributors: Masaya Kataoka, Michał Ciasnocha + 4.2.1 (2024-09-10) ------------------ diff --git a/openscenario/openscenario_validator/package.xml b/openscenario/openscenario_validator/package.xml index fcac94a008d..f70cd8b863f 100644 --- a/openscenario/openscenario_validator/package.xml +++ b/openscenario/openscenario_validator/package.xml @@ -2,7 +2,7 @@ openscenario_validator - 4.2.1 + 4.2.2 Validator for OpenSCENARIO 1.3 Kotaro Yoshimoto Apache License 2.0 diff --git a/rviz_plugins/openscenario_visualization/CHANGELOG.rst b/rviz_plugins/openscenario_visualization/CHANGELOG.rst index bb7e779a749..79a3ab603c2 100644 --- a/rviz_plugins/openscenario_visualization/CHANGELOG.rst +++ b/rviz_plugins/openscenario_visualization/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package openscenario_visualization * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.2 (2024-09-10) +------------------ +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Contributors: Masaya Kataoka, Michał Ciasnocha + 4.2.1 (2024-09-10) ------------------ diff --git a/rviz_plugins/openscenario_visualization/package.xml b/rviz_plugins/openscenario_visualization/package.xml index e0017d0932a..4b3ead15e69 100644 --- a/rviz_plugins/openscenario_visualization/package.xml +++ b/rviz_plugins/openscenario_visualization/package.xml @@ -2,7 +2,7 @@ openscenario_visualization - 4.2.1 + 4.2.2 Visualization tools for simulation results Masaya Kataoka Kyoichi Sugahara diff --git a/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst b/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst index 1a6ab678121..faa54eacf67 100644 --- a/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst +++ b/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package real_time_factor_control_rviz_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.2 (2024-09-10) +------------------ +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Contributors: Masaya Kataoka, Michał Ciasnocha + 4.2.1 (2024-09-10) ------------------ diff --git a/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml b/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml index 0e20f10e230..7c13c86f6fd 100644 --- a/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml +++ b/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml @@ -2,7 +2,7 @@ real_time_factor_control_rviz_plugin - 4.2.1 + 4.2.2 Slider controlling real time factor value. Paweł Lech Apache License 2.0 diff --git a/scenario_simulator_v2/CHANGELOG.rst b/scenario_simulator_v2/CHANGELOG.rst index fb4b6a60a67..24f7862fafa 100644 --- a/scenario_simulator_v2/CHANGELOG.rst +++ b/scenario_simulator_v2/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package scenario_simulator_v2 * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.2 (2024-09-10) +------------------ +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Contributors: Masaya Kataoka, Michał Ciasnocha + 4.2.1 (2024-09-10) ------------------ * Spelling changes diff --git a/scenario_simulator_v2/package.xml b/scenario_simulator_v2/package.xml index 49d9a805b00..283519dc6a6 100644 --- a/scenario_simulator_v2/package.xml +++ b/scenario_simulator_v2/package.xml @@ -2,7 +2,7 @@ scenario_simulator_v2 - 4.2.1 + 4.2.2 scenario testing framework for Autoware Masaya Kataoka Apache License 2.0 diff --git a/simulation/behavior_tree_plugin/CHANGELOG.rst b/simulation/behavior_tree_plugin/CHANGELOG.rst index 7ef537a12f5..4e250c4642c 100644 --- a/simulation/behavior_tree_plugin/CHANGELOG.rst +++ b/simulation/behavior_tree_plugin/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package behavior_tree_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.2 (2024-09-10) +------------------ +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Contributors: Masaya Kataoka, Michał Ciasnocha + 4.2.1 (2024-09-10) ------------------ diff --git a/simulation/behavior_tree_plugin/package.xml b/simulation/behavior_tree_plugin/package.xml index efc1477f574..e67b4a928e7 100644 --- a/simulation/behavior_tree_plugin/package.xml +++ b/simulation/behavior_tree_plugin/package.xml @@ -2,7 +2,7 @@ behavior_tree_plugin - 4.2.1 + 4.2.2 Behavior tree plugin for traffic_simulator masaya Apache 2.0 diff --git a/simulation/do_nothing_plugin/CHANGELOG.rst b/simulation/do_nothing_plugin/CHANGELOG.rst index cf2746a65ae..933d7bc003a 100644 --- a/simulation/do_nothing_plugin/CHANGELOG.rst +++ b/simulation/do_nothing_plugin/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package do_nothing_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.2 (2024-09-10) +------------------ +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Contributors: Masaya Kataoka, Michał Ciasnocha + 4.2.1 (2024-09-10) ------------------ diff --git a/simulation/do_nothing_plugin/package.xml b/simulation/do_nothing_plugin/package.xml index af96fccbee9..32673e7fe19 100644 --- a/simulation/do_nothing_plugin/package.xml +++ b/simulation/do_nothing_plugin/package.xml @@ -2,7 +2,7 @@ do_nothing_plugin - 4.2.1 + 4.2.2 Behavior plugin for do nothing Masaya Kataoka Apache 2.0 diff --git a/simulation/simple_sensor_simulator/CHANGELOG.rst b/simulation/simple_sensor_simulator/CHANGELOG.rst index 46f0089d1ce..507f914cbf5 100644 --- a/simulation/simple_sensor_simulator/CHANGELOG.rst +++ b/simulation/simple_sensor_simulator/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package simple_sensor_simulator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.2 (2024-09-10) +------------------ +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Contributors: Masaya Kataoka, Michał Ciasnocha + 4.2.1 (2024-09-10) ------------------ diff --git a/simulation/simple_sensor_simulator/package.xml b/simulation/simple_sensor_simulator/package.xml index d343fdf9bca..ed4fdbe2a13 100644 --- a/simulation/simple_sensor_simulator/package.xml +++ b/simulation/simple_sensor_simulator/package.xml @@ -1,7 +1,7 @@ simple_sensor_simulator - 4.2.1 + 4.2.2 simple_sensor_simulator package masaya kataoka diff --git a/simulation/simulation_interface/CHANGELOG.rst b/simulation/simulation_interface/CHANGELOG.rst index edd30f08fc8..b1f379c1363 100644 --- a/simulation/simulation_interface/CHANGELOG.rst +++ b/simulation/simulation_interface/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package simulation_interface * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.2 (2024-09-10) +------------------ +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Contributors: Masaya Kataoka, Michał Ciasnocha + 4.2.1 (2024-09-10) ------------------ diff --git a/simulation/simulation_interface/package.xml b/simulation/simulation_interface/package.xml index 400517c47f5..0ef989cf9e4 100644 --- a/simulation/simulation_interface/package.xml +++ b/simulation/simulation_interface/package.xml @@ -2,7 +2,7 @@ simulation_interface - 4.2.1 + 4.2.2 packages to define interface between simulator and scenario interpreter Masaya Kataoka Apache License 2.0 diff --git a/simulation/traffic_simulator/CHANGELOG.rst b/simulation/traffic_simulator/CHANGELOG.rst index 21f22614cfc..4dff0674c5a 100644 --- a/simulation/traffic_simulator/CHANGELOG.rst +++ b/simulation/traffic_simulator/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package traffic_simulator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.2 (2024-09-10) +------------------ +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Contributors: Masaya Kataoka, Michał Ciasnocha + 4.2.1 (2024-09-10) ------------------ * Merge pull request `#1367 `_ from tier4/RJD-1197/canonicalized_lanelet_pose diff --git a/simulation/traffic_simulator/package.xml b/simulation/traffic_simulator/package.xml index 5dd00456acb..8d8b2179152 100644 --- a/simulation/traffic_simulator/package.xml +++ b/simulation/traffic_simulator/package.xml @@ -1,7 +1,7 @@ traffic_simulator - 4.2.1 + 4.2.2 control traffic flow masaya kataoka diff --git a/simulation/traffic_simulator_msgs/CHANGELOG.rst b/simulation/traffic_simulator_msgs/CHANGELOG.rst index 803f9924925..8110567b39d 100644 --- a/simulation/traffic_simulator_msgs/CHANGELOG.rst +++ b/simulation/traffic_simulator_msgs/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package openscenario_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.2 (2024-09-10) +------------------ +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Contributors: Masaya Kataoka, Michał Ciasnocha + 4.2.1 (2024-09-10) ------------------ diff --git a/simulation/traffic_simulator_msgs/package.xml b/simulation/traffic_simulator_msgs/package.xml index ae8c2b46276..7e5ea839962 100644 --- a/simulation/traffic_simulator_msgs/package.xml +++ b/simulation/traffic_simulator_msgs/package.xml @@ -2,7 +2,7 @@ traffic_simulator_msgs - 4.2.1 + 4.2.2 ROS messages for openscenario Masaya Kataoka Apache License 2.0 diff --git a/test_runner/random_test_runner/CHANGELOG.rst b/test_runner/random_test_runner/CHANGELOG.rst index b37aebab5e6..a2314170a07 100644 --- a/test_runner/random_test_runner/CHANGELOG.rst +++ b/test_runner/random_test_runner/CHANGELOG.rst @@ -21,6 +21,14 @@ Changelog for package random_test_runner * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.2 (2024-09-10) +------------------ +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Contributors: Masaya Kataoka, Michał Ciasnocha + 4.2.1 (2024-09-10) ------------------ diff --git a/test_runner/random_test_runner/package.xml b/test_runner/random_test_runner/package.xml index 8366b28e337..da86fefa1a6 100644 --- a/test_runner/random_test_runner/package.xml +++ b/test_runner/random_test_runner/package.xml @@ -2,7 +2,7 @@ random_test_runner - 4.2.1 + 4.2.2 Random behavior test runner piotr-zyskowski-rai Apache License 2.0 diff --git a/test_runner/scenario_test_runner/CHANGELOG.rst b/test_runner/scenario_test_runner/CHANGELOG.rst index 056c894558c..34bfae961dc 100644 --- a/test_runner/scenario_test_runner/CHANGELOG.rst +++ b/test_runner/scenario_test_runner/CHANGELOG.rst @@ -35,6 +35,14 @@ Changelog for package scenario_test_runner * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.2 (2024-09-10) +------------------ +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Merge branch 'master' into RJD-1278/geometry-update +* Contributors: Masaya Kataoka, Michał Ciasnocha + 4.2.1 (2024-09-10) ------------------ diff --git a/test_runner/scenario_test_runner/package.xml b/test_runner/scenario_test_runner/package.xml index f62735450fa..991162b345d 100644 --- a/test_runner/scenario_test_runner/package.xml +++ b/test_runner/scenario_test_runner/package.xml @@ -2,7 +2,7 @@ scenario_test_runner - 4.2.1 + 4.2.2 scenario test runner package Tatsuya Yamasaki Apache License 2.0 From e34573261b6cfea7a385383506685f85fca3560f Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Tue, 10 Sep 2024 14:34:32 +0900 Subject: [PATCH 243/304] Add new test scenario `RoutingAction.AcquirePositionAction-continuous` Signed-off-by: yamacir-kit --- ...tion.AcquirePositionAction-continuous.yaml | 188 ++++++++++++++++++ 1 file changed, 188 insertions(+) create mode 100644 test_runner/scenario_test_runner/scenario/RoutingAction.AcquirePositionAction-continuous.yaml diff --git a/test_runner/scenario_test_runner/scenario/RoutingAction.AcquirePositionAction-continuous.yaml b/test_runner/scenario_test_runner/scenario/RoutingAction.AcquirePositionAction-continuous.yaml new file mode 100644 index 00000000000..76d8f4388b3 --- /dev/null +++ b/test_runner/scenario_test_runner/scenario/RoutingAction.AcquirePositionAction-continuous.yaml @@ -0,0 +1,188 @@ +OpenSCENARIO: + FileHeader: + author: 'Tatsuya Yamasaki' + date: '1970-01-01T09:00:00+09:00' + description: '' + revMajor: 1 + revMinor: 0 + ParameterDeclarations: + ParameterDeclaration: [] + CatalogLocations: + VehicleCatalog: + Directory: + path: $(ros2 pkg prefix --share openscenario_experimental_catalog)/vehicle + RoadNetwork: + LogicFile: + filepath: $(ros2 pkg prefix --share kashiwanoha_map)/map + Entities: + ScenarioObject: + - name: ego + CatalogReference: + catalogName: sample_vehicle + entryName: sample_vehicle + ObjectController: + Controller: + name: 'Autoware' + Properties: + Property: [] + Storyboard: + Init: + Actions: + Private: + - entityRef: ego + PrivateAction: + - TeleportAction: + Position: + LanePosition: + roadId: '' + laneId: '34513' + s: 1 + offset: 0 + Orientation: &DEFAULT_ORIENTATION + type: relative + h: 0 + p: 0 + r: 0 + - RoutingAction: + AcquirePositionAction: + Position: &DESTINATION_1 + LanePosition: + roadId: '' + laneId: '34510' + s: 1 + offset: 0 + Orientation: *DEFAULT_ORIENTATION + Story: + - name: '' + Act: + - name: '' + ManeuverGroup: + - maximumExecutionCount: 1 + name: '' + Actors: + selectTriggeringEntities: false + EntityRef: + - entityRef: ego + Maneuver: + - name: '' + Event: + - name: '' + priority: parallel + Action: + - name: '' + PrivateAction: + - RoutingAction: + AcquirePositionAction: + Position: &DESTINATION_2 + LanePosition: + roadId: '' + laneId: '34507' + s: 50 + offset: 0 + Orientation: *DEFAULT_ORIENTATION + StartTrigger: + ConditionGroup: + - Condition: + - name: '' + delay: 0 + conditionEdge: none + ByEntityCondition: + TriggeringEntities: + triggeringEntitiesRule: any + EntityRef: + - entityRef: ego + EntityCondition: + SpeedCondition: + rule: equalTo + value: 0 + - name: '' + delay: 0 + conditionEdge: none + ByValueCondition: + UserDefinedValueCondition: + name: ego.currentState + rule: equalTo + value: WAITING_FOR_ROUTE + StartTrigger: + ConditionGroup: + - Condition: + - name: '' + delay: 0 + conditionEdge: none + ByEntityCondition: + TriggeringEntities: + triggeringEntitiesRule: any + EntityRef: + - entityRef: ego + EntityCondition: + ReachPositionCondition: + Position: *DESTINATION_1 + tolerance: 1 + - name: _EndCondition + ManeuverGroup: + - maximumExecutionCount: 1 + name: '' + Actors: + selectTriggeringEntities: false + EntityRef: + - entityRef: ego + Maneuver: + - name: '' + Event: + - name: '' + priority: parallel + StartTrigger: + ConditionGroup: + - Condition: + - name: '' + delay: 0 + conditionEdge: none + ByEntityCondition: + TriggeringEntities: + triggeringEntitiesRule: any + EntityRef: + - entityRef: ego + EntityCondition: + ReachPositionCondition: + Position: + LanePosition: + roadId: '' + laneId: '34507' + s: 50 + offset: 0 + Orientation: *DEFAULT_ORIENTATION + tolerance: 0.5 + Action: + - name: '' + UserDefinedAction: + CustomCommandAction: + type: exitSuccess + - name: '' + priority: parallel + StartTrigger: + ConditionGroup: + - Condition: + - name: '' + delay: 0 + conditionEdge: none + ByValueCondition: + SimulationTimeCondition: + value: 180 + rule: greaterThan + Action: + - name: '' + UserDefinedAction: + CustomCommandAction: + type: exitFailure + StartTrigger: + ConditionGroup: + - Condition: + - name: '' + delay: 0 + conditionEdge: none + ByValueCondition: + SimulationTimeCondition: + value: 0 + rule: greaterThan + StopTrigger: + ConditionGroup: [] From c61459c480b8de2b182c2b3d3853625a814ff766 Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Tue, 10 Sep 2024 15:09:10 +0900 Subject: [PATCH 244/304] Update `AcquirePositionAction` to request route clearing before applying Signed-off-by: yamacir-kit --- .../include/openscenario_interpreter/simulator_core.hpp | 5 +++-- .../include/traffic_simulator/entity/entity_base.hpp | 4 ++-- simulation/traffic_simulator/src/entity/entity_base.cpp | 7 ------- 3 files changed, 5 insertions(+), 11 deletions(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/simulator_core.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/simulator_core.hpp index fc3a3f9edb6..4caf8c82bfb 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/simulator_core.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/simulator_core.hpp @@ -284,9 +284,10 @@ class SimulatorCore { protected: template - static auto applyAcquirePositionAction(Ts &&... xs) + static auto applyAcquirePositionAction(const std::string & entity_ref, Ts &&... xs) { - return core->requestAcquirePosition(std::forward(xs)...); + core->requestClearRoute(entity_ref); + return core->requestAcquirePosition(entity_ref, std::forward(xs)...); } template diff --git a/simulation/traffic_simulator/include/traffic_simulator/entity/entity_base.hpp b/simulation/traffic_simulator/include/traffic_simulator/entity/entity_base.hpp index c29eddf5722..6516f9665c4 100644 --- a/simulation/traffic_simulator/include/traffic_simulator/entity/entity_base.hpp +++ b/simulation/traffic_simulator/include/traffic_simulator/entity/entity_base.hpp @@ -141,7 +141,7 @@ class EntityBase virtual void requestAssignRoute(const std::vector &) = 0; - virtual void requestLaneChange(const lanelet::Id){}; + virtual void requestLaneChange(const lanelet::Id) {} virtual void requestLaneChange(const traffic_simulator::lane_change::Parameter &){}; @@ -164,7 +164,7 @@ class EntityBase virtual void requestSpeedChange(const speed_change::RelativeTargetSpeed &, bool); - virtual void requestClearRoute(); + virtual void requestClearRoute() {} virtual auto isControlledBySimulator() const -> bool; diff --git a/simulation/traffic_simulator/src/entity/entity_base.cpp b/simulation/traffic_simulator/src/entity/entity_base.cpp index ff4b43a4b0f..a25d8fb9b7f 100644 --- a/simulation/traffic_simulator/src/entity/entity_base.cpp +++ b/simulation/traffic_simulator/src/entity/entity_base.cpp @@ -218,13 +218,6 @@ void EntityBase::requestSpeedChangeWithConstantAcceleration( } } -void EntityBase::requestClearRoute() -{ - THROW_SEMANTIC_ERROR( - "requestClearRoute is only supported for EgoEntity. The specified Entity is not an EgoEntity. " - "Please check the scenario carefully."); -} - void EntityBase::requestSpeedChangeWithTimeConstraint( const double target_speed, const speed_change::Transition transition, double acceleration_time) { From 3045ccdd19320588ef28118c1c08b515785ef9f6 Mon Sep 17 00:00:00 2001 From: satoshi-ota Date: Tue, 10 Sep 2024 15:35:19 +0900 Subject: [PATCH 245/304] fix: missing param Signed-off-by: satoshi-ota --- mock/cpp_mock_scenarios/launch/mock_test.launch.py | 1 + 1 file changed, 1 insertion(+) diff --git a/mock/cpp_mock_scenarios/launch/mock_test.launch.py b/mock/cpp_mock_scenarios/launch/mock_test.launch.py index ee9f40194ef..9086c0910e6 100644 --- a/mock/cpp_mock_scenarios/launch/mock_test.launch.py +++ b/mock/cpp_mock_scenarios/launch/mock_test.launch.py @@ -166,6 +166,7 @@ def make_parameters(): {"global_real_time_factor": global_real_time_factor}, {"global_frame_rate": global_frame_rate}, {"global_timeout": global_timeout}, + {"junit_path": junit_path}, ] parameters += make_vehicle_parameters() return parameters From 4b79839b430b228108e50af5ef67748c59bf3797 Mon Sep 17 00:00:00 2001 From: satoshi-ota Date: Tue, 10 Sep 2024 15:55:29 +0900 Subject: [PATCH 246/304] fix: set default rviz config Signed-off-by: satoshi-ota --- mock/cpp_mock_scenarios/launch/mock_test.launch.py | 12 ++++-------- 1 file changed, 4 insertions(+), 8 deletions(-) diff --git a/mock/cpp_mock_scenarios/launch/mock_test.launch.py b/mock/cpp_mock_scenarios/launch/mock_test.launch.py index 9086c0910e6..7d298ed0721 100644 --- a/mock/cpp_mock_scenarios/launch/mock_test.launch.py +++ b/mock/cpp_mock_scenarios/launch/mock_test.launch.py @@ -94,6 +94,8 @@ def default_autoware_launch_file_of(architecture_type): "awf/universe/20230906": "planning_simulator.launch.xml", }[architecture_type] +def default_rviz_config_file(): + return Path(get_package_share_directory("traffic_simulator")) / "config/scenario_simulator_v2.rviz" def launch_setup(context, *args, **kwargs): # fmt: off @@ -113,7 +115,7 @@ def launch_setup(context, *args, **kwargs): port = LaunchConfiguration("port", default=5555) publish_empty_context = LaunchConfiguration("publish_empty_context", default=False) record = LaunchConfiguration("record", default=False) - rviz_config = LaunchConfiguration("rviz_config", default="") + rviz_config = LaunchConfiguration("rviz_config", default=default_rviz_config_file()) scenario = LaunchConfiguration("scenario", default=Path("/dev/null")) sensor_model = LaunchConfiguration("sensor_model", default="") sigterm_timeout = LaunchConfiguration("sigterm_timeout", default=8) @@ -246,13 +248,7 @@ def description(): name="rviz2", output={"stderr": "log", "stdout": "log"}, condition=IfCondition(launch_rviz), - arguments=[ - "-d", - str( - Path(get_package_share_directory("traffic_simulator")) - / "config/scenario_simulator_v2.rviz" - ), - ], + arguments=["-d", str(default_rviz_config_file())], ), RegisterEventHandler(event_handler=io_handler), RegisterEventHandler(event_handler=shutdown_handler), From ae824022e4fd0e1136b085f13f403326d0f04c19 Mon Sep 17 00:00:00 2001 From: Grzegorz Maj Date: Tue, 10 Sep 2024 09:33:46 +0200 Subject: [PATCH 247/304] CR requested changes part 2 --- .../test/src/utils/test_pose.cpp | 19 ++++++++++--------- 1 file changed, 10 insertions(+), 9 deletions(-) diff --git a/simulation/traffic_simulator/test/src/utils/test_pose.cpp b/simulation/traffic_simulator/test/src/utils/test_pose.cpp index 5834df083b6..fcbe0acf606 100644 --- a/simulation/traffic_simulator/test/src/utils/test_pose.cpp +++ b/simulation/traffic_simulator/test/src/utils/test_pose.cpp @@ -163,7 +163,7 @@ TEST_F(PoseTest, toCanonicalizedLaneletPose_noBoundingBox_noRoute_valid) */ TEST_F(PoseTest, toCanonicalizedLaneletPose_noBoundingBox_noRoute_invalid) { - const geometry_msgs::msg::Pose pose = makePose(makePoint(0, 0, 0)); + const geometry_msgs::msg::Pose pose = makePose(makePoint(0.0, 0.0, 0.0)); EXPECT_EQ( traffic_simulator::pose::toCanonicalizedLaneletPose(pose, true, hdmap_utils), std::nullopt); @@ -210,7 +210,7 @@ TEST_F(PoseTest, toCanonicalizedLaneletPose_BoundingBox_noRoute_invalid) */ TEST_F(PoseTest, toCanonicalizedLaneletPose_BoundingBox_route_emptyInvalid) { - const geometry_msgs::msg::Pose pose = makePose(makePoint(0, 0, 0)); + const geometry_msgs::msg::Pose pose = makePose(makePoint(0.0, 0.0, 0.0)); EXPECT_EQ( traffic_simulator::pose::toCanonicalizedLaneletPose( @@ -229,7 +229,7 @@ TEST_F(PoseTest, toCanonicalizedLaneletPose_BoundingBox_route_emptyValid) const geometry_msgs::msg::Pose pose = static_cast(lanelet_pose); const auto canonicalized_pose = traffic_simulator::pose::toCanonicalizedLaneletPose( - pose, makeBoundingBox(), {}, true, 1.0, hdmap_utils); + pose, makeBoundingBox(), lanelet::Ids{}, true, 1.0, hdmap_utils); ASSERT_TRUE(canonicalized_pose.has_value()); EXPECT_POSE_NEAR(pose, static_cast(canonicalized_pose.value()), 0.01); @@ -243,7 +243,7 @@ TEST_F(PoseTest, toCanonicalizedLaneletPose_BoundingBox_route_emptyValid) */ TEST_F(PoseTest, toCanonicalizedLaneletPose_BoundingBox_route_nonEmptyInvalid) { - const geometry_msgs::msg::Pose pose = makePose(makePoint(0, 0, 0)); + const geometry_msgs::msg::Pose pose = makePose(makePoint(0.0, 0.0, 0.0)); EXPECT_EQ( traffic_simulator::pose::toCanonicalizedLaneletPose( @@ -262,7 +262,7 @@ TEST_F(PoseTest, toCanonicalizedLaneletPose_BoundingBox_route_nonEmptyValid) const geometry_msgs::msg::Pose pose = static_cast(lanelet_pose); const auto canonicalized_pose = traffic_simulator::pose::toCanonicalizedLaneletPose( - pose, makeBoundingBox(), {195}, true, 1.0, hdmap_utils); + pose, makeBoundingBox(), lanelet::Ids{195}, true, 1.0, hdmap_utils); ASSERT_TRUE(canonicalized_pose.has_value()); EXPECT_POSE_NEAR(pose, static_cast(canonicalized_pose.value()), 0.01); @@ -549,7 +549,8 @@ TEST_F(PoseTest, isInLanelet_inside) const auto pose = traffic_simulator::helper::constructCanonicalizedLaneletPose(195, 0.0, 0.0, hdmap_utils); - EXPECT_TRUE(traffic_simulator::pose::isInLanelet(pose, 195, 0, hdmap_utils)); + EXPECT_TRUE(traffic_simulator::pose::isInLanelet( + pose, 195, std::numeric_limits::epsilon(), hdmap_utils)); } /** @@ -560,7 +561,7 @@ TEST_F(PoseTest, isInLanelet_outsideFrontFar) const auto pose = traffic_simulator::helper::constructCanonicalizedLaneletPose(3002163, -10.0, 0.0, hdmap_utils); - EXPECT_FALSE(traffic_simulator::pose::isInLanelet(pose, 3002163, 1, hdmap_utils)); + EXPECT_FALSE(traffic_simulator::pose::isInLanelet(pose, 3002163, 1.0, hdmap_utils)); } /** @@ -571,7 +572,7 @@ TEST_F(PoseTest, isInLanelet_outsideFrontClose) const auto pose = traffic_simulator::helper::constructCanonicalizedLaneletPose(3002163, -1.0, 0.0, hdmap_utils); - EXPECT_TRUE(traffic_simulator::pose::isInLanelet(pose, 3002163, 2, hdmap_utils)); + EXPECT_TRUE(traffic_simulator::pose::isInLanelet(pose, 3002163, 2.0, hdmap_utils)); } /** @@ -593,7 +594,7 @@ TEST_F(PoseTest, isInLanelet_outsideBackClose) const auto pose = traffic_simulator::helper::constructCanonicalizedLaneletPose(195, 110.0, 0.0, hdmap_utils); - EXPECT_TRUE(traffic_simulator::pose::isInLanelet(pose, 195, 10, hdmap_utils)); + EXPECT_TRUE(traffic_simulator::pose::isInLanelet(pose, 195, 10.0, hdmap_utils)); } /** From 8c90aa41c63fdbaf7a1982e33697a9f768165800 Mon Sep 17 00:00:00 2001 From: satoshi-ota Date: Tue, 10 Sep 2024 17:59:05 +0900 Subject: [PATCH 248/304] fix: global frame rate 30.0 -> 20.0 Signed-off-by: satoshi-ota --- mock/cpp_mock_scenarios/launch/mock_test.launch.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/mock/cpp_mock_scenarios/launch/mock_test.launch.py b/mock/cpp_mock_scenarios/launch/mock_test.launch.py index 7d298ed0721..0289e874095 100644 --- a/mock/cpp_mock_scenarios/launch/mock_test.launch.py +++ b/mock/cpp_mock_scenarios/launch/mock_test.launch.py @@ -104,7 +104,7 @@ def launch_setup(context, *args, **kwargs): autoware_launch_package = LaunchConfiguration("autoware_launch_package", default=default_autoware_launch_package_of(architecture_type.perform(context))) consider_acceleration_by_road_slope = LaunchConfiguration("consider_acceleration_by_road_slope", default=False) consider_pose_by_road_slope = LaunchConfiguration("consider_pose_by_road_slope", default=True) - global_frame_rate = LaunchConfiguration("global_frame_rate", default=30.0) + global_frame_rate = LaunchConfiguration("global_frame_rate", default=20.0) global_real_time_factor = LaunchConfiguration("global_real_time_factor", default=1.0) global_timeout = LaunchConfiguration("global_timeout", default=180) initialize_duration = LaunchConfiguration("initialize_duration", default=300) From a6a038358ae1f1a7a6d41adec7fbf723de29c56f Mon Sep 17 00:00:00 2001 From: Release Bot Date: Wed, 11 Sep 2024 02:50:24 +0000 Subject: [PATCH 249/304] Bump version of scenario_simulator_v2 from version 4.2.2 to version 4.2.3 --- common/math/arithmetic/CHANGELOG.rst | 3 +++ common/math/arithmetic/package.xml | 2 +- common/math/geometry/CHANGELOG.rst | 3 +++ common/math/geometry/package.xml | 2 +- common/scenario_simulator_exception/CHANGELOG.rst | 3 +++ common/scenario_simulator_exception/package.xml | 2 +- common/simple_junit/CHANGELOG.rst | 3 +++ common/simple_junit/package.xml | 2 +- common/status_monitor/CHANGELOG.rst | 3 +++ common/status_monitor/package.xml | 2 +- external/concealer/CHANGELOG.rst | 3 +++ external/concealer/package.xml | 2 +- external/embree_vendor/CHANGELOG.rst | 3 +++ external/embree_vendor/package.xml | 2 +- map/kashiwanoha_map/CHANGELOG.rst | 3 +++ map/kashiwanoha_map/package.xml | 2 +- map/simple_cross_map/CHANGELOG.rst | 3 +++ map/simple_cross_map/package.xml | 2 +- mock/cpp_mock_scenarios/CHANGELOG.rst | 12 ++++++++++++ mock/cpp_mock_scenarios/package.xml | 2 +- .../openscenario_experimental_catalog/CHANGELOG.rst | 3 +++ .../openscenario_experimental_catalog/package.xml | 2 +- openscenario/openscenario_interpreter/CHANGELOG.rst | 3 +++ openscenario/openscenario_interpreter/package.xml | 2 +- .../openscenario_interpreter_example/CHANGELOG.rst | 3 +++ .../openscenario_interpreter_example/package.xml | 2 +- .../openscenario_interpreter_msgs/CHANGELOG.rst | 3 +++ .../openscenario_interpreter_msgs/package.xml | 2 +- openscenario/openscenario_preprocessor/CHANGELOG.rst | 3 +++ openscenario/openscenario_preprocessor/package.xml | 2 +- .../openscenario_preprocessor_msgs/CHANGELOG.rst | 3 +++ .../openscenario_preprocessor_msgs/package.xml | 2 +- openscenario/openscenario_utility/CHANGELOG.rst | 3 +++ openscenario/openscenario_utility/package.xml | 2 +- openscenario/openscenario_validator/CHANGELOG.rst | 3 +++ openscenario/openscenario_validator/package.xml | 2 +- .../openscenario_visualization/CHANGELOG.rst | 3 +++ rviz_plugins/openscenario_visualization/package.xml | 2 +- .../CHANGELOG.rst | 3 +++ .../real_time_factor_control_rviz_plugin/package.xml | 2 +- scenario_simulator_v2/CHANGELOG.rst | 3 +++ scenario_simulator_v2/package.xml | 2 +- simulation/behavior_tree_plugin/CHANGELOG.rst | 3 +++ simulation/behavior_tree_plugin/package.xml | 2 +- simulation/do_nothing_plugin/CHANGELOG.rst | 3 +++ simulation/do_nothing_plugin/package.xml | 2 +- simulation/simple_sensor_simulator/CHANGELOG.rst | 3 +++ simulation/simple_sensor_simulator/package.xml | 2 +- simulation/simulation_interface/CHANGELOG.rst | 3 +++ simulation/simulation_interface/package.xml | 2 +- simulation/traffic_simulator/CHANGELOG.rst | 3 +++ simulation/traffic_simulator/package.xml | 2 +- simulation/traffic_simulator_msgs/CHANGELOG.rst | 3 +++ simulation/traffic_simulator_msgs/package.xml | 2 +- test_runner/random_test_runner/CHANGELOG.rst | 3 +++ test_runner/random_test_runner/package.xml | 2 +- test_runner/scenario_test_runner/CHANGELOG.rst | 3 +++ test_runner/scenario_test_runner/package.xml | 2 +- 58 files changed, 125 insertions(+), 29 deletions(-) diff --git a/common/math/arithmetic/CHANGELOG.rst b/common/math/arithmetic/CHANGELOG.rst index 7c95d4238bb..fd79e4bad12 100644 --- a/common/math/arithmetic/CHANGELOG.rst +++ b/common/math/arithmetic/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package arithmetic * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.3 (2024-09-11) +------------------ + 4.2.2 (2024-09-10) ------------------ * Merge branch 'master' into RJD-1278/geometry-update diff --git a/common/math/arithmetic/package.xml b/common/math/arithmetic/package.xml index 225fcd9dfe5..f67cfd3e6d5 100644 --- a/common/math/arithmetic/package.xml +++ b/common/math/arithmetic/package.xml @@ -2,7 +2,7 @@ arithmetic - 4.2.2 + 4.2.3 arithmetic library for scenario_simulator_v2 Tatsuya Yamasaki Apache License 2.0 diff --git a/common/math/geometry/CHANGELOG.rst b/common/math/geometry/CHANGELOG.rst index ed87df592b4..c8a162b4fcb 100644 --- a/common/math/geometry/CHANGELOG.rst +++ b/common/math/geometry/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package geometry * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.3 (2024-09-11) +------------------ + 4.2.2 (2024-09-10) ------------------ * Merge pull request `#1341 `_ from tier4/RJD-1278/geometry-update diff --git a/common/math/geometry/package.xml b/common/math/geometry/package.xml index 2d29d6f85f1..e87d2b65d4f 100644 --- a/common/math/geometry/package.xml +++ b/common/math/geometry/package.xml @@ -2,7 +2,7 @@ geometry - 4.2.2 + 4.2.3 geometry math library for scenario_simulator_v2 application Masaya Kataoka Apache License 2.0 diff --git a/common/scenario_simulator_exception/CHANGELOG.rst b/common/scenario_simulator_exception/CHANGELOG.rst index 554de126098..51b5f065bad 100644 --- a/common/scenario_simulator_exception/CHANGELOG.rst +++ b/common/scenario_simulator_exception/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package scenario_simulator_exception * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.3 (2024-09-11) +------------------ + 4.2.2 (2024-09-10) ------------------ * Merge branch 'master' into RJD-1278/geometry-update diff --git a/common/scenario_simulator_exception/package.xml b/common/scenario_simulator_exception/package.xml index ef3fd96b1eb..17bb3cd129b 100644 --- a/common/scenario_simulator_exception/package.xml +++ b/common/scenario_simulator_exception/package.xml @@ -2,7 +2,7 @@ scenario_simulator_exception - 4.2.2 + 4.2.3 Exception types for scenario simulator Tatsuya Yamasaki Apache License 2.0 diff --git a/common/simple_junit/CHANGELOG.rst b/common/simple_junit/CHANGELOG.rst index 3ae5e0e607e..df19ee8bf21 100644 --- a/common/simple_junit/CHANGELOG.rst +++ b/common/simple_junit/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package junit_exporter * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.3 (2024-09-11) +------------------ + 4.2.2 (2024-09-10) ------------------ * Merge branch 'master' into RJD-1278/geometry-update diff --git a/common/simple_junit/package.xml b/common/simple_junit/package.xml index 52b345ecc29..8b646b6b552 100644 --- a/common/simple_junit/package.xml +++ b/common/simple_junit/package.xml @@ -2,7 +2,7 @@ simple_junit - 4.2.2 + 4.2.3 Lightweight JUnit library for ROS 2 Masaya Kataoka Tatsuya Yamasaki diff --git a/common/status_monitor/CHANGELOG.rst b/common/status_monitor/CHANGELOG.rst index 977da120e29..3a0ed07dcfa 100644 --- a/common/status_monitor/CHANGELOG.rst +++ b/common/status_monitor/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package status_monitor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.3 (2024-09-11) +------------------ + 4.2.2 (2024-09-10) ------------------ * Merge branch 'master' into RJD-1278/geometry-update diff --git a/common/status_monitor/package.xml b/common/status_monitor/package.xml index 6e9f7ddfe55..239ad4b7930 100644 --- a/common/status_monitor/package.xml +++ b/common/status_monitor/package.xml @@ -2,7 +2,7 @@ status_monitor - 4.2.2 + 4.2.3 none Tatsuya Yamasaki Apache License 2.0 diff --git a/external/concealer/CHANGELOG.rst b/external/concealer/CHANGELOG.rst index 182b8a56937..9f5aaf3c341 100644 --- a/external/concealer/CHANGELOG.rst +++ b/external/concealer/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package concealer * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.3 (2024-09-11) +------------------ + 4.2.2 (2024-09-10) ------------------ * Merge branch 'master' into RJD-1278/geometry-update diff --git a/external/concealer/package.xml b/external/concealer/package.xml index ff2fb906b99..ea864a1988d 100644 --- a/external/concealer/package.xml +++ b/external/concealer/package.xml @@ -2,7 +2,7 @@ concealer - 4.2.2 + 4.2.3 Provides a class 'Autoware' to conceal miscellaneous things to simplify Autoware management of the simulator. Tatsuya Yamasaki Apache License 2.0 diff --git a/external/embree_vendor/CHANGELOG.rst b/external/embree_vendor/CHANGELOG.rst index fac779b36c5..78065ef7226 100644 --- a/external/embree_vendor/CHANGELOG.rst +++ b/external/embree_vendor/CHANGELOG.rst @@ -24,6 +24,9 @@ Changelog for package embree_vendor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.3 (2024-09-11) +------------------ + 4.2.2 (2024-09-10) ------------------ * Merge branch 'master' into RJD-1278/geometry-update diff --git a/external/embree_vendor/package.xml b/external/embree_vendor/package.xml index 009829846a5..e2d2cbcac44 100644 --- a/external/embree_vendor/package.xml +++ b/external/embree_vendor/package.xml @@ -2,7 +2,7 @@ embree_vendor - 4.2.2 + 4.2.3 vendor packages for intel raytracing kernel library masaya Apache 2.0 diff --git a/map/kashiwanoha_map/CHANGELOG.rst b/map/kashiwanoha_map/CHANGELOG.rst index ba56daf1487..cfed45d19b2 100644 --- a/map/kashiwanoha_map/CHANGELOG.rst +++ b/map/kashiwanoha_map/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package kashiwanoha_map * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.3 (2024-09-11) +------------------ + 4.2.2 (2024-09-10) ------------------ * Merge branch 'master' into RJD-1278/geometry-update diff --git a/map/kashiwanoha_map/package.xml b/map/kashiwanoha_map/package.xml index 69327d2912f..8442aa21541 100644 --- a/map/kashiwanoha_map/package.xml +++ b/map/kashiwanoha_map/package.xml @@ -2,7 +2,7 @@ kashiwanoha_map - 4.2.2 + 4.2.3 map package for kashiwanoha Masaya Kataoka Apache License 2.0 diff --git a/map/simple_cross_map/CHANGELOG.rst b/map/simple_cross_map/CHANGELOG.rst index 34c60095023..9fe9db19393 100644 --- a/map/simple_cross_map/CHANGELOG.rst +++ b/map/simple_cross_map/CHANGELOG.rst @@ -9,6 +9,9 @@ Changelog for package simple_cross_map * Merge branch 'master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.3 (2024-09-11) +------------------ + 4.2.2 (2024-09-10) ------------------ * Merge branch 'master' into RJD-1278/geometry-update diff --git a/map/simple_cross_map/package.xml b/map/simple_cross_map/package.xml index e0702113e58..483e01bb013 100644 --- a/map/simple_cross_map/package.xml +++ b/map/simple_cross_map/package.xml @@ -2,7 +2,7 @@ simple_cross_map - 4.2.2 + 4.2.3 map package for simple cross Masaya Kataoka Apache License 2.0 diff --git a/mock/cpp_mock_scenarios/CHANGELOG.rst b/mock/cpp_mock_scenarios/CHANGELOG.rst index 5cf1013e47f..e73e52e247e 100644 --- a/mock/cpp_mock_scenarios/CHANGELOG.rst +++ b/mock/cpp_mock_scenarios/CHANGELOG.rst @@ -21,6 +21,18 @@ Changelog for package cpp_mock_scenarios * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.3 (2024-09-11) +------------------ +* Merge pull request `#1368 `_ from tier4/fix/mock-test-launch-test + fix: mock test launch +* fix: global frame rate 30.0 -> 20.0 +* fix: set default rviz config +* fix: missing param +* fix: use global timeout +* fix: make it possible to change hard-coded parameters +* fix: load necessary parameters +* Contributors: Masaya Kataoka, satoshi-ota + 4.2.2 (2024-09-10) ------------------ * Merge branch 'master' into RJD-1278/geometry-update diff --git a/mock/cpp_mock_scenarios/package.xml b/mock/cpp_mock_scenarios/package.xml index 0fea79cf6ed..60a09d10358 100644 --- a/mock/cpp_mock_scenarios/package.xml +++ b/mock/cpp_mock_scenarios/package.xml @@ -2,7 +2,7 @@ cpp_mock_scenarios - 4.2.2 + 4.2.3 C++ mock scenarios masaya Apache License 2.0 diff --git a/openscenario/openscenario_experimental_catalog/CHANGELOG.rst b/openscenario/openscenario_experimental_catalog/CHANGELOG.rst index 94d30305999..d15e81f4922 100644 --- a/openscenario/openscenario_experimental_catalog/CHANGELOG.rst +++ b/openscenario/openscenario_experimental_catalog/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package openscenario_experimental_catalog * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.3 (2024-09-11) +------------------ + 4.2.2 (2024-09-10) ------------------ * Merge branch 'master' into RJD-1278/geometry-update diff --git a/openscenario/openscenario_experimental_catalog/package.xml b/openscenario/openscenario_experimental_catalog/package.xml index 14926ad4413..aaa3342b624 100644 --- a/openscenario/openscenario_experimental_catalog/package.xml +++ b/openscenario/openscenario_experimental_catalog/package.xml @@ -2,7 +2,7 @@ openscenario_experimental_catalog - 4.2.2 + 4.2.3 TIER IV experimental catalogs for OpenSCENARIO Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter/CHANGELOG.rst b/openscenario/openscenario_interpreter/CHANGELOG.rst index 0d6f45fa1d2..4f2c1bafe04 100644 --- a/openscenario/openscenario_interpreter/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter/CHANGELOG.rst @@ -32,6 +32,9 @@ Changelog for package openscenario_interpreter * add publish_empty_context parameter * Contributors: Masaya Kataoka +4.2.3 (2024-09-11) +------------------ + 4.2.2 (2024-09-10) ------------------ * Merge branch 'master' into RJD-1278/geometry-update diff --git a/openscenario/openscenario_interpreter/package.xml b/openscenario/openscenario_interpreter/package.xml index 22f7cb5e429..8ba2e126d37 100644 --- a/openscenario/openscenario_interpreter/package.xml +++ b/openscenario/openscenario_interpreter/package.xml @@ -2,7 +2,7 @@ openscenario_interpreter - 4.2.2 + 4.2.3 OpenSCENARIO 1.2.0 interpreter package for Autoware Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter_example/CHANGELOG.rst b/openscenario/openscenario_interpreter_example/CHANGELOG.rst index bdcf97388e2..aef3a67cb19 100644 --- a/openscenario/openscenario_interpreter_example/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter_example/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package openscenario_interpreter_example * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.3 (2024-09-11) +------------------ + 4.2.2 (2024-09-10) ------------------ * Merge branch 'master' into RJD-1278/geometry-update diff --git a/openscenario/openscenario_interpreter_example/package.xml b/openscenario/openscenario_interpreter_example/package.xml index 6ada7470f7b..585e79d4b59 100644 --- a/openscenario/openscenario_interpreter_example/package.xml +++ b/openscenario/openscenario_interpreter_example/package.xml @@ -3,7 +3,7 @@ openscenario_interpreter_example - 4.2.2 + 4.2.3 Examples for some TIER IV OpenSCENARIO Interpreter's features Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst b/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst index d59b9fa3a77..605c7dce33f 100644 --- a/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package openscenario_interpreter_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.3 (2024-09-11) +------------------ + 4.2.2 (2024-09-10) ------------------ * Merge branch 'master' into RJD-1278/geometry-update diff --git a/openscenario/openscenario_interpreter_msgs/package.xml b/openscenario/openscenario_interpreter_msgs/package.xml index d3e550e165e..d50377f1bfb 100644 --- a/openscenario/openscenario_interpreter_msgs/package.xml +++ b/openscenario/openscenario_interpreter_msgs/package.xml @@ -2,7 +2,7 @@ openscenario_interpreter_msgs - 4.2.2 + 4.2.3 ROS message types for package openscenario_interpreter Yamasaki Tatsuya Apache License 2.0 diff --git a/openscenario/openscenario_preprocessor/CHANGELOG.rst b/openscenario/openscenario_preprocessor/CHANGELOG.rst index 41fb89b0237..1b5a3958a07 100644 --- a/openscenario/openscenario_preprocessor/CHANGELOG.rst +++ b/openscenario/openscenario_preprocessor/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package openscenario_preprocessor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.3 (2024-09-11) +------------------ + 4.2.2 (2024-09-10) ------------------ * Merge branch 'master' into RJD-1278/geometry-update diff --git a/openscenario/openscenario_preprocessor/package.xml b/openscenario/openscenario_preprocessor/package.xml index 068ed93f7cb..0ce282b859e 100644 --- a/openscenario/openscenario_preprocessor/package.xml +++ b/openscenario/openscenario_preprocessor/package.xml @@ -3,7 +3,7 @@ openscenario_preprocessor - 4.2.2 + 4.2.3 Example package for TIER IV OpenSCENARIO Interpreter Kotaro Yoshimoto Apache License 2.0 diff --git a/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst b/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst index 09161cd0b25..fb7b3121a42 100644 --- a/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst +++ b/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package openscenario_preprocessor_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.3 (2024-09-11) +------------------ + 4.2.2 (2024-09-10) ------------------ * Merge branch 'master' into RJD-1278/geometry-update diff --git a/openscenario/openscenario_preprocessor_msgs/package.xml b/openscenario/openscenario_preprocessor_msgs/package.xml index 47c97df09ee..368876f8785 100644 --- a/openscenario/openscenario_preprocessor_msgs/package.xml +++ b/openscenario/openscenario_preprocessor_msgs/package.xml @@ -2,7 +2,7 @@ openscenario_preprocessor_msgs - 4.2.2 + 4.2.3 ROS message types for package openscenario_preprocessor Kotaro Yoshimoto Apache License 2.0 diff --git a/openscenario/openscenario_utility/CHANGELOG.rst b/openscenario/openscenario_utility/CHANGELOG.rst index 56fddf8f088..4550913ef69 100644 --- a/openscenario/openscenario_utility/CHANGELOG.rst +++ b/openscenario/openscenario_utility/CHANGELOG.rst @@ -24,6 +24,9 @@ Changelog for package openscenario_utility * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.3 (2024-09-11) +------------------ + 4.2.2 (2024-09-10) ------------------ * Merge branch 'master' into RJD-1278/geometry-update diff --git a/openscenario/openscenario_utility/package.xml b/openscenario/openscenario_utility/package.xml index e8cb1ec2f27..bf2f24bdd1d 100644 --- a/openscenario/openscenario_utility/package.xml +++ b/openscenario/openscenario_utility/package.xml @@ -2,7 +2,7 @@ openscenario_utility - 4.2.2 + 4.2.3 Utility tools for ASAM OpenSCENARIO 1.2.0 Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_validator/CHANGELOG.rst b/openscenario/openscenario_validator/CHANGELOG.rst index c30c56dc4f7..e4f33e66c7a 100644 --- a/openscenario/openscenario_validator/CHANGELOG.rst +++ b/openscenario/openscenario_validator/CHANGELOG.rst @@ -10,6 +10,9 @@ Changelog for package openscenario_validator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.3 (2024-09-11) +------------------ + 4.2.2 (2024-09-10) ------------------ * Merge branch 'master' into RJD-1278/geometry-update diff --git a/openscenario/openscenario_validator/package.xml b/openscenario/openscenario_validator/package.xml index f70cd8b863f..bda9faae864 100644 --- a/openscenario/openscenario_validator/package.xml +++ b/openscenario/openscenario_validator/package.xml @@ -2,7 +2,7 @@ openscenario_validator - 4.2.2 + 4.2.3 Validator for OpenSCENARIO 1.3 Kotaro Yoshimoto Apache License 2.0 diff --git a/rviz_plugins/openscenario_visualization/CHANGELOG.rst b/rviz_plugins/openscenario_visualization/CHANGELOG.rst index 79a3ab603c2..bd79e6827b4 100644 --- a/rviz_plugins/openscenario_visualization/CHANGELOG.rst +++ b/rviz_plugins/openscenario_visualization/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package openscenario_visualization * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.3 (2024-09-11) +------------------ + 4.2.2 (2024-09-10) ------------------ * Merge branch 'master' into RJD-1278/geometry-update diff --git a/rviz_plugins/openscenario_visualization/package.xml b/rviz_plugins/openscenario_visualization/package.xml index 4b3ead15e69..0893c14ad64 100644 --- a/rviz_plugins/openscenario_visualization/package.xml +++ b/rviz_plugins/openscenario_visualization/package.xml @@ -2,7 +2,7 @@ openscenario_visualization - 4.2.2 + 4.2.3 Visualization tools for simulation results Masaya Kataoka Kyoichi Sugahara diff --git a/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst b/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst index faa54eacf67..ec85a4ae875 100644 --- a/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst +++ b/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package real_time_factor_control_rviz_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.3 (2024-09-11) +------------------ + 4.2.2 (2024-09-10) ------------------ * Merge branch 'master' into RJD-1278/geometry-update diff --git a/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml b/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml index 7c13c86f6fd..da4ea4182c9 100644 --- a/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml +++ b/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml @@ -2,7 +2,7 @@ real_time_factor_control_rviz_plugin - 4.2.2 + 4.2.3 Slider controlling real time factor value. Paweł Lech Apache License 2.0 diff --git a/scenario_simulator_v2/CHANGELOG.rst b/scenario_simulator_v2/CHANGELOG.rst index 24f7862fafa..738acc323fa 100644 --- a/scenario_simulator_v2/CHANGELOG.rst +++ b/scenario_simulator_v2/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package scenario_simulator_v2 * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.3 (2024-09-11) +------------------ + 4.2.2 (2024-09-10) ------------------ * Merge branch 'master' into RJD-1278/geometry-update diff --git a/scenario_simulator_v2/package.xml b/scenario_simulator_v2/package.xml index 283519dc6a6..21089550ebb 100644 --- a/scenario_simulator_v2/package.xml +++ b/scenario_simulator_v2/package.xml @@ -2,7 +2,7 @@ scenario_simulator_v2 - 4.2.2 + 4.2.3 scenario testing framework for Autoware Masaya Kataoka Apache License 2.0 diff --git a/simulation/behavior_tree_plugin/CHANGELOG.rst b/simulation/behavior_tree_plugin/CHANGELOG.rst index 4e250c4642c..c7bd18c4095 100644 --- a/simulation/behavior_tree_plugin/CHANGELOG.rst +++ b/simulation/behavior_tree_plugin/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package behavior_tree_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.3 (2024-09-11) +------------------ + 4.2.2 (2024-09-10) ------------------ * Merge branch 'master' into RJD-1278/geometry-update diff --git a/simulation/behavior_tree_plugin/package.xml b/simulation/behavior_tree_plugin/package.xml index e67b4a928e7..a38c59d4341 100644 --- a/simulation/behavior_tree_plugin/package.xml +++ b/simulation/behavior_tree_plugin/package.xml @@ -2,7 +2,7 @@ behavior_tree_plugin - 4.2.2 + 4.2.3 Behavior tree plugin for traffic_simulator masaya Apache 2.0 diff --git a/simulation/do_nothing_plugin/CHANGELOG.rst b/simulation/do_nothing_plugin/CHANGELOG.rst index 933d7bc003a..49d4418f896 100644 --- a/simulation/do_nothing_plugin/CHANGELOG.rst +++ b/simulation/do_nothing_plugin/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package do_nothing_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.3 (2024-09-11) +------------------ + 4.2.2 (2024-09-10) ------------------ * Merge branch 'master' into RJD-1278/geometry-update diff --git a/simulation/do_nothing_plugin/package.xml b/simulation/do_nothing_plugin/package.xml index 32673e7fe19..b74f1f8e8e6 100644 --- a/simulation/do_nothing_plugin/package.xml +++ b/simulation/do_nothing_plugin/package.xml @@ -2,7 +2,7 @@ do_nothing_plugin - 4.2.2 + 4.2.3 Behavior plugin for do nothing Masaya Kataoka Apache 2.0 diff --git a/simulation/simple_sensor_simulator/CHANGELOG.rst b/simulation/simple_sensor_simulator/CHANGELOG.rst index 507f914cbf5..0e7965be548 100644 --- a/simulation/simple_sensor_simulator/CHANGELOG.rst +++ b/simulation/simple_sensor_simulator/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package simple_sensor_simulator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.3 (2024-09-11) +------------------ + 4.2.2 (2024-09-10) ------------------ * Merge branch 'master' into RJD-1278/geometry-update diff --git a/simulation/simple_sensor_simulator/package.xml b/simulation/simple_sensor_simulator/package.xml index ed4fdbe2a13..fd967ae57fe 100644 --- a/simulation/simple_sensor_simulator/package.xml +++ b/simulation/simple_sensor_simulator/package.xml @@ -1,7 +1,7 @@ simple_sensor_simulator - 4.2.2 + 4.2.3 simple_sensor_simulator package masaya kataoka diff --git a/simulation/simulation_interface/CHANGELOG.rst b/simulation/simulation_interface/CHANGELOG.rst index b1f379c1363..cb6ffbab7d7 100644 --- a/simulation/simulation_interface/CHANGELOG.rst +++ b/simulation/simulation_interface/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package simulation_interface * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.3 (2024-09-11) +------------------ + 4.2.2 (2024-09-10) ------------------ * Merge branch 'master' into RJD-1278/geometry-update diff --git a/simulation/simulation_interface/package.xml b/simulation/simulation_interface/package.xml index 0ef989cf9e4..0ee98a1234d 100644 --- a/simulation/simulation_interface/package.xml +++ b/simulation/simulation_interface/package.xml @@ -2,7 +2,7 @@ simulation_interface - 4.2.2 + 4.2.3 packages to define interface between simulator and scenario interpreter Masaya Kataoka Apache License 2.0 diff --git a/simulation/traffic_simulator/CHANGELOG.rst b/simulation/traffic_simulator/CHANGELOG.rst index 4dff0674c5a..e8f9123c5bb 100644 --- a/simulation/traffic_simulator/CHANGELOG.rst +++ b/simulation/traffic_simulator/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package traffic_simulator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.3 (2024-09-11) +------------------ + 4.2.2 (2024-09-10) ------------------ * Merge branch 'master' into RJD-1278/geometry-update diff --git a/simulation/traffic_simulator/package.xml b/simulation/traffic_simulator/package.xml index 8d8b2179152..4ff8fbbf7ee 100644 --- a/simulation/traffic_simulator/package.xml +++ b/simulation/traffic_simulator/package.xml @@ -1,7 +1,7 @@ traffic_simulator - 4.2.2 + 4.2.3 control traffic flow masaya kataoka diff --git a/simulation/traffic_simulator_msgs/CHANGELOG.rst b/simulation/traffic_simulator_msgs/CHANGELOG.rst index 8110567b39d..0f8103e7f51 100644 --- a/simulation/traffic_simulator_msgs/CHANGELOG.rst +++ b/simulation/traffic_simulator_msgs/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package openscenario_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.3 (2024-09-11) +------------------ + 4.2.2 (2024-09-10) ------------------ * Merge branch 'master' into RJD-1278/geometry-update diff --git a/simulation/traffic_simulator_msgs/package.xml b/simulation/traffic_simulator_msgs/package.xml index 7e5ea839962..2ad55e91c58 100644 --- a/simulation/traffic_simulator_msgs/package.xml +++ b/simulation/traffic_simulator_msgs/package.xml @@ -2,7 +2,7 @@ traffic_simulator_msgs - 4.2.2 + 4.2.3 ROS messages for openscenario Masaya Kataoka Apache License 2.0 diff --git a/test_runner/random_test_runner/CHANGELOG.rst b/test_runner/random_test_runner/CHANGELOG.rst index a2314170a07..dc87c1eb409 100644 --- a/test_runner/random_test_runner/CHANGELOG.rst +++ b/test_runner/random_test_runner/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package random_test_runner * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.3 (2024-09-11) +------------------ + 4.2.2 (2024-09-10) ------------------ * Merge branch 'master' into RJD-1278/geometry-update diff --git a/test_runner/random_test_runner/package.xml b/test_runner/random_test_runner/package.xml index da86fefa1a6..b6ad5fea61d 100644 --- a/test_runner/random_test_runner/package.xml +++ b/test_runner/random_test_runner/package.xml @@ -2,7 +2,7 @@ random_test_runner - 4.2.2 + 4.2.3 Random behavior test runner piotr-zyskowski-rai Apache License 2.0 diff --git a/test_runner/scenario_test_runner/CHANGELOG.rst b/test_runner/scenario_test_runner/CHANGELOG.rst index 34bfae961dc..f016ec22577 100644 --- a/test_runner/scenario_test_runner/CHANGELOG.rst +++ b/test_runner/scenario_test_runner/CHANGELOG.rst @@ -35,6 +35,9 @@ Changelog for package scenario_test_runner * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.3 (2024-09-11) +------------------ + 4.2.2 (2024-09-10) ------------------ * Merge branch 'master' into RJD-1278/geometry-update diff --git a/test_runner/scenario_test_runner/package.xml b/test_runner/scenario_test_runner/package.xml index 991162b345d..76d630c1eaf 100644 --- a/test_runner/scenario_test_runner/package.xml +++ b/test_runner/scenario_test_runner/package.xml @@ -2,7 +2,7 @@ scenario_test_runner - 4.2.2 + 4.2.3 scenario test runner package Tatsuya Yamasaki Apache License 2.0 From 816603cd625965b12cb09395658a725ced4ddc00 Mon Sep 17 00:00:00 2001 From: Grzegorz Maj Date: Wed, 11 Sep 2024 06:50:11 +0200 Subject: [PATCH 250/304] Fix typos in comments --- simulation/traffic_simulator/test/src/utils/test_pose.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/simulation/traffic_simulator/test/src/utils/test_pose.cpp b/simulation/traffic_simulator/test/src/utils/test_pose.cpp index fcbe0acf606..843fd56d397 100644 --- a/simulation/traffic_simulator/test/src/utils/test_pose.cpp +++ b/simulation/traffic_simulator/test/src/utils/test_pose.cpp @@ -313,7 +313,7 @@ TEST(pose, relativePose_poses_zero) } /** - * @note ttest calculation correctness with a non trivial example. + * @note Test calculation correctness with a non trivial example. */ TEST(pose, relativePose_poses_complex) { @@ -620,7 +620,7 @@ TEST_F(PoseTest, isAtEndOfLanelets_singleFollowing_within) } /** - * @note Test calculation correctness when there is a signle following lanelet and the pose lies after the end of the lanelet. + * @note Test calculation correctness when there is a single following lanelet and the pose lies after the end of the lanelet. */ TEST_F(PoseTest, isAtEndOfLanelets_singleFollowing_outside) { From 9d07e62f7754c644a87da91911b9df6833358539 Mon Sep 17 00:00:00 2001 From: SzymonParapura Date: Wed, 11 Sep 2024 12:36:23 +0200 Subject: [PATCH 251/304] docs: Update BuildInstructions.md - Added expected build result for colcon build command. - Updated instructions to provide clearer guidance through the process of building Scenario Simulator v2 (SS2). --- docs/image/build_success2.png | Bin 0 -> 22190 bytes docs/image/locale_verification.png | Bin 0 -> 51802 bytes docs/image/universe_repository_result.png | Bin 0 -> 129958 bytes 3 files changed, 0 insertions(+), 0 deletions(-) create mode 100644 docs/image/build_success2.png create mode 100644 docs/image/locale_verification.png create mode 100644 docs/image/universe_repository_result.png diff --git a/docs/image/build_success2.png b/docs/image/build_success2.png new file mode 100644 index 0000000000000000000000000000000000000000..ebd2a1efdd7cb05c6c31756cd4d2ff0ad1ac5b1e GIT binary patch literal 22190 zcmeFZRal(Ox~@x*;1DFi-5nZ-U?I4>Ly*SZodklrySoH;cXxMpcWG>qfB0Pg7;Dch z2m88aA2iKZ^;K2B)kW9+K2H%SD=mTuhYbe?28Jjm`c)nb3>@q2wGGVsw`XVKirBXw zfv$?G_VT(;gx0oJh9>4fLVFi$AR*A%#PF@kqEgrpVmBkq*E7XP)ccT*7&M{47^K># z9-Ey0GcbrR%;OJD42$nO39I+hPBjT58{_vsGa1UoO%zM7TFQ%?xf=meJFB3#xFMZ0 z6P?h4TEv(;03kLR?&)Hg6-wbF^s0TDMvE(5>Yic7VG%?^IR$-N5l(H5C z8k>l^+5#0^r4{vE&Gb19i1~QoK09;0HDCd>*ClkeFt@bha^@laqg}4I*S{|_5EK4U z#ommESXD}vP|(U2NXSCZLeEGiwm)a z--^J0tMdPRy8b6z|E&o8w<`b7r|bV;;ez|e<_>82wxe@;+q&t6d^>*I_CeZx5mSVD zd$_|G1b~4Nf{A?`~gdG~#tExxafgPHq*Mpy( z-ZJ-<$uX4pQwWbc7NlxHtBD39@ z=*`jG9A#(KeTH1j&Qfe~`H_4yAWuj(p91y3ElA7m*rqilY?qJc*7lmyGs#AbZ>ngG z3I9`GNZQBju`{47-3|@59LkM`Oo`F^ELWA@XWm;i!VfU3%%ms=FsrzN;xi>74Vl+L zuXE>&OhE-dp|i%ofAAA}BfLF*fPwU87bN=n`^DQuNUYx_A7Ea#1pI7VN*3$#q^S;0 z?qr2EdVi5uJ;os;q45dJ>|gtAXiYuxO%M!ZQJBe>*-wPf!+;op3@E0iU9`ZmNk0}v;j_VO?%J%g4&maQsLAvTZ1S}V4E@N;#^E=O7 zzaZa;#0tBsVpEDwaY$V07HX;mhFzT)N0s{{3POk}D(@bNp_SWFf6*i14kI`HsR09d zW=<}sEAYIlG?Ah`);U9QaR8R%o4+8P>+6+XD{HMm{QNMFAoKac?jvC@g3Yf-jY znYR-?lWZ`NhQ+&QEd|%}YDt*SzzL}FvIw~Z8jwx-sWNDfx{fJ4;h}xEQm5p-I4!|a zBP&w?EV@Q6Twoy+tU`!2`ws&B-v9>#_i z9CyH5odhoeZ`QvLy%(-#5^^L~lS@*Ec#*jBiVhX$86*NQLn`v)S`u#<}UO_SJ-FcN_B6mw_%%5)92M7 zO$$wu>}0zHekmf?39JRcl3eY5l8JF4b+Namygo+B|Duj#SCh}JCK!y`p~!R*qwuX>g(JFluO>W?+}ZsA@M1! zSe*npE9}YpEXktD66KoCAjwNXsU>Eq<#!_k$qBT4*+=EI#<&=lOUuUclXer#RKDma z!Rm$@Nz+@y&&S|GA9w9l&-&ZrM{9)@O)sDvm>mJn`Blr2w8kv<#I+jnHu-8^Da4B3 znL_tC%WVUG4tXb*T*@S3w zRInq=h->4Tc$YQL>(Tl~^t4!-n{Ir6xRi2AS9goKmRz-1m>k$-F z`qO5cL`xRE*aWGhW~A3;ly(-{K(=xRtaogoz4`hK>j=|dJubz;0LS)Pnki}2seP3^ z9?dSloLo^Llt6@8Z%ui)QT3|W&2Q9zvJWX1cr;$VDCOv=CaM}QM2na3L(obi%Tu+# z1n9%LRhht#M~(m=Q$?#2N6`g-L*^qnH+2v6khrok(?7#YxqHU~BvW@R>hOpUz2}jS zC#PUv>zg1A8I0}aVE5a{ycl44n=vGS^Y=AcZckQ?PStQ`d+yrw=j7Mz`vz6~ZJKCT zlBnt^lWpTlvEVSm!$pY{Zi=KU=&bZ7W|sblJRarA^QuZpcl}GL&&V)*jp+*cw%U`d zSQdqo4IVsr=!rS#5$Vcn%|DOC81TU{yn`o5jj46qO?pcM3@BILB@4thR5WulA9r1n zt3oh07J_t3Ls_OgR3D|x96g^trb6Fzg2KDzS6bTFG*af9PFQpY8X9Rx6j}^(r8dH7 zFtnawq(`H5GBjF=g|L~wSyBWwjO00m^98yQ>y_mzGyp}+PpH><^6(^_@^_&$UsNWn zHhY_SEy|Z$Qz5ZzXZHu$4ED9CmtfyUQeT_HY&ZKg1KfSoH(RGGkqC{uaz-C{02^;W zwiK^Oq27k+19CPY06LCva1T8HTwgD|NRh?69RbhP@rNz_d|P$&#*w?4wCr|=Nj&YY zgQ-O5L&wh@?<_;N)(Y`Hk3^h1?JSyS)0G6KR|(WP*S3C7{ib)u;lzOV$shHJV2jmr4 zsAS@C{NUHTmi%}=kWZt2SGytyiaA=GBVmEHs&nQ;`ybg0xlPEpTk@|=P_*Ky0-&Ag z)Z1YPl4?|>FZy-^RlO9Tw%pZK6pg^GJ@AlTjo8wtJWY+-Cv>-;PqVg6`LwJ*QCFFj)Ou=A(DKf7oREkL ztOgqq70%ak?R4BX#eqUlP3}E@la^T7L>Svm%=aklS-iqDXYa0josia`*~iFS5hJ-S zed?_}O+tm?9q^8(v;k)TL=@IWPsf5b?&@S{PbqxjO%(>8Bz*rJ*le@wBfs3cqhHCG zDhtVo%)OfqH~3Kx7$Me48CuHx(i$>B#?{R_UqjWQCbt5$3jL!rZS5Q!tR=-R)aeck zrh-pB+P1UZ;yG$BNFy7pvWJfbT0OrXq&HOl(h^zJ@ap@PPlRx%)3@DPd@eKdT{sk5 zwpgbMHHK7nWwT76Yr$rxL6npt^j=f@0&s0-J6mIcp5b)B%9e`=H7KjWJzXGMIBm?r z5E+jh1F~{%<)`6%Wd_6u_8vT^G(1C}xXv2sC*ZH$l@9(|QMhP(H4hI-MgsP{pd{d@ z^pB^@*l}b0;6HzX#F80kIS8~WNQ#@G(c^C=-0Fa+%+*6@mTSM76FHd6^3)gXJW*M< zUU$_7H3eW@AhYlkMxRj{wKJ~?{}uow|NSd-0N?`RKwWHw(usE?`-BIq;(vK-ET z`?3{le+)v*bvhy0AR``aLG7P8KAkSJ5`F5(h}X#?m*C~94V~NPVJ8hJKR#u#RD<1l zXjbHNjeW=gy4ZSq2lh{7BGgoOrA$qkXn-O`(*l{~#l(~qN=$*nANNF^Q;AG%`$uQ_ zne;=_tR!$a+j`sV>ASr9FM(^fFs%gh!H${l?aL9?k^R?=DuaUncnKRUa93@;jON}n z1A6ga37uuU5qzO648!u&tGVA1!R8bPT};IDO|~TlMJx!6HAm$K!I6A!A+_+t9}&uB zFLaGlWJ1tC>nJX;C4qq--ALB%+W&Y>@vcIRQu0uKF~j;`eXjP#pmT)qGb6UI7J(n4 zXgBM^Pq@Jkw|I@@NAIN^rgd*|>wv4*YY*wBc=U3vF;=S(G#&v{c~wG(lMc4f;wh`c zITKzR9z4%I--T3w2D+lr6;sBJYiMols;5AlZx4wd*NwyGpfBY>MmIB0uWk4ZDpRBTrCDrQU;z%+dUg}V5hjglhW-{dk*zh>D^`fBoqWXVUK;!c{d++)SIF7%)}m5pN=jVF!edf`8sis3vuC~E zkU)2e#TBR9@f;cdEQeMH1hlD+8VqMVl%(i=2YF(PsXTLhOuNz4Xn_2c(pBp^bx zH;ar4W0NqjCel@N^?Me=3<{tQHAc-J?KsTd=TuF-AecNr|0>VXj<(&8FYY$K8y$Pn zx*d4Eu(I!mwD_-=rXWFWCzn`p&`iMf8{d zTtGvrZ)XYhhzMf#ixx&+eIS_RA6$ZBfc{BHjJo!?f1Q4dQePd?!Ie0&)r+|;nTMW= z_!YEP?M@?{zBZJhUIu!}4=Px5)#G9QaFIwsWc1brN4I0(Iz&%|JS&a9<$aN0J~lqN zFiPw>e}H)Z8z%)23jWbaN7K)GqTk%~HZB-|Hb1p+%a1ljpsL^s0ll1Z=16rRg0a3I z>G2<^X4RKaP~bp!i8KAd9^CENU0Y*m$Bq}aD`PYCGlh8uJ|`rJ=id!m-{@;?fnI^>xZ15 zaluH59k%~C#GbZPl>=*FT8 zoIh4oc!}>!DevIt@ zd<6nq(^%ed=M$5%Rc;yU5p72%i!Gjz$}2LIwhdlu44wraqFgTF_C9{;l8a6(_o7N1 z5m|Sa_|?UGR6qx2+b=0jjwY+VN}SX4Fwy`_g(*ZPF14m5kjkw&oCG zu5-I^g64~b=r^XH8jiCUO?$yg-pPlkjWg0$&=>GHy5KGerG;DV8< zICZwalznTaT-Qjgpo(><&{%`WjD)xAtjXx<1a8yhi0;lGce`hr-Y-JEihmVeJp4z^Y;>%O_7##{*pM|TYUC!7{Ct6>H; z@P8mRrC)z1H3dAJY9kYIm}HUIInx^LjFcNbpsgw<##fvoQjOWkllyo!z5)TPNI zz(6&kbz8P1na9$EUeY{nO+7|2-96x{g2q@OrFm@9$wK0_!;I5@8p3K1k2clzJLHxh zOF{M)B6W+pJ;4+z(umQayHT?=SJkK?5xu+w2(f@_&2Rf!%}~R3Pw)@OYqtCq=bF-x zu9Z>HnSykLhjl->FcKh6*P3D3E1mahAIBX973wG5?RW$@WjP90_$jWt#w~jAcHH^vpPh&$NNx(J8!6b*+XVFH3OiF8tWyaLck>%NIQm#}wgh zjZ_XpfS=|5zH3QI5jVO$|I46~l-cwywY^)ZE!yE1+HI@L17P5ixe>`MxYvfLZ6uVO zj0b}!T3!?-97HnY88l(v3USNUkdnad%bE#i`oxih@>r`k+moaNTx*dlN7$LKsx-&L zR&E*?rH6+-stm}5V7A`3keEh>PpmO#G}8QpR?xN70vBT^O_qHs?*iwK1lvUz&;X50ri|j3RWT1t}si3xfX4n}vTqlG5+kMyd zSYVR|F?5nDXo#^wOI)uRX)NHJG#mC0MXYVp1m8Ed3M07aH=`L2k?|p)I+Rej zwUmGw3Y%Y4YIl?5jysheX)+jmr3OhYC(Pv|#x2!FtG;l9)RWOTiV5In*S;b;Hx(Iw zzDA=fBUF(s>BX?eUdA}`{6*<>hMHeX*IPRW3%-SaSReBF<`ZQXaVQpJ9a_(_;Z##! zdN)rZVoREIFu)*zP~;4Zb0UTB!*kB*IH6$Dt*Thp*kIOq=)j$*a7)+`Ql(eTrk2B+kJ!0 za;LY3<0HQ<5EmkWnchj&hZ=l%SIAB*Mw2KUMxI=~50h0|xXSNWHW6Qv(eE=wuQq%% z9fy7813LsIG;-^%9~<@vU_Wj7ssfs6WYT|$CoLuD)`@Iv@lw(?5fh_I9fC!soUH^W z8$qNpOY(Jc|0J&uFHTLA`$0rcd)COsVjvy)4JNt!`)}LdFcLxPlbDUwZu?BgDRR_wlQt5pW82(BMn;fxDUJEs!|r{ngo5N9&|-4 zG*iT#dgH&6A@(1K2iXC%{=VSyrZahs0DPmhdiF+Yb-AfHhgP&gEVrN=AMT1fMN+K8 zI)(RdxGb0XPI*TOlAcH4iRP1!E5P8sa(Hm)y0qL_{7lW!{-Nj-a2VZy%urWVk$6?M zZVz;Gs4iD5iYu~`onA_8mwj#*4*Y6GQ*>}f#QAu#uyKU<#pgY&*t>!m;|N(w`$tEA z`t1^Ktid3_`TU7EsMfK%ur8<^tUz}q@-UD>)dkeEUu@h$pjLl|QRFHK+)jaSZlOW2 zgH2rvK4YU1ZHVp4e}>ml=vwi1-*SLA41IqxidHCB%% zd<32Fl1Q_(=#bNLGxGkT7z-l`E9ps?0I24)r z#c%cF$MV(2K%3Z>1x9^ZZIv^kM6V8*d{}kEknM%B;+n#VUkEif@S$+A;-SJv1ugfT#wi;Bx87Re5~j&?9jBj%q(-){`TVIG!;C^rlH{e>;3 z&)(QF);B)0S<{B@ke!XxeF+X1DTU%%9FvGwCBQ3VqTzYl4-zF#E3B7}hKDC7UnNmS zJ&uBcG9dtWWk6P=t)G)8wKiA8miGC9LW7!Wz%)qdSBQ(i`_cg-ZViZ@kaSL#;+hnK z&x9J(!c5T^IMWRX@Wey$9!n&YQ&kuzuGhIfK(I$#?*Rfq%0c^Yep8gguh@P4uvQf9 zVB@4v)|_7io~@E}FGX9UOqi2c+Z@qxT3Enf7*KP6CY$b<9Avjz%s_@YOrf^`8;-1G<+0E)Mf5f zJI2?=eq>Z(qT}Gm_3$AvA#}1k>Jrj!-I{|M3lM{GA@t!>N*8;J-vrIR47gsEY{GPI zwEz*x%-n*^|82wsx77(T4*V0slrteRQc}d+I3P2*x-zDxZV{WQ$_diNbVJsj$wb)6 z+62v}-iN1+POp*T<0iIG6g<`DhR@8yy3?f^{?NzGt1;69&F=wF1A-d-M;(!DyEw`R zeem04^gA4QQbv7d3I?h>QXiJmlJ~B00NmpP0%U~cpuRriK7~n zb%=mk_E0%uHd^{Di;H4& zygz*DAG$3FTmmHO&>8^@$K92snfN{ULUW2eQ{cv2OMhv4E05}Gv>e#$)F2%}!~WzL z-agCT$T1_?L%^7w=ajd#WH3C%3nC_oTc@ky0L>}AExu&1=Q!r27u?aLcL&GSe1hsP z0yMORb2+%69crefmMdnjc#lgj_a%=tJ1jr;Ls-})3Z`CX>ge84{hqN1*9UZ(5{z~C zs|Hze_8|CtlKn}A&OV;Q1+cHm>A-5T1Jk!%$&1<>$%6k_hxjU%n&`i zx*pFItE|7UvzTUQ(WZYxc5xun;TAjaTU>kXL@<^Nocxqf%wl}HMslNl>&8py5ke>a ztsp`+2}4LmvzhdRfFJ+4m1^r>uqPc6 za#t8tR*x97Md8V{mignO!o$3G{orxXpNa!cP&=T5h;mJpdza6ZBzO>!(Xs=?oe95^ zZPR{$`5Hm=2imS{eQDOF`LXm9Cu*+dtXIZC z&&a63)rPkt#o@j7sS+lA6=pf;y%hK3-Uv{+{uX;rXwY7V`+s1r{Xb!@)j5{s8|J== zloGrJa1Rhm*drzyHJmFHEo`O1eEqV? znRQ>~0mOVuOk`vmlKOu`xuOC(DW7a8j`~vaW-L7ugzE?bG3)s0j zLTR#MfHpcM1u28qRkw!F`VZ$A0N&;9c-Z#raY7Lol5br!U+sUIjp%DTS`HZDhYQGS$<0EWeku|OpdgMi$YnFqJ(2k(IkCc>waHR*Q?nnb*DJY< z{!h4e*iJ(aD&&ZaW^!|+cN23je5<+_eM*msdJGA8olnRev%&51GWEa7u_s3K;?a^g zdM(bJM?5kYPLg1)CYkr$O;v^lAJNtCGjO#|-8zQ;<^|}#nPS&LoymGkh_g24RoLU+ za+pkXV1u`bRG+lsm!hkcoFT>69Ni>y<2>37z3Z@`)o_iIoJyL$-#4LqpB`p7V9tE& zxbMBvErrXwDfNw?v=I5#w*nsWHBqwnXqKn2FY$2!Du{acpnNs*2SaLPXuk+;9sQPc)eDDE!S;*~{!RWb!^Jx$^9LZuDM})xByFK8nSa9GYQ0jQ z%R1vLqz$s938OixARb2aQz4>T)(pQ~NgikUEE~=qXO${Jgup-?1SX#m#MNY*QHegT z=|IRVO)X=c9o(oLMJ0=Ty7(_Qy(^auC>pHT{0avK*Ln3TB_5uvl->18z7WWo)1hX1 zzv}%~One5n7R8A2|g@USVt>?lN<9jO$K|IZ?%-3xzReD%lEkqZ)h z7YpCS3zKmJbq|xlRg1!J3n&^*aL(Z-eUmGNE*P*6IznxMI9H(R4%#eGHWlR?%RF-4*07VUO1|}$9wEN4fB_P%K+G7F^hRGd zzEYtvq=0a0IhJCenFJTJkrX6#`@ev0L(gK_eUKR&GOsf7M@9|e!Vf%1> zpZpDUbH5F*A2ph8FvlfBtPtaV{jBQo*JOOZ*GvE5$;ms!9QpVvePG-m z68+8)gR(f<5;d7fuF3$GbbA%^9;{3Vo}1$y`LEa1WE#S=d;kJ6cE@Z&3f6@JX1fY*9qBWpf+qmR+3nk<~(Nk2^A{ zB43rS9?eZgC@RyF8)$Ho{{^CCuoyxP0pMGtJNMA2GEBBVOg2H&fa!TfL$Xj`p=o7*832(N}5toh0+v6qzS=ZXZknc(VWg@L>}fz z8OX-Aw*51dj8utdAB~m3VQox{O4=10E3GN=sVVLre7}DFUhcOwsUMx z_K`g64y59DB?66EQkb4;22Y(&WBE%B<8wVd1UJi82&rEg0KWb*gE3ptY%^>7th^&F zgh-N@U+h*@R)W%G}hho=Y#|(-936=>zqZU;gdoSoW?5pIeBa&gsF)hoz zR_SBFtg67>z5FEiId3;ccl5wyBSe`qK%=G$b=HK2xxST=qBjU4MsHcR2w)xp20;{kZlRa6Fls(&KP2fVqFZSIpf6c z3Y3Ewkh9X?xMf{F`5Zupv6D6&q3dr8BI!cf5gI}H3AJ}FRi=9l2a5haPm50OKxHA@ zZ~W@;dltAZ6kBm^a+Be%2{RF>Cff{-2tvwtdr*B@#E96tYS6`9*pyil+DhOg@(shw^=0pNH~Brtaq#nlD-~uTGL!)0sPe?t=VMH@cm0#X9MrEF%~5p6uS> z92cZa`{Nz5Sa3toTIEH_d}@g=gb@nkBZc28?$9}rPa<16y3h<3srD5xd9PFi2)IaR z`aTgDjcIws7bi^}cDcb5RSLSeyJ1hDWw{eO|J<%V22r9Q%CLexu9g_@&;6em`L;gr zSZ^AKDOo!fVIb&oufJTZXq5WakPC(rf9Yb1VJU9Pm_@kYX4Jk>Gin(ZfCPV>9 z4mJi^J`nL-&o2F=x!sUEaeTtf7N!wnER&!YaLC>RKtgL-&E!|Y56ZT{(j+q@8EAH+<%PgZyo%-$F~mF z2?PMSJ;ze!Nv}{sKUrRYTIhd8c_P=wQVlgd-(FMYWM}uF8KAt+n^$cOB?~+FcHUM|XULbdyO7>}9;zQx5dGczvaj z^25;J0+~JtKH>MKv)GP)TJ3kIA3qbzR9W0HxZgwu2pMF)Qbl)lrb&xGc)qCQP0GGr z_+&vUzh!nXH^Z$4g~HObzNE{D2h41>eH4s6Zr?u9H;!mdCu{N4b3S{mFbsyDvn(cv zZ!gzl9ZXJ=D~uxp`C5sI+%zW_e0gcF6}DScwvfIP(>7?!2@$v%9d1SMk0g`Q!7>=2 zBEj%!;}gY6n7XJqQiIC;YB5G1LXJCfIRoZRpXgwtGfHeS#@v6P|A-qtd=r&Y zA=YdTY5Jvh*!1Q2nDK~8JMfk=_phfjvZol0WLh&HJ*%txbVf`NfPrx3p5Qx>p64lwkiJw#|r|5WfGp zjhXJ@-`JR;pa>H^#x9pKaTBx{bX*rA;&9wAt_WoCT8!eVtJQ5F=jQb#j|@sZ3$&SRbUg3df9%klx2dz&=U_y@CBiadn*ZElKCB=Wu*xHS(Dq zoFn~{w@L}ds8RlSbNy{%KKyA{q24*l^Vm<`!OyE6s>V46K)((5-5OS#cB8JXTj8E5_JNI9`1Zr9X5k$f>`{ms~d?o}^ zWO&DP{4E|-&nzUF#fuPAyY^?*aPe7wXt7WG(q;>d_HUyd*M|2QY{7iOYk2$;k%{(* z0t2aT0GM_PM3DOW;6cGPYpeS@)A_3^=Ko;sWyAu4+wt46$Dm0V*&Ztc)S|Fz9;Lr+ z7Of35&ceE_r8Ez8{;3pQQSk26)n=5&pFy2H+Z&KzthDOWdSOJK)A)cI>9tX$l9*>v ztk8*`R8taiX$;q3MYxf5PdecUsqaXA}3=R!`w-`_BJP@bfnrn-DGT)k@Y*Xf(=s29t>--{AVkGa5!j6nfc@qv-Syqdlw*yP9CRN5+x`Z#|A&c z&*pI4{vs@>`XB=D?vDV}kfqPq5YW?HomU8FzN>;qS4x=DZ6Sfs$qoLbBg?K&G3CWI zgg4+VEJ&f(A*l>DR#&hhYKTl zM?g_s*_jg_5?l)k>vOwR99~-zoo-1VRwLfh*vp8Q?UN=ga`i8z)Xvc0AI_Lik(}j_ za=aKEz65A)in&=RKL;q$65elreak;wN1F=zAeb!blOgia1b4ENuR)x@+Yq_4J5(H% zsDv+c=F%a&t1Elh%pUnFQYfbg`bi!OXxO)XSn$|N0mJnl+v%7?<;9_Ik^BB5ix$u8 z;75<|+CqXAS#EiCPEO3|&QEA`GqoR4yM8gOBc0s5@P!pnWU&!hLS0GogrBv>u0GVS zW4|wjzBkbmsdYOUf>(x%(v9pzNLUKgv#dH;*^=2z%V})UzGP(0ISe0Cy*48$l{p(5 z9#Kh`dcYWu%d>|zf3LLLdwDusjyx1y_5*80@tM(U`RBj5xCci5#U+q2+f`CcwQRGK zRZP$^;F5}DKcy^&EZTx1rar)8%d(IoB=W)Gq(QTdI(2DoN+429{GCnRUvfG-2gLQ5 zQr>x&J@JOeL88JW#rO|f^8RjiPXQv@8oGw=*er?4I!TpI8r1y}x_S?1`(_r>>m{DF zs$OWU>nBB77vnN%`(N^nS)i=c-m)wtoMsF9Y|%;e%#TB8q=m7Ht`NWHH5CdgLk!ul zPRb}u@iE2m*=@qE&&E$ndu%#=*5*Q*Xj$i%fX~kyuxV2kQA+fvVE{JzC#eITp)h)# znXHgR?~-m>gkbS*98)_>Evd_mt`r@XaJIErqq#$k1dj_&R(w$9k>)HsP~mf`>e0il zx6*V?p3#u`viU9A)g**|!_U#P9;f7wIm?3^Q!iZOhK?NCr8Wo$O6jJcN6~>iek^Kg zmiD6Np!Qsf0EYE%$^VjX@ICZ}+CEyEe5`-xfPl*3$o3TbF6A%g@UR0{C->Q%V5{qE zxvz0uU*5qU{$VW-T&YrZ+o7Sy;~ZS`!e75n6a}nBlFW173oE?J3imZvfnR>042!4k9Y&se_#Mq&iPM_ro04M?ad9t@{AY%6 zLJU?@R>~Wo<+ABpUci(k=}U~9V!P`Rd9Tu~VOL0nvsR10!3z{g3b}F1D#U;-RHMLwV1XH zDrYPIxOSJ-;^*_Uw^HfA?HD>OntNhv9*F5L;LXMK zAo^Jo3S5mXh4Y{PxLkBnu(NXA#3{;?ya{sgpPnwvAuXm-t^w=_w3!<$%$PP!_yOF-zhTB(PWrSCPYId4M}-*Ne#g@EaM-hC?I+ zsH7pxRCN68r72vy!4b!>K2(feA6YDIN%ZWF@pP*Lyc|WzAe#*uOMFC;uFk`~;iI|| z?;85Ua$fm|<-7*x>&~lC-uXG!me|hX1m2V7R5JZYJnDoohdxNfU4p>N<*)9A`s=tO zmoA%uNL}qjTldL4klQ`=N%1qw(LAmz>#1n?828j$QtBGijAM647L8LI3i~V1j#})B zVc{)?nMMHgPt}Q>Nv0F0kUvQyN~wEAbY4VX4XM8vLhqcknEk1jnw`7td@>Q>UA~Un zdcYc@E#QUvA=$Sxhdvh(j=jt1k*nfP&&sbPH6-W!TgRG{wx--6yFoih?YayOFSKi) zt*1?POFqW(OV^?47iAsK+f0}UoZcTw_}BLy*zl!C8}|4m!cuvNr^9QGh!$vAuIYD% z)7G$U0l0%scmv~kR4MyzAzy1Gu?!!pJYKL`)%b#?9*e4`2K@WG&11;pVki$;8J-uGYO#+B3o|$MtA=ESIuatf(!)R zH6l8P+eKGGQ^pc)*J%#m?AlMUySFx1ENP3Y65;3-z7ZA2vl z^ujGDRR>A~5havfVF=0HgW2J=Oa=q8Qq5D&?@1Bc9W~kC|2hnBi0ppO!Tgf)$@Wr| z!-Sz9@GjnlL`};9S-(zd$8;#sc{Oq(jw^DD#GFZ;CH7sF^5hI*^t?oc%a(Jc*1xx` z<1d*0yNu0K96l;_r}Btl_KYUzrP1$ zT)M;+!_BRwP7f^8n3JP6e#r$O%!X=TL;Mi zF5I0#?hS%_Oo2j(XzRul8kX0xZ~UogeDX&dta_G4nT*BaS8`niUUR-wmYWbzXRqdZ|Is_( zey8)6Yv_fCFrSb2ee}#qq5iS{43EjZ;M+t@06NQ{6zhq@!&(O70wsepq-97a@2qy6 zs`|);D0fQR1ZDEjioBt2gnPRC=(S)jESD)~xIuv{{UjF|!3V#A3pQ zbc%!99EjvT-h4Ho@tK@)p!UVN*M~xeRsurE(HOG5 zEc1^K{=1KUHSBZ9kp4_7tAn`MnXuO?Yjy0{4=dq@Y%jEvlaG zw^;%byaT#VL$#H%kj)+`Tf@l4c^uMlg>rjkAc|_l$f}oW94CC5@hNJ|ZoeB9R9Ees zHx(u1W_X{{#Y%<#+Vmr(b-RE1rH09soV`HiV3uu|!#-ilrsIAEw)I`njBr`eE_%Wl8zn8^Hq|NR8;u!0t)8PhcPPX(G}KD_+Do$q~U zuHEhz3Demx`bFVQD^~nb#5$Cxw_1AFSE30cgW=z&9v(}^XmF7AV%v~coxH6Zs$+Fr z=h{Dx{eJ;&QK6+x*x+WqQ@`98Hisc;@Dg}b&(OhooRlT za<1K15Vn)9MKySl>TRwR?@9C_5n)B8@L%z$L>Q1IUuCE$V`DIwP_;}WA4cvYqVF{R z?uwqL;%@lOVDj6WZC+{JBq?^E-I(X|T=wBvR}U5^moDn!_Wnkhn@G z2jJ6<#AfM##ZQp5;{PN5lv2$LyK2{cf!)MUnEWc>S-{-A(!`?YxIMh%dC6GS(B zlHz@}97r2FoiBfsHt$~ALN)WJCyVjD{KzOGr0}@Q+a^9Jzf6Fy5eY7Qih(zl%_ZB` zvL!3#yELFw^Aw)bwV2?b->z$z$jRBuGLna*+ALh%iHW?R%sg<1KDMysWO9Nt`|@%6 z-iC$b)}p5*n6<6ZsJ~b^&VBpAS9;MkYjKdpLL(LR)#_|`%ZzIZ>?y_0>QhmGv8*X< zCPL;QCf!N3_)>v-Z&Dm>?R-!Xpnx(+mn&9I;8(7mg}r(t^`!C7uaIq|^+YC?Ur>o* zBZZ=p-A11xVHU+lLvdKA&K@40Mjuz59$N33*BbVI!LPWniD1M4H`dz+pL5NouU(h77kETC0w` zp`b{dNrlhsmhbiJO4fz%A|XkWSa-u}RcoZRVIXI2dSsMp79)sQS>w*fqtV~xe?k0! z-CuxZY0ljmPy3OP%nrcV@C1UdxV6XH6v?*?jUZ8wHRs-{C}*e%qyKgvk(v`5j>qwW z;~UB|dRFr7fG>S(vN>{i4O559qt;!wR5fmKU8=b``Rc0e{l$d1;K3L3y>|YqCXP5O zQ_GOl<)3J0H@Xj{$MW1lefn2Va-Tx?eWz+IG;0WhV}GJSz6n#N1U?X6VW~Y540FJ- z*-AH+EM}?IPLFaDrq;8|fyE)p_CQ(Y)IJBgIW;p%PL=|A_Ai`x*g~3yg_-(ct8P+6 z3w#uj3JlQE>XOp7#J$0HV?QET_w^GI;l*G;NrL{=NpwX!NpOc7!X6iwmc2b**IQdN zfeAkX(oxH89^#mom*;KG*%Oma6&pNQc6?)jx?Dr?yzo@+O2m3ASiux%W)~`K-=liQ z^7T2Cnd98YxG+hiZ2~9_5p42Iqyngtzp9`%1kW4|?%q6MhL2Q1C$LN)zOI9nnw&R% z@+h6DlTIsQ54YjS`7Y$4(*?A_^+S!&XcIU?YWVq!V~|cs|MS|w-H;K?^M-Tb+Lq~s z`!TL-^KpAvw#|{8Ej~O9LqvnyUL6^y63Mt189Wm+ zr&tI+^3T>pvvp@*o04SYoh&d>%udzrui5&=WUgXDgoJuMphS9s@>d3$DTl;zjjBp{ zRiz_U)swkb76yxgyqV~>?gtdO%R9lZ4JsT}d;w=p?@`@J1Kr^*ON7!7t94_e3bddX z=krj|qjKX}4y!haOD2pDEGifK#0P9m%Vx)eBR`O^}-M3{$ z#CiMeOZ%f!dZ!W;lx)nP3gp$px7$S54PGa#t*!qRH3rK0d{`59^KM5*i!7ZU9VL{M zRM5wfBrsp$8*d-JI`@m+z?4J!L(Oh0!CV58ENj6OdE(U$Y#h|ZP>*B?#V>5Yg zk9 z6srQk<6dOgJMv5mN9^=Xaj=!pJ3d3pb~zN?xI%LJZHww<{a=PN$wwk8(M00`6B*Yf zi-Yb5$WVZiL=15zdJh}Vu-KiPO)WsK-Hrx!_tfge(QI3Mgx+g?S--ax+XEs<$|y!x z+lj`+5%^ug{Yz_63I`{7Vp6uUWZPD!uQDaP;E9Xysr^Zw1>&1(oT>S_GK z5IWdET6rO}pY>};vS#`^{Ohb|&kylrn`%(sr4cy?0tipBVxM1w&g#`5Hf{96e}+FR zz!y}Z(z^9c+48~d89Vf(hEr6&*n{Dtp3oC1;w8eY>;U+Vlrderx4ixK-n4h z4I+c0DPA#_xwCJuBkUSxhmJIm`PI={h4#^s7gm;qO(#6o`ZCfP+@3HnaCWps?`2rq zUs4lSdi*t$+!{^j;yIB~?TqXmZ~(1?e6{FfU7gKb+OnPKDf5`~sYK!a_X#p8R=1Cq zT-Fw=0>NWmWa!#@urhQ4&UfzKVmUiUC}eK%!fonti#9K{xEAdvEMQnOdkT!v>>oc9 zzp}T;F&o)6W*W6WnS{Il2By`u#awWUob*`2lk&@3is=E<@wo26*l7dtUNsWOni99K zr*J-C2|w&lAm>+W!c{`1P2_Xu-Avs&hxnfJ3BRF1mXbm6gt63IItLG5KL*(4lX@n# z^mmjW*A#Ge!6?REo{GTzog#6Va(q% z4mmHCxJ|wUeG^ZvszskiXhTipb84O^({IjU@|0z)tgn)F?k6@6UB;&Jf0ihuZJNc0 zPV;%sdog~q?NDy#a6LYXLkR`i?V}|xtR?Htg(XH#9ZsbGP>F~zBbLANVI_a51tdqD zBx&d%7VY!I)|^Y)=@9$}eaiN*d@Ji?-567@e9P9IKCJf0W&6q_+$%GdY7MOMDSszUH^cW-aYWUx5TUbGn$TK{n_`)8uKC_2Ih;16NtPJ2n3>&A*c#= zv>o~mZHg|Ea;*T_!I>8(jmPz72(ynC2=fR80)apj8G@=lW!9rS^!%GrS_C->mp=0T&{%osl%%Ha7in1!{f%$fX4ny-EC2^V3o z$B@VOxI`cj2p(JPso%Oej`k1wL#Rqoh7se{LSd?hEHbnd4_dDi{0{ZFFo8fI5Likf znHLQjzvLKp+r^B13Qwk{-3S6XsW&V0Ms%Jp=-QK=9b{U$K~gKaDLh QKmY&$07*qoM6N<$g65wYApigX literal 0 HcmV?d00001 diff --git a/docs/image/locale_verification.png b/docs/image/locale_verification.png new file mode 100644 index 0000000000000000000000000000000000000000..2f2e475814bd838fc3f4b237518a7dd80b058b87 GIT binary patch literal 51802 zcmeFYWmH|=k~WG2hd_cm1P{U8g9mqaHtx>G9fA{ry99T4cXxMpcikVn@993L@96&S z=pXmT9pmgjuvgWpJy*>+tDgB(tzcPcQ6zXAcrY+9B(Wbt@?c;PNnl{$uCUN=R~j{vxm zxys$u7;x6Wp#=hcPPm;^$^GFMn>7;jvNAhJg!=?gf`1u}sdH;lqVL@g6KQs4aUDA6 zhwvq-)~(E}B$d?KHC~b1seBH2GD{kvyuj{hcO?e3M6zj+HGqNJ(@1KRl&OG$!9$zA zjY?HYk`rKUNvmgIt#3#Rw6u8}E*Ka$AJ9e*U~cF@q;F_!YQ^*Atf}n_k*NXC7ZnyM zdMO)0Lle^W&bt=o-eGdtbZB%r&R4o4h^Af4N1*&eZVD2k%eI^M&CH-Mc60{^82EnW6j7sd@L$|M#DN|H%K!$NzTM zzuon}^1%N}`QNMS-|qTfdEkGg{O{HE|1WpJ{}bF9TD>7U=Qrp!*5C8_4fcJo7Z6i~ zefzk>8vFzUBLWi>;#UMN9Z{Ot70BKk>5 z`Sn)2gZ2lioZ>UJyv0wbDDoC@q)c(5sHoMY*~C3z2vU@O=&Y>O^rOL03vwpoQ>Lb; zC3_>|m|DxFLntUHSYm$^0a&@;VPHKyJ@RmWf4kzZ;@8Vp6!=RxO{pYK^sYoqY6Ab4 z94_f^iEr*bg?yNaRF|z&WCwoM51w}|+YSbCxYtZXC-K1Qc5GQ+GGZu&h?s4NM>Ov$ zZNi9Y1d$OQFsmM)g^gzweB#`r)%AF6a&7B#QtF}xb8#WQ)wQdyslz#KO`gCMa~PV< zv%>L!S%SCmzV0ywemcv!p*r~F(-a2>AIf0)quYz0yijy-Ye~+uW2Wg-#3(WFB;(KS zX5Bi`>V)7(b}4PE^#^U_HGgv&e_t*O#NMORPf@7V)Dczd9|#lupfap*&$gYk zmu_%=l3KnX8OGsGMP-YSV7JFrJbGTDaDCj|V-7f2f1bAQ*0MuKz&x6~ed-0}ZPV_1=S*aXoyUmYp6Cvcw51LXY*j zK%@NR;=Vd;ld=~pKG<$^8wI^Z4>k=93O+S|F})6^v4uE58LD~U!*=~Eq{lAl`Z*4F zPbOC7R>eLj{5IcZDR=;KWiliipRU7gwTu8%%ar)7+RgSW9n$Dlkg>=`Zv3;!!eE)B@*~Y(RC!|Ok9WQVhBlU+b!i6B4&*^0b!4Fbhbw=ospqu+i0sy=4S#7uJx9-PX<>J2fsWW+a*91LB zJmM;Qvr--(IW!$YSlcJqdrBlFm>A}mC<&@lwD7$=cS){D| z)Y_pT@`}ECZeMOW4svet#lN$UmMYt9>w0i~l;8w5)#U1ahaElLxIdE;u6Qb!bb@{* zG)~d9cF?*^hl3KOeYKbWS}P2fGgL3*QqVS7`4n_{>T5Cjaw6D+t&Lol1sLY__j31)ae){ybg`r-Dc91jx#9LnTzzqI%GS|NfZo z6k_H~O5ONT`gh3TXa}Dq%!ZgKgQ@ptAcq-MVGMErL^KhNa6=CLj}A#nVqeM5?{s~ zY^j4|Q77}Vevp%`BU$)VW0QMXc14pPpr%_Mkwu{;HABpye3M#t^E=&)VcV!QTG)U}-QGu z8x*bMzu}GWTml4q+wX%hMB{6gg1iXar|g5LZyW(01#H$+qm-Fa-zw!y#f3;f=Am|N z=+kRV971g!ufg*equ%1DO=5P3>Qf%zsm5_SqSbvQN99~aCC(VUxt}M{Sw%F<;!!Vx z#74KZ+jKZt$VQeEKiYibcC5UO4-)Ca; zv<66ebMgb9zc2g>tPqp16ZO04Qba68sfP9eA{HdLtK~kM!iT`k-8fz(I3P-Vrq4^8 z!~*be-dYIh(mOO}@diRIq+F?eG-HR-1K)2%1%<`f5f4UY&8PhlR+C$4NVpPj$MPOB z5}mt7C7!}}K^IM)?#lMwq-`(jM-uVkE=0)wsGCzRXDy#)u|C|ZzTRUQnvtRHoO1Z( zkWgB*BZPzzBTOeau&?bShtwCFf;N=j zhetoWlvu7yc#^zGKPE!~^vDZYd^csOJ)st`EI*;mT1&|-iXXGEwQ3orM%FEuhv#;i z2{;<8>l{;-G{nh0emMakjjigmGSB%;lz@vk_=W6Z3d(thP*KDEHWTUy9oRWP0nXa> zOF9CYpFvpeC#*)_q+e0T0M%1^!w#$1hlU5{bmtS=u_Dgg?dN5D#DC84B~`Ux^ZoDe zheXqFyPMoGba+^UyP08f`(5WhlBL5wx}IvswLX1qBR7=G`Y`3NPQuM-%1!oUtv5(s zHY@O?a-~Vafd<44<@(e6fa*WYkEKaK<8C5)Plr(+)`st7aBZ1jN$mnP>bi;@KfEcCt+!XV)@kr>uJs;OkuAiOf1+~_2w7+dlq+PaJ<1BE=T$kv)Cz`Hh%SrEE5iABed{Q*@`?ypvVAI$^)u#HRN9+l zrDi``>-^Qo|Ar?D90xg)TxD;}fW5Dm#8|i~WRxMF$_nM>o2aSeM2;8dgs{T*UExIH zPnRx=jm!4~oa-%4rx0JA!0V3Hy0T>2Hj@*New1!B5m48Z0?v7E?zc`fTmWVe+PYJP zehEqLeNm!ifZZhP0p^;m(m7Xv4o6%EWGnejcSpr*%$y&|Gw)e{u+H6S<#^^A`=UdL z$cn>so_D^`tw(QNbeX;GVy{Pm_i>}v%8z~7o*WHQqj5hV^C5hSW{&g?!>Ysv`xuaq1r1#% z{2Z^Nr#BfGvABlCqpqXVX`N=u+bK)gSx{ILp<4O5M0htyQLg^pwxSn^XOeREI(0eg zmRPc!UlXEyIGT=;9E{0Dtl3Z7!MHQwdo85HejfITYToVWUW;tjs$M`B=C>A8Xu*I? z;8)E8n>4?wY~Fsl);q+`WuY#x*F_;nhKR8ECNUH+JlP|2X{*7B(+jl(r;T8i#@91= zkT?@>_`PR|2D(g4R4X-%s;%;6qF+fh*P!9Ir3h?!1Tv(UR^WpRIs3|;q0x0!}O~~6SSqkdAXvs_TP{qG_ z?lk@oWlE5C^E^mGxDoQU(K~;D4DqEP!i$73dnJZQ$svjCEf)F~ekiw%DIKiVqrTbI zREo?}On@}ACDQTJ=v@E2UXDIvZoeRUrs(QnMz+l7b&`QI6pT8FAtw4eLdF&>V&4{v zpZ3pz%%^3{(iNSnt+?=Bk>&p_+8Q5((!dDCg7icnkJK2Ye59PeKX2DF)x# z(o`W0<^v20w<9(+A0-F|^>9Pozv#y}8mJ>9I6`kg8UmHX)(O6E<}21-I5E51YzLpQYZ>TE4ElYbg0P1ex*&UFcXbza{qfDhSe7vt99dms@Gk$!|jf^%vj`x^yP1=qzIk2?)U>q`Xf!HtPId- zc_P;ZkKpX$in554d}X~HS`xg&sugN;^rT;7T>~n%g;_HwnUk7bYX*u|e8=wt{P&t< zZb#HOMd&m{s8&U{H%QRC^5uPdid1kEBZ5A@+}CA4p;cw8#?aZmc97UBP*{9eaG*a{aiN{47#=FJ$gahYC9gwmZ3Em zAvrR$TfhItl-QOQKWZX#B3KfP3DCB)#>X9rt!GGthBkH8B!Jxulnpa@D{S zhc$$wsU=SmapxDg3ehLfNQP;<#!#3mJ=D=FS}`=AW?fxgekhV?JW(;+LM(61O)hax zeAEDSuWW{(7PU4irOSe9#;=P!HrK$Qgo z{G4tCWyqwifI=U(&cL}CwHM4sL8yFnBK0mC%?{H9`|n36K67B=(!{yPgI)f0FBgU( z^xNjGWqIte-a!gQH_@Kzsi6q;G5bKvOm?>q`j0Gamvp#FH6?%C5lhugM$9%M2HR7h z)$>f2J==ZU5w!{9IZFB2PrpNvvEjCnzJ&QOUSGa0&k7n|_1Q0^m8Qb7dLEeP|Mqlm zQ1tzn^Vwk^kq1*X9fA+4$I;*0eauvbrLGN$#fxvl%{jCuU#vGAj#qNJfBa zwEcL(7W*hlgA2l3zSlH6skif6m@BiD#0Odrt__Z!9P4su1nrcZp{J-^M|&b#VSZaO z)TCBEumfxXsPDX$xo&|Z4QSEnVCh<LHI545W$1;ZDy3+0kS* z)l{{T#^_X(X3Ga}74gj2C|kXAmY<6$jxs#>tW(8vPgh!sW@oQl(zF$%%8 zu6)NFm1SFUU`ppKL?IEqOOw9aKdE*lJyhq#ZLjCCWsx>A5IBFSiAeZiJ{iUBhn+(T z!&j2zVQU8;RNZ5*R$E3Wcqp`0mg1>AyMV0DMjIcYU!|v%@odaJcFKO+^fdk&;)=x@ zFP#b~mI*3lsNZt3??+m!SUHwrv00%}LFL$UoBWFVfu1E(2?hZUmEvNjnNK`#;6>nv z<9;5@NL39*Yc)^FVuIKUv36+%6{$(wt|V6k%+h9cBmEx^+2yaU_)LwZfPNe0lubDr zc2P}V3WVxKWd{dDTm^}-I|=G`)#5GqQsIu@7?K49KiPv6j*6<%s%nA+o;Oq3%c|E~ zU-U0a?XrUsJyI$QwcQY@$o5k$fG0r=CpYV6_<|eRPBG(Vt>Ac)y^UPHS;~57JYH}S zc<3c@*!XO@I={v9I>IRKR#^T(T8;R#Eg}NxX?c_z&svM~)X%;f7gSLo9E~*qq5aoe z3-B9w@bcBP(SCm#Nsf5ICoI!YO9(a;YFE6EB%1JaSCL6VB{G1Qg^NmWySh1o zI~!8L794uSd(MbD^_7l_tF0?pX#N)}~%HMPZkd|qss4HbU^rpZcPO19aRmS0~@*f01RaYM^Erru7i z3u#ELsYUt5dSg`Nb#bX#y&mj%3cgksW$x?asS!0o+4C6uMoq0~>>ZYpem zU}u6l`85r@J54{ATjJ_p4$#bBg&Z4xYmY1+r&WbNA4YT@KH#k;M{rj237+=r3TmS; z92>pT!Cd5i+YTK&-F?aHy=XoX#5hwhW!5DXRL9@xYYpw62A@+lYJ0`y$>kk`(P7g+ zJ(j{7wb6t9NfZd&1-YY?QTTXV5V$_CwOofjC8hR>%R(fh8Y&mgrA59qMR--sHlYCbz-Wo2jUFzlFQ6rvc2Ak=0EKV=7D5!ZpW#llq3 z3{bb6W|(!X@W4k3cSW6wL{?@rNzj+PLN3X0ypbpp^yG&o6Ux=Dl!}?)O zO!O4>;-cO9*|w}~*?$c67vvQOFqz#|Bk4}~MR^h;Kd(o!O@ypO> zicR!9_dPkyoWOI}?8oq~rCqvMj)!`6E7!woH;`D~*h$?7SGrf*(n{8+O34Gtmc7Bi zdVMrRt_b}FufSl=m4E^8-Uc3-w4!dM(#G0hFr+UPtmbKSvwm# z`#nd5KbQCrgJ?d~O@vPT3SzlK0e|SBqy$1HM`7ywMGFZq*^k-{vzMdAt=9x?GQzC0 z)L#tA^rofy$l2=+hdF@ z3P^n7fAixm<@XBK%y#J7KWlK56COth0A`xU6>-oLwCxk5^Tb(N^1*URb&GyFJ2?3SLh@a!l;dLU#3b(o+zzv@rt;;W@Txir%NhMzgTSd=8J)+EgzZvwTKu7$UxOtutGKjEtw~?G z{v!Wp{dl!2J5VGqiY#qDa8-n@`FnM)JsUKPFZzLxm7Gx4FZwnxd1@hG z8ySeE?Ru%vF*w@tK}zCjZskc3>|PE{F3(|+`^siS8t_WNdkXz)Y1x zjOcPK7jvIpV8^-Y{yXM?P}BG>Yp=dG?%Ep#G%!}*mp3|x*)74+&2fY`E+6t<&-e*% zK(6vvh2sr`|5ecV%pCAu=J5X@^;emL_;os?;MePgY@;xD?`2`BeXjAP1Zb$?>!!Yl zXOvJta^uc(`_@Lufya|Oqx5sf$nJ!S?TqExZ;jK>VW(ZxiMD52*Vf~|s0HXYdL;rc zAFs90biCtDuY097O3MkF>k6M)L?!NuG~$stfY18dqom3$x3G8B`@^xBCk>5q)~78V z+(i*)ER8gG&wUMF%gIt9r9lnckM}i)gOAtMhUyc5efi}XD(@{=YHgRF9V4_k8uLBN zHUl=j9yK7}W9s+E(8L-&xD;9Z74QasA-mG;ui7~H?19~|`qayFQY6k32Dx+xqg5>s z)Gf=QY#SPBO}8wyqAUGTcZ9i?G|1RZte=dpyPhLkc*Ej7&Um{K6f*Zh0l<6(G;w8! zrdhPlSn5@NeZ2%SjDRgz2mBC>=21WE!{w_X1P6oH)O z>=^ac%iKFY*@!rOi)WsZUDW#2f2qQoccz3qwd_9l_1Yq??V9(9#>3@qPh}rZKJFV` zQ_AU#bPGqfRC+%JNTchN&rUWwY09vBi~ISzn=ktJF~hC-z5DIH7g91~g?;AFc5)O} zzzwy)n}~u1gkZD8?h-!##Ve^a_i_qlF!iZYl@aHZ&nQw|yA$5h9jsom4quX3$XWkH z$CSP(^2JEuMy$6yesLjxFRyJf&k!12 zJ$GCZMw_nXQTuGDjGt6GD37j5^(0d#{lveZoI@WmS{yczPGz38pDi~KBbEwUmCB2{ z!ftgy0rh%tU+#h*t~`C-!j#^7a3lHYw!`1+o+#g_)#Be>b2M+>6xhd?KKN9n{YR!` z#hqhYtySWD)`rE;#76GJsuaS5WBS&beGJx@f~j_)$B><4D#}!9XTrtav}@fY9ZeWN z?#TBto?NgQ^1jO!=GD@#+vOP&FyV=YY88ZD8I3_7OpU4LWht^4Zwc&YAui|^Cclz8 zJ}o_bb@?v?R$Mgdb3A~_8!POw_Ox`nKhaBmMK>^48?||+sZ~+fgrrlZonzdrMAZ%< ztpL1GX6Mqh7@Vz)KB9K% zdwy1P7l1R3`kk~_&7~67xVEbJ)KC|OLL@o@&`KF3GUyc>@-VfyRasuBqUe~!CriI_ zfu2w%N}P1A<>ku~baQW4YVE{HW8)uCB?duid)M6JjvDEEI7os`(*EqJF1?uJY-gGe zLFuov5-u_}22gtLVzyTCw2&aPYlpl}>jc0D^zdlt4bHs3poF6ZCtZqWs5!NSB6MnmMj>IkDhfl;2Qi?X1`Pn#Kd4xAS zDo9Z*VvU{uq598S-r5wG9?4MabKDv9+Hjs_(ADAI-4yM%HRr?hnVm>1pQu8`XXPSy zJ#GuH3nPL@${Gi>d6X{DOJ$U36CNM8gSh->4rMHp|P$I)}IqlB*M@bS2|gkV8|1T5gQ6${&$Rm)^L=K<|p! z#1v9Iu~R}}Et)%lQsOZ*Q0~E4N=(){9ljCVyONKL2Ld#W zjlwOD6grCPXmpfSXE>6elOpiOVt8q2lDSaO?z4iuEo`h@s^$R9bUxZ;AD7Cr_3ESNG;s63UJZ=9+g66Hx`|{+4lG;-z z*Q%)1?}u+rbpFUI)e+5Z;zly^EIkm7zc|s)m3TvaS)X%f$`Fv?<5zFCtQ;5XHeGho z5~hRFkq2lqn9YAMKrfotKb(4PoXzRz;q!egAt^Lz<+Id&jTvy{Tc48Q+e-x*%4aPG zo4CS3(t+A=q&4I;`5fT`=p@&h`b5r!dFPL6w=WqKfcp{olX9Xf!4tCGwWikece3Qd z1bn_Y)!UVrx%8Jlf#`Y7;Wzu^OmXS06AjlPkLYa;CquQbli7c;{ft_J_8O2Mo=dra zWvV^OO>p?4Eqz_t$%7|3f5lg-9LuHJ#+!`f8>kC;B->F=nCh4>?>@+azz%y~&;BT0 z@LOK35NSZ(=Hrj8^Uk@Ub-4L=^WThG7R6~LY5%fH&n{Q?FxUQ)Fq z5~yM$Re?l1+u z5AaoU&%uSHM%&uzxIXs4I-&mQ7T1*C5(jQImHH%<1NB+JOLCA(5X`7!5(ea=_!2nq`9F}_+iBxW}|MgXCA z4nW)BvX}X~Tvgq%=65;`8ztu3Z+AmsG9xi#*)So^j;tppk}vXl(zPr~?RC-YM5o4$ z+|E2)0}WxXlqK~euVR!aGp~Usa-3Yd7u(@w<-B>{PApaXtSM^c1y3&YG$`=e#+t6U zzZM3LyWW#5yE&_$^AAF^^xY(D9TU=u&F!P9Szz@-dPpo%t09i2eyV0Ct7sHUxaAGCaHiiZUCgr-f;$*wnVVnW z+w!s)o*1)6E;Nw|w<;3HQ0Kj4Kux#o{3WBkRk7OT^70!|z3md5?qi{nI!urF3vIl; z+{EWzBo}W{mkdu8t#v0BkeY()~+m7igJCf4#x{W+t&jfIB!;u zFc&@lf;@zoizG>badVR`tE@(}bl>ODSzj8H`$Vq)3?#7M#x$KaX_p7ntuBqm%OK@+ zrPNX9E^*!zSbjBdUX~kmhNvsNRW#R#({4^vJ54)_$Z1vteTqZ#%iIDCt8<3A#wtom zJp2ASStFfR#%t-(Ih`ZkG6C2&L4++aZ^CfV)f|BwZI=A(5wydE4$0l7!o^P(0&z?3cqepNCb^L zoD#7APTWz+HaBVXTx?9{;Yx;ME7=LArl_pTUEJ!b-He1W*yGH-#_7x5YBPuW6GO&$ zmPY4NxCHSWBc8M|Og;eFt8CfO&*!~fFr@mx|L`?g7J2TAWwizo8U`~G z(*7hh256R!o^I=*5=IHpQ@1gfc&ZL0#~{hR_29axY{csdL&Fx2Kr|rs$Mu-mLJrsQ zVgr>Vys(E*BLfOD!(5vg5lh-Mv%>&Piu#3+aB*v>b})xg-sxoLyWyS*hOw=KGpqO; zT9|WW#+MB7-IUtR)5}h%YT9g>a#SHOB^b4-^bMRtC@j1uAo3`XX}G~8E8goxo0!vF{y?dq|T5_ge?9l*y)`< zalhXmJ!cNnJW$4utrT#!28NN^IHOHTg94yzb z6KjJehWCDZ8d?{23QHYR#7$HwS6$cXr@1_{1m<{jCkf@-cfmqyX%6SgnGehbQI3MFy1jPHfYq3_X&tIE!T#9zo`R za`3VxMM9mcw0HgrrOoA7+U&>0>9+7>=Khx0r7Y|17q1X4U|THQ8eSGGDFpU)8g$-M z)jb=GlszVa_DYU^{s8D#9!`r?J4=aP-`KHzYBX7$)n3L1F{ciCH!^~ZR%UO7noi~B z#Yau8Q@Oba8Q}3FVqgpXPalOxl-)8phi|_uLpS>;#k=->VMO!@xssN8WdJrrXawQL zE1}s5++0XfaJ%}1i%iza(lbkiW@~_SLn&M6U|VdZn5u--vX5Jt*~p9*^C)SJTzEyw zKYCwBhSl#JM{YHhZop-Sfz7Ook-!LWq^=5Vt!?}W$$J+ z$;uR)FHQf5t~laLwU&-Y{B{4?57~g6`Bz50SHQ~ofTNHZ$Ezw&|D&Xd81OYN`G+hHr#ZF|7SFrqWK-Z7H(tv4GSd$zNnHotPNV6}(jvq~79B3VSuN~=7} zv!sqlCwJ&oOii6kWyfE)ZJKbTprrt&SY5Ye+9Q>SGBBBQ$T(29!I0A?misE1i%#y} zV=j&S_W)o9XGM9&!?m_`zULB~r)Ul{&QV5P7 z^h!4K!tNhGSMH_t4EUHBdVd&z-JORGYwZY!FECPnlcW)8{LqAW!i*#gzH~Eo)lmhX zzCs_T^boU(F}c%yF@Wc^c7;-hRNOZ?5Nvq&R4QDyvBF@THe83B>YcjISpzr!N=%Zj z7SM$zv~miG&9Mtex?dZ3*}6+_mW;Be`R&>|)QjqjGkLL18s9`%Psd-C&HPk#O>cAwTG&k`xSzC#x zE@sY;5ZK*XZO2zwUmkP9B&Vty8hm#Mjn3F4UsCU*a znov0pj#hEnAevBf+Fl`Wb4C|CS;^ya`s zr_o!Ef&n_LW9{Zu>yGbP+i4VM8YLI)*aEGg10~$1iV}C$>l5Tmh#(GF#r?g)B7$U?=@|l4&;7Q-q!g zyopeVjmJbf+Bc{N#;O%&a5?;AnTV|&>Dyz<_VohL$2~`h7ZhI3-*$2yBg_9_A>tDP zW+(Ngi~i`VZ(@d7fLOVPO5M)HxdhY~) z<2JTGWhYkGmv`ol&iDP|AUUtKB zaaRpYPm?JNL$sr%my6?px8eAT^%T+e_zJG!fT;_Z8VLEp$vEe+cz`dU;K3DhvZRZhZ2DJgFW-j=Sul%_#mq$20q4z*ZoO3-7|*P)=ajuGM?2>@U!YS!4-Lx zuT|*_hGv4uWvRJ!H#?IHTxw22R_j!6!Anz?Ux6!5GO176Z?{GklaOO?qCZJ}434ZR zfyWUQk|H62jfX(R(AHr`NQAq^H!E78GJ1;AK`E*J$3jg!WNa#?YD&+<$^vEV2Pv(& z3HK4ezu+nT`3WtTKQ8QDa7Z}Xbonz0M{_K6IM9fB*OeUxlt@o`#ch;&JbbNd+Mqu^36@F@~OdH=61SEtxmtd(6}74tS-u( zRj>-LU$JsfDI{)W`{5D&)wFNn)-k0Rx$b~JAc0r^ySsbdgS7|5E%ACtTdNkuW* zH~p5vJmUQ{j;1?H1%k=xz}{1{4lXk~m)uA)iiT(RShCFFD|1MVB1ZEw!`#ayiZv~) z!RYncyvH9{i52B) z{^@X;-j^Q}v&wW@{nGJ!c*avGiD^Q8Txyd7)%jw9{SN-}#KO?3$`*B6o~c<^>QtJs zuHe4m($LA671t*LkHuM?9};VWwJn~@H=PLAG_N6+11J-QL|vt9cIPcL24em1(BU;O z!}PSXtEfp4@!JF6rQ&f_v8}KD69xAyb!_Gs@@8&DOMPFdf`bKLn^z647gRc=zEnw` zNUG&pDASLyp?sfkw5qEaJ#L3<{y-$$P6g*6zzqDrd|RU0QETZ&b!_kdfXhl8rsWv6 zE*4GrHaVb~5&MiBemS$JApt}$Hl_vNs1hF0`9@}+aMw9s=Kt8$U!wQ1kriRt!?q zKK%BMzW(Di7RB_G?DxI-uP?Z4%H#@N0|bn?j}XMYls#SWji^H3HE4(b3ARMhgL@Rq zsQvOhMwk6ZiX}C=npqTF9Bd?xc~=89;2HvK6K%hxOa=W!rJ=VS@JBDcKUMbqSIWe5 zNRv?ys%SRi&o6Ky?^PXZ!<$AJ6U|#Fi<$+G;r`X$?#zvxyLR4I9ViMxwF4PEKB@gM zIHC+L8EdVP%i`4Hp`{M%V2S(ZWaIh*4>0kD$7#>|qN%yxJfU0wBo=i-o&AMSm!cz@ zWtRn>;rkW)Q)>DD5!ES!=Gk#|9;c^`@u)9lPKqYe9ShFvavm%^8bf!OT=fg3v%lTc zAI1*2S6HJKReJ8lk4(8dkLKP}Uv9pa(^AUJbXNaoR9583Mi{$(M4*4q(sr?1_K-3a z?u|Gx9WpV2>$n$^OL);okZz(U<_TxO!mATym<$Tg{}uDOkQtDv=@Z_lUjW|RU{LBZpC?GiHJEhl(iwZv6emQW zhjTCf#QtH)PkA!WRr_mepB2K1PGYb5i$cOf_e&T@{$vJ7kek)zYwvWji@bv_htye@RQ9H}Vu^<}7=n35?ctI>35nq8 zz7(P~YU`wfPVQ`aZaOT~E@4WJgfc&SF_IqqO$n1N$qfpKZ%n*lqhH~z08Fke8s@bN zQl7Gp8}VaRG^wP_PTr8;@&SBo0%i>+6T@oNaUw`>pBU{H@yWNKe)nwHeI$m2DxvR3p4qyKL=)$ddgeOJzhk8!ae6M{E1W*`# z_&C<^F9g({Q)NC`%DDIE+K~sOr<;|6x%ID&fu-wnEW!z$0u`x!*Lm8iLczJZjLEXE zhmVxXht8)$*~JfG2W(-Yr>;Rd_FQ%#=P8$UJ5bwt`T4q?Nd}HAXhflZ)gk(0Q*d)3 z%m}2o^YnB%&j^YA!j)UJzvN%z`Y(uUrawRFzp_n5>Cs&RaB@8CthD+!Q!;i-KalxD z$;-1dh{b=<^MBnYkU@Cop0K?x)A1!-3SLRRaacMjcA(8BP^aNa!pte>(hi)v=y()F z{*#f?{+p39GFD5z*#@!}&xgH{PWpu3(uYzbwfc&0)_#|OIAHw$E4Z7t2PbUVHOKy4 z`_a4KW#KCuW#J*R6=rbK20e!;7jVRDqUaMv^KU@X!9m>-_bKFllrJ(wMO-2~^@Ah>`)c!R)EB;0Gh* z`Ez;W*hFc1?9<*JLXtGKqB?bF&}4S|oqpwB+y*STBhDsQ6lQ z-{oFo%;jB_r472Ls42fvky3Mn3#g1(cg6FTtil&@zBTQ?A`=3p-P~mMg_QV4cOmQEBRG%KR&H+WNTko& zROg(pf2=K89iE*@UT8Fe5qqEzO_>=NVg70N+ns2q`ys*gmA3ZGPPa$_p-IzF`7KVe z)8$2)e09o7Vk53~pFiLI-N+ZNPZJA8=QZru#@(Ha0FlV_!sbLs)hSz^jKJ zu*X=XT^VkjN4OqWN6U-N{D0-a&@I4O5!0Th=y10$G7>HBpTI{8?~bbFilVjLZ#t2$ zA9vxPy;^@!C5!LPhi5wGV_Nno4-ujT{4@#=9-$^a(*5j0+x|xO0S=ev4?y*2o&hCr zR{D?2W8)DE-&*WHVeddDrj2d19OMf=F>Oa6vTj3t>ayAe*_H3M4cpZMwt$2Qi#B`J zd)V_Rt_!zzPgP6OnpXLTyf5a+o-`iROSg}-S z%Lx8Ye$8VulNp1X9{y>5Vwu$w#}6{|+=Tl`8?R@3!PF%Ge(6O{Qw=D+k~HpB8-nQ{g^ysb-bPp4b|p zcCflkt^* zn~2;cc&((1uNdkr3CDXSo1O1JX}L{-tl3Qv#<%T`Fynfs@h>UzpWed0!1EhL9rOJ? z8w)&Rhp{x(#)U1@CwGh>8mqPs{knj}zQ3exz`9Let(tr<0r}s%&74m+1f1vIz*VFi z9F1|7UJHFzz?XmEOTGRJalR_?|5Za5_$hA}@s3W3{i8De1311?P8(+nEOXADN(^M*VIV- zU}Rc;YIyq4sf8nhDj=BS&umL#tRVDHqM!N0u)Z1j{fL8z#`9x@8NOKpY3{|IXLIHt zaEsej^AeABw^?oDlEWho9G$X`nj&LrQD|DVp|~mHd*gK7Gh3P6urtLWGU0dEUw}$x zr*KV|BJ>|R$hc!1y-z}$e~Qgb<}ZYLVYz41-c#YXVoN^s! zUykz-7CpL<)WG(V$s;XPb6aUlo1r$X$v37>i3gTDSbSaDl?JF~LFZL4CAK*6V3>|w zB+C41HhX)xpKS)?ig-3^oI$N*eCMa*k+7pBunN4b$7MZw)6dMKy}97HPTu)F3{ZsQu@^?@U$c;i+Id&bhCS zA+`4PRkUTbG>jXW8zlb^YiAi1XSS{D1_C5#65K-|xCD1gg1fuByITnE9^Bo%a0m{; z-Q8UaE94fm?C!IB_mOe`)%d8YK`njOJKs6iL16G(`lq(!iBtg^nW)re39%kpAE``DLS)zrvE&9Z{_%QLI?)hLv*bmNw3*s%~)p zPT|FzM%B%fD_q#*gde#xyv0!38)a);rVoBvt?Mz686J6Uju`8PJcG4@p6|Aie=cED z!Y0E=8mxUZm0^aq8nPl-mi{hTLB$oNuh>ch-*vw_J!AiHiTRDAbj4cu%3Yf< zM{!eBUQ5`?>HoM5XGKzXDZQrsHDsJbpY(}e8kcH7XP#z=B2&U}0z=_({ z8U0cSQdWN7b0?E+vpcplNd)5rlf&pO$IFnBRr<#l0~eI_-;fw1GYrLWO^K;!d(4)f;pZ8{EN*>`)REOf0Cw11 zQG$+N)@(IypG=fbgPKuYgm6(SST=6U2r2c^^LTP%W>(u9zga_ap^(Mdoh4gfkB)Uu z+RVJXl=CC+ASn}jn9p7}61u+asvMFCleUb!yx1P~Hxi0M6G;A>&s%}?xEdW7&K{`f z7!fH^5_}0a!x@Po@gteds}du7)ti=7Chk8tLPr_jwrVpoTuzXe$<%~|Ki!G&@-rZ2|oRHD$@ z`qHW3QrLAabox^2y1CBNv2W$3b5KaUXIuFS?V#1G6M13PBGj=4LYF~Ooc#nXt zuVe+tw5{!(^he(dpqrCYL1SOx^u%PK6F+Pd&;B;Stw*X4dU&92P$c6-o{BOrsa>MgonDZ!OPN-2vkqG(e#v!MOOTKouC>^K z0?sGbF*gmB`5wC3ZHpa>SLOqQF9 z7%nF7z#FJxmX445(PwXK zt%(=D@qBO{{=7R|m8ZfYP0M86voN2Gae261GH}DmwE9bq4AB#RysizGl!1PJwHB_W zy_99&MePKO!eMGz;T?HS*+X~KvD3QUIWNQW^qy-Ry7MesN^E-*@8-!8?xPZ!?~!6Q zDt*h<4LKf9utNAd;55G1{V!fUwO=Rs1*LX*X6um_p@tn5oX7FbN zcyvc5Mm7*>?-&%H0l&h9BnvqhUuHaP-%2* z&FJC|adwA8n8sh4?VF<1O&=thYS6?8Ab_}Ewho|}ITgvrMx^7MvUxbu;SRPs!;7f4 zp?r@WvLEM`zH4fb%-Ju6sEHYS`*8=DZ$hr0qeV7({#db-2LK@e^g;BFyqj-#ob+l4 z9=t57TW<+n`V|nAn*7A`!faSc5z;#E%@){_AWE1FxTY6t_!(O?yiKRk6~YkID!)_b zeLflHZd+PU9l%;H*n69ICGGkYY`qFrk+jS<=Lp(_jXRN=f&kE-y(du@&9VqTiSXVW z6y;kQw2ryGP_BsF>=?iC7^Ql!75Lm(VR<^mf>S|o1(|m5(sl6I$rLtxVpb-_$uoMo zCpx^gvC1dY#rYX#8BOfy&@1!n;E1nV1+Vsa`R4VubjybB=7)EpzcEQmo=&fLn^aM{ z@)y3A)TUx^n)T-gG%n|Q{wr&%(XpGw8Y)kera1Q>bGp0vi1VW*t<=tJTk6Bx7W1E) zqZEPxMpZu zw`XI9y(bJ+g z5pIqUxWB+zi|kH4l3m^cDuT{=VO_;`D_*#`g@JBA(iD9i`??g&y$alBA1%y*0(^(D zSr4mlyvcKGev~=Tn_RizVcv(V^YGRWRI>5?qQxwXNfB*w86%fvC? z-=2lHFJHTjB{eZvV7bZ=Xti%iVl7ITF7-31ud1n$%n7Eo)l^MtZlmc8tgNwdiNiFE zbd}zvj@Q`dibnT$rq(GL>)dnH#61D@m244ijxjh&f-0wurl z()5QVDvNXGRx~fbv{?%<^_wmelcmVgx1@8!FAB+JRQH^_Xgrin5n|e#WJ?=ZB(0NC zx>c$Ao2AKTg4LubBf#5GWKHZZ>*mWEAoX$Imyk#>vT!~E^J}=L`0lAjKOBW;4cw|# z+xtFLDUGk_E}ilGumyQ;^oTFpj_~+CPVa70r|BrW5cijQsG|pgI?5{c?|>i?*=d-4 zcC_PqIh5P>PaTLOgdrwZWX$+TUsvKn?Q&sXo+Z;cs)vq<4=I7fZPdxaW8P?xK3{PWr+_Rq z3CE<|=7*D&$}}a85@l!F^3%7=h^~I}UWz!MGQho1T`s=9ldBmp1^m%vB$_u$^Yr<2M1>^9EUQ0WqV|C97H^`?)g~ zL>AoEkGo_%?shTm8bnHajWJi-xcUp30ob9hN*3!)Z2p3Btw|H~^qCZsd6Pt9z<3|u z9!zc}dvv14>oSnV(&bHJJ-qv?#4SZSeEFwMk)?1FQ=Ew<{)ZOVqmw=75YWT3xAELs z4ldl!O2z$aizIW4M`R+&1>O`Q(|ey@%B_9E@oFsI)*;~oH)}?e+pxl!?vqsj!d$~; zUOg7+=ZVY2uCQXEu#KfA=r2v8;n+isx&eXjHI_pxxTu7Kc|>h;4)5x5MFyRs^RW^( z;`i1k>TOgRy9%Q5Oaw^kYlS@h;04*_G>^K`~q7#rkD45Aiqw98iCB-aUX&hE;S z)f3TO_SZbUSW0kfD8uLALbl#>BUC79TwVAGH$2IQIzjw6xxw1UQvqyLyuQftJkRxj z@*grX0<|M7;I|I6ox0ZP6|OQBInI%y;KcRp#$)sew0?=A{7_AGOm?A*pXXRbeP>mG z{%YG{S~pj4+hmTriL<-HU<#wSv^9_bi6p|bJX71>VB>JPYxI0eRL{iWmnHw8cpgJ? z*|F9QA^K`;=9E{+7;or_A~?}T7!5{XEvm(lh|lD(Zv<3TxK8P5ujt-hNsCQdCpO@R zTq*U|0ai>F`$%d2fLw$);%w2tknyMmM4=_3`*7E69$x#Ll(PL-2^JKX+eWHUYkdf@l@-RGs`yTMoGoc{(hF90RU>$MxmQ zDp(nlzZ{C)A`}lFS=yR%r=B`Y%f<-X$mL=smIm~O=YBkIR~1X354_Sa|DrAnk#O2` z!@R@6kXK@N*~|ttzgdOZJmwt;Okeqgz(+8kbr^P5kS9e&hiPt=`oK*KF!u@N$5I^X zdfns(gEN&@a@#v^l`3^i>=!Qo@|94x(!A}WsNcAmyFLwiS{OOX$%a6ef+ukK^io@azFq8TdVIPg9N-|R=T}_#=J>JVyo3ab#l~Zk zwc8ytR1D6Rr@E#3Y0DsdU^Vctv*6E?FfXrdm?RyO|4APuEI}EW*h(w(%tC9DD8E4> z8R_5PB5X{zu2KqG$LQVJ;mK59MU2T)|8zDZCt@cyt@?UyiKrb#2-t<)C+t)ts0;V7 zC42ZR3QnC5b(YRdImwG~q~6fPd`)NBl{)n@6yIh!`T0tBa6@2P@nfyo;MXqG8C=(p zj)b0TIxWQURP(_}d2BS$_6;Xx&^?FX$hC^F9cSena_eJgrk6~C+RZeS;thJ&a1kgS z%8rP;hxWKTEzXk9n9?cJ#+@t_^V0pbM*`{0i9%7K@S?@*^G{GGgJHxwA}{=-Jax~n z&asZn6s1W-@$aS~!qk*HWDzM9zkfTleKhbK@-P50X`;&6BAt~z3^P1bOrNl8U*CgE zr!ZJ8(jGLUifCytdMUTvp&s-#?GDYDns`1gg#C+9Ygqf|CwN9eFXs{g(x3pbh)mv zQl(j@2G5F^n%Xx(=zo1N-K1K!B#RvYT0z5Y1l)!P5whgC?SB4yP_@&`LGxz(8?;^E z3F3E8WSxtwv!S5$An$BYCcS;MML)k}&Ad!%qs0&jT&RndEgRIkU=?hdCW$Mf$}$ey zpWsu%*X;KUPq2=)(Zx5mc1|}Iama8{tQGcFpss*l{yOjGDPjjS<}$*y=x@o)0y^cE zgtX?36JVK)YE0HNx_k&t?6LSq1?~>*X-p2hWkiEj`#zLm*@xW3aY6LWma;uKoEBsn ztME^{8qB2i3lvSjcIQH%TSc?mZrjd!pb`7S0EewWIk1*m4f5mWYy1fR{wU#tOIy-Q z1vc?tS$EGPHLZJghLN{zsQ#s#@4&dB(9dSNWMgZWQ?}%9P4TVbg2QZO>$mBoI1&nB z$`sHTZ-oMS`9cFo=(~ex-W=0k3%g!g40YRWc{;hXczH^ubrNY1SQr07MSwL7?`}K8 zvel|qY^)=TJ>q(5C`K^pJ4KD7W&D$f>Ea`gM^jJ=gtBMvSioK^>f870WH4)z-Mq+_ z-$R_=<}sZTFLh)WOw~0XjT|w#_}Z;h5K{Nf0J)PK{B?hMtD`us?}HJ}y%jJ;DzSx$ z25vfw33C;YG+DDDw-Q(R|1BD11z&acm z9J4$ADuDNtaOBM7J5=^);lt-_m&deh%8zUsp3QhF;T?&n;-CXADjWviTFo1lR*j>s>PP1@1I>L`t9?u|N;)rr;H|Q|m$UJ0UA8WX z2zD94>dt)j<|(^l8}t>VG$PM_8VigRlUNbe-$lja!XB~l5eU~%uP9yEm+@CLS&Il0 zJmrZ2cL1_W#Qd_+bY{yCzya>Aa_q3)`zsxaoViOzi(;>VppS6`?cX1Ls({UXoYm)5 zsy?cU+(SY25B7m9!ShXnmNmT&{|UQY$K|r&8vO8_?(PFQ<Hi+BBU;~qM~6@Swftu zJ7P> zlPq^Zjmn9DXyYmkBjT)tP#9dk-pzIN^{Ehyojob@oeBNu>5d5jQrTGMr13`$gwFlV zs~f@so8>sKPFn7*M(O2`hIrs4wce||vd0C?#@H*EgDeSqd8xz>ekiHM;h%5Ww&H$f zV>FIRTtTtvZ#661b#Qlq&hp5x5lyUNq?c(7+DP9lOpo8kL06QXVT#wpAIQnZ#{KZ_ z_s}`4HrQ+iCwRND9AGIxW0y8-=g&7GQk#vlHtb?#+H+aa&5apf2;ncj2^@Cb9e;9Y zffpR{I2j?9nYD==wnXo3Psg&{?jaZUCER)3i`!0_~d z`i|%bBTvxgaR3-Oq}{iQCLa$Lv>?5Kck7d>K^PChF5_zTJ61G1LLLtx2rb9)}a zeG&^0ht*Et^E`&Z%H_2_QrL1w&K{(oHRdBwY~{w2%guJANxlBaX%HK`fm5QVNr?IO zLzG&9BUL{K+HF`U4L4Wp=3 zbfR3kdPStAb!4fW4#mNBH8q&TKHY>18LxmA5pH5%9k{8nonW-FLbk zqFZI7igd8h&ohPg!IOS;tEViREkxA_+U~rRRid0AGg6sX$%@g}t+Uq5dPBslG*1!X znec;6RypdPCYsx3+t<%()9$6KhU$;*`?!LK-HJfbWs5G$q0gMk{WgmaQTwMS5l632 z;qxqa`Y4eQNu@cWxuN#Yb(w5A(eNJ<5BWNrO;3e9oGb)^5H|w+3B-c>O9j~d{pqzi zMf2~wSyiO%XkzXy;FVgB&k(be5IgH=4PB?9Ia>{=iA2W&=9^-?L2pe*G-~9cU6_+e zCpZFEbu<$Jrr}2S?miW2QE(mVWzu!Urlw1U$vSW-pIm z%Kt`qHcHsJZ835;rhPtgSP$IoECdOp%xPKL7lkty#pn}9Co8;X^3;sDd^Yx{k^EL& zTw0?0-|CFlk(Nv+SAZnXT0OaZe2=u3*zBY1Eg544VxK>JR122*`*1X_4NE(_&MsTC zZ4ZXOgbyBwun(1bOE~iapq1395Y_LXcqPlLgqAOZ}n1?z%(UcDU1(p zT5~zmWmVA+UfZ5@uLHnk=~F&w)VZ>PY{@8ol4~B!N6CX6hza9x>A^zq_P_Wig_c-^g z*A{{qfxxm^E%E=$_J&-Yl@jT%c4bCA#f6U3n*dqHzgf8lIEIY$jOy z0NB`6Q?JS)0m=EO_ZT_>6vryQnOJr1NGe4S* zU}(4`Kk6Qy@Uste{T9m_d$EiNOp*z#w5M9TGjf2zl z#=mOx^hOj&byO*zm!k-r9Crj?Y%AOaU!3ZDmYfObCNfH_!oS?#y&42VQ z4~;a-%QAMVAt#zZ>{h%Yman}C&3&^7s_xoo{)(pQB-=9Kgu2=~Ws?^4dgEfvmKEBW z&NC@2)mEbi$S291%&0&C;2hegoU-<$^FGCZd&b}mH+>fs7>9jfEZtM z;Mluz^F>?}@VghlI5|`t3iTj4m{-1+)7>w7!9-{AaIQ$8EE9>7IU5?QamjG}$O?h? z(}77t$jRDh5ANt~r~JY&lhM<(T%*la7&iGUzTbcR2YjEnc+<2Cx4lL`%6*Gano{EN z$c?7m_HUy1bX47w0pPP);MJ|4uA}T_qJ|`*x4}YUt+HeJ3o_!J``R1kOdG3;%zcn% zg#n-7kfqws1H;_2({8Z_+M934B#g9{ZaFmOx4=yT-`3NcY!+w31^UZu?jJsbY4i;# zQ%#OZ%KaV$bboRKc%1Lev5)8U>FY?U6*JD>r#w%KYaCc{@qOm%3A6}I`^ZM;kpknL zug%@OeHBnIX6irA9SZLeT*n5uaRs?U?J2fUP=b-XkkNz27V&d&*+aQcw5UM^$&bj| zJLGcXbE;IFk*LBqxg?;kfPGm68w8>sEClk+VqksTh~DfY9wp44v5Go1$d@DTo~BHB z-jun~riefj6O$_(KNbf0drlf@GcU9p94&FQy0L|QP9KAqN709#twFs_63ubwLm^60>H#XT0M@d21g|=USd-8{)RERn$``bQhDY8p3 zk|sHxLna;wk16y)_lGX$8$NU)OJ^vu?>TR*#^QVwFF2Q+38)YK8b=uQI0)G`3E%bi zq;-Z1(x(@3RICa}6;U>RAA)x%cX4`Wo2K+RWQlXyEM)PgE7YZQUPFvxVn-LY!#8ES z{XU-JL!_`dSnfAfUC{VRRVS;lptVgYBKa$X<7+${A%Mof zm$F~3b$)350{qFpMnn@;_D$N7x2C3q{eu`a77gy^m*T)&JQdkIKakNJLb~QQ zu|o@M;wyJSc{AN>D^(bCbL{TPZo`Ez%-SE9={Fo)fV-; zwMB~XAxqbVc(OI%;LcP>RP}WgvEtlNT7Skwi2f5Y(@pji*skxh#OD41(UX8?u(`rL zvLIMvtBnM^DtVtqM37JCg*HUbD@0a_oyeCoTk4V^Z2wDErpf522p4nC+(ZmcN$Da*X4`s*5=9ga3zAeF-2}nww2$+F0boi)#BSZ0K!|SNHv! zg(H`UE{yw%!2Aa9d&!(g%j%p-6xwqe0wQaIE-A?L`f={Ra5TBQzO!Hk!8vPllKHB? z=q~PcZ?xgn;Kq6y)$G9orL{5KeoB!s=;REuCsA3myy1bwgEgMF zv@OUFFEOGLz~i8k^dJQimYiPiic{!ik1#*K^MEx{W)jc~3cQ-5UJ)XX z@w3zem|{m`NN8Q#C~8#6lQ*Fb2Oj2?E96U$R0C=R$ospk)>{OK1kB0-^6y$0OS9un}D&T z^D{=c>B@v?FA=UcglDLhZ#jX@Jg4e-5Nn1et!pP1U#u7w8bjyhtrm=_WA=10bz##k zt7N|8+m0RzpBKcs#fSArA3BTyE%X?{k_++G=CHOU;;6aARyK=j3yM9@PSnoj*s&@@ z$r_7H4HIw^f#vo1*bsb_=a-%@;m`3)C@tDJ;%9CYP~36YT5WLGxkCg<+-|BC2*+}t z-gWK%XEc`7{}qi%s^lJ>g_52w+*xaR`P+p%G0}8?T)p!o(Lec5E%=N%{U(*c{s`J- zBujT}(E{{m;I8q`^&_!#T1~5e8^=LRkfQ5J;$mi?IA)EMN1%Nb32b7hpad|fCrB3z z|FCZ@zmg&IavptQ0DUf7PI{ipq3fx8A&*UW0D5;vFIm1?q97k_9U3MpU3#~_TI%); z$s-Umh&mcZzqHIozEBTbkvg+9d+^}yNI8@mP+K(_;(M5UbnfQ4#MU51Xno|ZA$LWb zyKtypG%Tl{kE@5GD044ZkDT~S>aZfGN-t^xwZ_+rk(d6646U4f~tGq9YX;a?atAGPac9n3$xu4gjvYSS@X{)mu z8BQLV>yvS*U40$i#JY#!pN-!gc`I5S%TVFGm6lytELj)~4nHe?! z_pvF6UQxroAQ2!{mMwigWA1zY7WsRaxc>ZtF_q}V3Znx_)pTjk`$IPFbMh#~rxF6E zdGLurP&A_3Beff_OL(_$+Un8x`g-E-Th}-KUc$wOsAg@x#+BgH7+B8D+D@Lfb{~mG zBn<^uYDq_rz)#|pF=py2e97@2bmd%uNGW69+Y z_k^Nvrt%N2z9#;ghFy}oWigJ<)M(0aG82KWci@sH-q=C+%d3i_UHbN5K?2(^`zWNg zE>9hI<)sojD)%RQMXAY_D4mpo4rC~Ls127?9p`dXIhSB>Kim(Vx>u4RPAf>eb&2bD zsVj0)LKVV%h6P18>$XpTc#-RViT^z`p?$vWE=iO2N@wno)48e)$YmsP9&_Jf_$O;b zQ+fkn$j;a%VFm@`gWmJM5%?Fo=-?bjUWLsM;}bm+q$(19*gzyOHyfOnT%qC?70}6^p)Vx!5LLck%_paO0m92eeF@}1Y-z;g0U5V&-9oYL5sXLF zQiJZh&&a>$2v#2KP3vdW@!VlI4r#U)G1`NzlCr1VLQEO7RM{6Q$96EVThtxS(>e>` zZ0nvYkm7zoZ}}=K9;J6>CQs|eFeW2i!pDLwQIQ7iv^Dn|S=3ON8dmRoON^?O=$Ahk zvcEfYs2gEdrbOVPN%ftblAf+dBJAu*nAKJI^%O{9cd}0pzpB3#2g|SW=v99sv1aJ- z=KmM3=~r-j_5T++)%*u`?7fHVpDE3v{|{s7!tcgXMm1Lksaj_om6=>?yK&kt`z|Xw z)j8ukk(>=gZ`01l@}BL*yWetmW#D#URFfMR1#M66)UQmik;=4hIeFlM;d>>7^U`fz zj{k|ew7XcCjP}1;2&r;*46AWGnupuQCQ6#v;l8TH#V~qzHs0q3$a|Sr@VM1sXe$&n zSg+BYX-1R$ldk}52>Gl0sV2ij0aBOwi;sbzhI=KY+Xy>w`C}56>t2jvfr@~DT+WHn zKeCoIRhjv751}zmKFgg09$=q>#^aja(jw5J5ZXAID^|&zY~&B!lE!r?u~glnM|uC| zM-9&)56|Zym+ke5H50OD^%7|toi$$K0Apec$e5WYm}nDEcHRoqfUOBILE>j?=-^%H zs5QM{W~^FNa8CXRi(xAgJxwB#Jk*`QqifvN@NBom<=}#|v*6rUspiPfwu6jQ5ms93 zJL&#ksHk9@@?YvAPxjPWL@oKWIAIBE;$g5yClFLGw%`_GPxzt6#m-_B1iciW`#Lc@ zuPeY<>?qdz>KaN<0g1;1AAC?95yS7#j$?S$B9n%mtTVjy<=iuV)4|-OrrGX)D>5cc z#k>(wQp3|wt`3OgpMNFl)qUShr=JfU_{b&<_%+v%8!_?w{k0))E5)+RxyM?w13aq? zT+S*^!eL_fhA#?c%R=n5nLHeAm#q$nyclf&g)!FUci6$fhsN;ti_T9GPV)lJHfN#t zG>O+k7R@%FoJ^Y`V-KkY3!Zh@a@5H^ISsb(N*mYeTvQtxsC7cJ(D=7M%^m~30zov( zANixaFt0YvjvKyiPZ#U!31eF)#o1VCW+t?|49-{I*$koVrF5QDz!5_9$#;~Jr?^`V z{cyOU5-7XS(%~Yjd;NI?mO-hJD8)5(|G%}UKBQk9%*vJ|<;Nv{1eXB%8=>$RH#8gW z$$voDNzm5bB)A`>dV)maFtwxuOSG*Rrn}%jN?!n&c&@1Pu=ZyZ(l?g--Et7e{#+C1 z_rkm;lK&98hhw%{$@GJcn#{*{paPzE=Vc7?WQ(gN|5W@GJ=J9Y(U z-1WGQ#SVf>WIA{a9y!wt`71oPUt()ELgIxNUv?aOW*JG{u!<1*xfA$kZoOh|n%wi# zGwWek_I>;Mf&`C(JG*4}4n~7byEtJXU+3W>$YxU$`Rk@CDo@#w_fSY|!4~d@=6#ys zoo?BxeY+J#U=26a^nLr1XvT{zew28$0m-)1fuy65=G@CedycsyhMDh&{R9d?6%Rja)2q=qwVfMX!n&tTtq%8Qe@1$VPE~^C=Z9I+8P|nqwsj8e zl3w_yth#H40^o(f93V@{!|D~XKAslnJ+01I4ddSBOJp{s%(BTKW^8OuuIPf#NT<7H z&I@~r|87Sen{;;n2M@viEh=x0R~@oOTZJhlVgaU&?8o>j=1{N?Y11p0eAahQok{c` zgY>dESZ<0R>uX_yAeld7oOMC^ig$cpPg9iM`dP#xFFU*!Tdgutg*GJ0sl?74Yi^rY zK_%@yK9ew@(TE>h4ZeImPe`NYX-sMUyV&PL4tAErwnLp+DboiodK`5sG=_ws z=V7FEkoN}P%-dZgpR<=DyHu{~@ehnK=L)aC2)msh_cX$331m6B9)U@|J49GiW#a!l z0OZYmhNiJ&^-{rq;-Y^1LPZ&&fRHTA03IwTt|n#rE#c&;&S)p(=-j`7B@(e^b1v0? zjIbj=pT~(!m;_`ij)x=i%!Fs|5DDuY8{gHY5{JvV@YJqpBJDsT?%cp_vCmbyp(cPTr|o0znxi{*w&XiiLAl>eZAT^K*X zuxDSoaYM|fhBov(n!!AV{LO$?$zeC7v0}9GGHjU$$A5jcKoWl814|T zIXKKlvZnU~Re>aB$9@w+Trh%MK_!S&u^eL)&q3*YivulbW(v2L=FK2*M!0sL+N{dd$d;Nmbtg@S>~hsFpDCtDW%a}JQ(J{NS4iAhIH6Ew^A za6oY>k@$F2s=JC-2$wq08c>*5EXH3^kx>en(^{4IYk-*XbNSfHh$B^&IwS6*3C1ec z^mg7MrBNv?}|Cq1w>$ZZ4_Kx`Z4PJyhT^^ zS45}Q(HnJWmr1v7wHCuN;al^Rh@vKZ%FVq-ffeufxMN7yjI}Iq<~h}9gvKTJ9Xkmf za1hr$Yk!5HdGym1K;av=##V8UItABCYoxO_R;zlNbpBcrk__nN^sC2{g_DNn_kb;^@p|#Ucr*ZVm~Q&K6UPH zQ54Ub(QD5a|5BxtU4!vLk~P`FtO*1jxk#73-#(i(mjeU9y>`w58rHwp&Oy#)#P8TE#thqvv-Gd!4$YB!uAOr<{I4kOCQ=~( ze_*lxD#}0mF)0cZjXws=`d?LU-wEGUg`J-Fl~AdkQQ;lLs2qAPzT5JJSxLeZ9*KR4 z^x?64>v)@CVYYPaY!gj?xD|ilXDykB#v<(Eiw3>1^dxvioV6A zlBmkRgoIPFWR&}#J(m+~u_K>+ojUab)G5pA{bwv~uCuVkT;Idy%JCL&=cD3m zftcV{5_?)ve&@SINJN#IP8v5Ti}QQ((aAhux^*2jC@5@dJpn-fkSbB5_jd`|8vF^A zWvKGvt_6x?`OXJ`f67Jbd#(t+mI^K21re8HyQ6vrb&PZ$u(A;Jb$z}6K_yKkcszJ` z6?LQQ&Yaz4$Qf@MmTT6k(x#X$((w{CFAU9QZ$|pAnYNr_McqJrx!?3LtW4>$f&`S0 zswVV~@I5Tk`@~*M%7!mZ{VSx0vyE(^+q1~u1HcF2e+d91@ctVA#h$c<0$;=vvYXW~ z(x4ATCGMQJ=h@NBcjFadHZ{)GYSjcWN})lw~mXHtna^r2S>7JNtrIIZS4OvUCp z!k2QYakvAR=ayT;Relr9vbrUO#1&aF;sP&64XqB%fS{`aY5wUP@wBDtN1n?ePR^kB z_v>j#34H^4B&2M;d_wIRFTVu@ea%b{2nrzEfeT3I!Fa9q=0vLvWkOz&MqQuZm;bf3 z{Flww5MEY3zYyZSihD)8(ZayCb@Xr_`O7OGJxDM4g5mRl^B>u{wYgu%h zth*MFv>DgYh+dsbEUA%DO?|f?!ca<=tuOYDbp)0?0I^eUXBekKa*Gk)LrDfaxF-oT zQEunxGPbHNyReFcz46>geP(*T2?MUe z=YtHg@Otv*;~l=&16e4O^r!JaF9?(k0b z6RpC9eJ9Kc-R?W^8avI{Ww(jiv?Sy9sU++&v-RZu(&2XR6|V5Q!nP1!EPkz3*1Tno zqRLV^XFJ)X6mvHvXx-1b!<)Y;zr+=v6p;>-A#Ey4I)x$#F;>3+vN^Q14{`O;HEG{2 z8M8wL#bQXmXPd`bYC56Cg5i(=dqBMZvWoEY1|u{ixWDVnKFRhCy&u*mY50tJ)(`?e zY+{nRJIRB7Y?@b~knJTfMe4bMtPMTxu)d1(`JajPWKE zzL&^FC7L7x(<;C8a9)nQoIHeZ1F@-0J@c^sL2y!jwSrVkte|h!O?U={1uCP_P!M~l zgzWw6@eMefq^#Yoou26U^0A`1oI>wAs2a!~D#+D$k5=efdG|LIX>4smOYfU~c(Yoy}Z~ z0}9XD=0ol4%LhxnX;34m?oooPhi68p0pw;sttim-J&x~oR7awTKIM|@v7>W(y3+B^ zfC?ir-9BZZ?dUUH^BkZ(*d5q%=;nY`GykPU?U7g-=%gX6IZ#)6T;AFO=zC+g`z8!D z64}r(TZrQSnV&x4qli}PkIQ_tdR$3ia~SOpC^NQX$iUcHV4qFY*>JBQQ|niquJE0r zZ;>npitwUrF*}#s`8Uupj38AB3bX>yOp*(}DAfFGyglN5rJ>!M_`=P1!m#F?m{@+w zFh%ca-ad8sYsR#Zm;oOLBSEvnkni)Kjz&2PW7HH{Z(liF^ot6$(H-W~cRa%-xqu{7aqAi(T+-oj;eTULG-pkRDG)-41i1 zzKSG&S}XV%;Kki(AJC_Zh7=1oVKo9$ekyRxM04xQJgNyux`uc$fX;oCbLc^2jd8gv z)T4DHF>du4%QfZ4q+!WSoTlPp@8!=CxGb*LL6iK+VtreH)AJj>prp!>EMoUZc3p$} z-ipdZZ&ofcS>)Ix9^KtbuMkiDkIRd#A!c3P0I)B1futeqo+G^Th4vUb8Aqhp-M}li zJ8*jQLGlJ)LLuZBGAiR*R-!J)pdBtt3ZXPip#*WI!GavOin_~GH6%vgxj|+1x*UEy z2*TUE9#`W6W?v!C<=t(P5K)D+xdcq${x~M9+rFzKKVRo5|V^sr=`&?u_HDz-bw2a;@2GZ=ndQ&_WU)En}< zECk6*Ec_$!uayS0ff0B2MV+KHYA;me1BD1o}C?FPIK^IDOQFk71AVPUj}L@K6O zMvAgvRr%2!OnU3k9f&SfWzs&q>D}u)OXIB!TPVImRTM4OWtBLJusgdkTl4nwINVW; z-@aDvlk9I_`YvB!U=;QF`@v5#p1bksTRzF2!1BT2wGJ9IHxU8Z-{pID0 zK}tsbPY(?d)X-Hs^8sTc{EO|qH^EA&fZ#!ARpkmGQ7X>to2rdjK6~#a!|2VBx`O-J zR1kjcuIa3;L;}BsN>_#YtNhal00`bq zwmRr^(WJGjB%@=Wr($y@*ludlEyt4oSaGXzXGDS-<6r|+S07SehL-n01)0cxaC`vNb zk>t&$u9OS6nTIGJ_#HONYC#9q|=jmkBq5Yhg%J*sapu%4Ph zt)9`@nMi!VdqC|9dm5uufA_+dc-#2po*mIN?4Gqt9ZIO_x@*W0H-RwZc=P!6v|QjY z?0{ad?;bUx=`p6>a(5HQvhMcov7FimWk%(; zK5-nch9uZe=vGXwH%lh4eGGq;NbBYCj1I(OPd$CSiTSFHd_FX+p9dZHxHxn21NF-KH18z|l2Pwm`WvOW!v=ch)sR63q?K7AO?E z7%_~$XcIKDJ>E`1lwT7edKzNvLFsp>7zWUOO|9#S4!nJ9C*$aHu&65`*kWIVsxU`s4m>iQ7M@R*CX!R z%`NI$?{*)4a)h{-LzTS08>K|IdCPKspHy{2QF;<(RxuNSEK8d;)>KTFYu-P2-`=PB z;K;2R=>yN|V1$GRL%orklr>_;N;O4+2L4@bXu{E3Mj{ZkBgZrhJ?QuTK5v1NN7%o@ z-)z>Zd?EQxE*<(3=iLtF=gOXk8?y!J5I~4s7L?y0v zdE%oY1_;hkhJsD~!#RtX=ZBD~N4xhN7pnxQj@${P$vz89aY)>gh?8A*IiH2d{T&S9 zo>$Col;27888;P50!QQ{Y~Gzm>2>UNfte6KdiZV`kgBM{(@!fOSBgLTTIeDr3ybYX zQt|LQtF;M&Jj!5zI0(yH!TAFhQpBs5@B-_sd>Y#3$7C^jTUyiAgse(_-}Wpg&t9NE zG6d3UU=9K`o5%H%m=;M+H*ZM;3-e%OFS$Bvyxz9M1OK$wdHol!*R5giMVr4GVXj%fgsC@ z`BYp>C~<%OlpB)U4V>)qod0=D*1~KtHb>+pc^;~t-;8xtf`jRxXO7>PgCR(q(DO#H z*v$YU99gwJie&D9`vRKwLL*es-M<FS~@c6^>0(=gLGAHa1vf+X0W=eQWd7{uvAwY2%V~GRp8E z+b{9nQM&$YfX9%Li7gHZ_@1a_$OVlIADF%f`=1>25RufQjqv1Tto^!|dM&9*y;0lv zIqRh)b87OPeKBh;H6?|GWP8p&;2K1QUy0SD2tnZ03xP1BPI@GrjnajQT^!gU6-{Yo z76u;V1d=-KB4s9Vg-B<}6K}))aGXsZ$g0o%PtFe3>y(FB&K1BH3lGQBn-k6Vn6*=s zGCl1Gb&$qUQ&OU9v*^bgdtlz1yc%ZNl_=@mbP}Q1?Vxly4JpGX1~i&N3>lrA^yta0wC!1P>nE-95OwySuvu zZ9KSZ0T|(+&rD_@T%WXRbZrI zs5=s#e+Q#RZ_0%^##6Hv!(+jeXilb>ctvoxb^NyN`Jt8j^eI^v)YZDXL2TR57_a_F zG@2*(EAzZJ>0-dY8$jBJ9}BUv`JX6^ybGwoZqH8OekCW$qrvZ$La>=%<)CbF**Ur; z;d{u*y}n^m|m5wNS&=XS45n(;l$5r2z?^Lu#CQIG1t@{KrF-lv}Z2}##0 zV_b@NB9X;d;!B%X#MA#R<=MTvOd-WPVO2`;N0OOO&f*uIF@?hB5Z76S25F!0`S48B znd3{hCg=n_3B6r(#d{}d%4>iLwUO^VbQ+oN1fI0Hr!x2<3_Q+TCzek8)I)X~PN7^x zr3`VSv8EEQx|XXl^*q|R{V^l+ff8=|TgW%d4jgRf&+Atu)PcR%=7=AtVo|^9 zsGd-{m-%==?4_W)o6UKNJ_z;=88vir`=cc7+Alh19K-5HCI{S<+ed2DL{hH7C#nxD zTyA3Qjd6reru=TX3b8Fthq*Y48QtiE8+sTHo*xM2Uao^Kgy)QOP#-l>o?FA+9K=F4q zLv|WvG0$G&0d)`fn$B1 zi!m)BvYn~I=PI+LEb}sY5>ujuR~6c&(YX6o1|tpjbyHxx-fj#G(NQ9gi#iPe-DzL_ zDPLU!JynpzRpn{mcv+_n@8)-lfKs(rDgZU&Y`u1M8h9s_jeEtL_Q`Z!{tx4^t>!;?;;ke0prwUwgUPy{u;imgjU(F`u#DGH#CB4Zh&vJ*D~MK zVMilXME8+HR!FW0x0zQCFg=ZD#7qN+penz7wK;e5y4NU#>Tav6K@IO-E)+}2U8@xB zjeB|K1;{9JJ(ssnG?LdG9+bbe(`^)f*H*B7(YYda^>m+~QNiD%JmLFov`GIs^6R~x zDZWL78t1A(zrx9VCQaNNAclfK!IY=ZlTUeTwT7qh$(oq1B2w^_#Xn1C4p<7BZ>&FM zd~xOLQGE8-Mpe=JgWJTa=B`;q`v|#Zg z0V_^vR7R9_bF(h{{mAS1K6RWO_yF=)PEU65ijyNoDpF{lM!~NxJhXS${6_`3UAbxV(gY7%1F z)ga9w@nif|bH%#2_d=OFi*L_=I-0Zfd$sx%d3xxE&^vEdQ4(6lyp9SDo_R6KvcomE z)8Tmmae)zslA$pQ$fx5N#J?jrUz;4tMhoenihvo&6s*L)I87)t!q%!&Eva-_U3?r@ z7#~Yt6WwNX%5ManODgXlE=|h6es;kaEzqU0&O3C&^3J_MYpnjDOhdZ4k0JPGMWS^Y zecS59-I~~OI~Tjtm?n!Zb?~{Jq=|iqGRJZ%nwJi+;~_@e`Jx~4d2U5PL9Rzo1&_vSe$Ar|VCJLy(&ty{>fD6gbGF+(@I@2gNc zf*0ht5Mk}M+$1n=@z+ux$hA7RYbAWKn10^Wme=jYcYYDeJ<2qwnF?B*D0TR{wP+a_oyRpVXDo)1osE)vDCU~oUxK6FHDD5aEa~dwrhL6pCK2) zTxMR02Ia8)QM%3i*quL0e_feRx1;IhwV!8l`n)~uK|43lS(zUgN`X-XQ&}< zwA%r-sWku;vUK(g8RQ9{)K^V#j>n9q+;njh^tJkU{y$_}wss#qb#+7#aa%vFE>C}| zbZXYdKTj6|Ezvn!BcH=)4a3*g5jcwgbJ5?=cK5i0hnUuZB4VGHE#R2M#>^>Q-^BYI z74d8f*vm*%7UsLAtz1+6yp*%$_&n)1Ha2&|89<*>xldNJ(=2w_R2r5c|BHSN@;!R< z{|$dV=l7Z;z3tHx=itL@eiqv?zcMHR9#^OTN$~8=+Z4@A<%2(cB5LD)WVcDW9Baem zZrx-m{JcDP!;ogNhmG)iTp`CuwUFRm-pcsw;l-|v^%BUFgfL)hSpCmfHefpYegMRPu94|bJ4k!6w(C_RW`g~3LeFwJX3UR$J2y_)3{n-w@+60huS>J+Zh@w5p7nIPGBa#!!-wn_1%W- ziIMFu66^gh30lLeCd9U$31Xg298VsMto$_LhR>DCZOr$eEg~M-G^dFizNz82=7a~q zEgxaU{x|Uyl3*{-JgH$ngZkTl;ySZPDXZ~;*7CFd3#TYC!t+M5$q^EAxsn{$ZcdW62OPeKCuClqzviY_Xjg z+7=EFRM@zPJ0u@;d{Se>X7kxCjg-Q+H>w~A5}`BoR_KX;jyf0r$_$&PR8W(GhNY! z@5v}d_GKJP_*{wB`@Qja`nIN3werIjeoLtvl6fhi z<492Tw$gr^UX^*p>_4X^ChFlPbnUdDgTY}(~T%wbpAGzk5)D5+G5wHo@bsbg}0-7m&=YZQ3&V4 zp+(osT@wnZkT0zn($KBn7n4p zA;voR;t93W4{N}Ml;7sTeF`BAZ-6= zNl%W}+J9M(6mDX7kN53Rwns4vF4z^V1^d=f|#|hwE9lZ8` zaBNiOrh|8v(lMIxAo&|ZCoxisq_9LRA84S?G6bCX^7hT>)(5#9j%|c7-R(rXe8!;< z&0l(iTxw)EAHQ92_Xs7#RF!yFp%F0idS>bdT(4|tc1hN5v1e1ICNaX=_lrB-GZK#%ukR~kE3`uZ{B!T&QGfR**9YO3 z`?Sv|lNXV%6Gc#npsi_rXfFpR#zH`|NBRhZIT*@7EX?PXQvasDF;i^y1q*>ULnfIabYM1gSQn3HTH77md z2$*r;4o=8O%s*M_O1dUb!Mo)~AE?+0bG5V{DpHAYJ-{}`f#gu!UmS!G+#0u0wARX0Jq0TH=9(|RXITICiz-4JW!KdZ(wBgM=- zr*yIgWfx4HG;FsBOXK98TDEF=;l@g0-7fY7L#EoNbxv zj_LDvJy=loKlNZ)3tm1cQH|RJnY7%*QS6@|C!*cHW=XX&>@7ocuTDQQx~&KI6#A73 zyfC22NAeiO&6ZlK-k}He9ZOo>NMA&A&%F^ob=pYINNpmY4*#oQ4_c z*}Zmdgoq1%@B8^D>D(mps=F)+t>+c93N~#6rfXLQ5?j7yNlV`Q2)B=tHZFXY|KvuH znQtRPLwy(7A1ek@iY+lD86B%E1K@a>C~F1yEL)@v+$EkJQ5*5RV#n)GRBGeG*6SjA zo%wz&4w|ZaF^9mAuS#!_V))h&#VkDbGdcLNsdx6;cVBbyI`VvBSTyTC*;jnNU|H!V zeFFwYKqDb6pp;YTJzjiY=57Dx__`;#(UGBY!Xv_+FFIf`KDn_%Q0x7#W<2?cndZKL zf&%!!$J&fvp#Lv-K+7e_9k6djpBK~lM54l5>o*Weqd!!@JXM{6VmXneSdOtvF$QXi z)sT;9sZ|L<2AFb`D^cEQT_Y7UHWV_>YVK;U56jg2Z89r>A{>jiVxR z9{!$O)v+w`Gjtj^bro{eUCA_OsZ`j-UMW&AEx(&e2yEz=ZUcg(!;6G~0$ z8{*{q!x zX);{{1SMp^Z7Ssi1C0h1WC*AUYe+p@iJ+mwO?@h;wu~h0+gp^Cl`*cl1<^5;mHFdn zhw5PdjhVFqV&qmR%qG*F`^}wFk6mz*r(l*`% zx9cVQcfhE8UAbmRMIum8iE9A#foR`7Fx}aJu zC1c_+9^41{%A9??E>j3mHiA9aHJXuus%06LWEneD;r-l}t`Ljn)6) z63`Jg1^)I3kUrn_g?|PSFyP0`l~^-vz6}h>4uC=JBdn{u9GWBCcq=eQmz}?uwWLI) za9ho0gB51qD!$SJ7}cO=8T7aQf(+W_<nEXK2&$0T+eekWnxY+E?_?Vfb zi6B=UNy81&yfx9S8NRY4ZK>{aP^&6W&vL2vy+v1LzLAoF*=$$^4RV#GR$lc%3_sL9 zh)QZ7KIt<|$DIe1ZRZQEEEnJ2{JN0=e&)9(O(}IYFVbuLLVP~9{{f0i;<=S+(%I7i z+#VEp_%wtaqX0VvwPvdNdtDRrgEn@|%a(D(EWRjxhRJoO}S8d*hB(UGmjySgDf;gj>~uVUW|Rx>izO@9ljY1 zwLUuwi|^~+fX(raxId0AiTLg+)+w^eZ#L$u#V5#s?XhjfBnFXZv$>DhNgDktHi6VDEUmXc74|j^t*zDj)HATeR2FJ ziTtKXJd-WH0I%rhw-pp@tC8Iwxom2UoU_|7_yF^rwqjQD|D#T>{bEk>zk+nO`cG!< z7AN_r5}8f7u5-wLBY5D0Nls@t*EomJ}W{K3V#K%AoM4;7IieUe( zb8p=8GofVQ!dk4Sg7w_%)XLlM6vby+qGw`h2?~GsO?E#(!S%1lOr%nmn_K!(lE13%9=*;zla*lLgWDw_I_r09WH2ZE`~{dlsu zw70(j9yBBN-`Q%|p+|I%`F;{7m!LW8;1t2#JS>_v{uS^tPqVSjBWV7+tRVlzd$aE! zq$xMvJ**n?Z>9%<#b79{lSu|x?seesP_aUeM)o#8D{MFCS$scny z2Cw9~D^WI=`COx)>0Be)R^IHELU+c+$%o}AleaXme+%GPE-_Q`9IiX?q(1%hc<-c0 zb$G+%OZhjk!Prv|a3t`a!HM=)vjqJETyIk!be?D`R5L1-Mo`*Nxf07=s>r>E^Iw`H zGjFgVO>g$$Y9)K=O zjDhgtd~$>y8h`$u4Mq~@!|x(2h2hnP|9TcKiElWu{;GT}v{YAbCu_0(K03o4<>eGSFAJ|?zp_B8&f{L(uHo_Ggb#&-^7Y6$l-%v?38`5l%qa2;C*jln<4k2v z^Ro&k1i2i1jdH@Gy7R;+FnoS_9zfsOwDtDCM6wn{=JHE0`se7;O#Emse^o=P5Vh71 z7!kvM&Lf-?UKK=hjswXcDIYOe@P)iLv2S+)T1_bjJp)ruLs_b)o31gdoUk0O2(bgT zF9WCTA8y2(gwA)|S_heycd5u>0k4>~4x2929t7!eNbO@UMd7HctG3k^Iniu+S*Eqx zT13B0CeT>+uTxtcB`k9tUF@la;l^!EX%DeUWyTK6-W5 z625816$*5eGo^aKiM3*7Ud$G*`*xELcb&(RjNHskMY0H-#HSGErXRL!H zJuPnluPpQ;?&Fu6g{AlMqZ&$40qLe)mfQA`7ntHK^T_pzxWl1uwr^&0ER=R~9h}kt z+wF@Eg`bTm8hDA=4W%i-b&5IV@Mw1o5AQ}N1oPbF0OU7jfyG{xBrev_{f+1hCV`fN z(h0Y-LMz}9Nr}u^JRLbotH%g1(HocN+(wu&KVu+la)F*wT6`Ll96Vg_bVNVg_8YWL z5i|mnGO9IwKWtYFPxF>_EFao)yFf-0LIS6wUFPB1RCn??>KEfd@`an&b=kUrpgBSG z^>|W~K~xhGqe20uv;yZ|<@H`x^Fap4Vj z>}&P2p@q=KQ>zq6i2a8JkbNPAR1x3umVeYz75Se3Y)#$z(xCM4u=#yZyu#s1M56Aq zv``U5P0H{W8;ttM-ir9x3{toKQxb~HkDSmkPgQm8DQLRBS~_nq)I|*Gz9ppa+u6uR zrN`RAtca_mVW)HQgy$13N6?#|6H$i<#I%2CEF0tayWRchM)nu1k>Abs(z*7RZOHL@?>ZeB4l1Ojvm(oZV;*xjwBn-C_ zb1cJt*O0?Wb2N!-+K?(L$D2#sQ{BYaQU7$E+B_WjMnZ&R}(XzVuM)wuFWqs*k zE2L$Ya9Hy$8|c!8;9!xVr=!%rCZVIoF4K(Wt&Z$biqK~ysys7Yl*hE=!pONQY_3O0 zTMu73jOJuRr&R-44zHJ=JH}(w7~Lhq(f`xHNE&rl-g__{zT^;rg!MIPAK4M}^7m&ih0t|$e*Ws}PTiGtxBF5u3Qw)r1#*`O zBcUe3lw^kz^c(+r?D8Ekkz>metGQkSLmytl+Nq;rTHBEUt#tnqP^R_*&aB^r2v}Ei zGm|Zaj+MY@fTE%o(fQoW@M$WdiS^=5Qyf;AeYFaL`W5Kb6QS?jRiQlWJ27D^enb}L z58&lM&PKUtGwwyPIIgxaZ?GT37jRC}Er+_|G@YLaF6!}VJ$KvNN|k5cx?Hh$*n;b5 zV6;bmzt#BkEZxMJtgman>M1wO@U&;DI-xsbCXYCrf|vs8ag1cq@fn_2q{UBrSgh88*&E!M$WaL9*FK1nE(UIDX%Cs;IE4>!g zs42ptBjhq*Sshx}ml_MWEm<#CzQflRv1`UkLPm*Q?iM!YN0_Pc`p8eUEIp$Gr+gzg zHONkUM$E+MNA>!yScJp*>EqWE!iUMXb>SM%8#(r>2o5Nqb0yZJF`%)#5=DNj>HcVx zY7%^mSz`?cs?6(+00s_*l-{6t9bDKoSoAn~;q7g}3?bHUJucI^)#FII#Jn&1ia5r; zox{MVy8KDs_8IJb`BThD94wb*bm7rFGeKr!CpT(8PAjIw_pK!3vbT*f=)k@*FX<|k z2%yFkr_#ihI*s1xm20#6eMIDw2@A@HrQxNCq@U}g%R@jkHeLUXVf0i<%$C*N!PpLV zf|l6tIt6a0LqeT-VC8xK5ef$2EsxK34=MJK;$~6;&9q6wFq&IdIprjbN`Y^#tyVXk zh%#DgTeSxh>uVyVOZL5Pl$fVTu&e-)TX`bo4ur=~RrPcHHg9;(vwE+UP^h@vJU+p> zMxulxDrkT|Y^CBJya?8v5vF(WHbIcq^%Wskx;Zq76BX^n8Z`~xu@|2M4LZ2rk zylzva*DEzUZNT~v>}Q&))#CF#K5Q~d=u!7qbtDaz(fYhW0TkqBYi9(#vc`s1Z=ElQOPHdM${9ceU!dybVPQzPKx#psF z-lq7Cr<|o$TzKIQ`EdQ`X)JjlKeui=%B;x&9cFnu8hx%AWc33M7-pI+Ds3bF47?NT z>~@D;zSr2g?Sk-te_)gE4C09y~(n={aM z2KR=YbYPDevDkc{yOUiqSH2zU^T8=YJZUQ2yM2@?M_N5%zDkjqvCJzuF}FxH#?qKr zys?w~GK6(|q?mV8Oei64gDFudlE_chK&(583*o%?R`S|M8z#!BFv#QWwVM-wcVuGh zDkG6uZQT7dRV(L-Bt1gtV8%QO1s?97AJAc6b?NORb4-91F~id zbunnah2k4Amtzh>ZTv(U$Z5>09cp^&u1-4cN{RZ~s&U}4gtc%f@nQl#wEk)9(o@G^ z4ok@W?4HHS+l5QDyVL=~A2qeUhT)8!$H4-*KaT^OMTh<6d*ZMTnN|A}eIe$&XPELb zjM79Hb*Z3Yg&;MF4W77hAGYtfz%j%uc{;EVe#{S{qzKJalkF(*?%{GE)b9Ty zH`Q!gR1l=yU&6ypOl_{cI@=uTl&O$k>4&q}vPYZ+s+tdzSPC*jPI4eBjks=>5!qiI zAdMTj0iD%#>;QqV)U1uId$b5Yv3Z*vrFqb~RIgm7pqxEoGYtgg zAv;t=Jw^s_poDG9d29Ko(Vxd%sp_49T}i_6a{THdjBP2>Eb8Rdl{>Q(|+^rexk#$$M_`q?H!G z)2A)TWgh)(yeyCo+n9^fb}ajW^O8XW6Zp9cLx(Ndfs4IfJ?K1a;GjAS(@9xm&;nuQ zWtC&<)S}J?iPoEesFihdT8sAzN{qn+OD&45j$?oU^N_x;S8uBH06xMJstv}QNNn$tD|;BW9eFr0=#m=1^So>9Pqi)hBJa!|c6{ zS0i$dL}}&aG;rikl@GRLH`;+FQG-CiHa;Hkz-~KHsEsdBLz}|mG-C0)Kc2|u5fL42mD2}swDobN}+ z-nOjK%AA?bH?kD+QJJ#h_+qOMHOJek!;u5Ekno)el0lE>ErtA|h&@ZoXPw8lo5 zu7+vowSn&s!(G(zv%L|}F#4Jqtz4OoR9E9%te)FX5UMVyU}Z+Fgz?@^b;HpJ(?JbO zQjoYB7qWU=umN*pH;D&es>(?edP^vxD^lRfzDpK^!Lj@>FAOXpA@Ml+!&)gHct5T2B61U zNL4*JKla-qsNsMWzzPN9LRb{~HIaIS1FM287!ok&Ka2!+OuFTv9De)uRtOu{NSL~r zLROaSg}`?^5C9-C0U1G5-za>g)mAbDPWPmh@F`ci_V3va&{Kn-*S%hl9G;KiGdJP4 zMgQbN9BgHzx1ko$Jb{o9RmL+5f63N_d_H@6dK5CZ#~rAQ7O5sjPf6Zb)SLk=P3jJ| z5opfiPQmBJODj(Ysdi6aGW=69*_IMv7?zjiXW2r+)5hB{Kb`VLu0OT$t*#M3fYDI} zl9YyyA;>bH)9+zkG#!hXw`L~bj=Q>09Q=TKuh+GbYZ$!BU4 z`Bs#{5*(VcQA?}swa!%j)_zsDSN&~N=$d9p$aaY02?5S)hnQ{XoARF!=& bFr$UxGJ> zcUO1Ueg9A)^0H#EP*_kvKtQk(;y)CDfI#(tfPja;gMYQSANb>a72h0$B$U5@{XD-L z|M{w8I*O<}D%qGix)|7-0GV0a{4$|+FtRr>v34-Gal8cWb?;re z=bre$-#suu!52*@|BxrwaAkD5glYTlDMg`;w?%vQx*4x@ly)dGnJQYy!b<%VNy zU74iev6YT7mZ)#VoBWu_EAoppu$NzMx4@3*x@F^!I_mci;I+L;ZC?R`rcCiguLCK9 zuM>cLRS~|93@vH_|NZ;7<%ygimj3@%o526FN3p+IWAf21EXh1Swy z=jqxwRd6vqRArJl;Ydp6wNNZ-W&F&I3cy;4W7f&szkAM-U8iWvZ3To|KJ*?KI48ui z!&vhc)so&LUvy5Vnp#cxSMo_Dp=Gj*66J|yVGEj7GW2+?iH%~h2h3Mc>go(!_b#u~ z;CTG(FG_-ZRkp_W-NOHK1h0lX{Ks95_zXTEcfnqGl)kI#^qVzcHX3J9tGN?W)Fobb zyxQfv&^a2^&clgWMyH_d-9AvFHM}A`4Oai0w{mbX%_5EOtVj5 z8}79#@Str5jA*|e+jJiP?H0U9XWF~zXqpmN<5F{Q{xWZ1wPa(dB`h9E%XWdi`1-j> zUI!x*P_6c7qrpr=))!y7{*G9-~52)2u{4V!g7K)aFy2sftu5h*E5HSTF# zCn{LXhqR{^Q?cV1f3TiR1P>X{>}s0uDUy)}O|47LmKOkSFvJt^+!9q%8NsJG;cdD1 z`@oLd;{2jyYgIya&SkdX_@d736}k{^eEZOD^5&x3ilmbvbcI&f$u}Fz+}Qh- z3N&i2-;O3V_q2QhHn=KEKpqj5To12<gdmT=1MX3ghAD5{Qg16Oe^I>D~N&@Nq#&{_~|ag`S@Wh zJnirWg`871#SktI+8*z9a$*s|s?>QKF2J=sR*7Grs|O0I(#|CF3f8}tt5JP&*(s6nI(0B#EX5;C4R19^pA&Am547m z@*qEMWyNd8f{UAP$PAUNe+$!t#j(CH2Zuy~4oZLjhR^9om=6&$eyUTY_DgRs!)Hr_ zt(o;nN&S+}UZ}@5nPe}Qq;2A?o1S*G867EMMP3-TToNBr%vOx)biViEBCv4ZkWcOR z4tl8YNH4Jgv7khXxV%|DHs!bz!&QsM)9A6 z%s6KKJ38Jfv!5>gc^{nqMfY8P6r_7AHnABw+N88QTj60oJ0@!tu7R!y$vMCO@OMgd zXy%3dck11z$Jxgjnjgf(me8X`(q_|zC`E}?lHI(n4*TC)*x&{Rjmcm4fZ4p>^h~{x zg}2@KkEX@sFx8HTpJxqb#KPU~&`#zdyUGq?QJ%?13%!RLS7*Y`&050jf)g34tgmDJ z473a}z<*0V|Gs)KzLmEe)4%C6m&bf`W1+%G1_r-XYczW#U*ov&Fe;VgQ>9ty zb$6r`=vDWd&lBYq81{f~z~~Z(u6ZJ3BFkob*Lm}HZaoX3+-yZcZZqcX_-es1^L#bE z#X#^W8P~Y~%&(mh6S@Ry?{P*i=S54z$g>0 z^E5n*>Jr=CP@2FNai3f-7IOcZyJ~$Gy!m-(uzc${L~|8)9vmEKIDBCZo>o9uazwDE zHE$l^>-7h})B@gG3n~l(SQXU@EkD4Mgk7%g#g_xTPIPo5#G91R5(Gs)FuCCbcoN2&|t^d`Ul+h1Zx#-`{96>|2B#8?YK64Xao7zv!$ zgwFd&oGgChUO@)y=0!c6(j=adEqfhQ=IS>1Ap=`qJwxNY0LlJ)pkRl2D%fLP7{rlj zXzCpa^&IGMW`ve3A%<7Ahg)9h;eCu<0H1(mEjR^|_=C1I7#o9Y&QL>afkP$=>$#L@ zF}gZ4;~^zSn-E3WCT?q6Y$~}@%vB$nJa(FfFx^OBzPsULsf>4=wYUgBlC3N-3yBCA zE54B~+EB-mmu1Xm6L;#lm>*LpehOTt)-V85GZw>KJXA6L%1CU%k*+{R zToQPI2)4f#uX$X!8q=GUgHz0mzkDR< zmSOF&C-hH}#d5Y^S#G|JoirrHmq4Z$6yH2hZawbz4!K1cPDdkugk$u_3d0Eq4@=mc zbWjGa$#k0G3uwLJ;mh!em}Y|J*}&#M#s0vA?;)o%o)E{T-pJ@{^MC&4j5k7k={*tO z#@ANI0jUx-(c-D;6mFsMGsW|fk7tj-eL_n+Ryjd1$?L9PJ>h|~F|M5Z+_9yS*9j(= zvjAw|pssl}sf-q}uhqUiYfs`mGNXy~Q)|QXM6RYl{{n+GF(%A3dfofG)Gn&d1Labi zZ+js8%yu{0*qTZ#1J=oGvx`zFn^*US=hVIn@58jy<`lUUfh`y+iJs{k1F|_(kdx1L zL$#}ZMGCAw?d{w`8AhV$4jTLk=y}!KD1N<`PTl!nGz!53$AuDbE#mn2?}d9f8s0Vq zt(UIuGO1H8tcbz%+WyxZ7*Q6N^Bw^m8{UND-7=@rayd3l9UI#{qAVvdw+gVx7o?dI z2XR5*V!WCC#7c41S@5Oa^=t~z**bp=W`Wis)WjS@bKcXO^YG>=x_X4!B5uZvxv7-^ zBTNnCf3ks26C?BNJUlb&sf6WajDT`IhSW0wT_>R16$kXh2hQzp;y2oL9Otr^(mhpP-xR&}!x#5tQ~x-QHM}>0ukdQo2iRYrtT)$M@gJ z(clwV{So71ftcqAiwr$gjggP%;)Y%_bV$HJ<~d9r)e6+3Jgr0KC=`c zly$qEM~Y`Sc)+Xf>y>7te`}wKwHj9GLPxAr8|}11!s*Mo#EQ*Xv?K9{)`zc3(hH~x zq4CA+<7xNinTawVop^B0U@>exT?zQFL;^k*>+%0^eo@PUcQy)bE_rgq4*8>DaR87LmUG3Q^Ce7o`&%y zp^C!U%Yw%i$+NuOj_q_B->ne}{%1vKhO_Z*g+crR9|)R^8iq5e?j~li<{dW z3bK4E$oOV(x(kSsoYBV>%1IgBs_`g+G>7dIK)PGU zFxJYm#Z$7haRFIqD@1BmS!Jd&EYDA)3~%ZYkr+Y|+-@&fMKCudPUnYv`po58WBnD| ziy2-Oba++Ak(sGzwab1Z2=T+Vs-(O>nM?$EP9^@PGtmv1qIBesAPHl*QYp20IGDaJ zF$$G*P*|~Iv^Us`WSudpJX6ZZ*A3b=6$n}p;1v6`oO2V~F^Qs?YBDqt5Yfuih*5X0 zZHhY#N%6BhLe(iG@^ZT#Yz1S4h*$(UFF`xe0?h1$wK{Q939RlpLr6)L5jBQXW5PrT z^Nt@)oS0$}t;3c}Ab{Xi5xSYF@WN5poTcc=Npo{H<8_JFfE`?Ip136JsNe$Eppod5 z-)RfKi5m6GE|?C4aOF5~*&N|umkq>vl+)9f&c!j(-8JM{WmlTD?^dpIf0s0LvcN2O zb|KHB1dLCDPF1~t=TVqW-7uh8w0IeCzwlPpum5n(5_2XQ?CH%yCXSU(xiGek{ zkF=yYd%I*=cxMRV6#Iw*1*qP>K8|X%UXy^y!i2+&YfbeU}WrDhh@&!%$LM%R}u zejDu8L*1u#V-~`!GMOsrXV6_HuEUd?lAngsYOUI6MpT&8YBh(QN=Gm97@JXXTNP;M?wCmqq*$Qugo%VV6}`@JR(+PFH)1aw+s~B@;e=*C+RbAdA~mo> zA%4z3yqYMVD=iKqeJ?Ha^iW@}pRhNG13k8;W~bXfEg?8~zy%vsl_;~m6Peg}(P3u2;S z*XZb_D6YNP)j5eNg)&??J#-;s_LCS<@kGeoxqHSVK=o+Gp=&}1JHuTfuU@sdsxHZg z`4P~wlp{pd?J?CTuT4}Gn(8Xu2xBXvD5t%>I1N`iPt;eFaEVfL3jUx9 zC)+X>O8Hj)oxPwfj5PoDgUbgbM9ZNjE!ZgL_KKq(yAlN2ax24l@y=yL2%SW^!X@Nk ze@V}Q2*GJ-iqZ>c9N5xL!S2Hlw6sh?3XgDq#L4v1x6EIYfk`37cS49{^<0#M3FCX-{42 zs<6pT_mGT1`xrm2>$Mp*`Z4w6X|bY-Y+I{~u<)08?cC0Ux#BQ9KKDCHJz#m2=n*`K zJQafos=H}_5?}j7y)3+OcCiudpOb{kf?)U)&Dv(XeC1pN6MBj&t6`_*W#LkWFjGwI zHTLJO8`x7}?zf3EXTIF>4RXXiCF7D@FR~(wlmrP8<5XvHo!e$?h29d6z~xUw1L9e} z5gf0*--sqB6OXT3WlQf$piLmZsVE4-GiNW@i$(H>Q9jU+`D2<)Wh`+$ZyjO$rsT^@ z|M^8j2=))U9ikBJTgXo$&%@@Y!$^0M6LAaNmO$fX%rRAQ-N)xenbLnW260>BBBw93 z;x1`;DN`tR_5M~h7FHA}-HtGobWw~BN{E6x?XT+{+$SDSou5pkus~&04 z`Gp*63Peeb-ACue|kz$hVmq#l_8?GO{jqFhOU^Z07;#9Q=sD6Ud7aX_GTnqBu@ z7*eJ`8ES>spxBh)LfeiBP&DR-6_EWRDZY$}F{ykf9u0Z&!~uGd6!P@O{ZN!KsjU)T zk_Ji1+enOgi9GC@MbU{i-iRn-jTB1@T)9@`@{1Tw&Sr1T{LLZvI*EtUawaKUla=Co zd7$2eMSc&<8V;7TkNSCI#GP5K7AKRgE8U z6Qe35i58bBU_&j8%Syd~4}Db8PD)*L{TmSG&!c|u8iG}ptE+*Fecb}sCwX);PleEocqb_hA1k2Ax$?lGZ)|1*e;#NI)qI4{PHd7F9XYbBeKOF4-v+KU zisa{Mn3$E@uvrPjH#9F+EeB&LBA4;@Cn{tZMEc@A7y@>W2o0^GW(pm=U_3&T0t~FW zGBSFr@VTVhHU@)BILlX>klAmM(dhVfd4BGr3Dk&C%Q!n8=jBN=V!7EtgoFb+`1Xkw zbDUlo;*ZQ_bv>nO)vF{nTwh1xndf!u`M5YXA5_cNBtG_|Ki>UJ9Gyps68hCG2&of^ zVBfs1W9T*$fR!!rlln1!Cyq8ecgD1w=-r*#2Vv=uJVb7WD+Py~9C1%51bRUct3NpL zcm?swKAJQ03d7y(_w*Kwz5~u5LyP;0=#oegl!cy$le!@Wlbtzu%7;qOswCtWab;$s zXKA&W3gdWfc@}|Lk?R=bSXlDc`ynAIIfnu@uhVAi@P;VizCSp7t8Ynv;Rj*70bq{oF3h7lw$5v@<~)=^}{d zb5WeD|4umzOop5q>-X%Hu{l2?*W1)eIMVLB^f?PD#$|4BVQz^y5Mj~pugz-$6g`#t zls7_3DJaKF5={aLI%)~1qKHA{tmfgnFpuRWuNl|DmWvE4WPr7*1v!Z#-DI2GbQ zZCBkWC?-a8YYJm{7;@ffo=_QZ6XfoJ2Z_dY5B=K4f)4PuE%OB&ij3$KD9-`WvoDNL zWk{inF<7q++nLCLHqOX3Ag6Kj&IE3%kikXhRH|!o_#JDis8r>>K`JM;I-48hw4jq` zLN~l^l$I~_vAv;FYrLaAc|Ya)wet zn%8MDR6yYz$b3E6wvMT=Pr6fm(?D-{+8IgucVjGaho+N3TwskvO(hfoz3BEByc?LJ zLovU8^cN~*yDI`_5!_iD9rjwq?VaEe)-7IVeypIM>)R+3HM21jx&$NdnC?583RcV2 zSrMs<8KyDDhV0fpTWe8CcAW=|pf~tfQUWxt=4}tcGkRg3nG({=sOFfe)4?wND+F z_iw0_Lk4S}z~iVlDP&X`!3otVOLyOTgx(4cX@I0G4YhRdc^HS)`$_f!q)-WH?095+ zY?$Lf2yOPnoKgxO#Zc!*;P4#ID{hCm(^{9Iu;fs$ZBH&gBtQ`#mXZp!S&lj0gO`#1 z9Xf6WW{?)RI2QESiZ52>vhD}sKqb+3PT|rei~uYcB`fmm7gg3OWy+;YZ9m4DU#M&T z!DkMRN=XU2JK!4L3MHASb6h-#NmXAP)V5D>aeQCp0xM#%6{xugYUP|ii7A3i*W=P!?qFodSUMza|;+gHUyl& z;=vf8fV=-rj1qH~KM#M-@c z8nwO(p$r|w1FHfa&(mh;Em*Oh*f!O&#N$`BE6|W{V2^P(Si4K&D@GiRwc*zffD6cRO<2~?Wz&A^Ys-9jCaw>`F4Tu%*Mr_U{;0; zL0Muk9;Wjz=myin=r#q{?Zps+y5TJZ^g0e^A)*isNC7d9OW>wZc>! z24hll7DZLN3{ZRC^gg$fQAt1#T#F8^wmsb`n?|tbq3uU|ThaUUp(e&t65N#Mv_(H~ z25ljL3#;{}J zS;RZJ#i@5w(}^u8ykvLt294zPqO3EZ@`94L+}3>F?Bd$i!5s)0Q|A8QWLnPW zQd0INGlo~2+%+6^`yiJWeT&T5rjG>h;T6psP3%Imzse}Wa5^9rjdBeN>9yR-Ifz5U z?vBOXomBpnZM`@yf0>`<6jA^cp%L_Nbk{bi-S*D ziDS-d-?+9nZ=ZSY<}4gZ+K-YICsGIzxg2x1%Mm;UZ!I`*`Oq+3Teqt%kt{r{B@fkO z);WXH7j-&6KLV_kKO(vG!1fA>)tlPs5#jlI()|tdVg+o8?MVk^zf*|_e%u3@{*)@y zNz-o!SRCu+cf#%RHJ%Z|_@#j|CvLT%(sQCHNAAga-_oJP*M2L-fHhiC1&PbxWe~B2 z?3n=RmiZ3}J$naS|KDDKf63_%bLt;lQlCg6NdmTcM6s2C5JM4NCxobbYxDZ{DbH|o zis)Fi`+C1l@_`l<@Fw5HFf;cSj3%xK$Y2+lvP@KRFiC6DK?7(<`}Z>|tyl2JAXOb% z0)(U9C3l8PT942bNvL3-%mJxgw(U8>U=ZJ}RK<6buks%y{jYpJ6;aXK@gLIqKZUKy zpS}O0wpRdG$aKKK9&_1&2)BYOw=IguVRnxP;&kECNABx2rULA$A!xI_BD!6kLtMXf z_P-;)mD~NgG5Jr~8x=mDnqqg}1cyI;eY~f-F;q$51I{%NabuTHbD@}sG}dy;ZUD(t zt}P1<_B{ihLl_pz$^B1~D&0ZCCv;oSH|fHK+s$h7pN#K6b=Q?I4kFCZm*s8Vv`zB2 zfX61dCVc&Nvi{h(D?Fh3W-_sJx9mJ)z1$s~>-}>rP0J;oG&EqdX3KoeW}?^g$t`Mj z5xD^#?E?YN5b~XF-wOd`Vp~)&v|0KiGmwrp@*2t*#r!A4g|H4r<5dQ4E-IxTQ6-sT zoV_PzK}^4l5d6`+1UiF)sHZf0t*dhk2JKY%Yn_<~Ykyi5(|cEZ-4Iuy^U=7G3vd5h z`#%17S<%>dM2BmKGhchkYtlcnZtYCvWkIocDYEJOn#?`kH|vjAxV^^NN3A9d8!=|1 zXR;O3!VxK=62Z+Ce8@dUZdjtYon8tPv3SE-a5g^OJ43WqlAL23XZ~fYtVxF+fjX(YSi;SR^-&u3#`uVbxyu<% z8T)B`hs_lqvUF<9i0+%V8!x{|f5ySpvU7*hRs&Kv3rP#m7`_z6)2u6}J8vQ;VvYC1 zK^_O6@tIC+O?b0~4P2|qr?7|^z3YX+tn2jDdn8Yo=Opm&G!J@$xUrG>eB?LXh~$5IzY`>~ z|C+tFh~-afbu8hQvoc}T1hzTtt)nZ0HTHXQY_07Ba0t6Nny zOx}-~c{v@s&Fqt#y`)kh>%bjX4uJ;g6OE`=w9pNHX+2c!-io{ zLQ&ZNE~j*bu_>W3{S4?Uw6I}jXF?Wgxw)*&%-4aY&yP5qdYsTCdzyaKXv*duDYQ|4 zyOBmx46}tUk6Ik=i(SUHS&`8h8rz0jkinZgGfyd$YwL0tMMIow2R;Ikui5M5Efz92ck9V4&0mDhE9bST`r-!ABvD0V-o7GvyGlk@H{ z`c~UcY5R%1MJ!yf~#+dr+8f>V8 zaPFu1p`(GD_cTZ21G_WI*v`fU>oXZ$wI;JgWF8=eUwGfxNj2)YDk{^J?!T%|P8eWa z@>vt@X^M5n&<_XxbUwg}L+f`Q55RT(m)FyKO2!AA3@-};q5L-Zyv_^cqoizesQg@p zy5uX(<_j`DX{=_<6!9SDj87^9-Y@)6Mjp(}JEax8v`MA!1+`f%I~_U1Y>w+$I!Ciq z=XqlII@f1s?_z)B!J@pujY(5Ixz4FbjjIt|Dp|G1y1@YNV#YyS9)}@B^Mo+W1^$n@ zeDV~wOBkxEpS4113NA>>iouyo6mI!=lc3GN$EX&fip}7v+}>r&x;lC{>UddvWgo$> zbUeWW9*m!6VL7g^^V(RM3!i*#;Is>&ul+G_-Ewo6Lu#RH6`w)CQbhn>@m z(VJwVuPrhA?xefoAcXpOtNLZ;ld77T>WV);PsQqsx8$c(@Lum1mUW=!K;zQ^qc4{PF z@#)8zWtJ+^B-h6Fvl^xq*2W{unYQI_DANJ!v zxbB=k`A`rH?jy?RtnV-(&q&_B{bJGBHtiXS2Ph98n1cycAxWoevaZQObCajy75W+p z*NL{Nt)$gHtCW&q97s#8w1`Ts91)`zKx(WkBqW&fDl8<%&3;aD4IIwavOVVysw`|O z!V7LOCg%=XKdrCtwmaNbmol6J{*)2_Fg`c6)U$!9w?x(!B#AEhL5lm3cnV5nmp znoG}{7G-fS%!fnxp3n2@FD^g-sF`@&&-2(ju=04d+a$x!sf_Zia5j8arL+~UAG@ak zGfdU_(5L2?8|??}VE#UNIkhiss691q4mug|bQ|hE$9P*N^5&=sqm@7`Tj%tJ!$Y#Z zuvQbkr!HLSC|>Z&!}6+XIk*2>I^zpQgBB~!|E4wC($CC#UoOInX^hD$7xg&KlD#A* zQFaDro4z&wLBUyhYAGTCy_B#KuEqo%5fuS0y~gf8zz}eQsMdcLm6ZilsO8Y9tra+L zSiwXTrX5QPeM|jFbe3v&!^;#$mc(KOI7chxq7KrCO==`P;D+I-#QR6*9AeHS(~QQ+ zH^~sOj>4n`n}-|!XMULG@(1iPG(LVvZulF3!6+xURG)#YAdc$%Oi1IUWQ}h=?3roE>8R73kDh(0|IntrZ^Ecq zTrk7c`WP@V9;7E#x-JKB*_>L3a9Yo*^p(3m%45#V==k@$HsTdN3VV?!b?e&URt6un zd22f?r$^?QA-N0DDz63pm$|caFk2);#k>FFOu@?3Ls_mK`-`yBwiBK>WG(6~oXp0l zQ&AO=;gK_}vQ;{*15~S8H|_2a7#mjVjE&%?=sPg5i+$OzXqFdee9iUThZj zj^za^gijv~D5j^=9XaR$M4?^^VgImpk-UOE{ru$2qr3=tiZp0evFsZisOqbTlh+vL zYlSBJn?GvI5L;icKiEA9ytt*wKO(2wIP!I$`5bLz!_ctE;Rcnu^NsHnYKO+;udU~P z6C}00R}f`F|K;*nA$VjT2f=5V_XtMO@aQt?otitTs%uA0j&ow4>{P~#EM);~7k#wP z0fD2B2wo&Xd96{=R+N`uA-HKWpf;7E@Viq=2T&yq^c8y@IRN;RCVoBWtdprhO6(KM zR%!V`L7vA2r7uBeoaH0wu~z8PgCVq=>=F_;Z&$pI1TrORtri%GQZ7t z2fgQXPVd`ii+9GFGrT!-&9HPN^DyTscB&Zdw3O)9UP!xId#>8Hf>0#B$H&4r zIhf4~IlK3ks)sRfcsG|LAUT$DzI1a72h~N-yO>-Gbswgl_O(}U3SaT=ho_8Z=~wJ!bId(2T!6`74|MJefJT-H<-pn>DU(SEBaCb5iD*e*#Bh>lW^MdDCd6%Is+gyAhr{ ziNb%v&+0vP>yMMZFX?*odw*=JWao{!p&0Uc1=IJCGe7k%-&GePv>*LiDElKa8GvYs z^)m}QB?VfXC;Izu)qbQNCe)a=JJg^;c$2-+sH?jo;qN!`6q5Yo(*>8+ z-YPhpn!v9cI0Mv&WDEy^k0~0$#J5ALXmGAsV6y3b&UoVotMc1Kw)208gJ7KnAV#~`vrasK+72eLQ zyB&wmL?_q5V{J4PfH%}Br!TTL|Fo1YIpb&7hIqq9&&Qjfu{&NY!kLf1I*M->IIoVO zBEgfST$riT9eXLp>|u_#Ik7fW5G>R(q}OtGw)6Kn@8%|}Aw3!NjXueGWOh4r?3wtm z$M2XCy_R`59eh~6m*gX=0R^BJkHw{e9WjFNKRjdQFqvI%tHVo z4}b0`>AW0OD?w+>;tsvb+jY3FDVc3 zJrl+daovpEmb({VfB#n}|Mmk+d9Y^pb57H0O+AuZ#>KG((~EBZDuCuUkhsg$nmv_8eObp4{#X6sB6VN{#G2`D&-ws)k? zdVKY>aW+*u)MoiN6R{PvRjBJs@t-#TZ|qPzYyWHj_>Y!=8}M@Pq^R`Abo-$a{A1HEoLI24>i0YREH{?5sgD5A~iru9K?v&e+HV-5)W1*QWy z;ro*tDB`w3ue!3F-P3U&a>u$+z$k||M{8Q3kxhGuY+mz#w!xctH)wK(QyWVnamR7s zazB-7SX#ZFHX(ai=U={~2{^{fvyJ|%$Mq!R7gz*FCII6ZDbg5xx(yclPFWuu z(rR{Y{7C6X0t#JomC;tgV7y%hVgJHQhPdPnn>pn=k4-j zKa4Qd;E(x>>qa0Cj%VqWT2{9^V47sf4v9nM549LZ7%U-Z>J00k6UIuw*#g$)*o}Po#bu?Cm^XFaQaVTgQbtvYuJ!t zz?>z=#;S7&r)+#3pI*)hrY2aCXSLcGnnO>Io+*bdzYK3$(nli&8f`qYx?Ltj6T1M9 zBnNWQPq~ZSRujN7!=(Mr3fq##5~BQ;3%7(9dE0L;Ccv4jY18}r)osl+e04sFdXwq= zZR@gv?%-g*3G=@PbHug(e+~RWISM{}PexSdObb=6J)Up{Sdbm()+^wt)y+&B@i?(Y z_5yGPGCAM(u<^G4wY$WT7&`)$zG7w~gOrUbHQB3Go!6e^ zJu0Pf7v7uSEBa5mxih(q(L*P;F2}Gi+}6XiQgW*Yv=%d5_4C!EH0CVYXV^x()CTP_ zy8|PC7ROL#dfu7z+HffU;B5C`GZUT2C^;urVpHCsPh?!Qwj<%NBJ*-5ZIX3dR-p;! zGaxZ(EaYhCRF(`i+X5`VABX(HoaTB^kzy)6I#Bc@#R%t>I`sWC@wzj{fn#gl_X7Ug z&J37*VJikYa&HGMafyxfP!%m>0kd72sY?d~vT>Qj>mvX5>CyWSW6_$I$tbsjk5rD% zq3It-UcGLojR|EkTwg2?MMGbO=|OTL`bnu|;+|Y^W2e5|9vWK#j;YOq;KF(8=xuus z9S!!}bj3`8(*I?PW+-`U{xO=L9tEaI0Xe`In&IsO4tvv2&|9Xqp>^KtsPY9`Wbnj_ za!=9(p(WoeirTmQWe`>}@dfbe1H5iKG`7~K!jVs$nmoJud zO_dSfYJrDe%}d?{kn?Xc`f2DnlNk0CefTW{>uc|>%HuxC{8aLS<+j9 z-pc$QT((0(c!N>cpq0#2OiifgBNJ*#LNJG4!(Quis|#m_0OQdOk?916?p?5dVcH!G@w6QgQ}^n_jCkO|aQXp%cq$II zrQYCZZ^PBbE!a28OHQ#QIb&j&iV~2?*>!NwT@CUI=P~;*^^I#CyUXPo)0}H1Fjnm3 znkO21sLZh4V85nRRIhVNAxf#ExGC#IuwwN$L!)QpkBkzM1IMN3+#0o9xe{GGUDp=O zP_y5xU|NE}3%5j0eaU>*Uwf^7zoU30W>LM{+!4C0@Un$1xGV}qa_F4oNgAoh;X5jn zLH!Lf6ooT;qjys<4f_)Uu_kr7${#PzAVx*FeX7eM=xW}75p}oE2AlI_`<2JAxe%X5 znm(qYGBo!mcZ3tawBba|=WbW&{M*O7{em@*gy6BTjvOYs(Rw%eIzPdVr_sE2EFE?{ zAm96wa#T-yh}j>#_Na82$!@aj*IA}TmwBwhgtgJf?(UPqqjcCQ!v>P9LnDc*4Y!lQ zW)`t;`zn%~wLV9L%$LWMSYVH<5gD%#fz=Cl7?njhsm%W25pZlKK9*#Tb`%`Y5m4Ns zESA{eos)-${w#!E8d_+fHlH|Qls`UK@5$GqdTlR48guE++jV!|FPK9Jw`- zOuTDF^*jN$M*ahz^bHsG1)ZEpbf~eAnU_HI++IzNG&;8riQw+i= zdmkog+w4UpIJ(iluYA{x71rqRZ64(%}qG@b>wjDI&D(!G%CjAFl?3R8+l`ycX$y@Iqin-cX^@VN9H{n_fqrGcODb zv0$P7$jDP&ytUZd@Gr8 z&Y;iVM@DyoavLMa#7!MIfYCd_h^#qlRQJkKo2m&>#|`;4AWjxJdC>Z+gaWt`nM%oh zE8y#s6pjaY=0LEfB-o4>Jgy`?U%BXYJR1^=$)av4(5E*D`Y=Am;qE02&6=3$z>e)3 zJ5mJ|K`x20o`h#swU@;=x(ru)+6#{5 zWpN*A!g4UvU7voA)w5{sypi-@Tz1zmNa(XcufDEtaBMxP$<`l5r`cFeN+P>IEDG)* zoSr|0zh!6i7&8PR=bu>Rj}V%W+q?3UDEqj_aQh!IZ;PBGsJw*k3zYC|Fw@PxnCr_d z;Wsx)l!B~-qnStbPO3uO2^j z^Z$l-St6&iB|&b-BimzoEKZ?{Jg!9$P})u1;oQuht~Ik}IGvDLA3;}1Pu33b4SZJ! zS-4G**#C**-e8+YnDy8hMCspz{2>)t>T~)-I*6w=()T;0=Y61v{K=Yn}{v(z6 zQlEvdqrUX!#&G?QYsBB86YP0MA7`fPVn<)t&1vucJ!_V|${4wo_~PY+_&=c{-8O#H znf$+jBEt6y-kmbN{{=aImhDO195fi%Fnla8e6EdKvtzRZ}HCkkQ{f=*l8pby7MV?8-spq$>J*lT`1D=^?wxH6Hlj&!! zdMWD%n$0gd+g@&xno0?c(iNz-Hqs$G`-yxfO*dI5=W4zW^27qd-rX!f-07vCzZc!Khn!}2lDYHB(swum4Yn4BPnR8xLCR&mn4N9iN=AbZ;5i#SzmoJ8p#RjjZTFFX9gxA_ zPWV!&dQDxF!e!qdosBqi=3v6U-sdkj^J{e0UqOv%M<&)smf*VIF6qcI`c(F^o@_82 zh0TAOU9Rm~c6>s7yrnxp5$?yH?s+e-Er%PRo9=NZjjypaHtVr9R$e<{h8es?r@V@* zA27i%HpYj>&QVcWLIpa;&?#m(c>DaI%5dN-l2zZB95jjwo(DW0-n)0wU5*~UKYQw$ z>B{nSibEx#)BB@eLOWPt&3DhVusLl~^mlqZmuD|DdNe1$Sat7ax#NC9yke+s{@HhU zt{8*8>ZWFl9~~ytZrTsJ{cyYc^~*x}GybgQpXmZIqTG2Ak$SV4#dO?)e$OHA`(sc-3iG>C{92jfz3iw$@~@S zddE=ZDpYZ)&6QSsz{wuJ!|}J45C7I?#yi%pol!U_EiM6Dx+Na0478!W16r@y(&fa1}w`Sd&#$`71t zp0TVnXbwq(2e?`x;pRO)@Kr@8%x%0EV{|5%MW>A04X5xPZBr=~!B5`?as*ZS*yEzOQhc_$FWDW8Xk|A)G_4sN^2 z8g%10abk{R=9rn8V`gTKZJC*wnPg^WW@bBPW@ct)Uge#I`DW*xTYIavZr#76QmLe$ zTCLXU=RD^$u>aF`3R=)J6Dk%l%c$)qi45u89+M^yxJHsD`W*hV*RMpd2Csv?2eWom z?>oX!rfNX#9tcavvEI*{C@&nL#0|YeiDg#$dVN}rLq$y38M{A=a3~`>hUP?>t{?ap z_e|%WoNe*wzAC?;y0H}E<%JsyS7&eEr&wRv_TO62wg-cyHdcCzIxuCNwhjav64)_^ z!DJK{PwMQMI0R_)k*vWd)Rdsz%GRZ>Q>cdn!YfeItvzk~EGe#)Uw@x@zOXskqfT>^ zvF1aMgwC&`#=Bbujkhz{J*H!}w2j#eRdMV!3Bc@DV`&dWMU}eN9BF<1g2Fr;x14v_ zI`~Dq!?TjmcLnpjL2l?yDUJze>|ZP{+EH4r)cx5R$Z#S( zjU_N|vfiE2$O_2@r(>p}$wtZ;{7^q}xe`8}EPcG?aubTs7nVWE6il;A;QT_XU~e>E z28LXk$-mD|s<~zRsx?}t5B^|Rgi=<_w*I1`QdTqB1e$5TVl5nk0cva+M~ ztp;xKuctM!y99DpSd0M!;|Z0&dP&C`sR?Kq?(KJXfF5G$G+wa`l+O2vScE@y_$x+% zZb{NTGStJDf`wR~T&&|w*GYCync#J?T>?d5ih4`64TN2*fnVh@X!=neF`{%*d9UIs%j5eA=f~HNT(?r{YoWXfB zaNu4~GFSbMXJ&AvB^@S2Vaq;!Q;cLY1Cvlu0$)CbS5Dzm)Vv+m^8iezaVys$uBemc zm8VB^)@Fd%j^1d*OZ%8!_4~-R6m%^u)^Gu$MKM2He<=eK@0tg5z?;Bnx*{-!lO9?S01tXgb}X(3Lp z13aGStmf-+La<^6sK)3?BpdZVZI20Ix6Q6x^`GuMp1eU)3omD~*}1GIuOe8}>#Ye4 zTofs^p%Qe|?=DGaTy-~po$OG zKJt)_Q%CiKmTdmdmkuVDO7nq{tVc_F@T~zq%}@9<5*T<>>MGDf+ixfmQbMfr_=2cf z$wQ!krT#l|5wFfOv$?r^)5#MH`nai*-SzDQKF#;NIE<^e6@=C_>);IO-s~ZBkbd62| zQ3TP*!4<-ch!9K#?TcD3w(s6Tp(v1|U`C8aQ8J{}=i)oH#u8csS)U&GsD*Z`r9jK~ z$cytWN3B8%zH)c#~{NpWtlI7WWpar#wu z8ivv+nt@HDs5<6KIL;5<0J6qDiblPQ25(i0Lu0^-$l;~e(C4UjoXrHW^^)OgP7AZq z=T8a4hp64GxBC~_Q&$?lA&muc2^7x+Lyk=s0VFuoU@?B?&^Zuib{9bCGVR{rrZ(ME ztbVEeWm_1s=6huAI*#>{zD5;8D6_sdF~7ZNPqc2v!4S+*9U*8uVf543;G{^KOg#{b z18Nxv5ss1j5~JI8sj*Pip=OuSw9GD~;{vn9GWgZLZ5_xF>rwjvXs zR0qHl{`M2tUY(2G%8KXLBwUp|x1bcYeOzw||& zA#qR{h4Kqx@Zxe(^FB`036^F~xq_o#M19PVY-z%Jj&4}nIiMUa*B~{SEasP-!NXe_ zVCWpITx})7y)PeY>-I#*HPs{%76NiFNzl{R%9K;0G`kf`8`kvI8p$VH14Lub2^NnGKpLGG2=vtwW=t~g9> zKruy*i{rPLKJf=3fLzVFKwo|6eov&{j;c0#H8!oKWq%-3HkSAB5r6Wv4X^%u|}z0V7hprCeQXRK?WLh2H)a zgIlXLnED;d28*GkMUO#dZEY5D7Z&SxYQw>lVQT)W;=QN4^^0c%99t!^T--FE_)ZOQ za*b;!KAeA%)*SJe!c1pX|-A-c^yg3Fm(+JnPp0&`sGpmg4Wjl0bjso$JH z^?nrt#o*=lrOano2x$YmniQ-9+b~wD0iITqA2edkG$A2HHj7{B-BK4FoxkPGkMqen zU2SUz3(Y$!_Npx?)nsafSBpgZNyY>)I$Z=kBQ&i!8Bs=jv`)7D*1}`JVAH|^$9>p0 z`^nv2QHrD5O*Xk+es5|s3boyPl5>RAU-EfxA(3a#z>Qq(e@p;2;>PPdV!Km5W|juS zf%meU`|TD#v-fnpz>26ByB-N^{Z#-7`4arjv%8*bt^i`IIT&@|@AN@{pv|G(CwB-D zCszS(mLer)Y@qM*rz5V}#xola+)})=`KSd+whG%SS)-kUQt7?mAm$vbQDRC!rn&JH z{wpiH1+nQ>2llAfsZ5AchGUM+jI5OA98+5~0f9Vj^;flPaE|2B?V38wgA9*^65#rE zf_NjRXA!|7g9~{)kCg7flXjAcK9KzsPt?)pqFHC;OFZL>b$Z{$b2mCe9j&Wb2kA{Q(t0BeXD1o8}M_(q(UU*|X*fQ*sLdsB{GeP3rFSwWv)c}5ds!Qdu zP1axN%bapyj6*V7u~ynh$T7Rsbn{_b8$)_-bq%a2diLqmVSx25$Y1==vHS0T|{Igk>CuqCZ5;m8Su^NLv(qC*9uowFlf&s(rkz92D zE}l>UL_ReVPLdjdUXj4u_jarLQMl2<6#$SZiuie9$t!jCwOW?>*G*G53>=zpgeXq_ z`UL$)!R|>`m%Fb07>`o;Z}513#h^Q&?dJjtQruM9iBpFSQXrhxESqyI0l~Lci=ftt zKpzu#61vPgb00oLvT28}869y$yG+Uwo^G-ba*s=l#tJBd)oiaGsXuqY8LZ#bDO>;A z4pn~(tx!&0ut~F-zBYF;$<#$im;PC(qQ7UT$6ph!s=_OHI&SKDcB3F5w)557ff$HVjZz?m@mBB(wX2?%I-+ij7HTTDK zoRm#N&P#N9!xZ9KI+Djm=%{)U@&CM%Dw6Z1V*N1X-O62`b)S0kmyBvAy3il%iN>WIG){2Oas^qb}GP_r_tU*o~9jfOTjaK?VCFu^0V1dJ>+ahEAaC5zsRCu*L;l&$q6t?j!*R{B zM=GlAw~YetZZw_)&(h_+p*q)OtR!U?#~m5ar^#K)OF=~lT=GMtJX;8*SwrtbS>N)o zZ}(AKKikzks`(t@d1U{Bd!nb}?yC+QCtZ(g0^@cf3b0{g^Mh_!v0CGaXfF$2rgW{U zhyL`jtHT%HqR}+?-JIRGyp>l;*Yb-jRBbl}#_Plv6?{q_XH}TC~ah zuuxi0+61ADLY}0Wb%f&I)1;=)|CuHQV0xpPwSeI53kT_qgZ7xU50WR)31@G7^fML- zt!toaR+fehuCIAfbC?ypdo?0zz;W}Kv*UAKh@GlCQp17X$f+XP`B^f1G?#k|o!yMf zo89Hk?@dk040o>w z6WF+)jN3N#)qZdW+7jFODtnQJ{1ZFtWj_y?hD7twB{cSMtstm`@ zG&<>vzuImx;gJ5W%fG z_I$c`^4Wp=BC+SRp9|14HrJn+{OcP!oxx8-wl|lte)cQzcp8}AtPw26Bx(Hx{SXg`&TMWj zPn(@z3g1w-scjAh(AI{u+x2&fuwa&`8Q^wj*=6bD)fM#wXpwO4popSNhyQyjc757sBHDy3w6N~2!CjS+(O=r%VJ6({ zSYo80$rJ|)P4Ou9B=c%O6ACGsZ~bwK7^}bim1u~Re9|@tkpSxZ5DXwxQ~J$_E19XI zJ#hS>>g4Ot$J)Y}vuHzU4aGo*RScOfD0aJY-zg&Q@$046!X(DE z%azLjV|B^{BUc-F^>1pktUhhIbP~wTuB^>+Se3BYlg;*2 z=1B#1kAVT+=z)jgG%;6zn3;>Zp(%qX0#hOJ#@!uk@9cXdrfsX`aRP(J)MHim=#S*F@pdfj?; zf}Khy&mHMYffDYv6M?kTn-%78 zvm@wYCQ;AbH}k1&;1IW)efUb*00;hfgr>Va5+ShKWD?dQ4oTKVjc=TnZK~v1rYF`=<6Ge#h>5kv6#6l)H50qu zBk)QoLk{Tw5t%{Z$k&k-A7}Cypu_{Xs_VGhoV&BAx`s8s0$iN&tB-`Q}2R zV{rRS=Xv?uWAT#A&k{xxmwW+@#d9>Mw;@-^bpB~Hd-z%DWI4)9DSqtgbV}&U=B@+X zvzkTLhJ%+5!^wiP2hXJ%@|>=oL8l8TS3v&||GM=`p@R!`p%08?J=&c28-nEhLw@317zeq_)&8K?4>B<=&xi|Ub zz0W5fUk6;h&Q-PwU%+UHtJjebbd-1VlyK{{^BXyI#8&5LJW-HywfX%QROL#)gBqZ! z?uY_=7BV`Pwla&h3C(Y`^|){IBOQe|7g+c+_nt^PTVFwj-+eUUz4{UgP;t-a`e|8{>i-6{y27~yWPZOCPZ}4+GcMe{@ z0Ujvk?P2#4aI^=4yGg2_Y-qERjop&JXgVYnW+0lp2I9R^AT(}Jc&s=%3Fj-MvRH0t>DIvjGf7NfQIHkO(4hEYD-l;&(kiJsG(7p9Dm6mF&zX~%f_zy6YYfbObnb=lvniv-W;ni~!ZS7Pqai)>1j&%T$@1%F zG}iQ6GFlw|^V2FjHxXEAuOP++w)e!}1m1kV1S%X=@6H34~<-@sAEPt|`^5=WNr;tN48mxZ?Ytr~@VUF`o8>g89 z`uRWImwltfEIef%J{L9`7Lhs!**_GHio(I|C*qHWUG2O2%RoKII5 zCRc$tukYQY`;%e!%blforkCQh_46Y}a}^v+x>D9d!t+5i!a@;af5XFU9V#bHCO%+< zZ^}xz-?DyTXrTw3(f56hF!U8J*JHOS&r`@E3@xSPawihaY#+_4=&v~zYexqde0NOm zi86KvGny@&#i(t5Q_wy`n+yz?cqQ$wDH*QPl;XG|)0K=| z;aUAvogMC!wCgqDVEva;_x7{qOVMi zRA)4sMSK+b&0=Sc=P&5<;JowW$xcH`;P}#wqt>C_Iq~fctn;5CnFXn^P{x=+xbb8@ z<0gmFw$lbao-$w4k-I;~;dnlJ^1&~@Gg9Npd%a=|rB0@g zh-~qt;(U&0Xw!jD1I-u$MnbSlcJ-sTHh%1_t4+j7yj=o2+}H*E4mnFv{0OE#sc&>j zhQ4p~%#K&bdJ-a&dh35!5>ihE2pb(|2y=MVY73yJ7pVk+41a{OhO^?Xt`N;R4tt zL%ZPsn=~e+T+cNr(jYJiz~w;A*xU|>Ua0N>>tJ)WC13{6%Y$Wt-0O_GXzho_ zUEk@+MF5yMR08(daonDmmZ^E7?WrVp5bkhryR)5nu6b@DGzb)DP98pwj{evS4!b*( ztvACO3NTJl(bj=}mI{c9R1Fw{Es3!kL9a-`hnv3vRf+@Y^C zV$sF#UJCry?QXajbdp=P}{KcV&M_*~01G_nQe>-1mWuN>)$gSqIfWOQXcX_#Z-`qJWMr zxOyy$*zACplCsRO^FBBEe5uJ-?>S!8Jul+Hev#W)ZBdPgeEQ|;wY`c|E*o;K{zC%4 z&N!eNzsZi>hZ~%*mFtS@Ij1s9br~aZwo*Twoid5cMgYk|%^^4=!j%ou5S0R5N_f3;r{AZvR z`<{K&(kPWSKy!OXuiuaLo82=)IXleMSeK1k2L?rapVqAl<0)Q@Xo-h?8JLQf1Tm2)pi4nBd%clU)djB{9KGCqqx;N>?euZzRz*|CT@23AK7^$F+&dbwJM=xgm=W?HX;XRJ2f2!t@LF(E1r+Oc) z4;AxU;^e|L2Zsnvq($6uLsxss)1V#_f`iq^>p>U(8)QSxc4-`eo0?_L zZ>E3s0QrWNKM-0`t!YrTU(W($SexRaBU6vrLH^@YjgNi|Z@Hsw{To{E1cX6{Z*-gtJz zZ>lgMSBRyf5cm&<&Ud5c8F3r(7+PWj5NlbHhb6LH%-GqAW2<#}x)mZ6n=hA^q%bwZT;6e;q2n3K z*RCFLhFd*Gawsdv7K#|8d^;vI)UB|&Y=`$u*BG0)53#(L1&#?el*lB@HdsnyaIp># z+BR$DQ48-m*Fuu0tW=?Dw=#rLwfnzDo|J^Ns<@{)vt7R6lWAzR!f3V9j8qvbd=Woh znsLvGZ7h+8X=Q)R`*+IKssEK`66S`lvMy;t41c55Fzo*8^}+JeRN({J;x-UO3pk|_ zEI%0iS7s&;W;8&qCpEN4MXBYHasvhXXf)Iy@haJMit@gD(yiNaQ4&}Uruoc-fA~O7 zefZ>2iIwCdLt;(B2#KU<9HTU)HT{+i60nB;Rlv&3)$jPh^7qhe5bQrgvp)*ff4}Oi zh7B7aRPKXq&o!;51@%Uu*CNLV6zp#FGn$$BtiGS?L5yZSt;W3lnCm@nu}H$KuyrVR z--=e;)oH465LaV}KF{fP>G5Z3td*{iT|?126M=4)FrKfuNAxjmEN^`zcwRBwn28HH zPc_>De^Orrs*~26N~z#98%f_nELQ|UyKF>$4rS-|>D#4r)LnJ1gE>NkdvH`y7NI^g zcL^_ryf4>n++)MfNtULF zlQ0x}&_+Lc;%quefOIJDMs3?J9h+%R;m(^!1*y{b<9#pJXbJ}QowW#=sb6y$8ev+J z^Htl|-7;;OA4ull!9v$c;JdPUY5Fih%GZ-2(5ukj%I2M}f#LQ>d z4H7AeF|ZBF4GahL-L_t>*jhqlaTSLj+p1?p<{n%&(eGIdU+U>SXK7B}`ZH{m9qCSE zeDs<-Tb)+jbr!z_KAdpiCY(1_Egw@BV72I_i~nWK_=8AfGfT;tztu0D8jU8+TiXa>|dbj%H4Xw)Y4$zn0BvhfC%pE)RVLRgk zHL>Qd+l@0^Mw(>*6`G*ZZ*%-|t$iU0ay4`Es;qfP_$EQQzG>*eAjJ>0xhqfvC+9z@ zGZx0j_2#y<>j_p{6y2DCN!bQNr?_m}z*KI=xUoOczz6^K>pV$Tp!>6UtgJ%zz7UBJ z5@9U*07^^x%cKjVsfRm!#-!dNLhNTFS&~(vaWHU2>?M2CpPwlXCYs>H5}cs8y)t{U z9n`sT7s2!oa5aKx-?lT8(WJ3ZGky@ShQx0h(9ap8Tc3mCnpmOqF&h9Ov>At8CT}ZZ zO$XO7|20M}_AP7-JiA=c_y??38*Eql-*-ZNSwP9Qh*fX?~eb6`Jo{zfKqi22T{>TiG zD^qoCmH%29EI8Pfw1wn5(x$a2Vo>B)Ue!;=8Orh``D-e_ELQStln*t@kp%Q9*N=Nr z$U5jO7gWFJk=NpI_|h#aM=t1)jv<(AU)2r_TpF`2Q91PJ08mIy3~Q(bc)Mvjbbh~` zs@xxrzdPqvH@bB!4t5oVD8EPaTB`eSZy?-0LIPR~cOUQ-fE_rg`zwzU?CulZYD2%WXS|B(%$L-oH_rI| z$ifrk;fYMSRoY;mrMKD4czkzRMk-%_eIQt8D)-z0{T|I_|Gl|2JyT!=5+}io?|=T-b?krEn?UaxXd%#!Yl^>G{hlSYw{{DV$^Bk& z4WrBs`M&a_NcVfv5=?Y9eo$+^UR5l**R+%C6i@WU+K%=HA%FGJaB-!6tG1Fi^IA&X zD>H&ZkTa;X^Z(THnnq87Sq7v1CwAt585xxqK{gP!wdGxy`VI?8F4;meH&N_vkHpPl z3#)bL*YeU;B%d_ipz|*v4K>44N})npzo+=lo1{QS~# zM8-+rZGT#mp#Vp+`decfXT~Z|*RByJW1!TzdJPA@l)*^KS9I>U|H#ldKTY&pkMI8E zr1BBLmh~1n7f=12fUZ50Q~&uB@osZ@>I&V@;Ooy`pm6q>Z1G(wH|C}D8p+fbV0k@H>KwfRMv+e}h|2c!$le_guw%u+Ie`Mvp^=PXs zG&L$remmbCaiLlLz7%NqaM=BJQo8B~)FY;QyHGk{Nxu6uGO3H8N7L{ zq?;{8&IPqMZ4T>6o7xL_e=x?ZQ=4kdPww0$Y1HfKDVE`$5uSH=)H1v%BL73-PZ+5ol;M2bI4U4W4OR=&c@VVsPK-IHsfK78=z& zu%`4Wk8|S}0u358S>jz$F6UI*T@Kb8Az@=3Sx<7_r2@%J(ps0I#~$-|Y;?yz&S^h> zd(WYMxqSu$W;F30L94(ZVU-xPw)BBpejy@f_CB^4+Q+ha0x$ir%TuG|c7)U_vr z-1cR5`!1dBfvZiO_@B7jq63J#0mfe$jTkc-8SZ8(V$1k}*#73izCy5aZ=zLePShuL zSK55(()K)RvR(mdOeS>@Wm3DhyS=6-&}?Wa!w~LS+CrF~0R;VqH2^Q{Iu`cnLUq%b zbe^s29}Shsm9XpdcN5bM^xS(|zs}q!&E9uP0@bLJeNZBr=!!jW9uy4B2mhWtlAh(c z@>V4ac1BmIxE&ze_LT!J3m^sjdU(`JlR-moESygRbC)%E)cPk!76vJF-k-}e>^C~S(!cQ*DCjL3oG*smeuA|=|_{^Q+V9Pew>8Jh-@KQvXHg(9{OAWkRfO!vHiSNy+F-Lml@Cs%}pV$Hke2Fa(JUBTdcK?FK_kTdu@ zGVBfyNBwPQZF2l@c^4(FMdV@3fq+iB+(Z-(zLQ3y|1;Dw&*RbNw3}y(DfoyRAN1M= zLq6z>nkih0PU>Vz(A2P9?ClF6P(5agu?&109AJ{A*;FN@I=s&gYK`vvvYU?X~|#-i1RN>1Ld z)y6Ke|ITj1^chj3bKCwHFbCdJopqCPdVjJ=B8bc`_2iRGryLw2>3daY#0KEZm<`*T zc=N(vxt$8f0;Mqv*RXqXFTb}VB+Z;~L{*(`vC-|IInOCSnR)s+yK-=sB8(RCdmh&+ z1OMOHZ6W_Zw%aE3|C8O;mqtsQ?RhiHf2xUEZ;n0qgnq1=_23VlPRChqCd%}Ad}|=+ zZSq)NwJz`PAgDsllZav!O8qP)sd5fwG@;IPE*>ln=az>+ISUTPaL&)vJ*=Lyh{dp# zvv6POW@{$-^+tjMY}Iz!l|Z4xKglQm&QFf*Gk)co1ABXSFpnLeCY5dpk*DjnCl^f7 z89)fK^3s$O0l{Z)w+>6nkXR$12CB|onFWTVQW5GjVCMJ-NXv+U))gPD~stp@+U)HgRlg{V>N|ye*@$cb z7vZ7QH!YU1%Y*=qv1v39PgcGByY1sT{vrV0<-wa|IXlhf&ZJc|3`?{+oo`iflY1g| zM}*<(1;E3Wm0vC$C`#~aleTXy`S-(QP9jG(z5X9@{aPn*{;V}&>R29@ZrR{6ZS>yl z`BrysgxY^k_WOOe8yj+Z{3*0KhU^+@6Ws;_3O1H^6MItPaCzyw8BvFG?vQ0a+D%_8 z!aV)27TydK`6fooPt!OfI#(>iR)wWRZ$oTYUnuobghQf)(1$|5pM_@YR%l)^)CBs`+p;YB+e4NS=5hK+?OUB?eYyPDw=bPm>53%BBgVeEmogtsMljm{j zY$l-@iMDNEn8VHkpAs%c&L2AhEdpR{oK#>iKV0ps+8j%X#DwPd!YF_Ko-6wSg0gz+Xd0-oejztT^iQx>{74X(Tf)(CA zSp1S9{Zz%BiH1{+aQjz@BTX>sMNfTZVeA>8|2Zy))$XErZ1B&qJ{$J@JO12A3dbD5 zV0D&=NXa5e_52SnWeU_4O}bCpq4beM^ZBAV)gtkuhxgl`$Z->cuh+LuA^vjHRfBrx zDWuWY-d_00HP*WifBmJLgZ2{v1JJL9mE~F)4ml9lf>h$UJtEX)sbg2Ky)T2XnoG49 zzoTEf3$xnAFK~J2_2VhvwF2<}yy7<`f~|!t(CuG_+>dXqA3_ef{?SJ7ACC-#tGNA< z0RQonF6fP0H8;^+Bjzm*g9uY190v-rScMERedp_v!x60MY{25JrNG11dT;1W0-)Cw zx}j3vnk1*4iv;urKJy9qH0?tUNxkXIYpi2V;`cw5>xoBQ-F{9F_1^19sfzqxCw#p< zf3A!76z+U78%R{4FxLvvl$znW`vCF+wZx$`+=|v-afQE2)8}cPWr+`}-;p#q>BE(! zdn6$QPt_gEPY+=%_c62KnvFzMA0|-Rr1Rgi=Qm9%9gWhcBI1Np?0-5!nLZ#FHk4l` zl4m%&I~C3OV#wx9UG|lJJV%nXYYW)+u$87`c1dMi;S`TrQo%q&lCDkYKOCCS6?*T_ z#vFe1%UCm|*)rCp4(0pD9A~=AoPUS)yqnyV_aGiN;?Rb6cfL`t*mOI;b3WBGTkxt^ z_k;T2$V8KF!G55+?2t5^h+`Rmg5HcWwwnqq?n0&HxPc94M5o!cAE3e32XDSJ6_~nI z)DWZck>D+iX+%u^6jEF(N@3jgyrl=Kpp^ZW3Q8v~(~?dR#+6m3w5|dw(s@%b^*s@@ zdi9`XU*VMwqW5XI=;DvFCJ7{NyCU&8qP^K_1kDm@U9AN56FOLd7REbF3fcet0&nV7 z#;D%@r}Vb6#qz&NZyYFpNpI)eBFKl;Pox%;{fWyZa^4(T(YwnMYizK?qlhXlwHJt= z{*C7*{r8?*)6jJqb@yEX>G~0G195O8Zlg#u9ev+{-pAa3E3_q8M=Mf1(Wv(dRmi{C zGknO%{nmQ!RB55Rs==Nld+QrD@_zlbU(e@K5~k-h85%AoWsglR_fO4Rod(aBl^Bhr zNxXXxzi5b>w;kOZljeBOD*}Hes(u<>-v*BTEgviBw=}_+WnKLdl(K3%JsOSOnPlL& zO{M~Te80B-ac;8nOP1L+lj&<~QzV*S$-6^4=1k;NUoD78UOtbqJ~nN;u%NB?e2~&u z=p<}O9(T~%>8U|r#}o>XR{S@*+t_(rnNW4#JoI>D2itZ-++&G{&OOgtYD;sdaRw6B z^yj_a<1^@CZq^>d^{Pg<@$gkGL$=)ouJLQ}02@^x&CY)!LkSPoe&BCRX<Sc$7HR)$owc(XVCSJ0>lB4!i}tjW*WMCMZ}QLB5r-y++vkHc2s(b}HXvND(5hpZ=9Klf<16Wed- z$<%)072II}|C)ro5g{nHo;nuiDQ3?WoHz(Yq?G1`nk+FX`P|_YBzw?5Q=-L^g??wp zqJPh1Qaz2E2W~DzP6yI>w1WP|-r?+M+G7`U%brmGhYQeRKydY{f_NDJ3U5z;UryqS zALo>2*f=Hnun!@M95XOu5Q&7$yTgRtk3bJ@g<&cEB>a6X<>gwE9%;d?Dl*BOOXcAW z^2{`LVTe`=_5WOmlQuMSF(3C|RCimMkAKLydpJ(!!T66HkNy8T$73A*|Cr+~BDx|S z5^|DfenlJDJ#n~s##acC_$BudbUH{>-4y|QTUA`42rSfcgRyDKkp6tf;6Pq zNZg{MV66$goV;^tMas>SxZVPFIKu6hBF5WxjjpM8)6rXJ{znhf1zX{i+u1cglK?$# z>V75{ll;;LP~E~T)c4iKlRa@Ojk|O3RcNCzfrHS;|BdKDOwVd9o}yuOfMC!t8qFVf z9eg#E#-1^-U#jo%X!>{AzW}|8eNO_#mmtd%bsJ*`OKQU8JIV&)JCsQ>D2yc)yeOI0 zadv>8?HX0UB)GcFx*5+UTMguD{l3s_GYRf&aPMiRc6xA76@9=h8G8u%DO&9>dUtL! z2`1Ce##P3#)CATAwJ)gj6ee}K&XP>t!_rp$L63%6ZpH3i`#3Doj&=p6HFbUvKfB)? z7=yUFlBXAAHOqK9C5!!Z<4gkb;GfDSjZ_^JSbzZOi{pR}P5{Up4B%MSwv^#`Y-Xw3p`|*QnMgDiX;{$QK3D zAK$fuvp`bsiVu#c6V--}Ji-2n4;U8ENFdzUXosNrE+4bnvC`K(-NNX0(tXBBBO*I# zaB0mPUXkuTBZWO`(PBY)KVxf3+0j7{v#c-iD(lV~D49VHnKT=*s7^qK2KQ)k&W}!q zYgql1`X8Cz_1`hQI}p>e8o>l{S#B**jH`^o)epxY@)aJB@?vpI99jM6?YxP;1lrEP zLHtAj!7D{Su&6RwGMm~xxKE>wH-P7G*HPG zV!|j4JIn52=4WYs>YFday+_`&7m692;-sq#m&JLK@A@>Andrw`b2xXdbWPU}saPfC6L zE6|L!D}(zqY!2wMo-@kt8Ex0VkS!O?3x*c2uR*`M`V7yj63`IUb%XJGzw3pR!RiR)MMmW#X$N`T4kRG_!F=rJSM{XDHXoIA?c#1!d&vjdDw(3` z+<1r$A;K=G$P4%sINvUlk>!dhsi;!?JWkI99d>e)`D_TqId8r%W;f@R;O4~4h4C71 zZbhFpwlg|X=o)nCp4xb~K?H;Hm;c9%bjN6<1*iD)LlzsZ(X@#xvB9nJyCnJ5Av?u}g6-waO9gXqJ7k?FSC{2ql>}W zQke6(HzilzcDZYL`}{=ed}wMF85J<4e7W(kIlOKbOV!!~pXY8hV*Bc1{(>?(Aoh9F zZ#9g-?ulmR0f5OfYTfIai+PCw{;Y+)olts=7Jbd`X0+gh_wDN%2^5Gj5`I6y1nSz+ z1l&gSQT1WC?!r2pcO)(Dmi+z*DMc!@oZ+z%a)obA?4Upo513!eEY<0%1$&(z%eB}Evqu0uYd=xeHnW+I_La8<#8&(d{RE7O^xFxRFGX;pM&*w z!iGi(DxDprc5f=)n%nERc+WY&`{G6 zQ=s5~(Lr6YG}QJwx`^1rOD|u`ePi}3iovaZU2#{aza`7t@NX2qyEU354)FVZ$B0fF z?NQggu=sdUvwyv#Eeywgz4#%`ehD;B?%_6T2cr~uXbhE(#DJg33ztk8eUDcRqzk%x zjDCXpU~}1DmiK38qLswM{+ONi*Hm_)ce*7c>~-G5bx*8tZj&^&M0VLV>bC< zd_+aL&>SMH4G)-(D<$c$yKTcjXS4j;+)r$a5s@TzO>*Y+C~fVT z#N$$KA{Vll`Y*+~?;tU-L^ZrPBK_hA;W8#X>~1j4nEc(=#W(>{zl=%2hZfjWW zwR`dnE!|@x+MAvF^<-tjl!gOp(Z|+^0uO6ypjoB2OS8rwhk_F*TdpSG3$t07K*9>e zIbbB7>{DH;_cH_Ds(S^UEe@BSyiTlt$duiLnM(qV7+(5!PmZq@>wQ&rfq3KCE;Ol;nKR7{xr1!CC~7WG1u?{BKay%x|p-dqnB z`PysH^6vC~Gr~Wd)Fb6Nd|+Y~(cSJow7CULTF|ZRbNw1Zdj9JtVxLD@n&U=>(6#un_o?1em^Es zMaNs808j4-6dLSo+MYiLQUl9zUhlHtbBMMJ)t8Y6o9F;L;Tb(?fel(7Kn(3a=-rk8 zP1}kq?Bvy=ETy{zH2HI_G{N@3hxeyAS#*vDKdcg|Sg@voPr=O)`2KcogRbbO-h=5& zV|miPD>QS<;Z;QxPp^rf1o3>=D=ySOb`V=5B?`m)GxhX0KJ29KC`fnt!$JHL7Jgm% z)%%YOa_}oH?^eot;|+yV-|{oNsX?4q;C!n>w#t{u^wHGRUQzW}ky`=xsWuJDT8qU^ zoiL{b3LXTu34?#nO^nTx$pQjrrQO>TE8EFltSitrcIBitpN}dE?jkCSk_oPJl51!rEy%;{?(-D?C>zE zEy7Cw1Y7Gq-%{+{>aFcT@S-5EV9}>XN6uS+N@jhy(6Sti4lW{$@MmfZAN~k;Gqy@_ zBBx-!QQZt@Xv$nsj|Kbb{-eF|>bY$2^H=Q9){pDgd)VZy^-LC~yfg?UT1KU(iHA&n zh-h#XGm0uE1AgC1^ktiRr%8O`ZYqXfS)EwP1x>Q&j2euU4xS*V2~v0N=C|Grv}m)~ z^(Wk($9vxD@w2%G&WdBae|DqL({6*^wzMpi>!!Q(EjT5x5dgH5sqIxS!#5wGRo2nU z=Dt#2-Pnj3UeL|wcD(ebY7H?$t!x}*1FnkoJ9_HHH1i%@H(nSbsA1k}wQTwWPs|*x zP3Ll+y!N`4*a z;%#vSb4=wkysKkPqSPX#@|od7DNgwi)v~&$K4R#}=`N@e*x)W32uKYtNPmfmnLU5d z@q<)Rp?bnV(jP6`)rnAzcD)_6klSI+Dv?;En-1i^;Es=m{e0OZ-|IlnfRCDM8bh-} z{%k+~@p0DGUHg@P!uOpkh>9$jJ&R6Tk>+Y4t)p-}_0Ah>sqtp7w#EEq`waX!k(n>L zx~JB38~_t76NoBT^w6!rx0AK7r}=V2g_w!$;Eydmk$%w86%>F}6$5gHV_is7z7Q{$ zsSCO*zN__p@t#$mFP7G~RMcw>HY}mp&Q;b0^y5Q8o@{nJ*?{3+)*RTgrU)4sj_JKm zl@*BWal^(byLfPLBf22Y!>iNd}9pr5J zgQK>{XcVARh*=tk-$lE@px93HvN0NA80sX?dRwluJrkPzezigTEL1lOA7|`4Z+FhL zkh8ybH}hz~W|{@&e5KTkJRv6+Ff!8e&UHpa%ah)okM3i6g5(kZ4YikMoagxdgC)rS z!Z)m@_&$Q!gDz6PAVe6g?QS}-b=_MlsIjNbSMcuh?Zsja%LqB0kwpg@k3p*)?=!bA zANBJvf1YR64szOKvm#A>RGiL5yD3s$J?lt?SD$-IE6A2=h@d=x54X9&UmkHAp5HiE zF&#c93NP`*4!s`wttP{=_81Dn*h%X25*NhmUS z_PFH}`Qa&Q;LtnE_VwGxw?~P}R@Rat&{-hInj z_;r>*v+Ko8D$(T|Tt8AppWWO1oVcrf9l&cg(mdnF6ZxVr<%B2vXygiqtkqBDyznWK z%+U3=6Ge4*Nr%JT61NTeptwN29YN9^z(ID1|HNu(7El-GwWzWyQWePdJYH+ zaT9o>Yxx3EE#}khs%IJ5*KztdM6+ZrjeNT?o+fP>fUi&QL7js08}W#ya=oIFn;AdA z3z?c?33(jTl`0~M*|`*cc6$F(Bc?$K?jTK372xYCbJ6>Hxr{ zaNgNYV>jD$HKZw0l{+#aJ$%m<2jM_g!7&vBYt;mf@xEED%^Kt(kK@d9upBj1futz7 zc}5DEYsFfWS-x9sB<~Rt$u878csN1gRN^<2ymN*S_u@FFTmXX31jNbfGsa;qN%=T%iI^`yy!O6{>Gt$x7~gw~}?L zhMA@Fj_u_>Rhd&Pzj(9xRhRU4l)~*tw8VEO_FEfHL4KZR&AzN~Hci2(FqGk_gxOC} zi~j-}_=R>BJogI%xw}$~<0(rhMlmc>u_E#TeG}@4uoBLIpOblr1u|CMZbwXAC;Xiy zN{}>y+lys1iosCICugepknf!}1~%RXa$MsI%+WGjWw;Ik_fQLf~k>I@GxR zdYJaq^LB+n|Ecn@Jha}EXov__5BUURu^KYT3VkJxBA)j{nu_!2R_Fdzw zj%5~x^g?u8{e%!2*}P*D;>*4sX5v+bbBq=NPj|)@z-8lz-3>`Sok)A*K&{)>(%R~% zBV0_Tg|uLPXWjF#hLErh?hliFCg1`Yt+Qr5a;^;FNxR%eaBp;;I4K`E%q&@hY{iU^ z11Vi_$OIYxu&k}(PA-Nbs~%q5Ye>$zE&6DjeiNwF}#W zpVX~vWkFBN1p8RNw_M86#{9_ObBs6DAd%&Y$Bb1t9M6GR(lMgbZhTYpQR!R% zyslI+p6=OuXtwlKVWmA@3P2LFMBp6V<$Pn+2Wspq1DAcK7$wnpp)*A(4EZcgV<=9KT7U%CTP%;;-~e_y=|B-UO^-^-DFD&GDX zROuM!r%wC;x<@W%uHL&}UKKJf^631$NB~h_aDN&^zf1chhAkJv5DrY~2!>fz&TE0Z z>oc*a|LjEA&kr)3x>Zp7D3F8F#3o?T}Jv~6c*=zrReJW6B zRl;*81a%{AOFr@8KvIO}ol!3};w?nHxXuL@?TZcZx}G^ITGB*=0J5qKfVm{yNA)<$ zqAhG`An>R9xp_?**SEaF`1?(vtLjj6!H4(918rd|DeRqfF$g@4n?cDKFN|1t0jG(c zHP^@tr4xSpml`Oo&YvFzn6c&O=H;a%)-;r0RcMbXRhCki*ao#);zOniNP1&FQakV( z4BsO~amKd4hWfo)43wIAB~~(0%$}PtYuKFidHB8)r~Eo0?Tm2e3#Y-p0amv%x4hQA zW{YHxZzX-EE@U;rC~o5fCB(I(sO7({r47=pzQM(}sLCNhQAEu&qAcv_2$PX6X@)Ca zu6?>{KMt{}z>||}&;sx!Gei&Ku-hU~)-gO)7_sYHS2Vb_teA$dSqqC=`rpbPH~Wy)9x8OxAkR9i zt8=^W>$#=|>k5IIlo*!-UGA*#7h>|IK3Q1eCFvKj+v>mmPQP)HOqg{eCH~ZaRdmKAhXpmZn@fa(B3Pe=X~}bzZ%De<76_|N5tQn=xVHa zF2Y?@UFogs6;<*$7`%x;`w`RL*Gf2t(i{tGt{~Wy}Wq z`{mjE=#*M&9O(w!##Ijw`C7bNL*wnYwp*)mQB(f4MwYO%_i2#LK6w}Slp!fzi5Mot z`|pPjJ5_PedRC-2yW9Nh^@i`m2lExxZfm2yi31W^7(+0c*I8POuXpORWhs?P;HS9| zb#pEeY5Z?=cUDZZS9noBtf*dqWeehykBQd8u}DYqxJV;3Y<`VsD#F9eqg0Z}1t(QD zYqoU&kaC;Z`4X@)JKBR#_2U#zV1xf*&i#~WJ3>I&wfcthch8eq(rq-^AgL)atSq&^cz$-dMiQBnQx2<{8=yxN;o|XNw>dOg9DC z-q%53qfy0ThpIrpsbSbZMVow;#A;7oylv7aBu~E-()1eKXLr;s;Bz;~)D%H^q=ycd zGXClUJyhE7&LFbe9wjEt=BT~ThnASquG>o@sIuygDou$?KHaO;Fi__k6V#lqkk zrpjDYn?}LrSWknQz0T1#!=Sz#bBifqeZ?YS$^&x6E=hGU+z2zkC_0no+2lQ&2RXx4 ze)JM(#-EETi9`C6L`>ZmgaNn7e(Ak* zt2@x$2Ai^wh`vYhB!>C0)%2)5VUc3=Pyte}ecfLEJ;>zXK{mq&tc7?`DL&k0j;CKX zq?~QMiS%BM&zLHkDmEEyZS}_Lx2%bb5-2kCi>-ZkF=sOP|Tep^(2D+ll>gEpsYtdymA zAuf+fCT;FMB`m~>&{Ai##MmvtMF+81sfV%f`v^>YK|zrclfpU(e~AldbAkfTzM|;LYy9P|1>J<- zGelP8GQk1o#^H6W-qG4A0J)T;g{)cc3Pl$D5K}cCVb7mZk!<%<=G6~7-EuRZv&=Qz zkyzV6cl7X}dt0kNLM^A)Zqf;d9Z+9cmqbhr-bkUp?a@vP{{{JhahXEGr_(WB9(DDW zxVx|UQ?y0F7|+?d#;+gN$H@k*&lKm_5td1lEtNmcocOl1T-uxN!^sYailMF6`Yx`A zmuj&tS0L2gC1wi=ASFmMR5Fptks#k?N8DBlUVCYol;uv2S3Wt9h48;}bcIqt))uQ9 zjTW>1?-bezzo_EN50s$sn|y+XtQN79K)l#ti1}Lf#bgv|oH3tcsRtD(XyBJ7shiQ8 zqi8HAJkjyBLi+j>k_1k>ePe>b7v5P|+gVBO-|c(`7xJZ? zz{-_?!SVWon&(95B+fIl`42Kjlh);QSkf`n$!uIz?p@~IiY11id$BZ)+5DOxQtBhE zf*e-%hSMM!-(`Y-xB$S!*rq7r@32KT*duFP_4AYawtbh%`}H3htR+Ao3)`(npTJOs z4R>#3I4(-g#&v#9$uX@UUNV+7zM=2DSWAa*Pr`#0!VZr(Q9~r+_z2%W=gBj>JeIhLI-k_F@nMUPS-UeCjx%^)a||SbY(;sE zMR`P@8{8NS7ePK}jkP9*4*n=FUX7YS!psU@X{eAKonr=PXTFrnPIo|ML?p=nbN=dB zVB~eAU{O9?bJ>;Q*@3uN(B&}y!`NMa=c+=pRM5O)W(}l@5p5(1Omot7!NVR5l0a4K z`IubV-3E^lJ>siWpItRHkVg^zu;1}|-M);N8hwWapE-6%cIo^gbj{A3@F;1zcl3y| z-XMBRS1lDCSMeYW3uH1OzQZl5uUO5+2J+652_ZVVF__x_exz=fcKVVq^rT7Fp!K6E zn`}JJVR+G=c~|YeXqR8s#=&yx&BThWpuBOW&oG)lL|6IxBbc{8SI7XM?y%iH9!%RkX&MkLkINGS

    83ZnnP!=Cn0fp?s}SyXv+Tzrs=^JYc>)Eu8?6!K-i4Sl&uwrk^50L zupRH`tj(rc6S0VQDmI)So)dO_Z;d6Saq1&if4D;UYu7Ho$rT+I>QK z_A*;nN1vA^;{i=8@Z&ZeiG{@>F7cOb$L85wV6$HqO>0<+;gN5;>GZB`XV@21>rR%{ zYZm+cP8a6qi?(JGQIXHCtFGyXU2==De=AKi#@lCoq5FGjBL5rGAsBVTXcI}8k8lj^ z&?8Rf_exl|s^SIcQ5=TpHEW8F);$Krs`_QWf5(aWl&IcW+~48{Q7ZYf+U69Y6orD5 z30yqsd(^^suu_$4x}<1|Zx7a46NF_y8L1~Au`{}NI!A0ilY*@i-j7A?(gCC#v*`n#bNBNGL#=iLmt}jV{}Udt-`%O z{j7g}-KUt4x9Tl1uF1`@UvBjPPRRN59~B5YCYy^Z6o~%XdN;a)y|0HEA0J|Jei9E> zq^%ZM_C|gzKT{M3b-kwFha@@%J+;E00cs`BisWbThy68u-y)nZ`cLR3EK1(fEouhL zlS{Q!g~{}$weGO;-d%(DxoI)_*Zfgfh9?Kbf0)zYx()+o<=sEaBR^C-9&7KSN(z|Q zOvsQdKI1z_2me<+#J4S#=3@(5i>#M`x4C*%j&u6C6t2SQ@i}O*;J3v7VFd@a<*v$- zH4x8**EZ?w`_1>!DqJV-x=fY8Sst(WlEOucHvo+|;X+xJuu+>JfLlfZUx<|*{_uTQ z))%IPskO^`}~aOBKXwRe0R{u;~zEr|tHe#j81KO|Sn1cfSPpoeTf07K zp}Pmv9tvxRGu{1H*=t&R_0jrM zK;nbZIfnBEtk)ex`)HNXEJi9OuO0+65};?6Jfw1I+YZDUa->Ff z=o<99Qwm&@Ww^qGRRrXT`@v%AI)^M6+ z4knd>ydS-{lfF#@LA*X)<>}f-K3DZ!pp?YdRHIsjCyZ(<$V-SBl6QuwssKiD2^V2g0Z02j99XLR>^ zaZ=P?>{OmH4hA;na4d0^5g{`u4m+}vXE_^on1jSYi#Gj7Z}@MX7T}9{JWH49u)IZN z)8B}(A?(%dxy&@BukBe8@N7byHMoQ+6H^=A&#Rp?G4#VK0htyR{wM5rE6zr1^-3K+ z7oeJt+{ZVu^Z5AfmRLtd+sRmBHA$`IeQK!k>Asx{Oru@!*Z>Jj5=j<>%_m&jfV*9S z&?rUjH>P4OC_-bbI%T+vBLspf4$~I~Ts72j)8Saf;Zb&YoRtx*eORSBXul^_x~FV0 ztDR`VbEmeh7sbJn4x>ytW%qtgc4ADUegA-(Gk0 zJ$gWrLZ-9}E4#MSUMxmQMSsxZgWg?pd?^Qh5Gh^! zWz@w!Y#*!1&Gf*PxCw3@d()2&T02|Dj3U)EzrhFnMDvO8yp)V{GbZ)ybYfF!1%6Ji z&Hg(|mo{;m9VdX}G+3g(`h6E`d26cUNy+St554tZn+^DJ9yOgS|6%pZ4Dz2V~_ic z#;c_!3WH8x$e5U&=nQK~yKnm69H_lCZvfrk_@kguNryL?$j|h zwyw2+l6DVz!|#yfS)T$mGL&)FlFBJhUoa|C>;f^S%-vYiUE<2BA&d8AatiolM}%Gb z$tlhYueEZF;C6QXcm9@ZDtN{e5^*p%ve2=oA%PqILbL`;;^-yOSSwHHN}PSp$)k)Y zkAlFBk&fj3%lhMQ*lmV0pLPQa5 zK^Vobnky)~g+rv#`{a*r`94fhq4us%c4}Zm{Sz}A%5+Y2pK)Py{z`Ky)NhJ*z_eY}% z;OdA6-t!;hbo|FSP496yCrD`7zWLgw9!wv-$0I@$D$=(F-h(J?RYsB+ke#8%XhFh+ zu2YcpD@e&eC5uBC6_e+iNn{um9*OV?xuLc{09&s3YZO!ZsaR`mfZ52>+(hU1u;n)W z2%xUNN4cKDDVi(J6VoTf1IPU@^8+X;XH#s=V}#k`8KWsR?S?UA6yoH(fcnq{*71S( z$oV*J5*Q_yd3IZl#j@R`k^Ei<*^?oeKhbQoO4zabYpy`9LiV_M7FhWDUg8c4!>)zR z8BS5iR`H!sdJQ!3^FrZ!=!p4w=UC)?pR`~Rw{hD=7hL8Uw+lvvGvs@H6z5D7{jh34 z`-P!NNQJ&r>;$-rM=rcs<+(|#OQ=4TmVu^ygNBb+n1!xzA`Kz44j9}7TsXxmm(nK- zZ~q<4g|jpOhm5js^$OT5=`^Q<*LZ8w`afOn`AD||p)5-%v#e5N#R-+Gx`s4V9bkie zCW1drw&zCz=o({QKOp)^q_gzhxZ&i*7Ai=K>(5!?w}k*0|2soHf{@U_1w+8|00UVr zua<-e|L*%rn|rO!@%8lGgz5ZecB2NLH45*Aomno!iQlrYMqHj%@qtfh16k;l5`vm~ z+gV04ZmKe2=TD0vg>o~qQt<@u?(mMODi(8f!bM36s)-sS&WWcd81ZOw;(S_8XQR7( z`0Im2htnOOpGL1J*pj0z?WXmBKc(esuKN6#ICg1ZB{jDhdH#6Wlo%qpX{Dr$^*~Tz zi2JM`SJ)gTt4b`jf|e=+?5uG|-agBf<}ZUob=MfY;UzcPiqYjf#OAHLc{NOGZK!Rv zw-)mio}>O|q)D|@qDkcho%CrPQ=utsGOF$78outK!!RpVsQJ9{9~$rn5W)|aB*&|B zCi1Gs51y4X3AepD^w=TpT^{HyLmyMpcWUwqVvthd%$o@-$3ES%PyWt~JiDN{^EhG& zeE;a5jkz4G_nd7PT-m4X=DYl8V~pP}?+1yTA{SD}|J;GLExaLhRA7idP}cfYUDQ$P zzhO%*qB#74OzD*?ZH_psO#^iwBK$|~_OaFtpCkPBa|JGw-C-ySKTZwzhAp&R(=Bsj~e zcjYQd5{kMJt1bsV?#Mj)>L^)opcxA^hPP*zQ3~~0TB00tw!Kq`BL z8r!BW9_>3OU?O}L6%o;_Itt?I@vrq#XST*G4z|{vJ^#Eh0jrp$fwh6uyynflNcXMG zHP^k`X{EhJhdUafx%eVJ7&>#jkfQXMB7olm5h^=MFFs6A1*&&BBVnk(CDjyvWB)+< zz(z2E>z;5Cv@B|*nXUj^wOtK~kWXt|@JyLkw>0WA&R`=TS!a{fKWC7d=)rP`C7TL< z2CDYNIA8;coljs!7(kX92`)q(9gb&7!^8L;n=$EYVHZ~n^ld(R5)Z=bY@%7|=xX=Y|q1y5f~ zH}2u0ybkyYdZ?rs+?cngosPcZL82<_Ms`J$9mX#lQ=N09zV?dNxBHlNn|)n6w)E8 zyM>d*k_edIZY4<-QY9y!gqS3KdLc~Nqqt!My?(vO5qC0h?HMBT`UW+tv;LUkllLza z)tc1FG4kl2w^uJuA9*9!!`drc^*_bP5?p>B2+ppzr-c&lx4E~hn@SX!MYGt8L+(Y$ z$HH|&h{I5HVi6UA@6=yMeE@06>resb(6$l#q2&56GGM&Tfq- zPL}THgE$Y;j~0$kDIri4Q;zT3;ilkU4r?T^$-0y&S7vgF4pZ)(Wy)7l6U07|# z9a>yd08xsUhmC3Kufa$+C)6yJ+tb4HE3*1i^6ZMz;r?uY`O|Sqvh=}2uMHbXO&fe0 zm8H=BX7hO5-%9Uq1m>FjDY)F_M;FWUjbhNsLZ`Tol_Dc2Q~5_>#-VygUAg?qm^wzm z)Q{2yyYf3u>V1@8*PzACs@1MV&yF1%T+*_4O}E1MBj5B`1eY82uegHW4Oigvhn4;x z`32zDz5aLWI9V$u)|A@`_IYuE=rOq|inR7I#AGAFy$kf?*7ufkclED#%nKw14HeY;^_rhG<;7Pdj6aH?eZWKl@6!X;7yY9oQrj~gvL|u*i;tBLz}qdI;uD>?ol}{sqqu~)5%>(c z5ZoB}#+QWy+BH^q7t!Wk8=@r}`-4TB_f&ho9cK_(B_3=BK6Za8BYAIo9)?5LoIl=} zS^E@9v9i2k$PaPmz3bJI3~o_hfo;UCwi@$7lJqGE}0oe)D=PzyM>GVJK6p3{M;((B;R6 zrX66cLG!)AfO(mQw^V?0Z`Fe?@jgwlvtf_GOoBcQxMkz}7hQ&XaERxBa}nd^lIU@8 z+t$+kebrxf$z2ightS&{zxYz|1>v%nNKsAX0F;9kzFfwk$v5?79s8@S%Zf1EXp)jc zm#mv-tv3}DgEm=CF(WD2rU=*~Ge?7e-H%14uA964_Lyl3##%U)!A~1cn`ZdQvAO3N z1emR}fg7n!)x*4444Erau~N@FY{}mEqm2A-101x^MJG7B$c%9$$uP2+L{ z>n`>XyRfZ$?+U{tp|uN64(R+#AAksh`LYNNN}FEXA@Npee5olDD9|WuA2*pfQTZ)w zk=H8(v9nEIog({-3!Qvk`u0A}zt=hkYQ!%oz8M6Y*xp&g4@S|ldW4&F1@Viu-ID@& zCJogg|C8I9UZ1<_Y?P?MQeYp@&PDsVVp0GdNvx-E_hVNZpksIy>io1&_-;o|T+_Ox z*gH;Mhv|``@d1@*cY8LzqVs9QWH zX?^5DbC_U(Jh5+mrd+`0uotxfEJf|i-z%msXYUp;bcRAw$KE!+XyWa}ont7!yR{+x zMii)4x{ILr>ybX@PX9c|Od${niSQ^d&VbKP5_jh^Jw*i)DLk7HZ$F%eofv;QyvU=8Z!7TKd3egl)G| zx24pd5u1IH@8Y3zct=m>shW6!zJ`-t3ZS*~Nq#P&unhD|WZIX#d zP-#AlQf_WJ4MpIrG%teME67?cy;l zZ|@YH)XOjORWQ6JVR@7JtQ1zopE<8NB(kC;r#!Ld{)Qpju>Ja*53T^tVY)%8+QxIzzz+83fWEb5(Aj=l)1!$mShK7;G0=8RD4N{_!gtwEs!RY8Y^>sA@G{LdOyc^!ry9l z=d4hlg)vVF{GIVEj{n7YEWSp4af9n_Fl`;vuvx@UB3C4PnzqSd^Z2SdD1()s$x$cM57xbkxt^RLEAE!{7RMq;?2M&6l8w|)X%Lp$0y5*+Ird-M#qm)T zqYr9MOl7+U{j}WXZ3g4At7*VVh86i=FYOE7z56i2*OB}01+KJX#2EP3zoVNO?Z42? zLM#~F=pSH-X+w9V0so=jiH2R)Fl z6q}6O7Q4J8Ckbs)MQD6Vu}Rgb$b`DaPDE+3q?GZnHtOjcj`N^Q;vvggI93q7L$Q?& z6x_XuS!hcx;875bJDwNg<_vYtO)E@{KWW-{nR!qb6sSO2>2xn6&u?>_uKH>RdhyV( z*Nzr3FM=wesT`O#!5#_dawh%@!fbv>eSu@;o9~l#&^pK87isDH^4~eki`*G_Bj`xo zRa?|-55^K77Hh_tIcl2Q-qIh>jv98K6g_Qkd^L5XlCa<&S_h^1b`}`U(Y5E{bmb!DM$-M>91Xnvh!iV=mx>>^;E0#*6+SiSqaPlQX5PN4oR3UWyki5`n!YEK@DMnn$X1%y zF!%0U>GqXnQXmtbt+JrZdVN)A+Sk+K!xG3pLB`+hx@ZZ{DN%@p4T8pPzrNe%OD0t{ z0Wg7tSPE69uo#2!(T2qlFL%Z&0%?3+Zs`A`!b6rH>i(?w3u?74Tj-8ZMr+*JS}0u# zd1dnPQt(R1pZle2BT!h5&uiHCGkw^KJD;9ppNR^;{|Z+3S*LFTSH^q4X|U9PWf=T; zV@$xSTB2-F_@W$I+`HZC# z8Z4*p#L_>4|ym7a4Irfb$P>HtRjvG!LY* z4}(}8B?CA7C*i}IprSJvqmaPMV0pPF(5a=)9K$8uSwVDJh{UCy*=CyM_yw6DCrPS$ z_@$prNaB1bK*x$$!0Oj1WDP)u#;|u;?T=jozj{ZMl$JV#bjMB}Ysb@_q6bx7aoI;z zB6(*ir+3r8nu@NYOI-qFiR1A-*(d2w1taVYSJ<>`(^o}8KDqo+?D>5|e;0ikP6M|> z^H(qQ>q%>-lRd4d$k_?u2Hl^F{xjpx=sKtG{mdSY^HE!!LZV+5@@D^9+Wtll;GeRA z{VU|~1spgM60~6s@n_)3T!qL{tA##G97!AnnLLVzWzUL!@c3MFpJyG(jhdWqrRou+ zFzWmFUnyZ>se(RGC@AT=v=dNBJKvU-s4;;!)1o_osrAdZagEHxe;(1$11@cbe>*PT zxSf;!_08X3qM@Ja(RHHGY9C&^atNiur<#~>_yc@_+BQx{* z$CLwMglDm$$jFkyX+;eDq-# z@TKJRSA-_Ng?>0=y%}_q_e8u?+5+F$bJ^w2CFd!Fw)LI>$w?m&0n*5Op)#qzMdD$G~lIhwunF|c{uUQl{##_o#8 z?7MORR!K5V<%~BOU3mJ%S=ilgedk9Eh32=2UPKy>gkQpeR5h5)X@$_o8G|2hmgR$4 zuL!qVLcqtc$DqY(lo)?qIZp;Syw${dRIbDgj+;rD#Zdgj?;C*>I_~n*Uhred#`69j8 z|K4@Eb4<3s=rq-2bID-I!&q>c5C!w7A!1J!ckWXe`lPy$NL5FfI0{uS2h)B&GY=!R zaQEA6%tjYtVJ>HbL``H}fmBK##_h#L%R3{Avdln=5-UngKEK6zo1Og&S@amC{iQH_ zB-zS2>B9-h;*cG?&;97qyJyR$Q8@xihpb`eJ}+Ms8^aV232eY>VkW4XE3HRzC%|N5g_3?l^3eq{9HCv>MU+UPyUsQqd z00|$IA>DpiAWo1Xp!~xd{Ve?L`B>-={Z(4SP5-(A8Jk|aVWuv8p5BrMytsPpKFRj< zSkhv}@(sL~eU9{uFgUd-{_ml@P@is|J&m9EzA5HoY{W<1H!WPKf6gQFM!(8rd`LKU>WT33qW=T02L^EG5RyB-EMM!K4Pbrpg2mS zjtSN1E9L)LoyIu0(73v{*vf$AEfR!$=Yt#AR{g-+GR1e^n$xn{cot{8d@{p)f zUSE;8^$l4o^%`Dugl{ekc?ck;d=qNRdP_ouFS~Qdc(!-rVTbKr-6d$51#fO02oqHJ zIy%m8EVoihnKzD(*t7RupVNjPIt-Q9AH{&-)y${@drM`A@7{@!th|N*1j{M?VzWdbgJE| z9;nTNdd*Xli^^UpI> z`7dt3gPi{@o|%FaE#S3xc*jNpjg`?_ro<7r?}Cg@IwU_tgm}r+zK%x6S#t3g$|n~Y-`YAOfEuEc zu>JEb-gmoCV+U&vLyqvh)Jq6JI{ zb%6L1U%&jl718YW|D)`ygW_oOb(4^g00DwK1b4UK?h@SH-CYxcyAKfD-Q9g)aCdi? z!SznQ{m!X9_w4Si`~E`}HB~*+J=6XE9%Y|gnvNYKnhPD(#~^OWNbuwJntK?vJOD?= zIFA0lJaAB52K>WXcm!%bMOnDmga|?$bZYUQ|2oIjf8PbQop8CN$=FDu^*X})01`?F z%uo@cddL(+IZ)vK&zf9s;*{}{8@I`*>Z`o(>H0GkhI5O^Ir#QjDqcYmN=ijvDXaM; zF3FB3e`vtR#=nG%T}JRoTOW7t*5A|~U9v)@LNiT!qM>*`hq#tz=`iQ1?A6CNyZWKv zFPhkM8lf8RSDWJ*g0ziBYA3Wl`S>a2V)dl<%lGoP=)62d@PX(gGMk6m34*GxHR`c^ zC2?;RCoYY)N;oZjYl(VbbNZzU&x}MNBY!MWOFri!(nVC&c%eL$Mct`-c5nu>Pwqd| zBbleE?E4xAM&KH`NUWwa%v78OH*4=zRtM0%lGom?$!U9m5@u^s(^@YwHfEeX`55G3 z(c5@bhU32Q-T2Q&Y?Vs%&VSf3oo5DO8T&xumOd4}vA`TlN?lrtmU#_B`$2^FNVb6< z&8>8yf2S}UCNmZz$muqj~+Qx=6#8(E$_ zB)fwete1j3i~S8x_`dKP8;DNAZsgu%DjBL;Iv6-VsIbiud+8@C6Ma}o}M`Up!y%bV0C#t?Pa zcIUf2Qj>_2`)sB6 z>9oy=5UXsQ2~;Aqdq93i^X}Y9^YKrpWm>U~J+h4}qjKVa(Uixa`NpoFXdN`BCYQRn zFbZ--d*aZu%_HfNK_Rn0sLv;{ko-qP$5!?rI}Knp0b!$D+F6$nZYlM+Q6xY5{ddfB{wI9WscK_%=;z zFYxWdr#@|AQADzUAwAXZcO?pm;<5hLbs!~=r}&_(MsjV1~D{*%7+oMcT zrqDC*(_FAo!*j zcgj6KK9yeMz!VXDugX5$>8@)RC~bkMLoReMFVnrkN^|rh9lJN5pkI&4mjo)!<)S1Y z#Xne&`xUz6>*n-Hupt#a9Bv zB$0~h4}(C*O`DHf_m66cHe)x^QFO0wqN6<48uHElKm@b(UK7MQu!fJFjA~;z0u>3q z%>9sTwn>!D)5k3r>LXyB)1q-O;`L%)6p5GVjq!Qf#Am#3KPaEWVs+E_r=1bmTCAD* z_k>&XZ%mK32E%ddqK!pZd$qWL{Wfq5>kpfGbfOU$`^Q{?jr;`}ea}!uck~&3yBdo3 zr(?=a?&uPo{Rg^gWF1iU;R$IK)y%0Uct?So~8HSM)vNqzHG9*^FbHY z9mP4)c*o1)vW8St(#*h5kktq`xGyLWvMM!SpXu{}H;hD{h843pG#SV(=>P?q;o(Y1N>e9XO?o+u}(wSEY*HHvd+ABcIM3K(#w_-kSYXYAGSRnvfN z^jC+|6GeJB>e%^@NR)*C40i&frvDh5lW*bOFRlfmGom_P{ruP??JtY#%?pDeL)D{S z>KM~M))~QNmC!$p*~#4e?co18mJfu{|Bn}}cl_nfnR&$^gD)}-cRhY(mrE>|i66YO zR2JWk6KARz@?97^%Q-pA8D%2CcfiLc7>vbk12XE%;kl=OB_;-o4qR^zRrd+kuQ{7; z-K8wTCH&Vczjk>J(GRqk`f{?<2S75*f=ACnwK*~inf%MDPKRx5W2mvDi!WyyS8EGR zV)lNuD3#(+8`!SLCEbh}mhjwPss(XxbsXH;Z+UOPLo&6l zqhcOLKcY=ZwRBqS8%+sr_=r|-3HJd6z*=d5|La&?Jh62egHDprR6&CKYoWCH4u&|t zTN6Yk4$@X<^c||L)`983r*rT^3_kF_1kYgJLz?bKL)BBTTz9h%M*rC|aO0CN9naPF zdUD>kTAD=jND?9_@ef5j$LzRJtrx*f;o#)8{d;?Xvam-lRv$fg@h|CnLGn6B7OWUm z3=KImrOHp9Jpiewr*8*sF(GXw`uCxN$mj{YdqHcj20c6A)QEY0Kx{=#5}K{p@Xefv zKyrqQ9VMe-*H)YxR0fdiKy%_p7}~$a8sHZzWA>u z_oy@ZlO=XUQg`9Xkc9be=Z)OG@|3!qO1APIRWF{ppQ-^J1o-+N_=2%c)N5--gfj55 z5Wih!HK_T5&HeAQ6J(((OL0<}!4(@A!==VNA4Orz(Vof>86#^VJVOxT7%wUf{ejej zelzMr-6u8fuqu2x+g{=R6CGiLDSh0=l2HfsI7w~wMq5A`(m4jnG^|A>eT1!(bt zZq++uo9cq+>*Cs`UJ0LUNL&r!@y2?Wkm{f7wtl1yihIK8F<#Z4`%*~W(j1ub!_DR-1}HXK<;X8+>;$cdHrp_du0{CyGX>7m zK*s8+me=-}d4|l>WDe7AU@ftNr^uz;wni~Sy{m;x##`!zGq3cpkM-4NllVlmNAe91 zVI?60NlH5{87Vz4P15O}e`Sh+^mz;NcCSuVNiDfc`AoJGtJEs+`u&8Woay)-LIbkn zdEhE^x7Lg4r+^GaYL+G+9%}X)`qdS~ zaE=5C)jl-gPuE~6pQ7OXyK=$}S%xmvr$#R;4ByWhAyLMPi}iG=i~yEdFKHuuQn?)e zhn6ZQAGp?=GIrZY;?qfC>8ds{6dc@301urquQ8uFjw^Osmm+mIdXw`xcdy)%cLq&jdKOP z+MS?kIzl!&k1uGNjYC)VR_yLrz-zk&H}Mgrxbee3)tS{!e)DhaK4WrO!aHtu7}sv` zAZyERCSRe+bQJejhpEcHr8qHL&0_lgy`qmBl_)m z!%TxvP%=V8oaJ-JKM8n?JeQ7@7YMI~2`aWwu)zki(n=pFz#70Hqtdn@nsdbM1_)oA{t#)tF!wK@BkW4K9pPyJE ze(0Uprw@JYngjjt*79kqp<7AD{yc7>>h@eTwr#^g&ld`brLt|Iu6G4nUVfZ(dh)OD z*={g}=WoHu7msgb({zG$(GzNC61k_vNGAawzF`0UTqfUi5%tE;8(4`u#jCSl;r#9e zskn`(uJ1>cLX>v*DVq$5*}WC6kivZ-m_f8uJ<9m0Vb}>h)hcXSM`%~vV>~xER(^z( zMiLFkbj`NWpxn)*Q1vifR=5jNa4p4~tu`#?h{Wr+?~)qX%b4vEg(VV&q6nSvxIe2! zNR8-0_C5BQ%Tph%l3U~IZWVx^uQh#J)7s4JVu)OZK9((W>;XM?`Bea_kf;eS(eDJK ztVq2xi24FsdWbzU|HSZJ>uK%+5!yCbo~Kf(U1*7x98(LFx*c4SdhdwjYlZMt-pQC` zF;bwuLtn?yYmS5@HaD?yz%=x|SvVU3ilvxu1oFXI|K$BiruRjj^ise<#tHC{0Z{uY z*9Tq~<)%Omneb@e#j0YrMN<71i7LZnzmesyJ;$^lbEu1uPd`#iN-_fNlC-dX* z7=ui;ifF^?f%#1< zT$odVrpZ$^X!V-)U+(X?$-k2`76@5VjkQV2Q9$h2<(kx+XDT9vz!@ z+S&i9^sNFUh>D#1`Rv{Ei21ZL$2B%Uc*7p&y%jrTsDs(g630Uc0jTjzpFy0J-KB4z zOPQusL=oxiSso-gJsD4SpmaDkKsx&l91TgNpG(-Lj0<%FQ4|UYHi_RY|PIEd? zyW-G#8dc0wyY(a%*HOnU369Ex5~BK+Qu>tX)G=d~7CM35BEyvCalL(y65{Zo@@g=Q zMX**aqeg;4swVZ^{X%ufTxlS)uzr^j!el2`Y2G<6ndZm+I0m$NR#RES^y5U!-Mb)3rgUrHBfMy8 z+$)J}h5&?qpn5j(-u9{`;2V-4yRIF4sFt~`>;pQ3*bIC9F78O{j4qI+?z-bZa?b1N z#z2uKNqZ~{gcyQ}dpNnT)VS z<&itT2Mfxky_hU@hBld5-Bjg_+4n&G`NkA{YunlkkrSF}Zs89d4`Z*hG--aB!*_#fVff>78uI4D7 zpI6j4J81uJP}f*G2Z`b<5mU3oWoQo7V&Bg8AV@A;8~G6HIAr;Vauj_F|=xoqN=vs{mHO%8h3BFR-u_ z{)6|XAK?@uhB7%V)J8Jy&{dl(n$f-I6QG(5*O%R5a@qZ0?aQN6CuNIoGAU(QkC|Ol z?jrm|>?axlu`fDD(Li6rMZhLVMu?VNHXrscjgv2}nHH5;Ok2pMgr*kHA<_S`5VUzF z&a4r~$Bs87+6q7reu~@rRap`Fi>Qf^SLLvJD0+DyJl@3C3hg zhb!x#7}RHCLZoc64RDqKX9iEnBho1zvEW~_aq*DgHc^3%?pg6%+7vkvWcTk8>Jvn$ za?xAwc(|~Cx{yGmp_<$AhDCRyXCuqr--{UB7#%x8NLd)j3{ik;V1lfauPQlLH@B^+ zHEnOh&wW<*xIK#@5;<72lFYI67#ekb2t51qPDokTL6?dd)eC;a z>jeJ{a;p^!kzJ<{bPeX+H7b*qRSe3;QA(t7?k;!u#6hywZTg~Lv@Bvjw$%G8WNW%E zx}1o3YU;XJx2Ckqq1$}qj}vsLh6vVl-OafF0=^Yk%xnM$T`vw^%dISwFRCyzE=&xX zG@mEMKAl`3|G8DA?0*r=ky3EozMZ~a9J_J;*tA%Q^33}hTxiKYIXa93`8rr>ByhqH z!z{GMM|jd9xzPr{xwTyOP0R`oKEVo}e$TT%*z>t|jBzl+>6@zClB-@_k zBjSYH$s*(+W764Qud_6{S+o?l2@X$aK4v0eXEM}C@28cF+uZvuE=jjI5m?^jzg~w* zy2w0Y{$AuJLjSHY6s5{C~%T-m!`d2P-Bd2|Ztu>53 zIYY%x=lMi_?D3@_{~44xUvcN|A_d!CIR&|S#khPflIMJAx!ALEmpbi$Dwg=#OOM+( zkpB4qBS5N_)j0m`@uDwJTTNlN-=`3I>5>dFdv*61H55(I?~hfEws!rDP*WaPnmoUF z(K=U|f=A<8Yow!xrBt#F0w&|jZYj$iU2}{F<=C!Mg2K97gL=PAs0;URPvM7SQf*+R z2p-7xU@cPw8nz*z0z6b48~`Mw#(UIL30 zL4xR7{OVbQAW?L=%s8`Ll@3pmKB`ZB>EK&88*KnG?4&VkOpsbbGh#`9xxR6i^D#HR zw3Vb!s0y9LvOf8;O-HE{m5tTI$1{1wpU7a}Y?B{0~6{;2X)otix8YfmCBke5!3rFO*T$%!xPi6Aja0Qc((NkFXC z|B1#x^$`ADMe^iUNipvI1}bBWWa`*=BOftR^0}4X^*F|+Yex$T0aZn_Deq4!&#!&# zL@)u)@S%G{h2uo^VRv%4EAB~INs*i;!K2NKNas<}Cxfe2$)2HXC8m`&s-!RW4tpv} zOp=zGl8y;HANw{*ea7X#Tf4(O?3b5Bo!i}z-QNmGCtn3ymm|ud6-(KFsMwAg#kS#> z8L0DRd2mKQk6SBx3U8Gjf{ESKMyhysf2M{+t96tt|ZGr(=@~<0LWk~&z zvO!Zi-}Lz-Lo%5W1Dx3MZuafHDASD6w|K0ImAiKPY^Pyj{8xPZG=#}mgL!<@3yugB zlU#e=7f8u@_6lokfR;z-cbzU`{7n~78MF3tlvu_HkdPcQ?xdljPH}58U#3Mq(>bP4 zjx^Xa!|q1fj@H9FVmX$gK%Tv#csmiUa=Z`Ue+vM5N8H4ISl94=u3{&=^3{R(d!4@o zvAIoIc46j6h3TJ!d;?uQCD`oPR9hys+>vlAXW~Iwu|xlV&@BDGqe5zlm2$3bU3113 zE|Zq&+vSk1_M~TL(`71N%hs3nV&2=NjBY^9F{k%Qej5pmi9}6bNju>Bm?Iv%ei(@L z?F?=-S^~c3$cO^3MWV4K(D?T^sv;Jz559=?gq$p&)`&Y8&1Q7GPCHiN5d9%P0>CgF zl1w#PUEoM=OB#oS{wgju)6X6HwM3GC%dNQJYZdsuxs*S9oJEC)WZMlbf;xDUgrwH-QcRB|8)jQ>FazeeV`lvbof5I+_Q4QS~GEW z+7+?#el4qXA7hMfNEQju_w~Z%E86Q$&AgT+)!K7YDBTzl%>1{soKeDFOXQ1`#f+*b za%P8V!9=u~FODa;I4!hBzbt3>Je>Nwzk0tP$D&8#gPYF_As=`|r<~zl@aD#6v2)py z&t6pCC_X##Qepx4s037buVa?(MP$x_I~Ej#Tdps0LxN9;cu~b%@gcw= z9y7nG_Q|Jvv0fL}+qC}4Gkrejh=buM-UaWEYtDFj(?K<9v zhw2nh9J0%>6DOYsd%7X=9ieBI$e^zD)K3y1Z2B~3omw)?oKHMs!%oE1mB857$#? zPEp?uhJ#Uc6WNZtcD20L*e;GWaOs_luEOb#pFF6MEDT40?-!AZVo9BYC%VXAOzyvM;jpmEFt=)}hq->ZGka>F!|zS6z9|!tg>Y1& zqGZetE8`=N`x&?LrbrN><*L}W+Q5Jr@DmWhc$N45{_c^U!p)G2yuyOok?1d?DmmsT z&}LQa6~cvuoo6jx^IjtKb?36>(4A}pix*d2a)_+#*_)+r<1j*)+ylLi<^CMz&)S9R zP0dyY$@gk49W}CYN5K-)Tv~I_k%Dzabi4-tu&95p?YEcAx_`4`fBkX)(Rv4pG!iL$ z>0mGy=ehs+Et&n7kwnDmRuV&DWU8Sp4hQ<57n(y7zt|k{j&|9Y_gg$6{|Jm>52GKN zoVK~;m_d}RCPqVQ2tMxR`TtKA#{`lpSiS%ElZ0G;SOqd3bb6C zjGs>C>Y~1pSYfVxH|ztJJ78ZT^!q{{cMQ|hV`JgCCwC{A*xE`!gpt4kS%!Q;Dr?gyf6Z93JNY-Ba$b8e zOm)7o;?nS8u82R?JNIK)wHvw!%Qryq1)8jft^V#hryBM=b;69VUgVU~V&c%V2EA^c zZPLLOFl!CFjq``Z|K^>#mNAfMgXfKem76x36Mrp11 zsinC7fPiFpbSb2-r7Otx@iA`9odAy6swBRrSxz0~8-ErtBZQ^hD#a@KulT1y`=2V( z7uTI9@?QX3P)%;Y4+Ywa2TE&|AuVJ#n2x_)GLOi;)%Wh33A}t72j6V27l~Zi zXbkLg9mmROn%sG;-%unCT?jOaHCBVqZLc1e*^cUBSMJ)nOl!-><108z_Y$9|1hA5w zYHd0xsa*^wLKaxuDlpKgo#^mhC{i+KXX2MhF2q(ajFuY4j{K8I}(CdGYNMy z?5`Sckczr~a(gcw4s7!fDDmR_c9V@d9zYygA5DNHPF~W2WoIZ@V>E#i;M@-?cqWxL z)x8>z$&K7TpdPMGW~0H}ucRRKuSQi+a0p}u^4YMo{o$sE0$gTH{@$+dfm+JAx4$;| z$SiUZd zI~+ip)VB@xS0SW^ROU|vQ-&|LrN)~eSRt}*f`HS|OVuA5*&4XQBJ=hB92WR8TzEq2 zwmAP2PoI7(U2wC<4Eb%|iJ}7E_&8{w6@kMxR6M|(+4J2<`st?XqlDG!R^+P)yKI@} zaBM^u)|#N)zoeR)PK+O5P=5KHb8>xZ@!C1?W!vwg(_|=6Wf^OJBuC5dn-ppk#x;=) zB3f`6jaS0u4wKIyw?7BkTeTz$$+H)MT=`goo*k39Z{J`<66huLc*#nQ9IRA?c8P^b zYe?$>%c$LY9~_nq(R!8=hRuX}=^*?-U_SHQ*0yU5xJtlHRM+6OYHfe2b-v{1#6diU22*e!i;~emG0G##K8#=)d2mPQBC_t0ncV zI>|@edsokNQ-b>dt#NtZfe&{SNfRc~QeuDq6K-jF)XuwC7XEhdS(DV%p z$ubPtT_^z{>SQxYfcm1!N^)s7fVrO{OYPIw@yK>BXv5to#xF@rkV>A_B35tcQlk#= zpGqE3wuEPJZK>D_K!AQc)s_pLQ18G=T&M zEp7ozC)J7%Yly4u7YB$ZzTl?Xpqp=*p+xo?bXg^cg@xomGpCS+UTbM6a-JQb<&|sQ zLc~{BU}dzEX@oGG(q*ys9+v$KIInJ*gz`$8gLjrCdtsR7?ddW{FmTzy*JHS@$M#t8 z4qM4S#)v~tPa#sYj9PviIt3E^KFL8gb*8MPJ0D?-ZZ@7YZ8F`8>qMuL(Tp~urG6M$ z*Q4Pg%?hmQ`9|kfbpJHvF)uFAi&+WI{x=jCw(v1B#Ijv!Iq5IS7%Ba5@cH|&) zl=ywarJ3rTy_i7N8G5z7kfu^W!{#>=EPcdu1C?cjAx$Jq2SkN`DUg21PMaqlwmBB@ z5kXq4aLM(Rjri0n2)=u_N0$qkQOM%ubx5^7Bq`+y7+M;Pd3d z-jz^MNA~Jr!UV$_@+u-ZfgJ)-Myok8Sm)#JS1lB||0e?_xqB44-D<EjNud$X& z>C+T3UZZbi1c@Xd25v8ifm@UUohZ02hdv_$z}GMMx(v-97n^bb)rpLr7iyU7@%wzq zoG*cpW{h#;ouVeXb(GA}`D#}Z8~0FZdRgU4 zb%6Lavw`g@QMny1Ws1>ew-8KA`Ob}ND1D@mDfn0l=9ZPWLROdsJ1y>OKpAa7o?E#v zZ%?s17Ayv1L9Prk#u+&wD}|^&X)mT6#xx-Yhr>Si*xQOsL9b1|7<5|e`6do@cp{gO zrSgz-;K+``Vx5*>r!k^8aH(deyFC0u4)1GgZ!MWM=K_+W85{57ZkC3zG=uFH9l;fT&Xno5yCdPf4Ml{e3G|g)D%CTXXpY0*3CY>8%T;;Df@HHy_ z+3%Le0`xTQ-#|e=&cRb;t%M(E;BUb5H`|Tx2CshpO`i7ezW2M9@vFm~hYdMt$E42n ze8hlz6DVpJU^EmE^(CuE~^nwF3yNaJZcG(sf%jT2K9W{~b9>i`|Bo!g>J;vIX5CU9WGbaa9om<60-DX@; zSPFjYK=VaOHQd2eSiYxGzt@?){%KxmU4qn;!cr{SIrptL*`K-bUoSYh9$&jYl>NSj zY?YG-?=$^bn)?4s3jjffcN6?Fb04eO&A6fU$pC2S;!hfSs zuY6`FqAq$rdNMk9gx0$(vk}MJWQ{m24~a6AlUtaD4w+|v92R!?grRlHSm}vJm2yf% z<}Hi{j*@u3@lvOQ1wfi`J{q1djWt&4;REZ(^mgj#&pEb-Cww7QFVnQhy1kRaUr*(Y z4;5N!VLL>CjjyZRMkQnq>jHGNNkSzRQZ*+PEvObZlnEK0m9+Fa>zVCg6`t=wIy02E z?+|sSY!8DVZzZ}=q46v7g!_Y6l;GD>GFA)4nPdFX@(nDmrXqc}W>JPxF>Am&yg z6tbE{LrUH?BA_89??=*tBzy3iP{9Edp#~BAjD{q59fgu1g0QjKu?%DM_G{chw^im5 zkSC$pD^ph2GI1%E2GfaJ29=-nO_{pW%Z^K&R?ezQ1c)O;=3lZF(j@3a;P(?QS9>+~ zm%zd>dZ+>2qmR314*{@ycVo@IchLE2)t$6yGe_d%lUfn8Vng5xtMQ6u`Wh4!-s<; zBE#sNd+|>5G~}yHuuy@vd9EaX3T{3OPmLn}Rd90#%(7}rEVIn-wdWfu!|HKy(fRmq z5&YjJZ`sh4sl-E%ziUAzj>40_(h+sGXhr^+8DUXskp2&{cu|^DY*q{YvRP%nnZlV& z7S_qR1b-Jq=OHr#S^M(=l3mxDf@2Hv;@a}4!zXTTd>rJixjHFHuyr$D#nNAah{tgT zY4tdi=z{iRK31esP#jOzZ2qFVM{Trf$A~vpdRc${J=}4E#PxZNX-J5<5 zbeH zft(ltUE_4iV09B|dOk+(9xW3^vQ{Q-aYyec8J`)w;J7*5v4MD7Mbe_nd?#K*wf@Od zQDedqBp9fL2cnug23D|=i1>d&j{fxCeq%ZJS!a6``JBByIYIL`p)4`KncBT z`nHpnLb-girP6BJcnkOHsr3uJ$_ChH&YOoo&AwuoQPrcslia3caO>U z5?dtXM%ocuAjaDellOEcKoz=(M09oM6pC773}5_YKIf_B@n@H7HcJeK`a;o1MZ|@1 z&pon!A9b~{Jt$O)gdZ9KhuW=u^u!RW3OF(S;q551%GAX^rVpQ4|C%o@;a3HL2$0GF zo*asMuye^{rNuF}3c40>bgQd3f4jhJC$<;QrTfH1)KxX$0}`@sk_uncX7wde6vOPN^54D-I?+hf{a``m+EM>Y}eNW4_K{$6CpltyIw3fsg~v%y>UIW7Kc zzM=mXG@f&8v`+W@vl(T)ul-0IDCriMFV{R}2hAS3p;pl&Y+Ro7@C22_TE7>j@F&DE z05_fcOElxZqYr|iyBf(oYm84R7faK-nza+|fP-n8@`Ds*)|4a4H@Ke#^4$G{YS;%m z5Dh@NVpfjcKZ@nFL#f@`Fc8gziGMAWv4(N#Fss8UHbM*^N8P#r@ED;j7)l>?cF9f*$&GFmt)D)1r+yjne`h z^6h_gAn1*M6nEYQ2jPb;$6`y4&!8?k5eT}z`d&nc3+ikC+Pq&~26XyA0A#nZ6Fdq0 zBsQ4l6Dm84<4I#l^fk+v67czU^v&|w@v%XQe7NLieLlA&xNJ=|!&}J$;P))w8`19G z>_qWk&VvbUzQZb{SVGEm{3LVnvb@+7UNBL-9dV?Kcsy`*CCQWb+z@|TC|9~)6dd}C zciZp@z$XDph5KOhC^gR%HEz#Dhhnp=4p|Wa^K)A8JRKudNY4`Twk9u$XxuNmVr*JI z_uBw}vUuTk!MvjT6*S4;X&lR;! zF3yhr^BJ)Z1m}-EPg?+Vxr#D7t-r~?qL=i6Y=q``=8x-XEe&A`)EOsZx@%gPz4!D` zVUV;|7@+pNyRb}S6d?h_Sdu^+T6nx_EVJ|O!s9#ZOMtgCSpSm!lcSIQ<+yG3UL^jKJ+o#kXc#eUYjA{25W4x$U z(QXgtY;R@396l8O-y;4ka_tdeSWM;jk~+A!SaWdQf#&td9os20#o@KytVW{)D(qfp zxnpQ^b%F*Kr4E@(shiTgKb|B(I`s+BTxmBPU42O^+H7*YXQA%U9Of$z**wAYlU;&u zOvGQh2J#?P6g^`-x-k)p(Hg1C!!yo}R#hztvNe)nn#H%LzIGbMXe#Mj5qyI_awp!e zyR_|}ha@a`2rhg3F59$aMdgKD(Q6N|Qr+?j|F=Ja`bsR-$wWAmUJB<%&ylVjCc({x zHWGuA$wL&w#iuRdQ{7wedxZ;K-msCn{L7V$lKo4X*dGy79EZ4qt)iKDF%P5oIQe2~TFDV^fFFCT&F@wVR+%vRs7)k6k1;!J0Hz)ApoG@rH_Z38F6jF6m ziQ=<$2i&%pBDd0=2cg_W?tmDuItHwy6ShD@wd)0&m}gtn>#Sjn!R?&q`qc>e!h()j23x+XOLln_DutMxASk6-QYHHfm^r|LpNZE^h? zAR%-(h}b*WinZzzNjWrS0Wx~1qsrauNoG1DiG|M?(E>I%jeLF}Tg2&6d+;iB@h%ik zoZjb&g!y$iV3_ykkZ-p=E{qoph?dTpYwW#bPCm?6v(znl%U)-nbt!$X&UYDmak9~Y z&Er)^YFX7^LQ@W`WSvc0IH7eQ1+)Ec{9TeDaC`oDXD*d)#F0#x1-h;6MFQY?Q~T%_ z^dVT1AfAR|X`A^lzGfDOFY6&y^Yb`4GeNQT8F7X3UY_6d33D_Z?a;P1-VnGwHEJ== z)qZzWN0enSLu~HJ_FN}&g^5X&2-pW0Ea-4JpRgBY2WcrJOs9IMO3jfep6vjzVi@Q( zVNpJpIf0c>50$y0h+}3T+?V zfgzuZ@@s*ft3eq8)RHmVAjFyS+Zfl5(GHTc$7-y4WstshA?$!n`2P6{ zA`6BpSHq7;Z;^!gLj~U>Ddh&gBVu4)Lsa^boXo?Z$2F!=ZamEO*y;^%+#Q}!yH9JS z&ny)xNWT{6Y>yqH{1ELvQyANb68k!pHTaXFZl3>gnHG!?cea(Y*AO08VRzR}h+s3kl~{EUB#j8O zQGH}*HDbv$&$@kJE=6HFSL=Jxt3V|bv=+IJ>>aMY0@~#ikXP{Rr4K(#0&Nf~&fnYO z_mzdNpW&xrF*wnFjMC}c8b?SRnFp>QkC@MnpY!BP1eqTN$ zo+l+DR-bTLHA#KuX^j5j=ekUakbal&_C&W;lRUvn9PuOh&C3xmFZU~*sP6W76ILy4 zf|Pk0uNTser}n|}SEM;_fH{ervsYJ%~FfEB(bsg&(tXg!~8?;tRt#ue&9_G-%?$l1TBJm?&%FBuSd zGtA+Zw8i+-jr?KDIUkYM0=!cZc^vh5T>5#dw=FT0c(zt~tkU(wPAOq~MyBXIeA0tRUJru5QfPjFdz^v=p; z6vQ`we}*>t@kH+ugX2(L_XRap+r3{fmw*?=n$drTH{Fc{+U^FV;&Z48FbE7cEY)D+ zH*HgM0TS{ajYgmGV7N4AY{eS_Fxnpr#>R;3F(7d`9VR<%dN(7MsfI5UqL1)8ZjaLa z(K|9G-PYZ|Z0wlHK17fO%tzz+e-MkgIu--^?|p+Gl+W_lxdz_$;`A0Phx5_j2L!WZhlED)F~0E{htc*dcDoY%EjxFw27EvKh#?< z%8{>zV4;j&jF&Re21S}K`-p*D&LVz!Qt1g!srxb<9cfzKo1@xnP*TuX7wRzo(rn83 zGI7w8N>MadL(O`cp&!sPTc*0o1d#$PK?6~Dl}ZQ^EQ9$aw^mtD#> ze{UNwNx3qwcf`yAA7_7<(ePfbI)BSnGwD^CJ81X2@q&z^71vGwOHOKF$i7yr3LKt& z<=A%b6ILmVirnqvMfhqB+R!Df2>g>@s`M+EZCrM_Wp-gstHz-9(vG+%%L05YKvC+B~uw&0c3 zPgXkONU6eMQ{0@G8|I>ND=4I}RFB_grg_DX(K~shIx!zl zYbVjxM9xE4I&ylG1vItT#J9}mw;`-tJzL{Rb$a7ZHt|krVryqFM7!<-^zGb`d(u#L zCU5Sc@BUf|&5NV2-oyjN^pBvhP;_G6%;OqFn0*@M!@%b+n&qz#XdR_6VjtYn5qoM+ z2?J&7437e|dqeKTGU-TgxB{a}LV^BtG>?x(^j?CD)(0RzpR~$__Ouq!=0w8%W^^LX z68LE`-89L*!s};;#HY2#3@;uI|+G#FG-rhRAE6!2%D)K743l*j@N^ z3Mk1BP=1Q9SkPdvT1Ngf+lr8v2Q~(PX0vzA zQQh-Iu^g8J#OHgmb(j1*w{`kcub0{73&2Z-7#;A;tAW!H9IlcEUc7EI!k_>(WS=eD zJH6KOqLrcL_U9{T64R^M&pkg?JcC5+emE)nUmL7oO|7_;Ep(!uvbW z5b!F^+VbP=;32r1^VKPS+P9i4gt;Cu_;!e%?Cr|I{LZ$)O!U@T&>E7ZvV(NH{DM@3 z7uP>xZX^#|a&6;QKJ?-Wsn6*f0mZ9E?~x>BSndFp=M;7oO||z+1meD%R&P*~c1?LQ z89KfXq!;P)fL!q4L-5Ulv0zvLaDky%VK&FQ*vw_o*<>N06;|*UG>pXC!Wpw@ISP`l zRQ7UhJ-rMJ0dE|>F|+t*9EGX(r#p_mO7V56x}Q@NYkRe&MP-&ZdbBjEf5^TTb&vAd z7_OWWAM#!pm?E`)B|TG1x}2b5=f?X-XO4@ZV#dL-hleRm2M;%U_Wxn+Era6P7Ip1F zfDk0OTX1*x;O_3h9fCU~5Zv9}-Q9w_yE~0r<9a)L?S1xI=j?UvSGT_Y)78~AySjUh znq$moys~o;>HoUS_Qog=y-_dd^dudSkaGA!r=xFt-y*MPOhlb1L|? zHi3!h8|v}umFuXKoX`A<7F>}Mq1U=(tMbo^)L%jGC)NY*etNuWI^+GLIbFtP4-z<# za^Qfi+gGXLbq z$FQ_*L2dm^MbIkI$m0{Liurm0Ov&a~n|+$wFo+6*wXU07Zgstdj5&+~M*Uv`Cu$=5 zO}T`dLbWEIuTG?Ac#nbate>cmuzsgeB+VC^hZ_9kd=A*@z|mk!(r_S`i5=J_{hCPT zckKutNApAEj0d$jf$PUT2P>)NTvpk(XNO$V?9>m44F!XR9S5qD)gB!~KCD;-0ux;z zIm-(U-+}T6rAoxBN9WX_@niw8pLsq)p|=eb^v1l-K@#wMW_tc%-@kM-Pu6pLVBtAk zN&^aHLhVd_zRd4PLuNxiMhb9+9uUj>rL^Lg;k5*3so*5HdQkU0B5XC*HlL@!T$}2& z_kHI=n+BBEN%iD1@OyS&H2@&vWhV+8{L4B4o?RgV4~8VIj{QWPFOzj-<=o1IJ^bIR z;NI}t6?2IXjf_;`**N77NF<%>OiCW36o z`y=R7K!!!xXK0&a7Hoxen zkUrA!n3Cbox43PuZLB3kg3uny0kZrN18Ro?zQORUq5f4KK4#8OEY{;$Hx5|xuqTo~ zCmjMNLN_$1R1+*%M+|Hf@hq7?#@5Ugtx*J%2R8<{0WskVSduyXC-P=!>_fUr1bE9b zyp_{E6N9u6!e5OgkXnU7SujTS2O26bs1p=^IJybsBR)jA z!0-kY4^At(@Rj%MgybmODzTTtG~eLYlo3b+qFs)}2;>N{zx}Bt8q&0ZmS% zI6U~pE;@PtCo-Y-@V=FWi_KC(tIM&=aFX;FjjTpY#X|7MwsL1Q)aqx(3LP#({V)7+ zC2aXR1048hm6D}hhM0>KzB;@S#$M!T#5Z$=2W5DMH{X!p#t4X`&h|!aHab8#Q+N_~ zKSbV0usy{#@}yO)s5Rwl>_3u7bQcKd9Pzl0zFgqi^034WymE}KMy{=6E!y7nc2SRI zc^5gHp<{_rpg&p;d`>quf(b%8^DKte;EfEI*`IlPo4>e;ZH2IXNj40u03K+Vit~Zu zd}ZU3Hv%(VBELlA%4{YyC2-LLmD z+xs$s-x`cDB)>S>WNa)=y}~qcT8hD!>V4Jec{zq3<{hXD%KTxH6Ja?dHRo~1_p%C& z#@_0Qj-FA!IgwFNw2Rx%fB1Spe_g4I?T``WNR4{F7yEE}u07Fxd`Xxz^Sm-17s}I3 zsb@VC9TbKS3Mx`Ydgir4P6+Lv_Bnk^GBOUJx*?Qs0sq#Se5~c}ehNNF@^y~h%91D5 zR<$x$ZCS?`*JnR7SDy#DB_Sn=cIIJd-;@kaW3U8kzlea`j(;{)Nxv9M+TP-fL(XLK zMF1{yHkPpTgZ#YU_T`Hf1SkFeZZt#8&w<~1ri*0epv&qROyf7b1Q}}ot0AGYKzHCo zcpM-S>TpgYwtH{MFZuZ^*-k%wUv^r+y(Pfzq&<$-W(Z3C8a2H>He{piM_5qGV3EF1 zGHVlV-`r5I?wvvElPs~`adDV@#9=o`t93-I>NlaVws(@p_^e=wfzmieQui{^#Lths zFqMgPKpQYytn0O|+8Xxb%WKdmWViESsQ(xK**xS!x8T(FPW`UeuB2joq#cih`i-(p zId;Rle~c_*Jt>Tbp-gZ+=9m}ih|8Xej7^qQAQT|OH-x{;2oQ6ZxuJpM@kn9F{Cr<- ztk+=f7Ml%CS%G8MvPe7R?D#J&Kzgu)NA(jwcaSR1bdS^M8j-^fahjj=3ZfY6&okwps#9;w^p6u+O&mjx=Kodvk zaz!K3Qs6lqk<%mDRm1WP8PR|st}$LfI=?V~XS5^UaluoBHDPWMH{1a1+T~*ox#i0) zJ>k$`TQO=EyOOakMo4|_PON=2?jk{+Qw`d04oS(gK9B9Gb?S~1ZI}%UiRKZO?{c#O z@smWc&Df{Iiym@AWg+bCKIffc@exar8u$<>uO1`3V70@XLoc3Pmx;-i>1zKtJ)48T z^NBLw_Id2^i}g%7D5WP%dh4=besjfQAvFjWb}i|vPBB|~!0k?JNrHGVlD00Rzp)3* zgQ-cK`Ai#s=p9^M%@N%X4-7`TM~xjHe?d{v0`X`9?zn%!(%)Yd-0`I->YsS^kEiG; z_P=PJMZUK^fHLJ``u%(i`Um%~Ft&|g0@czDhf^F=SYrj!%ite%jFQ=*iy^|jle+7+ zWcK)OOWYC-E?e#rTqu9bp(|-2*FED87}7g!J+?V+cu&X5gwawQPsMxeD~-9mk%nT( zUZ7@by^P}?jYLk|!>!e3afTuwL2s#mZ0$Urgx z^FH>`lX33@7fY3^6Kq~iS?EGJ6#Oi?9xFwB!P0mA>&LvK(xGZ_L)qA54-Sm_%xdcp zjCJGnJ#|!39kWAP!DEQ`ZiWU5yDx=776826aBbVcwuIg02T&<@C$22dP_HWIN^H#C ze&+6UeKL#BEv%O~YN>82mFoQBe52cIk5{t-+j9owIP;-m?k4;4=&@&C8}%#hL%m7` znT_CH#g6*@gv59+l-*$m#s@h%!(RjbF5u(_iHz3lbdnag_c87W<91h`7GOrYv?)JP zXslMk&-ri%$!s5PT5VxOG%zZ);IRuPj`jTf{jk_>EWVoSq^Hb{>X{=<5WcAP3BnxIYotsDUn_5%a1#OpNNmc(RQm!{ZS9U$d`E3OT$mUiXwF3g&HOn z2RrUzGPC0)<@Zcn$!-)T0)~*y()-5g-?2~O&B;P1%ZZ(8?k=2r~ zSoE60GBOFCuvq^Duhgycictik)C zV|Xm$==0npK%?HjdFO5E|KOcNB7g8s2zE?Wz|ZEEK5IypLTV)_C0;OUX={+R=pJY z?enf9rzkULvj98h(E(MOf0x?SqrqH2rY=UT$VZrJI-cPqcr+_l@~U>deLxpdKivry zGk9lOX|-3_;Y67*!{XI0!h%qqGGlotIp3POovG#RN(#B-HW1EgXkjuEd|aC*IC;K<0r)vHJcO2|{Dp@S2lSbBcEQ?a z4zaLoF7h*Pv26*kH(|y4ipC0B4Z?T(=88-Dn8Y2ll@W4M#Z8vJ-e)ZKocAo)=L>7K zIMT(ot0EuKf0JZcAnsR9LDqIY{=?Y@KTGc$ow4Wmw z&b{&VTP{L3KpKIByAm#X&-JeVHy)blEJ;(+xU2QVMj>>&jbw9=AW>pSx7l<7!Dz0^ zg2Ne(Br6sCG?}3jZNUgyMT5xXN?o>W8wxX7+D^8HvF0bdiKdr`xYKo<4|mGHeiqce zew|-vT)dj0SnXDlS6`NIH-T!j=eN$D38a54)Sal9ZSn~~JJW0g6@r73po}og@F5%w zmL_mp@x)4uWc*&0l3E^J6f0eNx~O|LlMcHn7Gh|sUYhX2W8REze>spy?z#E&DhJr= z$Qq=AaRipWgWT)X2-!)XD;huhWghb$=?>pewJQOcJ$J~>DvNm_Y)@z?C8E<>|5fc0 zH-$gmm|dp&bP?w%(jJ>E$3a4q*0HyXFBS!8T1BQVuy#Jc>^`Ad)_S-7wi?s-OgxJc zGGmlLY#CVSaFEzsb|+OJ{Ujj$YWyA+-)l^`5OY?vHKBT&E~~cd(F|0bpw6ST#^N8P z0)f59vb0&dft-bF#o}K zB8xu4Q(D}Q09fPv0G3L;zRWcYlxeSzBT(c!i!K~U8+0aTSJ`Qtt#OE8SZ^ONIDHuX zobguVRj|bKU>J(!Lgy1mn%t3Wq<8!ufg@%yO5!R~>Pe|YVA$E~M81n0j|(J3yj|*C zBdDy)?0Umxu_;~6uNrt;F*g`<#Aj=+5Fx1B^?YJcqTQYB5>&Cm0c7cUgWrfMESI2- z@3&Yi_{=jUTy2`J>Qex~FY&H2S=OFiWM1ea+eFZHnb{F&fI18=|Uk{H7kT>De? ze$V$q$NS!pwH4$^=p|B{Rx+-4E{Rea3-%wu620KkECy~vJ%ScM3zRMxWStAAOELyJ zOE{ke9;j(Rk7-iJzfq}Yu9#@yxS%r_R((@(Pst625ZuC006Ir*4-c11YljeDQtBRei z+N(l2klvtY{f!Ik;lP3L*efV$u_f(1cgoOe>|EM z3kVrRAKtKAvf=K0{M9Tkje~1=g2_FP@3Nnv+17Y4CiHF^n!6=YsZf`16meSPeNk+1 z`=w)bxj6CGWvGrG1-rDc#l={-e~#-%kR(^5@CF<0kdl(et)gX+qrVu|U)&Z+og5m_ z&-{BZ9fbLV?VuXJO;v`0dXTRtFy0-xzTVsbd_~?-`bnW|xg{&PGT*dnDmQ-rJ&y7q zRuOc_9QsV_N*j^~p;=*85X{U|eb1Ll^E%5ky2cjfGWEW6ms#oXC9@_WOw$9Oiq&VK zZ_$7F`(ALkFOWQ1F8v--yvyenr8%4|b>v+@m-eipc*~=kCMJ*kMN+kk6gjbI>MQDKuZe0iJxvG5ej2qPcnT@L zvmGOn7Uf=jyG;4o=tkAfS1A$9LrlIe6nodXTZ>)YbaFSf3?X7vcT7W;OR*91>SMKc zZi(O2?`rqFExnAM$Uv=H<+>;GU&wSCgiOIgO2*6-Mf~5^QC1nV)c;IO!Q1LGzk_C% zKY;0lQ|Ra!STd4ptBB!pUhsSq;5HJPEIf5)Fb5THp>-?y8+_$YOIK3Ynko;8xOgfh zU8#lPiTW$4Gs`_tJ&IXr*Kx`Pymf~aP%^1QB=IKTc|L3W zxPz^lA-k`8r>Xz`8()7QurZRUT4tPi*0Z05Am|z$3GOCaz#$fzzK(|mt35MC)0+zES|6#^Lj=g;ABjo6*@>*Ri5fyjq zwcb2ze5)kp=+JD0=-~##I$+$1l9C~zBQ2{1D}@Yvy4PHh%4goxI2Mc9@0!*J_QF~b zdn5#Wvu5%DR`U*qvZV24vB`M9W>DA%vnD?&D92>%2Vw4_9qqyqCvh-$vKc4a@Id{Q zOob)r>_+jmSTgujN7Y=9PSpYzw1kg%CrSZAfK@-}`=u;w&l!VkBF8ldQC!zs^j7j! zpwAS-HshRe>lc31Lt0Lw8&{!~4-PMl73#Zf}U!_avuU?mu#?(Kzt_ z9-Fcz{YPwi;`iRqz3J1>efnzkgL32FON3oaeZA+ObpzN{HFA9sc#BI>GTkPFrrg!FI;z2e^--I@#c$*EX}bNCse6N< z?ma7sY zrHmk3_Rwcuo%f_tZO`4GqAiP2f+CfaYE}H7GY?&Cop;8`J+tb z=!f(pGq0|n|Ky@-1tK0Rxb&MvT^~+MqmU5Ao3hDqxQ>XV0Fo@$nqk}vZ=^(k%+yPb zNEoa`%_Y>bH_W`+AU-Y&hK*{5a*5+lDuWjYpJ@uiTBeW1%B9-om`2$Cpe$l8$P0vIs)16RhegQQ)q!E1D@mTLdmNVJsLth2Oo| zu%X79qwL(-(y7C?7Ku-Vj^d_xdaY*!&RAa)@bQ*svi*ME>0%)3ElGj1=Bt@A*L5h33P_kr(H*wURM@D;j8alfK zWfiDuz~&7g60zuS_~@-6RKXZloj2Wkiyu0{i0WM4&B7Rp>#Z02Jh;E`XQlH2Eg|bB>aNI$Msf8$P!ySnDLuuE_;&oX{gv z*@o9DK|%q{!lDZaT>M}?ORy{64WZY=HXYURzjvdi;qp z9!D32wdCxEGYXo^^8R0L@jfvhOs)Ao$~)XqXtAx-Iv;5!P``fN@W;$hXUom;Jy{Gn z@B~0dXq{*PXQ=k`-?}alA)Ow>4b^wFPL924j=8a*cr0^k>CW)=XCA@IQrmvi=d)Ko z8Bu)1>Z4R^M3xvxv+Fco)Dg+OCg3%Lo74~{&|xiN{EV(RS5SA1Igq=pV$SLc_Z~;2 zs&t^baAOAfoVLXy?mH-8lPw_=zNiayZ_$E8AXaz^{vu!0$m0?h;p7X}ob6!4lofdV z`$_;#{IFz($ppX-cBD6Te!4YYTs{;Jfu(sQpV}-$lpa>@Ysi5lrB3`3Lt=$Jn?LS1 zu!=Bo*)JsIb`m)=`m%VM{^Lbe4!3O@4m7wHaENxG`#@J{oV?mmOMj#@r_#R#r17Mg z#$z1h!=vXt6Rl!d;t^!uMzkaFp~n)2!ZxoCzkyK8g=46z`HvDS4(JbwQ?u>`c4NlR zb8<4PZzt8MuF-HqzKV0HGhV%)EmWw(nP`8Qb%t7<-Qlcg!yX2H5k8qF1u6^2>c;fv z0;UEUFpH7+Kuv_Zw?5J}OhWOGQF+{8O&g@GK#p78;e^C>QL^vj%MyLI>t95LWsGL4vPZGCBesu> z3@SaU$Gi%oD{quVDFz(%zmL1$OsV;SS5N*O@@y<@*8gIQRP3^bN$n&2OcOI>}yTox)_tH!-f~Z)F#@NEo&QR&U{T z-_Ckm9Nu5)em#msnrbdOb;kjzQ_qML3q|@$M}_{(LRBf`=nwXsLi$=GaAECq1DD-G za?Th)84?4>p&4a2v7J9jh~JAg14)4e@@46GnQ@`Jzg|C=qa^+lUY^Zo`G)ZJPq#i= zg9{>4uGjEybR_zomss}uKuATou%lNJ*wZ*(y3a)@mvF%!#eb=>5}XjprEIjt9#`87 zPYfGn-W^-u7P8~Jzg3dlxKEw=v0MQ1RfF1Ox_5Lc1W?MT=L+T~y*<_DkSQ5`N2m*` ztmJ&{2s)AXbt3wX13=KUO}E}~`oGiBkX_P15O#&WG6X&S`yulE8O7?~FPWHrv(P`w zO)0^5$JA`{Vp#B>QJ6*95<3wSG5W6}m3>9|rS+FD3i|JAYsk_~#*F02Erq<@B?}m$ z3<;HH+sb)M7;fCOqMs&81;$mdu+mXofhsvYj;|f3!8@~ebr>4KR4j+f(E)qw-*3q^ zrt>zwx;IpY{Z2pEsjNN?aVK7i-W+)K)tVX2^g#_ual)BV(S0WOJ}%jqa8PUa!GoFpSH96Fbh7|Mj5nM z0$r&l9a;hc*dk=za%fh9#&gA(J*`YF)Wugv3d2T~;+zg~j1yBvw@pYgS9-gR8zrc95+}%HzfNbu*s#AuJ0QTGc8iQy zMgt8PRc4FitV1zn={A0SoN#dj_o3asX}N5;Z6Okj?@f;)kyp+VIkLR)zFv?aFjUBM zF8*7jIs^H?B2@^4j`jJZVd&U%!*D>O%)gOpL-GGWs=-2kAXQ=6zamwU|Bh5Y(h(6y z{7<21Yx(~RIb}#}TtAisKm|9QwF+zU896?RX=Ebd3#4hzv2pkB>u8`8^zK)y z=vK)r89`Y*1VB6P0E}RB2&kiD z$W$ljUaThPbOOij%5Lvu?MoZV3&&Pu(FlYW&VBS%Zhr(2`;7TO_3Juz)*IEdXV9Nl%JX$n<+-K&3GGn zRMG2R^5OC}#$;!zc)q^HkDY4losRoAm8M-Tji$x>Q~@`r(-4-scIk%!OV4$CZOR?g z4m=Y(_WYQcA70ZswtGjx;Hw4|jAB$A+-Y@&-0zg09Yzo;^S<(&H&vTRkCj;l_jX4m zwS?ysxUoW|ee~v%MU+J;;ct`@Hf{GtA9LfaM!bwv#}Da)T`$9j{N9~nl8at7J`)eL z18ahK?en#xtsb5mbUGwnJ-*%x`0|D%=om4h#{D_Yu>Y7JJm`RUa-jEUmIKo=0%dNA zqMleC<8e^BNyc>&-ljhUTR0+Rg*?zYmJBS$cI-WZ2a4`1!MlS2VW?jAu!gi=Uijk1!Z+}yX6I#Y+o72wU^xBrGW4n? zDJYENC<&H>jz>T`1#L`J*6`RK|gKK@+xY^^Sc0ppt^Zej_H9=rp+2Q>P`o0g^MD~M{hVu;S zN<@408-91S++cQ|pzEskM@f0WZdI@*wEUx)utStdY|I)9D1gcUwx zpgI~!@~S{amarGqoq0rq917mgLdynKUo{SDUKw_KsYbk#Krw0*JCnXMliUd$5FpHuq5L$9#ARd6Kt3L%ntDwnFJKx=lHRTIK-HH1B#fn*UgIz zzCqvl+QuoX3;4R=aA?$d=z-M*TX@}Z$jN;2Y7RmXOGxCCJ7_6X^9Xx^6i#{g7m*APGL2|MSZG6 z2BCBQ{}P!pOKns4iyjFc@2EoGRtePW_+VH!w{mj&f)FU4PKZDYg>BRK zS4-kWxfPrCR|W~0@Bac@4d=4R!0v<+hqN!TPD`xGm;}SSZ{KS!7i@amQXO&%la}I_ z!RZW>lcJh!^J=U)ya$s53W4$|{+ph)xdo&4rf3%aiLgQY?S|T010@3Hf`=f$d`$>0 z)nZ^Cw$&9nD*~XW=R>Cs5yjNRf|QZS>CdjzSt{ZLdm(4q&-U?OT7Y3Y9Uab0q@jGT z=!rLGjx5ab4lNPje7wBt+At$yK9aK|eWC1Ly%}&N$DK<8DEtsT$(_ zVo(BM0 zPJ9xjr4?4oq}?Fh=)JFI#rPkF0Bui^HY>p0d`{WU4kFG3l2xCpYzMw;3BoMYPl z)Sat*2R?h&4JUn)t8q6aKFz&=LO)~_CCHK$8>=JcbRD_#Fi>m#ABc5T4^+e~;>hEi zBrB-Sko~#@S`07pl!zSI#9p3>w_`IY82jc8zR*VhTYS3q|5`lbPIdn?!2PyR` zQ3012j#r`*T#)(N3kEElP~zXp@QFy4&J}p^BrN~H+e~!^@ZERte#r&NP$?VBMT-Pv zp0Pd=WOi+@J1gs*OSg}o=eATqSAJ;b%lGaDao;m2$n9hMP~;BT>ss5P%vc_{P=8sK zxgxN7O_#<6?|2@Xxgz=ES+hDW0kLuFl4;9hGP1dguRUqO+HhV$$_;qA>4liiV)TLD z{@xgR!lnZJp$As-G>$r;J>HE5{6EuLN#1|Z+J^vV-N!6$pR4o(`vjyv2;%ph;%2LsWWFhJ3$z9m!{r${67B7Xu)^fz$;fbX2%7ZPcL7Ii)#N%S4&3_azL!C z7tkvh$Ook`$w}AwkV~uP^uXEaq)=og-ijg7djnxJ{y=}jzupxIjNE4K_a_Pe!G$sF zEM$;Pd{$YQxnc9aXitq)kO+VBQVA6j4D6I%f9~oHNa+(?Z0BcbEt5%QHha;Angwq~ zCcIAD0&cq`gv94-j@2ZkDi176cjsBLTChuQOKe*co%4)yNgzct5`of#29rEz6RUGc z+IpCarVZhUHTxWL-WY4<9qNvs+@6k9)z3tuVyIus z88obgT-D({;i(w-28GG^E2@~!`=D+p2k-yF@1)VgL59_NmAKP?>Sp%r@TN<>o!yc% zm9yzD$gQi(hWT;AjT>+@j)dE|Si4`SGAi}vw?hbXbd57m)!(?d@PcWF&9Iw|m(H1q zB`f|FD)SCYBJ+FaMX0QZ{!$Rk{zGdIc^p4D<6LmiIH=}#O5-zn04Ve~^Qz&7Vr-4r zN|XP)Q!IN`!!?<6CLAeYF2~-HD$!vQ^BKs694PpBFib!UsD*9;aJ-la+mA-Q5<5-> zuEKQ$+KcN2+_XkM^-L>oVLwF#-4J9yGLfLSTq7|JiaVr%afR-cd}@U&g7r#@D-N+1 zft6IH`#~bH$WkPg{#zH6u@fE`aJ5KKnEX_|!u|fKJcGkEA4_=zvOx!=J>9X18fOyi zf_CXp{#lkW&`$L^akz>t6%C$wLZB{xC{=?QLQ;OyUOGR^7=VNj3Qzox73VjSAg`x8Q!cU?8 zmYcUIsGsRxWg50-;9^)6e%)!c0mWetq#_6&c&BvZUVpowcmZBGP%cN zu^fF6d&qB$29Lnv>Z4pe-_QldLpj|@!boIb5={|IuKbe2a5_-~?XkBj(+8^W6dQQF zS~ED@?RC+*HhRePo6Trm7G5JIR85K$31S?{-`%A?+}lw`s|WQeV+j79#f41``@z@T zpxe@Usn9yz-eV!LMl19LFj;=%3@HU|o1gWu-KA^vVCF?eJTp4;!Dcx`pa_x-z$L>9 z|BdX{my=#z52{Zvkq>+yvnF9u<(!BMC$6;R1i1*75LNkEpOibX?d^Feu(~jkiLEDc zL-W=+^4`p)5Y5A_cpl^P&UB2CaP25mTNY*uHLm# z`3Cn@R%05l5|0ZgAF+@sq%dLkn={(J^S=T5F;x=wEiYY4G>d;aL6~m&iUg`-ZHPwqqSD1lZM>srcBxk@jh} z!RYtlD-7oAnSCBmiW*LdzuH5SI9_Pz+qKWiMSdS%{a=Th5c50#Q78F_$6g5n^NJbg z&jgg|L3sTy8M&xnSNqiLiW1leufbTvsUvzp|LBkXLu1N_{rk-rQkh5i0@J5qikqQ? zBEi@SJacu~fk>s0!8Rh)8_^o#uGj}XO;mA^KJ_!IdqjIb>%HbzmNyE@yF*NGC*F}I zj~}kWt<`t4Fz)SzEb{x-{b^*(ci-qN_zhQ3eddPSRK)i@YRR^s)D&x8T~Dieo>i!S z{~fU(G}-k2rHK@ECf$Ql!#^?k3MvGXNLhFYaZ`Kdyt1TDcPSXf@tP>9LTsZCD=;A} zF0;Dlg-tV^&JVcdEejeg6_6Oi*Hb+2;*`yhqx~+enO-nH=F@Ij0UNIKIfm!+|)>kV@6D|o$)q|ll+d&^lzjjn|M zNz%D-;cb@ZB=|RkaghJd>d@bS87>Fl@5LTGM#Y@m>@fPtXdwR3aw{^s19)(zq z)v#TMRQ0A4HuL=BtEJwL(vM1Arv?1>XW2;CiEiA3E)hd*HWU`Kg$*Kb17z;N_P zm2Dw7F=m=Tgf3OO-oWRr@NT1_bNu7>EvfXlyYz{SiuplOL@)}R`;=~RZci*h`!5K+R zC+;i3cPhnl#!>u_3Q!(a*`?JC6;S72Q0p*O=Gdsl!w2rS_U?x)Jn2`WmB`0_Fj9CQ zzW%+{!lp<%#yf`@D}QOKX_IAJD}>uV>h-`}fGX2mDst*I`XI+WI+9 z{^fEn$OhAMo^O>!)O~Lz9sxsoUBcf%etYqBQLjxol|Yw1Vl-j+Xh0S6ivuLk>sq&@ z0a;c+<>D|Gvcbr8>YIZl`pBjjFQZ(Uu2qMvD(ix6+g4Js~H+%l22Fe1}=ngTZOBcHDi^Ch9+MA|&Fx z-6R6gn@m<1;*?Om4^{>vyD^_yj)734?+$kpnvP=qBCGdj*E=JcqPP|A%Zpgv9rkb6 zdvasAr)@_bjGh619@JaKa{wnOIUc3HnUz<<_D6+{#6pKatd=O8TnCt2rJ zZ{^fMb7=mr{Z=<=%ftRQIoWS|<-Kg3{a{B72oVI$QTYx*tOQWfg+1h|C+i8{16Yt> z+a(l}Ntjp;Nkjrr?0D};h=_o*bqDWOb?A(BMo1yFZyCRp;H}V~5$YQHIzdv4J9aJf zrT%IvV|>;DVv1)XWa>ZSXWmtjz7Bd;n5}r2$0IF>)f{yVPv(0n3jQElkDcRXN6b2P zU;d{{{tXLPK1_9^Jjd-=lA_JV_$Bx69Ob|GCEhqJKJ&h^Azgk~4!A8Hn5v%@Nx0LF zxbrI;jiqwx@eZP0@OcT*oBx>$&NC6HuX%^qQ?Oip(@nRX5mCtwa5_TiTT6AxG7uT2 zB;EF)Ggu(VS6}n|>_MfP)5eu@K!GMN&BN}fKkq95Y*mDi) zv2$o56D``k!^3CxQy1g^ZiZ*zvIIbqj1JH5#cKFHe12i-%zX5@9p~XGIQH7i%sYlhJnR67dv_18pl++5zu_%3|s9#82#4c|S^7@E`j6@VnLqbA?6fI(e zBw@0DCq_iX6w5p$KL>Qn;6WJTKKE*TT6Z|(ypyHTgm9pmME!Y#y6gkP-zjZeD@^3} zKykG@a#BymQWduKYe@c*JMa6g4T%CJ%*}9uDB;8|EbS#eUD-873a{kS-Mxh~3Z3-B zPlw=wwe#}ua1tsJ5uHFL3KE_buScxxG^bD#_4EE&whaMKQ7%)!#NLG-vxeKA4&ABC z-ehJghwC#`u^g*SHD*ftE7&=ReOfn0uEUmlW7&B)-bDg|t-Oocr)bM?1U*IV$D2Jr zteR-N-PGc31u~Nj417Ri(pK45$^G{BFQYad@oQ$@xE=$8SdJ5Vs zbV8U)*Dkeh?(ag9IZJTjDJyd}1wc0g9(p7gWNF1o1q;E0X2C0spufT=r$;QpO2-?v zwV}M|X)?5Y;vk=0E=gq*^H-Xx6zD^8`bV|>_Y=4+J>*QZ#)s9T9a0b!c>Mu67r+r^ zHYt*r#K;_5ZspW$vd}Ub!$Km>I&AqXJ&KTEnZk*KUG+~lTrON?Bd_TOCK1U@8J#&= zRarv}&V8s(%W?i>u&64pufgEpUc$ z6I5g%$E%!gHDB^fm4_*n7{OjqVn?)}K9;^m-B2$C6e0@dFOkO7MeSAbjjpi=!*0%> zY!SsJlZHK-WV0LtDFpovY`c6RURt89(w-JhXz$XY!bL;re8j^hb1PONv0zt_Iz16X zKk@QT&Fj?%Tt!vxL!M0i46s*P2%!pJ&la`xVWUx<0mk0Bo_eCiO~wlEhKa~1;&9Pw zeko<;L1q|s@oFCI`x5?fPbyRu*1{ng-Q*sZMM5@w&hRsz|1lC!r;QD+Zy<>y6&#+h zw4c#nB9|SEZ#N<{y3{TNJVomSiz$Rw?aGUdIe10mz-{^Aa9yiznF74v$jO(f<$mXc zo5SC&J*}u=+20*cPt3uDPWLWjAe0IQMD(|~&tdmZ+`g0}g(d;*!1V<#Bh{Kj?5TX^ zt%LS*CjWJwB8c=9SoO1o5BLf$anKZWf|$D2jnQsxZweMXsM_YO_6*AGuxCC!i=Ufx z?l!BZOnn=MGGSSs=%r6<_PoQ=R-T?2k_W+4RmcOZ&q0H`A}am`<#wUpj?*llwvkX@)sKCdGv<)si#l0=sHNyqZYV4%O$D+{zqe>OY^!?J zd>T|nCevgKRrUIU_>k6kUm3i$@;iaXIS!{|VgGXOAj&Lhf6ocam=0~8Zu#)wU8&SB zo@og&^%h?%xvcL$)%zIcL!_Lbd)Scw4`At_6GgPRuKTrY z$LO$Xw!4U>q-ukJ0xGUqlZG%;o#ZWi{H^fL!j)dxW-^oTg0uV4)FF4t0>8)bl9zP7gMe@axoc zunV=Ao#TXYd#PN2F~o^NeBoG928ZYeWTaH6{F2GM4GKP|FoTIt8{|&dHJsF8o8P6m zZtx{+-}o=XC54QisL*J_wOP@ob91h~ABLI5j}9@O8O@c5;k~QN6WRFum;tqR`od93 zFdA~6z(j4x`N2O^;ZEX~bZX3?>K(V)Ns7EcpAxI>1ulz%tcZmW37;TqK+ySiy*>kYA4g#F_wa9zxIKdf$$>Ic{@z z#Y?uC@HO<_?+Z9ZDk<`i4-9WCJsMi4`sn;aC19Nq$6+*{F}dS;xeXz;nxwDJbjs82 z^^VY;Wp|_!7VX9FOHrIlnRe>^VxdAC&c*wKVxzX~_=!4Ic27%=$*7hrtusL8m-89s zWBD@y%CLHtM62AiwGWRC=4HM-k$YTC-O(c%=@`v7&03VgRRq&b)-ycO%GS^bWjbks z-i5mYP!|a#4P_zm>#%v62kqB(Mq56VYOzG=stI@|y-O27w9#Z2B|xaxxmfJGZHgCx^8@Z~Nj$yB#?*r=JczBylagO`>MkZn61Mz9hU2i1kNpJ*WrHJ>=YJ&{~2DS<&zb zm$T2eWqsl;1a#a>oiC_f;{G|!h`Q~NZMtJaG7_I2QPeh)iTJU=b*+ts=7=4dqb;Gm zo#2qZ?=_>zHqoc}j5c-Lq4)Uptn|iHcAlOHF=%Hu8(msfeJXQ)e+J+Zm*PAnvpAbQ zni$2{?(9ugkp7AlLnx1T3-X^XK%f5XTu{TXV5PBh<{C&vV5oo`wn3Qan|fj4f+ciY z@oE^W~y>k%orbF5Y5uQEYJ^#jS;m1=ghJnaR-U6KcY+-4;=l2;q20wsgCK zVbR=JP?jc%OjRh@(vFIi3yz-DJyB{PfQ}{SrGcyyE2B;P&>Ub(`Exx|SwIM%47R$D z@SSO-vP2;TmH&CFCYVZ0j};A7(qJ>(_@$2Msnm2S!j>#A{B#Ydj(1#{&_X(3TU#6gDKKZ6OX zCFhF?F20vk>8&R1%+KHUDWg(5Uu=S2ygv?2^RxF?+R5 zYD%x^YN#Kp-uF?ZrSE2L(Y=^S8-k4Azg(DGr|97|d>443&pXc-lpM9flQ~}#4NslB zpZ$bS52h=$ORb+|fAFneACwI+AJP#)nftEpG_YB*BO0uxFND46#|5qpErEiUcLFZ4 z#u-j*%kkKB|4HcfF&*Vt+U7QVjx;F&3kv&a_Rm~7CR2&pTg$U<5v;`ZZ5IJuV#pwG zYKTL(VZTFjo0WO2cC&Byi0SnYu667`YSxcK?m+@qSMnoij_h0Si6R*kii404Tfa>$ z$l>c=OB}Gdk~j6)<+{~2rFi+s&Bfwp;45uNYZ`c-;$5l88q)I&-{oc;4<_1hMZwYR zdDriCLk5ro<4X}yb5k{jQ~er5XfzY<`y%wa@W`#0-uz?kC3QM>b~6Wq*;rq8J<O+p8NMyKT0V~PYU z>|R&Vrb0vMV5WR0TZ!zCRF%oI!8rOn%2U88mGpTVH`(CvlE+nDm_K8Re+-mdq97Ga-7Mp+-JkjHyKA*cxDHKOxw<0wM%Q>4SV7yE(G-eygnH_pre@wk(Z2Q)kW@t}3dojhlICrAN^*!kE6=BMjN?PtnM}6#? z2%;r`M67&FZvm~lfQN7~uBxYXr}dC;UL4?QD+wm+^P^&{?;#j}{xkXyVgCtP126OMSJJ`v*_2TX^`K!=s^lTI&2H$`o z4>j&ur**fo-C#aU8b`dR$152nTK2aCvet2^I|=zkO5nHyli7)*(d^H1c_ zdE~9-!KocER*IlKI;$V6sCr^CB_hwEV~r)*^*VyTt~w)>(djy-n>{@|VX)H>y3qKm zkp;YlijQIsm|4)1yqzm6Lh6Vj+m^Ch&!!&@@akPy9b0fd?L~}W{1e(Y9nWwYlT!L_ zg?y%4RA_-ysKgMH^5|@e5vr>-GjqJ=hv^(qGr)g7BOVcoaJO?%RX&$G{>%_-lneYsiU)n~SZa?`Kf)Q>W7>rpBrW1dp>`${#X_Ki7U40PZ-#V^8 zg+R_$H6i#ZO*l_#?3BTHI;yy|e}O;Z$sZ~z+9J@2fd5>lD*>R^OP$uwsW}!F5Q6W` zB3c!45@@i+4KWgi&q(!4vSf>`6s}YA7Me~~W#jZ|;~6ukvxYQWhS@pBo4=61A_-kb z4^t|U)v6D3N4|j-_e%=K}$|AGxX$(wm2FG+lSdLN5Te|mtvbePN zgJUxviCnQA(ZrfqLGRWpwrT+}TaOQy{eHEbGAo9k2Q$yoggy2Oz(3%RpAN^`O@_pC z!*Hdi{Aczb9X+1&f{)vqPTbEbR-GI5As{iS3m#73m+TBDC@`y3Z9r zf+0gT2}ZPY z99$>@qeG;HEmz^jgAAkQ(^GwCa_D#oXiNpFxC&xBiHq*^J9146)5;Yz!VoC9h8rB)Etu|oRJ<#0V@TKr|xIJ z&0cd+;d^pDO7i7;ui&A`8XTM1nwVI4PUc*)kTeo%vc-J~S+8POVou?Zkdt)7hxov; z^E17dD1^&N+t0b|dlPj>9E43Zh1vB?*INbZ^hS%DI(jTHsORQZE=zc81C5P_oGKH9 z5x+l!l%)j|?XnN9y5ztWSC9bS6Nz>*>0LN_i13k@Q$JzGc0Y)yP`BPx;#K|q3ON9`nRg341mdWjK z;Brn2AT?wCv~$m_V#4SFUFcL39GHUXHoP2eDfWPR8o?HycLu7KQi5t0m`X&*R_dyp zRHd_7{JgRtYEeo|v-B9$2_l*XULyr)RYGo9~xo`lb`&8&jG^FHM+EepV~n zMDUYsKOPpO{%R&cs;yS5CX*6!lFIA>n@m{HcSHxD(RCa6NDcgof6PN9fBQ!&ZlhQ2 zPo{jrv+Expm}M0N8Kt^|#^{Zwc;rq=>N%yn;XHi-R{m47Lx?MS^d)V~Me{N_hrta5 zUl6aj;EKr^El&f9NdvK5Q#_15D{D5`%sN7q9K#wdCRt<5zgvH$2^**Z6aVgyDtT}t zN_2L@<=fHT1e`=fa=A|ILT}AH3Uht6V6KqfHd6AXeni>VoUguBTd?KORNnYSc)j4j zt~Bsyvc?m5L{}l%v5RDiU7!5J-gBTsDH-KJ+NQ67(Oenl_VL70Byn~l%qiU92^>B? zC~GoV_U>Sd4`*se+@nfF}Vt6 zqP$4FFG?U*9yZ;NI_mtajas&@^RPtO3GB0m2?_YYi7YF}SmNQQ^d+ESQqcs<@qjmE zgxrT18coP7FNDIrJHwqnDl1zSMcJ?h{p-s1G~3A+I(#w1Q=2IjjfLF8-btWLW!{VJ z96OhJYprCU%Hz2JDw}GE{Ac70k_^@A>H;%KcgoRXUE?erBkj1Q3gS!JOH_mgyv%NI zA)o$tkOZvXW2D-Ir$)t&i&Es+^G_<-Sg3FuP|z zed(s8lOtE;>q|hODgK>-Cc!~4o99}^c;|Qo5?)T22x~ovfw7L#6AO zEqht|;1Z7GLw9csRux8}C5{c@FU@DZ$!`x_C5ZAtVj>^?rNMI0ZN{2{&9Kp)vqGoAd-kk zKf?Op8W)X^E?-Rx?}K-{1QLtqF?jtGpq6RwbQgvONsAdqxMEdWZ(IL6-~9aV`DSnB z#dX&Q-wewAmZ-BU&VNy@`m$!i{Q71MmcbeN!=xJ;_M}bhDn}~a&KpIaMb62|+Q1@y=;s{Pb-2&7skZ*jyoNvt=Ss_qy)` z)~ZLz*EqCd5Hs<4uKEWNHzi7#;<(Wc3}4Q*+xO->w$fWwP!ahna}SMi$k3`Xa?oyJ z(jcP{s)VcZ73%UGaOfh{6vcC-q`wc{QyxFP4du%}+UX7$NwNZ9QhuGT(A}s%@({;X z{fu$S$X$MOS)s)*`2PXnyd2h&j{0wSv+39WfH!YlqprKqKL$#V%RliZU?~0_w|MA= z%Ow=Txg+Zp4Ltqz&L7b->Fl0kRKsoBJ|EDT@?Fq?Fna5|xx|(9b*sCz){G;%lN*hv zr|^_v=rhA&+>hXY$uqZHxdf?PK`PCTdzN?c7iu_U&VT(A8&WAKoG|-q&01~ZrHTaY zy*`}ODNs|lT}4=|Du^j=$GI_+)`uN%J2UP&d4>!dvRy_4G2y;ns>iD_>Hh-~`8h}1 z?gKzZ;}bOCi2Y3-2kkTeSaSfM|C=wGM#a$l1u6f*8es?0P_TrI|3(O7Zl)R?eTAd6_&%E-jwzs|v-L zJ?7BS`bGW8(P#W|(2zXM92t-`T0Pc3(!A6EmZ5&o^ovYo-ZfwxpgQ&xV$6zCmyR2k zKI$jYLnHrWXP6EJ;SHKd{kkTk}rNAnNJ zns6g@#|I;Mcz;}q1a3kw1$($tIhXt#BDzak9A580t5p2+B1sGmZofHWQ>;E`Fj2IT z+G6n+g=_(csV==Y<24k5N<2?+uct9E)d{~0D4*w6Sq})*Ytb|oskc9(@QhdMKZ9#x zaF|j(-(_@<-+zUG3%egLeQmI4vBjwPq8;v1wlz#0hifg42%G{4k@2Uf9@|`U^e6f1 zv~G`G-*09du9v?|2hpKtkjQq-`Gr>y+L_I}PKCwFiZN#{M~9uXo((_d{u~oZGdv$8 zt0jvQ7Wr35Z3IauNq#e}^X1~68&(K>BkiESsHB_{WBEHr_|a1+E84(ho+a-5Z$mWH zKJaR*Q2p|Ev84PPmCD3fTwykcX|#&m@0`{xHCw~Ug|wPDo4XD18GXO!+-3LHu0@+y(DZNhho{%iV=y-} z*8n!Oi11zR;N*D4LjWh~zRGV4Y~|CcbUwSNoYIL@^4*pTpMBGnv#*=>;}QA^%=C5d z6e>JElHk?CC^f<$st^s|pj!LF4ip@k74&>65HOKN<%G)R{pJ}yvCHA}e``AF@9pMz zuzV1sUaZZs@2`%ikmYNF|M@dQ1Sh%N3wZ6yH9>aW6;H5IPuF$z<^*<)!8mPI4}KdLx{I0Gxhhg(N2qyiQq>d(N>Xfb2LBdu{IcLj9FLD1vBlEc& z3`urdZIRhNvqg11NOL=kqRY9g-IaLWAwKTF@^e=qCszkAo*mgSDkmc{VH{10>tGw3jn(Bd=x=Jy~$}EC-{;2#0wvgLe2feIcQOd`{gTA86IRc>!UgaxE8%QJ zsK`Ge*?xR$c-M_N0B)Uvfy+j`Ky&qXz8brH)A&}uE%`oJ3uu8}W+BQ%x)NV;){N!B zwc4+V*hPi5YC)$R3>r0dhJPP8=-P_G3Yb5bDPzBUHntaCXH}>O#c)Cy`k9S|w%Q62 zI9xw}KBEuO+ZnW}Ut(jWVT}3~7l|XE0Y8$Gu~pEHW3$kjgkEC=o%;HNNP09|dYmU{ z%<;LDy9DY-n#_C}HkaC;?_&y%h2nqo&%vru+k}^kj|0EWXBWSH9W5!ayX-Nfhg8y_ ztZseN>rDpb{KAUi{YU|hew~Lz0oQ!6sH9H2G$7uH!yKI>FK)vr4b(*X2X>o`MTL1gLyCr#<<=V?P3#~Af6{qKeHuU2J(fyN`ChRwJVv35^;k?&!>?eCP@QC&A zO#6EJbCqNjY6;mRX3m_-TyMERsqRR~aH!;ay%-WEo7siBOXBjlnT4rcZO`d)|KlUi z{^e)zQz{Rx9GQFbpOOrX@;!~F=O6D-rozG$c`MzrY>%HP z(z!+%OLiR}Q~CazonUp>rBj5SLxvF0x9rPn#hW;q$jU7IRECNJNv?Rub*qu~naLWN zhL>6Zeo)YRqp6g9-J6@Cf9iJiNugFg3N^)F5yEd-3AIm6@IRqkJ@5(8Bbt;|a!F0upWDC7cy~!6}iK z&jkL5R|JW+Q56`pC8T=P5USfAD4eDdvAG)t(SN!Cs_ZC+!%NwbT#tN6{1UaOA$E7M za#70~VI)wJsHDX&(i)sl>yDYT-r2~Tzd7wOoz5k84|1??r&yqwC}V6b(Wcd#tBPun zG~GOUWD-6KT=wpG4PS^({LcQhhwAPhsy7_xkrO{cXk`rYmkNk%L#0MlI4XH_Dn?w$ z|8FprP+1b{Bn=TqeUlfmVgzd0SD*$NfCT+$m96n@7YB5l0#zqV%10Q5D!m+d&ID2>4H*}|2ul5#x2>AM`X#0B?qKrYV& zFNV6rmackZynD% zx`8|;6V~zGR{NR78PiLs;qKIAU8~c*04qp3%p7_ryU;6XKG)D)nEv$zVwBP!*Ax9} zwNU@?UX$=#_4nHsV}*RxmLpeSv-ZE8!FEmcr2hQrs;&fVkvaYFEH|%1ds$B4o{$6e zf7ppEuRuHT`imw6@x(P`!!%T~gz;Z~o|{%*76ID~8lE!^b)&m&=W4>hGuQ#}>__6> zwod%TxjM1mH{F>@TE|&x*7F_00r*WWrD6cfZ-;dGupz4dIRDte0CDLAzC!IU#Z{gd zY_zBitm?p9?c(MA>`EEszlB>)XxI7B8eB1Nb$craw0&L^y%eTBtrAy$x)twn=N zEQDqFKkT=jf^z|^AwL8!GDXbkyEN8lafPhjOd5;}GuGv1oB`Ld@!CtegBH3b+MO1W zHS6c9E*Sp zI_K`I*2@VM+=nXLBdb&=Dcy^&((x{NA-ni2++WT31tMf{k_-PaM@3K6;qmj|FsylK zo3wa(U5Dg$MdzRJ$G~22kJ}Me_Kigx`!xuFS8wEvBxC`4Qx#U&s1tG%|>a z+6g+dn%MtWnmq>3Mjb&ZAw~B9~!5wmtvy)^^w~LV=yT{|ifs z{NG3t^?xHte?zC3A0*n3vKFQ@&hV?tib9%+rC|hN&8_@Cc3>V!g>>}q@WsG#h|wE^ zCvc@9L^ z!!@U`GjGN;(eaMlMsq|wcke4(hjC;jM-C6RC;+YNU5{+Mevj0omtKkm&K$ag=Fa_> z9s0O2rkinHL4!Apng0z5A^T#)wS*duWf5RU!0fze(!6n3N4{Av{s`!ZCLuEm!?5*5 zyTkSXWj&5&*CXuqWjAt z^vPRY;qgS4J6AL;^&X!YodKkPxDo`EoK(5tSeJTkLiw=!c0b)F97+QwpnLF{xKjJd zPG$!)rq!hIBU@$SN^2AF%c26fTtQxTvmeC?nm3ve79bG+Gp5`=)tyC7fjQl;8xoG-+0z+ zC%jatNkCI!sGL7@&D`deb2tM;r%Qj@{&_dgbcg0631UvH#m@#JtVP$=glo~?sbTEH zYccXB@`*9_)qo ztk~LKf-iOLzDvBGE53GlT@9&zj4`?X@ewtK!x;gy{}IfFvW77N2RPr>aRBlsuhizF zq39|Y+-If0^X#U9kTpySO6|W%*uZG`-z4m=N??o^q{H_)v1m&^kqf__Kn4r{l8$)n zET_;^HSVq7$L{7!wXFt|Ee3Baz2sq)4qXXXxZOcMjg}~{%bJsMZvqqEvFzfc!Hjh2 z6=&}uD`4gG+fG5%C|S-9Il@sJa1M^VTuvD@eny4{ES)&JO(>kkp&vC*gY*$L?ma_7 zU5C({FZFkQsmxx*q-phR&;Kn8$8jtY1pQ;D8V?Qbe4}BLqRC*|e+*}syZsG09!mDh z4f5JPn0tPa1u6ys#H{WQH=rro5v-k3%G486BTMx0D<%Li0_^r`*S5=Uqgf}GIkyP`mT0_b2C8qTL zdqE}*&54kR{o{!wrmd1Du*968O(Pd#*mI|yI=O_#)Y9%&BL*$|M&S)Vkx3<`` zK_z*WIzIhMtANu#d|&GVHm+fQ1TKCUMd=ouLIz0Z6s%X1*)Oq@=+6l6smP~24wOSz zPeVQDwJ0w|Ku1hCE!n2In+BiGg*I{HgNNpRn=vsoB?0Khb)c`a^R@1&XByp81##U9 zwA>6rD@lYS9P9Qxm>ZdnHqug|7^sn&-FdOKSbabnwnXGlT=Lchh^d~#YD@5{dnk|` z^S&~c;SAzw?jx)?azlaVZLAoxZf1B>+ZbnM#`&*<- z@7Jzk53EAUN2A)Os?xKDbk`JA;)@8bj(6zYgu^U2o_4-B6&UO*WbVN%=MYh|qiW{Z z#me$}yQ*SSlmvF*3JW#aEs#}dgiWIUKzow;w}h?M`@_<-wmc~5?z$%WHNa+4otjL} z{rT?O4;d`JOERthuexxZbaGjaq?!E>3ZjJ3fJl7l_E<1JbuQ-WV2{!Iv-d-wl>JH2qIg5GSIf zx^A%u<0SFr6L{qW&^MK@rO5>h>?9(t`nyj(?y6S2J1x;biP@?iPhhtkjTRJ1L4&L` z9IlDKQ>zE87kx%XLG2b!><}ujnhjd#NfCeA({eNHIh7r9(6=4@K&de8K5 z%#qGbPr%wifq&n@`=(TT&=i|bMUi#Yob)Pg$vIE+WZSotF~ge&ao_q!wl!&{26eWy zlcvaqOYJ+s8|voeFS&T9;l8Q78C9>tH>kDyY6|J1n;$*_3j0Unc-Py(w2Z&@4`oJ< z&kPp`Ntja?g*3w7_{`TbxuSYj8evc<?*;8IzwtYgMpkr@yNdk$}x;ukU_hs!{eB$;spe$lwO5R|b~(Yfm(_xl`;HnkxZ_fw?5?Tt!b z%CEz+TC7P(gqLQmrO3#BN6XI90>(||?aKL!9T0JmFL;q|nsq=hI&!~o-f4X|pLDM+ zYYq>zp(;MIo@jL=N0Zhd-ZmZnB2!seF}yte^-`!0%!>mv1hrG+Tk1%c8{{dLUj`a+ z&0-*3bSJw5{5){>`-X%32w`3`pFHu0{_A;6)|Rsf$myy`wj8op0#%xIlZJR}02Bq_ z$tR>r(DgyBvsn*@JR!7Gzgz1C@sp(J(fvcH(roa3G`yt+Fl9`Bf}P%t2>1tkt1_8N zT-y6|mim#{+ z8azM&nr!_=CN!|=X<{jekf^|XlsoKZLmbepQBjy!op@fl8D0!*>Ys+YHV%4o0<_$*%$Ox>mUu! zeUTnNg_gj8(v?s73Wa07IN|Qqr&l#hwqp$lmP>&;nkcM={4TOHD}F$pO)sF6wB!Vg zm@w~uFUa;}#X0RhR4)&;wp`)jtMQj~ooz-wFLml?*o4%AP`(hmFp!#$E~HS*Z*524 zId01z_Cp8ePyL4f$_itI9b7~akRzWg)n}ja(@0^xPGQ-rQ91TA&;{BfJSQDHpzW_A z0ij)&_KwC5zk>889py_aZPKV9HUXDnfZ#0fW7Sd#ZaiH#q3a8>Q_)asM4iEGE3DTh1+Jsvcv0br^?YJM)l~I zF5u0X%pS%=B)BO&zSHmPa_XVM>&fPaklvL7%wi7lw|E6VUmBSzVyFpF9q)S7^l&0R>s<#@~|glIs|B+9hcn$%@7qnYaZkMqXt z%&2gE-I8y_rCaYc@0Rfh4XPoVfUh>gCb;8tL)zd!d%$SIEFjHn>P-hWys;x%H)e=w zO!G@$4wt@P%bpcNpjE6uik%iv2>i8xb0g^I$Jl&Xtk|pld>pEX&(T3`@A~lb~ z`hAd-IV~K;jyw4tF57LyeA@a^05hP>Xg~uG*aDb_Vj^QBRN8c|oc-u}aXFHY6givhbiY|veyq0RXK=QpC_l!Pm@x`Tncnt8pA|0PUYM@cc%>&t%kW)7UavS z()J9HN!Fiz&;Lb_a>Z34`eX;Z=rR#U(^!7Kv{e(EEB@VfRJ&>U^XnL|{O*jxCBn46 z?>T;*ZlN#+l5tGt2QAE)$TlBn-Vzo8s(e-!y{D^hoXD>_?Q7;1QXzgtZfS*~XWVDz z?|Wl!;|Fux(RQaOtp$xyCN~dS!cS@6x+;imwgb+K-se!;lTL%j6RZdiLr46mV?v>E zVrx6qeh0W(ApD0r*EbvS)~>cgC)du-_^JX-j=fADq^ZAhDP3jB{f!bl;tSHyTe=F>ZGH5+~$!vuNAOdWL^t z05?+utMPOeIfEDaH-6pOwh|*APuLtB=fz#fmX|*fEEU$K&ShlEWs&q6fQr)pm!LSw zS{ZilBv-<1IX6Z;LZz@`IV&ch5{Fc*hM#*FE}UMa0NDE;A# zJ7L@Fdk+gaOx$USLM5Z!tb#~H@DOM|L$)G4Nq=LEVhOI}r-^7(PoD#KOoxX1?N%>Z zigxv(($HOOXeHT#a}|H4*1_^}@al|rcsj|R^iuOLnsf!@&$nz3kG5O-GmYs<@*Kp)VbFNY<7`p|vka;&Ik1367drxG(7H0v@Gq6-+N78u>tT!VCY5~xTRGxA z!?OXQ+WridV)*K-=b2UJd|)Wjv#p)>69Q}~MKDnh-)7PA+e7C4J0H*y_R+vJN4)0B z&&G=@<}0gj)avmde*CEU@{jV1zo2kg@U)?!Z?&p462AczT7rQKJKg7AZs=!VIS>x= zp>6X&<1ON{GGCZf^v|ozgZrWdVo1r%^iDKO6BqOt?^KYkiS!Vkr4g9WTdMl}Nl|5F zzo5tjX6o?@w94tT!<ckT%(`tHBXoizN70~`w<_4TsDBR*^c@~@CC)@#O|a?S<8-e zK^E+)+lsw!8+dfMMj(`&Wf4Tx$b-|~y%`93z7mw@IreC<`>QwLsag(=8sk45;3A$l zhsClRFSu>|IM^s$<^k^e_X7L9U)IB4GN@Sr8&|)#y+LD4`|)<%=f#F~<+#r`ozO*q zw(tkdCk;CNF$smJYl&AcA-PK1c4)_73=oVdo#YPQ*BZcp^(Qv0Th-xVO3(yT4gYnT z-{a5wp184};7|Bse5Zd9HVN&FI}!_$M^-HP{V15mT-ss)-<0+~xl9s_R=J#^XzW}4 zdvyYLO7pL0h47^I(_8EyVdV|4YNQ-v2gB=v zIP|*3qe0S(ZkDw8>So0`knX-cPcoxzt6$$vd{RjQMuk^C;>?4IfOen%A9-f2NIGEP z64~KwG_?8aSijTMGyok(qqTPpFiN7plxEAZ2C*K|QrYuvxH|0N=wcNbJIorZPZgAF z6BE!-SXQ)L#!{D|vH7%0r~o@_a!4QQf6tZVz<95$E^-xtUzTd3&h8B?t#piY5j-G5 z=*rudxYOYmT%D$Qpma$5yVDlgaxR2sU1Vn^TbyR+AYZN((a~%%dx0r)cm*MLjTs~Y z%5KZhYlKNC8u+3+iUjvDG>W3+bxwLV1$41>4SdhE!RGDnv;`p)>2x&vy0P!fg09!Y z_hhz?1Oe1XSXcjiRevzp-QsBv8|n69lK@1tu|@5^DxKl$h9cBJ<}i0UYjK_-^D`UU zV+|qco1PtUSfW0KmW*cx1p*ni4{qGPQ$87u#MB3c=Q?GflP{s$wD{tSf8 z)j7yHZ@aMVS+m3Hwi)Y6-%YK(VkK&7h@tj&`p9 ziMAw1GTq<`rq^GLYAsI}g(K@6Q5=$lhOy61wA?{SY@)D&0l0zAn9edH_O9k*U^i0X6sy7ZAv#ACecPc_ZTm41P!%HcSXN|f4tgv~}`dx^=1klK2Y ztuN78E~?yTz1F!l@Kb7?qr02{3S;4p36yP9@R(Anb03ug+g!18EDKRlyMcNqgqWP% zt0rhV2m>koI!Kuf0AP46PNDUrUJECCYflY?+FR-VF132mr9Z5|&O&D?D~i^V!A8Zi zS<>)SbrsrrrwROjwG6LZ_=JQY_()L;zs7XSxp=8iB+jzxkm?b>W5=g%P@B?Giv zCh79aL#I<^8CzxzC&}07&eR#hmiW;(nHjZSIOkXri?bNTJi7ccVpxhm0)HS@SZ@m zI}&=zdAAoXtYP75x5^${<;kdNQpc(-y}mr+>aGs3ow(1Wp1mF=c_0sDkA7j+Z24tf z$^-6^Kwr(@6iWZm{ZID9l+7Lm7o>m{7i%QxVEU!)o#d&0OxJKN6HuM)l>>Tu++*vo zY>JzLPf!?fr3Rk=h~0gx1@Cna%IdI|Ht2b*6C+3_KGez*X$m;kTQ3Vq4T9P@h~sJu zFD@ydLJn>~4|}HKSt(%5OVs1jL^X8TU)EN2KcsBG_qhn-9Ah5e4K*>&*d&Pq4f7v2 zDjJs!7X;sOyreOTF!T4!w~N(tJUlrXn*+SE;Q*3iqDU594G^h9uxy;9;ul!*k0Uy& zPkMOYn$9AuJ>a<;+Eh8K&HVAGhNkqo_~yXUx>@=nxP-k7FTjDDp?w-p-)4z&Ykp-g zWYNGvjqoJfFgsaEuXl<+xR2XPoobAGi!L|nFDD8)+G{xv$r?La`lmOKbP7^2*u^`7 zqxNVR#fke-dh)M2z;`@9+K^Mjk6)WVlnYA+C(4EENe>@V*xYjj@23IJ!L{*wQC=gf z;(!Vn(jXP_fdz7lRAXQ6DRf%Paj!p;FzdmcY`im5*sZ+d_HRmdd+%*v7wD6QVAGDb zPJh6-{mGSEpI2(UHZcDjF#dRJ1;1=GH;xP?XwtTlz~H4nIbF&Yjp-g!Ijr2|M1hb- z9aXqd;`?>=JNILf>}N}mU*W!3KYTU5ZLGWjbqNEAeM|K#+2?5DUA!LxSBXEzkcX)D zrc^(+(^Lm;#}cTW@M_k$#bp)A*s1M}e@gL@fs{HN4a^abQ9iA=Jg~zVTI!Hz@*@EP zC<7=ciziw=VZ;{rL*^7^&VvST-Z9Hx7Q)8&jwe(ZH;$XemGc%*a}x8y1F9}DD5`@J z8eLR{`&rEN#J|HyR7$%avs&5T*&kPNh51YB6h21?bTCCqBB*`z8Arw_)91f8*KIMNR*LvO(UQq)0_Stit>1#lAJbx>pkE?1!9lVw|Mj=|q z3pj4J%6*{=wY?sXx~N46n>Q4nUbLdLQ@TjyNXzr0+gJ#XDtVe{4W}B~d_Eu*^C7dM z#E2dl!!xQJ;rSh1_RMe>ush=Qz?QRWoz?5@FaM@9v_G%7zCTYi!^o zcW?1a$qV)K8oz-P&Hl_3LIQUYpFeUxNjR%r5g3Kp@8^&R#uCv&L z*hXs{c-zIF$c4F8H-*kE@cW*Mnl&^rl{-2!()JKmOu3=H5^l`tf7{d^)9)MiVFMQ1 z1SVNQ?xpQc3?R$a%y|WG1@Rew30fw%TMD1ZYIlv8wu-3l{G$F5MOfw?R!0Q+Z4VEj zXNWGHLGUTO$>AeGC+c(~-9BSVQ4CuBVMoT@!Hx2tX?cDt7SOv%XYr6Y>6j0s!H^E7 zPI?HW?W#Cnn~K_sc)n2OeEZpH{P?&J4$q#}*%@+{&hwT9*#-`q`>#$y0zi5@Zhc7+mew-ZF<8X>RQ#IbX9jfYIAK)8^4kyM#7M^zB1&RI`I2JH3qz z%G>KLRDRRfg2&#a-_*(6v2IF!IY|6MiaRqbcvU+37Ha4ZemaXMq&4pK-L|XjXC_oO zr226Gi?p+hs-w%=ZGd3G9fG^NyGw9)cX!v|4#C~sgF6IwcXxMpxF_kayWj57eaDr5 zz+k|sQ+0N&ntQJG*lDNVaP;&YG8KSC9Xr&~;~=$|P=do1a@p87%b>FrGpKk!N8q9c z=Ky&|1?sCgkd6b6$H5b6isR;xP&w&4Ap2`+VJYSoePK!(a$KOy(z*`e~2ggAX*%g&tr#68(g~Zt}DFH6qPMS*$R6R9+f)T zXEcPxx46tK&QUQs)GJ<)fO%SGW;k?f!vP4Z5t7J`53<{9-2Mk+#7F7Z1WPu^ED*TXs)Nf?85{F+Oy)PTnQC#QOo@64JZZ z6AJ#exE#^LW&Jg$$8>ci*<5a7u?bzz}>c*0zw2#>hLo^|l)3C>9G7&lQsk zToImzB`Bd_$>j%y0fM@BSQ$*7+{2FSE zW2ic7!Dm&bae5Us_>+}6opC)T;&AHwabjACG)pv(z7u3TASImYy0BNZ(vfA1SNP4`w!KpHyOR}HP@^@EJ6WeMBF>zIxQ4=Yc zSliW>ya>`V&m%(jaCe--6Ajv^BOb6Fj()2eu?O_Fr*tWclXwEa3?w?Ja_rFGB2LA) zQ7C=@3C4c7lQ6%8FBy$&>)r)C5@cPaO{m6t(d=E3NmHaM$|^2x#1F!){1Gj8w*$E( zj$NKYt{Y+PCsj5s<%Igb^OS};YSqTlD@j*-E}KdRaq*GQg(2YVFgWu$s@Hv2ws<`% zZ*Ge|BR@N2-V+Vd!Wx&qkQ}HLItCB~l7v}B5N&1T$yLLF?5*<7c&pFph!bZ;T``_c zmfAJ=Hg7-_q zSa6N)3B+k*w8>#(a8sHA16_VCY6a?SVqxaA^0YoJx9ENY7PUGI*%B!kn1h7%$uKCv z8xtc3%-2ZNjIKQBXCp`Y;H7#S#G4j&IkOb-`ejyr2Tz)g2dHiGI0cRTZQd$42WPI_ z378#O8bGQk+Q{(KWHCp3&;36dK+cYBXYtzl(U*LSK+S7OsW&jzAHQY$0VNBL? zKvJ^s3pHGupI;5;Lg0952i7t^;EQcWDG3b3a7UJzEY$-h>!IvcoKv$Ux-{>bd(Q?i zKya;gg@5~(i%){X=*>q$E(gdG91pt3)*jE6+C7VK4DIWUpv&4ZRm=$ zzu*xyW5HmeZrvyNKu)|mP?Ma6EHcXLH`kbOcfy?V7bQYLSTLm9JSz_?JFn|A-`V4J z4egmNx7ha=0HG?m);fX81JfcVJ`ri-+|ifNfP_4~Kna%))f4_a)Jt^TK~*Y&$AkwwSDXobf*Yt(hmA6q zv~>NDa7!ro+u6iT%wKENagg>3Q-u;OMTIoJx&IMiAe8raVB}OdxN#~9?vFAFv`Z+O&K`cN@3!>28VoL zw50}0rjx5~(uJi9hVRH{>iZQMqi+*n)z7PhIW2Wtt&4Rw5Vb|`0A5_+8l)kcv!}xJ zGeASe$kD~Q)?Q5~F-mJZ7Ljtv6E9#fJ~zHnE$XoyC%vf>G;GrH7FnH(qbudR7!Hxf z&Z9F3Rz;>QHwpa-tUsRyx`2xZt92Q8&10+ZsN}o9R~Lo(Emokz+ll2#-NO;5>i(2y zIn7SU;}Zq}y)xZB(&OdkQzC3qkWLN zWSD{fgBBBPBw5~ev$F~XOa7e46c?3x%sz<7bd@$+8pnm#^Le2wI|2GApz=>Q5wiD7 z`F4M&d((`=M*DZ1DaoUyCs#v|FtRLL-bNjkyQx}4!hFuVt*u&!2`J*^KAp!k?$kLU zf-F349>1v4eQ*gse7E3tk%K$-b(ru-ca`<~qN%@fF3Uu)2T>n*)nO1j{+oW#Lo%j+ zn}UCRkyK_%7Owix7(I|Vhp#i{@Nm%{a-E>)itEc;C1)?=oMD9%PJkckn`2z8B_t9g zVNS0N?mnEA>Kb@?a`BmUdf7Q<_A>`0)UbT~NXhv6T=Kf#AioW$B3Hzov=iPW^;ya9S}*#Etjvj7M6@?GYz3VijF|+qsa1Z_q+_ z_|OqwBj@UP!I8whZ>Q@*cC|z~x7y_}D)wI75ISW+iZt!cLAw3+~yBsLx; zWGe?METcBD-YA_TIowV8kF`J5;O6(YT7UdI-u$wglFvk3Pyb3l-%6UIeU{mHl_y~U4{cIe8< zwKPF%QEK_7Yl|hEcDFskipbtbR+WUl2V3Aud^}qtTy4RZ)J#a$ZUu~kw%hw>5@H}Y z`;$8{*>IXphfHW0CcC5D@1mj*K9}NK!Mrr|Ia5&0y|O8;h~3x&?!Kd4ALD*tyYI&_ z{_a6HxG7FPZOz*Qk`HZ)WIq3j_Ob1EZ*iEnY8})U=74|R89ac~>Kv~>i+hP3 z7sQ-M+uLr6?6IEF9Gl>vu6LK~L{3#)Hf=p@_}u7#_t8wL(RX^vqG?=1yO?1x3F>VUJrvG? z#soS4MlJmmf90~^MxO|#aj=lQNEXwkiD_?>PBiz$cUVFce2#qPn5nlCjvIE%X@JsI zFE1s3dl&QOI1W8n3r`QbH9qOmIeZp52TW-C*sYn?b^o+``$IW%Q7zBJl;L z)jTtg!T!@H=Z{&glkDDWY7#K;BGS20UT-x=7F+`7lo@A$LS}vtHQVA705Wi^H3SHl z9*UrG=5y-gO(3|V)6>ITw3Sv$MyERs(u=Qb?wHNxf zfd?w>v!R4mb$_3ttnN6CFFgI_w&hBooWbIXUTZCrR9t%zVPPAV+m81K*KcFDW!Bxd z&90nEPz*ACWM35z#0UwOPSFO;+ z_zK}P`kj=PGKM=8FD!~=Y7q11};|9p=+BLY*m25G8rjg9qh<-Yf>kT$51%B0< z1y{5Ue8trnbm2amKPX}Ck?E$K^k7@6-YLD&!!L8v67j;CF#SfDo(KIjplOBw-vMY0 z@>MM)2WDR-QYF0^r{KZ4d-YZ?0&I&{{GOMJL9_IlD_;0``ljnGDC|px{&JPi&#jFc ztk$;7YTTkdQ-Bw{<>1|p+1rqE$9Q)^P^W!9g3(z$%Zxve-@i_DdaYEsCN5MYK}7LL zk;Bg#BI9iw&!_Pzn{Z160v`>StIf6iyI(L~%&n0tL|q7CYmqkM+I;SrfUOMp0p}Kld11j2VWPe4qFKUeXOa1Ac^)oU5+nxjZr%+ zCcKR}D>J5xpMzRH#BMb}mXLE$Y5{`)s&nkaQD;N!Or}{yU3HZ*jr}`~XPsHaosNS} zLWzF;7oJ#~HBW!oGg@3SR{)}Pj=i6R1Q1@?M<9-%TVD82b?7qMS@XWhV-?R>VD0#P zMCMZh=0KzY7rUN?GZ8xMuq!)Gjn+QRm5HsRw26k489xjYL9(7`rQ{^m(T&U1Q-qZApR1( zkMB~&^I3_2-hHBvi{yU8qBkjmR5(e}^S7aTi^VK9J*2&4!s+&a8%dQ z=GSF``PR=_eZGsT?}*A4UmeUwJMNaTrSGVY0VL``Hkb^^+Ia%Qb*_{gJy%O#V7;d& zFi8~_AB^ney;y5ppR_YSVL^7)jB9I(a8w&+fvahIxrbV+pw##E zi)S=2X3zXcPaZ_Nn$h-iO8Jq;NA-c;rK^!F8+G6B)&`p{86NqsK=fej4-l0>qyHNa zb^JQyWVY9PdC~kSYUOh*TlVKI9uxLKjD8=bNO2Z;Dm)~3+>y`>lW%W(AnNTMVZVLX zVVmi4dx8Tl+8?iN#%`<|d>V$rU8Rar%hDLX(uPc)&UBFh;W$mdBt@FA3?|roz4d4S zHT$3SrMpZ zJ6fEv&5LbnXIMW}L<1eik;$I7Mf0hzk!tUZ&ZJ(w2;?40C6u6=UgVdp`DfT)RC(Go zm#!WPt%q?e#7BnrJB!QrfBzCmHX|rQ0x8@;Zp!H zY#O>=A3k$qGIKuj#qx271h!&5XCFz21^E{!IeTLu@ded&|A10tV8NF$DH~#o0zfTGu8Gd(oGfVxXhjFYh@%ZJ#==Pu;FKphRo}y4c53w! zsbBO5-1BV;-4&+t{c?xB{djpT7krhW!eZY$_^#)yB)wL`>v7qqa!!h%?`@5nHsnd} zpRqet6{zd-y_2HJd`|Gdz3yPVgbbk%%S*);m?<$7_K-)4BKHjkLE_~r(6{Jm3;;I0 zFqCP1e->5h$jf5pbdv zt94OoVJ-bF?txEX-XFjT)>14T%u)oTWKBPv6nXLr4RQr|u=IQ8DqE?;`O!`b^~f$7 zUzhAAJ&-iy41+JxsdpG|PcE)9Yp#PZa!!lmz_%?d7FH~TJGi$!_dF-nBG4&bPsdBJ{TK+0)A()*LN6zYy zcJzrV@n?2&L?CGl7LA`6yPuU_oz9;f1o>jRp0#Ef*H_lPeW#{6-9>HL?q>V$dv3K_FuoF~LeEL> z9aQ-@jL^N&Vj3ZbaZx32l$?P5BZQICwzWcFav z_Q;yMfzodwyZ<Z7T0$YtK5<%~BT2 zb#iRAbKy;B4aCJeS8D)4^|OQP@UaJG=HkVP=x9aAdox75Z> zv;z@mWbjOz#=l{{X^1JA^vzo>dLNm*??g#L&q@vwoDwu#zDl88n@eWf8qw}W?s+)B zRFd)Q!leCEG}KdO({FF0+O-IrrUzv_pg=a~Ml6UWTFOJT=!o5O$3=%0i-;u=~F@7R?skR>1d-VVCy}w_HIs1)J2`d1;0tr6zL}@qe>d@0^*WD{)mpyPvRq~jSW@_% z-XqV|LtQ+1P5D)|yP}Apg|k(yxtvyFfX3uoXo4jVynv;+ocIEj=&LrIwB`cf!+Z|3 z;CG&jGYfK%`M`FS{TZdHw_z>E)cT^|>W&Z9r!gdD$mb`ms&Hgxo^7R1hE>KrkCzJt z>;|_t(Fa!mdEEBmrWabIAmMPan2o|(26wqO^AF;kq|4f4xCZRbKBQKWc%>`PR>;lk~zA|&d z0AD5m3RorloBJ%S@U^2Lz}_tV#@$4Ss!~%7b>LXCPJC}-L&-{aM&C%scV~!Di7Dlq z%VGM4S8~a|L^+wu@4OS92O70pO)BDmZt}QsN^6kP+eX4wc0~8tKQco1wTZC{Sn2(- zMgdL7Msz)DkT6}H6NbY6YPZjweV*^Tu>2NX9F#3J6;E^vBW3-yVjA#lAckJp6>Da(A{!l1Hw0f?UUX1!<>9 z_?1f9s{^++I$@yJM8DzzDdGw7SGJnt3t+1m%>R|Gz7$6%uHYCP`Bd==_B-lLUU-ok zy~yFd>DJ@U49eIB_j|%Ve&e`X&2G5P;|%AG zXsI^Aij=r_kiOF9M4&@_^{Rel1N;#uiSFctF<{*iaGM)7C0KkP(SEi(20m9{H@Jho0e%?G#Q-cj=fyurDbL>iCB%|{6Tze=J&P4p># z^Xyr&O2-4@A9lTLog*$QyDHjaL1Ga`I|*jtA2nwLyWPAWYO~C?JPmP~?>&c`+Z7L= z1^BZ|k0MsCq#wOk1Bu_SiHQI>aflN1GV$lGQH~fT>2hL}?!f(sJ2(#kLm-^RvGa-4 z8L0}Orw%efkXgM2I&aHMh6H=;Bdzsa0zEoQrIGr5q#^v$d>_@}KXTT?X{crtMRM&> zj(SVE)31|8=MdsHY2ODx|BRSKbN~>|4~($u{iF+p?PC#Gty$Jvgc$OGVsZJBdL)0& z$ei+al;vPK&6~Gib}h}Th@pp`k`MgP+Xo3&e-5%O7x2MX-IT557z2OUEemrdv)f94 zGs1#u*u5!|x;2|=Lc3|W&1>6-MQa>4x)qZ7vim0!=Lrrk`Y)3xzXAQ&NZR@5WXjOb z|EiAi|5Y8W_QXFI&Re`WA5ADvpZQXTRw1Fsua)4eKr+*r0rK>4m!%StMBQ)r{$vxI zWtW_mp1mkvHNi##ZAP{u3jnU8l9{AB4OS#ISA}raI~$W(`Bs#Z**zY!)LIZh{$bcK z?y%VsC)dT1Lt%?|h%1$)%n^6hJfp{^ail4pg4H?l;Vx#XeU+1vMDYuNf&BLr2S_vC zo(r6MT0g$1&hGEnd6_B<^c!YD-WeecNxdQ$!%2l!`yGxH?q;#{)MtGApQ$wB@FuuWo>le25lwL!sv7Z_aFpe_qu>?jiNHtU0JC4njN3r6_RD! zc^Ygp%6^aa6q;$1IN0dh8lvUa$lWQcQ12jWzQ)__Yw%pzj2aVTDDqcFR8p@cRjr&h zP2_z0!02vkWF^T#wCjca&(TrBGP+`1--Meh7^rTkmVI%CO(=eDxr5Sdqa^z%E`A&% zktQ{kbR8$v-h2HUZDo+Ya+bV$*b~yEJHP?t2nM0yXcSI2hnj^0)B0=xR8%TA&5$XC zn*%m?P4|phz=+Ef(V_!6m435vvedPu-s>D7p^~!8t^m7;>z@RrLuB_tN1srPUZ^%3 zpYEDpN8lpv0{dx@FdChJLa9Z6-W0NQ)={PxTTE6;P;WoH4Xb%=IHLd#Q5b3BY|~XX zA;(N!uO*Eg_u1Zhr)cu|=MT9}Z<_1_VQ1|*Hc#^F8z^&yJg!~`MN;?H?ntNyok6EJ zGvs)m|1PA?z=jD!4l7egAJT%PbW$Ru)zq6Z8gnVQCN7 zc0POvZOp5=-2N94)WilEgl9D9ITE(63Ta@sbUETVY4%1JkMg1+q>bjyYJyCA^( zUTuVBQH!t1AN2r9xqqO!UuzjmY5EkUz2tvV+~U40k>eUZ)wFTl<0Y;TMouzoBp2k; z@s?1ZG`{V@3z0RrV|k-F9^!nD;VsWTY5HiH_>8ru>WHU}_Mv}YY`l2z&4gPuzMwB4 zupEjb*d_wkBkFZ{6K>czKBsbQQXz@Gsn|$_xBC2-U-C$~eaVk4i?n0M*P+NW1mE;1 zp0Ow`LD!yMVw9W?s$2(_+rDI5F3h>s@A{HV(JA!a(EGT3nTazho98ab6P#%5NCy+| z3KDj9r9YgQ$9nIl!^PM|o|9}NARi}ZAKi?$WhZHJ((#bXvaLBnHr_nhP|!jSo|rus z@<@cI&rmHC^4<|5O%P5ww!X$SoH(3UqG3v7ZDp^Bs%_*kDnww!(VL8h|M)L%X?L#o ze2gt&zz-;(^p(!QjUcM6HY*7pbDim4lY&nKR``>h0natR{k~DY|2wd{6w&Z+V0Gl< zL|%SKwNvgVxenOM?1_-3%uB_!I?`9A1$(_5IA;)*pJwI=tGpNkL$&Jb9!2!`;&g?c z1B(C8f~goVl_}dET%o6T#@q(X04EhfLIz<%X`wCm%QqxKo>4xj3L5NU`wP0x^hwUU zVKosklgTwW{SUvR({>E0*loTH?H%-w7aJn2r_U-I$b5YkI=T8lv^&i zdP;>14GRQr-d<9|Lk|O6EtQz$KF|iMuMR|9Rx&$IOVf@GnBnOtTnEx7B|6Y-4Fl-$mhFn35FhWZVJ?f3;#21hQz`BzEJ@DA4i zGy5s+XL#}f*N^EheaRtkQju9IWUv5rXc&^f+gm-|h@dOncnc?W_(V%&v&Ivp0YHZL zGhh7N1b^`gTv3U2>+QGS&{qOtcXs1YtZ&B&bSu#rX$bdmuNnp!n{R9XqL1=W3d2(Z z{t=>C74R(poqPuvfE-qVE_@9-7Cr6L?>TORYh`f!31SiJ?Y9HH?;eqlu~+$rv7ym` z(VAhILaBdoN8PyNf|#hvT=bUH8-%Dad!sDOv_$p}#lG#~qn&dVs-A?!Qz-@5-+xPQ z$q1OfWfm{R?+?fuSe{fkUGYjM{k5bEzWya$EUn?*QX4Z|dXUC$#VN)&{gNX?IZ1`i z)hchpm2^I1RUl#nf|F@l@uCFF@=)Xs~;}BXYv!zfIxM5Gt$A8bUAxRsHv~LA_{MT z%7Xmo(ZilqBi2daqBbTb>}TT^EdhvIBm4|TIQYB%XuyRN0Sv(PUQ4T225cW(3C(sm zRUo7@hBT;oYMX}Y^-j8is!Ykt+V1dX59p#hZxUqvLY~FU^xoPfY)sZkV$$%}HwsIN z8=^5F35F3~bN1f`p>rWx)YV|~*Gm213b}hfh zF>`jq9QD1csNrJl*Kv#sF_BwSKBtl2@Vu&0EBNd2%IWRchY}~?bb^MxKhhIt!YKTp zH;#CXz>Rs$Yj*+Q;y`s`iEQ}DWxzehB8iXv3iwUpGXn1VR4OWOl{waNtppKi$P;@o z@9bYKQ{XF*{a!-yQ+6;Cp##;9N3FRnq}9wDtMnYYWuWcp5hmFxpK-)ao(ZwB+&RYL$W4r203=(#W_pmOUNze;!L= zZ!*`1f|8+GD$KAji^Q==La*rt#pGr_Y3(pD^(7%b_PbB6EKtS~^jnYgf};nx>`&|{ zA8uaBwL1uNLGRt^6Z())VMEEIX%Z$mY{=obc~)25Z&Wdceb6o>yjxd<*o!N2nmU=D z{|S?3B`GAF4Kl%@iJzhO4BDxYYJY0+c-Mqbn7ZsiUF2>J>FNNbPAv(!ygKmqwp0mS zBsTOQQA9CY%>_=)#;Y`HpeIhG^q9X{`Gw0N}+s|^_>hw^kuUNm+ub|QqPgtUl`8d5#uxbppjFrQjD zi&UqZ!4+IqW=w9r_Iv+0>eKOUVfr0kK0I?dR^txBb0_}^e`wEi@h3!M)vJW-ewGD2 z7rmT`BRLW2Np`YT1KI`tUkuZc`@a~bz@`SFq4V

    L}tzavV|z*KJFcLBCM?fvfd? z?>D_d$2=m0nt}Q`F2>|KMoO+)T`haDCPSY>EiW&_Dqfvdu=PVGyO#qldc<^ zRlBJE4+C}d%D@yFZ!^oU_mrOGR+B|x6b+pNXCo5tRh%xk$ZMiyG5X0_Swozxd2&hC z8i9Nu{*itXm9{90_`~S>eT-KNI0p!!Sme%7^@FS}_pG?MV>Gd|DjzpxG5{Ru`6tm? z$6Knyu|lspn|!?(U0P$XAy(N>OUVx-#zPI5bW8suh9TM+1XPKy5jX?j!}$9x8{Hk! z)TdeR(JWiATMM|^QZU9V7XwenjpU>4=Dq`Frke~g&aR9mXDD&e2%&iTfS{s2PHtO_ zN?Q`Dz%Lo140UeMFCJ&a;!v^y#(71P+f$I^pM|dRmc9-&Vs4t=1)R`_s;SIEKhwdK zHD;nJja4O25e&h!LZ$PE>rVU_$6ZaDig zwrng@S-WBMiF~fSmrJAf?47Ux-nZ|q{>tmvN3b` z@ch(xucm_vyEUDdSh?nj52Bh}m|UwC>&k!6RIWLT^26gV|}OBA5n1= zam6_}x49j&aSlZ7b&bH7nmj~|cUjtR;U3)$PEvv7MB`KrcttF~AR5coG&Ce4}=P>WIZbhL}2BI59 zp(M?SXF}uYc6)@_?zcs5OW^Q(E^h1G|JE!&>WsSn0}kk~&GKip;e+T?YDnWE2lR_$ zPB{y)AN2j}U!OiqLdCPWLDV!V;bAU{&x z(A^D~dNRNnjrh#Me%CSEBg;sby-w0LKNNw{-hM4VD?DvK6gYZ$29H?JJekOl!8wJd zXK;M4ejsH$KEbu4t{~i>reAG&8$7<%IILS$=Z?9+D!LiVW~WLujJ%iQ0>DsPI;JDD zR?=Sl5SD z;dOVBrkTI4J>pRiKl+qv9gBBKhl2ze1d~Cvy?qaS&Sr2G9xzo}ALz=!Ey35IgUri-sXu zu{4+%^tiU`w#)as(*CV7a~1FGO5dC6jN4mW5pXn{_98ZbW0{{#-!q<+|5G+U0m({2 z^ryj#Q9GO!LP~cqU?=vj@IH=GvokGVIOi+1R?yUC2WebX>Z2TPD8KgDV+{KK-iZ#N z2I?qvP60o{SLghLj~XoFmP#m8%oRnf?~N}$NT9BJlm5+>)hBT8PoNlv))+YIElZ!c zb_k5K;9+nB)zWHYt>q@UkxLNZju=BY`I<$4!Y z@wpP+3%^aqEsE#I~YpjuaWRANmncSH6xB%xu)m1UNrHwuQBSn_5Z&@jzQozKN8 zUPRe!M|)3tnOPSZn|K}Il5!7Hv)((~Utp`QPC?k-y~c+CgAn*f!`ju;8tY5RXw53- ztwWRLW=oTnYvUVCEfzxNDD*D~O2o^vm*OBW4B;_q#@R1$MFPaeL+j=*9JHSD?$SND zI$tyw-Z&rLR^hZLQJ!Te1R(GO;Asom4g!vf9&^TkxfpTY;jou`P2JS+vuU)`;DX^y z21DRVOe<{}qb(v!?{&M*Ws|)A0oklHv0`Ckm*f7k5cMufN>mA5bsM8nk zv1|%_!m62_QK+ucR>A{=8R==YGL#KE^=BKVS3MR&H+t%ylCDCc9;tT@&mK_K_<>d_ z+mw0uC6p16Vr44z&bu-5QOZQprgRvL!^1G0I=6S%x~t@r3ZV>&n2C&!OsF`JM-*Iy zjije?zj~s<>fhftfnUwWdJ?|Spfj*!l8;17wY%F*GI5S6T58a3C()7toSDmRPdh38 z{-72Lt5zk_t4TObvO!Kq#>(mmH{kkr&F#M4mrtL*N_-RIR~#5r!?tzd;`2)frw)J@ z2wBiv565XS%mwj-yz_ZP>rNQlJ^d_TB*=ZhUe2~No@K|=^z`1J9uxV~n@z{_^5hNl z0e>+~S^xV>kIuC}TXp%K0VPR){PV9+Gmm>avf-qg#&$b6o?o#s_4byGOzu9wojPx6 zwU9~d?#`e(j%0BTnEKvlKy+0C12zk_C#i4;+vC+98}REau4)2O2|2ascl;DDU{N~@ zloQgL$YmrEt4ye6b3G}YAJXHyBQ?Yst;hpDSB}ap?g+N`L}?w#BRL+CM{}L`4wlu5 zKP@@FCXvx<7Bb}@=Dk~dYeo<#&cayJq4x7(CK}2)bZXRtG^5G)jUi7d>9HW9Mg_c!l_VGzI#xmZM$DMX)2U1o= znX#X_K*W#kK+EY}o#UYp+^CKr)%qd_5FRI*M;<=LMP=JOXpc9Rdq=C*niMvL3T*p> zp3h)CRc~0%D-Xmx+8jajb6PzTl^j0!?qUdWRbu970T;PI+k57YT?WByN=@dTAj2Z3 z1sEkQslm#0Om(d?J!uJJo>uOpv3o6Ga6cy|wDA$`7(1sc8KzeaAn~U+8QdmAMeaHd zv|MKaXDoEADMC%)am*t*zGh(C+%PHu+-g>*Jj)}Xn91T8CheDO5@_$+KHtT-NLmJ7;A4H7_ zu}tV3nfREfcCBW-4XCEVGLde9BA&;y$WEKmT(}8(LTlu_j0Fy#Pu>qkOMW6NDmyC{ z$A1g(ZQYXX6uya?6XR$@pXfC)WHoMBRLzeqZOCg~d#mj0e?Bg>oXj)4i4;~ZT1obhOFhcy@Ht#&|RY%0jz-tM?pk zXx+wW>^>4QThzlk;U&3aEqsT2$6>#sEeiG0ac0ui6e$eT{lJmqTH8}rZ^3{B>1&3* zaT#H+`P?F}n$W2cO)!P${;tptZ=wS}M>xSAh5WKSs5(*v%3x7!Ix-`LPeaJl1~ZHe|)T>sGx;V6HMAaq=06ckfOEP=aY}6GrUkQsnKMC7a@QZ^*_xoQIt~ zjd&5BIJ2qYAf29V=#xYz6>kW2K1wK*mPf|dSt}Ht=>1ob#rT?_6~H)C&S;y}H=x}! zYd+9ufcAWs3g1BdJ;FpYmqPCIStQffkDpn27IQ?P8O9H7Zd5KX6Yr88fRj|p!1h`N zPE7kccucAybElMS(DP`u>{L(c{b5PNo#}x>g!%w{1tn{GFO4!Qc1`?eIn-DmQt8*B za(hjo)uO1DdnghWxd6=NZYG|ml(91wz86I%G*DC-k(URhcOT7H+&hsgN(Z|L6b)g~ zcK#sTQx8@Iqk{SC-c1SGIiApp_0nQ)*8^DJ+ZWFYdfAREu3i-v-wLu5ZErXpm5o1 zwl1LYV4|OH*lMi6M&8sN%szl%KlX=nc2vI6*9jJ)s-mBWeUo%EeyLOOHqw040YVWT zp350~#E?{PMXe1Or?RCS?2&m=m^+uANW^I3JR{2e9u0)Lzes038N-5Nv(+#H@W1On zRZo)GJygOvl;u|4m&E?L3A+z+KDj@Rs#wEyl6^6?{^^m;nD&;LJZwaQm|@T;k3;!C zQ8JE&>479r$O+;f_lJ(Aa7$5DW6ns~oe4=Y6a_l{mbf6Ej#aCkV) zt(|#qB7LSIFb005q}M`ZI57syzzx0^Q&F@Zy_5uv3xKmX(QR=%fG5gzQD!7gEqU=sj zXHNXV1_X?J3ktg1n+(7yEpcbdG5ZDfZ#~mM)9S0ocABiGC z^6|OKGAc!px5RkrQfrlGWOrB-t0yy=FAMPn-&RULHm?pJ3UJbetAb!}U8|7V*H471 z9$M%%pWy)#!lsfVnE8&ZtuXN=f7TA_VS=R@~)l4`~77%P2* zW2}{;rzxOys_7`lH4?%M%oTw!kwEjdZR84^362_VY^k4dmh;goiMii_2*p>&1(Lke z1}9BpaU6%sC6!7QX+#5`FRr$}XVy_5^#^s_*is%guN)y@VbFhrW#hx6_`_$v>Lv;CmoNlOzR4)KJUd;&!9<>y|5@2xz|hHp2M!tEW65CM>^+jX;X4^ey89^_V+6J3*7 zX`$EJM!0=(hm4tE!AE@|6ZOT+-9-g@x}2yPh~pv;Bztbi3M03#p68Me*K((JZ=4>` zdyFhN3Fex(0||_WDi~N)z(*`YCna;zN+lw*Ri%9&2b~VQUQ_UabS#qVPT5XNVo_)B zoJkiEIn}a1EpHI0sX&(OnM9O30E;ce)v`y_46H&kS1qq#Rdm1GB_6=Y;zzJzX!M(? zxw@@lrmT?TZkv zjov*|Z#hJ$>K^i!sr!S)8c4Rze(RB}Zd#4Lwg!Gh3f#bp-kHN94B3ApQB;!sZ& z(TPnu>9*(<7x#?JN}a0xw1O3(P*A(qIW`zI`e;eHSq?X;Btb|99h(Qkos8}~hJNbO z1B5rQjk(jd$$P`+?CJ~()<`=(G5&upE={k28|W3n@|?7l~8s+(F-AX4sop zlk;DB%W?a#M!wt~G0esc+n@+$B=YSV!Oh>Rjfy;gPpFU!%ch~`4P~p{R>(ptOn-}j z*nZ8erdl^%tToEs8t#vDjY{>u3FvqA^vcANu_H%SjV}>t&E&=~w(9v_fSfJ$&+{S@qVqIwOs^W84~c;9-$7|jt_v!KR>f-O3NfkN@RH>9`hilH6tyfQ)#>%t+U9$Xhg7(DAsc}3hkyE26gGEvOV z9<+tGY>Lh=SNXrLaeYEyy#1svRdW7pa9)IVDuw7hyyxWn;Xr@B#|pY8z2cW|e2{qK z8~$9pWz{s8Fkx|Fc5}t4>sktQKl4nTB4pU|nbC1?pW0fZl9&@Mqzr9eUnRnTD|n;M zwtFF1LFpG22S18%piq}6)+cw@p3Z_(u#tDuIM_ShaebsM0-9X;6q8UWs`GxL?ZTz! z*{bP*fue2D7kxUW;UShL6=8xO-G7A3hTG*^2%x_$Kott1$5vagPVWWBq%5szoF=ai z_XsKN2KEI>+RK!XpEORrauMbGt}yD_!*l;A`Df=aNp2y>pt*;B zE~Gb4O|k{l;$ku+NTHc+J1>BSj-qa>B9fGPHzKqiOs^8a06%x5_U?A{POW!{+8-9f4kl!!~KMlB*sok_O)V37jw8)S>%CXlgbm{X4hw z!aBDCd-K?@~kcCA7eUd?~5>&>z7$u+ebLPjSc;G~6)enIXDyj{8;+6atOXj3Ef^&yaZ&lL!(r3+42H; z>f$!@NFWi<)Sl0MPR<*zx*E6Tv;4jrtcOe9ghS0WE>J%L&^__GDcXd z4hp2pyDZJ^r!0yrud`OLNcI!G;97d2vfM*sF1f*>o943n9#mzI1St=k66u17FZKfQbSx2xu57YjzQGV9w^ z<tp?5%(vN>#A-^ne(tD|tuE_v5zWXUPhw!hJ0<|WBOV zP7CMxi5-I=?2AA2**#wQAo7Kn+lO~00a1UYv+_Ub%)va9dN+ti2sieYzRcgM6l>U1 z^;ENdiX1!s`KGU>wZJg8?lEQUt?Uk!+0K9VPb#|jWPd$u0t}y@>o?z0q%T$nYZ3yI z+ybZtsHCtO;kri=wwX10`9ZvGT!72_{o(WHbgO}NmFc~-sv;xx%;6yZW^%=9f2B_e;q2Qa%eFJ`n^Fdyea3JfiwiArgn$Io z^4Z1?y_2jZaYz5SV{w9`g!kv~9SehgjRNS^wBP)?MR?Fgq_4)ts-!)Kgf`WfQY zQ_)0cx0_FRlumB!jZ z8qfa*9s>ptN@FJ8EAEcdP#7lo^zNC3s1K>D^*<8k$w32SrT*3`DZFOD^%obas)hR! zrgLALqi_S3O$NBGsLq^9GaC}}LQ+9KxPGwjY# zuxfGKPcdZtN6%yF%VJJ5e(;vOid$}u`ew}V;p#-5OEP=HJ1$0baERH7r_s?E+_%#>*tw_Mvz5GQ=_?=WIL%)j=`jA z*Mm>LTmmPV7d!A=V!5+?FOIXe>nw4&6k6j-+}eW=rd7PG@`Vh@z_O~76gsHMl;VPD zgid8aAXzN&-m9<-n@&iu9u!=J#hAl?ya)9N{+5fQ`IhmO%^31ymoXthWzX%Hn*tZyL{)w*n}i z8Q`g!vdENh91YmEq4yP28kkR7YyXHK8>Y_nJ*DyRmD?IddVa;p{1(E6$65c&(lg7x z9VQcWFzIG9@p3$834dhsMpTu{!w(bx17E@oQyK*R2jMY^GA!=PqYxVCfw^0(`b`GT zW_QQMt8QfQ$1%R_f+<N=<=;-(}3%B@nOG_8g;E|tw3ls=Fq?*EEl zU~wCWzQq3Nda&58IG-6MjG~nr(8vsk{oKY%gdQ=vSDAb)#a@&8{mHm31dx@Ck&}#cjV_) zJ^gbpJrMCG1BDdPc1}F4Uf%l!4a9*Hw?;N|h_!M;H@_y4sWpv=9kJ`tVcSq6;+Hq_ z9~8kJ#&YyW6R8U;=Sglto3s1OdZZ`Mc0I~+xlNPz9ucR%8w0XA1Nrkc!y6GBqtByt7$kKFf*6uwW zcl$O8$#0YTe@}2c)RM%1^2v+HMwEF?zmbrq-g&mN;Bo6J?+(+dqSUej6pWnqGA z5~LXva>^ZV?6vgrjJQaV5EgIth2+%n7Sc~|Wi$DQqqx{&QB_qHG^8TtJ@xKoW81~b z^JM$rhx~-tyq{{Aj6=0kg`!3UT2Y|uJ7QSM;hb2j#4GiP6R&+yll>`H%%z3_;=6sA z%!}*P{%Wk_3CZyiinkz*oV(tF*1Qoe`kPz}{@BM;gYFOR+H958mT4L>(1-A7`P^o! zH)v`O+W`f)O3Z5?z6x4^(!A@Ze!Fc;vMg>j!k;e5mvYPKcmw_jw%8;j)FsFekH%`jWEAvy<39wXIz){jF_9^W=}#O^0kopJkKgXO_@GrXO1rq7T+Da1R>Wg6YQO~Mm@&DS!F(1r97Qlsv)@2>+th1u zL_B(Cizut|Q85N;Ayu{yUAccV!Z literal 0 HcmV?d00001 From 5af2c1bb5e895018edf8780d75485b654ff5c787 Mon Sep 17 00:00:00 2001 From: SzymonParapura Date: Wed, 11 Sep 2024 12:44:43 +0200 Subject: [PATCH 252/304] docs: Update BuildInstructions.md - Updated instructions to provide clearer guidance through the process of building SS2 --- docs/user_guide/BuildInstructions.md | 141 ++++++++++++++++++++------- 1 file changed, 106 insertions(+), 35 deletions(-) diff --git a/docs/user_guide/BuildInstructions.md b/docs/user_guide/BuildInstructions.md index f2829a40571..42845d5fc6c 100644 --- a/docs/user_guide/BuildInstructions.md +++ b/docs/user_guide/BuildInstructions.md @@ -1,51 +1,122 @@ # Build Instructions -This setup instruction is based on ROS 2 humble. +These setup instructions guide you through the process of building **Scenario Simulator v2**, which currently supports **ROS 2 Humble Hawksbill**. + +--- ## Setup ROS 2 environment -This framework only supports ROS 2 Galactic Geochelone now. (We are planning to support ROS 2 Humble Hawksbill) -You can install Galactic by executing the command below in your terminal. +1. **Configure the locale** + Ensure that your system is configured with a locale that supports UTF-8. + + ```bash + sudo apt update && sudo apt install locales + sudo locale-gen en_US en_US.UTF-8 + sudo update-locale LC_ALL=en_US.UTF-8 LANG=en_US.UTF-8 + export LANG=en_US.UTF-8 + ``` + + Verify that the locale is properly set: + ```bash + locale + ``` + ![Verifying Locale](../image/locale_verification.png) + *The expected result after running the `locale` command should look like this, with **LANG** set to **en_US.UTF-8**.* + +2. **Enable the Ubuntu Universe repository** + Run the following commands to enable the Universe repository: + + ```bash + sudo apt install software-properties-common + sudo add-apt-repository universe + ``` + + ![Adding Universe Repository](../image/universe_repository_result.png) + *The expected result after running `sudo add-apt-repository universe`.* + +3. **Add the ROS 2 GPG key** + Install `curl` and add the ROS 2 GPG key to your system: + + ```bash + sudo apt update && sudo apt install curl -y + sudo curl -sSL https://raw.githubusercontent.com/ros/rosdistro/master/ros.key -o /usr/share/keyrings/ros-archive-keyring.gpg + ``` + +4. **Add the ROS 2 repository to the system's package sources list** + This command adds the ROS 2 repository to the system’s package sources list, enabling access to ROS 2 packages: + + ```bash + echo "deb [arch=$(dpkg --print-architecture) signed-by=/usr/share/keyrings/ros-archive-keyring.gpg] http://packages.ros.org/ros2/ubuntu $(. /etc/os-release && echo $UBUNTU_CODENAME) main" | sudo tee /etc/apt/sources.list.d/ros2.list > /dev/null + ``` + +5. **Install ROS 2 Humble Desktop** + Update the apt cache and install ROS 2 Humble with the following command: + + ```bash + sudo apt update + sudo apt install ros-humble-desktop + ``` + +6. **Install development tools** + Install the development tools needed to build ROS packages: + + ```bash + sudo apt install ros-dev-tools + ``` +> **Reference:** [ROS 2 Humble Installation Guide](https://docs.ros.org/en/humble/Installation.html) +--- -```bash -sudo apt update -sudo apt install locales -sudo locale-gen en_US en_US.UTF-8 -sudo update-locale LC_ALL=en_US.UTF-8 LANG=en_US.UTF-8 -export LANG=en_US.UTF-8 -sudo apt update -sudo apt install curl gnupg2 lsb-release -curl -s https://raw.githubusercontent.com/ros/rosdistro/master/ros.asc | sudo apt-key add - -sudo sh -c 'echo "deb [arch=$(dpkg --print-architecture)] http://packages.ros.org/ros2/ubuntu $(lsb_release -cs) main" > /etc/apt/sources.list.d/ros2-latest.list' -sudo apt update -sudo apt install ros-humble-desktop -source /opt/ros/humble/setup.bash -sudo apt install -y python3-pip python3-rosdep2 python3-vcstool python3-colcon-common-extensions -rosdep update -``` -reference : ## Setup workspace -```bash -mkdir -p ~/scenario_simulator_ws/src -cd ~/scenario_simulator_ws/src -git clone https://github.com/tier4/scenario_simulator_v2.git -# These lines are necessary right now, but it will be removed in the near future -cd scenario_simulator_v2 -# This script clones the part of the source codes in Autoware and add it to the workspace -vcs import external < dependency_humble.repos -``` +1. **Create the workspace directory** + + ```bash + mkdir -p ~/scenario_simulator_ws/src + cd ~/scenario_simulator_ws/src + ``` + +2. **Clone the Scenario Simulator repository** + + ```bash + git clone https://github.com/tier4/scenario_simulator_v2.git + cd scenario_simulator_v2 + ``` + +3. **Import Autoware dependencies** + + ```bash + vcs import external < dependency_humble.repos + ``` +--- ## Install dependencies via rosdep -```bash -cd ~/scenario_simulator_ws -source /opt/ros/humble/setup.bash -rosdep install -iry --from-paths src/scenario_simulator_v2 --rosdistro humble -``` +1. **Move to the workspace directory** + Before installing dependencies, navigate to the workspace directory where **Scenario Simulator v2** is located: -## Build scenario_simulator_v2 + ```bash + cd ~/scenario_simulator_ws + ``` + +2. **Source the ROS 2 environment** + Make sure the ROS 2 environment is properly sourced by running: + + ```bash + source /opt/ros/humble/setup.bash + ``` +3. **Install all required dependencies** + Use `rosdep` to install all dependencies required for **Scenario Simulator v2**: + + ```bash + rosdep install -iry --from-paths src/scenario_simulator_v2 --rosdistro humble + ``` +--- + +## Build scenario_simulator_v2 +To build **Scenario Simulator v2**, run this command: ```bash colcon build --symlink-install --cmake-args -DCMAKE_BUILD_TYPE=Release ``` +![Build Success](../image/build_success2.png) +*The expected result after running `colcon build` should display a message confirming a successful build.* \ No newline at end of file From 28915d790e037a571d63de329be941c52104491a Mon Sep 17 00:00:00 2001 From: SzymonParapura Date: Wed, 11 Sep 2024 12:59:13 +0200 Subject: [PATCH 253/304] docs: Update BuildInstructions.md --- docs/user_guide/BuildInstructions.md | 5 ----- 1 file changed, 5 deletions(-) diff --git a/docs/user_guide/BuildInstructions.md b/docs/user_guide/BuildInstructions.md index 42845d5fc6c..c28f8cecbf9 100644 --- a/docs/user_guide/BuildInstructions.md +++ b/docs/user_guide/BuildInstructions.md @@ -2,8 +2,6 @@ These setup instructions guide you through the process of building **Scenario Simulator v2**, which currently supports **ROS 2 Humble Hawksbill**. ---- - ## Setup ROS 2 environment 1. **Configure the locale** @@ -64,7 +62,6 @@ These setup instructions guide you through the process of building **Scenario Si sudo apt install ros-dev-tools ``` > **Reference:** [ROS 2 Humble Installation Guide](https://docs.ros.org/en/humble/Installation.html) ---- ## Setup workspace @@ -87,7 +84,6 @@ These setup instructions guide you through the process of building **Scenario Si ```bash vcs import external < dependency_humble.repos ``` ---- ## Install dependencies via rosdep @@ -111,7 +107,6 @@ These setup instructions guide you through the process of building **Scenario Si ```bash rosdep install -iry --from-paths src/scenario_simulator_v2 --rosdistro humble ``` ---- ## Build scenario_simulator_v2 To build **Scenario Simulator v2**, run this command: From 06465ccb1d427ec7a11c84f5d57abd3a148150be Mon Sep 17 00:00:00 2001 From: SzymonParapura Date: Wed, 11 Sep 2024 13:03:09 +0200 Subject: [PATCH 254/304] docs: Update BuildInstructions.md - Added a new line at the end of the file --- docs/user_guide/BuildInstructions.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/user_guide/BuildInstructions.md b/docs/user_guide/BuildInstructions.md index c28f8cecbf9..6ef6230a6a6 100644 --- a/docs/user_guide/BuildInstructions.md +++ b/docs/user_guide/BuildInstructions.md @@ -114,4 +114,4 @@ To build **Scenario Simulator v2**, run this command: colcon build --symlink-install --cmake-args -DCMAKE_BUILD_TYPE=Release ``` ![Build Success](../image/build_success2.png) -*The expected result after running `colcon build` should display a message confirming a successful build.* \ No newline at end of file +*The expected result after running `colcon build` should display a message confirming a successful build.* From 50f9222c283c12f2a5e26cd088ab2887cefbd8e4 Mon Sep 17 00:00:00 2001 From: XiaoyuWang0601 Date: Thu, 12 Sep 2024 15:26:51 +0900 Subject: [PATCH 255/304] fix: install add_cpp_mock_scenario_test.cmake first, or build won't pass --- mock/cpp_mock_scenarios/CMakeLists.txt | 3 +++ 1 file changed, 3 insertions(+) diff --git a/mock/cpp_mock_scenarios/CMakeLists.txt b/mock/cpp_mock_scenarios/CMakeLists.txt index 84a18e37be7..669465e6482 100644 --- a/mock/cpp_mock_scenarios/CMakeLists.txt +++ b/mock/cpp_mock_scenarios/CMakeLists.txt @@ -64,6 +64,9 @@ endif() install( DIRECTORY launch rviz DESTINATION share/${PROJECT_NAME}) +install( + FILES cmake/add_cpp_mock_scenario_test.cmake + DESTINATION share/${PROJECT_NAME}/cmake) if(BUILD_TESTING) find_package(ament_lint_auto REQUIRED) From edf52957fe74fdf688a1c3644c99350494bccc2f Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Thu, 12 Sep 2024 07:25:43 +0000 Subject: [PATCH 256/304] doc: fix architecture_type in documentation --- docs/user_guide/QuickStart.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/user_guide/QuickStart.md b/docs/user_guide/QuickStart.md index 1203f12df49..56bb42778bf 100644 --- a/docs/user_guide/QuickStart.md +++ b/docs/user_guide/QuickStart.md @@ -65,7 +65,7 @@ This document contains step-by-step instruction on how to build and run [AWF Aut #### scenario_test_runner ```bash ros2 launch scenario_test_runner scenario_test_runner.launch.py \ - architecture_type:=awf/universe \ + architecture_type:=awf/universe/20230906 \ record:=false \ scenario:='$(find-pkg-share scenario_test_runner)/scenario/sample.yaml' \ sensor_model:=sample_sensor_kit \ @@ -75,7 +75,7 @@ This document contains step-by-step instruction on how to build and run [AWF Aut #### random_test_runner ```bash ros2 launch random_test_runner random_test.launch.py \ - architecture_type:=awf/universe \ + architecture_type:=awf/universe/20230906 \ sensor_model:=sample_sensor_kit \ vehicle_model:=sample_vehicle ``` From 5740aa4f45cb5f2d9661c716217dba403313f0ea Mon Sep 17 00:00:00 2001 From: Release Bot Date: Thu, 12 Sep 2024 08:57:17 +0000 Subject: [PATCH 257/304] Bump version of scenario_simulator_v2 from version 4.2.3 to version 4.2.4 --- common/math/arithmetic/CHANGELOG.rst | 3 +++ common/math/arithmetic/package.xml | 2 +- common/math/geometry/CHANGELOG.rst | 3 +++ common/math/geometry/package.xml | 2 +- common/scenario_simulator_exception/CHANGELOG.rst | 3 +++ common/scenario_simulator_exception/package.xml | 2 +- common/simple_junit/CHANGELOG.rst | 3 +++ common/simple_junit/package.xml | 2 +- common/status_monitor/CHANGELOG.rst | 3 +++ common/status_monitor/package.xml | 2 +- external/concealer/CHANGELOG.rst | 3 +++ external/concealer/package.xml | 2 +- external/embree_vendor/CHANGELOG.rst | 3 +++ external/embree_vendor/package.xml | 2 +- map/kashiwanoha_map/CHANGELOG.rst | 3 +++ map/kashiwanoha_map/package.xml | 2 +- map/simple_cross_map/CHANGELOG.rst | 3 +++ map/simple_cross_map/package.xml | 2 +- mock/cpp_mock_scenarios/CHANGELOG.rst | 3 +++ mock/cpp_mock_scenarios/package.xml | 2 +- openscenario/openscenario_experimental_catalog/CHANGELOG.rst | 3 +++ openscenario/openscenario_experimental_catalog/package.xml | 2 +- openscenario/openscenario_interpreter/CHANGELOG.rst | 3 +++ openscenario/openscenario_interpreter/package.xml | 2 +- openscenario/openscenario_interpreter_example/CHANGELOG.rst | 3 +++ openscenario/openscenario_interpreter_example/package.xml | 2 +- openscenario/openscenario_interpreter_msgs/CHANGELOG.rst | 3 +++ openscenario/openscenario_interpreter_msgs/package.xml | 2 +- openscenario/openscenario_preprocessor/CHANGELOG.rst | 3 +++ openscenario/openscenario_preprocessor/package.xml | 2 +- openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst | 3 +++ openscenario/openscenario_preprocessor_msgs/package.xml | 2 +- openscenario/openscenario_utility/CHANGELOG.rst | 3 +++ openscenario/openscenario_utility/package.xml | 2 +- openscenario/openscenario_validator/CHANGELOG.rst | 3 +++ openscenario/openscenario_validator/package.xml | 2 +- rviz_plugins/openscenario_visualization/CHANGELOG.rst | 3 +++ rviz_plugins/openscenario_visualization/package.xml | 2 +- .../real_time_factor_control_rviz_plugin/CHANGELOG.rst | 3 +++ rviz_plugins/real_time_factor_control_rviz_plugin/package.xml | 2 +- scenario_simulator_v2/CHANGELOG.rst | 3 +++ scenario_simulator_v2/package.xml | 2 +- simulation/behavior_tree_plugin/CHANGELOG.rst | 3 +++ simulation/behavior_tree_plugin/package.xml | 2 +- simulation/do_nothing_plugin/CHANGELOG.rst | 3 +++ simulation/do_nothing_plugin/package.xml | 2 +- simulation/simple_sensor_simulator/CHANGELOG.rst | 3 +++ simulation/simple_sensor_simulator/package.xml | 2 +- simulation/simulation_interface/CHANGELOG.rst | 3 +++ simulation/simulation_interface/package.xml | 2 +- simulation/traffic_simulator/CHANGELOG.rst | 3 +++ simulation/traffic_simulator/package.xml | 2 +- simulation/traffic_simulator_msgs/CHANGELOG.rst | 3 +++ simulation/traffic_simulator_msgs/package.xml | 2 +- test_runner/random_test_runner/CHANGELOG.rst | 3 +++ test_runner/random_test_runner/package.xml | 2 +- test_runner/scenario_test_runner/CHANGELOG.rst | 3 +++ test_runner/scenario_test_runner/package.xml | 2 +- 58 files changed, 116 insertions(+), 29 deletions(-) diff --git a/common/math/arithmetic/CHANGELOG.rst b/common/math/arithmetic/CHANGELOG.rst index fd79e4bad12..0812c8d344c 100644 --- a/common/math/arithmetic/CHANGELOG.rst +++ b/common/math/arithmetic/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package arithmetic * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.4 (2024-09-12) +------------------ + 4.2.3 (2024-09-11) ------------------ diff --git a/common/math/arithmetic/package.xml b/common/math/arithmetic/package.xml index f67cfd3e6d5..dedd48a5205 100644 --- a/common/math/arithmetic/package.xml +++ b/common/math/arithmetic/package.xml @@ -2,7 +2,7 @@ arithmetic - 4.2.3 + 4.2.4 arithmetic library for scenario_simulator_v2 Tatsuya Yamasaki Apache License 2.0 diff --git a/common/math/geometry/CHANGELOG.rst b/common/math/geometry/CHANGELOG.rst index c8a162b4fcb..9ed062f33cf 100644 --- a/common/math/geometry/CHANGELOG.rst +++ b/common/math/geometry/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package geometry * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.4 (2024-09-12) +------------------ + 4.2.3 (2024-09-11) ------------------ diff --git a/common/math/geometry/package.xml b/common/math/geometry/package.xml index e87d2b65d4f..9fc27e2f994 100644 --- a/common/math/geometry/package.xml +++ b/common/math/geometry/package.xml @@ -2,7 +2,7 @@ geometry - 4.2.3 + 4.2.4 geometry math library for scenario_simulator_v2 application Masaya Kataoka Apache License 2.0 diff --git a/common/scenario_simulator_exception/CHANGELOG.rst b/common/scenario_simulator_exception/CHANGELOG.rst index 51b5f065bad..60ea49ae64a 100644 --- a/common/scenario_simulator_exception/CHANGELOG.rst +++ b/common/scenario_simulator_exception/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package scenario_simulator_exception * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.4 (2024-09-12) +------------------ + 4.2.3 (2024-09-11) ------------------ diff --git a/common/scenario_simulator_exception/package.xml b/common/scenario_simulator_exception/package.xml index 17bb3cd129b..4e446fbd3de 100644 --- a/common/scenario_simulator_exception/package.xml +++ b/common/scenario_simulator_exception/package.xml @@ -2,7 +2,7 @@ scenario_simulator_exception - 4.2.3 + 4.2.4 Exception types for scenario simulator Tatsuya Yamasaki Apache License 2.0 diff --git a/common/simple_junit/CHANGELOG.rst b/common/simple_junit/CHANGELOG.rst index df19ee8bf21..3852989aa47 100644 --- a/common/simple_junit/CHANGELOG.rst +++ b/common/simple_junit/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package junit_exporter * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.4 (2024-09-12) +------------------ + 4.2.3 (2024-09-11) ------------------ diff --git a/common/simple_junit/package.xml b/common/simple_junit/package.xml index 8b646b6b552..8d130590fc9 100644 --- a/common/simple_junit/package.xml +++ b/common/simple_junit/package.xml @@ -2,7 +2,7 @@ simple_junit - 4.2.3 + 4.2.4 Lightweight JUnit library for ROS 2 Masaya Kataoka Tatsuya Yamasaki diff --git a/common/status_monitor/CHANGELOG.rst b/common/status_monitor/CHANGELOG.rst index 3a0ed07dcfa..5f889127dd5 100644 --- a/common/status_monitor/CHANGELOG.rst +++ b/common/status_monitor/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package status_monitor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.4 (2024-09-12) +------------------ + 4.2.3 (2024-09-11) ------------------ diff --git a/common/status_monitor/package.xml b/common/status_monitor/package.xml index 239ad4b7930..67f9c9ca118 100644 --- a/common/status_monitor/package.xml +++ b/common/status_monitor/package.xml @@ -2,7 +2,7 @@ status_monitor - 4.2.3 + 4.2.4 none Tatsuya Yamasaki Apache License 2.0 diff --git a/external/concealer/CHANGELOG.rst b/external/concealer/CHANGELOG.rst index 9f5aaf3c341..359c2ddacd8 100644 --- a/external/concealer/CHANGELOG.rst +++ b/external/concealer/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package concealer * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.4 (2024-09-12) +------------------ + 4.2.3 (2024-09-11) ------------------ diff --git a/external/concealer/package.xml b/external/concealer/package.xml index ea864a1988d..1c7dddc5d7f 100644 --- a/external/concealer/package.xml +++ b/external/concealer/package.xml @@ -2,7 +2,7 @@ concealer - 4.2.3 + 4.2.4 Provides a class 'Autoware' to conceal miscellaneous things to simplify Autoware management of the simulator. Tatsuya Yamasaki Apache License 2.0 diff --git a/external/embree_vendor/CHANGELOG.rst b/external/embree_vendor/CHANGELOG.rst index 78065ef7226..68cfbf7a078 100644 --- a/external/embree_vendor/CHANGELOG.rst +++ b/external/embree_vendor/CHANGELOG.rst @@ -24,6 +24,9 @@ Changelog for package embree_vendor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.4 (2024-09-12) +------------------ + 4.2.3 (2024-09-11) ------------------ diff --git a/external/embree_vendor/package.xml b/external/embree_vendor/package.xml index e2d2cbcac44..7d4e8ea8e4b 100644 --- a/external/embree_vendor/package.xml +++ b/external/embree_vendor/package.xml @@ -2,7 +2,7 @@ embree_vendor - 4.2.3 + 4.2.4 vendor packages for intel raytracing kernel library masaya Apache 2.0 diff --git a/map/kashiwanoha_map/CHANGELOG.rst b/map/kashiwanoha_map/CHANGELOG.rst index cfed45d19b2..66d819a7149 100644 --- a/map/kashiwanoha_map/CHANGELOG.rst +++ b/map/kashiwanoha_map/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package kashiwanoha_map * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.4 (2024-09-12) +------------------ + 4.2.3 (2024-09-11) ------------------ diff --git a/map/kashiwanoha_map/package.xml b/map/kashiwanoha_map/package.xml index 8442aa21541..b282ae09300 100644 --- a/map/kashiwanoha_map/package.xml +++ b/map/kashiwanoha_map/package.xml @@ -2,7 +2,7 @@ kashiwanoha_map - 4.2.3 + 4.2.4 map package for kashiwanoha Masaya Kataoka Apache License 2.0 diff --git a/map/simple_cross_map/CHANGELOG.rst b/map/simple_cross_map/CHANGELOG.rst index 9fe9db19393..e50a2bb6d24 100644 --- a/map/simple_cross_map/CHANGELOG.rst +++ b/map/simple_cross_map/CHANGELOG.rst @@ -9,6 +9,9 @@ Changelog for package simple_cross_map * Merge branch 'master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.4 (2024-09-12) +------------------ + 4.2.3 (2024-09-11) ------------------ diff --git a/map/simple_cross_map/package.xml b/map/simple_cross_map/package.xml index 483e01bb013..e9718313746 100644 --- a/map/simple_cross_map/package.xml +++ b/map/simple_cross_map/package.xml @@ -2,7 +2,7 @@ simple_cross_map - 4.2.3 + 4.2.4 map package for simple cross Masaya Kataoka Apache License 2.0 diff --git a/mock/cpp_mock_scenarios/CHANGELOG.rst b/mock/cpp_mock_scenarios/CHANGELOG.rst index e73e52e247e..0af95e62029 100644 --- a/mock/cpp_mock_scenarios/CHANGELOG.rst +++ b/mock/cpp_mock_scenarios/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package cpp_mock_scenarios * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.4 (2024-09-12) +------------------ + 4.2.3 (2024-09-11) ------------------ * Merge pull request `#1368 `_ from tier4/fix/mock-test-launch-test diff --git a/mock/cpp_mock_scenarios/package.xml b/mock/cpp_mock_scenarios/package.xml index 60a09d10358..c417eb9e07d 100644 --- a/mock/cpp_mock_scenarios/package.xml +++ b/mock/cpp_mock_scenarios/package.xml @@ -2,7 +2,7 @@ cpp_mock_scenarios - 4.2.3 + 4.2.4 C++ mock scenarios masaya Apache License 2.0 diff --git a/openscenario/openscenario_experimental_catalog/CHANGELOG.rst b/openscenario/openscenario_experimental_catalog/CHANGELOG.rst index d15e81f4922..af0ef196625 100644 --- a/openscenario/openscenario_experimental_catalog/CHANGELOG.rst +++ b/openscenario/openscenario_experimental_catalog/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package openscenario_experimental_catalog * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.4 (2024-09-12) +------------------ + 4.2.3 (2024-09-11) ------------------ diff --git a/openscenario/openscenario_experimental_catalog/package.xml b/openscenario/openscenario_experimental_catalog/package.xml index aaa3342b624..5069270d319 100644 --- a/openscenario/openscenario_experimental_catalog/package.xml +++ b/openscenario/openscenario_experimental_catalog/package.xml @@ -2,7 +2,7 @@ openscenario_experimental_catalog - 4.2.3 + 4.2.4 TIER IV experimental catalogs for OpenSCENARIO Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter/CHANGELOG.rst b/openscenario/openscenario_interpreter/CHANGELOG.rst index 4f2c1bafe04..4853d958587 100644 --- a/openscenario/openscenario_interpreter/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter/CHANGELOG.rst @@ -32,6 +32,9 @@ Changelog for package openscenario_interpreter * add publish_empty_context parameter * Contributors: Masaya Kataoka +4.2.4 (2024-09-12) +------------------ + 4.2.3 (2024-09-11) ------------------ diff --git a/openscenario/openscenario_interpreter/package.xml b/openscenario/openscenario_interpreter/package.xml index 8ba2e126d37..9c34db6aa73 100644 --- a/openscenario/openscenario_interpreter/package.xml +++ b/openscenario/openscenario_interpreter/package.xml @@ -2,7 +2,7 @@ openscenario_interpreter - 4.2.3 + 4.2.4 OpenSCENARIO 1.2.0 interpreter package for Autoware Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter_example/CHANGELOG.rst b/openscenario/openscenario_interpreter_example/CHANGELOG.rst index aef3a67cb19..0d8a8c28fdc 100644 --- a/openscenario/openscenario_interpreter_example/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter_example/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package openscenario_interpreter_example * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.4 (2024-09-12) +------------------ + 4.2.3 (2024-09-11) ------------------ diff --git a/openscenario/openscenario_interpreter_example/package.xml b/openscenario/openscenario_interpreter_example/package.xml index 585e79d4b59..77bd1d6f96d 100644 --- a/openscenario/openscenario_interpreter_example/package.xml +++ b/openscenario/openscenario_interpreter_example/package.xml @@ -3,7 +3,7 @@ openscenario_interpreter_example - 4.2.3 + 4.2.4 Examples for some TIER IV OpenSCENARIO Interpreter's features Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst b/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst index 605c7dce33f..618ada540b1 100644 --- a/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package openscenario_interpreter_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.4 (2024-09-12) +------------------ + 4.2.3 (2024-09-11) ------------------ diff --git a/openscenario/openscenario_interpreter_msgs/package.xml b/openscenario/openscenario_interpreter_msgs/package.xml index d50377f1bfb..551aec033b8 100644 --- a/openscenario/openscenario_interpreter_msgs/package.xml +++ b/openscenario/openscenario_interpreter_msgs/package.xml @@ -2,7 +2,7 @@ openscenario_interpreter_msgs - 4.2.3 + 4.2.4 ROS message types for package openscenario_interpreter Yamasaki Tatsuya Apache License 2.0 diff --git a/openscenario/openscenario_preprocessor/CHANGELOG.rst b/openscenario/openscenario_preprocessor/CHANGELOG.rst index 1b5a3958a07..ecab3cb174f 100644 --- a/openscenario/openscenario_preprocessor/CHANGELOG.rst +++ b/openscenario/openscenario_preprocessor/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package openscenario_preprocessor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.4 (2024-09-12) +------------------ + 4.2.3 (2024-09-11) ------------------ diff --git a/openscenario/openscenario_preprocessor/package.xml b/openscenario/openscenario_preprocessor/package.xml index 0ce282b859e..a8cb4fe6958 100644 --- a/openscenario/openscenario_preprocessor/package.xml +++ b/openscenario/openscenario_preprocessor/package.xml @@ -3,7 +3,7 @@ openscenario_preprocessor - 4.2.3 + 4.2.4 Example package for TIER IV OpenSCENARIO Interpreter Kotaro Yoshimoto Apache License 2.0 diff --git a/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst b/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst index fb7b3121a42..f5115de4002 100644 --- a/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst +++ b/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package openscenario_preprocessor_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.4 (2024-09-12) +------------------ + 4.2.3 (2024-09-11) ------------------ diff --git a/openscenario/openscenario_preprocessor_msgs/package.xml b/openscenario/openscenario_preprocessor_msgs/package.xml index 368876f8785..6668ee204c4 100644 --- a/openscenario/openscenario_preprocessor_msgs/package.xml +++ b/openscenario/openscenario_preprocessor_msgs/package.xml @@ -2,7 +2,7 @@ openscenario_preprocessor_msgs - 4.2.3 + 4.2.4 ROS message types for package openscenario_preprocessor Kotaro Yoshimoto Apache License 2.0 diff --git a/openscenario/openscenario_utility/CHANGELOG.rst b/openscenario/openscenario_utility/CHANGELOG.rst index 4550913ef69..22e2f71af03 100644 --- a/openscenario/openscenario_utility/CHANGELOG.rst +++ b/openscenario/openscenario_utility/CHANGELOG.rst @@ -24,6 +24,9 @@ Changelog for package openscenario_utility * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.4 (2024-09-12) +------------------ + 4.2.3 (2024-09-11) ------------------ diff --git a/openscenario/openscenario_utility/package.xml b/openscenario/openscenario_utility/package.xml index bf2f24bdd1d..89e4941879e 100644 --- a/openscenario/openscenario_utility/package.xml +++ b/openscenario/openscenario_utility/package.xml @@ -2,7 +2,7 @@ openscenario_utility - 4.2.3 + 4.2.4 Utility tools for ASAM OpenSCENARIO 1.2.0 Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_validator/CHANGELOG.rst b/openscenario/openscenario_validator/CHANGELOG.rst index e4f33e66c7a..9a749463a89 100644 --- a/openscenario/openscenario_validator/CHANGELOG.rst +++ b/openscenario/openscenario_validator/CHANGELOG.rst @@ -10,6 +10,9 @@ Changelog for package openscenario_validator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.4 (2024-09-12) +------------------ + 4.2.3 (2024-09-11) ------------------ diff --git a/openscenario/openscenario_validator/package.xml b/openscenario/openscenario_validator/package.xml index bda9faae864..6ef0a343a72 100644 --- a/openscenario/openscenario_validator/package.xml +++ b/openscenario/openscenario_validator/package.xml @@ -2,7 +2,7 @@ openscenario_validator - 4.2.3 + 4.2.4 Validator for OpenSCENARIO 1.3 Kotaro Yoshimoto Apache License 2.0 diff --git a/rviz_plugins/openscenario_visualization/CHANGELOG.rst b/rviz_plugins/openscenario_visualization/CHANGELOG.rst index bd79e6827b4..9a0d1705d1e 100644 --- a/rviz_plugins/openscenario_visualization/CHANGELOG.rst +++ b/rviz_plugins/openscenario_visualization/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package openscenario_visualization * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.4 (2024-09-12) +------------------ + 4.2.3 (2024-09-11) ------------------ diff --git a/rviz_plugins/openscenario_visualization/package.xml b/rviz_plugins/openscenario_visualization/package.xml index 0893c14ad64..589d454f0a2 100644 --- a/rviz_plugins/openscenario_visualization/package.xml +++ b/rviz_plugins/openscenario_visualization/package.xml @@ -2,7 +2,7 @@ openscenario_visualization - 4.2.3 + 4.2.4 Visualization tools for simulation results Masaya Kataoka Kyoichi Sugahara diff --git a/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst b/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst index ec85a4ae875..4167ed89c31 100644 --- a/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst +++ b/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package real_time_factor_control_rviz_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.4 (2024-09-12) +------------------ + 4.2.3 (2024-09-11) ------------------ diff --git a/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml b/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml index da4ea4182c9..5241b815471 100644 --- a/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml +++ b/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml @@ -2,7 +2,7 @@ real_time_factor_control_rviz_plugin - 4.2.3 + 4.2.4 Slider controlling real time factor value. Paweł Lech Apache License 2.0 diff --git a/scenario_simulator_v2/CHANGELOG.rst b/scenario_simulator_v2/CHANGELOG.rst index 738acc323fa..6266f4590c9 100644 --- a/scenario_simulator_v2/CHANGELOG.rst +++ b/scenario_simulator_v2/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package scenario_simulator_v2 * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.4 (2024-09-12) +------------------ + 4.2.3 (2024-09-11) ------------------ diff --git a/scenario_simulator_v2/package.xml b/scenario_simulator_v2/package.xml index 21089550ebb..839855315d9 100644 --- a/scenario_simulator_v2/package.xml +++ b/scenario_simulator_v2/package.xml @@ -2,7 +2,7 @@ scenario_simulator_v2 - 4.2.3 + 4.2.4 scenario testing framework for Autoware Masaya Kataoka Apache License 2.0 diff --git a/simulation/behavior_tree_plugin/CHANGELOG.rst b/simulation/behavior_tree_plugin/CHANGELOG.rst index c7bd18c4095..5ae4eb6d887 100644 --- a/simulation/behavior_tree_plugin/CHANGELOG.rst +++ b/simulation/behavior_tree_plugin/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package behavior_tree_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.4 (2024-09-12) +------------------ + 4.2.3 (2024-09-11) ------------------ diff --git a/simulation/behavior_tree_plugin/package.xml b/simulation/behavior_tree_plugin/package.xml index a38c59d4341..6517e5c8d69 100644 --- a/simulation/behavior_tree_plugin/package.xml +++ b/simulation/behavior_tree_plugin/package.xml @@ -2,7 +2,7 @@ behavior_tree_plugin - 4.2.3 + 4.2.4 Behavior tree plugin for traffic_simulator masaya Apache 2.0 diff --git a/simulation/do_nothing_plugin/CHANGELOG.rst b/simulation/do_nothing_plugin/CHANGELOG.rst index 49d4418f896..96457e13608 100644 --- a/simulation/do_nothing_plugin/CHANGELOG.rst +++ b/simulation/do_nothing_plugin/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package do_nothing_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.4 (2024-09-12) +------------------ + 4.2.3 (2024-09-11) ------------------ diff --git a/simulation/do_nothing_plugin/package.xml b/simulation/do_nothing_plugin/package.xml index b74f1f8e8e6..e1af53d0e9f 100644 --- a/simulation/do_nothing_plugin/package.xml +++ b/simulation/do_nothing_plugin/package.xml @@ -2,7 +2,7 @@ do_nothing_plugin - 4.2.3 + 4.2.4 Behavior plugin for do nothing Masaya Kataoka Apache 2.0 diff --git a/simulation/simple_sensor_simulator/CHANGELOG.rst b/simulation/simple_sensor_simulator/CHANGELOG.rst index 0e7965be548..78bc0b1f978 100644 --- a/simulation/simple_sensor_simulator/CHANGELOG.rst +++ b/simulation/simple_sensor_simulator/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package simple_sensor_simulator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.4 (2024-09-12) +------------------ + 4.2.3 (2024-09-11) ------------------ diff --git a/simulation/simple_sensor_simulator/package.xml b/simulation/simple_sensor_simulator/package.xml index fd967ae57fe..be150b832a6 100644 --- a/simulation/simple_sensor_simulator/package.xml +++ b/simulation/simple_sensor_simulator/package.xml @@ -1,7 +1,7 @@ simple_sensor_simulator - 4.2.3 + 4.2.4 simple_sensor_simulator package masaya kataoka diff --git a/simulation/simulation_interface/CHANGELOG.rst b/simulation/simulation_interface/CHANGELOG.rst index cb6ffbab7d7..8cfe366c7e7 100644 --- a/simulation/simulation_interface/CHANGELOG.rst +++ b/simulation/simulation_interface/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package simulation_interface * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.4 (2024-09-12) +------------------ + 4.2.3 (2024-09-11) ------------------ diff --git a/simulation/simulation_interface/package.xml b/simulation/simulation_interface/package.xml index 0ee98a1234d..7f366a46793 100644 --- a/simulation/simulation_interface/package.xml +++ b/simulation/simulation_interface/package.xml @@ -2,7 +2,7 @@ simulation_interface - 4.2.3 + 4.2.4 packages to define interface between simulator and scenario interpreter Masaya Kataoka Apache License 2.0 diff --git a/simulation/traffic_simulator/CHANGELOG.rst b/simulation/traffic_simulator/CHANGELOG.rst index e8f9123c5bb..6b3fa410146 100644 --- a/simulation/traffic_simulator/CHANGELOG.rst +++ b/simulation/traffic_simulator/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package traffic_simulator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.4 (2024-09-12) +------------------ + 4.2.3 (2024-09-11) ------------------ diff --git a/simulation/traffic_simulator/package.xml b/simulation/traffic_simulator/package.xml index 4ff8fbbf7ee..e92380cef6a 100644 --- a/simulation/traffic_simulator/package.xml +++ b/simulation/traffic_simulator/package.xml @@ -1,7 +1,7 @@ traffic_simulator - 4.2.3 + 4.2.4 control traffic flow masaya kataoka diff --git a/simulation/traffic_simulator_msgs/CHANGELOG.rst b/simulation/traffic_simulator_msgs/CHANGELOG.rst index 0f8103e7f51..2fbd24e12bb 100644 --- a/simulation/traffic_simulator_msgs/CHANGELOG.rst +++ b/simulation/traffic_simulator_msgs/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package openscenario_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.4 (2024-09-12) +------------------ + 4.2.3 (2024-09-11) ------------------ diff --git a/simulation/traffic_simulator_msgs/package.xml b/simulation/traffic_simulator_msgs/package.xml index 2ad55e91c58..c6c4bc942bd 100644 --- a/simulation/traffic_simulator_msgs/package.xml +++ b/simulation/traffic_simulator_msgs/package.xml @@ -2,7 +2,7 @@ traffic_simulator_msgs - 4.2.3 + 4.2.4 ROS messages for openscenario Masaya Kataoka Apache License 2.0 diff --git a/test_runner/random_test_runner/CHANGELOG.rst b/test_runner/random_test_runner/CHANGELOG.rst index dc87c1eb409..bd3b00143da 100644 --- a/test_runner/random_test_runner/CHANGELOG.rst +++ b/test_runner/random_test_runner/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package random_test_runner * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.4 (2024-09-12) +------------------ + 4.2.3 (2024-09-11) ------------------ diff --git a/test_runner/random_test_runner/package.xml b/test_runner/random_test_runner/package.xml index b6ad5fea61d..4f7a6d0ca7c 100644 --- a/test_runner/random_test_runner/package.xml +++ b/test_runner/random_test_runner/package.xml @@ -2,7 +2,7 @@ random_test_runner - 4.2.3 + 4.2.4 Random behavior test runner piotr-zyskowski-rai Apache License 2.0 diff --git a/test_runner/scenario_test_runner/CHANGELOG.rst b/test_runner/scenario_test_runner/CHANGELOG.rst index f016ec22577..5722598381e 100644 --- a/test_runner/scenario_test_runner/CHANGELOG.rst +++ b/test_runner/scenario_test_runner/CHANGELOG.rst @@ -35,6 +35,9 @@ Changelog for package scenario_test_runner * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.4 (2024-09-12) +------------------ + 4.2.3 (2024-09-11) ------------------ diff --git a/test_runner/scenario_test_runner/package.xml b/test_runner/scenario_test_runner/package.xml index 76d630c1eaf..1f02d6ad762 100644 --- a/test_runner/scenario_test_runner/package.xml +++ b/test_runner/scenario_test_runner/package.xml @@ -2,7 +2,7 @@ scenario_test_runner - 4.2.3 + 4.2.4 scenario test runner package Tatsuya Yamasaki Apache License 2.0 From deb3e05248a6b778eaf9d0eb74de61853f18f3c6 Mon Sep 17 00:00:00 2001 From: Release Bot Date: Thu, 12 Sep 2024 08:59:41 +0000 Subject: [PATCH 258/304] Bump version of scenario_simulator_v2 from version 4.2.4 to version 4.2.5 --- common/math/arithmetic/CHANGELOG.rst | 3 +++ common/math/arithmetic/package.xml | 2 +- common/math/geometry/CHANGELOG.rst | 3 +++ common/math/geometry/package.xml | 2 +- common/scenario_simulator_exception/CHANGELOG.rst | 3 +++ common/scenario_simulator_exception/package.xml | 2 +- common/simple_junit/CHANGELOG.rst | 3 +++ common/simple_junit/package.xml | 2 +- common/status_monitor/CHANGELOG.rst | 3 +++ common/status_monitor/package.xml | 2 +- external/concealer/CHANGELOG.rst | 3 +++ external/concealer/package.xml | 2 +- external/embree_vendor/CHANGELOG.rst | 3 +++ external/embree_vendor/package.xml | 2 +- map/kashiwanoha_map/CHANGELOG.rst | 3 +++ map/kashiwanoha_map/package.xml | 2 +- map/simple_cross_map/CHANGELOG.rst | 3 +++ map/simple_cross_map/package.xml | 2 +- mock/cpp_mock_scenarios/CHANGELOG.rst | 7 +++++++ mock/cpp_mock_scenarios/package.xml | 2 +- .../openscenario_experimental_catalog/CHANGELOG.rst | 3 +++ openscenario/openscenario_experimental_catalog/package.xml | 2 +- openscenario/openscenario_interpreter/CHANGELOG.rst | 3 +++ openscenario/openscenario_interpreter/package.xml | 2 +- .../openscenario_interpreter_example/CHANGELOG.rst | 3 +++ openscenario/openscenario_interpreter_example/package.xml | 2 +- openscenario/openscenario_interpreter_msgs/CHANGELOG.rst | 3 +++ openscenario/openscenario_interpreter_msgs/package.xml | 2 +- openscenario/openscenario_preprocessor/CHANGELOG.rst | 3 +++ openscenario/openscenario_preprocessor/package.xml | 2 +- openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst | 3 +++ openscenario/openscenario_preprocessor_msgs/package.xml | 2 +- openscenario/openscenario_utility/CHANGELOG.rst | 3 +++ openscenario/openscenario_utility/package.xml | 2 +- openscenario/openscenario_validator/CHANGELOG.rst | 3 +++ openscenario/openscenario_validator/package.xml | 2 +- rviz_plugins/openscenario_visualization/CHANGELOG.rst | 3 +++ rviz_plugins/openscenario_visualization/package.xml | 2 +- .../real_time_factor_control_rviz_plugin/CHANGELOG.rst | 3 +++ .../real_time_factor_control_rviz_plugin/package.xml | 2 +- scenario_simulator_v2/CHANGELOG.rst | 3 +++ scenario_simulator_v2/package.xml | 2 +- simulation/behavior_tree_plugin/CHANGELOG.rst | 3 +++ simulation/behavior_tree_plugin/package.xml | 2 +- simulation/do_nothing_plugin/CHANGELOG.rst | 3 +++ simulation/do_nothing_plugin/package.xml | 2 +- simulation/simple_sensor_simulator/CHANGELOG.rst | 3 +++ simulation/simple_sensor_simulator/package.xml | 2 +- simulation/simulation_interface/CHANGELOG.rst | 3 +++ simulation/simulation_interface/package.xml | 2 +- simulation/traffic_simulator/CHANGELOG.rst | 3 +++ simulation/traffic_simulator/package.xml | 2 +- simulation/traffic_simulator_msgs/CHANGELOG.rst | 3 +++ simulation/traffic_simulator_msgs/package.xml | 2 +- test_runner/random_test_runner/CHANGELOG.rst | 3 +++ test_runner/random_test_runner/package.xml | 2 +- test_runner/scenario_test_runner/CHANGELOG.rst | 3 +++ test_runner/scenario_test_runner/package.xml | 2 +- 58 files changed, 120 insertions(+), 29 deletions(-) diff --git a/common/math/arithmetic/CHANGELOG.rst b/common/math/arithmetic/CHANGELOG.rst index 0812c8d344c..d7a29893e86 100644 --- a/common/math/arithmetic/CHANGELOG.rst +++ b/common/math/arithmetic/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package arithmetic * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.5 (2024-09-12) +------------------ + 4.2.4 (2024-09-12) ------------------ diff --git a/common/math/arithmetic/package.xml b/common/math/arithmetic/package.xml index dedd48a5205..88b3fe97051 100644 --- a/common/math/arithmetic/package.xml +++ b/common/math/arithmetic/package.xml @@ -2,7 +2,7 @@ arithmetic - 4.2.4 + 4.2.5 arithmetic library for scenario_simulator_v2 Tatsuya Yamasaki Apache License 2.0 diff --git a/common/math/geometry/CHANGELOG.rst b/common/math/geometry/CHANGELOG.rst index 9ed062f33cf..a217b54bdfd 100644 --- a/common/math/geometry/CHANGELOG.rst +++ b/common/math/geometry/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package geometry * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.5 (2024-09-12) +------------------ + 4.2.4 (2024-09-12) ------------------ diff --git a/common/math/geometry/package.xml b/common/math/geometry/package.xml index 9fc27e2f994..8d7f2ba65ec 100644 --- a/common/math/geometry/package.xml +++ b/common/math/geometry/package.xml @@ -2,7 +2,7 @@ geometry - 4.2.4 + 4.2.5 geometry math library for scenario_simulator_v2 application Masaya Kataoka Apache License 2.0 diff --git a/common/scenario_simulator_exception/CHANGELOG.rst b/common/scenario_simulator_exception/CHANGELOG.rst index 60ea49ae64a..17fbfa2c75f 100644 --- a/common/scenario_simulator_exception/CHANGELOG.rst +++ b/common/scenario_simulator_exception/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package scenario_simulator_exception * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.5 (2024-09-12) +------------------ + 4.2.4 (2024-09-12) ------------------ diff --git a/common/scenario_simulator_exception/package.xml b/common/scenario_simulator_exception/package.xml index 4e446fbd3de..7fe20b1548b 100644 --- a/common/scenario_simulator_exception/package.xml +++ b/common/scenario_simulator_exception/package.xml @@ -2,7 +2,7 @@ scenario_simulator_exception - 4.2.4 + 4.2.5 Exception types for scenario simulator Tatsuya Yamasaki Apache License 2.0 diff --git a/common/simple_junit/CHANGELOG.rst b/common/simple_junit/CHANGELOG.rst index 3852989aa47..f85b4bd0661 100644 --- a/common/simple_junit/CHANGELOG.rst +++ b/common/simple_junit/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package junit_exporter * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.5 (2024-09-12) +------------------ + 4.2.4 (2024-09-12) ------------------ diff --git a/common/simple_junit/package.xml b/common/simple_junit/package.xml index 8d130590fc9..e7e2f31c693 100644 --- a/common/simple_junit/package.xml +++ b/common/simple_junit/package.xml @@ -2,7 +2,7 @@ simple_junit - 4.2.4 + 4.2.5 Lightweight JUnit library for ROS 2 Masaya Kataoka Tatsuya Yamasaki diff --git a/common/status_monitor/CHANGELOG.rst b/common/status_monitor/CHANGELOG.rst index 5f889127dd5..c400af7386a 100644 --- a/common/status_monitor/CHANGELOG.rst +++ b/common/status_monitor/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package status_monitor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.5 (2024-09-12) +------------------ + 4.2.4 (2024-09-12) ------------------ diff --git a/common/status_monitor/package.xml b/common/status_monitor/package.xml index 67f9c9ca118..d3edea8c479 100644 --- a/common/status_monitor/package.xml +++ b/common/status_monitor/package.xml @@ -2,7 +2,7 @@ status_monitor - 4.2.4 + 4.2.5 none Tatsuya Yamasaki Apache License 2.0 diff --git a/external/concealer/CHANGELOG.rst b/external/concealer/CHANGELOG.rst index 359c2ddacd8..62bdddbb613 100644 --- a/external/concealer/CHANGELOG.rst +++ b/external/concealer/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package concealer * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.5 (2024-09-12) +------------------ + 4.2.4 (2024-09-12) ------------------ diff --git a/external/concealer/package.xml b/external/concealer/package.xml index 1c7dddc5d7f..013840213cd 100644 --- a/external/concealer/package.xml +++ b/external/concealer/package.xml @@ -2,7 +2,7 @@ concealer - 4.2.4 + 4.2.5 Provides a class 'Autoware' to conceal miscellaneous things to simplify Autoware management of the simulator. Tatsuya Yamasaki Apache License 2.0 diff --git a/external/embree_vendor/CHANGELOG.rst b/external/embree_vendor/CHANGELOG.rst index 68cfbf7a078..a4b10b817d9 100644 --- a/external/embree_vendor/CHANGELOG.rst +++ b/external/embree_vendor/CHANGELOG.rst @@ -24,6 +24,9 @@ Changelog for package embree_vendor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.5 (2024-09-12) +------------------ + 4.2.4 (2024-09-12) ------------------ diff --git a/external/embree_vendor/package.xml b/external/embree_vendor/package.xml index 7d4e8ea8e4b..638bf8ab53d 100644 --- a/external/embree_vendor/package.xml +++ b/external/embree_vendor/package.xml @@ -2,7 +2,7 @@ embree_vendor - 4.2.4 + 4.2.5 vendor packages for intel raytracing kernel library masaya Apache 2.0 diff --git a/map/kashiwanoha_map/CHANGELOG.rst b/map/kashiwanoha_map/CHANGELOG.rst index 66d819a7149..5f3b0760b8a 100644 --- a/map/kashiwanoha_map/CHANGELOG.rst +++ b/map/kashiwanoha_map/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package kashiwanoha_map * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.5 (2024-09-12) +------------------ + 4.2.4 (2024-09-12) ------------------ diff --git a/map/kashiwanoha_map/package.xml b/map/kashiwanoha_map/package.xml index b282ae09300..7cdb2fd892b 100644 --- a/map/kashiwanoha_map/package.xml +++ b/map/kashiwanoha_map/package.xml @@ -2,7 +2,7 @@ kashiwanoha_map - 4.2.4 + 4.2.5 map package for kashiwanoha Masaya Kataoka Apache License 2.0 diff --git a/map/simple_cross_map/CHANGELOG.rst b/map/simple_cross_map/CHANGELOG.rst index e50a2bb6d24..b76707ceff8 100644 --- a/map/simple_cross_map/CHANGELOG.rst +++ b/map/simple_cross_map/CHANGELOG.rst @@ -9,6 +9,9 @@ Changelog for package simple_cross_map * Merge branch 'master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.5 (2024-09-12) +------------------ + 4.2.4 (2024-09-12) ------------------ diff --git a/map/simple_cross_map/package.xml b/map/simple_cross_map/package.xml index e9718313746..0fdb585a731 100644 --- a/map/simple_cross_map/package.xml +++ b/map/simple_cross_map/package.xml @@ -2,7 +2,7 @@ simple_cross_map - 4.2.4 + 4.2.5 map package for simple cross Masaya Kataoka Apache License 2.0 diff --git a/mock/cpp_mock_scenarios/CHANGELOG.rst b/mock/cpp_mock_scenarios/CHANGELOG.rst index 0af95e62029..9c8bce49f06 100644 --- a/mock/cpp_mock_scenarios/CHANGELOG.rst +++ b/mock/cpp_mock_scenarios/CHANGELOG.rst @@ -21,6 +21,13 @@ Changelog for package cpp_mock_scenarios * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.5 (2024-09-12) +------------------ +* Merge pull request `#1373 `_ from tier4/fix/colcon_build_error_furthermore + fix: install add_cpp_mock_scenario_test.cmake first, or colcon build won't pass +* fix: install add_cpp_mock_scenario_test.cmake first, or build won't pass +* Contributors: Masaya Kataoka, XiaoyuWang0601 + 4.2.4 (2024-09-12) ------------------ diff --git a/mock/cpp_mock_scenarios/package.xml b/mock/cpp_mock_scenarios/package.xml index c417eb9e07d..6e9270a030f 100644 --- a/mock/cpp_mock_scenarios/package.xml +++ b/mock/cpp_mock_scenarios/package.xml @@ -2,7 +2,7 @@ cpp_mock_scenarios - 4.2.4 + 4.2.5 C++ mock scenarios masaya Apache License 2.0 diff --git a/openscenario/openscenario_experimental_catalog/CHANGELOG.rst b/openscenario/openscenario_experimental_catalog/CHANGELOG.rst index af0ef196625..bea5f9f1a52 100644 --- a/openscenario/openscenario_experimental_catalog/CHANGELOG.rst +++ b/openscenario/openscenario_experimental_catalog/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package openscenario_experimental_catalog * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.5 (2024-09-12) +------------------ + 4.2.4 (2024-09-12) ------------------ diff --git a/openscenario/openscenario_experimental_catalog/package.xml b/openscenario/openscenario_experimental_catalog/package.xml index 5069270d319..b20a1a446a9 100644 --- a/openscenario/openscenario_experimental_catalog/package.xml +++ b/openscenario/openscenario_experimental_catalog/package.xml @@ -2,7 +2,7 @@ openscenario_experimental_catalog - 4.2.4 + 4.2.5 TIER IV experimental catalogs for OpenSCENARIO Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter/CHANGELOG.rst b/openscenario/openscenario_interpreter/CHANGELOG.rst index 4853d958587..96465f9138b 100644 --- a/openscenario/openscenario_interpreter/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter/CHANGELOG.rst @@ -32,6 +32,9 @@ Changelog for package openscenario_interpreter * add publish_empty_context parameter * Contributors: Masaya Kataoka +4.2.5 (2024-09-12) +------------------ + 4.2.4 (2024-09-12) ------------------ diff --git a/openscenario/openscenario_interpreter/package.xml b/openscenario/openscenario_interpreter/package.xml index 9c34db6aa73..6afec9f0261 100644 --- a/openscenario/openscenario_interpreter/package.xml +++ b/openscenario/openscenario_interpreter/package.xml @@ -2,7 +2,7 @@ openscenario_interpreter - 4.2.4 + 4.2.5 OpenSCENARIO 1.2.0 interpreter package for Autoware Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter_example/CHANGELOG.rst b/openscenario/openscenario_interpreter_example/CHANGELOG.rst index 0d8a8c28fdc..cdce7fb5205 100644 --- a/openscenario/openscenario_interpreter_example/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter_example/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package openscenario_interpreter_example * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.5 (2024-09-12) +------------------ + 4.2.4 (2024-09-12) ------------------ diff --git a/openscenario/openscenario_interpreter_example/package.xml b/openscenario/openscenario_interpreter_example/package.xml index 77bd1d6f96d..a198937c5ed 100644 --- a/openscenario/openscenario_interpreter_example/package.xml +++ b/openscenario/openscenario_interpreter_example/package.xml @@ -3,7 +3,7 @@ openscenario_interpreter_example - 4.2.4 + 4.2.5 Examples for some TIER IV OpenSCENARIO Interpreter's features Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst b/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst index 618ada540b1..20d14b6686b 100644 --- a/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package openscenario_interpreter_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.5 (2024-09-12) +------------------ + 4.2.4 (2024-09-12) ------------------ diff --git a/openscenario/openscenario_interpreter_msgs/package.xml b/openscenario/openscenario_interpreter_msgs/package.xml index 551aec033b8..95ecc9359b4 100644 --- a/openscenario/openscenario_interpreter_msgs/package.xml +++ b/openscenario/openscenario_interpreter_msgs/package.xml @@ -2,7 +2,7 @@ openscenario_interpreter_msgs - 4.2.4 + 4.2.5 ROS message types for package openscenario_interpreter Yamasaki Tatsuya Apache License 2.0 diff --git a/openscenario/openscenario_preprocessor/CHANGELOG.rst b/openscenario/openscenario_preprocessor/CHANGELOG.rst index ecab3cb174f..15f31957d52 100644 --- a/openscenario/openscenario_preprocessor/CHANGELOG.rst +++ b/openscenario/openscenario_preprocessor/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package openscenario_preprocessor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.5 (2024-09-12) +------------------ + 4.2.4 (2024-09-12) ------------------ diff --git a/openscenario/openscenario_preprocessor/package.xml b/openscenario/openscenario_preprocessor/package.xml index a8cb4fe6958..2746f2c95c2 100644 --- a/openscenario/openscenario_preprocessor/package.xml +++ b/openscenario/openscenario_preprocessor/package.xml @@ -3,7 +3,7 @@ openscenario_preprocessor - 4.2.4 + 4.2.5 Example package for TIER IV OpenSCENARIO Interpreter Kotaro Yoshimoto Apache License 2.0 diff --git a/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst b/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst index f5115de4002..f8203512908 100644 --- a/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst +++ b/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package openscenario_preprocessor_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.5 (2024-09-12) +------------------ + 4.2.4 (2024-09-12) ------------------ diff --git a/openscenario/openscenario_preprocessor_msgs/package.xml b/openscenario/openscenario_preprocessor_msgs/package.xml index 6668ee204c4..f38d83f0b2d 100644 --- a/openscenario/openscenario_preprocessor_msgs/package.xml +++ b/openscenario/openscenario_preprocessor_msgs/package.xml @@ -2,7 +2,7 @@ openscenario_preprocessor_msgs - 4.2.4 + 4.2.5 ROS message types for package openscenario_preprocessor Kotaro Yoshimoto Apache License 2.0 diff --git a/openscenario/openscenario_utility/CHANGELOG.rst b/openscenario/openscenario_utility/CHANGELOG.rst index 22e2f71af03..84083f58a50 100644 --- a/openscenario/openscenario_utility/CHANGELOG.rst +++ b/openscenario/openscenario_utility/CHANGELOG.rst @@ -24,6 +24,9 @@ Changelog for package openscenario_utility * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.5 (2024-09-12) +------------------ + 4.2.4 (2024-09-12) ------------------ diff --git a/openscenario/openscenario_utility/package.xml b/openscenario/openscenario_utility/package.xml index 89e4941879e..5b5c8914dea 100644 --- a/openscenario/openscenario_utility/package.xml +++ b/openscenario/openscenario_utility/package.xml @@ -2,7 +2,7 @@ openscenario_utility - 4.2.4 + 4.2.5 Utility tools for ASAM OpenSCENARIO 1.2.0 Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_validator/CHANGELOG.rst b/openscenario/openscenario_validator/CHANGELOG.rst index 9a749463a89..926a119cfa1 100644 --- a/openscenario/openscenario_validator/CHANGELOG.rst +++ b/openscenario/openscenario_validator/CHANGELOG.rst @@ -10,6 +10,9 @@ Changelog for package openscenario_validator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.5 (2024-09-12) +------------------ + 4.2.4 (2024-09-12) ------------------ diff --git a/openscenario/openscenario_validator/package.xml b/openscenario/openscenario_validator/package.xml index 6ef0a343a72..37350a6a76c 100644 --- a/openscenario/openscenario_validator/package.xml +++ b/openscenario/openscenario_validator/package.xml @@ -2,7 +2,7 @@ openscenario_validator - 4.2.4 + 4.2.5 Validator for OpenSCENARIO 1.3 Kotaro Yoshimoto Apache License 2.0 diff --git a/rviz_plugins/openscenario_visualization/CHANGELOG.rst b/rviz_plugins/openscenario_visualization/CHANGELOG.rst index 9a0d1705d1e..209a8f4be8f 100644 --- a/rviz_plugins/openscenario_visualization/CHANGELOG.rst +++ b/rviz_plugins/openscenario_visualization/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package openscenario_visualization * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.5 (2024-09-12) +------------------ + 4.2.4 (2024-09-12) ------------------ diff --git a/rviz_plugins/openscenario_visualization/package.xml b/rviz_plugins/openscenario_visualization/package.xml index 589d454f0a2..458b89ee890 100644 --- a/rviz_plugins/openscenario_visualization/package.xml +++ b/rviz_plugins/openscenario_visualization/package.xml @@ -2,7 +2,7 @@ openscenario_visualization - 4.2.4 + 4.2.5 Visualization tools for simulation results Masaya Kataoka Kyoichi Sugahara diff --git a/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst b/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst index 4167ed89c31..5128104bb4c 100644 --- a/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst +++ b/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package real_time_factor_control_rviz_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.5 (2024-09-12) +------------------ + 4.2.4 (2024-09-12) ------------------ diff --git a/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml b/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml index 5241b815471..d2b1d90a7c2 100644 --- a/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml +++ b/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml @@ -2,7 +2,7 @@ real_time_factor_control_rviz_plugin - 4.2.4 + 4.2.5 Slider controlling real time factor value. Paweł Lech Apache License 2.0 diff --git a/scenario_simulator_v2/CHANGELOG.rst b/scenario_simulator_v2/CHANGELOG.rst index 6266f4590c9..6e6d7364c7d 100644 --- a/scenario_simulator_v2/CHANGELOG.rst +++ b/scenario_simulator_v2/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package scenario_simulator_v2 * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.5 (2024-09-12) +------------------ + 4.2.4 (2024-09-12) ------------------ diff --git a/scenario_simulator_v2/package.xml b/scenario_simulator_v2/package.xml index 839855315d9..782eda0da2f 100644 --- a/scenario_simulator_v2/package.xml +++ b/scenario_simulator_v2/package.xml @@ -2,7 +2,7 @@ scenario_simulator_v2 - 4.2.4 + 4.2.5 scenario testing framework for Autoware Masaya Kataoka Apache License 2.0 diff --git a/simulation/behavior_tree_plugin/CHANGELOG.rst b/simulation/behavior_tree_plugin/CHANGELOG.rst index 5ae4eb6d887..0643dfcfdab 100644 --- a/simulation/behavior_tree_plugin/CHANGELOG.rst +++ b/simulation/behavior_tree_plugin/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package behavior_tree_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.5 (2024-09-12) +------------------ + 4.2.4 (2024-09-12) ------------------ diff --git a/simulation/behavior_tree_plugin/package.xml b/simulation/behavior_tree_plugin/package.xml index 6517e5c8d69..fb87f0aed9a 100644 --- a/simulation/behavior_tree_plugin/package.xml +++ b/simulation/behavior_tree_plugin/package.xml @@ -2,7 +2,7 @@ behavior_tree_plugin - 4.2.4 + 4.2.5 Behavior tree plugin for traffic_simulator masaya Apache 2.0 diff --git a/simulation/do_nothing_plugin/CHANGELOG.rst b/simulation/do_nothing_plugin/CHANGELOG.rst index 96457e13608..8a3255c7f63 100644 --- a/simulation/do_nothing_plugin/CHANGELOG.rst +++ b/simulation/do_nothing_plugin/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package do_nothing_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.5 (2024-09-12) +------------------ + 4.2.4 (2024-09-12) ------------------ diff --git a/simulation/do_nothing_plugin/package.xml b/simulation/do_nothing_plugin/package.xml index e1af53d0e9f..2a62bd160fa 100644 --- a/simulation/do_nothing_plugin/package.xml +++ b/simulation/do_nothing_plugin/package.xml @@ -2,7 +2,7 @@ do_nothing_plugin - 4.2.4 + 4.2.5 Behavior plugin for do nothing Masaya Kataoka Apache 2.0 diff --git a/simulation/simple_sensor_simulator/CHANGELOG.rst b/simulation/simple_sensor_simulator/CHANGELOG.rst index 78bc0b1f978..e36da68a953 100644 --- a/simulation/simple_sensor_simulator/CHANGELOG.rst +++ b/simulation/simple_sensor_simulator/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package simple_sensor_simulator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.5 (2024-09-12) +------------------ + 4.2.4 (2024-09-12) ------------------ diff --git a/simulation/simple_sensor_simulator/package.xml b/simulation/simple_sensor_simulator/package.xml index be150b832a6..2577d3eeefc 100644 --- a/simulation/simple_sensor_simulator/package.xml +++ b/simulation/simple_sensor_simulator/package.xml @@ -1,7 +1,7 @@ simple_sensor_simulator - 4.2.4 + 4.2.5 simple_sensor_simulator package masaya kataoka diff --git a/simulation/simulation_interface/CHANGELOG.rst b/simulation/simulation_interface/CHANGELOG.rst index 8cfe366c7e7..c6cad508735 100644 --- a/simulation/simulation_interface/CHANGELOG.rst +++ b/simulation/simulation_interface/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package simulation_interface * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.5 (2024-09-12) +------------------ + 4.2.4 (2024-09-12) ------------------ diff --git a/simulation/simulation_interface/package.xml b/simulation/simulation_interface/package.xml index 7f366a46793..ca5afc050c4 100644 --- a/simulation/simulation_interface/package.xml +++ b/simulation/simulation_interface/package.xml @@ -2,7 +2,7 @@ simulation_interface - 4.2.4 + 4.2.5 packages to define interface between simulator and scenario interpreter Masaya Kataoka Apache License 2.0 diff --git a/simulation/traffic_simulator/CHANGELOG.rst b/simulation/traffic_simulator/CHANGELOG.rst index 6b3fa410146..d3cf5191c14 100644 --- a/simulation/traffic_simulator/CHANGELOG.rst +++ b/simulation/traffic_simulator/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package traffic_simulator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.5 (2024-09-12) +------------------ + 4.2.4 (2024-09-12) ------------------ diff --git a/simulation/traffic_simulator/package.xml b/simulation/traffic_simulator/package.xml index e92380cef6a..86dd23e340a 100644 --- a/simulation/traffic_simulator/package.xml +++ b/simulation/traffic_simulator/package.xml @@ -1,7 +1,7 @@ traffic_simulator - 4.2.4 + 4.2.5 control traffic flow masaya kataoka diff --git a/simulation/traffic_simulator_msgs/CHANGELOG.rst b/simulation/traffic_simulator_msgs/CHANGELOG.rst index 2fbd24e12bb..bf58991cf79 100644 --- a/simulation/traffic_simulator_msgs/CHANGELOG.rst +++ b/simulation/traffic_simulator_msgs/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package openscenario_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.5 (2024-09-12) +------------------ + 4.2.4 (2024-09-12) ------------------ diff --git a/simulation/traffic_simulator_msgs/package.xml b/simulation/traffic_simulator_msgs/package.xml index c6c4bc942bd..38503ce6845 100644 --- a/simulation/traffic_simulator_msgs/package.xml +++ b/simulation/traffic_simulator_msgs/package.xml @@ -2,7 +2,7 @@ traffic_simulator_msgs - 4.2.4 + 4.2.5 ROS messages for openscenario Masaya Kataoka Apache License 2.0 diff --git a/test_runner/random_test_runner/CHANGELOG.rst b/test_runner/random_test_runner/CHANGELOG.rst index bd3b00143da..1803a4a44cf 100644 --- a/test_runner/random_test_runner/CHANGELOG.rst +++ b/test_runner/random_test_runner/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package random_test_runner * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.5 (2024-09-12) +------------------ + 4.2.4 (2024-09-12) ------------------ diff --git a/test_runner/random_test_runner/package.xml b/test_runner/random_test_runner/package.xml index 4f7a6d0ca7c..a9ebfec6973 100644 --- a/test_runner/random_test_runner/package.xml +++ b/test_runner/random_test_runner/package.xml @@ -2,7 +2,7 @@ random_test_runner - 4.2.4 + 4.2.5 Random behavior test runner piotr-zyskowski-rai Apache License 2.0 diff --git a/test_runner/scenario_test_runner/CHANGELOG.rst b/test_runner/scenario_test_runner/CHANGELOG.rst index 5722598381e..95d775687b4 100644 --- a/test_runner/scenario_test_runner/CHANGELOG.rst +++ b/test_runner/scenario_test_runner/CHANGELOG.rst @@ -35,6 +35,9 @@ Changelog for package scenario_test_runner * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.5 (2024-09-12) +------------------ + 4.2.4 (2024-09-12) ------------------ diff --git a/test_runner/scenario_test_runner/package.xml b/test_runner/scenario_test_runner/package.xml index 1f02d6ad762..b32d9b41730 100644 --- a/test_runner/scenario_test_runner/package.xml +++ b/test_runner/scenario_test_runner/package.xml @@ -2,7 +2,7 @@ scenario_test_runner - 4.2.4 + 4.2.5 scenario test runner package Tatsuya Yamasaki Apache License 2.0 From ff030b15359bbb7c99db59ef092173fcf9f88133 Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Thu, 12 Sep 2024 18:21:38 +0900 Subject: [PATCH 259/304] Update the scenario to drive laps around the closed route Signed-off-by: yamacir-kit --- .../storyboard_element_state_condition.cpp | 2 +- ...tion.AcquirePositionAction-continuous.yaml | 170 ++++++++++++++---- 2 files changed, 137 insertions(+), 35 deletions(-) diff --git a/openscenario/openscenario_interpreter/src/syntax/storyboard_element_state_condition.cpp b/openscenario/openscenario_interpreter/src/syntax/storyboard_element_state_condition.cpp index bcdf30c71d8..5d8758f5ca1 100644 --- a/openscenario/openscenario_interpreter/src/syntax/storyboard_element_state_condition.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/storyboard_element_state_condition.cpp @@ -38,7 +38,7 @@ StoryboardElementStateCondition::StoryboardElementStateCondition( Note that there is no guarantee that the StoryboardElement will remain in the same state as when the notification is made until StoryboardElementStateCondition::evaluate is executed after the callback - is called. The In other words, the StoryboardElement may immediately + is called. In other words, the StoryboardElement may immediately transition to the next state after calling the callback function. */ diff --git a/test_runner/scenario_test_runner/scenario/RoutingAction.AcquirePositionAction-continuous.yaml b/test_runner/scenario_test_runner/scenario/RoutingAction.AcquirePositionAction-continuous.yaml index 76d8f4388b3..db959904eb2 100644 --- a/test_runner/scenario_test_runner/scenario/RoutingAction.AcquirePositionAction-continuous.yaml +++ b/test_runner/scenario_test_runner/scenario/RoutingAction.AcquirePositionAction-continuous.yaml @@ -6,7 +6,10 @@ OpenSCENARIO: revMajor: 1 revMinor: 0 ParameterDeclarations: - ParameterDeclaration: [] + ParameterDeclaration: + - name: laps + parameterType: unsignedInt + value: 3 CatalogLocations: VehicleCatalog: Directory: @@ -32,7 +35,7 @@ OpenSCENARIO: - entityRef: ego PrivateAction: - TeleportAction: - Position: + Position: &INITIAL_POSITION LanePosition: roadId: '' laneId: '34513' @@ -45,17 +48,17 @@ OpenSCENARIO: r: 0 - RoutingAction: AcquirePositionAction: - Position: &DESTINATION_1 + Position: &POSITION_A LanePosition: roadId: '' - laneId: '34510' + laneId: '34681' s: 1 offset: 0 Orientation: *DEFAULT_ORIENTATION Story: - name: '' Act: - - name: '' + - name: loop ManeuverGroup: - maximumExecutionCount: 1 name: '' @@ -65,24 +68,106 @@ OpenSCENARIO: - entityRef: ego Maneuver: - name: '' + ParameterDeclarations: + ParameterDeclaration: + - name: current_destination + parameterType: string + value: position_a Event: - - name: '' + - maximumExecutionCount: $laps + name: '' + priority: parallel + Action: + - name: '' + PrivateAction: + - RoutingAction: + AcquirePositionAction: + Position: *POSITION_A + - name: '' + GlobalAction: + ParameterAction: + parameterRef: current_destination + SetAction: + value: position_a + StartTrigger: + ConditionGroup: + - Condition: + - name: '' + delay: 0 + conditionEdge: none + ByEntityCondition: + TriggeringEntities: + triggeringEntitiesRule: any + EntityRef: + - entityRef: ego + EntityCondition: + ReachPositionCondition: + Position: &POSITION_B + LanePosition: + roadId: '' + laneId: '34408' + s: 1 + offset: 0 + Orientation: *DEFAULT_ORIENTATION + tolerance: 1 + - name: '' + delay: 0 + conditionEdge: none + ByEntityCondition: + TriggeringEntities: + triggeringEntitiesRule: any + EntityRef: + - entityRef: ego + EntityCondition: + SpeedCondition: + rule: equalTo + value: 0 + - name: '' + delay: 0 + conditionEdge: none + ByValueCondition: + UserDefinedValueCondition: + name: ego.currentState + rule: equalTo + value: WAITING_FOR_ROUTE + - name: '' + delay: 0 + conditionEdge: none + ByValueCondition: + ParameterCondition: + parameterRef: current_destination + rule: notEqualTo + value: position_a + - maximumExecutionCount: $laps + name: '' priority: parallel Action: - name: '' PrivateAction: - RoutingAction: AcquirePositionAction: - Position: &DESTINATION_2 - LanePosition: - roadId: '' - laneId: '34507' - s: 50 - offset: 0 - Orientation: *DEFAULT_ORIENTATION + Position: *POSITION_B + - name: '' + GlobalAction: + ParameterAction: + parameterRef: current_destination + SetAction: + value: position_b StartTrigger: ConditionGroup: - Condition: + - name: '' + delay: 0 + conditionEdge: none + ByEntityCondition: + TriggeringEntities: + triggeringEntitiesRule: any + EntityRef: + - entityRef: ego + EntityCondition: + ReachPositionCondition: + Position: *POSITION_A + tolerance: 1 - name: '' delay: 0 conditionEdge: none @@ -103,21 +188,24 @@ OpenSCENARIO: name: ego.currentState rule: equalTo value: WAITING_FOR_ROUTE + - name: '' + delay: 0 + conditionEdge: none + ByValueCondition: + ParameterCondition: + parameterRef: current_destination + rule: notEqualTo + value: position_b StartTrigger: ConditionGroup: - Condition: - name: '' delay: 0 conditionEdge: none - ByEntityCondition: - TriggeringEntities: - triggeringEntitiesRule: any - EntityRef: - - entityRef: ego - EntityCondition: - ReachPositionCondition: - Position: *DESTINATION_1 - tolerance: 1 + ByValueCondition: + SimulationTimeCondition: + value: 0 + rule: greaterThan - name: _EndCondition ManeuverGroup: - maximumExecutionCount: 1 @@ -134,6 +222,14 @@ OpenSCENARIO: StartTrigger: ConditionGroup: - Condition: + - name: '' + delay: 0 + conditionEdge: none + ByValueCondition: + StoryboardElementStateCondition: + storyboardElementRef: loop + storyboardElementType: act + state: completeState - name: '' delay: 0 conditionEdge: none @@ -144,14 +240,16 @@ OpenSCENARIO: - entityRef: ego EntityCondition: ReachPositionCondition: - Position: - LanePosition: - roadId: '' - laneId: '34507' - s: 50 - offset: 0 - Orientation: *DEFAULT_ORIENTATION - tolerance: 0.5 + Position: *POSITION_A + tolerance: 1 + - Condition: + - name: '' + delay: 0 + conditionEdge: none + ByValueCondition: + SimulationTimeCondition: + value: ${90 + $laps * 120} + rule: greaterThan Action: - name: '' UserDefinedAction: @@ -165,10 +263,14 @@ OpenSCENARIO: - name: '' delay: 0 conditionEdge: none - ByValueCondition: - SimulationTimeCondition: - value: 180 - rule: greaterThan + ByEntityCondition: + TriggeringEntities: + triggeringEntitiesRule: any + EntityRef: + - entityRef: ego + EntityCondition: + StandStillCondition: + duration: 10 Action: - name: '' UserDefinedAction: From 6d6e49a9a59ebf86011a16b1589a283c09ac495b Mon Sep 17 00:00:00 2001 From: Grzegorz Maj Date: Thu, 12 Sep 2024 12:17:57 +0200 Subject: [PATCH 260/304] Change names of relativePose tests --- simulation/traffic_simulator/test/src/utils/test_pose.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/simulation/traffic_simulator/test/src/utils/test_pose.cpp b/simulation/traffic_simulator/test/src/utils/test_pose.cpp index 843fd56d397..a7132a31c62 100644 --- a/simulation/traffic_simulator/test/src/utils/test_pose.cpp +++ b/simulation/traffic_simulator/test/src/utils/test_pose.cpp @@ -289,7 +289,7 @@ TEST(pose, transformRelativePoseToGlobal) /** * @note Test calculation correctness when only one pose is zeroed, the goal is to obtain a pose equal to the second argument. */ -TEST(pose, relativePose_poses_zeros) +TEST(pose, relativePose_poses_zero) { const auto from = makePose(makePoint(0.0, 0.0, 0.0)); const auto to = makePose(makePoint(10.0, 51.0, 2.0)); @@ -302,7 +302,7 @@ TEST(pose, relativePose_poses_zeros) /** * @note Test calculation correctness when both poses are zeroed. */ -TEST(pose, relativePose_poses_zero) +TEST(pose, relativePose_poses_zeros) { const auto from = makePose(makePoint(0.0, 0.0, 0.0)); const auto to = makePose(makePoint(0.0, 0.0, 0.0)); @@ -330,7 +330,7 @@ TEST(pose, relativePose_poses_complex) /** * @note Test calculation correctness with the overload. */ -TEST_F(PoseTest, relativePose_first) +TEST_F(PoseTest, relativePose_canonicalized_end_position) { const auto pose_relative = makePose( makePoint(9.9999, -0.0009, 0.0126), @@ -350,7 +350,7 @@ TEST_F(PoseTest, relativePose_first) /** * @note Test calculation correctness with the overload. */ -TEST_F(PoseTest, relativePose_second) +TEST_F(PoseTest, relativePose_canonicalized_start_position) { const auto pose_relative = makePose( makePoint(145244.7916, 786706.3326, 0.0127), From e78981c6ffdc8a40790c7587ecb0d6be1855d607 Mon Sep 17 00:00:00 2001 From: Release Bot Date: Fri, 13 Sep 2024 03:22:39 +0000 Subject: [PATCH 261/304] Bump version of scenario_simulator_v2 from version 4.2.5 to version 4.2.6 --- common/math/arithmetic/CHANGELOG.rst | 5 +++++ common/math/arithmetic/package.xml | 2 +- common/math/geometry/CHANGELOG.rst | 5 +++++ common/math/geometry/package.xml | 2 +- common/scenario_simulator_exception/CHANGELOG.rst | 5 +++++ common/scenario_simulator_exception/package.xml | 2 +- common/simple_junit/CHANGELOG.rst | 5 +++++ common/simple_junit/package.xml | 2 +- common/status_monitor/CHANGELOG.rst | 5 +++++ common/status_monitor/package.xml | 2 +- external/concealer/CHANGELOG.rst | 5 +++++ external/concealer/package.xml | 2 +- external/embree_vendor/CHANGELOG.rst | 5 +++++ external/embree_vendor/package.xml | 2 +- map/kashiwanoha_map/CHANGELOG.rst | 5 +++++ map/kashiwanoha_map/package.xml | 2 +- map/simple_cross_map/CHANGELOG.rst | 5 +++++ map/simple_cross_map/package.xml | 2 +- mock/cpp_mock_scenarios/CHANGELOG.rst | 5 +++++ mock/cpp_mock_scenarios/package.xml | 2 +- .../openscenario_experimental_catalog/CHANGELOG.rst | 5 +++++ .../openscenario_experimental_catalog/package.xml | 2 +- openscenario/openscenario_interpreter/CHANGELOG.rst | 5 +++++ openscenario/openscenario_interpreter/package.xml | 2 +- .../openscenario_interpreter_example/CHANGELOG.rst | 5 +++++ .../openscenario_interpreter_example/package.xml | 2 +- .../openscenario_interpreter_msgs/CHANGELOG.rst | 5 +++++ .../openscenario_interpreter_msgs/package.xml | 2 +- openscenario/openscenario_preprocessor/CHANGELOG.rst | 5 +++++ openscenario/openscenario_preprocessor/package.xml | 2 +- .../openscenario_preprocessor_msgs/CHANGELOG.rst | 5 +++++ .../openscenario_preprocessor_msgs/package.xml | 2 +- openscenario/openscenario_utility/CHANGELOG.rst | 5 +++++ openscenario/openscenario_utility/package.xml | 2 +- openscenario/openscenario_validator/CHANGELOG.rst | 5 +++++ openscenario/openscenario_validator/package.xml | 2 +- .../openscenario_visualization/CHANGELOG.rst | 5 +++++ rviz_plugins/openscenario_visualization/package.xml | 2 +- .../CHANGELOG.rst | 5 +++++ .../real_time_factor_control_rviz_plugin/package.xml | 2 +- scenario_simulator_v2/CHANGELOG.rst | 5 +++++ scenario_simulator_v2/package.xml | 2 +- simulation/behavior_tree_plugin/CHANGELOG.rst | 5 +++++ simulation/behavior_tree_plugin/package.xml | 2 +- simulation/do_nothing_plugin/CHANGELOG.rst | 5 +++++ simulation/do_nothing_plugin/package.xml | 2 +- simulation/simple_sensor_simulator/CHANGELOG.rst | 5 +++++ simulation/simple_sensor_simulator/package.xml | 2 +- simulation/simulation_interface/CHANGELOG.rst | 5 +++++ simulation/simulation_interface/package.xml | 2 +- simulation/traffic_simulator/CHANGELOG.rst | 12 ++++++++++++ simulation/traffic_simulator/package.xml | 2 +- simulation/traffic_simulator_msgs/CHANGELOG.rst | 5 +++++ simulation/traffic_simulator_msgs/package.xml | 2 +- test_runner/random_test_runner/CHANGELOG.rst | 5 +++++ test_runner/random_test_runner/package.xml | 2 +- test_runner/scenario_test_runner/CHANGELOG.rst | 5 +++++ test_runner/scenario_test_runner/package.xml | 2 +- 58 files changed, 181 insertions(+), 29 deletions(-) diff --git a/common/math/arithmetic/CHANGELOG.rst b/common/math/arithmetic/CHANGELOG.rst index d7a29893e86..e68997a6ef3 100644 --- a/common/math/arithmetic/CHANGELOG.rst +++ b/common/math/arithmetic/CHANGELOG.rst @@ -21,6 +21,11 @@ Changelog for package arithmetic * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.6 (2024-09-13) +------------------ +* Merge branch 'master' into RJD-1197/pose_module +* Contributors: Masaya Kataoka + 4.2.5 (2024-09-12) ------------------ diff --git a/common/math/arithmetic/package.xml b/common/math/arithmetic/package.xml index 88b3fe97051..20092372646 100644 --- a/common/math/arithmetic/package.xml +++ b/common/math/arithmetic/package.xml @@ -2,7 +2,7 @@ arithmetic - 4.2.5 + 4.2.6 arithmetic library for scenario_simulator_v2 Tatsuya Yamasaki Apache License 2.0 diff --git a/common/math/geometry/CHANGELOG.rst b/common/math/geometry/CHANGELOG.rst index a217b54bdfd..5fb01b98c21 100644 --- a/common/math/geometry/CHANGELOG.rst +++ b/common/math/geometry/CHANGELOG.rst @@ -21,6 +21,11 @@ Changelog for package geometry * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.6 (2024-09-13) +------------------ +* Merge branch 'master' into RJD-1197/pose_module +* Contributors: Masaya Kataoka + 4.2.5 (2024-09-12) ------------------ diff --git a/common/math/geometry/package.xml b/common/math/geometry/package.xml index 8d7f2ba65ec..0f0fcd166e2 100644 --- a/common/math/geometry/package.xml +++ b/common/math/geometry/package.xml @@ -2,7 +2,7 @@ geometry - 4.2.5 + 4.2.6 geometry math library for scenario_simulator_v2 application Masaya Kataoka Apache License 2.0 diff --git a/common/scenario_simulator_exception/CHANGELOG.rst b/common/scenario_simulator_exception/CHANGELOG.rst index 17fbfa2c75f..ac504e87df9 100644 --- a/common/scenario_simulator_exception/CHANGELOG.rst +++ b/common/scenario_simulator_exception/CHANGELOG.rst @@ -21,6 +21,11 @@ Changelog for package scenario_simulator_exception * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.6 (2024-09-13) +------------------ +* Merge branch 'master' into RJD-1197/pose_module +* Contributors: Masaya Kataoka + 4.2.5 (2024-09-12) ------------------ diff --git a/common/scenario_simulator_exception/package.xml b/common/scenario_simulator_exception/package.xml index 7fe20b1548b..76f250cf85b 100644 --- a/common/scenario_simulator_exception/package.xml +++ b/common/scenario_simulator_exception/package.xml @@ -2,7 +2,7 @@ scenario_simulator_exception - 4.2.5 + 4.2.6 Exception types for scenario simulator Tatsuya Yamasaki Apache License 2.0 diff --git a/common/simple_junit/CHANGELOG.rst b/common/simple_junit/CHANGELOG.rst index f85b4bd0661..55b2cda1d44 100644 --- a/common/simple_junit/CHANGELOG.rst +++ b/common/simple_junit/CHANGELOG.rst @@ -21,6 +21,11 @@ Changelog for package junit_exporter * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.6 (2024-09-13) +------------------ +* Merge branch 'master' into RJD-1197/pose_module +* Contributors: Masaya Kataoka + 4.2.5 (2024-09-12) ------------------ diff --git a/common/simple_junit/package.xml b/common/simple_junit/package.xml index e7e2f31c693..a69ba87142b 100644 --- a/common/simple_junit/package.xml +++ b/common/simple_junit/package.xml @@ -2,7 +2,7 @@ simple_junit - 4.2.5 + 4.2.6 Lightweight JUnit library for ROS 2 Masaya Kataoka Tatsuya Yamasaki diff --git a/common/status_monitor/CHANGELOG.rst b/common/status_monitor/CHANGELOG.rst index c400af7386a..d4e38cf3d60 100644 --- a/common/status_monitor/CHANGELOG.rst +++ b/common/status_monitor/CHANGELOG.rst @@ -21,6 +21,11 @@ Changelog for package status_monitor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.6 (2024-09-13) +------------------ +* Merge branch 'master' into RJD-1197/pose_module +* Contributors: Masaya Kataoka + 4.2.5 (2024-09-12) ------------------ diff --git a/common/status_monitor/package.xml b/common/status_monitor/package.xml index d3edea8c479..9b0e0363f7b 100644 --- a/common/status_monitor/package.xml +++ b/common/status_monitor/package.xml @@ -2,7 +2,7 @@ status_monitor - 4.2.5 + 4.2.6 none Tatsuya Yamasaki Apache License 2.0 diff --git a/external/concealer/CHANGELOG.rst b/external/concealer/CHANGELOG.rst index 62bdddbb613..7e33e392a19 100644 --- a/external/concealer/CHANGELOG.rst +++ b/external/concealer/CHANGELOG.rst @@ -21,6 +21,11 @@ Changelog for package concealer * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.6 (2024-09-13) +------------------ +* Merge branch 'master' into RJD-1197/pose_module +* Contributors: Masaya Kataoka + 4.2.5 (2024-09-12) ------------------ diff --git a/external/concealer/package.xml b/external/concealer/package.xml index 013840213cd..66ec42a8adc 100644 --- a/external/concealer/package.xml +++ b/external/concealer/package.xml @@ -2,7 +2,7 @@ concealer - 4.2.5 + 4.2.6 Provides a class 'Autoware' to conceal miscellaneous things to simplify Autoware management of the simulator. Tatsuya Yamasaki Apache License 2.0 diff --git a/external/embree_vendor/CHANGELOG.rst b/external/embree_vendor/CHANGELOG.rst index a4b10b817d9..dff3457b904 100644 --- a/external/embree_vendor/CHANGELOG.rst +++ b/external/embree_vendor/CHANGELOG.rst @@ -24,6 +24,11 @@ Changelog for package embree_vendor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.6 (2024-09-13) +------------------ +* Merge branch 'master' into RJD-1197/pose_module +* Contributors: Masaya Kataoka + 4.2.5 (2024-09-12) ------------------ diff --git a/external/embree_vendor/package.xml b/external/embree_vendor/package.xml index 638bf8ab53d..94aa1a8a124 100644 --- a/external/embree_vendor/package.xml +++ b/external/embree_vendor/package.xml @@ -2,7 +2,7 @@ embree_vendor - 4.2.5 + 4.2.6 vendor packages for intel raytracing kernel library masaya Apache 2.0 diff --git a/map/kashiwanoha_map/CHANGELOG.rst b/map/kashiwanoha_map/CHANGELOG.rst index 5f3b0760b8a..6cfdef7b9c2 100644 --- a/map/kashiwanoha_map/CHANGELOG.rst +++ b/map/kashiwanoha_map/CHANGELOG.rst @@ -21,6 +21,11 @@ Changelog for package kashiwanoha_map * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.6 (2024-09-13) +------------------ +* Merge branch 'master' into RJD-1197/pose_module +* Contributors: Masaya Kataoka + 4.2.5 (2024-09-12) ------------------ diff --git a/map/kashiwanoha_map/package.xml b/map/kashiwanoha_map/package.xml index 7cdb2fd892b..5abcd9bdf79 100644 --- a/map/kashiwanoha_map/package.xml +++ b/map/kashiwanoha_map/package.xml @@ -2,7 +2,7 @@ kashiwanoha_map - 4.2.5 + 4.2.6 map package for kashiwanoha Masaya Kataoka Apache License 2.0 diff --git a/map/simple_cross_map/CHANGELOG.rst b/map/simple_cross_map/CHANGELOG.rst index b76707ceff8..7cb5593e1f9 100644 --- a/map/simple_cross_map/CHANGELOG.rst +++ b/map/simple_cross_map/CHANGELOG.rst @@ -9,6 +9,11 @@ Changelog for package simple_cross_map * Merge branch 'master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.6 (2024-09-13) +------------------ +* Merge branch 'master' into RJD-1197/pose_module +* Contributors: Masaya Kataoka + 4.2.5 (2024-09-12) ------------------ diff --git a/map/simple_cross_map/package.xml b/map/simple_cross_map/package.xml index 0fdb585a731..7d815337fc6 100644 --- a/map/simple_cross_map/package.xml +++ b/map/simple_cross_map/package.xml @@ -2,7 +2,7 @@ simple_cross_map - 4.2.5 + 4.2.6 map package for simple cross Masaya Kataoka Apache License 2.0 diff --git a/mock/cpp_mock_scenarios/CHANGELOG.rst b/mock/cpp_mock_scenarios/CHANGELOG.rst index 9c8bce49f06..20d34347807 100644 --- a/mock/cpp_mock_scenarios/CHANGELOG.rst +++ b/mock/cpp_mock_scenarios/CHANGELOG.rst @@ -21,6 +21,11 @@ Changelog for package cpp_mock_scenarios * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.6 (2024-09-13) +------------------ +* Merge branch 'master' into RJD-1197/pose_module +* Contributors: Masaya Kataoka + 4.2.5 (2024-09-12) ------------------ * Merge pull request `#1373 `_ from tier4/fix/colcon_build_error_furthermore diff --git a/mock/cpp_mock_scenarios/package.xml b/mock/cpp_mock_scenarios/package.xml index 6e9270a030f..96951d807a2 100644 --- a/mock/cpp_mock_scenarios/package.xml +++ b/mock/cpp_mock_scenarios/package.xml @@ -2,7 +2,7 @@ cpp_mock_scenarios - 4.2.5 + 4.2.6 C++ mock scenarios masaya Apache License 2.0 diff --git a/openscenario/openscenario_experimental_catalog/CHANGELOG.rst b/openscenario/openscenario_experimental_catalog/CHANGELOG.rst index bea5f9f1a52..65044e494e8 100644 --- a/openscenario/openscenario_experimental_catalog/CHANGELOG.rst +++ b/openscenario/openscenario_experimental_catalog/CHANGELOG.rst @@ -21,6 +21,11 @@ Changelog for package openscenario_experimental_catalog * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.6 (2024-09-13) +------------------ +* Merge branch 'master' into RJD-1197/pose_module +* Contributors: Masaya Kataoka + 4.2.5 (2024-09-12) ------------------ diff --git a/openscenario/openscenario_experimental_catalog/package.xml b/openscenario/openscenario_experimental_catalog/package.xml index b20a1a446a9..183aa7683f2 100644 --- a/openscenario/openscenario_experimental_catalog/package.xml +++ b/openscenario/openscenario_experimental_catalog/package.xml @@ -2,7 +2,7 @@ openscenario_experimental_catalog - 4.2.5 + 4.2.6 TIER IV experimental catalogs for OpenSCENARIO Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter/CHANGELOG.rst b/openscenario/openscenario_interpreter/CHANGELOG.rst index 96465f9138b..7e7cea1c9a2 100644 --- a/openscenario/openscenario_interpreter/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter/CHANGELOG.rst @@ -32,6 +32,11 @@ Changelog for package openscenario_interpreter * add publish_empty_context parameter * Contributors: Masaya Kataoka +4.2.6 (2024-09-13) +------------------ +* Merge branch 'master' into RJD-1197/pose_module +* Contributors: Masaya Kataoka + 4.2.5 (2024-09-12) ------------------ diff --git a/openscenario/openscenario_interpreter/package.xml b/openscenario/openscenario_interpreter/package.xml index 6afec9f0261..8d76cc63258 100644 --- a/openscenario/openscenario_interpreter/package.xml +++ b/openscenario/openscenario_interpreter/package.xml @@ -2,7 +2,7 @@ openscenario_interpreter - 4.2.5 + 4.2.6 OpenSCENARIO 1.2.0 interpreter package for Autoware Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter_example/CHANGELOG.rst b/openscenario/openscenario_interpreter_example/CHANGELOG.rst index cdce7fb5205..5fc71f01669 100644 --- a/openscenario/openscenario_interpreter_example/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter_example/CHANGELOG.rst @@ -21,6 +21,11 @@ Changelog for package openscenario_interpreter_example * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.6 (2024-09-13) +------------------ +* Merge branch 'master' into RJD-1197/pose_module +* Contributors: Masaya Kataoka + 4.2.5 (2024-09-12) ------------------ diff --git a/openscenario/openscenario_interpreter_example/package.xml b/openscenario/openscenario_interpreter_example/package.xml index a198937c5ed..31a24a5f6e6 100644 --- a/openscenario/openscenario_interpreter_example/package.xml +++ b/openscenario/openscenario_interpreter_example/package.xml @@ -3,7 +3,7 @@ openscenario_interpreter_example - 4.2.5 + 4.2.6 Examples for some TIER IV OpenSCENARIO Interpreter's features Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst b/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst index 20d14b6686b..132cc94f163 100644 --- a/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst @@ -21,6 +21,11 @@ Changelog for package openscenario_interpreter_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.6 (2024-09-13) +------------------ +* Merge branch 'master' into RJD-1197/pose_module +* Contributors: Masaya Kataoka + 4.2.5 (2024-09-12) ------------------ diff --git a/openscenario/openscenario_interpreter_msgs/package.xml b/openscenario/openscenario_interpreter_msgs/package.xml index 95ecc9359b4..4ad2ebb4b03 100644 --- a/openscenario/openscenario_interpreter_msgs/package.xml +++ b/openscenario/openscenario_interpreter_msgs/package.xml @@ -2,7 +2,7 @@ openscenario_interpreter_msgs - 4.2.5 + 4.2.6 ROS message types for package openscenario_interpreter Yamasaki Tatsuya Apache License 2.0 diff --git a/openscenario/openscenario_preprocessor/CHANGELOG.rst b/openscenario/openscenario_preprocessor/CHANGELOG.rst index 15f31957d52..d8971f74d34 100644 --- a/openscenario/openscenario_preprocessor/CHANGELOG.rst +++ b/openscenario/openscenario_preprocessor/CHANGELOG.rst @@ -21,6 +21,11 @@ Changelog for package openscenario_preprocessor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.6 (2024-09-13) +------------------ +* Merge branch 'master' into RJD-1197/pose_module +* Contributors: Masaya Kataoka + 4.2.5 (2024-09-12) ------------------ diff --git a/openscenario/openscenario_preprocessor/package.xml b/openscenario/openscenario_preprocessor/package.xml index 2746f2c95c2..970ff5b463c 100644 --- a/openscenario/openscenario_preprocessor/package.xml +++ b/openscenario/openscenario_preprocessor/package.xml @@ -3,7 +3,7 @@ openscenario_preprocessor - 4.2.5 + 4.2.6 Example package for TIER IV OpenSCENARIO Interpreter Kotaro Yoshimoto Apache License 2.0 diff --git a/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst b/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst index f8203512908..d8ff2ecbef1 100644 --- a/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst +++ b/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst @@ -21,6 +21,11 @@ Changelog for package openscenario_preprocessor_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.6 (2024-09-13) +------------------ +* Merge branch 'master' into RJD-1197/pose_module +* Contributors: Masaya Kataoka + 4.2.5 (2024-09-12) ------------------ diff --git a/openscenario/openscenario_preprocessor_msgs/package.xml b/openscenario/openscenario_preprocessor_msgs/package.xml index f38d83f0b2d..8fed6123a33 100644 --- a/openscenario/openscenario_preprocessor_msgs/package.xml +++ b/openscenario/openscenario_preprocessor_msgs/package.xml @@ -2,7 +2,7 @@ openscenario_preprocessor_msgs - 4.2.5 + 4.2.6 ROS message types for package openscenario_preprocessor Kotaro Yoshimoto Apache License 2.0 diff --git a/openscenario/openscenario_utility/CHANGELOG.rst b/openscenario/openscenario_utility/CHANGELOG.rst index 84083f58a50..45f7eb74886 100644 --- a/openscenario/openscenario_utility/CHANGELOG.rst +++ b/openscenario/openscenario_utility/CHANGELOG.rst @@ -24,6 +24,11 @@ Changelog for package openscenario_utility * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.6 (2024-09-13) +------------------ +* Merge branch 'master' into RJD-1197/pose_module +* Contributors: Masaya Kataoka + 4.2.5 (2024-09-12) ------------------ diff --git a/openscenario/openscenario_utility/package.xml b/openscenario/openscenario_utility/package.xml index 5b5c8914dea..1c543862bcb 100644 --- a/openscenario/openscenario_utility/package.xml +++ b/openscenario/openscenario_utility/package.xml @@ -2,7 +2,7 @@ openscenario_utility - 4.2.5 + 4.2.6 Utility tools for ASAM OpenSCENARIO 1.2.0 Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_validator/CHANGELOG.rst b/openscenario/openscenario_validator/CHANGELOG.rst index 926a119cfa1..fc7b800cc87 100644 --- a/openscenario/openscenario_validator/CHANGELOG.rst +++ b/openscenario/openscenario_validator/CHANGELOG.rst @@ -10,6 +10,11 @@ Changelog for package openscenario_validator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.6 (2024-09-13) +------------------ +* Merge branch 'master' into RJD-1197/pose_module +* Contributors: Masaya Kataoka + 4.2.5 (2024-09-12) ------------------ diff --git a/openscenario/openscenario_validator/package.xml b/openscenario/openscenario_validator/package.xml index 37350a6a76c..d6ab006f31e 100644 --- a/openscenario/openscenario_validator/package.xml +++ b/openscenario/openscenario_validator/package.xml @@ -2,7 +2,7 @@ openscenario_validator - 4.2.5 + 4.2.6 Validator for OpenSCENARIO 1.3 Kotaro Yoshimoto Apache License 2.0 diff --git a/rviz_plugins/openscenario_visualization/CHANGELOG.rst b/rviz_plugins/openscenario_visualization/CHANGELOG.rst index 209a8f4be8f..3bed24897ac 100644 --- a/rviz_plugins/openscenario_visualization/CHANGELOG.rst +++ b/rviz_plugins/openscenario_visualization/CHANGELOG.rst @@ -21,6 +21,11 @@ Changelog for package openscenario_visualization * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.6 (2024-09-13) +------------------ +* Merge branch 'master' into RJD-1197/pose_module +* Contributors: Masaya Kataoka + 4.2.5 (2024-09-12) ------------------ diff --git a/rviz_plugins/openscenario_visualization/package.xml b/rviz_plugins/openscenario_visualization/package.xml index 458b89ee890..d5c3f29ad89 100644 --- a/rviz_plugins/openscenario_visualization/package.xml +++ b/rviz_plugins/openscenario_visualization/package.xml @@ -2,7 +2,7 @@ openscenario_visualization - 4.2.5 + 4.2.6 Visualization tools for simulation results Masaya Kataoka Kyoichi Sugahara diff --git a/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst b/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst index 5128104bb4c..f5b3156a918 100644 --- a/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst +++ b/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst @@ -21,6 +21,11 @@ Changelog for package real_time_factor_control_rviz_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.6 (2024-09-13) +------------------ +* Merge branch 'master' into RJD-1197/pose_module +* Contributors: Masaya Kataoka + 4.2.5 (2024-09-12) ------------------ diff --git a/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml b/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml index d2b1d90a7c2..2fc0460ab4a 100644 --- a/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml +++ b/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml @@ -2,7 +2,7 @@ real_time_factor_control_rviz_plugin - 4.2.5 + 4.2.6 Slider controlling real time factor value. Paweł Lech Apache License 2.0 diff --git a/scenario_simulator_v2/CHANGELOG.rst b/scenario_simulator_v2/CHANGELOG.rst index 6e6d7364c7d..c300f15de44 100644 --- a/scenario_simulator_v2/CHANGELOG.rst +++ b/scenario_simulator_v2/CHANGELOG.rst @@ -21,6 +21,11 @@ Changelog for package scenario_simulator_v2 * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.6 (2024-09-13) +------------------ +* Merge branch 'master' into RJD-1197/pose_module +* Contributors: Masaya Kataoka + 4.2.5 (2024-09-12) ------------------ diff --git a/scenario_simulator_v2/package.xml b/scenario_simulator_v2/package.xml index 782eda0da2f..bb6a93c3a2d 100644 --- a/scenario_simulator_v2/package.xml +++ b/scenario_simulator_v2/package.xml @@ -2,7 +2,7 @@ scenario_simulator_v2 - 4.2.5 + 4.2.6 scenario testing framework for Autoware Masaya Kataoka Apache License 2.0 diff --git a/simulation/behavior_tree_plugin/CHANGELOG.rst b/simulation/behavior_tree_plugin/CHANGELOG.rst index 0643dfcfdab..f172bf16e2b 100644 --- a/simulation/behavior_tree_plugin/CHANGELOG.rst +++ b/simulation/behavior_tree_plugin/CHANGELOG.rst @@ -21,6 +21,11 @@ Changelog for package behavior_tree_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.6 (2024-09-13) +------------------ +* Merge branch 'master' into RJD-1197/pose_module +* Contributors: Masaya Kataoka + 4.2.5 (2024-09-12) ------------------ diff --git a/simulation/behavior_tree_plugin/package.xml b/simulation/behavior_tree_plugin/package.xml index fb87f0aed9a..40f5df40c7a 100644 --- a/simulation/behavior_tree_plugin/package.xml +++ b/simulation/behavior_tree_plugin/package.xml @@ -2,7 +2,7 @@ behavior_tree_plugin - 4.2.5 + 4.2.6 Behavior tree plugin for traffic_simulator masaya Apache 2.0 diff --git a/simulation/do_nothing_plugin/CHANGELOG.rst b/simulation/do_nothing_plugin/CHANGELOG.rst index 8a3255c7f63..ffb67a74fe8 100644 --- a/simulation/do_nothing_plugin/CHANGELOG.rst +++ b/simulation/do_nothing_plugin/CHANGELOG.rst @@ -21,6 +21,11 @@ Changelog for package do_nothing_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.6 (2024-09-13) +------------------ +* Merge branch 'master' into RJD-1197/pose_module +* Contributors: Masaya Kataoka + 4.2.5 (2024-09-12) ------------------ diff --git a/simulation/do_nothing_plugin/package.xml b/simulation/do_nothing_plugin/package.xml index 2a62bd160fa..ac7db92b15b 100644 --- a/simulation/do_nothing_plugin/package.xml +++ b/simulation/do_nothing_plugin/package.xml @@ -2,7 +2,7 @@ do_nothing_plugin - 4.2.5 + 4.2.6 Behavior plugin for do nothing Masaya Kataoka Apache 2.0 diff --git a/simulation/simple_sensor_simulator/CHANGELOG.rst b/simulation/simple_sensor_simulator/CHANGELOG.rst index e36da68a953..2f6109d038f 100644 --- a/simulation/simple_sensor_simulator/CHANGELOG.rst +++ b/simulation/simple_sensor_simulator/CHANGELOG.rst @@ -21,6 +21,11 @@ Changelog for package simple_sensor_simulator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.6 (2024-09-13) +------------------ +* Merge branch 'master' into RJD-1197/pose_module +* Contributors: Masaya Kataoka + 4.2.5 (2024-09-12) ------------------ diff --git a/simulation/simple_sensor_simulator/package.xml b/simulation/simple_sensor_simulator/package.xml index 2577d3eeefc..b143e0c0f82 100644 --- a/simulation/simple_sensor_simulator/package.xml +++ b/simulation/simple_sensor_simulator/package.xml @@ -1,7 +1,7 @@ simple_sensor_simulator - 4.2.5 + 4.2.6 simple_sensor_simulator package masaya kataoka diff --git a/simulation/simulation_interface/CHANGELOG.rst b/simulation/simulation_interface/CHANGELOG.rst index c6cad508735..d01d4e14e94 100644 --- a/simulation/simulation_interface/CHANGELOG.rst +++ b/simulation/simulation_interface/CHANGELOG.rst @@ -21,6 +21,11 @@ Changelog for package simulation_interface * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.6 (2024-09-13) +------------------ +* Merge branch 'master' into RJD-1197/pose_module +* Contributors: Masaya Kataoka + 4.2.5 (2024-09-12) ------------------ diff --git a/simulation/simulation_interface/package.xml b/simulation/simulation_interface/package.xml index ca5afc050c4..cfd1599295d 100644 --- a/simulation/simulation_interface/package.xml +++ b/simulation/simulation_interface/package.xml @@ -2,7 +2,7 @@ simulation_interface - 4.2.5 + 4.2.6 packages to define interface between simulator and scenario interpreter Masaya Kataoka Apache License 2.0 diff --git a/simulation/traffic_simulator/CHANGELOG.rst b/simulation/traffic_simulator/CHANGELOG.rst index d3cf5191c14..3e05ff5a106 100644 --- a/simulation/traffic_simulator/CHANGELOG.rst +++ b/simulation/traffic_simulator/CHANGELOG.rst @@ -21,6 +21,18 @@ Changelog for package traffic_simulator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.6 (2024-09-13) +------------------ +* Merge pull request `#1371 `_ from tier4/RJD-1197/pose_module + Rjd 1197/pose module +* Change names of relativePose tests +* Fix typos in comments +* Merge branch 'master' into RJD-1197/pose_module +* CR requested changes part 2 +* CR requested changes +* Pose module unit tests +* Contributors: Grzegorz Maj, Masaya Kataoka + 4.2.5 (2024-09-12) ------------------ diff --git a/simulation/traffic_simulator/package.xml b/simulation/traffic_simulator/package.xml index 86dd23e340a..ccbc7d4a345 100644 --- a/simulation/traffic_simulator/package.xml +++ b/simulation/traffic_simulator/package.xml @@ -1,7 +1,7 @@ traffic_simulator - 4.2.5 + 4.2.6 control traffic flow masaya kataoka diff --git a/simulation/traffic_simulator_msgs/CHANGELOG.rst b/simulation/traffic_simulator_msgs/CHANGELOG.rst index bf58991cf79..3952a2c8b99 100644 --- a/simulation/traffic_simulator_msgs/CHANGELOG.rst +++ b/simulation/traffic_simulator_msgs/CHANGELOG.rst @@ -21,6 +21,11 @@ Changelog for package openscenario_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.6 (2024-09-13) +------------------ +* Merge branch 'master' into RJD-1197/pose_module +* Contributors: Masaya Kataoka + 4.2.5 (2024-09-12) ------------------ diff --git a/simulation/traffic_simulator_msgs/package.xml b/simulation/traffic_simulator_msgs/package.xml index 38503ce6845..8f74d486684 100644 --- a/simulation/traffic_simulator_msgs/package.xml +++ b/simulation/traffic_simulator_msgs/package.xml @@ -2,7 +2,7 @@ traffic_simulator_msgs - 4.2.5 + 4.2.6 ROS messages for openscenario Masaya Kataoka Apache License 2.0 diff --git a/test_runner/random_test_runner/CHANGELOG.rst b/test_runner/random_test_runner/CHANGELOG.rst index 1803a4a44cf..157b598fff5 100644 --- a/test_runner/random_test_runner/CHANGELOG.rst +++ b/test_runner/random_test_runner/CHANGELOG.rst @@ -21,6 +21,11 @@ Changelog for package random_test_runner * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.6 (2024-09-13) +------------------ +* Merge branch 'master' into RJD-1197/pose_module +* Contributors: Masaya Kataoka + 4.2.5 (2024-09-12) ------------------ diff --git a/test_runner/random_test_runner/package.xml b/test_runner/random_test_runner/package.xml index a9ebfec6973..3ba5639cd21 100644 --- a/test_runner/random_test_runner/package.xml +++ b/test_runner/random_test_runner/package.xml @@ -2,7 +2,7 @@ random_test_runner - 4.2.5 + 4.2.6 Random behavior test runner piotr-zyskowski-rai Apache License 2.0 diff --git a/test_runner/scenario_test_runner/CHANGELOG.rst b/test_runner/scenario_test_runner/CHANGELOG.rst index 95d775687b4..3ce96e94b6a 100644 --- a/test_runner/scenario_test_runner/CHANGELOG.rst +++ b/test_runner/scenario_test_runner/CHANGELOG.rst @@ -35,6 +35,11 @@ Changelog for package scenario_test_runner * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.6 (2024-09-13) +------------------ +* Merge branch 'master' into RJD-1197/pose_module +* Contributors: Masaya Kataoka + 4.2.5 (2024-09-12) ------------------ diff --git a/test_runner/scenario_test_runner/package.xml b/test_runner/scenario_test_runner/package.xml index b32d9b41730..b2b9f270dad 100644 --- a/test_runner/scenario_test_runner/package.xml +++ b/test_runner/scenario_test_runner/package.xml @@ -2,7 +2,7 @@ scenario_test_runner - 4.2.5 + 4.2.6 scenario test runner package Tatsuya Yamasaki Apache License 2.0 From f6ef3c93445f4eb180992dd5a3d13f80fb161d13 Mon Sep 17 00:00:00 2001 From: satoshi-ota Date: Fri, 13 Sep 2024 12:37:57 +0900 Subject: [PATCH 262/304] fix(mock): hard-coded update rate Signed-off-by: satoshi-ota --- mock/cpp_mock_scenarios/src/cpp_scenario_node.cpp | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/mock/cpp_mock_scenarios/src/cpp_scenario_node.cpp b/mock/cpp_mock_scenarios/src/cpp_scenario_node.cpp index 70559cab61e..7864980bdab 100644 --- a/mock/cpp_mock_scenarios/src/cpp_scenario_node.cpp +++ b/mock/cpp_mock_scenarios/src/cpp_scenario_node.cpp @@ -64,8 +64,9 @@ void CppScenarioNode::start() { onInitialize(); api_.startNpcLogic(); - using namespace std::chrono_literals; - update_timer_ = this->create_wall_timer(50ms, std::bind(&CppScenarioNode::update, this)); + const auto rate = + std::chrono::duration(1.0 / get_parameter("global_frame_rate").as_double()); + update_timer_ = this->create_wall_timer(rate, std::bind(&CppScenarioNode::update, this)); } void CppScenarioNode::stop(Result result, const std::string & description) From bfd14626e3dc428754be2129fe63a9ca52802566 Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Fri, 13 Sep 2024 16:04:28 +0900 Subject: [PATCH 263/304] Cleanup struct `TransitionAssertion` Signed-off-by: yamacir-kit --- ...ator_application_for_autoware_universe.hpp | 5 + .../concealer/transition_assertion.hpp | 118 +++++++----------- 2 files changed, 47 insertions(+), 76 deletions(-) diff --git a/external/concealer/include/concealer/field_operator_application_for_autoware_universe.hpp b/external/concealer/include/concealer/field_operator_application_for_autoware_universe.hpp index 0202d488eb3..ff9db9b0b73 100644 --- a/external/concealer/include/concealer/field_operator_application_for_autoware_universe.hpp +++ b/external/concealer/include/concealer/field_operator_application_for_autoware_universe.hpp @@ -84,6 +84,11 @@ class FieldOperatorApplicationFor auto receiveEmergencyState(const tier4_external_api_msgs::msg::Emergency & msg) -> void; + /* + NOTE: This predicate should not take the state being compared as an + argument or template parameter. Otherwise, code using this class would + need to have knowledge of the Autoware state type. + */ #define DEFINE_STATE_PREDICATE(NAME, VALUE) \ auto is##NAME() const noexcept \ { \ diff --git a/external/concealer/include/concealer/transition_assertion.hpp b/external/concealer/include/concealer/transition_assertion.hpp index 55724ba70b8..d8478d718fe 100644 --- a/external/concealer/include/concealer/transition_assertion.hpp +++ b/external/concealer/include/concealer/transition_assertion.hpp @@ -15,7 +15,6 @@ #ifndef CONCEALER__TRANSITION_ASSERTION_HPP_ #define CONCEALER__TRANSITION_ASSERTION_HPP_ -#include #include #include #include @@ -23,99 +22,66 @@ namespace concealer { -template -auto getParameter(const std::string & name, T value = {}) -{ - rclcpp::Node node{"get_parameter", "simulation"}; - - node.declare_parameter(name, value); - node.get_parameter(name, value); - - return value; -} - template struct TransitionAssertion { - using clock_type = std::chrono::steady_clock; - using rate_type = rclcpp::GenericRate; + const std::chrono::steady_clock::time_point start; - const clock_type::time_point start; const std::chrono::seconds initialize_duration; explicit TransitionAssertion() - : start(clock_type::now()), - initialize_duration(std::chrono::seconds(getParameter("initialize_duration"))) + : start(std::chrono::steady_clock::now()), initialize_duration([]() { + auto node = rclcpp::Node("get_parameter", "simulation"); + node.declare_parameter("initialize_duration", 0); + return node.get_parameter("initialize_duration").as_int(); + }()) { } auto makeTransitionError(const std::string & expected) const { - const auto current_state = asAutoware().getAutowareStateName(); - using namespace std::chrono; + const auto current_state = static_cast(*this).getAutowareStateName(); return common::AutowareError( "Simulator waited for the Autoware state to transition to ", expected, ", but time is up. The current Autoware state is ", (current_state.empty() ? "NOT PUBLISHED YET" : current_state), "."); } - auto asAutoware() -> Autoware & { return static_cast(*this); } - auto asAutoware() const -> const Autoware & { return static_cast(*this); } - -#define DEFINE_WAIT_FOR_AUTOWARE_STATE_TO_BE_WITH_INITIALIZE_TIME_LIMIT(STATE) \ - template \ - void waitForAutowareStateToBe##STATE( \ - Thunk && thunk = [] {}, std::chrono::seconds interval = std::chrono::seconds(1)) \ - { \ - using std::chrono::duration_cast; \ - using std::chrono::seconds; \ - rate_type rate(interval); \ - for (thunk(); not asAutoware().isStopRequested() and not asAutoware().is##STATE(); \ - rate.sleep()) { \ - auto now = clock_type::now(); \ - if (start + initialize_duration <= now) { \ - throw makeTransitionError(#STATE); \ - } else { \ - RCLCPP_INFO_STREAM( \ - asAutoware().get_logger(), \ - "Simulator waiting for Autoware state to be " #STATE " (remain: " \ - << duration_cast(start + initialize_duration - now).count() << ")."); \ - thunk(); \ - } \ - } \ - RCLCPP_INFO_STREAM( \ - asAutoware().get_logger(), \ - "Autoware is " << asAutoware().getAutowareStateName() << " now."); \ - } \ - static_assert(true, "") - -#define DEFINE_WAIT_FOR_AUTOWARE_STATE_TO_BE(STATE) \ - template \ - void waitForAutowareStateToBe##STATE( \ - Thunk && thunk = [] {}, std::chrono::seconds interval = std::chrono::seconds(1)) \ - { \ - using std::chrono::duration_cast; \ - using std::chrono::seconds; \ - rate_type rate(interval); \ - for (thunk(); not asAutoware().isStopRequested() and not asAutoware().is##STATE(); \ - rate.sleep()) { \ - auto now = clock_type::now(); \ - RCLCPP_INFO_STREAM( \ - asAutoware().get_logger(), \ - "Simulator waiting for Autoware state to be " #STATE " (remain: " \ - << duration_cast(start + initialize_duration - now).count() << ")."); \ - thunk(); \ - } \ - RCLCPP_INFO_STREAM( \ - asAutoware().get_logger(), \ - "Autoware is " << asAutoware().getAutowareStateName() << " now."); \ - } \ - static_assert(true, "") - - // XXX: The time limit must be ignored in waitForAutowareStateToBeDriving() because the current - // implementation attempts to transition to Driving state after initialize_duration seconds have - // elapsed. - +#define DEFINE_WAIT_FOR_AUTOWARE_STATE_TO_BE_WITH_INITIALIZE_TIME_LIMIT(STATE) \ + template \ + auto waitForAutowareStateToBe##STATE( \ + Thunk && thunk = [] {}, Interval interval = std::chrono::seconds(1)) \ + { \ + for (thunk(); not static_cast(*this).isStopRequested() and \ + not static_cast(*this).is##STATE(); \ + rclcpp::GenericRate(interval).sleep()) { \ + if (auto now = std::chrono::steady_clock::now(); start + initialize_duration <= now) { \ + throw makeTransitionError(#STATE); \ + } else { \ + thunk(); \ + } \ + } \ + } \ + static_assert(true) + +#define DEFINE_WAIT_FOR_AUTOWARE_STATE_TO_BE(STATE) \ + template \ + auto waitForAutowareStateToBe##STATE( \ + Thunk && thunk = [] {}, std::chrono::seconds interval = std::chrono::seconds(1)) \ + { \ + for (thunk(); not static_cast(*this).isStopRequested() and \ + not static_cast(*this).is##STATE(); \ + rclcpp::GenericRate(interval).sleep()) { \ + thunk(); \ + } \ + } \ + static_assert(true) + + /* + NOTE: The time limit must be ignored in waitForAutowareStateToBeDriving() + because the current implementation attempts to transition to Driving state + after initialize_duration seconds have elapsed. + */ DEFINE_WAIT_FOR_AUTOWARE_STATE_TO_BE_WITH_INITIALIZE_TIME_LIMIT(Initializing); DEFINE_WAIT_FOR_AUTOWARE_STATE_TO_BE_WITH_INITIALIZE_TIME_LIMIT(WaitingForRoute); DEFINE_WAIT_FOR_AUTOWARE_STATE_TO_BE_WITH_INITIALIZE_TIME_LIMIT(Planning); From 8d189b12b2eca96fbe393bd5f433328647871cb8 Mon Sep 17 00:00:00 2001 From: Release Bot Date: Fri, 13 Sep 2024 08:24:38 +0000 Subject: [PATCH 264/304] Bump version of scenario_simulator_v2 from version 4.2.6 to version 4.2.7 --- common/math/arithmetic/CHANGELOG.rst | 3 +++ common/math/arithmetic/package.xml | 2 +- common/math/geometry/CHANGELOG.rst | 3 +++ common/math/geometry/package.xml | 2 +- common/scenario_simulator_exception/CHANGELOG.rst | 3 +++ common/scenario_simulator_exception/package.xml | 2 +- common/simple_junit/CHANGELOG.rst | 3 +++ common/simple_junit/package.xml | 2 +- common/status_monitor/CHANGELOG.rst | 3 +++ common/status_monitor/package.xml | 2 +- external/concealer/CHANGELOG.rst | 3 +++ external/concealer/package.xml | 2 +- external/embree_vendor/CHANGELOG.rst | 3 +++ external/embree_vendor/package.xml | 2 +- map/kashiwanoha_map/CHANGELOG.rst | 3 +++ map/kashiwanoha_map/package.xml | 2 +- map/simple_cross_map/CHANGELOG.rst | 3 +++ map/simple_cross_map/package.xml | 2 +- mock/cpp_mock_scenarios/CHANGELOG.rst | 7 +++++++ mock/cpp_mock_scenarios/package.xml | 2 +- .../openscenario_experimental_catalog/CHANGELOG.rst | 3 +++ openscenario/openscenario_experimental_catalog/package.xml | 2 +- openscenario/openscenario_interpreter/CHANGELOG.rst | 3 +++ openscenario/openscenario_interpreter/package.xml | 2 +- .../openscenario_interpreter_example/CHANGELOG.rst | 3 +++ openscenario/openscenario_interpreter_example/package.xml | 2 +- openscenario/openscenario_interpreter_msgs/CHANGELOG.rst | 3 +++ openscenario/openscenario_interpreter_msgs/package.xml | 2 +- openscenario/openscenario_preprocessor/CHANGELOG.rst | 3 +++ openscenario/openscenario_preprocessor/package.xml | 2 +- openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst | 3 +++ openscenario/openscenario_preprocessor_msgs/package.xml | 2 +- openscenario/openscenario_utility/CHANGELOG.rst | 3 +++ openscenario/openscenario_utility/package.xml | 2 +- openscenario/openscenario_validator/CHANGELOG.rst | 3 +++ openscenario/openscenario_validator/package.xml | 2 +- rviz_plugins/openscenario_visualization/CHANGELOG.rst | 3 +++ rviz_plugins/openscenario_visualization/package.xml | 2 +- .../real_time_factor_control_rviz_plugin/CHANGELOG.rst | 3 +++ .../real_time_factor_control_rviz_plugin/package.xml | 2 +- scenario_simulator_v2/CHANGELOG.rst | 3 +++ scenario_simulator_v2/package.xml | 2 +- simulation/behavior_tree_plugin/CHANGELOG.rst | 3 +++ simulation/behavior_tree_plugin/package.xml | 2 +- simulation/do_nothing_plugin/CHANGELOG.rst | 3 +++ simulation/do_nothing_plugin/package.xml | 2 +- simulation/simple_sensor_simulator/CHANGELOG.rst | 3 +++ simulation/simple_sensor_simulator/package.xml | 2 +- simulation/simulation_interface/CHANGELOG.rst | 3 +++ simulation/simulation_interface/package.xml | 2 +- simulation/traffic_simulator/CHANGELOG.rst | 3 +++ simulation/traffic_simulator/package.xml | 2 +- simulation/traffic_simulator_msgs/CHANGELOG.rst | 3 +++ simulation/traffic_simulator_msgs/package.xml | 2 +- test_runner/random_test_runner/CHANGELOG.rst | 3 +++ test_runner/random_test_runner/package.xml | 2 +- test_runner/scenario_test_runner/CHANGELOG.rst | 3 +++ test_runner/scenario_test_runner/package.xml | 2 +- 58 files changed, 120 insertions(+), 29 deletions(-) diff --git a/common/math/arithmetic/CHANGELOG.rst b/common/math/arithmetic/CHANGELOG.rst index e68997a6ef3..5a2fb5ef910 100644 --- a/common/math/arithmetic/CHANGELOG.rst +++ b/common/math/arithmetic/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package arithmetic * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.7 (2024-09-13) +------------------ + 4.2.6 (2024-09-13) ------------------ * Merge branch 'master' into RJD-1197/pose_module diff --git a/common/math/arithmetic/package.xml b/common/math/arithmetic/package.xml index 20092372646..e717cb6ffe5 100644 --- a/common/math/arithmetic/package.xml +++ b/common/math/arithmetic/package.xml @@ -2,7 +2,7 @@ arithmetic - 4.2.6 + 4.2.7 arithmetic library for scenario_simulator_v2 Tatsuya Yamasaki Apache License 2.0 diff --git a/common/math/geometry/CHANGELOG.rst b/common/math/geometry/CHANGELOG.rst index 5fb01b98c21..960205286db 100644 --- a/common/math/geometry/CHANGELOG.rst +++ b/common/math/geometry/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package geometry * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.7 (2024-09-13) +------------------ + 4.2.6 (2024-09-13) ------------------ * Merge branch 'master' into RJD-1197/pose_module diff --git a/common/math/geometry/package.xml b/common/math/geometry/package.xml index 0f0fcd166e2..595b28a4815 100644 --- a/common/math/geometry/package.xml +++ b/common/math/geometry/package.xml @@ -2,7 +2,7 @@ geometry - 4.2.6 + 4.2.7 geometry math library for scenario_simulator_v2 application Masaya Kataoka Apache License 2.0 diff --git a/common/scenario_simulator_exception/CHANGELOG.rst b/common/scenario_simulator_exception/CHANGELOG.rst index ac504e87df9..d5374c143d1 100644 --- a/common/scenario_simulator_exception/CHANGELOG.rst +++ b/common/scenario_simulator_exception/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package scenario_simulator_exception * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.7 (2024-09-13) +------------------ + 4.2.6 (2024-09-13) ------------------ * Merge branch 'master' into RJD-1197/pose_module diff --git a/common/scenario_simulator_exception/package.xml b/common/scenario_simulator_exception/package.xml index 76f250cf85b..be1bc7047ea 100644 --- a/common/scenario_simulator_exception/package.xml +++ b/common/scenario_simulator_exception/package.xml @@ -2,7 +2,7 @@ scenario_simulator_exception - 4.2.6 + 4.2.7 Exception types for scenario simulator Tatsuya Yamasaki Apache License 2.0 diff --git a/common/simple_junit/CHANGELOG.rst b/common/simple_junit/CHANGELOG.rst index 55b2cda1d44..798f39ad289 100644 --- a/common/simple_junit/CHANGELOG.rst +++ b/common/simple_junit/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package junit_exporter * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.7 (2024-09-13) +------------------ + 4.2.6 (2024-09-13) ------------------ * Merge branch 'master' into RJD-1197/pose_module diff --git a/common/simple_junit/package.xml b/common/simple_junit/package.xml index a69ba87142b..230fc8fa2a4 100644 --- a/common/simple_junit/package.xml +++ b/common/simple_junit/package.xml @@ -2,7 +2,7 @@ simple_junit - 4.2.6 + 4.2.7 Lightweight JUnit library for ROS 2 Masaya Kataoka Tatsuya Yamasaki diff --git a/common/status_monitor/CHANGELOG.rst b/common/status_monitor/CHANGELOG.rst index d4e38cf3d60..3777997de87 100644 --- a/common/status_monitor/CHANGELOG.rst +++ b/common/status_monitor/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package status_monitor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.7 (2024-09-13) +------------------ + 4.2.6 (2024-09-13) ------------------ * Merge branch 'master' into RJD-1197/pose_module diff --git a/common/status_monitor/package.xml b/common/status_monitor/package.xml index 9b0e0363f7b..e6240847dd5 100644 --- a/common/status_monitor/package.xml +++ b/common/status_monitor/package.xml @@ -2,7 +2,7 @@ status_monitor - 4.2.6 + 4.2.7 none Tatsuya Yamasaki Apache License 2.0 diff --git a/external/concealer/CHANGELOG.rst b/external/concealer/CHANGELOG.rst index 7e33e392a19..dfe7871201d 100644 --- a/external/concealer/CHANGELOG.rst +++ b/external/concealer/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package concealer * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.7 (2024-09-13) +------------------ + 4.2.6 (2024-09-13) ------------------ * Merge branch 'master' into RJD-1197/pose_module diff --git a/external/concealer/package.xml b/external/concealer/package.xml index 66ec42a8adc..3978cf815d1 100644 --- a/external/concealer/package.xml +++ b/external/concealer/package.xml @@ -2,7 +2,7 @@ concealer - 4.2.6 + 4.2.7 Provides a class 'Autoware' to conceal miscellaneous things to simplify Autoware management of the simulator. Tatsuya Yamasaki Apache License 2.0 diff --git a/external/embree_vendor/CHANGELOG.rst b/external/embree_vendor/CHANGELOG.rst index dff3457b904..fa29fef0a6b 100644 --- a/external/embree_vendor/CHANGELOG.rst +++ b/external/embree_vendor/CHANGELOG.rst @@ -24,6 +24,9 @@ Changelog for package embree_vendor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.7 (2024-09-13) +------------------ + 4.2.6 (2024-09-13) ------------------ * Merge branch 'master' into RJD-1197/pose_module diff --git a/external/embree_vendor/package.xml b/external/embree_vendor/package.xml index 94aa1a8a124..d46a9f5dc58 100644 --- a/external/embree_vendor/package.xml +++ b/external/embree_vendor/package.xml @@ -2,7 +2,7 @@ embree_vendor - 4.2.6 + 4.2.7 vendor packages for intel raytracing kernel library masaya Apache 2.0 diff --git a/map/kashiwanoha_map/CHANGELOG.rst b/map/kashiwanoha_map/CHANGELOG.rst index 6cfdef7b9c2..e2d80251f69 100644 --- a/map/kashiwanoha_map/CHANGELOG.rst +++ b/map/kashiwanoha_map/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package kashiwanoha_map * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.7 (2024-09-13) +------------------ + 4.2.6 (2024-09-13) ------------------ * Merge branch 'master' into RJD-1197/pose_module diff --git a/map/kashiwanoha_map/package.xml b/map/kashiwanoha_map/package.xml index 5abcd9bdf79..58e76215a4e 100644 --- a/map/kashiwanoha_map/package.xml +++ b/map/kashiwanoha_map/package.xml @@ -2,7 +2,7 @@ kashiwanoha_map - 4.2.6 + 4.2.7 map package for kashiwanoha Masaya Kataoka Apache License 2.0 diff --git a/map/simple_cross_map/CHANGELOG.rst b/map/simple_cross_map/CHANGELOG.rst index 7cb5593e1f9..21bad9eac16 100644 --- a/map/simple_cross_map/CHANGELOG.rst +++ b/map/simple_cross_map/CHANGELOG.rst @@ -9,6 +9,9 @@ Changelog for package simple_cross_map * Merge branch 'master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.7 (2024-09-13) +------------------ + 4.2.6 (2024-09-13) ------------------ * Merge branch 'master' into RJD-1197/pose_module diff --git a/map/simple_cross_map/package.xml b/map/simple_cross_map/package.xml index 7d815337fc6..7bff8b394b8 100644 --- a/map/simple_cross_map/package.xml +++ b/map/simple_cross_map/package.xml @@ -2,7 +2,7 @@ simple_cross_map - 4.2.6 + 4.2.7 map package for simple cross Masaya Kataoka Apache License 2.0 diff --git a/mock/cpp_mock_scenarios/CHANGELOG.rst b/mock/cpp_mock_scenarios/CHANGELOG.rst index 20d34347807..8a5f8d6fe76 100644 --- a/mock/cpp_mock_scenarios/CHANGELOG.rst +++ b/mock/cpp_mock_scenarios/CHANGELOG.rst @@ -21,6 +21,13 @@ Changelog for package cpp_mock_scenarios * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.7 (2024-09-13) +------------------ +* Merge pull request `#1379 `_ from tier4/fix/hard-coded-update-rate + fix(mock): hard-coded update rate +* fix(mock): hard-coded update rate +* Contributors: Masaya Kataoka, satoshi-ota + 4.2.6 (2024-09-13) ------------------ * Merge branch 'master' into RJD-1197/pose_module diff --git a/mock/cpp_mock_scenarios/package.xml b/mock/cpp_mock_scenarios/package.xml index 96951d807a2..077636374e3 100644 --- a/mock/cpp_mock_scenarios/package.xml +++ b/mock/cpp_mock_scenarios/package.xml @@ -2,7 +2,7 @@ cpp_mock_scenarios - 4.2.6 + 4.2.7 C++ mock scenarios masaya Apache License 2.0 diff --git a/openscenario/openscenario_experimental_catalog/CHANGELOG.rst b/openscenario/openscenario_experimental_catalog/CHANGELOG.rst index 65044e494e8..b5e1570e9b8 100644 --- a/openscenario/openscenario_experimental_catalog/CHANGELOG.rst +++ b/openscenario/openscenario_experimental_catalog/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package openscenario_experimental_catalog * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.7 (2024-09-13) +------------------ + 4.2.6 (2024-09-13) ------------------ * Merge branch 'master' into RJD-1197/pose_module diff --git a/openscenario/openscenario_experimental_catalog/package.xml b/openscenario/openscenario_experimental_catalog/package.xml index 183aa7683f2..b0597456e2b 100644 --- a/openscenario/openscenario_experimental_catalog/package.xml +++ b/openscenario/openscenario_experimental_catalog/package.xml @@ -2,7 +2,7 @@ openscenario_experimental_catalog - 4.2.6 + 4.2.7 TIER IV experimental catalogs for OpenSCENARIO Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter/CHANGELOG.rst b/openscenario/openscenario_interpreter/CHANGELOG.rst index 7e7cea1c9a2..85f8304ba99 100644 --- a/openscenario/openscenario_interpreter/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter/CHANGELOG.rst @@ -32,6 +32,9 @@ Changelog for package openscenario_interpreter * add publish_empty_context parameter * Contributors: Masaya Kataoka +4.2.7 (2024-09-13) +------------------ + 4.2.6 (2024-09-13) ------------------ * Merge branch 'master' into RJD-1197/pose_module diff --git a/openscenario/openscenario_interpreter/package.xml b/openscenario/openscenario_interpreter/package.xml index 8d76cc63258..04fb15e42d8 100644 --- a/openscenario/openscenario_interpreter/package.xml +++ b/openscenario/openscenario_interpreter/package.xml @@ -2,7 +2,7 @@ openscenario_interpreter - 4.2.6 + 4.2.7 OpenSCENARIO 1.2.0 interpreter package for Autoware Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter_example/CHANGELOG.rst b/openscenario/openscenario_interpreter_example/CHANGELOG.rst index 5fc71f01669..b66c7420bb9 100644 --- a/openscenario/openscenario_interpreter_example/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter_example/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package openscenario_interpreter_example * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.7 (2024-09-13) +------------------ + 4.2.6 (2024-09-13) ------------------ * Merge branch 'master' into RJD-1197/pose_module diff --git a/openscenario/openscenario_interpreter_example/package.xml b/openscenario/openscenario_interpreter_example/package.xml index 31a24a5f6e6..c49eee5d4ce 100644 --- a/openscenario/openscenario_interpreter_example/package.xml +++ b/openscenario/openscenario_interpreter_example/package.xml @@ -3,7 +3,7 @@ openscenario_interpreter_example - 4.2.6 + 4.2.7 Examples for some TIER IV OpenSCENARIO Interpreter's features Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst b/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst index 132cc94f163..d336fd244ff 100644 --- a/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package openscenario_interpreter_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.7 (2024-09-13) +------------------ + 4.2.6 (2024-09-13) ------------------ * Merge branch 'master' into RJD-1197/pose_module diff --git a/openscenario/openscenario_interpreter_msgs/package.xml b/openscenario/openscenario_interpreter_msgs/package.xml index 4ad2ebb4b03..3f306dff4dc 100644 --- a/openscenario/openscenario_interpreter_msgs/package.xml +++ b/openscenario/openscenario_interpreter_msgs/package.xml @@ -2,7 +2,7 @@ openscenario_interpreter_msgs - 4.2.6 + 4.2.7 ROS message types for package openscenario_interpreter Yamasaki Tatsuya Apache License 2.0 diff --git a/openscenario/openscenario_preprocessor/CHANGELOG.rst b/openscenario/openscenario_preprocessor/CHANGELOG.rst index d8971f74d34..88f23930a07 100644 --- a/openscenario/openscenario_preprocessor/CHANGELOG.rst +++ b/openscenario/openscenario_preprocessor/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package openscenario_preprocessor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.7 (2024-09-13) +------------------ + 4.2.6 (2024-09-13) ------------------ * Merge branch 'master' into RJD-1197/pose_module diff --git a/openscenario/openscenario_preprocessor/package.xml b/openscenario/openscenario_preprocessor/package.xml index 970ff5b463c..1451e68bfd2 100644 --- a/openscenario/openscenario_preprocessor/package.xml +++ b/openscenario/openscenario_preprocessor/package.xml @@ -3,7 +3,7 @@ openscenario_preprocessor - 4.2.6 + 4.2.7 Example package for TIER IV OpenSCENARIO Interpreter Kotaro Yoshimoto Apache License 2.0 diff --git a/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst b/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst index d8ff2ecbef1..ebacc4b52b3 100644 --- a/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst +++ b/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package openscenario_preprocessor_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.7 (2024-09-13) +------------------ + 4.2.6 (2024-09-13) ------------------ * Merge branch 'master' into RJD-1197/pose_module diff --git a/openscenario/openscenario_preprocessor_msgs/package.xml b/openscenario/openscenario_preprocessor_msgs/package.xml index 8fed6123a33..be1055ed6a9 100644 --- a/openscenario/openscenario_preprocessor_msgs/package.xml +++ b/openscenario/openscenario_preprocessor_msgs/package.xml @@ -2,7 +2,7 @@ openscenario_preprocessor_msgs - 4.2.6 + 4.2.7 ROS message types for package openscenario_preprocessor Kotaro Yoshimoto Apache License 2.0 diff --git a/openscenario/openscenario_utility/CHANGELOG.rst b/openscenario/openscenario_utility/CHANGELOG.rst index 45f7eb74886..b2dab44f9e2 100644 --- a/openscenario/openscenario_utility/CHANGELOG.rst +++ b/openscenario/openscenario_utility/CHANGELOG.rst @@ -24,6 +24,9 @@ Changelog for package openscenario_utility * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.7 (2024-09-13) +------------------ + 4.2.6 (2024-09-13) ------------------ * Merge branch 'master' into RJD-1197/pose_module diff --git a/openscenario/openscenario_utility/package.xml b/openscenario/openscenario_utility/package.xml index 1c543862bcb..6376bba6dbe 100644 --- a/openscenario/openscenario_utility/package.xml +++ b/openscenario/openscenario_utility/package.xml @@ -2,7 +2,7 @@ openscenario_utility - 4.2.6 + 4.2.7 Utility tools for ASAM OpenSCENARIO 1.2.0 Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_validator/CHANGELOG.rst b/openscenario/openscenario_validator/CHANGELOG.rst index fc7b800cc87..21b6c9c20b4 100644 --- a/openscenario/openscenario_validator/CHANGELOG.rst +++ b/openscenario/openscenario_validator/CHANGELOG.rst @@ -10,6 +10,9 @@ Changelog for package openscenario_validator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.7 (2024-09-13) +------------------ + 4.2.6 (2024-09-13) ------------------ * Merge branch 'master' into RJD-1197/pose_module diff --git a/openscenario/openscenario_validator/package.xml b/openscenario/openscenario_validator/package.xml index d6ab006f31e..133896d8176 100644 --- a/openscenario/openscenario_validator/package.xml +++ b/openscenario/openscenario_validator/package.xml @@ -2,7 +2,7 @@ openscenario_validator - 4.2.6 + 4.2.7 Validator for OpenSCENARIO 1.3 Kotaro Yoshimoto Apache License 2.0 diff --git a/rviz_plugins/openscenario_visualization/CHANGELOG.rst b/rviz_plugins/openscenario_visualization/CHANGELOG.rst index 3bed24897ac..11a9a156088 100644 --- a/rviz_plugins/openscenario_visualization/CHANGELOG.rst +++ b/rviz_plugins/openscenario_visualization/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package openscenario_visualization * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.7 (2024-09-13) +------------------ + 4.2.6 (2024-09-13) ------------------ * Merge branch 'master' into RJD-1197/pose_module diff --git a/rviz_plugins/openscenario_visualization/package.xml b/rviz_plugins/openscenario_visualization/package.xml index d5c3f29ad89..1a67d93e687 100644 --- a/rviz_plugins/openscenario_visualization/package.xml +++ b/rviz_plugins/openscenario_visualization/package.xml @@ -2,7 +2,7 @@ openscenario_visualization - 4.2.6 + 4.2.7 Visualization tools for simulation results Masaya Kataoka Kyoichi Sugahara diff --git a/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst b/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst index f5b3156a918..bf2fde2bbf4 100644 --- a/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst +++ b/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package real_time_factor_control_rviz_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.7 (2024-09-13) +------------------ + 4.2.6 (2024-09-13) ------------------ * Merge branch 'master' into RJD-1197/pose_module diff --git a/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml b/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml index 2fc0460ab4a..fa688c26a07 100644 --- a/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml +++ b/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml @@ -2,7 +2,7 @@ real_time_factor_control_rviz_plugin - 4.2.6 + 4.2.7 Slider controlling real time factor value. Paweł Lech Apache License 2.0 diff --git a/scenario_simulator_v2/CHANGELOG.rst b/scenario_simulator_v2/CHANGELOG.rst index c300f15de44..05a97a5df18 100644 --- a/scenario_simulator_v2/CHANGELOG.rst +++ b/scenario_simulator_v2/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package scenario_simulator_v2 * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.7 (2024-09-13) +------------------ + 4.2.6 (2024-09-13) ------------------ * Merge branch 'master' into RJD-1197/pose_module diff --git a/scenario_simulator_v2/package.xml b/scenario_simulator_v2/package.xml index bb6a93c3a2d..6f4ccc31483 100644 --- a/scenario_simulator_v2/package.xml +++ b/scenario_simulator_v2/package.xml @@ -2,7 +2,7 @@ scenario_simulator_v2 - 4.2.6 + 4.2.7 scenario testing framework for Autoware Masaya Kataoka Apache License 2.0 diff --git a/simulation/behavior_tree_plugin/CHANGELOG.rst b/simulation/behavior_tree_plugin/CHANGELOG.rst index f172bf16e2b..4805eb53181 100644 --- a/simulation/behavior_tree_plugin/CHANGELOG.rst +++ b/simulation/behavior_tree_plugin/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package behavior_tree_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.7 (2024-09-13) +------------------ + 4.2.6 (2024-09-13) ------------------ * Merge branch 'master' into RJD-1197/pose_module diff --git a/simulation/behavior_tree_plugin/package.xml b/simulation/behavior_tree_plugin/package.xml index 40f5df40c7a..9565295b9b1 100644 --- a/simulation/behavior_tree_plugin/package.xml +++ b/simulation/behavior_tree_plugin/package.xml @@ -2,7 +2,7 @@ behavior_tree_plugin - 4.2.6 + 4.2.7 Behavior tree plugin for traffic_simulator masaya Apache 2.0 diff --git a/simulation/do_nothing_plugin/CHANGELOG.rst b/simulation/do_nothing_plugin/CHANGELOG.rst index ffb67a74fe8..683aaece85f 100644 --- a/simulation/do_nothing_plugin/CHANGELOG.rst +++ b/simulation/do_nothing_plugin/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package do_nothing_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.7 (2024-09-13) +------------------ + 4.2.6 (2024-09-13) ------------------ * Merge branch 'master' into RJD-1197/pose_module diff --git a/simulation/do_nothing_plugin/package.xml b/simulation/do_nothing_plugin/package.xml index ac7db92b15b..0c6523af9bd 100644 --- a/simulation/do_nothing_plugin/package.xml +++ b/simulation/do_nothing_plugin/package.xml @@ -2,7 +2,7 @@ do_nothing_plugin - 4.2.6 + 4.2.7 Behavior plugin for do nothing Masaya Kataoka Apache 2.0 diff --git a/simulation/simple_sensor_simulator/CHANGELOG.rst b/simulation/simple_sensor_simulator/CHANGELOG.rst index 2f6109d038f..06acabf3c45 100644 --- a/simulation/simple_sensor_simulator/CHANGELOG.rst +++ b/simulation/simple_sensor_simulator/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package simple_sensor_simulator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.7 (2024-09-13) +------------------ + 4.2.6 (2024-09-13) ------------------ * Merge branch 'master' into RJD-1197/pose_module diff --git a/simulation/simple_sensor_simulator/package.xml b/simulation/simple_sensor_simulator/package.xml index b143e0c0f82..bf5f7bc4636 100644 --- a/simulation/simple_sensor_simulator/package.xml +++ b/simulation/simple_sensor_simulator/package.xml @@ -1,7 +1,7 @@ simple_sensor_simulator - 4.2.6 + 4.2.7 simple_sensor_simulator package masaya kataoka diff --git a/simulation/simulation_interface/CHANGELOG.rst b/simulation/simulation_interface/CHANGELOG.rst index d01d4e14e94..236ffcaf713 100644 --- a/simulation/simulation_interface/CHANGELOG.rst +++ b/simulation/simulation_interface/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package simulation_interface * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.7 (2024-09-13) +------------------ + 4.2.6 (2024-09-13) ------------------ * Merge branch 'master' into RJD-1197/pose_module diff --git a/simulation/simulation_interface/package.xml b/simulation/simulation_interface/package.xml index cfd1599295d..71dcb942319 100644 --- a/simulation/simulation_interface/package.xml +++ b/simulation/simulation_interface/package.xml @@ -2,7 +2,7 @@ simulation_interface - 4.2.6 + 4.2.7 packages to define interface between simulator and scenario interpreter Masaya Kataoka Apache License 2.0 diff --git a/simulation/traffic_simulator/CHANGELOG.rst b/simulation/traffic_simulator/CHANGELOG.rst index 3e05ff5a106..d7e37805abd 100644 --- a/simulation/traffic_simulator/CHANGELOG.rst +++ b/simulation/traffic_simulator/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package traffic_simulator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.7 (2024-09-13) +------------------ + 4.2.6 (2024-09-13) ------------------ * Merge pull request `#1371 `_ from tier4/RJD-1197/pose_module diff --git a/simulation/traffic_simulator/package.xml b/simulation/traffic_simulator/package.xml index ccbc7d4a345..b3a60eeb163 100644 --- a/simulation/traffic_simulator/package.xml +++ b/simulation/traffic_simulator/package.xml @@ -1,7 +1,7 @@ traffic_simulator - 4.2.6 + 4.2.7 control traffic flow masaya kataoka diff --git a/simulation/traffic_simulator_msgs/CHANGELOG.rst b/simulation/traffic_simulator_msgs/CHANGELOG.rst index 3952a2c8b99..2a1348d11ca 100644 --- a/simulation/traffic_simulator_msgs/CHANGELOG.rst +++ b/simulation/traffic_simulator_msgs/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package openscenario_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.7 (2024-09-13) +------------------ + 4.2.6 (2024-09-13) ------------------ * Merge branch 'master' into RJD-1197/pose_module diff --git a/simulation/traffic_simulator_msgs/package.xml b/simulation/traffic_simulator_msgs/package.xml index 8f74d486684..14b89ebeb03 100644 --- a/simulation/traffic_simulator_msgs/package.xml +++ b/simulation/traffic_simulator_msgs/package.xml @@ -2,7 +2,7 @@ traffic_simulator_msgs - 4.2.6 + 4.2.7 ROS messages for openscenario Masaya Kataoka Apache License 2.0 diff --git a/test_runner/random_test_runner/CHANGELOG.rst b/test_runner/random_test_runner/CHANGELOG.rst index 157b598fff5..e448bd933cf 100644 --- a/test_runner/random_test_runner/CHANGELOG.rst +++ b/test_runner/random_test_runner/CHANGELOG.rst @@ -21,6 +21,9 @@ Changelog for package random_test_runner * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.7 (2024-09-13) +------------------ + 4.2.6 (2024-09-13) ------------------ * Merge branch 'master' into RJD-1197/pose_module diff --git a/test_runner/random_test_runner/package.xml b/test_runner/random_test_runner/package.xml index 3ba5639cd21..f878889d515 100644 --- a/test_runner/random_test_runner/package.xml +++ b/test_runner/random_test_runner/package.xml @@ -2,7 +2,7 @@ random_test_runner - 4.2.6 + 4.2.7 Random behavior test runner piotr-zyskowski-rai Apache License 2.0 diff --git a/test_runner/scenario_test_runner/CHANGELOG.rst b/test_runner/scenario_test_runner/CHANGELOG.rst index 3ce96e94b6a..ba0a21255f2 100644 --- a/test_runner/scenario_test_runner/CHANGELOG.rst +++ b/test_runner/scenario_test_runner/CHANGELOG.rst @@ -35,6 +35,9 @@ Changelog for package scenario_test_runner * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +4.2.7 (2024-09-13) +------------------ + 4.2.6 (2024-09-13) ------------------ * Merge branch 'master' into RJD-1197/pose_module diff --git a/test_runner/scenario_test_runner/package.xml b/test_runner/scenario_test_runner/package.xml index b2b9f270dad..85de3e104c5 100644 --- a/test_runner/scenario_test_runner/package.xml +++ b/test_runner/scenario_test_runner/package.xml @@ -2,7 +2,7 @@ scenario_test_runner - 4.2.6 + 4.2.7 scenario test runner package Tatsuya Yamasaki Apache License 2.0 From 984cb93aa9bd7d4aacc52f946ef637b072349249 Mon Sep 17 00:00:00 2001 From: SzymonParapura Date: Mon, 16 Sep 2024 12:49:44 +0200 Subject: [PATCH 265/304] docs: Update QuickStart.md and BuildInstructions.md --- docs/image/build_success2.png | Bin 22190 -> 0 bytes docs/image/cpp_scenario_launch.gif | Bin 0 -> 4819282 bytes docs/image/cpp_scenario_result.png | Bin 0 -> 125175 bytes docs/image/random_test_runner_launch.gif | Bin 0 -> 8120021 bytes docs/image/random_test_runner_result.png | Bin 0 -> 210254 bytes docs/image/scenario_test_runner_launch.gif | Bin 0 -> 8652491 bytes docs/image/scenario_test_runner_result.png | Bin 0 -> 226197 bytes docs/image/ss2_autoware_build_result.png | Bin 0 -> 158108 bytes docs/image/ss2_build_result.png | Bin 0 -> 134394 bytes docs/image/universe_repository_result.png | Bin 129958 -> 0 bytes docs/user_guide/BuildInstructions.md | 58 +++------ docs/user_guide/QuickStart.md | 140 ++++++++++++--------- 12 files changed, 104 insertions(+), 94 deletions(-) delete mode 100644 docs/image/build_success2.png create mode 100644 docs/image/cpp_scenario_launch.gif create mode 100644 docs/image/cpp_scenario_result.png create mode 100644 docs/image/random_test_runner_launch.gif create mode 100644 docs/image/random_test_runner_result.png create mode 100644 docs/image/scenario_test_runner_launch.gif create mode 100644 docs/image/scenario_test_runner_result.png create mode 100644 docs/image/ss2_autoware_build_result.png create mode 100644 docs/image/ss2_build_result.png delete mode 100644 docs/image/universe_repository_result.png diff --git a/docs/image/build_success2.png b/docs/image/build_success2.png deleted file mode 100644 index ebd2a1efdd7cb05c6c31756cd4d2ff0ad1ac5b1e..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 22190 zcmeFZRal(Ox~@x*;1DFi-5nZ-U?I4>Ly*SZodklrySoH;cXxMpcWG>qfB0Pg7;Dch z2m88aA2iKZ^;K2B)kW9+K2H%SD=mTuhYbe?28Jjm`c)nb3>@q2wGGVsw`XVKirBXw zfv$?G_VT(;gx0oJh9>4fLVFi$AR*A%#PF@kqEgrpVmBkq*E7XP)ccT*7&M{47^K># z9-Ey0GcbrR%;OJD42$nO39I+hPBjT58{_vsGa1UoO%zM7TFQ%?xf=meJFB3#xFMZ0 z6P?h4TEv(;03kLR?&)Hg6-wbF^s0TDMvE(5>Yic7VG%?^IR$-N5l(H5C z8k>l^+5#0^r4{vE&Gb19i1~QoK09;0HDCd>*ClkeFt@bha^@laqg}4I*S{|_5EK4U z#ommESXD}vP|(U2NXSCZLeEGiwm)a z--^J0tMdPRy8b6z|E&o8w<`b7r|bV;;ez|e<_>82wxe@;+q&t6d^>*I_CeZx5mSVD zd$_|G1b~4Nf{A?`~gdG~#tExxafgPHq*Mpy( z-ZJ-<$uX4pQwWbc7NlxHtBD39@ z=*`jG9A#(KeTH1j&Qfe~`H_4yAWuj(p91y3ElA7m*rqilY?qJc*7lmyGs#AbZ>ngG z3I9`GNZQBju`{47-3|@59LkM`Oo`F^ELWA@XWm;i!VfU3%%ms=FsrzN;xi>74Vl+L zuXE>&OhE-dp|i%ofAAA}BfLF*fPwU87bN=n`^DQuNUYx_A7Ea#1pI7VN*3$#q^S;0 z?qr2EdVi5uJ;os;q45dJ>|gtAXiYuxO%M!ZQJBe>*-wPf!+;op3@E0iU9`ZmNk0}v;j_VO?%J%g4&maQsLAvTZ1S}V4E@N;#^E=O7 zzaZa;#0tBsVpEDwaY$V07HX;mhFzT)N0s{{3POk}D(@bNp_SWFf6*i14kI`HsR09d zW=<}sEAYIlG?Ah`);U9QaR8R%o4+8P>+6+XD{HMm{QNMFAoKac?jvC@g3Yf-jY znYR-?lWZ`NhQ+&QEd|%}YDt*SzzL}FvIw~Z8jwx-sWNDfx{fJ4;h}xEQm5p-I4!|a zBP&w?EV@Q6Twoy+tU`!2`ws&B-v9>#_i z9CyH5odhoeZ`QvLy%(-#5^^L~lS@*Ec#*jBiVhX$86*NQLn`v)S`u#<}UO_SJ-FcN_B6mw_%%5)92M7 zO$$wu>}0zHekmf?39JRcl3eY5l8JF4b+Namygo+B|Duj#SCh}JCK!y`p~!R*qwuX>g(JFluO>W?+}ZsA@M1! zSe*npE9}YpEXktD66KoCAjwNXsU>Eq<#!_k$qBT4*+=EI#<&=lOUuUclXer#RKDma z!Rm$@Nz+@y&&S|GA9w9l&-&ZrM{9)@O)sDvm>mJn`Blr2w8kv<#I+jnHu-8^Da4B3 znL_tC%WVUG4tXb*T*@S3w zRInq=h->4Tc$YQL>(Tl~^t4!-n{Ir6xRi2AS9goKmRz-1m>k$-F z`qO5cL`xRE*aWGhW~A3;ly(-{K(=xRtaogoz4`hK>j=|dJubz;0LS)Pnki}2seP3^ z9?dSloLo^Llt6@8Z%ui)QT3|W&2Q9zvJWX1cr;$VDCOv=CaM}QM2na3L(obi%Tu+# z1n9%LRhht#M~(m=Q$?#2N6`g-L*^qnH+2v6khrok(?7#YxqHU~BvW@R>hOpUz2}jS zC#PUv>zg1A8I0}aVE5a{ycl44n=vGS^Y=AcZckQ?PStQ`d+yrw=j7Mz`vz6~ZJKCT zlBnt^lWpTlvEVSm!$pY{Zi=KU=&bZ7W|sblJRarA^QuZpcl}GL&&V)*jp+*cw%U`d zSQdqo4IVsr=!rS#5$Vcn%|DOC81TU{yn`o5jj46qO?pcM3@BILB@4thR5WulA9r1n zt3oh07J_t3Ls_OgR3D|x96g^trb6Fzg2KDzS6bTFG*af9PFQpY8X9Rx6j}^(r8dH7 zFtnawq(`H5GBjF=g|L~wSyBWwjO00m^98yQ>y_mzGyp}+PpH><^6(^_@^_&$UsNWn zHhY_SEy|Z$Qz5ZzXZHu$4ED9CmtfyUQeT_HY&ZKg1KfSoH(RGGkqC{uaz-C{02^;W zwiK^Oq27k+19CPY06LCva1T8HTwgD|NRh?69RbhP@rNz_d|P$&#*w?4wCr|=Nj&YY zgQ-O5L&wh@?<_;N)(Y`Hk3^h1?JSyS)0G6KR|(WP*S3C7{ib)u;lzOV$shHJV2jmr4 zsAS@C{NUHTmi%}=kWZt2SGytyiaA=GBVmEHs&nQ;`ybg0xlPEpTk@|=P_*Ky0-&Ag z)Z1YPl4?|>FZy-^RlO9Tw%pZK6pg^GJ@AlTjo8wtJWY+-Cv>-;PqVg6`LwJ*QCFFj)Ou=A(DKf7oREkL ztOgqq70%ak?R4BX#eqUlP3}E@la^T7L>Svm%=aklS-iqDXYa0josia`*~iFS5hJ-S zed?_}O+tm?9q^8(v;k)TL=@IWPsf5b?&@S{PbqxjO%(>8Bz*rJ*le@wBfs3cqhHCG zDhtVo%)OfqH~3Kx7$Me48CuHx(i$>B#?{R_UqjWQCbt5$3jL!rZS5Q!tR=-R)aeck zrh-pB+P1UZ;yG$BNFy7pvWJfbT0OrXq&HOl(h^zJ@ap@PPlRx%)3@DPd@eKdT{sk5 zwpgbMHHK7nWwT76Yr$rxL6npt^j=f@0&s0-J6mIcp5b)B%9e`=H7KjWJzXGMIBm?r z5E+jh1F~{%<)`6%Wd_6u_8vT^G(1C}xXv2sC*ZH$l@9(|QMhP(H4hI-MgsP{pd{d@ z^pB^@*l}b0;6HzX#F80kIS8~WNQ#@G(c^C=-0Fa+%+*6@mTSM76FHd6^3)gXJW*M< zUU$_7H3eW@AhYlkMxRj{wKJ~?{}uow|NSd-0N?`RKwWHw(usE?`-BIq;(vK-ET z`?3{le+)v*bvhy0AR``aLG7P8KAkSJ5`F5(h}X#?m*C~94V~NPVJ8hJKR#u#RD<1l zXjbHNjeW=gy4ZSq2lh{7BGgoOrA$qkXn-O`(*l{~#l(~qN=$*nANNF^Q;AG%`$uQ_ zne;=_tR!$a+j`sV>ASr9FM(^fFs%gh!H${l?aL9?k^R?=DuaUncnKRUa93@;jON}n z1A6ga37uuU5qzO648!u&tGVA1!R8bPT};IDO|~TlMJx!6HAm$K!I6A!A+_+t9}&uB zFLaGlWJ1tC>nJX;C4qq--ALB%+W&Y>@vcIRQu0uKF~j;`eXjP#pmT)qGb6UI7J(n4 zXgBM^Pq@Jkw|I@@NAIN^rgd*|>wv4*YY*wBc=U3vF;=S(G#&v{c~wG(lMc4f;wh`c zITKzR9z4%I--T3w2D+lr6;sBJYiMols;5AlZx4wd*NwyGpfBY>MmIB0uWk4ZDpRBTrCDrQU;z%+dUg}V5hjglhW-{dk*zh>D^`fBoqWXVUK;!c{d++)SIF7%)}m5pN=jVF!edf`8sis3vuC~E zkU)2e#TBR9@f;cdEQeMH1hlD+8VqMVl%(i=2YF(PsXTLhOuNz4Xn_2c(pBp^bx zH;ar4W0NqjCel@N^?Me=3<{tQHAc-J?KsTd=TuF-AecNr|0>VXj<(&8FYY$K8y$Pn zx*d4Eu(I!mwD_-=rXWFWCzn`p&`iMf8{d zTtGvrZ)XYhhzMf#ixx&+eIS_RA6$ZBfc{BHjJo!?f1Q4dQePd?!Ie0&)r+|;nTMW= z_!YEP?M@?{zBZJhUIu!}4=Px5)#G9QaFIwsWc1brN4I0(Iz&%|JS&a9<$aN0J~lqN zFiPw>e}H)Z8z%)23jWbaN7K)GqTk%~HZB-|Hb1p+%a1ljpsL^s0ll1Z=16rRg0a3I z>G2<^X4RKaP~bp!i8KAd9^CENU0Y*m$Bq}aD`PYCGlh8uJ|`rJ=id!m-{@;?fnI^>xZ15 zaluH59k%~C#GbZPl>=*FT8 zoIh4oc!}>!DevIt@ zd<6nq(^%ed=M$5%Rc;yU5p72%i!Gjz$}2LIwhdlu44wraqFgTF_C9{;l8a6(_o7N1 z5m|Sa_|?UGR6qx2+b=0jjwY+VN}SX4Fwy`_g(*ZPF14m5kjkw&oCG zu5-I^g64~b=r^XH8jiCUO?$yg-pPlkjWg0$&=>GHy5KGerG;DV8< zICZwalznTaT-Qjgpo(><&{%`WjD)xAtjXx<1a8yhi0;lGce`hr-Y-JEihmVeJp4z^Y;>%O_7##{*pM|TYUC!7{Ct6>H; z@P8mRrC)z1H3dAJY9kYIm}HUIInx^LjFcNbpsgw<##fvoQjOWkllyo!z5)TPNI zz(6&kbz8P1na9$EUeY{nO+7|2-96x{g2q@OrFm@9$wK0_!;I5@8p3K1k2clzJLHxh zOF{M)B6W+pJ;4+z(umQayHT?=SJkK?5xu+w2(f@_&2Rf!%}~R3Pw)@OYqtCq=bF-x zu9Z>HnSykLhjl->FcKh6*P3D3E1mahAIBX973wG5?RW$@WjP90_$jWt#w~jAcHH^vpPh&$NNx(J8!6b*+XVFH3OiF8tWyaLck>%NIQm#}wgh zjZ_XpfS=|5zH3QI5jVO$|I46~l-cwywY^)ZE!yE1+HI@L17P5ixe>`MxYvfLZ6uVO zj0b}!T3!?-97HnY88l(v3USNUkdnad%bE#i`oxih@>r`k+moaNTx*dlN7$LKsx-&L zR&E*?rH6+-stm}5V7A`3keEh>PpmO#G}8QpR?xN70vBT^O_qHs?*iwK1lvUz&;X50ri|j3RWT1t}si3xfX4n}vTqlG5+kMyd zSYVR|F?5nDXo#^wOI)uRX)NHJG#mC0MXYVp1m8Ed3M07aH=`L2k?|p)I+Rej zwUmGw3Y%Y4YIl?5jysheX)+jmr3OhYC(Pv|#x2!FtG;l9)RWOTiV5In*S;b;Hx(Iw zzDA=fBUF(s>BX?eUdA}`{6*<>hMHeX*IPRW3%-SaSReBF<`ZQXaVQpJ9a_(_;Z##! zdN)rZVoREIFu)*zP~;4Zb0UTB!*kB*IH6$Dt*Thp*kIOq=)j$*a7)+`Ql(eTrk2B+kJ!0 za;LY3<0HQ<5EmkWnchj&hZ=l%SIAB*Mw2KUMxI=~50h0|xXSNWHW6Qv(eE=wuQq%% z9fy7813LsIG;-^%9~<@vU_Wj7ssfs6WYT|$CoLuD)`@Iv@lw(?5fh_I9fC!soUH^W z8$qNpOY(Jc|0J&uFHTLA`$0rcd)COsVjvy)4JNt!`)}LdFcLxPlbDUwZu?BgDRR_wlQt5pW82(BMn;fxDUJEs!|r{ngo5N9&|-4 zG*iT#dgH&6A@(1K2iXC%{=VSyrZahs0DPmhdiF+Yb-AfHhgP&gEVrN=AMT1fMN+K8 zI)(RdxGb0XPI*TOlAcH4iRP1!E5P8sa(Hm)y0qL_{7lW!{-Nj-a2VZy%urWVk$6?M zZVz;Gs4iD5iYu~`onA_8mwj#*4*Y6GQ*>}f#QAu#uyKU<#pgY&*t>!m;|N(w`$tEA z`t1^Ktid3_`TU7EsMfK%ur8<^tUz}q@-UD>)dkeEUu@h$pjLl|QRFHK+)jaSZlOW2 zgH2rvK4YU1ZHVp4e}>ml=vwi1-*SLA41IqxidHCB%% zd<32Fl1Q_(=#bNLGxGkT7z-l`E9ps?0I24)r z#c%cF$MV(2K%3Z>1x9^ZZIv^kM6V8*d{}kEknM%B;+n#VUkEif@S$+A;-SJv1ugfT#wi;Bx87Re5~j&?9jBj%q(-){`TVIG!;C^rlH{e>;3 z&)(QF);B)0S<{B@ke!XxeF+X1DTU%%9FvGwCBQ3VqTzYl4-zF#E3B7}hKDC7UnNmS zJ&uBcG9dtWWk6P=t)G)8wKiA8miGC9LW7!Wz%)qdSBQ(i`_cg-ZViZ@kaSL#;+hnK z&x9J(!c5T^IMWRX@Wey$9!n&YQ&kuzuGhIfK(I$#?*Rfq%0c^Yep8gguh@P4uvQf9 zVB@4v)|_7io~@E}FGX9UOqi2c+Z@qxT3Enf7*KP6CY$b<9Avjz%s_@YOrf^`8;-1G<+0E)Mf5f zJI2?=eq>Z(qT}Gm_3$AvA#}1k>Jrj!-I{|M3lM{GA@t!>N*8;J-vrIR47gsEY{GPI zwEz*x%-n*^|82wsx77(T4*V0slrteRQc}d+I3P2*x-zDxZV{WQ$_diNbVJsj$wb)6 z+62v}-iN1+POp*T<0iIG6g<`DhR@8yy3?f^{?NzGt1;69&F=wF1A-d-M;(!DyEw`R zeem04^gA4QQbv7d3I?h>QXiJmlJ~B00NmpP0%U~cpuRriK7~n zb%=mk_E0%uHd^{Di;H4& zygz*DAG$3FTmmHO&>8^@$K92snfN{ULUW2eQ{cv2OMhv4E05}Gv>e#$)F2%}!~WzL z-agCT$T1_?L%^7w=ajd#WH3C%3nC_oTc@ky0L>}AExu&1=Q!r27u?aLcL&GSe1hsP z0yMORb2+%69crefmMdnjc#lgj_a%=tJ1jr;Ls-})3Z`CX>ge84{hqN1*9UZ(5{z~C zs|Hze_8|CtlKn}A&OV;Q1+cHm>A-5T1Jk!%$&1<>$%6k_hxjU%n&`i zx*pFItE|7UvzTUQ(WZYxc5xun;TAjaTU>kXL@<^Nocxqf%wl}HMslNl>&8py5ke>a ztsp`+2}4LmvzhdRfFJ+4m1^r>uqPc6 za#t8tR*x97Md8V{mignO!o$3G{orxXpNa!cP&=T5h;mJpdza6ZBzO>!(Xs=?oe95^ zZPR{$`5Hm=2imS{eQDOF`LXm9Cu*+dtXIZC z&&a63)rPkt#o@j7sS+lA6=pf;y%hK3-Uv{+{uX;rXwY7V`+s1r{Xb!@)j5{s8|J== zloGrJa1Rhm*drzyHJmFHEo`O1eEqV? znRQ>~0mOVuOk`vmlKOu`xuOC(DW7a8j`~vaW-L7ugzE?bG3)s0j zLTR#MfHpcM1u28qRkw!F`VZ$A0N&;9c-Z#raY7Lol5br!U+sUIjp%DTS`HZDhYQGS$<0EWeku|OpdgMi$YnFqJ(2k(IkCc>waHR*Q?nnb*DJY< z{!h4e*iJ(aD&&ZaW^!|+cN23je5<+_eM*msdJGA8olnRev%&51GWEa7u_s3K;?a^g zdM(bJM?5kYPLg1)CYkr$O;v^lAJNtCGjO#|-8zQ;<^|}#nPS&LoymGkh_g24RoLU+ za+pkXV1u`bRG+lsm!hkcoFT>69Ni>y<2>37z3Z@`)o_iIoJyL$-#4LqpB`p7V9tE& zxbMBvErrXwDfNw?v=I5#w*nsWHBqwnXqKn2FY$2!Du{acpnNs*2SaLPXuk+;9sQPc)eDDE!S;*~{!RWb!^Jx$^9LZuDM})xByFK8nSa9GYQ0jQ z%R1vLqz$s938OixARb2aQz4>T)(pQ~NgikUEE~=qXO${Jgup-?1SX#m#MNY*QHegT z=|IRVO)X=c9o(oLMJ0=Ty7(_Qy(^auC>pHT{0avK*Ln3TB_5uvl->18z7WWo)1hX1 zzv}%~One5n7R8A2|g@USVt>?lN<9jO$K|IZ?%-3xzReD%lEkqZ)h z7YpCS3zKmJbq|xlRg1!J3n&^*aL(Z-eUmGNE*P*6IznxMI9H(R4%#eGHWlR?%RF-4*07VUO1|}$9wEN4fB_P%K+G7F^hRGd zzEYtvq=0a0IhJCenFJTJkrX6#`@ev0L(gK_eUKR&GOsf7M@9|e!Vf%1> zpZpDUbH5F*A2ph8FvlfBtPtaV{jBQo*JOOZ*GvE5$;ms!9QpVvePG-m z68+8)gR(f<5;d7fuF3$GbbA%^9;{3Vo}1$y`LEa1WE#S=d;kJ6cE@Z&3f6@JX1fY*9qBWpf+qmR+3nk<~(Nk2^A{ zB43rS9?eZgC@RyF8)$Ho{{^CCuoyxP0pMGtJNMA2GEBBVOg2H&fa!TfL$Xj`p=o7*832(N}5toh0+v6qzS=ZXZknc(VWg@L>}fz z8OX-Aw*51dj8utdAB~m3VQox{O4=10E3GN=sVVLre7}DFUhcOwsUMx z_K`g64y59DB?66EQkb4;22Y(&WBE%B<8wVd1UJi82&rEg0KWb*gE3ptY%^>7th^&F zgh-N@U+h*@R)W%G}hho=Y#|(-936=>zqZU;gdoSoW?5pIeBa&gsF)hoz zR_SBFtg67>z5FEiId3;ccl5wyBSe`qK%=G$b=HK2xxST=qBjU4MsHcR2w)xp20;{kZlRa6Fls(&KP2fVqFZSIpf6c z3Y3Ewkh9X?xMf{F`5Zupv6D6&q3dr8BI!cf5gI}H3AJ}FRi=9l2a5haPm50OKxHA@ zZ~W@;dltAZ6kBm^a+Be%2{RF>Cff{-2tvwtdr*B@#E96tYS6`9*pyil+DhOg@(shw^=0pNH~Brtaq#nlD-~uTGL!)0sPe?t=VMH@cm0#X9MrEF%~5p6uS> z92cZa`{Nz5Sa3toTIEH_d}@g=gb@nkBZc28?$9}rPa<16y3h<3srD5xd9PFi2)IaR z`aTgDjcIws7bi^}cDcb5RSLSeyJ1hDWw{eO|J<%V22r9Q%CLexu9g_@&;6em`L;gr zSZ^AKDOo!fVIb&oufJTZXq5WakPC(rf9Yb1VJU9Pm_@kYX4Jk>Gin(ZfCPV>9 z4mJi^J`nL-&o2F=x!sUEaeTtf7N!wnER&!YaLC>RKtgL-&E!|Y56ZT{(j+q@8EAH+<%PgZyo%-$F~mF z2?PMSJ;ze!Nv}{sKUrRYTIhd8c_P=wQVlgd-(FMYWM}uF8KAt+n^$cOB?~+FcHUM|XULbdyO7>}9;zQx5dGczvaj z^25;J0+~JtKH>MKv)GP)TJ3kIA3qbzR9W0HxZgwu2pMF)Qbl)lrb&xGc)qCQP0GGr z_+&vUzh!nXH^Z$4g~HObzNE{D2h41>eH4s6Zr?u9H;!mdCu{N4b3S{mFbsyDvn(cv zZ!gzl9ZXJ=D~uxp`C5sI+%zW_e0gcF6}DScwvfIP(>7?!2@$v%9d1SMk0g`Q!7>=2 zBEj%!;}gY6n7XJqQiIC;YB5G1LXJCfIRoZRpXgwtGfHeS#@v6P|A-qtd=r&Y zA=YdTY5Jvh*!1Q2nDK~8JMfk=_phfjvZol0WLh&HJ*%txbVf`NfPrx3p5Qx>p64lwkiJw#|r|5WfGp zjhXJ@-`JR;pa>H^#x9pKaTBx{bX*rA;&9wAt_WoCT8!eVtJQ5F=jQb#j|@sZ3$&SRbUg3df9%klx2dz&=U_y@CBiadn*ZElKCB=Wu*xHS(Dq zoFn~{w@L}ds8RlSbNy{%KKyA{q24*l^Vm<`!OyE6s>V46K)((5-5OS#cB8JXTj8E5_JNI9`1Zr9X5k$f>`{ms~d?o}^ zWO&DP{4E|-&nzUF#fuPAyY^?*aPe7wXt7WG(q;>d_HUyd*M|2QY{7iOYk2$;k%{(* z0t2aT0GM_PM3DOW;6cGPYpeS@)A_3^=Ko;sWyAu4+wt46$Dm0V*&Ztc)S|Fz9;Lr+ z7Of35&ceE_r8Ez8{;3pQQSk26)n=5&pFy2H+Z&KzthDOWdSOJK)A)cI>9tX$l9*>v ztk8*`R8taiX$;q3MYxf5PdecUsqaXA}3=R!`w-`_BJP@bfnrn-DGT)k@Y*Xf(=s29t>--{AVkGa5!j6nfc@qv-Syqdlw*yP9CRN5+x`Z#|A&c z&*pI4{vs@>`XB=D?vDV}kfqPq5YW?HomU8FzN>;qS4x=DZ6Sfs$qoLbBg?K&G3CWI zgg4+VEJ&f(A*l>DR#&hhYKTl zM?g_s*_jg_5?l)k>vOwR99~-zoo-1VRwLfh*vp8Q?UN=ga`i8z)Xvc0AI_Lik(}j_ za=aKEz65A)in&=RKL;q$65elreak;wN1F=zAeb!blOgia1b4ENuR)x@+Yq_4J5(H% zsDv+c=F%a&t1Elh%pUnFQYfbg`bi!OXxO)XSn$|N0mJnl+v%7?<;9_Ik^BB5ix$u8 z;75<|+CqXAS#EiCPEO3|&QEA`GqoR4yM8gOBc0s5@P!pnWU&!hLS0GogrBv>u0GVS zW4|wjzBkbmsdYOUf>(x%(v9pzNLUKgv#dH;*^=2z%V})UzGP(0ISe0Cy*48$l{p(5 z9#Kh`dcYWu%d>|zf3LLLdwDusjyx1y_5*80@tM(U`RBj5xCci5#U+q2+f`CcwQRGK zRZP$^;F5}DKcy^&EZTx1rar)8%d(IoB=W)Gq(QTdI(2DoN+429{GCnRUvfG-2gLQ5 zQr>x&J@JOeL88JW#rO|f^8RjiPXQv@8oGw=*er?4I!TpI8r1y}x_S?1`(_r>>m{DF zs$OWU>nBB77vnN%`(N^nS)i=c-m)wtoMsF9Y|%;e%#TB8q=m7Ht`NWHH5CdgLk!ul zPRb}u@iE2m*=@qE&&E$ndu%#=*5*Q*Xj$i%fX~kyuxV2kQA+fvVE{JzC#eITp)h)# znXHgR?~-m>gkbS*98)_>Evd_mt`r@XaJIErqq#$k1dj_&R(w$9k>)HsP~mf`>e0il zx6*V?p3#u`viU9A)g**|!_U#P9;f7wIm?3^Q!iZOhK?NCr8Wo$O6jJcN6~>iek^Kg zmiD6Np!Qsf0EYE%$^VjX@ICZ}+CEyEe5`-xfPl*3$o3TbF6A%g@UR0{C->Q%V5{qE zxvz0uU*5qU{$VW-T&YrZ+o7Sy;~ZS`!e75n6a}nBlFW173oE?J3imZvfnR>042!4k9Y&se_#Mq&iPM_ro04M?ad9t@{AY%6 zLJU?@R>~Wo<+ABpUci(k=}U~9V!P`Rd9Tu~VOL0nvsR10!3z{g3b}F1D#U;-RHMLwV1XH zDrYPIxOSJ-;^*_Uw^HfA?HD>OntNhv9*F5L;LXMK zAo^Jo3S5mXh4Y{PxLkBnu(NXA#3{;?ya{sgpPnwvAuXm-t^w=_w3!<$%$PP!_yOF-zhTB(PWrSCPYId4M}-*Ne#g@EaM-hC?I+ zsH7pxRCN68r72vy!4b!>K2(feA6YDIN%ZWF@pP*Lyc|WzAe#*uOMFC;uFk`~;iI|| z?;85Ua$fm|<-7*x>&~lC-uXG!me|hX1m2V7R5JZYJnDoohdxNfU4p>N<*)9A`s=tO zmoA%uNL}qjTldL4klQ`=N%1qw(LAmz>#1n?828j$QtBGijAM647L8LI3i~V1j#})B zVc{)?nMMHgPt}Q>Nv0F0kUvQyN~wEAbY4VX4XM8vLhqcknEk1jnw`7td@>Q>UA~Un zdcYc@E#QUvA=$Sxhdvh(j=jt1k*nfP&&sbPH6-W!TgRG{wx--6yFoih?YayOFSKi) zt*1?POFqW(OV^?47iAsK+f0}UoZcTw_}BLy*zl!C8}|4m!cuvNr^9QGh!$vAuIYD% z)7G$U0l0%scmv~kR4MyzAzy1Gu?!!pJYKL`)%b#?9*e4`2K@WG&11;pVki$;8J-uGYO#+B3o|$MtA=ESIuatf(!)R zH6l8P+eKGGQ^pc)*J%#m?AlMUySFx1ENP3Y65;3-z7ZA2vl z^ujGDRR>A~5havfVF=0HgW2J=Oa=q8Qq5D&?@1Bc9W~kC|2hnBi0ppO!Tgf)$@Wr| z!-Sz9@GjnlL`};9S-(zd$8;#sc{Oq(jw^DD#GFZ;CH7sF^5hI*^t?oc%a(Jc*1xx` z<1d*0yNu0K96l;_r}Btl_KYUzrP1$ zT)M;+!_BRwP7f^8n3JP6e#r$O%!X=TL;Mi zF5I0#?hS%_Oo2j(XzRul8kX0xZ~UogeDX&dta_G4nT*BaS8`niUUR-wmYWbzXRqdZ|Is_( zey8)6Yv_fCFrSb2ee}#qq5iS{43EjZ;M+t@06NQ{6zhq@!&(O70wsepq-97a@2qy6 zs`|);D0fQR1ZDEjioBt2gnPRC=(S)jESD)~xIuv{{UjF|!3V#A3pQ zbc%!99EjvT-h4Ho@tK@)p!UVN*M~xeRsurE(HOG5 zEc1^K{=1KUHSBZ9kp4_7tAn`MnXuO?Yjy0{4=dq@Y%jEvlaG zw^;%byaT#VL$#H%kj)+`Tf@l4c^uMlg>rjkAc|_l$f}oW94CC5@hNJ|ZoeB9R9Ees zHx(u1W_X{{#Y%<#+Vmr(b-RE1rH09soV`HiV3uu|!#-ilrsIAEw)I`njBr`eE_%Wl8zn8^Hq|NR8;u!0t)8PhcPPX(G}KD_+Do$q~U zuHEhz3Demx`bFVQD^~nb#5$Cxw_1AFSE30cgW=z&9v(}^XmF7AV%v~coxH6Zs$+Fr z=h{Dx{eJ;&QK6+x*x+WqQ@`98Hisc;@Dg}b&(OhooRlT za<1K15Vn)9MKySl>TRwR?@9C_5n)B8@L%z$L>Q1IUuCE$V`DIwP_;}WA4cvYqVF{R z?uwqL;%@lOVDj6WZC+{JBq?^E-I(X|T=wBvR}U5^moDn!_Wnkhn@G z2jJ6<#AfM##ZQp5;{PN5lv2$LyK2{cf!)MUnEWc>S-{-A(!`?YxIMh%dC6GS(B zlHz@}97r2FoiBfsHt$~ALN)WJCyVjD{KzOGr0}@Q+a^9Jzf6Fy5eY7Qih(zl%_ZB` zvL!3#yELFw^Aw)bwV2?b->z$z$jRBuGLna*+ALh%iHW?R%sg<1KDMysWO9Nt`|@%6 z-iC$b)}p5*n6<6ZsJ~b^&VBpAS9;MkYjKdpLL(LR)#_|`%ZzIZ>?y_0>QhmGv8*X< zCPL;QCf!N3_)>v-Z&Dm>?R-!Xpnx(+mn&9I;8(7mg}r(t^`!C7uaIq|^+YC?Ur>o* zBZZ=p-A11xVHU+lLvdKA&K@40Mjuz59$N33*BbVI!LPWniD1M4H`dz+pL5NouU(h77kETC0w` zp`b{dNrlhsmhbiJO4fz%A|XkWSa-u}RcoZRVIXI2dSsMp79)sQS>w*fqtV~xe?k0! z-CuxZY0ljmPy3OP%nrcV@C1UdxV6XH6v?*?jUZ8wHRs-{C}*e%qyKgvk(v`5j>qwW z;~UB|dRFr7fG>S(vN>{i4O559qt;!wR5fmKU8=b``Rc0e{l$d1;K3L3y>|YqCXP5O zQ_GOl<)3J0H@Xj{$MW1lefn2Va-Tx?eWz+IG;0WhV}GJSz6n#N1U?X6VW~Y540FJ- z*-AH+EM}?IPLFaDrq;8|fyE)p_CQ(Y)IJBgIW;p%PL=|A_Ai`x*g~3yg_-(ct8P+6 z3w#uj3JlQE>XOp7#J$0HV?QET_w^GI;l*G;NrL{=NpwX!NpOc7!X6iwmc2b**IQdN zfeAkX(oxH89^#mom*;KG*%Oma6&pNQc6?)jx?Dr?yzo@+O2m3ASiux%W)~`K-=liQ z^7T2Cnd98YxG+hiZ2~9_5p42Iqyngtzp9`%1kW4|?%q6MhL2Q1C$LN)zOI9nnw&R% z@+h6DlTIsQ54YjS`7Y$4(*?A_^+S!&XcIU?YWVq!V~|cs|MS|w-H;K?^M-Tb+Lq~s z`!TL-^KpAvw#|{8Ej~O9LqvnyUL6^y63Mt189Wm+ zr&tI+^3T>pvvp@*o04SYoh&d>%udzrui5&=WUgXDgoJuMphS9s@>d3$DTl;zjjBp{ zRiz_U)swkb76yxgyqV~>?gtdO%R9lZ4JsT}d;w=p?@`@J1Kr^*ON7!7t94_e3bddX z=krj|qjKX}4y!haOD2pDEGifK#0P9m%Vx)eBR`O^}-M3{$ z#CiMeOZ%f!dZ!W;lx)nP3gp$px7$S54PGa#t*!qRH3rK0d{`59^KM5*i!7ZU9VL{M zRM5wfBrsp$8*d-JI`@m+z?4J!L(Oh0!CV58ENj6OdE(U$Y#h|ZP>*B?#V>5Yg zk9 z6srQk<6dOgJMv5mN9^=Xaj=!pJ3d3pb~zN?xI%LJZHww<{a=PN$wwk8(M00`6B*Yf zi-Yb5$WVZiL=15zdJh}Vu-KiPO)WsK-Hrx!_tfge(QI3Mgx+g?S--ax+XEs<$|y!x z+lj`+5%^ug{Yz_63I`{7Vp6uUWZPD!uQDaP;E9Xysr^Zw1>&1(oT>S_GK z5IWdET6rO}pY>};vS#`^{Ohb|&kylrn`%(sr4cy?0tipBVxM1w&g#`5Hf{96e}+FR zz!y}Z(z^9c+48~d89Vf(hEr6&*n{Dtp3oC1;w8eY>;U+Vlrderx4ixK-n4h z4I+c0DPA#_xwCJuBkUSxhmJIm`PI={h4#^s7gm;qO(#6o`ZCfP+@3HnaCWps?`2rq zUs4lSdi*t$+!{^j;yIB~?TqXmZ~(1?e6{FfU7gKb+OnPKDf5`~sYK!a_X#p8R=1Cq zT-Fw=0>NWmWa!#@urhQ4&UfzKVmUiUC}eK%!fonti#9K{xEAdvEMQnOdkT!v>>oc9 zzp}T;F&o)6W*W6WnS{Il2By`u#awWUob*`2lk&@3is=E<@wo26*l7dtUNsWOni99K zr*J-C2|w&lAm>+W!c{`1P2_Xu-Avs&hxnfJ3BRF1mXbm6gt63IItLG5KL*(4lX@n# z^mmjW*A#Ge!6?REo{GTzog#6Va(q% z4mmHCxJ|wUeG^ZvszskiXhTipb84O^({IjU@|0z)tgn)F?k6@6UB;&Jf0ihuZJNc0 zPV;%sdog~q?NDy#a6LYXLkR`i?V}|xtR?Htg(XH#9ZsbGP>F~zBbLANVI_a51tdqD zBx&d%7VY!I)|^Y)=@9$}eaiN*d@Ji?-567@e9P9IKCJf0W&6q_+$%GdY7MOMDSszUH^cW-aYWUx5TUbGn$TK{n_`)8uKC_2Ih;16NtPJ2n3>&A*c#= zv>o~mZHg|Ea;*T_!I>8(jmPz72(ynC2=fR80)apj8G@=lW!9rS^!%GrS_C->mp=0T&{%osl%%Ha7in1!{f%$fX4ny-EC2^V3o z$B@VOxI`cj2p(JPso%Oej`k1wL#Rqoh7se{LSd?hEHbnd4_dDi{0{ZFFo8fI5Likf znHLQjzvLKp+r^B13Qwk{-3S6XsW&V0Ms%Jp=-QK=9b{U$K~gKaDLh QKmY&$07*qoM6N<$g65wYApigX diff --git a/docs/image/cpp_scenario_launch.gif b/docs/image/cpp_scenario_launch.gif new file mode 100644 index 0000000000000000000000000000000000000000..fd07b2070da26f25ec986c3fbf869dcf67edd6d0 GIT binary patch literal 4819282 zcmeF2RaYEL)2@Nw?hb*$-QC^Y-Q9u?4uiYv;O_1Og1fr}2pZg-kj#GG-?6`1eNe|; z>*~9D-Bof5vit%TdX5V?Jj%%+hs_>l!;k*$f5BY08hJ#pcnad9zmNz8Fg8t@2-3DnXEHSLJLxe&t< zkkK%Z1L(gJP=6J4001bc$dsv=IB6urXer2OCF$sBSm~6M=o5c3eWhb!VqhlZW43Bw zVP;~nRAUwAWYtt>)n#Rk_hroovmsHjAycs#S+e=KvE_NNv$L}6YO}j5u=|g*r`mIb z8*@a3aik=3dbo3u7;$p|xOq6Zb=CP$X!#TT1cVp`w6X;A^MuS)g*7#VW2HnSMMVOG zMG;ZO@Tet8&?OxmrKuQY)h*@xo#Zk%tZKswYHkPHumW>HkRu)#EV5^2&YZoVL|8LeA z={DN7HV&4y+G4h)y>_iLcHJX(J&X1vRE~@cj-|bh4O1=vWKTy|Pd9llXDeXoh;O8y zpP!F^^GqOVP*B%O(9lJ2esPEyQD}TB2!IaKHwhC&iJE(i8CXt`6iL!iO4DJ;7;ny$ zLCvhK%A6m_%F4(Z>CZ06$!;pjZmZ4i?#S`r%$XR=onI+z{a##ATC#Rk79U@sg<5g) zST(v@V`5xeTU{?9T5rbPR213V)zK1Z+p@ObYK7mnKGGq`+11t2-QC&i>i+%5_rA`$ zetY}j0J`DZrxB3MXnEQA*6IWg=fvLLq=eX{IoIUm*wn_t)XCxW>hkpQ#=N%1{QTHL zPx8XX;!-r{()RkYsnK$n^V-_VMzhmqf!=ljX#3&uXKd8ZpIf_oKY!)O?w=kVZg-z) zlU+2JUGxNA_HZ-#+}Dd$`+uc({GMIC*-$ zeR_U)-Yb0m_xGj8?X}D7_4Vxa_35pi^KBLM_V)7r*!&0j<4-x%pSQ(7pYMPE{rQCb z^Y7m$1oD>>f}$#;ttBO)F2l*n{^dUupeWyA;gF#apqT&1#{V#h{$KKcko+Gc|Gz?l z2!RqoB$aP29tuaqVKkm>E*Xi26{62LD+wQqhi6din`|kYNXCZ?BUNZEpNgkqZM@5A z9Z|%=H)_Jo~7r*%GTN8&o2FXR{6iD2Na)X0{N#g`#&r`M=ph?T`-d_G&wR5F?t zj?-b9%u;U3f(=+^+)B2asihI{yw=QM>Vr8s*Rq=j1O1k%C01>_L%tD_lK!q zU!RRunI_tkcKz%1v92el>E$X{8CGw9k0*-6-;l0cp01=RSnj>0@QiNMSx{Zk3t66o z(Gn%!rSLvF?70d3!IO|2MLZgnpkqSLq045KSp|0#!b zfx8usS_%(#NJxDlvL|DoESCA|vAG0FlJO}CFHxul#9|l9A4amfb{i!O8Tc+Cnafn? z#YpNz5rafv1difi!=9<4zfZ{@rHYkKQpc;u{U$Q3)6o8zsc&0zl4b03ev)k-#qc}F zI*TDM6DdeK*M(RocU#u2_IW=>MZ_kvKmuAO^P7lDWVROm`MF&|gsJqZlFBabS*hZ= z1D(3Bq~TeaAGV;5R=h1^W4WfRo2KrZ_ zui6SzSyvBY(9LP;_DQ)^4`9sMYH{iz(v+bTh1YDeF5p=M@f1{Bm^23)0ur_hHpQX9YmwU|0km+Ej^n9&|L=eS!?Z#AEDyhRl1<{dLC^<_jqqGR$N4 zH&5amx}uPMvMLF`WgX{T;Cj!--5`M$AK5SgM9DqyLZQkmgrYpV!2NIMna4K~$xTb$ zX`hV!UW&>$T|@HU#^zm^#5%`S!wzG|^KueDtsN$0a~?rT$WDVOp^ zY>z|bVd%K$@UsZn+|;8Jy{%ph$vQfm!mo*bydN@2Cc1)aUiSiDA=j_JLJ?Ts_Kk-X z@-k-}j~fo+!&mWI8D$!AOUWw0=Vk#PPgUg^x-%D=<%aVPrRCAnXD3k}5vO|KO4It% z3cY_=y7Co@wU=ERlS@a)vX{)4gJ1l#wLNxmGt~ktZ_>?&4;`V*`tYMJo8XHFnaug8 z1X(u5O&M8^DNV-t-zvk@j#pW9ozh=yvgtox-S)C<-z=B2Tyq>-rj~XU;&Q0_$;~AY z-Uz@5o74hS&4Y-DlQO%F)cb0PssJphjooHLmw!DE^3(is4B&oMdIAL4pkPdtvvW6J@{>RDa>EAr$ zV-4a$hY1<=G~Cr98uHq+fR$Q88A?tD)7@IVKaPmw9b*xE_NZw;3)^K&2p75BNL4M# z2MGoU*=-#G`Q)#Y6QUpY$)Tv!&f{{dA8YmQF%hKK!T`bK_6p6iJjKQ^&M5~4PS{Am@O5vppsSFn7%S8$zY4*My3n(;1tIIaei+p z=(dL;Ar(f~^+Wyki#pJGPGexU=569CY%Ph^b)e>HVe%N5sciHA(ji9VmaSQ*U>Rna zUGIErzh|hmKP%J7)ZwW_*Q2uNKiRpPkCx~%v*8}G4B-@HjTV9ck|r0e*xwOX1p&f2 z!Fy7Y5e^h$wD}aMCX+>YmCT}4%4d_*$ivs6%;wb028bn8&9JahLR!7VKNY1$9(Svy zD*X+x{Sa63D9`Okku)M5yE6)=xf4XgXI18Es7Xa#6y!)#aK$32h&x(B)UOTkx)fHs zC>1K?UJEz1)BX-vl<)1zK^lbs3BJ^dD4lNH0sm2^n0FDX~8U8>j$HYTehX3(F(>}*xI zr{)oo6so>L&vHX@=IuJvUvRX6OTJJlpv~M~TF}~SF^rNq&|IH0qVp~s_1b=1xLQ5VaxszyR$}a5fCQmncPYB- zH{UlVa$H-v0m)p-k78J^5^#0YV$gYQUrc+&MRQ_FD)FM1+?tC`cI*z<_Ivr$3WXt7 zwW$nMRJ-Q*0f?~9_<6}~HEW?R?K*+)ndLQk7&G);AyRpYyZm-M%7vkxEm0<(b_&3$9gR-)@JM7k z_w%0iO^?jn)!n?7ni;*?bq}-$`ZVuJC%9rrA>0q008vuOStlW8nOSd zBo93ei?k~PkTab~-qY-Shk`aazuOe-3KACn^^Qp$Y?JtRn#c5a;VX~5p{w-jAC|QC zQMn_>OGNDQBl|840cVvYahxye2?pk3XlDyy2aggcv^f?4UwbK*xI)xc5;5ldeW|sA zX1IaH(sv0yL=;<*bhzKe-;c$HYS+EH3Q z)Sq*|FVzfmY<_L!dK?p4>)$wEazb89aHRh@Tk!<11-?E81{n_^;Mx0cia_I4 z3YkOZ^kL*aZem+c%>iC~kT)ZHP&9ylm^#8DlBc%$Dp@%KGK~)W_xD~fZu}qPa+b2o zd@p5e!*>ih_r^+Tb{!7}327oae^FYMnkp_1I&EWVDRI2+{#m4(a$n(Wpcr#q|EnM6e zQ*$Gra>7^_7?9S2m-L0+?~t~_Mi9(PKTPcd0{Fy5I%VPLcdY<3Dr|G58T|MZ({-71 zA_Nnxne%v*!q#lTtA7#F@eqjXQVF6_M;^LK{cj5;BHiPG%DbD&A2p& zFES!d4*>ub!F%f=-Vo&_QKiej>9T|XgCb3~Pbo>K(Z)#7Ha z4Dt1h)u9od3kxm04`kx!!RrpytTcgr4H3-dCArrju=l)gWsy0wPVd&Pybp2G1_{Ea zno5WpLVF2kTjS}+dzPs=(dZ1?#z_#S0R+;hYviPIoV9`ea&NlvT)r*VLRRv))aH>P zF$8I=g2|9EyX^>|gS{a8RD?MpLotky>jp#Yb9y{}df}>LycfQweC*`1qQwEDYNnEh ztXEqVn2MN&?#`cvs1`ZJU(>C}$0@cxN_)WxxX~oG$^2%U2_W0j4J>hC z8sYe5oA^LU{#2sz$A^6FHKSBxBuKq!_TyNd4%qRq(d9ITb$A8^_{!~)3Z@Jh<~ascaDwUr(b578R-3q3 zV7n|H?39-Xmuh1W0+-s9J;+jN0>+^oh+D6V=j;F@*en17Fqy{UY_8CCc?@& zY=*}~-V3*m2@h&3uo$|ZTl+7_WY=}5WYclyZekbkGsC9EW=BdVw&kF4h}s+yBP)tU zY3Jk|Zu}RO~D46)vYQR$C4pdd! zp{!e)-06TOO76y zWn?*Qc|MtFwsA&L`0a+hkA{85DqUpOSR7|mLvJPeXqzFQBCCx2WoiE>M~FI=+lzyF%vKx5N8^{dN`AN30Urp;{uQ4l3Layt2&up z627G5kDVpGt=#WHIJs(+1B@{v@(Y7=*s+eXpJde)j14*YM)N{wx$Thv$uZ(GP>@^( z)&d!$r!d_GX{Tf(4oWMQ+R003g1kmJA>7sTzKQ+v2^Ur58MX2E zx{2jTV6z!^f|0xheYf9q39RiL3xpaNUL3g3HD6zioYsmwBSH#>M71C5zw(D7@~bu2 zYJGPEG3XQ^3i#85h$4-spWm%qM+q?4lfKtdjXH+OMtRy$TYFhbtJHBxr`N{jg>`_MjD^A05#UV~cTNVyBPo zbZWaRRci6--?N1>v)(`d;YPD-dHY&A%q-I#vHo9{%((c31 zLVc+n$xPD2X|C|eySC`>BxWYm(c1LK3P6&nMIiwLlIC8VJhG$ zZ`ET988Rd8x27mlOs(?cL8k=z`j>Z|-w5(h&m zUj3cqbA*I7U)Qai)cZ&rFcQBm4^uT&bF>5=mxmemmHbteSLZ-Z+`*2-1x;LTt`gW` z^RpAlClB^Hft1F4MvC5&kDE0TOB-pZCY2o5$e-#cB0R{Vc%d*6E zdsQMsen%h3hfh^mv*~11uX0O@4K8ynqauAYJJgq;!)8usBav+a_ZAq|;va1HU9RJq z9i;S22_@?OCFDY?;?P;q8Zi;o%5VvTgv<^r5r)pW%qj1BT+an1GC11Z6{dak>D>8y zZ4==FP8ShrT2;j-&uv6l)71HC-KlaE!X!+6Qiys)TyLy0AYE{c+GtDBn7evmY|Uk7 zUhBKr@_~7~K<9|P#tkibbFLlzf~ZGh?Q>)ap8VT2Z7K zcV3kW?_!1C&uHOWAlIn}%BO+i6N^Jb|TX*5auIptfh;r~|-dYksQqgbpq)(8`k>qP13 zY*SJBLWWmKTC`7oTXS(ZQLJ7@IZ%mAapu#%X-!B!=7lkq*FJ!@tf~WsJp~qc(98ri zCwTV*S81*W?aNBve{ZqRS{Tc=bCdw|mpE@f(<#4{!-}JNBWUH;evd4}z^pzPKObHb z)@jQo{8%<4d;~fG(I2AOxlLi5#M((?Vd)dN2;-~mIPKP?LDmADdJ5DC5HTy>Jc@ie=HRuO}wk(3l z;Fi}~IR3(0>|nX#;}d$JiELNLc>hejAsjbNl=4P%#|+XYeT(&0soQOkGQc}z|6OY} zy93`Xi|Cg!6-UgI-9v9pOuABRe^XY|#-B(>`dN<~Z;AIU zkN_~UV<;u3)oUvwVRV+!0%kGr2P>4(EabDfxd4Z0>8w%nrxKB&Z^;kQ-i4~8p9sR` z4hkZLa#>2XF{!UBG#5_uyKMtq&T&fFETUS$2E>IpDn^P%R1+aBR?M@2Kw160W?rn* zg2h|uM!VL^8hLr7p!QkWf+H(6t~A*j0~=sjLtd^6*$rvv^oUx5hM2NC8WlSa%jg*$ zyVFmJE06>+)C~#O!4*hjPjrm9SsX(;7!7AMemcP?;?zco>}Qxy7jeV>Rb zo=M3-N(-ik%Y#bChzom@`P)C=?k2-tqQKrtWa11a-VVb$fZd>S*e(dp_5XC32O|YBD_YYr7k>%U{(7)%PVgG}Z}F^UKsw2bW3JShgZ-771a~ zt_SPvQ$>U%^S61xF0$aRY{-II5X0dkf2ai95=K6++OU(pHlvnpey<}ape~n-#FJk4 z+m}=;Cj=|wi+Q@%z|$Xm{h@QUnP)zgWU@3gDgk!D>XorStTP6CQBIT5Yh5Ga zAX_i5F>N&NgCm6eBmeju9S(6LZ0{oaxf*w5qR~}4b+_6~7x1v*$G={VwEKMZ2@U9N z)58gr8w^GJDSe680MU57EHkqf9$jYyt0VziwDTJ zqN^?{{s8+BE7djR9L7~6R`kZw!C?tfMj&}_W74;5PAiIHsv%;PH{d_mQ($3w(3j(p zVGq$@Tb66U;xbb}!;-kSL&0GN!ctC9M9*SPP$W{f$^pVxLnFvp?9(RUJ)Sh=u`55Z zBItS4m*vo+o?52iYpv5F=$mFa=8%?0mlbeJg*jE&!=2kyFweNTRIX~3poB$RaMY;p zU{x3@!k%WDAb_STp)2tid1Y=*>5a?8<;2Y}+$AX_>s$6jQ4ueiH0<4`MNI`39gROb zo(tN~vZcw?Y7SxAYvG(8YLq5?iD&C3IwlKx;i@9ftTaqsudcKu!w zJ5xPvH!%wTK4{0%i+dh5!MS6c5Wm6nR5>qKmz)9hZo^VHXUZYSE^tAwO02-k}d++!m;=tS<+>E5psSDfs zUdHcNNY9*CqZ_}$b6SU1?HuF134-T^dUflZD9JDyn{u8M5`i^|s~Lfcyk0)CA(kEi z8!<@s-rmbYme0!gQI#=T7<+QiTUm3SWF#SdY9gCj%Y!{rIA59RoEj&Rm+oxmj`<{` zO_^m&I!HmpT{-=k;?EAw%Y`J^$LFy+FN;Q

    CkANUwLT3rCAtDR+3;iYw=wTq^! z8=FYK8XLR-7CB`J;wd?4Tj=HUNw$l5RcqNW-8fU@DRN75wc*u_e6bqvwQQm@y-gI= zEToC9JRy;lsPaaPQE$iW%$Ny9kT!?G>lTOSO#!)}DD~$2&V=b?Vpc&(jlz_|Un@U> za94l~$1Zq=AL?brg6;{Bm?DWml-Krf0VO8F)j7dqDO@;t#JdTd#5j_3;zPOSE`m_u z)Xvl_D`3M#DWYNh=-7bVIUh^e_6giX;pMGT?_k-so4^Sl-N!`F zZ}RpTw*(oT@2ZFxstQKgDgso`)8I2mbP$q(2tJ1K%l@eCYnBsN%F zMx`)-!qDyYv@4atlI6oXbI#(tLJ*ZiktOx?DCLxj@PkGIp`73>*158hX2BV$T+dSC zys9mDKcdE+SW#=PUJC?lhv*XkbMOf=vEtxl8%sqi!Bwbnx6IOwum zUaxzLDMS%AsDYS5m?2F;9naDK^pf^kKW#qqi2(?((1VjY7Ekh7E&B@RATOhche$hV ztma9j$L!0}J;qVtX-ySGT}I#sCo7(xOEq$A1Fm>iGEImDTXRcwtcWLA{xjTMii*ps ztAVTFR%S5Mh5FJJIBV5lur>KsK|U-$%cp;Wu3zEFHAqhY@nXs4(afaH0R3#lJK*~fHm}w^zx|arHgX`AuxX?xJeFICsHvv}v5iW`Jx-_362B{_ z+@8r=Nr$)-zC=6iD|lfAdqt8QQpe(jl4DXFuARPiB8;Zxh_(P}wfb|W9eoW#9SSAZ zC;69Qq55p4TC{D&2Nt)M%_zlovd#BB$f?C;Fh2CN`j_FS5> z@_7%?-nd@F3Rs1^=JX`kfNO;WFR-=LCU$TZVWJB}IXrDw9MQ-b^7kIMvjc14VxLm< z(qz7WE8hMj6D!~|bF1CZIYGmBT-qRip;7iFt-%X1bCH9<^lAkTr?HDNF`N4uTJK=o zLP=eAef{j9_a}15`e#j@mYyMB#tQE@DI@BUR@Pk}Bb{w)(o3=2>NU6uhLq-40AH+05O9FwJHtyfo4A-1 z(~st@C4E!tGP;wf!k?E zNqv%&XPqJzX}X*YARUprSdmABPqi(`HPau~WQ_$v(%pet&=R6HYgyO$P1)n*pfG61 zq%_u>-?CDsC-M9GnevWTK7Yvdrv90q@1Nf+Pl22#em>>8bwzM;Z z*AzN&y212*4HzOi=44dL0p%ty?=waVB-32f*4Ci-Tc94ZGj+sE&R}AM7$kM?Ck}*4 zUYVnJ=P}*ANw%dCK^ZWjCz|pD8$+|BEqAez!tw|#!OrwK>HmIk$Wc*=p*uVVV!NAeTo7(AIm$Wg( z`+L7pqK6FjicJ=_btOj3xTN~jqReM|2a;>(dt@=|BOW5QFgf&iXchb)Eh%J3}=6B&fO6w#VS*V zGiBKdQ(^0*03cCcVuawTHQ9plX;6@}ExUZUceopHZVtFutY!0P4;H{^`k4@bHC^b= zRr!=uNzDcpa{U_oyl5Nk&jl zKSH6s$9A;WOB++qSfPYZ_9cGcVoZ_@By{~~8O3yB83HvZ2mbh}NNOD4u+!Q=In-}O zEV_0+y8DF{moSWdDWCp6m99CA(msqbbZox7V*Wtngi(gEg?HNe2klV)#?SO^tYrJ; zBta@!d8c+CPj;s%QRh-V2dHh`3uO{|ujv2Y6y;W_~`Vx$c zRK48P>dS+aGywGO89@EEdi|k7sWB5a-jWcb(1`f=R^sHwG$K~iDN)|NA*Y)WcYK)<$>2X8FlvmQ(u&6+)+wDv6dvmi;QYC3p`Xm6wcV zW)nbL{xGxBbLPe>he~tDrTJnsX{$5o7mJ}nHe{<-br&&}ci>!ku93ESDzxx!=1bA5 zt=1)aRg(6iE3Ofpk*3!6X8147GFKV0tEwJe^ay!uA1FxBy?IYWaz;x7$V`JF*dk^v zD{t7M$1CT~2fnp+^ZH7c`Crophw2MRaoGdm|(S zlSffXV*yECIRsaWX;%WNPZDXc^8qeX`QDuA3-)tA_0%y~lr=wY{{khbYhj9UrzH??LzroVrAQz08iH&K#Qz z<>p8mlhjZ=Rm588TzfxigP3s3U#~duB&JxtQua@Jsb%3GKMj5jRUrlr+;eBZ;m%@( zk`1-_wlSnsCu@FBKe=#ug;@05s~Lr-im_fiiWiaY!8XDqsbs zVoIS@vc42$y-0T|?UCib3AM~eg_XU9!&LRaLxz_J^-7}U(gw|iY3A-g>dBu$LrT$ey=;ZC5YGoBR zr@(E81ct&1!#mWU15H0@0GrHu{eh$f>9RQmiR-+nD&=5HdjNqMxmAvVWQ;u zour#q=?NiIQ@BR12sq#XumOe9eL36#CbJ{oI!inua}->dQOCa8ng>%1ey9l6ZpC$H zQ~#ZAYHv?d*@7oJ(8RGp(~ax6G8c!nK^NH0`p=;FG6;#Eh%`TVQN|x)?soto8I2f1 z$no>Z3oW#J4|_6K$&xx(>(YKYrct`)TlLbAiwD`Q~1+F(M))uXljlQ$k7V{l9(BtqO~4cEKnsPTR0?kBD9)bWi*mmT$Q!`OlO zAlyZp(F(YUgB>QA^zm!hh2C7T)_1-~i(^w6U2oF$7f)Xj%5OEPr*4JX|4O`^yrTG#b)AXw z?PP3PbH&A*`~cp8V7u0|SXry^7Kfi82H&_09dO z-UGGW0}b$jmcX4pM%Xvwd#o}xf zume2-zdRLyo@}>|SoAQwMP6LV9@KRA_{m;s5HI;?FOC7PEc!>44Ns1Rdu%f=LIQ6= zyI83zZ`o5XnWksGiDwhwy}{|Tl$jR^!HZ_{vpV0472Sie-iw)?j|uR_CgjC7`UQt= z0u|v(A>mP>-SuJb#r5>X?e*mw!mB&Ms|VeyC*P}=+^e_VtIyY0ARln|-iHq0W=(MG zuUB=s4h-Dz3AFPB>H$+HZvqM4+y-7VF<-;KK7#CGT`*$PYJiX^pl<}-n_m}js^8Z? z`t3#1C#nk=T?BMN@b#g44;6di&wfqFZc21}3m|w;i+)ede$T0T&+YQdNq!5z1*Ty5 zg)I0+n!U;YdQJZ7nepr0lkLs-^)1Wn)fxC+WcCrVK~@&>k%!>tyYXJj_g41xJzvc? zzUmFU@KHGN9{l>zK=+=n7f`YA(dHJ=HsIgx77(2MrzAR{9tbSIeUByh=<4!sf&3Xn z_#7hm9RB)=HTkmN;q!6qKMV{UiT<3({+xV$!Rz*Smm{K^4xBFfoFDLu;R~E02v{)t z?~eYuM8BIIZtpZD@H{RBY{z6*mg64s*E0C9MI=9WPphK~M zeYe10w|`Ic{{6NK-aGxg?R@J4{<{bX9@z+N==yg(@bBjI-|g)`Pd@*vfxw&vpDF~% z)9b%yJ;+PQE5BLbFO}ezs*u;NkO_i6yJqhnr;uEP7%VziY*PDXieV6<9yRIG9mQxg zHWg=ry*pq$9G1ZL%J-g1E(I4!SNiO}Tt0)5r`1@X)OtDx-DcU#;IVQppC5Q}HT77v zP%Ive%;LX9uUV>?&S`Sd&ahfVQKp$`_*}bIF97F%cJa)#*=#wH#^UtCyxs1&(du%! z-XPiF(Xw3Nq-V3+2Xwl)MpkoxfqY-{#x1I982q4X*|a;e^~;L>g!$%z(@ZuiQ4~dIS`Ae+A2mEU%@i5CI?~`M?{-z1vaQOmAl9}$wcq)E0uQaRG`W7 z5~Ti>8vsI}DGK@!(3KLg?WshJK##L6j9~=Rm&FTi)0ZbJ64zK<&YfG8h(72`SAt9R ztPAqNZ?;v^@B-(G0snd!>r~+xe^r+T>(>_N0sI&%s(<&^HTFMz)HMyk2wk}f5i`;^ zcrb1)g4=%UTegBP2=&ycn9mkF3=J-AJC$AHSsKYY1X+7dXt)=v=hMKfRe}-nbSa3>u77;Qk#bH^RKfkGnb|G=7 zOXm5fjVUno8%P!Z_-r4KzUkAL)@cgtSTnHd?^rjvjBhNsh+}zdD>KDyZqu5M^Xc&L zSM*Zl^}M3h@K8#8TK2ni(Jl5&7O4v$jV~V2FeRDiIgDm1o=IcsA>fvd6q5LE>~-T~bued)^iIo$s;%=-s%>2XO`rvWD;Q-y~nUaw4f=qI=z_ zC*DQe4&4R^Ho*elBJgy*O2%*m9_<4pRqf7whLG}DSH{U!$bCT^@g^rPgp^7F1zB@5u)b>R<_D@7O z!{b9l`Tf3AZ;N>Ns~DK{!EDrz=nxb2Ba06Nxto@ySe3pqr9%WpCTTavS*^V!&6pah zrJ)!bZfhc@(~_T4)RGltMVa3;M{FHX14Zi05TRcS6V6hi3qNtf_jK6Ldg4WH7-1e& zLw{hDVkI}WQ!&#>g+b`kK)xEQFod@D*i7UIa9)dHkCVmZhVWVlmef*^dU1G``eGV@ z!0+3$YB+w)s-z^OGS0GCSpiPYti8Vfy!%s1`qpBD!1m1i`SD?_tYwpHjf$D|@dAZy z1;@bD70UQcI0E~dLKneP{)YX|=b+Z&x{Ex-cRs*-wcR(E{b6ip}HEksMex76(}V(T7VI+u{xlVzMc^OOQs8 zOYOucYcd{Jsf8j*s4|YxkxD0M!H(2yZi-dgsw2#O`2qze8OEAYf@tYw&c~Csf|K%8 zhRhs>Vu-B6M+{j4$=b-Pk{vF$F?N(w?VsbCi0iVrJ^|dxhKx`6`zm-nn*%!-@jM-s z6K%EQ82Xva=Hlk6et6Yb((Idxdh)ByukS+T&k3r99W*olu z$q$zFT)n5am^lm@RtvV0U2VF=9IR1kJz8P+_s+S7SHnXEUVS(QFFU+ZA$m{mn?P{y?CzrGF~nK0&W<{qfLu zQcx6>7PND0?Iv|B#kngs+xz61Y_`YX2y3;;7?%(9RSDrLmJ0`g#LZpL+Hqp47NjcWpU%PPFzmj# zWzaekqx435X9v1<-{8Q5Cgo5eM^;U3q+!w1=JdZJmtUxJobmdbLi4{_s|@~|gY%|f zr-a;x$zRR5hUh2&$Pu5kLsOVtx#69zn@!u|j2K%}H&LFLSr776ERvtHWhgirlT~hQ zW}@4QU1GHUTn`Yd>HL!X(FKF`DQ0i`T+j5wTQ{hGERJLc)S1NB%W3Z(AY}yFz^5Gu z>iIScqrU&&^4Uze#GMbvi^Y(vNBu2KE1#Kstk|3dR3&|~rBxEx7Y#;d9;M97#VSu;JLBI(LTUu&R`$kow>J_YIJ}8O!rvUH zpR$cj?nu-quBhqNf9LFWNabJYz!+wrzP&I;Y@LN!UEtl=u~d-~HN6tawInRq4jDj* z)KZ`?e0L0We$QqnxUq-w*Qt<|;$NZ+wiN20eaU`b)A4tkx(#YyRH7xsH9qECC%Rq4 zKVs9sFpJ62MltBNxoJ>`^HmGpx7RsO*&;DxHzd7b`hAf=1Mw@RdMl$d5893X^w_)v zzDzrRKE4HOqGPMSq6eGm?G|2g{Cmju*Ae=sb<9m&u^mt&tesk&F1$4>l!@&gJ2xDo zCGxz!>K*Ycyz9(RT-k&A=q2$rC^^p@cEe@g*M0*I6jOtiN*S5|dsFRS0mZf-l047C z4vYM80|A1LMEwadY8)xs+~!`8SqAhThssuKP$o>zK87q28x5({qz3x1$uJVc0&6i% zNhcHAGEbp|oDk87iznsSukeT8FDZTPOqLZ}7IlpAVyzmDM1vjti%`s3jV~Qv2^S5c zRSXDLiTPCU2{AG510&c(hVbt-;8jS>=XS*r^Ef4pG3QJ&RdA42_c77G@~&Z%cV>+x zQZ{6kfXT?ASS)foEN=P_TE{HlmJhh+zEU5SoR?5Ay2|aJAwC*U3#20U1y1ke#62$} z=Tn%tXQmA1qh~@9x1SBp+Z0#YpjP!Cw#};3xfgTFPE`+~&XXbef(j5S06dlZ!QE5Z z1#6w|)8nz?II{kApmk$I@!gT1?l1xwauV(#WF%AMf{ZIO z4k@wyTRjf2d>y#cA`2Qw(qoZJxOmW62Wdj+qyhK(nq+wQ2VjXpeb(3`gB~nF(*l$* ztM-#T0aa7@U2LL3BB3NIV&pvPu!sZ=(-F8s9OgpNUX2DMN(3TP`1NdFa9Kjf5uXQ@ zx~T@oNjY^=-M|R(i4J4t}``ra5S=>W>ncJhn91`N>k^7!99aSLstF zm<`*+HC~}d|D(qpAqu*v$bcmD7 ziIEzJHMGkt9V;C8*JL#C^w5a3UDiN474=AYvQy^la4UxWgkcR3B7WXqxJX&@NXIIc zMr29&1upsO3YFqJ*gx-Q2`STwYAPe~Msd@Ygr|3Jk5~ORiQ5IVG+Rh*O|=`ma{~oN z`5aT(y|tYgt3qS3`0?#@IO+h0aQ+m#BTALg&R3Qg?o zLvae4RN(=IH)5|*M67-*ql_(n#4UKsAv1l__2-xWRv_Krd`5X~T(v(6R@bwk+*lHk z=KP>ZY#lqfBSi$q#XS95^qmR&Pd#nn^Sz6L-}PAj&Qpd#N-_!t9q~%h&2v-n7jXRv zpAxM2V^gz(v~m9~uyE)`tQqR|XL`(Qvk;Ar!Bxo8r(};==N#_g=~%;sEg>(j)~l@G zWg5w?Vx`+KwC`f;-S6TaVjt|3KgC)}g&}6CE{$-|K(WErD@d60-`jCa zXXhKP%oJDYdpK3N=8>>!Xg&xv(0V3}q5fOFtI<@4Sj)VSHENUI!zmVU+N6w*UBlu* z*`P2?Z!>(gR)<$0C_!4(swVr2D6x z`u3uVA`_$A96wGfpHE&(1a%SryZk|KSg}GrzW@wl9~qKfsl0VD}|B^%Pzk z_90VusLy5WwiC1LkTFy-bfoiFK{bq@3CJ^2}rV#YZyioeemQl`4}Td-GBC?fot4nA4}9f z_0?G{VEsKq2!8+HdM6j_-PFxkC{q9xP1`hw939_aqUe#yw{4nB0-)SYoV$KPFaC#!Sqs-MSe zyG!&({Tu3LE{Xz^-a;AA0r=Vqp!4v`*xht=M)&7but%Oc?W@m8({PHwR_ZaFR!L=L>y$rTut?0w6LJ7cA?jmpT~(C8Y(av_#4SCj$=Fv~?&<{}2OJ_2u@;0dBF>2~C z3ZF9Aus2$GHrn7Z`PE@^DQCPwZ~E$O`iI9H(qS$(Zu;e^gOs;B5XF+o$C9nnDtsnP z`lVBz*G8?=MvvE)tJ78t@?y)^X$R!B_w2L}@UhK)u_@|wsN!{O>U8XSafp7gqv~{8 z;C0&Ib@|ola?0y^+v)ns>jvp`Ljc;0@VY1Se#_&vQu1-1;Pqtd@|^K;5d(TA`*;|2 zdg;Bon{_!l@p(RWdfB}KPkDiMyg;CjPZ7{htIJ=FFQ5t-(9{($!56sj8nDq7_>(W_ zS68qbF!+@(*oZIa$j3LJE992Xx~bEaz{l)gS8!8%xEOzg9Dg_gf23M>gc*O7U3Zil zf3%%>B#=KQx;rMBKQ_BNwunEjsykAsE6!8NGT<#P#1~}Noxt^`7~&gu3XIrz>x%e) z06sv$zqpQ*_>a@LjXOAxU;j&sk9d*CxRM(-?^RVIe=gJfzLU1 z^SPS$If9dUcklUlNC-?yV7Rr~JnU zI?1nm%fEb~yZnL6Jk3`;%-1}~_dCw-{LS~g%KQAW1O20u}-A_H;4}HpmJ*dsRtlK@{?|b0iJ>g3^)aO0oul?Zbz0NOw;yZrfKR$ay zzOIWr-(y$gXa7FsTlnT{zT^kJ#&^Exdp^?3J?W4B>3=@jqrRql{N-Pl>c@WS`}*v& zzU(Wv&ELN6gMRHFyy@G1?*~8dEBo;Cy2ii0L5Y3w3qRQ}zw@X3;WNMVkNoa4{>4{6 z_D_HI!~FBty2T@ZLHYgm|MwFtZQl3JwQzgs|92B;koLcSejAf@o_|bgEyX8&`iIk;D^&4>g9oC~{*-k|#%| zG^rBhN|!BRvXuF9CQKb2PsF6TQ)kbJ9Y6A{IaFxTkUCI+$?4E2QJ+mALVY^bpa-j0 zv1Zk}mH%s3uV2B26+4z}S+i%wQkCkI?b??Dt$=Z>mM+T?O_UyFd9z4PkZtSEH8>)! zz`%zACl7F}|5=+34&JAL@MbnCZxM-*x3 z8Z~X(r*GGO2|0IflXvq<9Ld)&ZsQ>dd(`M#_wwVT(MFd(oqBca*U3KDuC|F5D_XQL z)a!D!^5#gtgJ~%6$#*gjNm%KkrArqw=4a{<5q|04lUDHCjyV9CD^S1#QCsM{`NVUI z!0ph}LOsLU)8f4m;+wC&`-swyKY{#vEWqXl9MM1$5j;`F6s1DSJMbFpDY+9BwD2K< zn*T_zp$s+bq6&~g9AUpFW<=4*6^~>wqzW0Fji(3CLqSIh-Gfg)`s_2YBoCihO1O-m zL^3zlqDs;>ZJatHPGrL@H6w*;Cs`OGh=h9RzPD`!n(}R}XHQ8s0MKQkn4*gEg{ED2^v_Wn4 z^9eu&l1;YnoYct0SD{6-*;LnaHrh@{I@L~9Sv|p3!eG_TTR>?gbkv{Ka0o^X7;W$y5y5FYJv>3=O&{e zrzv|;t_S0K$n5ZNjGAu+RYoXfscDOi1d!@(*SE#ALLrLKC4BoOX1tw)8;p|4_Zwr z%hQ^ky0#P{eF!rCiAzov)CEiBh(2{%nn6O?Ka8nFe+MCw4oh>B8!Aw07(CVkPe8Sm z4X{WlY##z|6ub7!u4+um%kRF!JEpADxU`g774d}+GoDQp_7FUcQk6q;K`g_A zuR9g)TivMw2xew0*x>0ds>D|h;l_|e73UzSb6KE(GlEpACr5nyWqEYa9n_g}Sfm&X#@UjMS`NN!rno8Tl;;?~0| zP@XfL|5_)Ja#Tw70CSfHbCx~TDVKc~p`X>;DnJE#PjMNKr?nHMLIwM&a7fKn0)?#BysnIYIKeM^AyE_%1(WF@Pe4+T<{7 z#4K*Y6Ht5t*!ZfKos`~*Ap_$P2id5FQB-+Gd`1_D;4@6A8#SNcz}5=Ho11xwpFmPq z8^g+hH}=aJPXJ`ObU}4ixR8)XY~3zJipk8YGVn~AL^GEsc^w!*FJan2<6(Kk@u`Ag zkQ__cgt^8w^jBDV6KgY30x!p5F3 zW^)GB9Mo%G^T?1^GLwz!kIdI>w#;VU~s6;uGd126C}kc?gZKFjLyZ;1*k}MI7lRH(8rqOInn*@aOUnL_fp^ zSsfoM-ZpW`GTkoB*C;iUYbyZ%Ae|N$pHxoG(;Z> z_2(b~1p}UwUs`)UMD$Ho+T(O=N)k@(LYVhAh@CZ>8-?pzCeO{Cax|e;BSrDQkGw+` z5BXImp7J+St?X(DE|Q?MhKxu$uiJd>dQ7bQRu9Wc593hJWO$?X&=2x2kAfKQf$F9D0k`2Pw6`IPTwm@k6}tbw9WWvGwh@B;fMR9LQW-CLqghxH~1|7a%R==&j`ba2m23cn#}wJ z@U`T^(OL-fB(DdT!U3@+4c{XIRj(i@P&3*o_KGJiOltg0??Ol-SBQj51|tR?Wj!#B z;zZ90T_PyjZ&+?afDW&P_zVouYXtRg2)l1#fa)_wu=%it0G-PK1qT7AP60=Z0SiJ6 zlYk9%zzrwxJzS46Tn7X3MFY`ArVPvjX(*(64@4fX1j!8Xh)?n!Wd*??`&>|IU@(E8 zPx@#ORBZ72SWx>+hABvKga57v2;+~@K11|&@%)NMuL2`{9%*bC!y!DaJrso|1TP)c z@$cp?BS4~cjuD3jNtRG*Q*P`s=&^39?K1r2nnF?3aBWDw=U962K`H|TjLjf`%9*B& z_5KE^8ixfAr3iY=Ao|haM(j|YZDABf#=?*sSI;m8g9HX?@dRgiav~o|VCH-+JSwt* za>s9Ush2bl%joe=VvsldY^~OhVd%yRtj{K)t#Dun*YM?io=+3aL!kUhAN|d?vdjag z0wJ1)Jw)<2*dzX?3~H7vXPlBUBxsQI4o8;qZ<=V?pk$L|V^d`44fBc5(z0qW%Pcnq zYFI$ZbW95*a+_YVj{n5yp)}H@l12wBOkqHTH?FdQO416)xMU#1FzUoAAuF?Vit;j83L@=tBKz_p-3g-D zDTS8PosxzZQ8N5FE`bO|?~(B#-@A$;pJMouejjVZf;Az(8-SCcs7?O5h= z${YyB9>QmE@^!GrEq4q$kFa+BGoK3QF6FX2_L3p8^KUScJBdUv1<)f66C|B&Bp0(W zQS#aN(;rc*FaK*zCjEpaHM2Bxra;jp0jq!~fd?c;6EB4F6i-t*k8+SUVvG^TN7(PKesH$>z`C9t|=ar3&bTjoiw+s!xUNbcsN?G>j-yAg<8;u5wY6Xc(14=;&0$FmZYmbW4YZOcC?silXiw={=3KMbZo| z%>z^+MO1Mu5cLy!IumyI<3YIQf;G{lbOPV*FgLWxf) z&QDzcQ2#GPP|0*t47F!&$N4PPPaIWXAk{pEE!LifAhs1#&1wVhZ^k+`ONaGmLX{=e zNHCCe=pLy(b5kPL&r@rTfgbf&9l}?*u3a5MOtWTFdIiMJ)RmG$@1`@!Ce=+z2u@Y4 z?T+YJ=S?nzNYs)wl-7`uh;aPqC=e&E#Te*bT>?oP;ysV!9oe;2-L)@Zl^{OsRf`j1 zyAmKNPF7Q`SHvUuBw3MB~9B2WRgS_@SRG!|I1 zmB6-@47wGgC<9y{)?KhxXfBm9H8ov1)u;dqE`9C@Y4-k-kTy?sS!e{%!l@@`qDu94 zZ~xZ>D)93=V92JT(W3Ix)|zrGb!WSxv8C{YQ_X{LofC$P@kP}$iQ4jver-VsLB#tuCg-+OGTnsF6$!cgIS2;x2c6;iAx?{h7Lm`?F!kDyqbE08?4YJc```%`k~Lq2@eK?UV>v(NzVE>J> zFqn5CoL77mmwdPCL8`YQmX>Y`M|*psS*+4zbr^gB7kU+zaBKE(5odf&54IxM)*!b( z;ldc-2fY%noT>&d+G=zEq;r$TraCr;K?QaHg^PVum)Zrrri}Y0cwaF@SJM}OQ&qR> zE{qp~o+4&0wkdplSbEF1k7U+?SvaRgn0;k$>AbRVpXW;GH)cYTe@RMzT?C3X19JqJ zvjkW?2-tL$$BR|ht6~&XhNXc6Id&l!#%foFD>#ZTcy~2;{(kpcY7kU%SA^FWxk@;o zPWUN}W`*k*Y4jMo{)$;gm~XNdj$eY&!i5B=Pd9q9nAg|^_;#6@8BXFDCjU$l#Eh|b z!fc9oMn8-2O7vu!tu06B_XIbWG0EUVm^V^{*=o!qn-7nM#BWvILzu5voZE#3b_PmD zOp6-AZPMc$5i(WK`I!NY02L+wP!0CPZ$GSsXx`Z{=;l=hnlWLdVMXX{eyffGn0p4+ z%yOs61}zX5ubsKs#H_hx^f{sV4pIU!eWG$pC?(O-ESZbqqvbE8s~MtUFkgg7qqo^R z%uG)LcW)dNnRNQV{Nfz9O(Le~BwcZ#(~Nh9=2D!8r|U$8tl8SyiCWUELVWZg`Z>!U z#I?lBYMCOZuh|v5;GkbbPiW}y8d{vPFo10BUm+S}%fzB_38SNHod4@E);ii`WLgkk zq<2Paq?HE%yX2%Tmv5fVDQFCs?e($W8l(ez%}#)@u~~K)27fs23`NpqqTMjGfh|gtsU)GZyQlNHMz(qcy854yBdopVp{?7j(K?|&kgWyBq2D^9;~G6Ex~|*W zZ$84Q_xfvy`?+-|y8QxZuDPW71F>m1OO2wj*|S(`lu}`$ng2<=#KEE+k0Q+u4d6@; zAymlO4#HkcdoV!7UW)mH11{Xu$}pNRC=!z?2yHOVG2n)!JXWAM6vZzH?Hykn-;OR) ziusw(krqcKyuD4xqaw^y2unZhYh>2Sw8h4wbT(ZY$hYp(D9+Me+Ux4{*uY%Hy*wo7 zY0G)yQjB^@OT#j-9L-d0xmy=_O#8@9&b7bErN3#+`>dT~1I?X{$h{4(KVR(wYv=VO(a@+@5Q^(Es1uA#&U@c061RondTzti3JU z$C}RL6F>yLNo^h5HC@(g{Kvz5*ZzXW>uS=!#?%xM#qIUZo4azPecN*V$KxE@(;S_1 zJjrj}OPKMc)6AlHoY8^D(ZdYVH96b4z0&_Y#)W*`)f~_|9l1Z4DX3i3YaG*&`_#+5 z%P;-STb<)CLfuFG-mkLOq5alb{N%Yj&MAWWxVzUQxEDzV+G zkI3Zg{3;*As7f7JBHg#R2KLUnO+6OIH+kVH9S@!D-L2f_-+Yt3F^zzy)R~(q6K(3( zZ{OdYfeGePwB_MLGd``H##JlVro85{JnN16ng0o<#Sz`1@ICHh{bDZOyxgVe*WRcv z#py@YKMemvVf^6-!^?zM#Ft*{tKQ-h#_JJ1>?vxw$$mV5{o-ubF8G1sq26~gc1Rfnzo>}ezGr6<*?|7pwx@k0DJ%$_NLR14@J@x}h^^V{(a z1M)#%Y>%ITKOgp4H}kvg{J1HSwLVuX$nBU}(1D3D-5f(92Jd}y$t!h{efA{>a2 zqC_iT9!~UV@S??qA~8B_h?1d7i6RvuO#gXOWz3l{BRX`ck)})+9(wxx2{fqCp+t)s zJ&H7`(xptBI!(GWYRrr{M_73R)8R{WKzW1R*T4)q+DHKjrbaq z%2C8#UeyWKqlnw(24PFwbv5Ho?uPG2$d=j&s_`ok?#_ zH`7yo{t0NHf(}aPQc4Qwrgk5?7+ZvCf|;m~Be?}zcHMP%7+3rK#@d5-Znj;23AuOZ zk)9z*;0Z;ns@7n5-8o&SU2O&-pV{#_YLe)*_)>;6_znxfkGP_}YS=;@GOW`!TZ%R(#XeCpOKZ^b;$izlg<;un=~orT)* zzR2D;GPANe+t@vf7XTCD~1k3K+>h1&YtCD~%W9Ax*_=xqsyY&u%^0}RY!ep!EO{X~Ii=Y3n z1|#n&Zh+*HpSC_HK*M#M4P$sl82@^aZm4794d>-MH8!V$X}lm3h1SH%xi5%BtKGebh(s>3jD|1d93211 zJSM(RkVmu_Bd4S?Ia+RyKb#op0@=k(Vlt18%%axpbx01P&5D~eSqC3kO5&w5c%aLW zBsEFO&MlFXfP5q$X^AmBE>c%@w4{4_ImH-;Qj!50qcM+(%s~m$g?`*+9b2fx`bG1A zri>wuPFYJ_9?fia^rNM2iJ#UqvzxG_W+s98$!10{mgU4|5|PNw9A5C7KNKf93AsvC z>hp<@d}i_J$F|rF(U;|XUOwB2&VynMd2$3N7n9XQMJ6gsK%)M(ip zx|3vzbpNCzElM^C>dblGQ-`-IBr&7N(B*mbrMo=j>o7XWlkO9g6GdntG1*hxv@xP^ z+o>!&3Dlj*Q;$0JsX~qFRC$3kiRx74QR$^LCq6ZuqKv8!p_)op%5oC9C zRK^z8uaVtmQsEiGb-J{&UUlqZKU+?J3Uy(jo9i1v%hS$66}5&*msn-E2bjyUo>_c-?Bl zeR_ALupO>}58Sk6#+H_%rLR+~yWDq97G5(PDsC05P{QJO!qCKUH77gXou0Fdtn2P> z%PZdvt2o63HL-nLt6dhy*ue*-G11yP!4-E{wwfF<`zpL$Z-Q6C^$N0i5sc&{OU=XT z#b|?doJk8CxwqrRQxAP5-Sl1=%0&JxXC+1C5J%a^1MadknJi;2+gQa<1}J~8>P{M~ zIka;ICEV)#IWbc=mA2F{Q~P_}`c4_ON-ngakD?PWR6)^Q9Rr4WbUUsY{LOQ>!}FtX{RNTm9)3q?yVA{c^3}+E^HqxwMI8 z=XBRRYhWk0&8RY=X@f08JntIWZZ4Ow7p&lp*4Ws+u5Oi)YFQ3@_0Zhzwog`51vDgq z)LQ?l*9sTZdryJezW;eO*4exf(d)@nXx4z@u?|=h*;QuZ-y$zo4 zgDafh1V=X*+Kq2{*Sp^luQt9!U+SfjIx3637<)*vY>mK*K zzkTm>*L&ajj`v2R{qJ+m~I1*28}GvadbuV~_jW(|-50&pqpP-+SJ#9{9i? ze(;a)`{FAf`NU_w^Fg)z*hgRZ5~BX|r+@wI`+ob_=f3v45B~3q-}}k`{qdJ?ee$Ot z{o@b6`di=r_`iSt;dj6N<-dOV$b&W*f)@ybDtLq}7=%lhghrTxO4x)<_=HAS zfi4(>R|terxPvD+g%;?A6exsY_=Q-ggfG~IW=MursD^9EhHdDEZwQBRD2H=MhjnO& zcZi31sE2#VhkfXWe+Yhroj|hp8D2bCuiH9hGmpELN zsEM1%iJj<)p9qSfD2k&5j`SF?zVxu}b~ z$cw$`i@ykr!6=NwNQ}j3jK_$K$@qu1$c!VUjL!&-(I}16NR8EKjn{~c*{F@%$c@-o z1Wy2t6xfX8cud`x5Z!2v1c8q0Scl=5izomF?0ARpn2jXx1WzcB`Dl$#Pz2rRj`|3Y zomd1-up8jW0%t*v2^mJ+NCG5~gU~nvBA|}jC;}t^dz=`N6M2UhNr{0`1)yjZml2PP z$Pv0&lC3xyBMFKpIfuisha=#UZy1tYppuEmk^xD9DOrdysfUwc8DyXXXyKFR5tJvO zlY@Aa8%Y^7*^)(>lQ%htA^?@5IFmJrh*JrONhydtssD&D>6Ai=m50cc>j;ilaTREx zkZFlNzc>O7NdjLmG9sFv^fG`?7u zdD)OKaEBz2mzubj_z8P;xtAT-mi}3vwpo#RNdE$b`HL)YpsFc}EKs0$xS*8?0+}H$ zPrw2XNr+eRjaC4ZZg`N!8Hl}UlA6(q6f%luIfvHKm+0xCCjg>>_@eA+qLIm>_h|+F z*q&!G892&;koku*YMZb5hAIkzJ{pKtA)TMd0z!I-B3g(*Du_h7h*D~TMrw#uYKLAy znJVcO;8+A4T9hb&n_%jOV(Ob@N{NlBrWT5j@ad+7B9wRudwZFmMk1$Z0h4rUr}cS} zblRs5X_RkiBru?-n{lUxYM(kPn43YUe5t7X8K-V}7>`<~ZRn>I*p`i&sB9>gh-#>d znyFO?sc6vzHQI)Rd69wHmN_W`7nqSQQ2&v!dZ3HC85KE^4{9WZNthOys)1>%csi?Z zh^w_)5VgvycnKH>??H zsJ7axvYM*TdKM>{qo+Eam7$X7S)Q9QnU(|D=P|FAss#!=l4AOk^J=jW>xLnz1>-rdjj6FhIkA;FlB21WYN)05 z>XZpfvf`<*0($}nJFfuSu_?%y54*6Nv6P%CuXtLoG-;(e8?co5v6Mju5zDeUdjckF zoFPdEm!Y&V`?5Csv-c{rPkSCoD*qw>inB0#k_9WZ;EA*&tF#V#v2U2MM{6W3S*nUT zh$#!SB1^F@TbVE`vv}IIHhZuPyR%i;vlLjW5xa&?3$+Bhw`&WY0vnQKU>q zNZN+@tG{V_6+_Umu=l0|EdMBqs;P0>sDg^9c6k;8I-m>OkRe!~lB%d3*pQjBpNR?> z2@IgTdZ%q!s1tm_2JEOJtiYU#pA`J549td^+Lj=UsBH-t(;BFg%A1stq!pO0<*KT@ zd91-o5VJZF_S=xLst}-Rs1l-}zACOoyr2?d#5;_w>R5fs>a9kcolY!~Be2B2iWc5V zm>Vd>*@~*aO2o6;tWk`hLb=9etgKyZlm)u0Tda;({KTsYeQ#`$SbWAt48;qYt)=?C zZYZ0pA_C>l>`?~|2i8GXGnn04Bp-Hq~TD-E!k0iRJnem;| ztA?Qbjb|~+tJ1lv{QsrZ3zk(dnX*g<9XOf%SgOEDlcB82o++Dd`@9tTjqQobku0Vb zI=|~G7@j<@m%PYOOp}IOo;u*9XpzXT%*c)m$!>_ev)stGtf9FK&0xUGyy?p{3Cx)4 zk*;zU$IJrBth~a^rkl~2Rlv?~h@uqe%$Yoz!`aCkTAszM$^ebc3_7r^Y?(_61^^nP zd?>#aO3b^Q%I$m=?|hQ~Jjwe!&eD7q)C`r^jLERKq%qo-i+s<8{K(C`DvgY>`^uAy zxy%&k(N-zYWh&3@Inz%m%lq2M)ZEYR%cS5kki}cl_Ux27O@Sc&%r3gj0PTi?Jdhlb zf$p5lBG9q*{Qu1-kjP#E%YzuyIK$HPI+Fg})SoQTqTI+&P|5~vztNo1ys4Zl`K4CL z0@Uou_&S+6Y^WwJ5S#3qZ@si*jn2wj(eT{D^?c7rt)o26)3r?4$b6C@u&@QK$!!e= z8CcZ!Y|b&7uR-0;mdTvUJCM>D+DGfzj#!punSun&+J2&_r`f46ti$+er<;ncv>m7& zyr>cEsex+SqDtEh>D$7sD!2`-pi11l4Z|+{soYEguA1B=0KbFFpKmGLE^Lvb+T57R zm=D>*3V{}IT!B5TpoMA1<*ku~X{Q9S#kM-GL@Xf&@t}IitZZGN?k$+=oy66*#jR(n z2fBf%TK|FQ4c{F3-Pzin0{+4mDc+d+s|0Sw1rDqtu-+M|s_$*afhl_ty5RQvlaXwx z`x@Wbxv(Daq4CH9F`xx?y@uL(s#D3uH>?>7&An&w6$c5L>|2uctFwX)yC}Qkyt%d` zIm(`E&ScPrR$T>F{m6?fm6v_uJuc)2nY&;>0$uQt9@@x4j<+bz<)s;do(Uv4-UYCm zzbtT@B#OKv-sQ1b;!&RBD;~68?Bs%>G%gIt9>-oGgD%vSy5gox;xYw4TJuaYj-lpfw( zod4#Fy_?>BlU5A|Ca%7>cYxjq#)n0|yZq5YjyMe9hd(P$ko8#Op;zLNi8TjwL+?rfHy%8DjvzzOV&Fg}`vNw96 zcuS%Md+w-C$bmlI+)4;`w*HRg4qF8i z+OJ=X<&s_V9Xg2xc@>e|+Ck40d-|4t+QIn=!Ycg0>b#eS5!;Xo^+n&?OwX6WZU3L0 z>X#2WpL=Q$kP5=GhT9-4!H$~SG0fb+{lIm3j{F&_5<=XHYNR=8$9xRm4(`MR0ml}; z-m%%N=$(;I+^u(?#eezVvU;i#3HUwi!{*(r6E4Mm%=i2as&=fz#~S(HN~?=jokNx1v1q^sc|I zpLHc~oWKuzCBM8bFz*C={A=g}e(sT;UYAR)yiQ)`c#0M~fWvVpm9)Rfusf$qNe4zN z<7n}PX)bIV*pZ##y{L(+WPYV!My8l=qqvM1K zfnbW9V91a}mntI~PNdk-3K)tbtZ3QT1*66%3|V+Q!D0u-6B;p!=#pfj#1j`&iqL|x zV#63VQIK)Lg5?txJ9V(QS=8v!h6p__WXRGbLzpB4cA+DXOi3#t8OluAq@za_2U`|x zV)KO5hzwC^snXB|MHWSd%GEJ~g^Lj+*urcI@$E~m9BVRkp*QVBy+!U)24MS*N|gb^k! ziG)bWOv+Iep=#7qG$C~q(@-&`)Y4NaeQ8p=R5c3HyebX#)Bl;!R1{6?NWCv5QK5_! zQacxw^;AqN8n)H@Ol^n-Q-{4YQ%BoeR6JQh4R+K|VRd#US3#vz#rueoiaTQ=y05yJ zGHmDxufQ;T@QnrOtayqm*op{Eq?15w1^rE`VZTqaq@H&D@IcH4EL1LS%R3 z*iNIViis<>NDGX?f~(_?A@d2Mcg3R1yrD)2*$STfs$#*SM(7N*dhgA5-}f*o_@;o7 z8~A9OKydhkvTP>t?TM!5xn%259>Ki3qeE#VmtmF}D*u|{+S<9H7gIWKtD8Pc--`S; z5eyHkrtdn%^`2;K5sM_D-KO1cldbD$QjA~5w|mL)iy~k8>WT)(S&Oaq9=sx!n4$@& z>*$K>EYLyc4WCpt`;(gnMX4xBLfU?tBo@6F26-rFF>XJjYG$=dq5Ql`Ri2nyk=tAKnsYpP46Ajr^#3!`HST%Fh zql(2XiC9Vmk!ng6#Uuh>*~L_iiWIAA)kPWp3Nn+@m7c(8CskRBBF&;zt|Y>&I7Z8i zm4b;JzlbC|0x4FE%3~I}cn~l8DvZop6dAMV#cG|UQ5%C5bZ!E`qM(Z*1tZ|#h?21g ziAZ=!XZIlYRRGFRiiLH&;|wazl9Tn+geV&&42Nna zQigWVZJsk`P7AsmzCg?%>AB`-7V1yom}H~}kttT5(iwL$1fCzMC09mLQo>baEtdhQ zQUwPFtdRhs|CwkP3}{j7XyI)60w_?0bH4?_G%2@KDN2`xGnBM5Ud}OGJ;g)TiK+`U zKmpRfh$Di*iIrOI+#XWlhN1^rK|>j&Y-KHbS6mjtmIjy zc(zbXByDNulovTUNl$Cq?49s(CjZXX1-EzFRS`War7oEkDXRU8YJ;l7WhF#7etZ_T za7C&{!SGhBVkC4&a4Sm1s*8(K)~(>8E9SBfO^o~&bd?3i?`HSBWOS6U5IHF>IsP*6+pt&~7oc!Iw$a~B2| z!9-8R4AgpCGhkMjDHnNy4p90Kg>3kkgLMdrkw+A^M($xAsc?l=grN$1g()~Lf{wiz zO#AGl!Y~t;i({6}Xm<1{3>JZkPw-$ch&V+fK*3TTh@KdyD`s><3)VnD;Uhm8%tUrU zhMjzq!T@oChrpT4iSQ+$2a!lb6ZDehZMM|Gb2W2U%sLCl$5ni(FH!fGm%V1{8R@g@gkH>3(rd!2~ zHqe`2T)f%Hctfg&3rn6S>{e$5YU4RhF&k8byEW~4*j`)}D);Oncn94}(eO}^@-jOs z=8oxx_+>b_=9*|YMgJE{Im}voZo+8f)`Bk02p+DohR95}>4KVKNS5b~bgtpVR!Gq2 zy}-z#2tt`GoCBNs}ho$YSFUZ2n&x3u>O zZsqFZ+MNUHPex$p6IhmNIZ8tlfh+Y1hGEw zy-h&la6kLDl>eewh(HwR2b20;7>q#);&vcC7(m|cNlCWvZIPIWY9C_`lDo2hCG$P& z**`D{z1&Nh=c5|4DmCf=p1wFgZQF>$SiknOs`rBosc1MB&_9BRGx=MBK>nL5 z(Evc(X{L&}9)c)97~4P8*gJWP4XTM30n~^Utf_7akNc?^da){z83^9%6X;vOzA`?U zVm8?*Gpgypn0mq_oWIG)iz~E=8&j?*%(GVNsquh5IK(goWDAvw3PQv)I6OL}_>dIT zLiTe${r_XXw17dY%D@HmKkVy0CUgt7>B2l*4zH*R0O7q7>?*8jv4#`C6EG3>!$13b z!!GQT40OfcQ?8$Bw~_!v1cbh%$;B(|rV+G>Qsj%ivL%V41Ay|1fuMusSVbu;j;_+b z(-=QR42~v%tQ27gsM|(v?8a^!t}UrX8~QNEnlEuA5jQzUxDh9%NhBbFiV?{+rFj+T z5T{clk$Y4`b|kNl8;+8&qu#nLxJasHxg>hLBOuAgfn=)kI|@W8ij5J-f20U%e47wy zkBWpyq+-X}Fd41!LBddw_9(`QAfT+7M;4$)j!dG3oCt+Hfv^Y{gA@)I5Xtd4MU(6k z5&v09lR6;p(MTd{h>X06p{yCSQ9e4W#+gz{xcQ%oc*&R?51-u0n|R2h_zMW>Es_+D zq9lra5Ng0msjTo6J1Ny66_$+)n2Fqwo|F^Z%kf z+4Knn`@!=XPxfq2v)mqInhJ>;#kkan`2>(bb5G;6&-*kg{RGYAkP!d;PXZlI{+!SJ zEKp(U&jD4?-8@iB%#Pzv2m6uHJJI|1w5P!65W3jI(JWlz=w%@Iw@>k3g6rO=3r z3-aK}qgzqMh#416(awa?7Nya}%uXELQ4+CH8P(AV^-+)G(bn`)93)aCO;X`_AQX8_ z4ed}Ujnb!6QYx)dE4@-IRZw{x&8^JRbL>(t4O21Yv}~)tD+SXrB~u_xQ#NJKtT>Tu zd{QZ$Q##F{Hoa3k%~L(yQ$FoeKmAic4OBrLR6<=+$DFJ>O;knokwR@$NB@0PNR3oU zom5J#R7<^7Ow~>2WYVQuR8RfX8p%{q9aT~-RZ~4xR83V?T~$^c9>@w%IR#Z&oz+&Y zRa?DPT+LNo-Bn)gRbQRAq%#pjomFD})L%VTWKC9OT~=moR%d-y0>#i1>C|Ga)0R}O_&e9c#V z-B*6?SAX4BX}vPYv{!=w7 zS)dJCp&i;JmDgeAS){d7qFq|1ZCa;&TBv1AmIc|Qty&6-TCB}lt=(F#Wm<@(TB{9P z9_d=LEnBlaTeMABqa9eWZCedWTeyu|xt&|OMb@chTer>IP_0|O?OVV7TflWxaiuVw z)my`jk-$w{#a&#+ZQLD|*TOwq$z>78tz65!T+Gef+`QXZo!rUQT+j_&(H&jV?X(kt zRnJXbfh%3sZC%%WUB2~LuvOi>g+u==K zm0tSIU;W)*{w2=AjoAAQ+x{J30xnp3Mo4V^a3iRDNYxj%9yx;#QtxS-xdl&gBMr z)uXNDM%HCu4rW-MWM5uXVLoPL{^T=Wl|o=PH6h2WrNOVg??y={$77>=njo&i@s>;Eoh3SOpNYmj}G2tPUnrL z*pDu0lXl%{9%*?#X_jv3%++X>_C}YUX_{u-d;gAUgRNxP|b zu^w5oUTe1YSFKKK%W7-6o@?jLig86_xSmqF-fO=0)|AfcZ|rNq9&BfQYrw`J!cJ_( ze&f>x;KM%Z#g1&rZdIRtY_*vd2QOR?J*5&*~To}-fiBdQq|7w3+ip*9_|#4ZQ#xk;!bYmR?v_>ZrxsP z=#FmY{A=f?Ea|>(>?Tg*uI|0fZtwo?*#8`D?w%ma#6EBKZf~U8ZuLf7 z_nvS19ue`5@3F0K{oe0gKHXl%Z_VOw0q1Y{2JjXca0IV!+%|AVO>hTi@84$d8+mXF zFYf|p@CwiH>~3xe4{#0t@a3lN4&MnQ!4|pc7 zc7PXngCAmjU+sfmcpirKQ)hUHr(uGp@rbW@7EXB5ws?&n;cs8}jsJKJF87BAd6I`< zjPLA{Px%J^cZyeemmlDIH}{vH`TYMqdCR7GoS$Eock!I>`SqQ6p7(j74_}*q?4dt; z?{)Z4M|!5OUZ5ZGrjL5&E&9WjdaEDaj<@%#-+J8@`K9N2uy0{?Uw0P?d$ULB#>VTB zKYO+p-I!ndwvT(vrFy`Yd%M5forn6n-+P+288lAAXWe{5vOph_O+zfSwV zKXm!Oe{5a;6vu!5FKmE#^2CZj7AH=4NT_fj!-ftYLX0SJBE^apFJjE7vEspw9zTK% zDRLyqk|s~0OsR4u%a$%*!i*_%Ce4~QZ{p0Ub0^Q9K7RrYDs(8(qDGG*O{#P$)22?J zLX9dl=s(;Jc!zNpGh?XZEL*xI>ty_2O-oAeW4=#K-@#4mhBWJAH%I)3GpF{VWd^+{&)~{pF zu6;ZA?ou;X-Rw6y`SRu=dQY!@J^S|V-@}hD-)wk-&Clb{4}CuW{{H_17@&Xy5;&S> zO>m~4f(wFHpo0%W7@>p{QdnVy;1MKVRt$33VOSP|7@~+Hl31dNCoWc>ZR2^^qKg`# z7^93c(paO7H{$rwa(!+1qK`kKm!ptF5?Q2?MeOSGtOt-h!5Mi$B5dyLxTMeyi=f^WOV$sOK)J@52*cJZoeJue|x%NM@@0;zxsT;TNbhrsbMFoF{79rPYJzX@V6gRDEC1zn`U z4}$-2bI9u;1Vd=T6ArF|BupR*Tj)Z$ad3qkdLa#K7&h>MPKGnIArE`_wDjrFNj@AR z5q}oLAnK=xN?an#9EijgF)@l#{1^bA=%XoOF^dX2q7}`f#V>-CJBnr;*$Q6*$Xj&X(23Z{z&TIos*Z(iC%@TzMxw>lv9_%5yOG+$TQ~lgfNn zv!4PT=v(3mP;?PAp$bI{J`ehrg+erd}w>gqa)_3`k3A z(wk6pq@p<~OIzBKjj9x3E}bb&Ng~de2BxMu-RVIniPMMjG^j3x=}#RZ)T5rXp+!X~ zQk#m=e=ZeTPMvB*i5gXfP&KOyRq9ncs@1RdGo@YS2w2N%Ppfv-tZIFyNXNR7wZhe$ zVs)!b<7(GyqV=kG-D@;&O4qmYHL%F^>0dJ<*uw@huTe!TV{6IP!ak(2l5PJbR3Yot z$zs-%id|}EJDbVJT9zT69c?7%8rp@BHnoY|Y*AI~+CH}Rv~_(gZQW>E*;1^wxhS9IMoh@*S8%4qnH%P`^?h<>8Q|3aqh@i!7bgSFL$|l#S*4^$4of}i`f)|C; zm2G&-3&Puy*SzYTpm$Ze-uE&vw%HXeeCs?SxN7T)mk99&TjgLrro4sD1_ygU4o*u*M!orfK| z;uo(@z8QuwjYo%K%hou@nrrbvb?jrw2{^+V{xOjWhhQNWImv}0%+7{^bZ z^4c&wV=7}=Y)sB)mb?75C_~oEV!qmq!#rjxjerZ*m_`*waOUA`S)Ol}k_h^c3}`5$ z3Udx;hOQF6`R*A>AP~hcppgtVyCBfNDRW^JO(YS_VHn1MMxoj4W=F>+&g;Z|FqmhMv zFML_{&LO@dZlP*h+TxD^cr!I#p@xUs<2NG+Z6GFO?TS1?)i!v_6?1EaxBNi_=XcB# z!*OHQ{6QdBch2$BZo2loKo}2s(CM=60TRoa_VA{OSiz?D4+-_uD$1 zh^H?6>(3hW=h6Q9PtEf=yZ`?Kis5b3$pK&iS_b~fkpU{8Wb|KaE#Lz-#`pyv1X3Vk zAmAERU}_XS}QYLpH7;13$%5)wrN`W6#Hp-_aN|3zUH_Jj#`kris; zPHeiQyT>1QuEm8nWR_tRVjpwqYEegzdqh9NM8ssNoac;T}#6 z531AL@nImIz!1uyAO>O{B9S2)q7y!sA_n3VI-n!&AtDBmB=TVw(w`;TAtXMbCdwft z>X0XHBFPEL{H2#DwjmuBA}XFCD9R8krlKF3B89=?84@B6)}k1?;tJ)WEz05zW@0aD zAtyGXFlym0l8`ZOAts)pGDaaWewQ;=Au@K5G*;mouA(&-p(^5{HX0!{T97v~AtOek zIBuf=&SHw0V-SMl1FhpW{$d%L;XCFaG`bf(>R>w}5I*W4GtweIx}ZJ!7eLOSJ_Zm$ z&LB2+BSMlOHwGg^j-Wy64@9OQIo=~hj^O_-J|sqFphU_KM`mO^$|FdApg=wtNot@+ zst-zPpg*c3OG2PYei%$rph}7lO;VsjZX`|uphGqzPZpp}W)DyDBS%xJk_TW{b<@)*L zKelE0nPu+8rCUm664s^qDJ5Ly<@U{G?DS>%8Rba^CijVDj}<2O{blMTreX5n0H#`F zTHj$dnPghuVup@oPNrJ^q3mfU^1bCte&+FECgzN0^9|-qp62oGrD(2Z@0BLxye4bj zr4P>L@KGk0-KOuwCgSX-?|G$}{U-nJ<))ksC+_to7#=6>>Eu!_XX%CJS3aleC8ym? z=j)~BSYBu9wWf4#C+JnD+k7W?)+XkSCv;jRUY;j-BH>7`=jR1yw7sY173ZeSr{;yH z+1w|6a%MVu=YA?)bP6YcE?$0i4S_;lb|NN%1}HiLqjNH7-Wh1sL}-APCjnOI;MM1` zW$52cDARQ4-^Hiag=pSwXt|ZBgtjMJrYPJsCttRx*$Jq8#^~C8=+M-ti(Y7C=BSK1 zs66IYkDA?$>Wq-8oq|@Tk%rxg2Aq9F`saX3sns!Q$6e{xLFvhC>D9fc zYkq0b%_xbEDbsan$DFCuA*ugvu4&SBr3=?I#FeR`PO8Q=s=-{U$hE0)ZmPw_DUE*W!DXt) zj4Gw(sb`*QzV+$XttzRmsCvGtzZEL#%_^%Vs(IdOzLjds>?*xQs+|66wpFUF4y(BJ z>f0QvxOJ+1E^D`is+m5kvn6Z1Oe?ges{36lv9+q(Z7a3Ls-k`?w^HeY!sxhSTDSHc zy5?H7?hL!uTCj>LygFL3Rv*1`n!B0{zM5LIawxyn>yNr8z$%))-VMPjn!lnb!tR;6 zIv&IBnZafb#Lii*-Yfsbj+w)H9>$)T#GVbuW^8|&tC)i9l-Vo!m28%IEa0SUmnm$M zwk(!KtEI;5ldWvz)GU>~td{2NlWA=0^{mZ?tF8vEl36Uu7A=weEbk?4lHIKAG;NW| ztF%UKjupWZWQG=q0JZ^X)e;#C2*eW%0TFbjwt8)iu>e+hMAx3}l(B8wIvJ44Ek``b z7q-^ieqBU-q1_gSzw8FzlE=ud$bfrGo^D03uI0L}LX7U~;_mFW zF5^0h?ndtK0&oBD3h(d|?~h!r>e?>lif-uMF6NHz@hJ#YuaA)K z=U#921~Bzruk}uE0VD7L2XOhaFXxi40yA*@4zK|eF#PT=?Ut@XEN}xK@BtgJ12=E- z-mX^IZ~vO`38QcdtMCeE1mCuA0(Mg}w zF97eY4nuGVN3ZFYFa0h=3A1n%OYsy_aTO!({~oacYjG0ua0l1$5w9=pelZAdu?=&v z_$Kfd&oBQDi}3e`@bytw&M!r{@aAf;73=XH^Kl>haZLGc4wtbHPp}M2@cPCt z9xtvJbM6;=aT-H%2P5(SnywK;^6DZn1Gg>^!!aADuldsMAB*xRlX5AW@(KmA_YN`- zuksc%aS`9~Amec-w{jr|aQHrQ7<=ygIx-gbup(zM9gnab^YSMP?kOX4GAr{kGqb0l zFW{1{8ndz?tFI+vFD~nF9b@t&M{*bUax{bSDu?kJ6R{!BGAHM77@sdLD>6fPax=qo zJj?Su)ANFquIDcDB8+QKsa`_f@UsH7mr}J7P@Ix=POEa)RQ*%J)t|V)(5;t#U z7x7H5HDrTw`bO|(JN99tc518kYM-1?OY>b%Gx%8hFPe;gXz<9LocM`EYAQj0J}8#QR#wpMrd4WGD+yKxy` za7&|jD+75MuXs+kvyM}Fm0S6h*X@#Xw>oz?jC*y64>^x_H*Vi>fG4y&kN5u^7x`&F z@i&KVO|LhW%lVwsd7YO>hR-e-`#65PHX4Vwh)21ZE3hu3IEn}HZm)P_`*-06vw&-O zAlrGQOZuc!I#;}PQ_pr+zw$>@@>>h>qkD4~yRo4M`5j+3a`P~05A~a8I;2rs5^tmrJ zhwFM>uQI5&bb9l*T4#HIXE$hv`=7w^@x|ZP6s^2 zi?k#IH>Pi|!9TOQ3kJ%w{Lv$Q(*Lf}Gx!tlJnnXU%#(Y+e|K*u_^!V$nD@7lkNlq# z@Rlok!XLBJlYQBny=*Z(MSH!7OFht!ceW$)VxzOPdv&tw_uG>%2xonAKYG~HxZj_B z;0ylXhZeI-{me&wUGw$>7ki^CxwUUOi)$`JbFUCn^+^MM(G&jWbAIQS;ls0i=xegp zQ?tD1Hla`Uso%C6r@nPhedc?9?92Y_3$M!$xsYe}dG9^OxBCB?<8|a8d(F2uy{q`s zr#(m0e)22-^8eN0_q{I&7bL;V6{ zeL5HQLI3lAqjQIwI(6f7@mv4#Zv?xKfBx(L{*w@{1H_3A9tIZdAn;&8f(r*C^ziVZ zLWu-BB($h-A;OCZ8D^}=uwli45IaH)SyAK1i2@m>^w`lMNtrWg)?8>4XHK0vdG_@A z6KGJOLx~nOdK76=rAwJMb@~))RH;*`R<(K+YgVmWxpwvX6>M0sW672^dsgbmiECS~ zEy!|Y#F8Z0ZsZu(phkyoE$$`A(&XH{BK_8-2)Ely({26p;(L&YUObqh0!MlMm(oNk~C2Np<>k|H`aVAH(dPTmz$Xg-eiKB@ZH+~#> za^=gJH+TLVdUWa2sXxYO*f(2*fMu_gSlIMQimQX$M)}b--nS}+C;n|aHFukFtJk-G zAAf%R`}z0x{~y2r1?0@I0{{9>B$RS{jWya}f-g3=_B!vTkRGJ4K-?nqNTSwgqHn+u zMI4dD5=}f2#S~Rsk;VNCd@(V^7W7a;2vHL+!}Bma%st%F^9?SzHuUhr7L7a-$t0Cr zlF25Wd=kphU>vTc@rabIz4j~$&jTU1lySC=wnP7~Loj_ibIbK~0x`-q-Fy?yIOUv^ z&N}ThZb~%g`Y}&6wM!7V3v~pvyzxwv%fK95u}|T^lLe7@@^T^|nHXV0Ek54^0-4mxqFMSo(SY@4+)>>`76{$XZymHZ04LVR%F$qmCrHxi) zQ`Z>}oe$S$oqZPCXr-N&S^;%6(AQkLWvab)YbxS zndqX8J{swymG%icgjY@1V0{(q?PtNb+_cE<3S8}2kq2{n=B33Ro9wd9J{#AjJuVI3 zR?+lJYMntc^XcwDjY|W6z!W=AC~Ydd~A5z3<`mH2lD}D7Ja0sUI|y_y&)Up8WF7KOg;+ zt4^Fz-__2(Uaq^3u}lTSC)MNh_22)W|Ni}lwPfsTAMf6`p4B{#LG!EM+<gi5ZtMV5Dqvk%1 zg(^!!nho7r*h3%w5Qss9Ow5h~x%9M7VkeASY>EXe;DCpRLX_eZsaQoTLZya3F{0M| zbUnV&&ro9u7u6DYMKhiejcHV)Y+(4lZQX4pq_ZK6QXLf%<$@A2KWg%r(A4HOx!KJ(t#WaP`_WLgrbKKO)0^p3=Q`QxpIfpGT;_Be z$B>Dy_E4;y`PAn=`MI2HJ}r5!Y@2H2Nz9D&6QK!J=t3{^&(h&@gT|v!DkbMohF%n- z8PzBjbJa#u7IZ=W+UQ70T2hn3u!uzYlWtNe$dkSlrZJT%N7Xe@QwbDkx18xtdD>H- zLbRgY8eq^aDbSxD6{$(xr-ckEqw3wzYf6>sRH@3)%B5;s%sSPcj9OK%eif{t6j~WA z6tF^pEv#u(>sn_ywXOdx2A*5JBwOiPSGzK@Mozpbt1Nm~zy1}lLVVGn6t&5~9u~2Q z{h`eGB1ds57P66*tp76Q$F5EmvzgWG;Nqv%&3+cNq1{~Stan+_o))#Kby&S3r&`y( z7PcqjU}kIT4_)=Ok8mhp^@8`p})XJ9ne@s45pC&w{yV+l$zkBMC5 z$({s?!75hkjND`=W0rE}!7+S>{A4R%`L2T@V_w&bWiNlZuG;M~n8{pbuLjr5X;yQX zBfMrezgex*gY%r}9OpXU8P9pv^Pc(KXFvZL(18~8pb1@QLmwK^iB|NY8Qo|{KN`}J zmh_}4U1>{S8q=B9^rku8X-|I|)S(vjs7YOFQ=b~usaEx>S>0+^zZ%xDmi4S@U29w4 z8rQkj^{#o{YhV8w*ufU|u!&u4V;>vY$yWBVncZw>KO5T7miDx%U2SV$8{65|_O`j* zZEt@Y+~NNg_qfSjZgZa--RV~My4l@scfT9n@s{_z>0NJo-y7fg*7v^o-EV*Y8{h#K z_`nHXaDyKl;R#px!WrIhhd&(R5tsPHDPD1lUmW8Z*Z9Uc-f@qA9ONMv`N&CLa+9AN z0Woc-yQFH*Zbc2-gm$M9q@q{{NM>+c*7qa@rhUb;u+s~$3GtOk(d1BDPMWZUmo+B z*ZgMYIp2BDe;)Lq7yal-UwYG@9`&hL{pwlYde^@m_OX}!>}g+n+ut7dx!3*fdEa~A z{~q|k7yj^xUwq>qANk2w{_>gMeCIzO`q7vE^r>Hc>t7%H+1LK|x!-;7e;@qe7ynlR z0stZT1O*BJ2LLPp0000t2jT+&2>$>92pmYTpuvL(6DnNDu%W|;0|Q8$NUvi}ZQd~is@ym`CySh1qOj_utilvpsp`;O-+GHlOLA_4>g z2!KEU2=phPf%MrI;DP}T^xuC3{zrfS1Pma60tqDWzyJyi;Gu;Ka;U(F13W-thaZ;s zzyldV;Nk=@y7;1t4%Ap91P9R~3PTEcL5)N@(BzXr8X2UM zH7>d2lv7?1C6iQc38a%#I&i_54rI_k0~$0y0tqCh=;4SRPH3Tr{{=Xq00SV%}q znIeFC0(j?~AL0q1hj`*yVRzE;i2}UffCVmOA4D7(L?6NoH|+4k5JxQW#1vO-@x>TtjPbz|^OqoeF13f! zdMu$7lWibPl=8|ZqZ}A*ioqsxSzF=7l~iI`=9JEsJq6lSW2N=hSE|9KTF_Sot@F_| zr*+oNLO&gs)NVap*Ijw(m33k=_tmvuFK5J?TtD^JS9t_9W}E>gM3z)ms7Zy|WT=gX z*#VesKp6uYnE#f8Xn&t30SZiAH=TGu6(<+gL76R+O6%cv5n*79XIpWEm1oy$oFf1o zQO`9>-FBZx$0l|WFsFe59Y`0R>)Mt6Icv1nR2=5INv@l21Zp&Ld=>$}@WKicf1k?v zxyLa=!V?&P0QMccd_){iL=b}^J~&}vdOjaui5jl>0J7MQ`u)51ZusfF8OA6hjxtUF zzm7ldNWYHsf61hgDIketlVSoBn2a<)0TM7wJ4#ZNt|TM_a_LJ+vXP8(gr+nZi(GD^ z(4zztC{AI(b$$xe_b3#w6p`>Xt~!-=EEOIFY>!SAx>M#lU@21}=R=vx+^Kw(EH^2j z0~#2WiT`HB!yR^xbBh|0YhKf#B`Tl+71|W4rYNix5=&SIcz|?_B`V~QfQHq2)(=P2 zMRbXgR+mB+u}DQI4%O>U#u}aa5qD^Od1!_p+<};s(&9;n1EaPO_HnX-&M_r%{Sk@q-h&`pwnqR4;wtkF1lACN5=0NG(+Jz8 zM_heKeS=hyhT_Gd_QA+~_@mK{>c^w}@fAq?>)-!;6s00j>97hUAYc=lr3M0!uaEr^ z1R7w0G|jP$oZBM~^F$a7bbyA!>eUG))hRnoYKqROAr(2bsYzw-IT&zL>7pnnBmZ`4 zRG8vW2g=wwak&OXr&`phHZ?2US_nf+^iXnDMZ|20C^=-@Rfi4`MAq2~j7l8VuiUEL zShY!wgEZFn&M2s6=?Oz+To?INrAY7=l8^7DYY!3CE$$K$x7EV0cb!WsNyaOZkfh`T zMv$R7?n?vt!k3Be=qv`2az4@9PxMY{y;)lL!Who5hBwUN3wvyM!5bNSe3z1zn5>s2 zJFzfTd}0)bjd5Ko=3B6`OsJs+Xv|4nHKRh%9S6;vc0p&;aCT#-9qq?wA&WS*)--fR zjc7Ec3)U3#PPX8sF^h}wi?tj!-7#}<#thGR?n0EsJcgU8fr@Aj8chQz^#3yqm1spx zBY}u|hM{=-W=9b>Pbz~=Fp?|rik&B+0*KT#mkSAn$fJ|nxrTC~a}IV`=ekCjt^fz{ zDNiYVL(sVfcCkBZ?PzBn37MLAsLti@wmRVoOAo{rF^N~VO1=1u5_-}L>x63^9|>_# zLJh`Vo*1km^&RVc@1>-_GSmQk;T3*8vfp2)4O#w4>4E$EAC{!VZESNpNLu0&mZ)u5 zA6W?k8GwKVJvprAqKW_t_#h3X!(45h%2gtilLotEDRHSVPKrX|6fv;GMU{@VdXm$o zY+J)wCD8zZ9FeXrWn1B5D&VwhQ%6(uFJG;2xfSBhn`kH^cF&QFqW?O;Zj~sa+~Nwf zY&_$MxTW29(YJgfT2Qmzl<5(TfLwkACHh)E-&d{iR+>$heTSv2WNipV#tvh);C09V zV+eisGVo>dwMhf(k-^v#knxI_Fojh3AZPEe+SktZw!8i9uB7$x1nrT!e}p3~W{GWb z^E<8b^6w`jW^4}gvTk0*WhXL)z449OWukg=!!T zvoeGHPSDS0@GqvP^2xw8H=@bdbEh)aQ8)hC#g34%M zq7v|doauZ~(rnbGN1cn}jAJvufbAqu6`SwU8WYahr1ddO8~YApyTj*hw4b}+;gUaH6@dN0YsfEUZ5a(7(h(SKYESBU#;}vu6RdN>;MkS;wZT}TlNyjdIgmm1JB1lIp>}5t! zw@6~7E@&h#i?|`6NH6bVE0~looTM+BG*=CFEeS7TMvj&b2pi?L;ZVNd2U6kt{X(szHb5dkh~sS|nQfmBH~c`w{bDV z8io@A@@Hu(=|zi|Y45i}t^*WD1s>)nYFU;$x&I?M#E22u7c$QCVb%kbALCRF$ctkY z5k*-M0Ky*v@*V^eArO*Qr^bb7RVNv^R;XfD7cz98k|=njNbh1-A$V8vlOuYCf@m2* z10;h9lmcJiKQS1CD!4yVGA7%GK-iXp^%Ep{g>D(30SHC{mjrRtv0K!E0yiZqE|elf zZjx|#;&Ai@L#`5ASBQRTxIvr(DW@_jp>N~koS z27`96sEhcSpZd9<{0R}j6N@1RId(Uod{>|=b4w)wOv99n$MjK!cV%=Djm`9X)VO2Q zldfzt_MIlf(AyAHT zH6f7{i(vpV5CIjid%VXPpHWQ(31x6#XiH%AY7ruKQ2&`yQpr6znSp85s5<0|!saHH1XqA~nc|5r7C@GI z1#M_aZbA~5hGnWn0)yA)Slt#uYKd5{nm~IgK~;io7x0&xgaR6{Cc8=kC_p%01apbx zn|{(lt(ihMw^`j$Tc{!_0=1ZoA}%OILd;sM_U1#nf`{f}M8CC}jd?qqf-TA-Etc6G zsbZba!X_lJs}HbSpS6dnrCQw*a!MqGLMW}oiLZOaM$n0bnFuF>w1|GRfjg%FYBa2H za){K@h@BWNO*cMFCw2SfiJ>U4qWE8rltn;TV3|Zm6L3kacrBI+pZ7U{Cc7W@sWBzn zpDf$5F8i_$^J>R~AS3pFzW;-FbjM43cZ@7kVzTBtS_-2x6Qk`|eH?0JYkHxmlN89I zjk|YFoyU$vQx{3|dEi)NNrSW#S{2m?qRo^|O2(pj0eVtnW?UwZW}|vC;iEx{6D80S z<~L@V@e{If06!`esbNiPW}&_Ze8Tq`b|xB3N@sz?P?({cZ(~!fp*eEvP9AxE8QC(B z10jVmQ{mTA0Vry9M|d(mB_bl>b1TC3Uv9K) zpBk!XIjZD_s^0s(iT@>TtGaElI+qZXmjbj`Jm{C{wyV^YX_;1srHO}2$9}1Wg-_T< z`U+pLG9j5$0I>ycAmk?scSM~cEG*|kbVx@Or-pl?S|#b40$ePvQHV;ISqsN18t?$R zd9R_u!1UUi=^~jYQb(mioEtc>L{~^bx0S~wut29R4BH`kRCL^VoNv;e20LF*r*y+9 zE}ANd(ThfCgt0ITo`pz?fpnhCmSE}G04$PoBCB)oIUo*Es8^gyD+{w++{Iq}vL7>d zN-3Zk2{IzKr3WgE$+%)AV~omJ5`~wgjsZ_qvrR~0jY*MXPy2X01GS)c7#&Jufn2rY zW_BD%k7`Ia)v?qnaA`vU`#cCJl@yVb z6BcOfJWAR_lxZap0wQeKB8n=KMO;ZJ2Y|xtL69*mYnp%W;D}2a9C|qyQu|4?q z8Ulre8~>MEoTDfwWLtjNAzi3j44lAJWGVFKz(y2us8Wj3nuM7JoVyi7a|lL(BvfxQ zgzQC{?Lw^6slqrsoKn;#q*Zh4k}do?h?;o8jikcW=`HKSUlChhEKRX3ZFTSxz5X>K z#Gc!~xqPwTZK1LLIHWp6Hd56bO=lG3fk)l>>$68ypANt6gmrah$ zPO{w-FKWp`i^)`hkvF*$5%9KlQ2{}E0Gp#sZdNusK?FZ~8PTM21vQWc>1GD$H>1Ij z-v4bkl~H^;W>c^O8?~&XqsKKnYf?VBe=1?Q5sWr*8ytKlX3DjAD~TOGp>k7N9qDI; zamqr`N;+aD6L^|ZsD@8I>8JV;fE}UBRfTqA)gJ78sOcELIY#M z(SUgXXkv$GLIOXChY+W(Y*L3mRfkj!)EqK|-P*8F7{N2G9ZPM73I~NZO@;`JBAKHq zbHsjUh`&gLD$P~XV?F>D07lZuUMnXmpQVQY8$_EaD^*Q~6Iia;aC;3xQN(`UF){KpS0dEu;yxhI@!O--hT&73Hr00t)N=!##<)GD{5u@)EDE3 z-$Tk{;WUmdDjVMT7GLJuLsQ63rf2r(c~G|7>3G}P-s~eq$w1)*NvaecRW{v-+&Y1y zZIc`yr5V0wOhl1;N>Kt!u``U9q(lMm+C6-s!2mw6%H5strJ*;l{4;40w=pH!iJ|O% zr<2;JOCM2av@rlL!MTi9rih~)I;N)UXM~%!TR)Y49OdP+!}1}Yxp<0`m;W7T6s~~l zoRR0;*!9tCPYFCrIcxB|%|96*F=54{L?C51;)|+tMTbXp4KAW}o%b>U`jRhq1p#FV zs=&AoR~JiYE9sanQ(7tAq7k)3S2`*L`DgKU90&fRiv7eKl#XtEOuygw4y7L zuUm7-CV|A~^_IFgH!iu7U8Q11Ur8t~{DI#kMXqv4?zTp+iCZoV=?&{FY_u$mKk4w* z=?;ru`Nb}y*qj?OasIX9czueS1hT8xabSl%M!)kS4(q*p>)OBl-2czm#G^bCsA|9% zjKZ#w8`;Kd%*H3fpy!T}$VA8Ugn3SZeo&FxJth^7_jqJW$6T?F08v1oKm!8>5-?bx zpaF&r2R4KV(cnUc3KL$mNH8Ntgcu)gyx4Id0g@$27BCsWWXS>tWXOo%1Y!i55h~u4 zVZs0r6DUg*C}H5IjD-VOMqohmAVP*OZ7QV6Flx;R5+p=5VAa4>s#Y0nunIPZRS93o zk{xT6CJCAc43Jo;px{B2C+&7TiBcefl>}7!C8?6HO2U2v91g%&aRI(1jjk-9psvXQ z0*wlkEP%iOhHm8=ko#FK3Ar8Kp4RXdZfMX7C07n@IkM%IeE*FqCOH_v;lY3tBR*^x z_;3P>cMnI79Kdn_0hm93j(9hMb63fa0+>9Z)xYW!(qwd>mOa$C3bIddcz|zVB z$P|-J4d9EcHObtB&Cb`-j1$f=2RQS-9|L5QP57iF4gbqGw`7w^C>78k0V|EVQ%geq zBh*kVskHP`Ehoh<)AuHo&rtUO4X{-Gu#~b;Q~krzzV}ik6;@4GwNlJjHN8(v0Ii%f zSW_<@HdJ5>1+dUhOnhR*0Em}zDoIPqfX^nm!>HlPtCi8gZMVz4OC7lW&f(RKFaVmna zi6{XL87ioNhy#G4sDgq{G9am^c5VtLnQPiADimy@NiCbM0-UO<&LWF}v&Lc^aS2Gc z>Mg85YiP?iS$YiXl{F76w~jLg-8h6adyFJC>3S@61IEP6^wYNT473PBiy-!xV}|R1 z*(twswme~z?efjU^Srpv)x{V&0vv8^FzcRgc;4s7oBnz1B2LbE-VPJsx5gOrOI_-r zLytTFu(OR&($_=RzW7SLl0R;%Rp3DT3A8}L1R>zx!U#>g5R6hVzz=ZfxVI6(Bk>DpO6GQ=2$7n>&F9On~B{5Z837GbNyg z`-$O`6!n@+#ZUo>%3%YF7#U4DaZHNxlnr48D)+SMh?zPSsoduuS>@_KtYV|Gf(0Kj zy{Auc)KsTV<*NIvDo)EfBBqXIsXYFQh`>@LB=>`>MN$$=^sCkZs)a3YtuS2R@|Fg; z#Yc0Us#Moo7`;-NFjltGm9K3|7qZV?EPRIP zoX9vvvXpR)B|<})$%K{=ykHGzO#kc5X#mF%xXA2i-;|nOhNc&C7EPQ6=}6Hwmyo3y z4V-fcXUnGMw46DFoI~Wi4AV4LmEOm&_rgGSHkR zPMf(*<0S@}z&R#vi1*CPTn3t!%Zma`rx3TiO)hoP$?YgNg51F+hi|DX7wy6{vJ|Tuk+;RBj{2Iz;n=JE)QU~Xf}Qw?-Bqa4C zsZS-i!TV`2wKQ43`gL-J1Uf(i63~G86yv}V*?2Don8%$x6Q+BrosW^!IL zBPkPFn6V5sbFz~nH?i47jK(xMyE$r4qsx`~S!IMc!3k3khzTMf12jZn5fMN`M+JHn zKf^=@L;wodI`fp9DC8<5N!rYupf{<2bSizzil+^CxRsVg11VLU04G5R)!547wf_t{%6E{)CGlW0{j%Y#|Wzk&t>8eurKrHR{$`Yqa@%*JLX~x-q_n(vO7+dB}TD3h4Z$FANL|?dr*htmtUR;uSxD#oo%*i_aw= z^DrluK<;toHNSbzci!`#*O#|{sXU;PzO24!46Zv?%+>Go$#=P$PGetYXfB0k@SL<< zwmGveyZ=mSHw#Ib&pG^X=4EH|Tr)-_g3gbC8ELQ1NSvX@5j5L=$~!f51b`v~KO@>~ zFCm=nOrSTe@NJ$2iOTQ^Vt|g4ztf-wwf4&of5V|PrB^|V1XOAj-D#lJQxT1zp$*5- zr=7vF+8~+cNuJTujkF>O%_xq`F)HDawW4}9gb_YIU_FGjO02y0t>E|lN7ZZIyTu1H#wBtTA?j+uRZE61=Az=S}-@dyU1&! zUJ1n^{I6Do58Rr&NzAV#Oe0qeq!(MluzN*f89cok#tIV_Ng9?0#8AnwDy>mpzbX3Q61iiQlGU6~RVEU5c9Xrj;0u zaeK$=u`A0fy>Gjh;W(e}(VpMn7#}3Ezl5HjQy0M~j(VHC7lW|D;ty((AH};L#e>5B z;h)F4poud>E3A+YVYrObtS=xqFeFVdgiSHTxQv4!Gt9!){5TreksXo4Q!6a8LY z5E5{%;ki39dW|-*IxTw6Nqo-%i!fb`umr#^J906%^AGx1k7Dr@{g@(1im(^+yEoFs z!g?e@Dx^f}y1NrQ3d=BMgcabjBx!`kHkrn1Y!XS?7H=sK548Z!w1E7uw^B+MailSM zNl|!NQFe6E7lqLnmC?{6w}%luZS$pDlT2d5%Ad+d9+fgEgFS!Lr=S0YCexRQjg3jKI@ALfC>L1Fv&tI zw1)C1nIQrLkb$2l0hu%aws{EcV~9)hHK+g_lq5>R8A=JDncC?azKOrBAdADe);K*|A)rkb6q z;vLLbor18ynF=-v#LK$Ejo0fb?qDmxB+PB27{kn$T}lidEDW*2gbSb$p-t2z%>qJKbPdDUq*sZv*9E`= zcx_FMlOW16ksHxX4*Ja?0Zt_8kyC4cx46UIA`SJ5Rn{^iMueo*Nv{7ixkO3~qC^}- z>hhf}`6BzouS%gr?CiS)b4HP+#4j2w?Q)eF0>vxIp(0_Dr#queAvW^lJG)!L1{*t4 z8lvMW#Qt0(0&SB_q%a31F!doYodrhw=#RGZPWhUzx_i+4;uTw&BoHfEU^#$Wxg`1- zF)Ny%PGYf0nE+3sBPEQn$}2}zYSHMJ(YTe{xusintkH6VM;9DDAJxYw167IPDUk_| ze)Q2GI38^_#<@+Wv1&J@+2y?332_2mz>gRX@#(_@jw9?Hm96E1Xc<3PA0&k1{Fz zLkqJw3kDbqEdR<}3 zLSfBP;WG3>jLVPhBlU7dGRjUPqQuQ`7Bmr+1dY!xy1M@;DH1Lcy9)ag1%=S}?34Ux z75sdkdwZkx=uZN>FD)T9wL`B_QP7>u75y3{r(Kny<2wUYyIGOiWPC z$SGcLGTz-QO2m28lxiIP3kxLvzxOq^0X(Yf-6#Kj>eSu{40)_&VB%jDybVpIw&F0= zFIiQyl%1!ND(jjOC)u4JDd~cE4P4zSyF|~SQb3acUv+byV}0NoHDwxnTfy8mzR-@+ ziOjy->AqUQ-;hl8NDLG8ul8XU1p|;~0oQF=F$-vb&@9&woUCw;c!l8?mSK8* zIM|#`8#cJJrePQ!YcZVRdgYMQ8XyhY%{Jr_H>|@q1QI)3xg1(p1Na-Y+@ek~#cLfC zjg2rWDHP}$%W3hjrQNONY!mEqJ6YUT0UKj6`8lHy6K6alZ=sSO(ILMgPrbWXG}Fmc=~ou-@h0!`{ufzJw{_DFva;o0#^~+k zQ624D-be{w9;UwV$BCv&a$4MU`n?deiO+CSd$OmgDeyDWfyd?H-!pl~7zFS1=APjJ z58YsDY|U1sl{^9A4-1_nX=FkJX#f?=p9uirfD=s-{%Wvx0NWH1FQjx!mutCx*R^JA z*~Ih~E}%@m^mh$d8^P<=$^cW>fE;N6AR%qI6i)vmZ1`d#Q6$9a6r#C&&nar+{|Gz- zP)p!aX7{|4Mnu`f_UvRoJ255!&Q6~_KCi&L&m_`L`vlrlAuz{wqdCqasKpP`knLOv zBD5Pqpfhg%(rx>a+O)HyZG|x7-Y+~(+D}}@RjUU)LIX&y+2l*r0WTs-4Qo2MF^uO{r(dDD$1e%kPru!&7801Bvp!4avd z2;NT9ot0DyijtY%W69qIN~9PmK>aj?1e#BS-rpq)uvp&v^9r!93btrUn^^g$Dpi!| zN+Y*kiuM?0n#aQEB^MMb;<*hnXM0(bHHK)!%ZUxRWDPIxK)0|e1E8u`WmQ%+FV;yN z3FMq!y=jbZ!NCm7Sx%0*CrpJgR-bAfxyq~ZQ0f|tw;}9&@d*I*QJ+!%b6xo`ztga( z=9UIH+X=vGt#*({e{}y6?&{Bq*BPNr$-)BGd|`<>*8%GE=3m3t zq=D(*k(299IyAWvA^})0PA3uBQ{)sgg03=o#7ya~CB77fMPuQrx%d*K9+FP^cjC>? zIU!6?VCjH4nIRGYh!F}D3@B(2fk6QS1`;%AP(cBQ1sO`LxbQ*4g$V@+AfRvnLX991 zg#0K`;XsEOAEsoulAuYL3O^2{X_2DEhYxJ7yg5-L!Jq11~fzhA@9{@c%03+0a z7!!0*kie={5(&0y*lIy*0*nJV&Kx_IBZ2^G0|032_O05tZsW?WYxgeRyn6TY?d$h1 z;J|_h6E1A{FyjBjiWf89%NFnBxN9d*CO~n_r1IJ_1xB9 z+vc5}yLI2;wQJuk{yh5e<-40t-~M}d@3iOB9z7Z~0RtwS6sSO;LIe>k_uFy-8Ym!w z2oC3)1j`jT+<_4WD8Yfh8Q7qM5JqPlhXHnYfCM3mC}IvHO2EJdBZ4TPauIYOpaH@~ zmz!w=$Y!H_y|XrB>~)@zulHYAa#k@O=0HkyVXeo4L;TLBQo7!hs-;U*k%!gXN4 zmRJfmLURAb38&na16&zpl~m%0W0Dae*^x(}9VusPsgYJ^XP3cs8J~Ruh8dHe@ySsD zX{FUCpKYmyP?CjCCa0kYkj0TmXU$X=N z@M^2E!a6Ih3(z{Nt+qO_0I$5ln!*CW2Acx03#jo$u*vqi?6AZ-`-K|OIy)_~UsQW- z3dmARtQyWXyREmzPHQc=x>Ghu7Zkvy(R-e7CVzJAKJ>-kSkL$Y4MP z(FaIigvOz6eTKjh;o*WEdMM$96mowchS^h(I*c%e7=ei;nkYevA{w|agfR|yrj!4- zDH(c`IwBe5@+eoiLS=?Wi;~l85crz?naNE~iirKpBpiiAX*dcvPK-<-oC6d zmb!#N!CRg>1EeB7ZY_@64CClx!@IDhhnrbao)9G|0UWA^ zj#Jc;K(Z(y{fHzanbc1vMHZ*^tY=7JNZEAqfVi3JRHHhTt6UW;R)z6axH2OenYAlk z73%`qLKd^)2(D<6t6bGmLn4lag*|4gkKeMRx3bkOHlmAK-7*)mrbUBf(ZB)ga+f1B zpn(lYQUfG7z{E%}$xH4l0siWMm{O?1n2k~-KjWA|IHs|%8Q=j1NI)wgCQAQ<$Sfid zlL*H?0-B%Ms3X1vNkK@ELWF>(m#7SzRupi6fy5{Q!pz9eIx-eiUQuRLtca#^G7+wA zgd-oTnx%+#7ICHoWlgbJ(~efPvS=-81z`#}jRq8LYLinL>sr{9))KMJvur_$$`!A; z%nn@T0btQeshnwnwOvI4n7R~M@b(zT9Im1ky(mUAs?m*dbZ~Szq7D%iL>x+vfR~Bk zkRsBmZ!Y=&?r8&k&fwxvn2~Uh(NBJ(NEK(yBvXzH^QIS_X-|?=g z#q$pCd{-W)HZ`d;{aj3MDgzmmz%~XDUj!DxfKN!k2~IdrPj~ZG16lts0=TJOghs>w zw6fJeKJ96N4!~CL$?tuB6_EzSmz=@!bV>?~4FhXLRR0}`HJrf@o+wkqBC6(p3B0W6 zc%wpvQOQjbv|pF(hb7Q*34?katpvLR5dx&pflAsRqRbyczf{@Osj>gCA>BnM`qod}v{i4f0z44eN)DHzxWvP^;;(;=*N znKh3Y5@7CW3?<23o@W)e$u+0!(`pp?npCbBm8;O1pjsh8LbtMF zDB4YlhtiAUIx6Tv6S~lbJ~X2JGSS5yaksctZfingxyq)LrJ^z5OFgr=%xTU}vTwpuw#a zC_n@lU>qla)i@Md#DRz~9QheY*$KklftRfV_c<0Y>c#du!u)@oO;S}%Jqu&ZJz7+3IJ)_{dY-v#(r zzh-bi5B6&SBVb!nBf3`$jIndFo-tRM*C<;VYc49ubBv+}+Cyh~O*_y;WWnGRv@ zm&5krreTwwWB!zuiTKT*c!W~jOuf$4oO`3GlZqxYnJHI--FPY)YbT*+Hf^>PP>qc! z$zOih0BV#KLuG9Y-OAgX85X8U7w2gCv)+1}=<$=k{N_JD`gv&bMl<@OIjrHKB;C^a zZ?2@Bjx-a42vf{q)v?&IomBx(hN#X?A;-9(N2>`{P0>!Mg$}I!p9B8R=;+#e^jhs0 z)psBj0KQuP`CpHWh5^jg_ee+uV2`kkAcO>n44hS2fff6})r7EHh_K)Zf}4jBNUC*D z3dTr)vxOEezO z?AXObp2ZZCl{mz~c-BXJ498U7E`k4qN8IB?V8p?QqcnxhLKI8~L|#A&1kW6a?158H zxY*4cgqOvH>P^`ceT)LoBSiAjPjJ)IIHZ@2)9-!Rblu!LISuh$WI~Rl)f69+u^F1- zlRiz2OPGy7u?$t%8TL(LLphWbSxQ9hja>v9qop5E2BlCAB~c2F`yC~pfSgEGnjO** zN=@43;9us{9{_0%u-T3S-VSuAj_Q!x>m;D7xrYSC23GyrRbFL$^xAq{U6w8*#>mW*&={?PwM|Ii1IIM#gt(U8cTp%Bn+ElH0kkY%NbVx^XvD3-=B z9Kky0{_6}}uEI+|)2A|8&MbNNuAz=;!W#xBK4 z?b+i)eZ-|4pUadDO@zu;^xX9&KqXoLcR_%6VPbe~qN@}_}#i>P*PsgepA~Lr9EKM8qx`SJqer@L5DiM9r98QRUqY zce0o_*#s1U%$kYQ>!q2K;@l#Nq?VeJIC*E%B&3z?O$T8=0cIu|y5T_~*a^m0non~+< zgveN4k!4=Kk>!H6-uNWkjQ~+xMnJDh3ccZ5FHxgY_$*z z=~zFaBazm~6$1ajoXk+Tj_amMhNt>TPo7-9PSn2UR$7GWaWSU=0KlXmEW%0(!m@=F zkp;r?S(1Vi%0NXVZqax`BI)%U+d$%YvQ5WAqM)K!=qU}HLEHw#h}x)ZEGbiQs7+NI zzz49v1F(Py+^oimz{S!m&0>T=sLhus04Ryx#&$rccn#VRYD>BV$qwq$riAGAD2|5A zZz@-fEfB~kgvZg=qg*FQH0osih>y7s?q55s__hGNI)yiP@Sh*_N$v zISS1&m$wFhan&595I|eBtwhyUb@J^Hl^h@%B;R@j;(lM>MoMZbECNLA!4i?ea>V5t z*TRy8!$$us7Fj?){Vu5X|*2i0wL@9zTf z1{44B5NB@?`!EQDa1Oh04fAjdF%{?V{kni0yMPYJaUIVw9_O(h+i@M=@g37~{K9|^z(54!Fd-iR3?MQL z5HcedK_eG3Boi_TBytguK=nE@3|vwrBl7!7FCQ204QDYXCvqn1fF)njA`h|(Bef^7StAB0DlI<8mxNu`hdY4WqE|jxYG4aR*cH7{jpqa_eOuNiCeHv{trb3VI32w=d#-mXD!6as{R4y-^3G_*rMG(<ngHB|4eKo|5uSGD0(z(PZ{ zR&O;|cePi4HCTtWSdTSXm$g}+HCm^&TCX)*x3ycpHC%Hw?^b|S*Y)7&Zd~WJUhg$u z_qAXDHDCv}U=KE77q(#^Hex6CTdx2H*tKK#O$9KtVox?@SGHweHfCqGW^eyCXLq(| ze>P|j_6pGTW0y8!Ab@0twra07Yqz#*zcy^gwrtNfZPzwyuK-n>wr>AL08lgr{B{NW zwr~$OaToV+3$<-0w{kBxb2qnhKR0woH)soYa2vOETQ_o7G<9D$cN2GZKlg5j_g|oP zL}P$LLo#}&w|Yae4oJ6qzc+lxw|vhxeb={rTeNw%@_O%gdbc-zpErL8ID5Z0_=&fH z*F^wez;`!v1V2F$I5>nq_yIupgg>~2Q@Di}0b}1chj+M#e>jMTxQLHZJlRx=wtnoIi1(Jo!>d0=eeGToyTW^d1`GmK5p-bKkr@E?3GzI{=26wukJNl=; zx~PA5tEV{tuepg^xTN!XtRKLri!|>B@9wtrurG9KtMsuKyGLVsnQJ-$M>wY|aEs?U zqYrtdue!ExJGXbcw|{$Ww|cH0`nVH$i?i>Ill%29xVRhox$pmav=4c;cR2uOJ4Y9? zrx!s=MMdZRx)#uxC3JNk{IxW@zf!*leb^ZJ?#G)b?#u1~njk2K8x`V-7NMiYFG8~ny+ zdB)Q_yu*9STRhPhz0n^%(kDGh-#WsZJCWnMtY5qJf;_GNyp{WUpws&G4t+-RJE&*) z6Zm&X_BPr1gA{EEjq*DJl=?>*o5z29ql+*>)M zd;Pf2JFYu8)zkajmwd+;I=#=hwdcJ>XZ_-Dx|W0V%B%nR$_uzU$|HXN$YZqx%yuLNb&CI6wm<`26Vu zFx8X1ydSyZPr2zA!Rk+R_15^{uQ=Ol^z>_dqrKK#djOIyGx=mRD6wFj8NJV?X)M>IejctRvZL4yYoCRDhPVMB)xEu7Lv zsl-Ez7ZrLiGf!GYi~zBMIPDjn#I(F^cy{A{do_%}w?_<{V`q(BkMxCi< zg0?iPTb!Vw;!G*drmD=q%k05wDzB&l5F;Is638tH&ALekk|5lQ!maAE5JS)Su`tGX(uuAjl3@f4&IJE_B9mculIwsE;0sd7A&D%~$Rm+VQYPN! z(WaD4L@8#TZmPhjgdwW)t+W%&XosD0+Hr@E4!Zm@Of*_(<{E3R5oaE5R3NDZal%0Z z$cwTg=aB=HWa!E)#XD`zI`7;~yFL3%RMABlZImX@Vl0A@TG}e&miwv#@vG^g(uph* zaa1r<4W)AMBFC;;i>#eUaxABPoU@Fw3QHWx)hC82WGhK|-PT--USKf)6esyXNeP?gW`>{=|h7)Zj?$ zUEq0pJFfXv*j{`Os5tF76FQ*njov7g_Jox$WKe-?42h z!lj^bL)5VZNhZdeR4t;=07d^@zQ-P?dW_Vms�E;Zq%Ot*uVRXnVO540WFwZQ}c) z@ntNc5PR->qL6to^)-Bkkj-EJ{rOiBM*gO^NZx#i0&xIENQ2V3Itp@tlruNrvEf z4lmSK5Z*X38!~j72e6Bp*UK%2Jl_i9LLmDp?6ZdCrrb zqv;g)%8?bESmg=jP>c7Z(iBd0MJxo=3G;SU7YYf|A_(2kgb3=E`&q;Vs49Xzo^{bx zT?iu;ot{nR$B6eaq6*f_2}kkQKb5YOr7MLI0Rzgs1Py2()w?J}W2(SVN32e@0OPo` zRo1EQZFH?8S^4^fd2FW#ZwhNw2`g9Cy)in|DM3*A&?Vl!$*(KeD_MIZ##6|n7UIwb z!H~Ox4iL3B2S}rsemho4%vG^g9IiNu8v@m`7Pzp*fNX2`f!hA{wtda*ZYj}QZiLsh z(KYXOK0yCm>HL(y1vYSF9I6v@D1})9F^6Xeh`oUls4lQFkb%s?EP;+BL+yJgt!y&U zhjiF0Gj&UXHiQ$AkT^#2bB?b5SrwEnq@^{s@r_yZKj{guGY2@Jh7Oo28CAf*MKJlMA9aHF!)k!(G<;E&>7 zRyt~(VRsfXCoj)K9U4=?0TQ7OY?NTlZQf1|Pq5Xl*03Oc=5Em-p^r(B0%W{U!z!t4 zWi0<|IlAhNVmqEQ4}2L{t+J-|IBdO2KYL(cc=b(0oI_2-k>VZcXhm^Im=1~%ZOT=? zvOV;a=he1ahQNN#utyN;QI{Ialt8try?Q8e>$x|@o^`En&5B%qJIi?fb+Ct>WPuM{ zTTyxFO_EWEgT@pPJo?`BomWSa;ePJRShEe(UG2Xr8|TKeJBRF zDUs$rQv)5Z2*Y^@Tah_^!|IHC1bO1RXV@lkuu%3j*RP)C7Eps1Q>#Z64iIap?SlUq zVAr}YS6fu6dtKaO>rJ4Y!ws+#^*nt~w4k}s0(%S_k9B1H!QzBmhIoJrxIlvy3;~XC zBz0gISUcLiuGO%8&DUbWz+B@h$6oAW8mCakF4!s#&~GQ}z9vU27?Fug1Y+C?!Gb(i z-+FJr;vQ)7B_B@To7(dRi}T=Y2b!LZd3=KsS)Y2tWA_t#_UFW}lPybYuDarxv233QBr7BvnSPAuOkR9U9l%hVJ|JaSX|B}exsuA0*nu1*A=J)HoXn7fw6G!y(P>Jc2nI|c zP*D~2;5h^bu}aYn`wGhbL?2QC5;Cz07V8KhVII~H4^7btp)d>Wj2i#aL1$cG7IVWE z$?&qO1R6Q9`cAk3@ao~B(~?HE-Y3=NR2w;hS=d6#^Fu=MB6IjDU%^8&2JY{ zs2sxK5_ZA;cA-vckBjC39L%WfU`T`bh)lZ3j6gC3uw);IGHd@x4QuAI8$c@rN`P(H zK_0{bsX9On)B!OMjdR)t8w?_iq-?ty0@Q4YFprWQv|%;?%naV49NI)35C+uR0gLdZ zOWx8;XwhgEuL|mDl~&*>wLvW9ks>@`1iGXhPKX`i$!18Q9q^@&d=q9=6E0_H7~_h& zPHh)#=_sLL8G@2G?BRqG(Y&UbCk3=fjr2%Y!du3{9Jr1MNJwSIp=GM111d%w z&H){iAsD?f1Uf)wWC%;q083PcWn88pNMI1kXdRM4UB-}0y_6lWln+K=iI%3y(BT%4 z0}Z^&>|my1)Pd`ALj(-rUkrzDM!*Y-;T!;UI+$;iT4umP=Ut*9vku|_`XC#?Avs8` z59}p5rcE4l;ZCMTTo?)=G641-VY@~^X2wAsu0dQ72Tj2x8R(FxB4HfHL0m#dQ7w^6 ziAXZDXBMDTp*7GK59lf<%`B zLq2R(GVlphav}VKE=CqZ1!84wG)HN+W)XP6iVpq?Rxh;se6ggB+svoyo1n#6pF9Hk9Av#RrDJsGP)Te0|!fyW+LIp}yA)dl%4OhRhz zA{scNA_YV)*yfP;gF!f1CJuoiEJgosG9Y{IA@g^ISy&&_j3wrmB}gC)U?CgKVRH1; zG`dnt*hBJ^ggTw$IpiT0EORuhmxoothg*1wnfM_HGy!2M!XVT?2qbpVhb;)@-4 zDm>XCU^bz+qLVM;ja8Xubu57BgDpm+=d}1B6}gse`Id1xmvwoU8wJ5c7ot1`mM@S* zE|$R_*=4E6219v(#du>A5|#f|LIQU;#76m(dDmB<*&=>u{53L#7r5Iy;5bBb% zc$jlSvGw}0F*~z0d$Z3O1K6jq^VyUm8={0}Av~Kvre%Ty`+A1gNE`dL_s35>sw{R4 zu@9<~=bE#1d$)PJw|yIbOCYB4*?H$f$bLn>NG_gtY-349Eszwpq5D`G0t1|ax-sAb zsJjBN+q$>gy1ARWOCYy@d%VfJyv_T(lg_)ae8C?Gzz1Ax3E6NVym0?}!U>#h2|U9iTtNG~ z!&ijCK|I7oe8m4ryu|y&!%_T1Onk*zyv1Go#bLZ8Qhde_BgSp~#&JByb)39uyvGM) z$ALV^g?z|~e4Ty#$p50qm3+yWyvdz>Xpub1_W}dlyUMBj%B?)hv3$$5yvw=#%e_3z z!F*=ZubfzWqsCZz1D60)^R=8b$!=)z1MyH*MU9Qg?-qGz1WTY*pWTi zm3`Tnz1jbr{n?>C+NFKkslD2*{o1iT+qHe$xxL%H{oAR%)Jq-Q$-Ugo{oK(#-PL{F z*}dJ}{oUa`-sOGX>Al|V{oe6C-}7DEODZb(@{^Bt{<28QcIlkjP{^LR3-6I~!L%!rq{^U_U6L!znZD`aUFdt<>7{<^ zslMv1{_3$l>$RTap`OOK{_DX$?8ScU$-eB({_J19>t`J8*}m=F{_WvD?&W^&2VU({ zobLbeKJWE@@AM+-R@Bw@Cm>04gc^FKk*e`?lt1@Z9r;P&`tiN_ zpMTb)fBNga`nezb|6Tjb-`$(P2&CWqhaLTwpWeOS*2ACr)k+!;fcT3)x)mM;074O} za^tkM0z+hl!i5YQu5dvDlC%R3D_Xp0am1Zs>y)8Ucwl44k4kpUJ2_9Dt`is?x&Z&N ziCX1Dh}&+Y-NmQF;8B*+O^WvpJgKjfIGMD z-MoAI{tZ01@ZrRZ8$XUbIdR*}D=LBIt&klpX(FNfq{FWWQqnH#z=G~o7+Bq^d=Edq zJP9pb$hh(IO;U*177z5ehlYMd5Ttn3Zm!mL-2s@C3tfQ0&=XzsMPP$8Js1Dobk$v# zolY(Y=pA_Ck!PNU=~b~_d+)_J-%j@7r=LUo`R8C-7joC)PzEBnkb(@xh+~d)K`0${ z)?ud|jFX+WVR=M;7@~Xd$yb{T_wiv?iaNSAV}c7#sUwdP{#fB#7!K(nhevXlRz=2lYIHyC(?a61Ke*Ot)pvEDk0~f`dgAOkp9MA_a=5#d4 zLR?TY4mqzRAy^;Ah?5R0MHo7drI;Qt2r%V9s?dtrDRB%XMcmIpENG0 z(890by5K^&l%R_)OuU3(lQdmoR74`&pgU=$m#&~{X~(c)(@81?dj~Moj-W<3RS?nI z3Qta2j;)Li%Zd&pXj+gYjU~Kr!%vd1t2xLjD=eqHh(Hy8MjEP4qKh{As4|f%l&`IV zaqF#JPt@_mOiu{Xvt)(xs_3;b&%8p-`%cU$t;K}8bg8GxoN9low)$$Uvwr%t%`oN4 zZLhzcP%^Q`mNW9Q&58`Iv;`k*EzH@juo9e3L>CQxoyhnl^1Q#@cA?(&QfB!w1O4h+O||*(aw=%F4yGT(sO& z(@d$&2jKjz&OG}JG@5x5I5eWMV>^4&wQEi>*HDitb+(FQ4Xdn9FMli8yuRWqC1l@0 zaj^xX4XoPEwryDC)ut&s(sg&6JHLGEP06|G{`$AO@SY-XLxsCAMB`wIAUj5&LSG3n z+T4D3k(~wYXF&_h0SqO)mk|$Xh@;!)I;A{`HE(v$b5-=VR;zvS3s<_jUiP-vy|bka zWovs@w8{rJ^i6Of>${u#@}@5N`Hfxn6I@RAcevvv&T9T*oZ}#OFws@cVWfkY#4cE| ziy0$h8&eqN&hoL4rA>7xn~2KH!!nl{uy_@`ncdn)7X|T;zQiExM%L-EGsC2=wJ~IJT)c*#ptCA23bf^nk6AHp+x_r zp#?1@;RL^=r7bDJ1#fvk3Dn@m0bF2)dg#CkZqPy`6A6h$?h&8bNJSSA;f^&mqy_ho z4?XRP&w5lrnZX1WC*1&spVX@x2x8SMy0Awg^zr|Xkq9I>BRNVlSc(p5K!cl>@&rIU zVP|0Q-BRwD$B>Q`kn3_}I3*cSW;!yIk|c#PC~3)WMQMbr;G`#qic(UV5|yfCr7MjJ zOIf<}mdw&6FMSEjcMfx;#zdwvg{qKf0#2>&T8K5R2m)+s(Xa&n+%DCj{Gx*CQ$w6GDKXm~0L&_!ZYqlw_Czdou{qmtC5 zgp8_6Y1z`3!c?X-wP_n|gHt{7QM5dr$z6de&`&;6u|`GeC6~I%pgt9prk(05Qn|`R zwDOgn)M`bil1n=5vX{vWt1uTrOhJ_OTgm?n4_ckM)_+Npns4oxT;o#Lm-JPg+gaor zV37`54nmkaEoo0*TalQ~)RV4FN^C>x$J+W-u|aJlaSxfu-d6IrnPjR{bxYKg8W*`% zWo|41`%dV3mAV+du0pcAU0-^)k!clgc)i(Hg_M_J=WU4#>iUq|s+Sjf%twja=BSkjHH4_0rggbyCf(rEf6BnFdJK5|X zja|U1PXwAFe%AAfFmwQWv7iU;D4qXAj*?=O!9xc_;7$jY1rNaG84{r`LJ^)&gg_sl z)7f-ag-l(911RB=FX7Itzg25FDFGN2W7kf&K)QzL+0ZVK^)WutFj22Skz;XKI>Ld5 zPV=HmfWCC9ilL|%che;>`Gk|6T?G{M$JGGcGzs{uknK#v50G7f-#+{kI! z%p&K&{45S^3{0HiEfIO!ncjKk+qv1IkVYH)(!m)Uu{^xNiMSA(e*LI`FklfXxSC^NrZXM)nd%9?)j@ z;Mvh8V!9X3aeiU@(=awlx4-|bFmdyO+#f%9QPj=uHNE>G@vifo>+R^9Q-0K9lx45j%=szP}(1a$!!x4RKi6>m{74Hv*FwTuhS6bqkCN;>V@oAE~Yt*Ga zb*dSj@@c-BxL#w0e}egd}lcS`#~@84y|AZ(V~3lq61%`FgmaW zr~nSvKn?QJMMvQRAvl61r~?=>N*;&?z!ei;@(?OWg3`b+#ei%vQ7rbN0}RCndiD^k zLJ8R+RcLU662=EaXoRIy1!`aq^KcJjz#S@}10zsMe2@Xz&{Hk|h4yd{VZen7aZWAJ zDrAU13qg8?Q4t5=2jGxPuc9bjlpQH3f;XrGGT2lNW^BN+0#XGAQkDp%&?*_wDkETn zEU0{$M=9c<4)VYb)P!A}MTnF@go#FHQWb>OHWlkIHZxIy7np%@!g(HO9*HO~O2CB# zI22D12fcF{p@{#18pt=rW{Mzqhb(x4ABKu82qP~DZF)$9cDRB#2m(4d7FXzlKzIOr zBN$Bhhoyvsm!^c!C{<4wg;Q9CSD1xc*o9vhhGVz_Wq5|;n1%|mh8N+6aQF&x*a37{ zgSjX#!pMh2ND+W2h?QuF$_?M`PeF#cx;)Ng}c~^pSS|DIEs2^iyzpF zs(4?M;fk<$b~@sav?wmXc#87ag1<+Mc<6#17>o_JNisK*C76Rdh)9vf4L?XaLWp-o z7>&@DgqmoLP6&lkNQKg1g;*F4TDXc20ghsrJLH&@=ePptcoFaj84n?ZK9Q-hZ0eTy-1I4*@yR7N`WX1 z^`ei5*pD(tPvhW-kSK`&*O`M@kgNF#2sxAr84;eSJ)mfTvq%77K%c*g9*K)-Ns+AB zieAZ^1>yo=U=5p~5R70A&7>0&sGQ5moPbgwA-E2_@OT4)Ptdl7)4(32a4$4?N7FzC zUBDe72^7hsFosqviPl9$(VgEJp2rwJr*L|a77bO<1AD1!Tv&%rcyJ)$gzr|Je6Ry< zKuG>romFuEYemrnk7NgT)Jr3z3yG#z9>b5kHZ6*wzGOpao!nDGqT0D@q403ZwOj z1}$(6UFd`;aFzC^47)It*ae-^nVt_Jjn|o-+)x@Grf;kzQ@`00b{L)0`C(T|qgfg! zIqIF@X@XZ-pyt_oRazRwu%_)<4DT7A%0-{{nRzH`r3$m3e_93pnS}v5ph8lh2dWSW z+64=`Z4L^dBP5}6LZKFlp&H7e9y+HrI-+7%qSJPweyE}>N~AG5qnvu95|N|4u%kWt zqYV-Nq~S26FUku>ilj;!bxqnwP?~eRhzes`rPYZBSPGt6s;Cy}rC-UF03xQ+iKBly ztY=!RX_{7a%ARdHo=!-j=-H&}$)OgBnQxX{cmCpiX$K zjOwTj3KI`{Y!RAn6H1}SHWP-HqBxo^_mF`n_$39ZT6q#?UwRqMN~X|CtlCMfn|iI{ z8G70(c5(W9-pXh0DXxN{r{$`up_-!UN}c`Lu7xU~@QSGN>S6TCptpjrpP;YH#;Zb(Tb`E@T_ynsyynW6%nhmTBOi+s~4O9 zt8B5WQR=I}dX?nKv{|~PHi@h=#jv*F0#A?(s-OzV@B~58oO4UJbqgFyp#sTNX;n&c zT%ZjcN{151P-qa6_Y$a@Mg$QNlS=mqG&s28nTMpH3$jEBiev>yR}?B25%5q2yC?#u z&}x#`kdVL)MX(SSGqRh@FrvExEYU9b(>LYHyxmZRnoGJxK%fF*6XkIf zd20p<#iT&dw}0zOmqvYH_EalCQheACSu* zllx1R8&H>C4OMR}ZULBc3v#Tycc#yZ7ySv-FP3g74 zJG`V@yxoMn-fK^+(!5phywO|0(OA+|n zz7@y1`WCv@61` zNy36*!oHir1uVRsnaM6Jb1=-j+iSywi^CIZy$^B>+DpUS3zRSnzKANmr$D|6QNKz2 z#*wVWfHOFC!N~E;97RwIwP3+LVYlUM&U1?tARrxGkO=ap4TT^Gw!{h@Ku^(7u|qJj zh_(yUUXq=e;(#!OUFXRx@YYtIe z4D`d)&-JXZaYx;u&i&lZRnTeg9M8N&&(vVg-c zT>z#!k=E?&&hRYHaXr_3hR+H8)BfC5ZV=EjP0$97&>u$C4DHZW0MQan(H4yc7_F{Z zT~Qs)NFRM#ZXnVNu^lCC2q(?dcHPo19n&*y+c!-*IUNlyoOT}H#2Ys-c9i9#S&=Eb+ z6@Aeez1^1-5gtuHAkEr=yqYHP2F2A2wdF|*iGkQy)JRiRn+O-#emk~U7i}w6`9mGO}ypAP?T))XZWHXag;D!v(0jjkJ4!HvDgMnkXeh_a3@xxVY`;OiX_SK>ep zIB`40VCs_cDGpKwnjkm{@c3JGC4<6bDVw%6K2N`Je}l<^v$KJw0|4W;fvsIKa;)9Q3X z@3B7XBwg#bt`PXn>%RW9wx|BLC8!s4x5be|67t?a>*&Y$w-t8z4 zisDWo<$mseSTO6Z5bgd=yFF?{{+e2 z{L7ATS^w-@e-6@4?JyMfaWVGX?(N|I@@ap;YoG3JzXEXo5^`S^iH2QqH4f>pI+@Q< z1xvl8fDXsIWO|F&qB2i5JXo0jNk%HoH}&8T#$ey&Bclp2fP?OXN{K*5u~)i zI;U;Y0f;09WowrX7bS+$AV!=h?%XwnE|e6zIO53@9XEA6Ot~`R9bn@;LOd|2*tv4v z>z`}-MW(<>WU-Bi)FELLm_e@M=8VsNcF0?0Blh3#grf)jsSWt zU9>8C=ep=oIb!C`1Az*i1Tmw^6(?@b#qy1k5`*%*QJSi)S;wrL3m!!GN+1cYUcpkP z#9JGs6FSUjLxWfKckofck0)RM-h6og>D8}i-`@Ru`0?e>r(fUxef;_L*FRq#BneWa z0ci#A@)`jm@m7*6!O-TCDk20Qk}EIK@^XO-YLu}f2^WfZ!lwxzRKY?CA!5qG5q%QR zh1&>o;e@DMB&cA%=ru4EuG}BZQLI4F6OSJ)S%q_@}8hU6&24Yg3J7724zMpDVkHLnoCOt4cYeJb$DA!AHw$XAWk zcVB+}TcJ&5Gqo1NXB~1h&u{f=QblY9-PX!(m7FkKZ^?z!+!%LFcf56d%F$gOeRNhu zQB^#$(o^FNa^cky#28{&*}alHTlLy9KqgtO)m<^kG_&S@gYI`fqKh{AXrz-?`o4Wx zv{TY+a2 zfD^Lkd;7_~7hYJ)+4sLz(XB0h#=;%_?B~2TK~I0+W8e6ax4h=@E`9%_Ab4VTK@4V4 zgGXx`>H4Fye%(oMFREY(=Td|wXn_n`U?CYe#5)t_&x3@UVcAeuH$KHseH}{S3S0O> zwbf9EL)4!C5NT$_58kkHIV7SBVnxLDf$(xjB%Bh*MnWj=5QQpap$dUmw=C*#gJUFP z8Os<(G^R0p=yH)7-S|d0#*v0>lw%$3ctl-&cHSgsIn8-abf#0C>trYU#Q9Em&ZnL8q-QljanDUaLGXAKEt$J0gW)-Sib!u0+`c3UbY<`u7d)oWk*`d7aO7O;aAY+(s|Si>e3v5Qq~V;TEc$3_;i zla*{`DSKJVW)`!D4Zu=8>q;AhRnV((BTN8WpIfzm|-2D zKm|46u!BVaf)CVy#Vw}sX~U3;__Cl6&zNzIS*v3nQ~1U{Ch~(>zz9iXc*sR&GIZ&n z3Mh{P5HhxbiLDGf470!oJ_x~sK>z^~P+7Jt=r0Q(00Iy6Sh`;hvzlK^=IOTo;2wLB zv74bggkAjOAMiMWn1#y%NbuRu>a76_5&@4opH~Ul;6r=+KlZNLIB41pB?&JHf5Sx#s} zzg)aEXn{Yt5pC+a9OtWDv?X{A+n)cNv?y1(%zdkKlW&;jHs85!gZ^>T;<+1+umT|H zYy+uN-Rd%K0Y7e@ba&VM>rfYV%2(d>(>`6aOCS4hk-ZCLgFU)LKfBy-i*&NLmhEWA zt=f(2cN^^8?zsg#!tE06kdM6NGv)$G79Z@!x8w284R_^7F=KOQ9%=fGK@NEEf*0f< z0t0t#p|{-S=-y!65?HsqZJ>G|us+^}<^c~Rzyo^=oVLh5bByy|gM{z51_wBEny1Tq z7!Q85z=yyApj!hopd%GzpaUSJ!1vu6x*Cq411aWAdeX}H2rtia!P5#s z5_Grx6G8afKoz{f8XN*epoV>r24K@Z?(@Dq7%?t5hgYBjRQLuy5W3Jx!X<3NCzQdv z1GjGrHxko4F5HjMVu2Ufve;9B5eviIg8|V>w{^oeVZ%Lpi@iQmLmyzn&@#gukN`A1 zxzl^S9B4NiH~>3@!y1r7I%I)6WU&vxfggZ47I4GWb2KymWJ4Cqy>*j;4-l%AE}#tz^;VFUq%3#}I`IAsI@4j8d7 zdqxrPz0;CLUCe-LWC07fMulUsZFD#d@Ww1CxJxX!He-Qs?8So%$1}@Dtm8#r?6G%j zfHt#%a0G#I6f@w%MbUD`Ui`(A6GmdhMPy4xcw|Orghm@MN326fYwSgTe8+D5MuRLk zgp9Ev2sB`;f%Nl1V*rPDNQby%fySGMlGDaP00(>jD2I*{K_w7}SwO8iD?qFxg?X@t zZ(xNHyNy0eHkP~tV-N>>&<05$JtepWYOsfdfV6c0hk4M3RbZ{F%*w6QF>9~~l1s9a z>jP_e2X*iUwM4B}Q-^O*g=|0vO6W71%m$m(KUu>{tyDJln~7(Lg47a$oZQKtWU;Xf z%=O~}WAKVsh=M}vgQ%R!s?Ri zluXLhvFyyu=;X|Sb4i$#$+!Cl(v-B*tj&{~#aaxu<^0XyM7GcT&$v@L>Fmtq+y@I~ z24o`z-?Y$uz)(E%&C={K`HVZ%LQeP`%@8HE*R0FC%uA+xyST$U&79B?TTtK(&;d0~ z+Vo5OluGSXEfyFAYETDgXos2Pg5fMq{9Do3%uD*@O9KV2=X5p+<7j;Vdj7%ln zG!13W;9S%AWYQL$O+TGXVBAr6#8RjKw9^JXP+9~#EbspA5>BxwJ8+cY=9WfkOy=pbqIsCWL zvw?7py>Ue?Ej!kAMS*pTJs;qKRU-krHG( zKVgFa2rxdZ0|5|d0EbI6;#jy=g5_}HBlSs1(7FFV<+RoR|J#+H3qqxDEb zLx-?LRg0sBX`ln@;{zEpgLJS3IzWVU2+!!7K00uO_fyCg(1%7)Ef>T&OryR*FjHiM zgs*c-L$g#SRNN73fp$;^?gNA;9D+o^+(^*e)Zzkg@Z9QqLJuTeebB$w<-XEA)6&8} za+rickUle5Pw4C0zYSamdumA>UYT+^~$+|^y)<=gZHUQ&DB)h%8= zJKj^1u`FmjRse%6P&MhL-U?LS!UeYf&4vITU?>bcqI}%$mE4r9-0Qqt>@{7^9p2Er zUOFhBUWGQ#atau zV_8gxTWUi4Q1l~z2YZ!VBibiQqJTotzj~_VWG5T28LokR%JL=g4>m2 zNp|D|_FeTo_<+zmS5(A+5-2U34ZU_#))laUe3k-bl{bS9 zJXHJu6|jMc=4UYM!`JhH5(rn>8|Z)@=+Gj8*fYh2R#pSB0ek&{ejRCrzQcWfUlvd| ze0J$}Jy*v6g;yB}y$+aFdzFD3h_@}n0MQbG*yGmFk})eNh1M*|lib)#T-oGPGkk15 zqFD$CYl9nWukLED z&T4*cxHB`yiEGC?I{>a`YH~ce;OlD&+{LwS>!YsgL7Qr0>^-=~YBuY!y6(uY{<5%c z*s<<0#}2Jxq%xG`YLabh;M)a%(1uh9<5lC-VhGA;OE$d>wCht(_S`??c?RSa$^xV^ zEmroda9a0T3LBgXGWI{@I$ zQfSLk=00xWHdXkZK|uSuj2P!5=mE_I-vn*Xnayx2TX6R_&+4^s@Gf!t1~wCHH2tnX z{w}}-hldTUfuwFtC7^~k)id7R@E$Aj^ZoE4ceJPD?flbJmh|u9&I0GoKpZ#C44m&&Ur&NYEZUNz0L}kZ}65g?Jn>=;BL(S zQ1TiqJvYDdz>9Mc&r}lMbI~kr6oHcD39_fm+&h0bR%CsOqIV!g>N4Z?^C1oqqg%?H}ve@ZeAyJ@5b{KS2^77Wh!4j zCRghCjP*AaaFt_WHM{M7e)3h|TS<`Qd3*9%zyf*bb^&iLRRuS9hG%wf4;kycIh27F zQ^hXRSB*w#TZL8`gI9W0Gm!?kL#%-dgsG>t>@ysciHjlzI|{9z5O&9gMe{J zP|<3EbO=h8lw>?xhhE@P2Ly&`(7_p$QLGz@a<~S2XtZm$&PRUqI0xTHhI95a!BPEs z-j_7IqhsBNzH?tbCHRH|Zv`0A@6Igw;6Ev*{_MAS7B`SOcTam#4604Y_qHLx+2k z?n251U8Ar%-@=Wn6{bv@3$IQLi&7;^dk>{{g^Bd#pld~sQoPD4r$w$mZL~0vf2GgA)3uM+flWLk>RwgwT->KA5o8q9w4fs0=1- z;DZbw91%kf5`ko z22ON9YYw*BaD_zU2|{sJ{Y1{U}` z1il|wd_V>bXfOc?HUKOz!4Mc+gTy79b}tAAh;RT4EXbAd#wvesFU2oiY;pz%T$TmC zAOs9?MI&z7hd~#SSv+Q!#7F9{jiC!vrl|nWt0ZwZbnRO8zqEHhKd_YC{ zOqWydB%uu$p)&~?N>GE;0g(Ld6fgC`gv}8Uh{KUh{SmmDPNz#G)^uh8_EX}3*U-W} z=nW@OI){__5a&>>{<$}({Qjg)44t}o_6_M8z>~{> z9)mf}an5s~+t28<_m$J7PImrromgszIG3>hpiEg%gHM#VrZp9iebAF0;i`ANEM(6= zV3A7qA_zV(jn5|KtBpv|_rb?mCPS71UvFLmyt7dwhnGu44ZoMb*c4GD$G8$>rUN_G z%_oHi1fmBk0zW0Bha7vz!USLPl%GsziA{Wt0<+RUixducJ(8h;dU!a|jVFLF?93Ox zQ4lfCPmV4+;R)Xelm~hbDJ&=>9xZ4()L~I89^8)mkeI_DVM8gVYmE6kaup{P$u&kI z;+NXUH^GHuk)b=Icl0m3p8Zzb_d4Z0Z@QhAYkDvp%t?j2RTm3ixJ%tL?baT ziXtGzCQTE$$qln3wG5>JwOwf)qXNX#;Y-N>|GYD7yY>(0cNK12^!2 z2U;Zs9L&>Gp!&$UT)|7_Qw8qiKnXG=&qk$Gp8oWW4L-n9tz7O= zE!F5&eDH&vvTJCcdW#ZXaR3Zu$Ty)W8wg~x5Q{}kVF|cg1|X0ye(_8<6Dxsfp!(Dd zXy7F?D;vpd096i{H3JDyfmB0Mwgz~>G!TQ!TS357gOyDK6$_eF^SQ5n-7Bk?GYQam zb^r)KfU8X908{sx07~(zST?c$7+k$1)~0&qtZijMRj;};izc4KjM=Vg)ti4x*2e2Y=4=*)Fn@cj=MgMo=Osu`Dx?2t)m0iPxrk_c@! z(m&3~4>d((!NDw#x>B$%Sr*xiBV?y5-UTk@YI&9$5~R0Lfy8%}Qr*yO<+fQcgFaS~ zMdU^aDempkTy_CUhAbq!RB?t`mzy83m`ohIT^&Zg`xEtw;J3gLiEy{M5cmQ7W+og>318?u$+=(FF8`K?-wGr5x#Yz#dK=MT9g8Q>Jj8Ny zO?*i`lNZ9jtujmqoEs2qc$i0s$do}O#tf%-!$$5ilPgzaFf*6VIYvtbrORjdUKgq4 zgL9W3Pv0YM^`h;+TlQ`As z?|%b4-~uO9PJNpHsbf_{Q4)C6u~?OZAMoG@$MTm(dsD54M|@Y~TDYQ+rK^W4Dgqr* z*3>G6@eQym28@#U4_ZY8V=e0=Dv-EO$%QO(wVYh0ssRobCGle&cjF94Rz0)jgJ3ZR zB)Y0Oq$;v>niIh!@U(bPNU@J*GBB_zztk@x-FP)*RA_o9ky%0}B6O+HIhAwr>Tia0eOYyK&!xnTf#5z_{5iZyw_~(EMnZ6;3>sgP1h+9W0=rD=+ zx&!!!FfbS9@eDc)FDZ1a0T;yK4M)(y`=l!n?ikYk_s9SHm{a~B)DeuapacK;-$J~| zE&YUgAfNIfLP9*BI4A@B$zSa>gg!V3<$MJ61z+mepZh`JBwUUeq{B4CUm@_p{DH+H zd4uMRA5w&m68#c7AOFzE0g6!q(!m0P2m3i-2eJ|xIrQZ;&-~Ab( zBY_tGDR3bt1t1;t-;!MfB&>sQP+h*w2L|S#1|9($=HCoTAr-nI3aX%i;gFx10Sw9@ z5Hg?h>4w!I$5wC%hja!*I7JqEAlM~QDnY^+mSHSe!ff2c5at~gIO6vaA^vG$T=-%8 zQC~%!BYI`kq7f?y$* zAcp1Q9w1)~3LydVVTt`>7z!g9lArmZpG2r1fgqS5hT-~Iply8OP7DDx*u$97;wn;z zIi!LBNx^BrVHaM+C2B?{7NZP$;w1&5`Q@NFM&SsSpam)jOgJGy)}t-<;5CNOI#A>P zRw!c)I$t32VmS`RKzd-+?L#H906=<3O|U=~SOF=BSeDp;8Cc&75fJ-e;rNYVO zMf~MdY9Cy-O0akY3Ge{9w8|dd%3!_5@80lMca?!UugUNRFy$AZn>Pc!PsTX@FAc{}jVMK;yk3pM9;) z5NN2HTIz>}sN!(}iJGW$wax)vsf$XNZ%nGGLPC#*sAmj`IQ)%f7NtilY5-R0s8WQX zZfTdYz?XJtHi+q_dSaYq$e*SuDBY=oGH4WmAf+Och=|0aM(VT1nQnNfJ&Y+FWkUtt z*%Y~kliI^NRHBu#sFTFStTw89{OPwcMUa9~t_?wvmM9fb>xP0-rdlho4hghM4sxZd znjUMLw#x=>(~-QXJw<7HG zEo{T)8io$)x00(SMuNIR?C#WQmKtoLB3B<6MG8t%kuGRvKI_g7C{R5Ct zXqx?lKXgSPQo}hUY7w2Pf^b1G7%5HQ8^+4VzPU+KI_2K-ZQnK}0os&Gnd+k$Kut|p zP1%57aU)y=u5=LY5%|@Fbf)0u9_83nOMQewbwCHKfJ(tvjF`j+=!EEYrVs&z=%$H0 z835#ZiNB!LkFJglly2;zZb+0Xv>g|I*4m5w#2$if?$H$ga#7o|X(n!1K zk(YiJNrw0gy_hbk!K%Edrp57K?^cdY051Uwukcb^@mf~>QAChBq><2=_DYkADev+M zQRN^La7|eAGKBKFhl*(*`br2V@lf^FZ~OuW@s1Mv_8I+7uN#dLa?Nl1GEaQq?)`$V z4bboZB5$)cuK?E;0lTmAJg@}6FY}IX{fY1Z|E~fMk^MGs5anHwbdj?{0Bp#H`xd1E zqi_PJFmf^Q1&f6-k=Gu|n*FYCyr}R2x9_As?A zFc03a^7gJ46Q$k8Xn9%itq#!@gKZWsFZznb5+m{d6f^M<^V;;LZ~P9CnwXFl+i@t( zu@xh*34`$(6EO}mF#Oho|^2kH>Pqo&FPQ`$MJS>2e&cUHW}`&F%TPZ5_hj|n$MA3bN>4AGzT&+sVHEE~x2y3=C zvo&Ww_JpW*T{CuJhjk&Z^=tEXXXkeRZ+GJ%>n%?ccX9hIhKep>pHS@r_iHnEbNe>z zLbq9$F!%Dd32St9Pxmjw*LHii-SV-B&~ObrL6UHYhy3;_mv@H*WO{%1dn?s?D@l@^ ziE_g?O^3JhnuM&~cYpi$W|Oyh)3Qf7dDnM=D|qD`_<-B@fId2R1g==_{D|tE~vTJ*BS9`a6`?rI8xQqL^lY6-< zxUoC>wyV2wn|r&v`@6$?yvzH%(>tx(`nu!$PS^Xs^LxMh`@aKxzze*0qkFy^d?OEh z!Ylm3Gkn84{KJR)y&wGl#Pco0Tl~die8y}1#&dj~7d*v-{NHx`$di1@oBYY6e9C*V z#D{##2b{{oe9X)I%+q|$1N_Ike9rru&GUTE`~1%XebCD~%ja#xHbN=Z^ee28q?9+bj zGrj4Vf|L`M!^E?0ZLqD_!|MItd^jrV+ zV}JIyy7E(h^=tq4gMavof1gi(_f!1%qksCV|N8eh_nZIuvw!@{|NPVcbeI488+`ri z|NirT{{w^#fddH^G&pdSs!<6?)er~(Vnm4(DOR+25o1P;8##9L_z`4Cjt5DWG`4ebRp+kulHF^|jQl(3oHg)DIM-7jIs@dzUg~xRq>R!Gj4G z?#dT&V#SO988>$P7;QjhtO)@d_WT)i=&zYcmo|MGb!yeCS+{om8g^`? zeie2WeH(Y~+p>B0_Wc`paN)y=7dL*q?q;nIbvJkZJS=kQ)2UatejR&u?c2G}R`{1W zbn)ZKTkL)weR}ol*|&H99==oMw#(PI?>v5f{rma%_x~Tj03V~Rq44fI5W&v`T#&&A z9efbN2qgq?J_8fH5JRyh+>pZ#J^T>F5Jkj`K>9K~5yg*2T#>~VU3?M77+tK8s}ya# zF(Vmu+>yr~ef$x~-%7L)$0BhI63HZ$T$0Hqos^13Bc&|z$ttb963Z;LWOB$Fr~LB7 zEyW!Flgu*BJTty1!Cdn~G~Ij?&N$_qv$QVRyz@Xh_1u%sKK=X?DmC#ObUZ)}JrvPI z6pjy+cF;f&M$nBL ztea)JYEHHO8tkxHrMl}=#XcMDv=`;NY(mw38}7K{B)e@%<-Qy5ysc!r?mPAV8}Pt) zq`U7y1wS0|#5?4>a4;2r9P-HhBfN1oCBGc=%+F)Iaw#?c9Q4qOqrCGkML!+&)LG-a z^dnV&9roBGBfWJaWxpNw-0xz&_7rvh9r)nSqP_PUg+Ctot6&Fp z6G9W7@MIh$VRKN}LKj+Wge&ya3u#!xfvHf2ld|Csd1$W~<`6VJ6ygxcg~N#iAOJw5 z6%m=(L}>jGB1lxCV4PS*D-O$uQ}oOgx!6TlK~alK^x_!Fn5is=kuYUc;~LkN70y5k zjpbqE9O>AnGsZD6b=2b?-vmZHYKV`46r`5!_(wnv5|N2qk{=B@8bv-5l07P9BOMt@ zOJ0&ijHIMUFxg2@ddPuN+~grYSxQqbXnmp_C0I_`N>}!0lB)#CD`{E(%l2qemL0L> zE_u0~Smsify%gp!k%LQMu8Ww-RHl%4)x2YhW|`5HrfZD(%!^DDo7t>WGvR2>Eou{- z;hdctm*XpMrb?XYR3~D7c~0}J6Q1#;OEukDFL~Y*pKEDnJtvY+fBusy^yDW109sIk z_Jy0~9B3L3+E9lEMWFnA=tL=+lYK6fpcU2VMqd)qdU6z`Aw9`O7b;Sdp7bi@bS6fF zg;JMtl%xZF=}ar?QFqc5rw)y&M046xfZFt&J{4*{clsq&8f~aag(pyrbW~s|6{_hh z>P@3s)oe1=npV}SG^ZNWt$vl5SbZi~$=b`Vdb6x)t)*CxsaCiDw(_i5ed}C3$yQ*} z6|a|!>sa&JS4G-2mwpxOAotqV!5&tRfR!a;89T?q-nFrjC8J_jDOt;Q@v(uu>}H)v z*->&9v_#D8VnbWn9eQ??rd2HsM_bv|zV?Kur6g==3&PfZwzj#QpllndTi-J9wyFK? za0kd+LlPIc{0r`EliS?)8TXIQl`i_0+uP}0cYDyqBX+rqz3LvfyWv%ycH<~s^B(WJ z(LL{abw^$_vKPL$OYe5$TVK_=H;nex@9E}S-u?bpbNJOFfC+rL{=T=s309ndr>I~D zAMU{Ueei_!#$Y8<7{hmq@PISi;RdR-n=Flvhe<59);iVyza>_2)+mc&1g{vzQQL5X zV_ajUSr~{m*74D1eBmAcSZ6rSA&`lDvmWQT$VqmYkY%W3C#Nu>A}-96sr)e}udvEl z-q?|ctYt4t?8+qk@|YLKoN^2h-eUeVG}{Zk98=)@;E!-??3I7BimtJgz!F zu+M?smY&%xXhTQq&j>v9qMb!(J2M*6#7cAkBVB1-IU3NG)^x2Vt-nowx>cA~G^j~E zs!q?Z)TsuQs41;#S6k}T?0faB8O3T((;C-@igo#N-RnQu8r8lQww`wFyg6B5J-EAjP+t}X!7I%}L?YwcHTT@ZqHWks`?jM!A zcdEa|q*Lg8&}y ziC?@_`d&E0G2ZdXDSYFs^!Uj21M$|89Odw-xWQB2^7WX!bS{@UdR89sncrMHFz+1B zd48RmpSC33gjVY*3p?B9HKX_=~4I1&tooitHb8$g}eIJFP3zrbCT;} zM@`oICU&!Lb0Lq?_SaQ(cDGxG>~(wl+$Tfzozorfj){BQ^4|Bw*uCg}7yMrKUbev> zo0-$Ru3t-t2)iO&<>7p?fow`lN%UlHX$zb41; z8T6?iliQcQ`q^iR^l7Gj@2BMYa{vDLNy7b=kstj92|wS{-+uFpto`n1e)IbofAqgU zWA?xQ{OSKM{f{62Am;x7kpKEGqXtm>0`OoE(EHZU@E9=r6wqHFFais(|0uBfB(PsF zkop`j@;LDMG%#X7Q29*7#S9Q4NU#Jo?gUX#1(VMMXYU1xPXy;>25Ha&>F)-AuLcoj z2X!w7d+!HxuLnnF2x~70k?#m;uL!~aWeJ%u2b=E+VXp}_W(rj=38(K0Q?CkZW(!F# z3%lwula2DMz7R}}s&#o3na2Lfc7dzz_&8`=1a2Ufb z7`^5gxvm&}a2c;I8SUm7p|KTDZyKqQc|z7p@Gz%lB)(Fw_s>BP}( z(DCTZ(F)m7=+x10;4vPnG4$yFu^zK=?Hcg_@e$|T(F^_Y9}SToQ&1oWauHXG9}f~C zvqB*oks)smAk8o$WlkRPq#`ZS9yc!|UG5^Erz25rBHb_~N$w*przA~sBNs0vRZ<@d z()n7_<3`dBW%A-qa!qWq<7iS6b#mfx(s6w9Cs&f~gmNff5+>`xF^HE}5s4k!_% z1?}l653VVVDv6M(DhDnqr(`Rwk|@9KE4h*&3vw(4?kZLBEc>l1J!dWPEiGm7E$6K* zZD%g&GAxzuF7Xm6lhXh8vfbiR7XcI9>XJ$bvoP~A{jxTh zZ8gU+H;?T#uctSMZ8z63IDPFm!=yNkb2j%aIhFG^ld?H`Z8+yKI%(}VGo(6kZ8|YB zJ7?`W&8ItGZ973SJX7sEzo$ISb2-;7Jyq>I6Qn)WGa1o)0Q5c_w9**VbR-ngAXI=Xl+h^ED>Zb{Fm!)B z^w2oeEk#t&Kva%Q^hDQl+f;N#pA#lsG|))YE@c$YP!xh}^hQ~9okMVDU9^UibZm8O zbZpzUZQHhO+qP|fLC3b)NyqGbH~;9?9o*rmb!rXH;8d-(-~BwQQ?9NOM$5E*uD>lG z8N-%m9a)27TW2G`_djXqvx%y_xvo-Ps-vZ>vxUncwW%|i=&Wsz(~Xb8y^k_gsb!R!VA7v9nciAysv|R%vQcwXs!o zqf|4xRvl_l)38;upj4N+R$FLMm$FqaqSCN?QZ}pBaC1}WVAABfRzGObfmCnyNvEn> z57bt#f>!?o_@viYt^Z=9k4(DY76cImkGu1NRMRE(}fcA30qOQ~nDGIwi+ zXC~mHwO@>tn7vIGhUMF(ja!Wkjg_qpob||~?LxY>o1@(ZhD{3w^PYO!l>5c`bK7FN z;+=cj^|SVCyZy+wCSk4hGyMUYqxCUe8HK}XOC1)w!|90KhM2<{KbfB@-I+tiiHpsJ zVcJmySnR^4;Ydv5N`B>HQROP<;mStihI{3z)Zm6><08f8j(z1eUF?ox*CULq|EEV+RKa0J8#WtrO~@i!Wi&c z2x6hgy@qmWcB*n#C~8vaWtK~38kl*O8)j15y_Q*K8o6PWIcnPYy_R}*nuM*F2Cfsu z0X-wNGP_b=BbipIIb*SlM>$_q0|`(9(JIK{_2OB&Z>=Q3l4 zXyT|~2Guosw0=TlhH*CYavV%7=Q=&3&*|WN&)45u*5;oEd zXtOh5vTCw2(%&4Kw6Y4a*t@i{THhRpv@+|nat)+%g#sf*ZdJ6t(^z$~s4 zuY6)IlRsJMn_2}tF!@Fu1qadj8!Uw{UfJZeg?dp1XgJAV*dEyLc~ISA#N5SqT)tHA zDHu2;~_;n}s*o3&yl@;^l6g^cUigyr{e>W{SR&$8>UHtTP38V+zklF#c(D!&1H{fld<#Pd&EI_xdo+n5U6cxJ^w81X&OSOc2EXqr=OmgB+|g zW~(y+w<|@bD}$#qYpW{;7bIV&%WJCxg{ZqOr=eu4leD;ln53&tr>88ZYXrBmWUFCT zr@c=Hq`s%iFX#KQV+XebNvD-uxXEs-pKq)A>7%llxs{2e?hLmLDt8cWdk_gvK^1rK z$0v#H)&MZOndzgKMJH8Wu^F_7WYwn`TPHP?rxT#lE229(fIBMj*(swtTG!JR^}P?w z>Gr|x+SnR3*&dnJ8DTmcG4k!R!vm?+8C$>|+463~%pn=fX>$U84D<1jEp`v1Yy%4L zrb=|D6hw!3dWMO02aR}|t#}#|CP`RzCe>hi=X(0td^>V{#+P`zcZmyc0by$s@VQK$+o*%Pyy92q0n`PYwe}SG^i}Ef+2MDE_;p?2 z^{U}@ff8&a1e%sy8fw$byR~M%@>7$dH zx^PNk{CyC8F0Ojv>>+9X& z8(8{Sz|Y&p)oC5+{j=47Qo?t7mVa}#d!xW`!&1D>vDNSJ)#lc})6%;j!c%|Y``6@S zMqu~QN3T2QYxQHN3kBo~hX3+uXFM$DYRqRn0Jwbs)qe@a*A>J|!s@?|NwA0cHR9!S zrn7a1?YDsMD=)A!Ag52(suykxym2vj@z^_g(7$Q$oz@DNrouZ53RvRN@B7GKh{C_t z+P*IcIDpIR!UrD6@xFbNxAgk%?{bfZwmNh2*NS%6f9~}N6nvBkyaNi(=Dzwlf+r9B zpPlxuajUkx_P%ZjflNCu2?0A!1VkXl{)zzJF9J9rily;MlOysHBcM1Ey(hRIL71n`up-YF%N2QLH9amE{F{TYEna6%l$|D;}|#MB4A zqqc|wP9zM^%()Y&>o;NSv6_aV4fNxEK0itjgrqu76vePQPLljpMV7Gg&tl&hO$(wh z!1%xu!)C2YeO|m&sMR=Jur0jU5&M@#N+{)~DW0tw%1=^xrM!(ITl;QLV;4Sbk244G zS=Dkmr*cl^aN1w3C*};!ZH5`)+NxPrT2bXDDs(rU$7Px3)feTt?w1!8h2hkfm9}y? zR%z)$?3BR;eVLXe1jN}!!7m7s=n_@Nl9p1WJMLTgQe_u9ng+(usabd=HN`m*H`tU7 zfa*}%sL*Ga>k!e4<2*6tuIQB5=cFgXQVw%;y|hvsE9>s-_N$wozvDEwy^r}CR@wzs zZhNuy+*aBHZ*pBEgFX4=_P`u7YS=&WLo2^(N4kTx{@6@$h3+Uw-hX^Hk zHMPgYr=i(Jl^<(&teAz?moQxQ*!Qun**?s2o@GA#=6$(tF+898WF7=VvvVDam5W%U&Rq{BB<`rv2-|6J%Y-f`kgdbEhSL+aZqb;n&ZQo(*yLiAug5 zVLo^)o$CD<6UQ(u8vBju8pt~!br(1;L+pVk0 zk7e$286&vjw>t&5wA!+zO~SVw7p0wG$d(nn1jlfm-3N@xK}hbuLCCR0`si5o9f}ns z!zKAg1Z!meW3#T1!-f~f7~J+r^x~kFnUn13OpbcL{qAzmKAY7WAIB0n=due5OUG(& z^bpms@etyq+lPLmQw!`S6{2QLj{f4li&8}Y2__>ZYT^|JS{&B;~_bqCc(a)^#Au2!3f?gzz%d#3eNevBg}Zz3$fM2kZg#lcyLNhO@a! zY%vL@RlX?meNrMY*7P@CRYyCKVq|!){!u$t-}JJyq2Gfn7D^eCr>ejkhn?T6`Oum`;q_d`}f5gBWR z)U36zLUu*9X=>?+l$2Gnq0l4Y()+J6J5)-SZsDk`P0^9H(JHwh;j$A+2}-o$sL;;s z%&YrSRNkBFc=hi&);c6jebkz z_@|=g5SCKbUR=HSOFMgpZMM+5l~h=dm8aTpvij@?KD?K4ZXs%$4cBsdV=A?Pm7fh) z;!5txrRYk$>XVK(4Tk04Rp!aC=30SaN=pfu&Bg3=uVOwLP$llc5;~O-UOv;bWPqIa zW>g+48$ONF>++`7a~O1qrh^?!dqDWLl~0)-U6Refte$Mcxb`xXRSAE+n|i8lo~oF_ zG{J)NOV7nUrRM~V`d$5)IOS{(O3bU!H$%t(6zs&dI)umj`F90qse!o-XNRjlOdQ!( ziP8-a{8y%WhHaCmW8}S;4Eu(oJs)_ZoLfvQG6}RFdN~7Di;w7i_e3uNVpF7qtg%9o zngvk!7DJ3uzD@otXRB7Ntv3_L?w23+sv&p@@}=q#%e!olxR#0X9`Vk95)v6|;LUyRPvkLE<>T)jR_pk}?%IEQ8%J7z38WWO2PsGkdWofKu7qO#r zLhk0lJ&Na2jVV_vPZ`gks}1b<(XB&RXV%e9d=$R9Kg4!^0c6b|ptVtm-J>Z)TqjJm zU8aaoW7sP!HuVsIMp~(X}eM%Ml1w&vGl7)o5Iz-Q>;@FVQ zxHFZ!I-zIa@hVZT33oqDiPW<`A^+U0lC-7&Y+d6(KYZD?UdPO#7`!{Ba$yT}Xh+8& z{P@&92gX~S6Qo$}6&MSbP02MeGF>;TR&{ejY=@!jbWVw$ZyEi5*;cWu0qwAP{_XSi zP)Ol63AniHbZ}eJUFq#M@yCwe%BFqtKd-%kJ1;emKX}D$jAwH`$0tbDS`~gb4S8}A zkFhNHn)$c<`+R**T;G_H+jGKtRtr??lC|d4_xwNelTSeFra*(c+#FBaX^gi+LQB_s zTk9XgFJh0|i(AT?I4Q!<^Zzq<`GZSlH#)jWmEg7>W~Zz7MQs zXpqcZLXI*)3edl7yHR)=SeWWkW!gzYtWrIQmboxTjSMvurCNAy$L(-lLlv>Yl(9JR zGD&lfnW=v0?2DSTbQqy=ni#Hzv6A=<{=y4}5|muyhahDORhOXw7lAythz_SP4fX6t zHEcZQI#c1tu;5=R<5WFyyBpI|(ToiDjEscll+RTEvl>cn<{uu)=cplBk>sqS;mJNu zeP&73<4V zd{Xc+)@7$u+NNYjKDBu|Ci>O`XCIIeVu?SQT0OD}552}bdnUYQCY&fGd@9G#oY@03 z{c121iH_svI3u&g!|N(SyOqW3nj$nje0t4^C%}|o-AH1~4DVHK2RalADoK_|%%0IG zMOtxHJ;6kJAJ-r}B++Lu3SmJ*$YRsrZ+nA(=^3vxkGiaCuDd2#Kbcd!<`u zr31dfT4dYF0fjfVpZEO|OX%~GFiP0@MeFnRn^ zHCBVuB-jmyQ{#z`QV3twd8rH-s?xK&vT~_XxDWj|$!y5iNt~&ow%8MO#^P($gWXYo zrlG}*21lKUm|cYaO43L&I;1!Z5m8cM?^@OT4UyDs_Dc>XtGAg5mNJq)%Rl8vt!yo8 z9y@Q5E00>kpFYbzaow5j*;uNRbYIvcA(FYvSOxE!>V2Rx?i>(Q6<3>-!Np0@?jnJh z;--4aB@P|0^=;D{%fr#graF;Z#x4ZoE(G_^=G0O?#lUNTtfxcD3JY34L}m z@dl?GmN1e_@p?58Z)Nc%pmG~_i<|J$!1DIFoRkK(C;Naq^KmZbGG=E%aF?)Zmnd}F zGrK=RUJy4Y%`BVQ8YVe%q-3;9r*%)9wClKoP4 zQBdnU6t-#Me<9oVMUQo#8RjZ1NW$hr)c4);?;qo(b{fMpCp^u^)yb+ppE8AGx?vXH4gw*XX^4?;x*I^2gN00!Fg z5$e~pyJ_yZVSSe+f@Fd8_X%IOgG_a(4rkr8cf)IT!`@2m8k9NDrL{G8-KH1gN=dG8 z6jw%+=;wn-T1Whbv&&Oi20vx!pDt=-Kt29u01k{D?P!zos>NWqDGf|E4_EoScQa*9 zGp?rC?PS$Pm7hjsUERH+i-+fP3W=)a zL%h^k+(K5JASR=N8AD|4wWIEu6h#8OT@FkP$9Sg`eOlTAV;?ut z*{aiX-qhKigT?sLnMlJ&^RwNsr_jONs6wLJphAm2+QqapLcEJeA69Q%S!GaNRXm7U zhrI@Ut2Y2s!B*83!zaQUx3qaHrAw#()Tf_g#4GfnZ5X-{s!KgiQt4=ev$3b8lT-8w zq7q(BYZ0Tqy~0*ZLnZLU@Z*=4A4S>qajCR4yx z`mxTCAl|5OESb%!to>cp7D*j=i`X7l^$w^FGG~ZGX#~@CV^p*UMD0KrJDRw9&E2;q z^xd#2RZ|v@r}_RDzDB12@2KtexIHc5Pf2fU_}-+C!BJ@o2b>&1uBiO6I`WW4sEN9w zY07%-0ZfXJ;dHb2iQdO!)5uslr7H1m&5R=UCI#`{?i7au2*&3d;0XDj9%j+D(;*FpZjcOp==KbiihNfsVxB zfr!4g$E{2i3j7?p-U51@`_D7;s<9#BPW|cHIjWx{C{7k>n)5fTIdrW838$~nwU1?oirrbv`(d-s@cb52fW(2XrS3xs)FN&`rEto07$KbdiwPaU5DgAkc zb9s^$Uu-+6jIPc-EL2v0i@PC@B|kvWI9-nj=&hRjtp+&Z$1dhAO-8=Jn^#3 zqB$IO5!!am2Gu$M?=CaI+gy}vY+=mDVDbW}puaPkJ(hjzu{%o@z2oSva}dH6Jle}5 z-qkc05lwD(r9G3g6^m=lvs!V*jV+2%(m6kAvc6{`jOF$Ef18av{YJPOHWgtG5n*lr z02yqvP*<^qHD&DNfdwDa;%X8&Q?nNrHQMQ|ycGs8R5sE0TZ?={wy9)gm+Qa&^K zVySaDbOYn0aTwmHL|N6&aJr4ri;RBTikMExXJe>ujnaO-%X)jyetX*s&bJi)c4D>C z|3*o-m$!Eoz*4jpjwTkzEu*BT0%uESY9zcU`y{v}%eHLaV)wA}4^**sc2`5g7FS(j zXP9l2H^*gxWNNVxStgS`4ya-HTP<$1i0c9;9#}T?f-h)V(FSx>Yk2hsp-oHt1jk`9 zLD>Jag>epH7k666bHxd&lJ!PY&jOYCv}XKtgrmol;)dIwg3W7U>YeHj&(+)0*9GGb z_~?%<;}a6-OhCR8PMBl)tXtS>R>fcoP2db1?Q2_#Wu-#H7b(fSK>!^Ix_s~~@duLm~+d1s48f3`ct4(IIbPq)kPVyZ^V z$!~KC(AJa{{o7~%{RBaH>V!k*>?QBRQcD9RXmLr!R~&47pBvc=qkUi+gr8` z&P8uu^zSej3Txwr8X*qt5q5UJns0KJaVJKhif~ynIJ_?yWF!9$d#y0lGV_}DRrMPp z*wog$-EkH?EP9>d?GS$7Hr>T<39p$*<9|F@(u(5$OSPk@ygMZ_?eH4rsYe0_~M)a8b+!b9Z6n*G&^!|fxzn6Sca}K-V z3FtlWg7cb%vi&5$5Q}-EEsj(t$=jYT6`sFTC7Zj_*RQ9hdG|E$}prRbN62b=!Ed;pJy?v$puR-8tdoEp=x3cPN% z{qr_R_$m7P_Y`mJv+g_Ct=oW&H}<%;-0g`6RXb|tz~^(3m5O03{64K#wgKhmF7V$D z)H{3nyG6uj!R9%^To_Gyc}~)9Kf{FKH|kusxWha5S}xQ_W-cG`>vInX0xGyK7z}|x zAeyOoARLZ>&mW4VbSN7AlTI5RSHeW19{f~CL-A;cPuEvdSx7(lHu^f$C{eHiHUl4ej-+S9I1j1j?E`KIdqg>ow zuTg8)8d&L$Qn#IG6=qqWj3NI$Txd2HD2TJYZB#DCY1#DKU%Ec2)-{{Jbxw7&$ffs) zz@EfvzB(R`#Su#6>%KXk&gKb35a_+TUao*bMd0H29H;lGH1yW$na^bOj}-)bX1hwQ z4iFoh^m&`uZdDqQj{V90@_&=V^#LMrUO|%0*ZzT>xe)}%G;I`uA`E2|h5=HPHV&Wu z=AmpY?uJ9+n|Hlu6wNOTw&mDTen2X{c}z(V{jjg09{AENO`x2T1#c3C^EhsjSn>sD zmL!fKYnCKU5Jlx$JQQ}|e^B34Y}yqyjTJ!7jHt3=aKQRMhEziMbN z*9@(d-es0ymghPvZIS1>9c5AAdpTAihG0;JuXx-3yp^IHL1z%5#^htIOc*6$C6zpi znd-xi(@w5p1E5n^)!g(TRVvu2CNT@eT(YRCX_&RCX&8jDscR*DqLsXM^Zs1ZVKZ&j z&=a|K&;Zyjql?LP2;Yqvqcl==V64ctEMaG@X#~iH)xtt`NfTT|BSv=so1trufg(zHI$hfB=0l~K|*^m48t_{DLHU!sBg*sGSRs{x6QerQ=nTIiZF7uNWZqIdyNgjn!nJsVSKeiw<1o%; zk>|1dOp}a3w{S+dLf&nOz9;9PEL5YmU}7?zf}mx3XA(!9p4BEz%~o|ny9@6H$z$6z z@vFzSB`dVEUY1avw#Y4{UHJ&qOj;n@MDT9X%dS-K`HlaQHORoAvX3ex)F>ubj z*J*+JbkmewN!&3F4zDH>Xe0+Y!1J2lMDGUgEi)*fsH0C{!i0;8- z2XL6+^Vsn?>wCFC9Me_0LFMCanP=klCtn+7R^?p=v;VitqDH{m9#|Dj5V#GGsq0yU z-Mr&*H$gGr`!FXVU_5hl^nS%Ca&pk#w{%mYQAu_gC7om>iX^ zF~&3)BwtMutyqV&0XR9Q5Ul!q@G0D`$X7=12k0N;x0ZB8!;pcA*IOU+`z_n-E4_t2-uX+-Mvluw2sJQzBXy zd{tCRu_`Adj<$_$EC?=1VT{GZ2w%muZS*n({qm3)vf^FoL!s$yC;nQebahn8F)C*T zIWO6i8M1Im<@CkW3Q;ra2VvniwTq-*v8C?$kJ412_FnL0hW^Y^gtbl3)Fin$%8=#K z#u!VP6QbtKa<0@G=2YnuB`1>4734e^@s7*6t7p0$GC0&rIeXw1oMTi%>Ns;r&bA~a zsh+&t-s3ivDf%k85VAqGNK`qkW(;-Zw6t+c1we30?RG51U~$VrGO7*6i&cfVA%^S} zT68>tbJ64|#r)No-K+9N8RmnB?5js(Au;Ynr*Po1I+<8iX!i3=T$8Fx93TgmgFR7+ zX};uR+tOd(QZ9GgGXDuJR%(KBITbRzQcP_{iM&{~l%0)>#_b}an0g6{AHCc|x3JZ_ zTdm%{O*5VvUZsmtz2Y#e)=bPsJEn`j21l;?=nhA;q&wwWY?g8cc3loQM%!24$Y-Hu zV+g^cIgGJNfAYC8xL@6gDh#M|5rYvJ=x)fb{++F+J5_;bt@+!1wWR=p?p1oFiI5My z()sD9sRjFnBA2vyfC@f3=tlB^7EbY!Lq(1}r<^%!UmE~II0hmCc3$hBDbKV`&aH(FGnJRy!NMIw$$1YR^fa32 z*cctzRP-&mm5Q-;S3W3tjZrh!M=eyU=T6NzG=&rUWzg+sa$!^(Ot4&g4j45j>kRuMhp&91Yf$`1zHwSEUcx)!#ym_ZgXnOvYd z%g7wn%)x9fB!s)BRILyxQKOIRYXK>pA|y|eHZn(%;$17n_%4SuuR0?8m1EN?$DA*) zmP^CkYR%{{Rd`h9+*n&2q{k;U<~G*`Al(~T@bujQkBd;s$j$%IZOu8hHs&zw%AaRu zD0}AYe4k-j+xqP6=dyM0-`2gUt(#z4x_*$%m!^ zzZ;Lek3ELF+abd9Ed|97KUCoBh@1bD2=_lzQ{c$qp8xyWUcp00z}M42z}L$j5C}C0 zf<6dJHVDQ#_(OCMTopJ7VLAxuItUdy2%S0zQ#uISItVv92){ho>@$GyIEa*6j|e`5 zLNKbqF(b2rG368;|X?WC(Y32yb}^|9FVtaflFnmRuF?_i))Ai35#HqyzT*-8#}NVWQ9<-kA+k|n)=?4BQBl=z z_~)p&>!?KNsATG>ROzU6tLWwA@EFa2%&}+=Ky>V5R33dyiEK=nbxcKcOf@!MQFToH zaahiEOp{fVD)oI#yLC)wRLss~O!s(fu(M4TTmZgVV7C@h}3Db5EoVNWJ;KsDhaI^n81;buAkgFE3KD)Hnq z;aNK2-8$hjI^m1n=Y@{wuUhbUFX6{K7RU-8{5b9aP7#7W8D=^ej!qfj${rdj$)z-z zm?OEFG8w~*YJr{{y*wFwH<^GANFoCyvr2)%1019PDW-s3Er7ijAUze3RSL*%1>}qZ za+d*l$AJ7tKmoY4cTMAOxT#{+sS?qtQdMcZDao|&A8F`R)=>Qr^?WO?fpJ3KT9 z@f$b_`Ej!e~4^R+L5D;i^5F~K$|1F4vM1sJ8pneyyL4YuLl=Fl`A<$^lx|5AX zBN51?(z%h0MF0Et|J&yOE&SJ?2i*U=KM=$Y8jrGZJm~-SmuxB?i@{>C-kxkKnMfcK ziN=#^E(N4es#NO&n#-m$7)_>3r5aCXayVTsw*f5`a|MDSu=vugl?x@3Vyk4CtyN1E ziY3x{(rwi%HJUBTdfbXvlZ;ip(PA*{RB+DWriv9W;we<<%PHT{>!)FFj{kFXcT6U#Y^o;C@&p`Di^YWb>yo=2Eix(3 z>38s~9<=tI0b7-R#PslKl|u8*i!h#wOMK_@7uRBsNOgC+UNSPp3T&P&SpX(%rb=Np z>5dtSUT0+<$Z&@6LeVbdOddL(e%O(P!KfRnh>nm#ltxx0@>uzfDA}4j68Buj5JWzY zD_{aqVVNXh!b}_+QCMxS#<8StkjCGRu};M(ac|d9FQ(v*Vo90&HOvS#G3=uhaxE|L zWL|w!GXwQPVFaFCMN~Y@jaHS@RHOK=a!aCXEf~2w?>8 zXZe0#z>QzU>H4asd5l%uC!pQb?$H7_|47NxQr+3F3KHqHvEg#u->rlzt+UHp;8qRA zIhYVz$+30MNnx-hMmu77r}3TW^7uUA#4$`w@2arRONA$hE<`<$YbI)i&HUEiSJu)o zS7DRGI1g(a#G~;?Bsn#nPmWVTD7*#-kP?ow$y9J!$*~@>MV$r{?nN2v(e-kj90G@) zk0-$tbVWwVT+lBI89QiMs93jXS7r__uTka*Wq48MKs1h^@k_T`CMtAuA7Jq-eMck~ zBq;h=g#ke$f9v7d{<$uzR^Fy#*D9SC7 zomMcVVCIpCb;AUI^R+;P>=-HF`Y3GXuN>S#5>rG_ZRofq6t_MKM94J^-ZSOI9*}@U z5Dcf00X3QMAO8vA*BeqGToW>PAk)D6fno&jF*2MUv`9phqa0M{o`Zh-z*pH{t(oF* z?!r6bdb&w=m0A*G~&=$d9FEI9IS_B`zY0fIA*o3F^v z4Z(h~%F$m>LpaYwD%z%K0$fw#DB~a#Jd2>kWZ8=XtDX_uy-drO=F?Pz#k#puC?%2;m)$`d>7!QY~gi^B!O`0A%a&g9tqSY{Lx@|`SlUbJF4?j|q?ukDF7|AvziM6iRk5#i&gD)OGa0b|z-S#&R5 zkA%rse>>lg!QYo!OhQY`2OipH?2aZkgx)bsCl(ii>?ApmSS$F#!W33iF1OTY$wgMu zrHwoul9Wk~=@S%Y8oEN$nn_KEqBjK+N#k<-c%QTXx-z3>9BF*an)lDY1|dT@0QhF?^5Q;v=r&J*OsY@D2y@KoA8>hj#Kspp<>EA<_SGel)6vT1jtq%LNmM+xd zb4;5AVmfC`tOBDGlJyE+RJuD?mmX8aZA|f6Pw~gh80{J0uDR2^;A_r8_0IeTT*XU< z0yfyQisWO(bggVs5tHx{{;s7}Oja35EO08D)c*ZW>U*`paA#fWot=gWm^UMhnv=Wf zOQ3`qLVJD=9ozh%~@Py{>72U- z`DKnF>L($sm>q^|bilWrdwjZ8wiWMqPl*W=wLPQR-=GycEQqwnFy~|#@Wom5pb6t9 zQEhft&)k+0d*j|Pvvy$QoO*_1f#0xxm_?ves$g3UKDA&DuL#2g<9WBg~kNK$trl>7`L?!8e@pr+s@!|GCKG_oa>i z6Mg2FcGX#*LGaus4rhSX{2n>CH)yPdC@AqVAwLj0kT~9B-a&dzps&ZdBYJ)A5Y8w4 z;Pyxab}NPC4_)Gw%rw zpEFRNiq|n!qL8`ukA99O;>e zJg^C|uTa?4Eo|i=bj=V^$rBu068kOPl?k{O?h`2I+ll1MsrsZA(bF8hT4F>i2)n)S z%!tYOwhDIT=qO2n|15_6?GW`@kI*O%zZeY1ad-1ggnkZ$SM3PRkd&0AjP|OCI#P4n z6LddDjyj%)rYnp{J&#sVmZOJ?q+aGOIt$(S7S0wjZy8}LWJWSs(48$rr7cEoL?SO+ z#)U;lp&jWVGa{n9f($}O^@GMKhQ@0^#5A9WJ5ol72q&;Zz%M0Ixp{&^mqR8mVoL8P z;In`?DhlkbGnx}&-7884cHpIus=69Oltdr+o-SEhtsg(%lIx9NY4_=$%o7`+_za_xdrVamof3hZo<+i$sXtRiHZ<8b5+S`1 zVx>|oRR|%Z_*O?CCSDn0P$E<#U_-_sE}xnC0ulAqewe%QJEytPbMf^_l0*d}rU*iI z{cwSsbm-62!a6rdIU$Q%kFDYIq$?rywM6=2L}E$}3(>GxeqyWzL#!z_dMV{6In#4; zbIb^hzf+>QeYlTlyvWL=P_$ZmyJ{)YIyD?Mdz;jup&@Wd=Cq z-o>`_4;39M<$CXB55Og87Ybsw;7U_(HNbOJ40mOGbv^^R1@aM1)(VSOW4Xq-q>i;# zvUa&hbn+*59uS7P1sV}P-M1n;n!`IN`%yxB$ipN0 z*}_XAz-IyMYp`BT*qPwNCeurEeRO%zZ^L@ESC^iBEs3XW6fy-h zDYjWT_`9R}8hTyMn$xI-gV=c!n@HR36edPv5gQ}uVIy7_MhW>9nekPN|2qwrPZ9cWXqn-|iG5Ag~=@EG_0l4g;S4|jwf z{2b9Y&<>i(H(JOw$3ucL8d?(y8|#o$oK1`VC8|6pJ|!$AsR!$KV}N8@e8v`iVtW@L zy&ERTQ4)eUGp9%EuenMwoafwpEB?_rOFN=AcE zru{pL8Es!CCH9djJF z8h(nNqN8i{YT(r(Ye9pLc98B8OtD8%lFtz71;u;^QZlg>}7%DfTr zo*9Pw5HbF5G1C;pLn4CTcU1v$jF;1|yweHaPAu>9(ve z??|vJA&Kqit(kVXVstrL&KgA1woxLSyT?fo;vE}IirOfvtUiM{R9K>^t|45<2*e?y z^>P>?lP@ca?l1*>Ns(pCofh4dn@QOu9`WZ`SR<4~uM47znd|)MyRqN%;III9;UApg zaG-C)J(Z0Ip6XTMgzqN}8TpUl(`LlGFlhO0FkwkV z-@p3axu%(}cqY2z7N1sk%nT2Va9pPdEmBZ7F{;29@kGO6O1$V-Ht0)a_*sofSH&EM zk(dpx83)?HCR!ZSdqmY0W6@}Y61FG4-cPo>liVa5jxVHEp&9%yDXeur9cFj zjZ#iSfYx!n462*c&V%m^pfqI={+WkjTsCc-V^CYTLM0sWU8M4BK8{g+QeSkgTO{$R zXPqP%493PPsq06{*3c2TYhwSlc^WNPII(F^>eLN$fmaeCUKy$;=OH{3A)X`S6N?I7 z5=n(!(S%V5{!2mp_t@(CeR-JA^H|LGX$;H{J?JPUIYn;+zXYpI&U=@9Bh^loxKz+A zIrT7c-GbNQO-l0pT`kE`m?CovUqs@09&vMD|Cg#@yI_y|ICY2OW_lcKCa`W}`aqNY zqiMw%Jj4*;?AvR5$1qQ~^CoIF&|07mzK#B|^}J6peb=h;Ve>*K#e2_imbc3`wmXiz zLq+CM`4=&b&T)cGIN{F7#9~{;n*fiIe19wQd3JhQwY#=C>s4vrKUo1s{oq(APp@Y2cnP*CX|SD2k7haH5BHJa=u35p&Mf2o&E?N#DG_Uw&;1e4Yk!}v znVyeh#~U9aWg!Ya9Uzzmie~ix`7)+w$g(pZpVO6TH0-=tHgo(Cz9F2P6YjqO7T+K* zIqCW^A83iJ9NuIsJ5k2mrU5MI;7}k2ZW&6tRg&}7Lz}@BZt1qFeun)W0ob-qKp|WkKDe5-$BpD0r;@iywdoJ>c{DMftbu{uJnX(++pXi~2C+)Fk`r z6gu66vv>E~>o)Yt$`A66Q{a|%?ly((Aus2Ko@3&(mq?c3_NW?98>@hZ@Q!M)heBXX zPoWAmKU9m5nYrN+#po74;5lEM$PV!gCm`QO;8~2pliJ{~G4PIVPxejz-srXv+u<3M zAy)?}9Ma(-bl}DS`d-;#U6>(cH;~{`h(MAs!^+?#tiAjgL@43kDQo2Nd_)zqkQk`2t$iGC*hGCy0{BzF-g(Jb|cZqG4PpEGB>G zDhN-yaT1pd#=<`Sty0+nW7Y$o%uAM{k>sgie**gjvM zPBc}E#pCG+5xMU#3cIvLZ0_IqtH-k0Y#b-~lgPi8i)F$Q!;d)XwbB?NgBv<$adSyc z-;sxZ(9hJX<*EnXV=x#EJ2Ad5=4x6Za(#Ti9^Tz(G8^?1Nu)>+;ZzEblDQ5p)pW7$ zcREAZbnJDWZ8zJX;yul0-cHR|+*CU3WgeJqem4MX7Q^XQ-H#JVY0mT!dKoMay3H`x zus=ARSLCw<6h0NHzcUYY1`~+eRQp$39&o(M*d2F&x7%VUcccQA?y~4TD$NMw zS|Y+YuQcvX=!bvcI8L1m$K*pQt(6W1`MC^i=6S$dq7j8^vsaR&OKw%7WEf*rk>faV zrKH{7Acdnsyd^wSqLw}Xxkj2 zEKc|chTVq~lEO#Lz(F1C_jgGxIwB}M%eU9Jgr!c)a|m9f83{?(@~^<|iYyu**P3OE zeSwzk3BtI78?$}-M9x&8ce&q53-V6=M^BZ8x~it1frA|+(}akSSnzoA`XY|^TdIs0m)_uQIS@FMK9K;ui(qN>ktk$ zygu95@qO~VIaIQ1G_?Hcp8Od z(6}agE27#yw%vs&jCbNPxHXZZ7U^5Y!X-y&PPS&@$MJ@|Sule6y68zNjh)PLS>TAZ zRQ|GY{NJE8dzc^JHmNtV3T^`LBJuI}>e$~Mj&Gsu`8&p-^_uti&A*uZy$8v{yQWDI zm$lx%7IwgYSSMnSg`%hSiyh_+gj>1%{`9|74`c1Sjq|`^Mmq(Aej|Yu`S+?EXw@Li z%aq;+g>CWup=l?*UKN!yD2kQCA`;ewMtr(h0%T3PZ_#|xf4x=z{k!YFa!UKJe^B(6 zIT)}<4B8n}!%^;PuLh@n;+^%BGhe#~bG#aIR0fL}N(fu<{+zoKjRY|q1|Lly66%f+ z0@65pG|(uXC@Q4^xm`I%8ouCs_QzZ>B1aR+3&|ek^WzBqmphRT)+-3RSsXV5Fr*ie z0Fs|4MbEC5BSq0ozA+6oc7IP|+0~9`Fj2B1vm#NXQ7MJ_k2B&QPIe`xUY`F`<|8@|kWy#VJ_|np_odGjK){ zz~sagC8u#H&#)`7pV?9@uc*u(D( zdQ{PYUZ(v#qnfDtWGTq-g4)s;dU>JyYUu_f(sWswc_6FM%pST(kt*Nm&LP%ZsHy|P zdml+5wxRepFbgDrEDtC4Qn|F`xyF>pB=^WUzTn?^x^}S2=HY@c{f76Lp6T+Y#LUYvaxN;uVF%wC6o>Sdh8jO~90r$dLs}bO(#E zo-{LThPlnM#V9AMWA!YnOc#x=LbBq0maj*Oz$eqNo>fD1ljz}CcV_Y#O%rbZNB?08y zfo3oQX3xx4D6`J#>YV*^tLMVOXf^d8a7&d|kH-eNY&yj0J$cZ6v*FvtP&;i@t_0Um z$xz5T<5?u)U|b(}dZEA4Jn5dcSS;z>1vL{3n^zqflXK@DLt}Z?t_$9DYLL6NSt{)V z1;G}tJEKvA0mhQpnJe6JjWpyKf~a7lS#};<{Qg>i1fIH0YW}_Qcx-{V>G;*_wHF%W zEkc7+-gz?oeY1eI?K`#r0l2T#qH+2X0K9wGFfYmwP{dR;`P)%U;Z1MS2(H-qrvWKM zup7f?n^Z-->?ylZp%it`AB7ci|LK*NIo!b0-(Q&rNx*rtT$nl0pX@O&@I#_ia?{gQ zULr_tkf#a844D?4`dUX%N(uMc~HWVjsJpr#^N z7zH-b>I{)*cI-^HFlv4XG#=6)d_ewn&L4Q9rlLRtR1yDsmc?`GEZqL~AiisQ6ahIP zJVRJuWpKz>e`BCn#)l1Vu@vVJx1bS{0hL}^NehQ6+h{(nvj-erDH!!f$-kUlnbR{mvi|{M7 zF!Qbo?yTrPnFmN(zO+;DA2=E1uSrh&SXJ}Dvn=v2v8>xo1gR^mrdW)E!7ow~C|4br zt}L%=z?B8Y85Q`P$ol2+^hGSg zhzWC(sQFjKaDxl*AChjGfUQiVLIR+CWhgZE1b*{}h}K8Aw@b^~urTpNe|l}^gZW9- zXBGt-0Heu9brGv`&|v)gqewwvUN16L^JCxbQfpaB_8Y=oQ>47grEXM03~5HwKcW&e zq@x{3Lli)Y7ei0rlA&mlY8qJT5|WzTL;uM)~=K-C8&ffzDRqko;_R#x|B zxNC^b{j5#>EkG-DGlxxgSWI}l;@$K*pp zRFgscB~QpN0j_p|n8YF2+G_cmjO=Ot7}jRE;GiJ;pa#6exHe4q!IVi5&!p_fRKpZX zfdXjN9&KV%4kB@4C2V@t0pB!}OEoew&IYa)aXQR|hLQw$vWND`P(E#z8M$dd(YZK1 zTO76hG2P(63nMynFco!b5X+VY>Rp9+ErL`7OHIm$6!D?BG8n{0lLvtyFEN!D8GfUQ z!<{yxqNpakgu%tFDJ35&^tGdngOqGDm8>D*HVxojAC%W9W+7q~lY`;uB9UpEqUq0~ zL=Ge0TuV1>P|he=VO>@F>nRS+&%L)}p4=KJ7d`p7XTkscY43+-Z! z^?`PMoGYiuC(Sb#E(!Y_vqX<`5Q<8VE_3Guv!6Kg>>;qdQxj}rlVnS1aT&A3sq?fY zYDI4I@9pz+J<4$}v%kjF2!d4^u@+b<7uYx#;7##6c@{o7Ef=^v7q~Amu}uI`Vd}35 z>U=$MX3Wr@6~bi<4N_fi#z2hIGz|hydW-L3};ZX8(a!aPqg&7s!&04 zw*W}OaZz@9ZtS${okRnPlR&8lL47z{B@jVg@|!?nRL}h4k6Vo>m8E!|MUKEY)xQgd zH4?*Q*lMg;46>=3;Muuq8O7zP5&c+(dsxQf&?dG~rVZ0dOKr-r{Gn%Q&WXehkJ!^T z;NMX-yj;Jv%cRFPVqV(Sxf&++HZ3=Rf$OxFTf1u6C=y(TAox4Ndnv{Qy2AaSZ9Cr8 zo^=t}PuALhAn^H%L@xqmX9A>~i1hBEG54+adWrbdV5u5}Z%INWqwAEi@m=;hT1rqP z_&E;O+27lRo0+r*C-(>60Wv4EBJ<3(DfbL_%C#tlr%gFLt9n&8IX|neU$a{PBEMzk zI7+k4G_nPJExoT^Cp?yvWjGMDnoN^bB8gtiiCG<(-m1p+wR36m<&8Xusq-xRVbPpC zm(d=*9*rJp*GHkYOVCmRU4a#!RGH~y4*Cra1o6|*ivT=)02O1nSy*cWkIjp&1bJCG z6CF8B^Bpsp0<3t1s`v)GAMorZIXfV-ckrL6cm?Qe#A+^ttESPf-O49WVljWNSu|%1FK@klR-Wg*!_Xg-$M%d>@yS`id zs)d(ldDp(A6jANuQKSj)u>TYbr;!Y?F^pQUNS~pI)kutJ;o+Fdx8F6lgEWArl-$vM z?K7_u2dTtRR7UT-d55}01tP|ekI;NeCj5ye@JdKSkDzO$onl2+Mpx4V6@(90jU2>o-4j|LEZ4jTE|2~=D zmx4(tn~uu7GSNI)qb$>mh<1uXqY%^fu3xmhKO?KmU?P)GsN9R+B4l6TN0*$11tpYL zU%Seo`Z*WFcM9qhT1BRGZ=C~`B#W^95CgVYZfM%Xkb{K6qY2bQE4DPoD>L;{Na{_? z4D<>eWJ1b-Lzy^)X3Jm!@L-1M{_4?SS`*OS%--GR>?E z7gi}xDZ3NN<0^LYm7u7f+$jNKiV<<5V9@VNT@9~CdTgyw&|A76Qnt=_msKfPUa2F? zTqB27TZ#CLH(sg!`^VMF=RTe8<~(C-WmKsps4JOaY(mavpej9asur!by1We=M6grL zAq>Vy9FbP5{j&Q zV$7>uih;GuR)Yw>l6K>@XIbbS?go7k0@QeV{M5Ub$%LjVCd#^4vw5nmcgFy6D;AIsz+QdHa@$F%DGrzPi3nNk8@} z0+{>QF5G066=eO-%B88s{c^vB`jbO;&g^`*$;`65X(=5iGc)4Ye=D02^;=%NlYdu; zLz}!NLuwLj;o-X}-kY%OS?$!F(u|zgCY?^%AZuCL0n0tA;=fQ7x!L{2`aIw+kQ)W- zty_;Nur`1q{7veoO>NuZ;6J1Gm)WZt3~;lr@aW-=Iu*q2!9Ss0*yJ0Lks8Y60RAEo z8usm6>MkK9eaM%rZ@pL7%V*gcj!z0{&rTX98PH8=pf%s?fYxwPFla|qN*!1Qh3{e} zIK(T#<*4pNa)g)U*O)3*b4YZYH}xG)10C`hD0%W_crKl(=3KGj4hHTW_7psJv$M|k zoF?vsnzL zXXg8C2A|CQUi)LNYY#Awdshm!my(Q(Tot7f2J7Ehj%i*80!!o%7)4yOXglQM9S-X9 zKyuz5Jl@Y95Vx`?!^yn>^}W({v{x zh?uypO?hP{yS=5V+C#WQaMY<4pw(A;$(L{Q4g3Dd*+k~%Hr0uYLP7e@ojYe<2(B34 zri2{oP<^w^Txc|_b~eosdT^@GU4D}eH++}xhd!53-PKUIK+O>Sja%#*eNPCmh#9^? zE!*I8aJzlrT_otY_tHk!2Wl@l&l9qHL^@BkL}Uqhe$F#8Ln?AS&>3*e*TYIN9fNHA zORWn|Eu&r*&Q+N5!YBNRUywzOalhklKZ)^(FV(`Hi1#W~B4?s5vYBG&)5YQ_GBPAo-mcuL`@nax6qRZ_&`Ey!SQ9=YI@ZA?5 zmh%)^;&*G>8L3ctZ-NLQn26P1`gtH7C$hD-bG%o*D)Q>RSDHXrHidz#ZutRWQiwnz zI7lp6l z=7-)f(JWP%l_F1%;C?zxI#(TYRt>QelwzKtuVVt4ZU*?mJ_T}$cC`EPc15;fK!)9M z1gdHd%fVrA_5`?%@|om($;kCA$xe8LeBm#P3j7 z`zP6=?*T(U{TAj{5<~8N?n%^yz&+t*R~bDpzdubK>?%Lwnk)0K3%E%jz>E|Fcwrm! z^98pRIM!SjU)&FcH($IA+*m{{(R}FKme43pWu9~WNmSgoQiMau_a#30k;&tPF(yt6 zxtq4qcfKRGl<&|JtUp_2^J5q70oPqm2z~V2c#mAYv&O?&ugjCEJPa@o$YPYRu~PY~ zZ$TtsiOrDt{&T)Q5|M4W``;|2HGL`RZAH0AN#0JGTXHFJu^@1pDBxmjS<>@oY+bYKVr<)r&|1=#KszjV zz8c0nNIK)QBLEyu-JQz@hj(3pUx9blcD^QMU-i7rBdoQX)|A(FDCPZO?)eApkkf}~ z39s2V`vqPddb6@?=t+G=(CoT)(`0cM#JX@9q%fy$a8@b#NT2vz)ts9B^&{9}egLuz z|5l50L*QtVwawtFk9M1V zYt$0tT3e7hnkLefY1r>UJlUvAalf^R{9RvI)4IVg+-dR4>9fn#3S*=CdRLu#ihEGM z261USh&ztu@Z2t-UCb?6{CV87ZuP7>`tzfGmvk_iCo${2hu|zvmWl7Is?C6BMaA{I z&tZwV>+^cdV9mpM76x+WQAWC;!0j;p4}rUJXD!Y8e=f<7mK7-7nkx0J3xO*J8-bc+%JS`S3PzS^ z05vPY0e>ie{L6!hn+MIuPOk_Jd=|sIs|N~wkfKgM{c7}e3V}t~2X}`ZLMCg7WTDt? zi#Q#kRcnaS>i+sYe1;hQ#TY9xkbN6`;bBc`h_MnN$6GiRr7}~E#IgVi+@Fm%JH-S^F%{FMq$aowofW+O#qQyoO_#yI21$iDJnZr zAB1c}OVMgGh=8kgoDlh7PA&YJsbMs4gN#c_qi81kiPhl7+rD0GZB@~(o#m7mMv+Gg zPCI3auI{P>!rVrmhrIhMP7FJM1e}_sXX+09($BylytyFx+nA#t^F{ldre&FzGI~qc z^>fPV^0I`Xq?=WP^Zn?+#jbB+h)q%8(T5W;s$76C&xhuhI>dLe63_WDWzEnQqA~?i zi<*kGCjVCXD@+K!@W+Amf}O~W1s&ik*`z7^@nu#u8!aL!86#<&i*qh66e1&m5}u$& zOwMRF0dU%|x>qi6cu8vgFa^i;B8Ou`9U{GJS2F1&4JUsP;c}rh)w4>1FD-@?Ku{fE z)k5paYaC$%fQRPXjnWoxvBwxARaxbmi;zWr!U&!hFGs4S;1+9;lNIBjHck~S2@_G{ zJC&Sj{ym>f21wRs^3wONpJ%stK{wPz+3RXsK>wrz@GP#v$eh_}cN6tBW^kr!jI)3| z1ZV<&gFzZps-XYQd#Kcfx==Ew-@x^vB#@`nL%D%ZhEp-e*)y58NS}b}7Lt-@myA@K z4%gfZpF(V%&VYq($aniligrHxy7A_6pMAUBGCK#@l77v(&qxe|;S*!Kx7<+9aiYwUEa&GbUrU;r(O(R~m9 zR9j~xhdN3-J-8W_Fj$!cS648vp(}~`(#QS1K?JKXOkYJ@SUK%FPQG#X-+;yBjpohw zj*DK@L5hH<-FhJZpVC_60Y}&PN^Wz09pLV zOvEG<%TXa<_zZh3D}yw3@(JI$R~*SOa6k=}gnDQ`V_EK{Sk+1`hna?Xt)NWUBk8Eu z^Q-CGa+g)qjLpL?g)9q28>X6Qbd)BdG>|CtvYWTX0U@rqpH+>7t;fd`LgG$}KpHO| zCyNL{SivG*oUk7Yk`N>Q!TIH3t|nacnp(7(bb3-2n}l*xr$E~%g`~5q!FFZ$H^A0~ zC!2S*VKfax^zgxUpSg7Cl*pD|Y~^ZwCV`M~K`FAoEdB*Uiqd8UE?h0+*trnw97r9u z<8i~?hgEh78p>9CE*0;^P*3z&v_L&UmFgVsxpD)ZTQoZjr4(ASJe!g?BH;28cK#)a z5ACMMlja>o$q(}u2}2G-^=emVy~>1+*glQx{8dNfQq@(qzt;YuI}hPnsz5*`@yV^w zjr^osnY~5t{5qNVSU!Fg3}pk}?-O?u=C!`Kk2AW|)fG!}3}$$mL)PB2J(JSz zs{7*C%jUy}aaZhxqV`!?MOiZ+f%O5dambFHXFk~ZP+C@_a2($G9x%AltPAyxj8k`O z)ttDsjuYDh;kO4O5f$M<(B?B0j%x*}8Yr7k0A{F2kU^Beyshw9mm4}XZ=a=sEj{2N^I-$<(=0< z`)!1T^QH?#{FXnG5+%s*VIcvR6IC%W4pbqA3Ne0l{i)jbQ+$hLAI#*~0wxL-@J^av z^s*~9OClPy0~z{s51JZuDGYur&}Dz7>Ro|c@4F5_Lr0dTe-0S`3MVN{05sc zES??kO?^BziQ*}xfz0%tW|4r! z?aa)dDJi(rerACmtNitaf)?2yuRD<*`_!!>d?XT@I6DAPXriyO%8i*3=}*igvv@>s z3PgF-!ong%QMuGXt`Zp@-Y8}Wa}!u{)~q;=H)DiqNN%c4o?dzJxkARQpSa!709jlX z1#unLAvfDkDE#rb4^MLYm+?-Aq6G>9=Y9j7^8L(9ar(v))`@+zD+snUC9&^?sutv4 zD&|}|MS=+c;Yt}})^DP<2ShpM0C;4Nf0Y9s0=;yoqw^(l2dF{~CCc~WZO0m- zZx3S?7Xw}S6m;dgE*(VT4`6&Ma!3zZZeKS8Pf0<8l0lCo8WqR@MU6Yw9h&u@_mtDL z^CjppkgKVvIAJsT^P&b?-xU8@Vq1V?`Aw+s;G0gA6bB6&Q*OfNCC%|znexHh&F!%5 zA7QI~5+8?~brlR!Bm~Qt9B_Utxyo26s2ro-p_~AQRcOF@3rmu5icV3Div|KYjK++e=VHsr;0W=wwF!GBs^^~Q#Dq(B15`RV1 zH#&;yPB~-*q7M}W$LWQ<8H*=~HOFRwcx_yzqTf|ZBAjRpEcXu>0W}?Y;;T|GL6CK4 zMwy}{Zm!0}TzORJWP%XlQ5q(Fv&5p90HX=w+Hw-{1Wh%!-Lb{#4u*1oRaQk#ep%2b zd<14FAZcje5ni}dIcDbcaf!xt&xV{t(#)Y8koqA~@{IVi$R(ID4D}lbveE8yQR5~I z6IWBgDl3= zNK|gmVP46cD;etk;Eu6_%Z9eYhpSvWYQX+vpv^N;2j$eQl`uQB9=`g>CbY}lw#vo0 z1bdW2e*cS7dn#9x0jmMHPS#lZ1WnwV$%1`GUVJ!bgpFpT$UdUOXO)k?+>O5BA?RTZ z!zb6}J}`%0jEBz_fI-SdAj%cc=oKwVT*a zr%YZAARexsFI)URRLeinLEM?8jM<;OQj;3?K=TkmBpgL0g;oe0O85dnkQT)#L09BT zH6raHkTXYg+@LIED3H_N5pGoedCBX_L8QQkxif4e`4dAyelnC1)z=;Kj>R_3fj$xz zH`6^6#iBU9r7%kpcZ#JrR?K!$&W1VMprkfUyrZzha)+d<_%rPeUzweA1No{xb{o@u z98>k?B~HqaJs;$TY`8}Sygx%sAYo?TEoQ$=NHU4ILsR@zphTEW0kOYHAfq0*L;rT? zww}?NJ35*AeU;x-jD#(C|NAgl^`D3;1xoYw=D~5;e%Z3pL9jbN`OGyc%_X2&XG#%Y zn_UKy>>iLMAnq$tTZKEG?jHb3j1I2kD&Q$P=o@zx?*$$ek7aSA;$-S zlQO#oewoKV7A`#y`LYEK_h?mMvzGe3%1T0W7KesADr1=@ zQcwbHq6$K|B780MJfvQ2NbrRFsD zkF_!%Awv6Y*QIA~j6h^5@9?wLapy_nO)VlxibXTRDLalSRfMY-Y@{Ow~TQ=gZX7pVHx`6Q3Tf^9L9E_EU<`GePpYqHE-8%)fyc%l>SmQkm+bfhj#8%qJf69J*TMTdFPJraq?m$$5`@~Y^+*8$*bmL5=(6H9f#n;5mH2TZFRdJ0L zv}AKVZN?X6UJ+;J`kLByqxQ#)0c(h!hmaP>*u59qIFQ%jQPW4yn}bRt9VX2#uH9;p z*L1q$P;EH~YSfxg(QvNc5Dk=Nh>ahyY?F#zTCl8}0?04)EfyF_f$8|_66`X&LP94P7^`0*{KV6kWm7j(E9pcv8dLgp)B zVa@}eh*i|AFP^lPn8k@36|0l-_mehN7dP4jH-6eLJ$x-)GNK1kud!_}6ZgHdNf)1t zKgSik%^J6LL$_E|Dlhg8H1cK_yqaAA_~M5ZxT+E7cNM~!)N$+OimnUQ`IR_ktGm6% zn<`fZujBF2Fce-Y2JlnP$W@y2O|NuEf2UE{%&EDAs6EpQWJ|qTLZ}hlTIEY_kd+@p zWOl@Kc_1WeUPD-3!Y>Ob#fZxt3e2`??Au;T?w?)I$q|$LPOzq$vlC8u@-In&z;L2v zqbqe&yGUYVMQ`0XXF?aS31_h}m%~aWCg?(pFAVd$#&XYhLpjH=KW}rLo^U~OXkj>K zaoV54s~i~BS7Nwk{8_t{o{RL1zrGZ-Zc4B$+PmLDFa@<~w`!PuytV94dush} z5hkxYd}4QFWQ{s+i+THu`fnYZeMr*ew60Nz)wYltCgl1Q?T*sVIG!lR<+CLgbqR7!L#r|d3`SynQo zq=Uk;29GrFicc0qEK(l?xR!|}?ebYt@d+{=#Djptlb}h|76nO1sL0Ex7S=;b$5EV9 z4Hsf!Q{WTvyrAS#gmWU(go!v|1IbzKb!c0xO(#-NNL}e^LNvG&*lA9SnX(TyfDMTP($<=&4JkE#Mt#w|$d@WaF z;8>MB{xnHN`}^yi+7};g5G636OA>UqGR{N?3#J9qtJokFN-;|H+N+qy_Th6Ld~IUo z*VDyiWV^D_hia|W<_FULW?^<3_2o&b!a`)Ud++Ex8mysLD`au0OQ#Fv`g#6YX|P`D z&Gq-b-suN^6V40py+4_=*8-JnthR+?(F?Ez<58~8OsQNJD63(!nTYJ~*LS7Jj8eX) z@Qfsd6zbOruB7OUCgIiJoKucbME^$FU_&Pa6KoTGZ=JfZEM#7 zVnJ)-9cE#ue^Rhy!@=mQHbUyjNYgG%-OwRmOA<_x5=#q|6k;#q-hs%_qS_Fkvry}9J84B_)qFjdRchppo&8PsoBzy)L+KOW3j5!=T(Hy3Z zha~C>o`;*7Q1li$P9%I!8%830vN;LN+)no2KdCNdRm8d;;3srzH)UqH@a2byEc9OH zhx6=CAH*n>`=P6OjdSNUu}$s33DkJW?3JE24=yvmp{PJ)*t&!!mzx`_?c?b~gG=EH zRent>u3D@Zikv7hkxWpw3cokq=M=TKJl7mow!HTOwF{PHLLOn6#%v{eLuDMXux0@s z7bWC=pCV<6U4A$$>-GYeUP^w_gQqFhCWBVZ+DH5$P<#>vR5{}2_-OR87^2qbY{;Ug zOffs~XVMW@VQHje3RL27v9R3{Nyn!eGH@wVks}0*sXBtyzfG>2Z22yyko~Sh~=`qln`MdDABjh;@5o zpdKCXrs6r7-cS8xv!-Uym}Kw_i^R zKI4tvq-g^Z7+wHrproCCQjkfwF} zk+bI?5_tdCzEYTeF;G8#vFjm`+*I*CQhtBApAw04>7?Qf^^&U8i)aVk!u}!qn|JMFRNZ!lC`PYg7oCZR&A=+88A1@&S|8EHlT}><0gK$}#xD zdc%Z^scTg({pH&U$7E9BhkZ13mE4E9 zAA-+K6e!CQhS0i;_ic!@4bP?jEBh6?&jAhRoD+lGm7j07>^fms37y^<1NUv}t7)Dn zL2~5+n9#7w3Z)rDTOJx`bnlQ?D;>o4U;*23LbCKd0Bzk>|Fzbjqm6l<#pR#Me&G)Md z>9a-|bn+v7Vcm_Ea!Q8=RA+LjE`wMZaHTk-FyM7lW#lBSBsDQ6<*fSQi-V-GjeNk^ z1B!${#|NfX&$X&d0q9o=L#Q~SNY=YlhzPNOOi-mt2$x2rBiT1Sa$MbUrL@M>7KhGx z?)+-v=kTr`A3j=NONp(2Iyd_MKH@#4dm&CI!N`x>2slqFKrZC4&ki8s0A8!%u^lee zFaP6;3K3E1AE_Hs0*|Mpr-Clc5v0gJGFEy=U~9Pzk~X&13)`NzF6pyU@z6Fx+jg;- zo1-?iu9rpB-S2gMcmtTtyTu7f(onudp&9&bea^vF6YG^?2b`&Se{U5`gQACxglY1T z;wh+c^u{p$K<4#YqF=XCfc1BN%Ac*tfny z*UKp`h2)?xnZ-Qt_E=Rl=3t4UFgGXF+EZ;PYUGIr8gjZU_B}qe$&U3o%?`m0HYxgrEy5~*%NbT5e z8&p>!4LQK4=KkR^+$G><<()$Sk^VfFnCDSKohxJiByHUo>V}afNtY|>Fj02sQ63Gm zzm-`wq4|$cX)vNG_wT3#^Gt5NcP^ z>$La3``C=wEZW{dAxZVm|sVoPERvl`e%ccr6!*BNybe+1KME(W!wX7FqN$ zFbZTbq9k*<2lC|FV=B3`6lhXHE=nr&Vm2dMVV?nh5eP&z!~*mJyopFm=rF!30Kq?K zCcH%0R34RS!${Vble6^>*4F>1FYXxSkbVtB&xCzea%m%2_%ph zXCfGc;*{O$CLyQV;tyI{-@?R z|EPpz$V~QOtja~ZNXQccq(t><@gK{-#ex%TlM;15kVo2RERLBEDUVFq~NwhMeG};z~eWpas1^TF!WXwtL|Imn>C~4ChX_b)`x^E@x z`|t^ZqC@Iy(FtKw8SH}s7G3klf{-=NNn(!4{?*h>T$5Ihz$@*^KZLNBg{HKN z!cXmDaAPoy#T61kvF#=ylZg^9{!tQ9=Qx4-iAqY?rv|qjTnq-zj&hr{PD-Dbj7&iK zy|jrh^oFt49p-w{Y2VIV%pLW~m8aa4M{~lXlN}FXpSOdAFY-Lk%@)-{?yk8>P-iz> zgalvU5YB{Le3l)*n?2L-o*TuA8^cs2Sl#@t@?)7+=;S`tXwt#wWNo(yZOBec`_TES zn2{m`%O$kKt6y9b*dl?(s`w!Bsk(S&5_vxqj(}GbuN92YO(qOsA^&7bjClb2#_AtZ zEHVkhS8mP84z;l`?$pp)ACsE54&^sicaRor~goTbo z9q{19@Wep!@+pP~aY!0IYMQ3{V&2>1s0*DA3Zc&vz(ojuh$qj^StDAQY*O$WMh93F zI$cnT85BZTqv=M-N}0&$er7;1P4%5mSiqW?O65d+!FvvSW0gF@sqGY$!z2veEC@9( z)mtevkS)de4w-R}4Be4c4<8vVO4Q^4(rlIk$Hzv&7Anh2DpF8kaS=>vmYRA;^jQg* zz7khi#Z@lhk^@Vo-v+dUpuF%H#F#ahsLgfN6iD+dIf}#es-f8Zt@X9eEIN(~B3dNO zA1zI}tcsA+dT)*HERDSij5qg;Apik=x3X9vY~0D3=SLa2WQ^36~9cnj7zQXW@vW^G^1*%6mrE5dh9w=3u+u2S=VrOunn@^jSA z`(CDMXs!;>)??WHpK>s67glbKUr->eJ`SL}0E~yvk&lHcDFy7e0vAtAuMGoh7iLWu z{%J2G30)^h2i8SzlcKcKv4pVEgt!xXICU#kZcj~bS&k=0baMaFB!8*}YuO@l$&etO zRH5ip{X~c;ofSfn3fAGH9~ojnn+I`s*sNA+E3yMV)Y1u~VSU2}~rWjcP`@S&oc8sf|06JnOtxfRv-Ec~>&Lpgmy7osE|S&~0k ztj!CPg=kYg$wp++R8!@~8VqP1w^&wXdVfQGM$o^6UQ5)k9Z7!$;>MS1B;9abv`XN2Z2~@}?+yXyKYQOBd*v7uk10M>4%lcIP7=r{NA%#&r9247A4N{aIr-Kbo$Vp9(6RszsQ_ z@ta`BF!U?D$3AI}*bmKn#F z{VLrUcvdYvoGoQ6`BAemb;%UhxhBIjFT+=})QNl+3-5n5A29QfpLH5jo9C^xrZuzw zsl)eLh{ACCcHlO1T+DRs_8Vm4^c)j^T&&Cw&tHk9wA0I1-^N%=@3gzQzD9#`il@*A zc2Z~PRU^vZ>|1wMZU1LK?lJ@E7Mbk^`nn0FOCV3N1-Hw#XAtvXxRnyFMc=i7JPq4e zAFHXhx#rnpQoL32y*)AewHl!i|BZMS>QSSi;Tv4%(oAI}f6dRgPDQ28bYN%ldsqMa z^MC?m?)!sF*Ne}4S4UUtZ~pGB_a5WaZcY}@SG}GM{N7vsU-A0A(@MYozW)Lj=+jRB z#V_B7^wEbV(0`WDH>uxG_|Z=)FyI^CPuV@d_%Xoxu|*>=$lEyJt!J5q%Ye& zq!=I|@iC+sFs$1>j6yPOC@^9fFhWi+V*4@TDlodYG2+=h8u&3PnKc?5Fc#T8W~wGJ_jwJ%#o@Up^ZU{5F+2Yc5d$;eUQu z;c@&sL=FpYi|4LyF<6Q-4HMK@DVG4H-bf(dTD|svT0XNV$2n~mW3-Z)y5E|Z=hD3& zmmMaWS@yt8M9GN8o2!=MV8Oi_uzzP;FHnuffn?i?-XZGmdfJ@3o+`FHA$bMW`pzuVU&*zQGQLnb7gpB9fT zRvFGwOVmb=`)8IbAxMm47@}sR>1l4HwBB1lk_ei85Jj4enGSM^$6h#0MSHHC%B$6$ zD+dxbflsAt%XVDac&TboA|a{?n24EWDi|0^B!wk%2quXI1l#z5Y}FbN*9J!Jb>1Ih zOj_Ro1Vy_Ya}}GWCmn%ix#xvfbGGHmU{;<6q+Yf?$@Mv|p!W0-;z$L4$L-LFlCP23 z^Bz$wCv}3ar82fS*G$`yNzAjVP?Z$ZI&+G_@+m3SN1{CpG=|5d4J>bz-pEuONY@5~ zAo)bKsMZU#vb8H~J+sPup@mj2qhI!+iE*;SDau;aT{+2{;`(#ZG%F>q**JJKrds$N zqO3fYZ~dsI-urRb#_Xr2uUZAHA7*}qaI4?0ZAW0{p_WNMpIx08(QHY)l&>DGnLL%x zc1ccV>2*K2{?dA&wUKUhP0U#qQx*{0|8lUMFuJIj!29BMlmwWgRUcAFRqn-&XO|ou zjMP;~eyLht$?4aiVOLt)(XT6~b~c{aNXTJU7DZQGjtH zd=eNALJXAyZRn_t>z7KXVT7}gWx$j5>MK+9QL1*O+kBq_-(usxE9pcK>(?bXmM})>t~2GAVV8A0 zhpC{Ul&Q%lW8R3hHiP5c1i_}LE97wtgdWxYn8-#d(%~rjB~s^;cZc+0Fqb66O~>r{e}&u#M2^^}%`@X# z%T?H-{C_o{Nj4&^hsG)z+-L;`<>Iz-YtA&wG|H59awE3MRzZb5=fMfGC3l4_51f>Y zs#4aL9!bG6AuS&sSNZj zrxyb-2Qm#yt#}RzosE_TotErvvH##vl4lfkZ^@YcGC;ng+aHtFyU$vsAZbZquUFD) za2^zm<8EMAfK`%8>FG3`X+2^0Xt?vkyVwWdAB$bao~tzuMI|{reJY_3sB)1?6bM_d z)w8tB$|vI&xAnae9)y=!?#n5y(x^>4=sgtTOedrKm12!lYL0JqPsB`A!|2GJqBZHF z)WK}4*O)*^t?EWhc*B@*5yFf)Vz*Loe4Y2$QaAixWZh*@99^I;YHS7@+}&M*I|O%k zcXxLZYzBAN;O_43?hZkMCJ+K4Sjb$yU8m~od+-15s_yEpTC4kA>wOUCnU2cZ27Hfh zb#A;Zs+|poEruE83OUmc5()YoI;u*Dd^V_CXLK%{@np<0wDi|k6#4|m{8LlXW+2b$ zwDV`~VfiQME>Uec-Rbp`bw^8w&#FcZOIZ@s+2zFNDJGJunquKBRtV{fa|rQX3*QYV z%7mns0Cvh#aj{Vo%zX`ke_D&^Q0*QN#3AIBy7~d+hps5C+(6u*I8h3g&rC#hP)>Wj z)9r+X-#dz&%X2|%X-r~dyWCcq31AU2Qp53qa5BK-rq)k?rd0FfgWF>NXFb#cf2|MpdO#(RDJO> z{dIh)b@qu!HC`E#vjpKMOy1e-u0oQ_4}YVTjGM&a_LT zOLwpr{(I#1+L9rt?b2qDU$cGWo9?G6)HuJ@@?>J?tRA2Unx~b_gBsT+YB7=oy-!ek z%jn>)1ny_2S!%u<^D}cl+3qzNPqX2*4NuE2OptmU72Y_Pat{56k3v((7Th=Rkr4_^s2X*q%t( zwr6=oY#!YD!3L^FbYZB`s;bs^Jc|0zv#xrTTEPW&V^EQ#1{|`}{It0dxcPiWs6;j2 ziH}&FVera&=q-l5yisi@P%HcZQ%F!x_fR`H@uNVlgo4Y9ymdLN{a)6Oew1PG>6ip+ zwTg}!U8|~+%hz|c+Oa><3t*2XWVrOG@H;$sC&IevIaOgAal#UlY8kc8q8PYX&$CYpt?+zAZ5CaO^6`xA{rgx>mTJ8 zuHX|bu|^<6lFD}!C9#+4b7&nlBc+GlVx3k@Yp(NI6N*F}D$P!drQi2x7n`CjFb=_{ z_0`hXYg!?P7L!+dn8^ZVjwh@ex!E2*_4ozFee5af1tVP9bkOV=1q^XE#I$xL_p zR#}F1*SZUBm1ghxv#5EwxF1`IIu8+RwsCj_vLF3jG~^iX;U%IaqbmWQLTK!ky+dk# zMY8;H?EWpAb;?8Csc3CaVb80~t>dVtrSGh*$cP~KRIKIRA%VQ9?8WVO!pDa;_Sric zYx+Eq(IKiiS~vrd9|PA?uGvL{PloX!-1CpRDs(I0cr{eeTFBlh$P`{1{;>yF zpR`TM-&>&lkJJP&wojxh2%p9uI-5yPLbSUQzyJHylf|5o3EEyiPY%%GXpv|9@& zSU{SJFXZ2rOYmbdzJb|ArzyN8yPOYrqg6=oOy(o5W#Bn>n2q^GtEbGkzW1~b`b82a zw%W8ezu{v>s$kAii^0Vco@I9`M4KMj5=Gr^h2$lU27*Z6{pjWKi1)$ln*7g!-B#zfSjN5Ia4|LSP#Gd;Vfd7qDKEGcLt|Tjt{Qq>QGcHIZo@_DA9%J4L!pL0m9b z`NTGXH^q6hW5|XbIH$0Vv`iE}gT;c@j)gL=0HI zH0QolT<4cSnJGEUa%$7|S6KUCOAy#z<|vBm~IWVnaG)G%P>IBiPR`V@|5}7ElQu}dDZDlyaQG# z)f781lHUOzRE7_(nVDo|!#*;i!P09hNzu8 zt|RJ7&z({aSwgZFS`%x#R%yzWDL3LLhG9Ai5hVYjWn*(f&qs)>e_OG9M?s*D)Ctw6 zKkM0?0r5lj$rBOPb31i>HBwLVnX4lqBNr7+bTS_eNiTW7#MiiYj^rNZlxX=ACxI(1 zsy@YR6(4sOaCSs$t{6t=;FVjj#Q7G4F^agH=Dd1EFYGk7`KOY%=WoL`;Xmfgr6+AU zhE+W|YFSa4`KK&h(AhJ%eM6?in`sd6GV96A3b2UTdh%jpXzZp74`hxOCr+#0GWdGg z$Ql=cKvLhssPREb153Xi32Mj~Ztwne$~sW!Q)^_2FeF(-H|3+;hra2`VII!PN{%7i zm}oB+j?t`TpA68G3xiyd!%mA~P{f_Q%0HU=97i(FSp{19g8APBZbYoW$|^(VJcT=! z6k>Ub=KZB@$l>@wS;>H>c56IlAfnc&{`=Jj|K=HJ_!^SauE zb3$62#c(stAG(Vuw=V6E=mRCy4Oxi;)>-$l*kPbQhkZF2Mx>BV%ySNKafpE ze?jVGI@7|&338TGlYrueJ8?#}8x71LGcv5TSMvt+ur&40_FlAyF1@&%r57C;WvOzT zS0dya+|w`Fs}<1LBYNc_`#2(%mxrS|e|lm5BN*#ukUC>IfDI}=Kh+@NrFN3ne6d#` zjf&j1a4y7YBkW1p_a9{C8hNfsX2tcptd*di?OLAleUPkdMIWH}Y4b2uE!sD6h!?Un8T=uxou{YB=1k>0drY;0bK*?=RF~Y@U)rTs#%#)` zouD}Bx9UQLqtnIS4f<+&$EpPDGzn&$QPseeb7dYx4gRRa{iMstkk3}oic zfnz**F4Dnqp!4ogejUEJmZejcSd>6rqw&;n@QQv=nOr-J0k{9OzJG^hWoOxVbIP&T zgtkZ5#NP$iqlI3=CMIlMa{4*!qbhuhZVsZs$Ssjsr`c0J36jguP*6BEVLO-X)Yhbe ze7e^sL8ecvxd765U!jWI{AIpqlRVzmJLScBXTJ3S0;>o6etT8}oTYl4aV_H|xmZ=S zJ6C4WPczUpmmdJ0`bY?PhN9`HDYJH2{5qo#eny)ibCJ1MlYgaPZD9O$RWQ%l_H;$I zawdFsuz~gC<#&#u?V+7ux&huoA(~O(kMRhCHQW7+0_QdJZ5uhV4qDkkT?H(Z*VV4_ zrbK}+5lZW!ooY}7e}sL_d*T5#{e_BbiD+blaE)ra{w@FL#a=J`IG!3mkzW41@+8QN z7n-y~ZQXr!n&f%YUCBH_S2xXE;HTH>z>tdg{++#yU<#LMYS@Bl-O^|05U-G3HkFAo z$JLo{mNYe+zqOOQ(TrgK7Udta^ObCUc~{xybzok1T(7$XgbG^w2Ru#MyIlH8-X{M9 z`qV&!X#hChlIbO|+S2;lv~^S&%wui!BJ)oBd$$QHEzG-CL`9n+Bci$O+1vJSY5OI_ z!eIndXt~KWjOD2GI){60F-+|(eoFj)>f1ORi4}XlOpdHks_0GzJckLg0fSn6X)_y( ztyY@>S2LGB^B#aoKLbnFjc%j+N@IOBeUuNVJliiSt@wo}ccKiApy3sdFJ>Mtd%sft zi5_>MEzlk~%06@+UG|x-xt3;kN=XI1on^u1fE#!sg$7P1qB09vJLG;1OAxN4t7NG3 z?*@@NqX^T-I_B2EovxvrLgvr-T_~jaXk!5?kPs3ErHG~Z)6g4dmf8W9XB~>1>P4ua zj)2kj=q4^&NVjHv-RRXyO}dkg^HQZsDEjNdRAO zsaEy(N~zDRF30`~>`p=%C`-cmx@L{@2nP1 zCNxMMSylpR3|W9sNwv|c@ec%wyJDM<67g#}W1q>%&Q?#$_t~nu=Z6mc&Um1}!=e~w zkB<3k-Y_fnJ9gAN>aPrtf%`?jJG=Fx--WvksFh>S$}X;)BLzPVwaJSL?$4BUBp2^7 zqi*pVObjW~&?axSHt}_;>$4W-aRbNFUXmZGqZi}6Rx+;7)0F69mcK_o_(Ba5*B-Qa zCy_DEBnKAlYm-o__I1%>k_LX8Mkt`UtZIE_T69ghR4Rjuai$PmxRHl@Qp+gx0a2;loFGsyem~mBlsu;3h*o+PDOP& z7|YQ*S1l9``G-KPeW6|=lRz$$t9_|ip;90QCf2!HE2XJE3!d^c*KJT}#eWOLJC^}V zf3PK0N~4#KBWB?eK_#%7P9(L7b*^={e*c5_^2bGxJ5(`)jU?5ZMfaEGL;~4I2&uuH z^-Knv+0AxF(OFX->enB8MBGa)lDj4QRUH;4?bY|G1>doLnP)ITw?`toJDYCSC>?Ov zgZ(>HmW|~87xQ_eV}5bDF7Y{Yp|8#1$b%Ez?E39N`Y!5w?vJV0lbH;>ZrQ$m!^fMH zCXB$v9D$cl|K8r9h#W&OajS})^YKE95nn`H>hA~|J=>}VH8s}6RVWXkC4ZYz<#2F8uFqT}39j@fd1 zG^Hs@yD1!=8EH=UZpAW={yg-&tX%*(CdqynMBrBDoa{^C1OnD(dkPl%7E8*tdvE3V ziG;XRTik=3`WXsDhWIcZQIIR1W{!W!EiYK6L6v0)Y}z#B5QA|mrRml@R90enRAf?r z7}u&u{v_3uXWyRD5=F;~zNBSWo8|bx%B#sSFK<`gu508r-Y#2Pl&h^(S=X|pN#jQS zbL419SVdcUKYyw$U3vaH9bI|7gG_<-Jnw(ZXXdWy=kbQ&%RrY8b?!dc3DOoeLRWHy z3;8%&%4Qi(BEm*K4_`NGT)c~<#Sw|gIBAa3ecf#ai(hijW#N>Ow+^Wu+28@JZD$g@4FiTN4D1>H~Xe& z8$tK#9k+bO((Nl<|2{>6Fa;HTGl<;2O@%Lh(7$|F*e*z`#5=R+q^(jWz8+^F0$ou8jD zA`eFcC)0n(Bn#rCqud{!)4&~rpbF#MYN?;#sl}RI>^5r5YgoG^@qN)Fw1TK+EibZ( zxXSHiF3oqUY(8KmItG45!5!C3ufpwEik6e62H5b?1Mxf@MJ^BX6tnntLYrcx;T8SNXF?kzhq$F;L1l7wH!$<{}2}lhyHzlUS8FAC9P`~bXb=;!JVjJ ziWW~=UPmWB$+VO>R5EMFRh_pSvXa?3Rz8o(#7dp2cPm=3Vbr^|h>k2pg7b zRz)*DUMu8;V6ET}6Aegr{15Xv(?*1wP_3dahM*mE(LG9OW39LF`-Bl*NF!D^-Nfpd z+6IYdNeM8|PQ6MXjWC4Gj?5O_P&&n$WTTPU(dOG9#PGPmh!5suEU^vHfh?33KkI{~ zA{|UJQBD|2FK5c-WNH9bC^_Antlq_*C@g-XP$;{XwUWDTVIW^!mg*^SOefXYz%5=f`i>D&kpZ!DmmHZbMJ4 zvJ6G6pDzYG8+?wJtaRu0LaQsj=&}3x=TGYA)Y~H)9g{LQA877XS5P!0pRr14GO~=X zbP3#~<6YKLH<|`*m&EppSH0fsOztu}Kee8+0Xj(x_lQsPNtI{a4_8rFWn!=xD9 z!!oKr69S>i<}|2CQ!0=auc>v@_nJu|=6KJ{c4K}Vz149fI4`D75nHaowOsal&z$wX zGndmx6OMVtyi*Z7BB7?ni&*Z0hraV(Ho@uOcji+s+N4q4AXyE+EeVIsR#p$NEFb*4 zgf4`onkpd6x6r$S#{N>(bh~kg^)`oB)KO6`cdb&^XBJf8sM|^0CiJhOTj1K!aPuYC z{FS7zp5MvnF&EO;z&5XZ?PR&?xYfVm(wx!%qk(Iya}MI$Hi+QtptrlTIpN#!pYkb} zwzCiP>lzom!KKLCJD26(8Ypn}?R;O63GwSY75%A_XEa`0;Wv=ebMtXGb65mmg31v2jwS!8ti;?;C?$ zz>Lm+%;(u``&W9C|D$|1_>tKV%b{=ellxY+R{glf75=#(=G)Zp_R-ajVQ*W^uV-`r z#&0s{;9f|EqjvRhZm8o&EJZZSYx)I`~~F_y18o zpH>zR{!qNDoj!xFG)YOOi|yxcF=1}kM~GjaCgnce{l|Rre|`S1^0NG62-9ofOIzo^ zhxY%NPpFVD%fCjF!jQVCkIHBKI4>3|pMG|Jefv4d`?tOE)3aIOzlX_p=JWH~>raZi zx5vT%H}feTZ#5{?+6Xir`cL`P7D5ssL@gTvm5ITui4U9%q2qRi{;!xE4h9B>7x5VW zzl?ek`8}ha4U0g+aAubKkA1|5Ly(WY#g~eHXBo$$L#ZVZNG2VE*1~ss;;8-?%b2gw zS~35BSVjg}_rn(CexQqScd2|Dv&qbVEF*|JL1;Q!y;w3QwSWb2A!EHxUdLcOkVT71 zvMb*6A-4Tu*+X+Pp?4e!v)DpbhqEVFXMfqq$|Fp8relfCC$teotR~BiYw&a_m&LDM zoy!Z1!NA`3U*<4*GR5wN`ABEv8YmEqI)){vuPsRUAbd?nK3$LiE(%KRpF!w&(t@_1#vrc zPvZ1QbJmy!S6%$s`Z$KMqUt!7wd3MAj$?xHBwmaxd6_Zv8&Wi>AUgbl%BeMWRHDe) z)?BWU%I|YP^UVC%u7h$LYn%25P4PoXS zBRKl}kbVhdrNcJeR;}afCy|Cs#h_tZA++HRRN>kn)X zIG1G^#O?N_9;&)Vf@e+V=DInqicG%Yo|TT3DeF*4=Aepd%LLw!9Rag>9_U(Aypi~x z2Xy73tIAyYhCTMt!RRLpMas`8&c&mdT!{^Rv3^Xg7`Ckn^xNrLjO|DKqA?a?-VX*|kaviF?@=iYP|i3y!WQTY;?#28Mn-p}!DI^WL=oCl{R5KhxA z8411FryEMoPAx4<(U7eOXdn5xZ6^dTf2yRa@_=9#a z$Vy&{aK|0OUq^-RS2aq0b{i#vP=W!CkRPKW)`*sGD~b;8lE&iu6{EOjj+N#=#svID ztlx*nb5%CP9{4NH98^j;JQZCHb1Ha=6zljR%U6W?LCAh>zHy-n#r-!MZ#C=~+k*Xs zb2eC&_D;{cMS|45>XLaRHjz@nd#X0uBju2>Y&%qwv1J^KF+rJ@!YosPTNRrWe7DSS zjTFr%n~J%TGed8W#b7@LOAMJyrl$&!Tl;38WI88HwAqZTC^1Uh_+yt#o)%vq7mLw~ zvz!7IR$hpjBegk(j=GXs89)r5)G>C-&dH>twi2G20Y?#2b1AERwp7J#x=NZei}PgkQEHKScD#9O5x7K)8akCH|uR=%#Q9Z&_H~WRR^7FofIU?%T z2+BrNq-dSxuh@3hgPC;HggWa<{b_MY21ZZ92`*M{^r8!y6dxX1N>gUC3qqRKL1zdr zw!VR^Ega@Q&;`@xGROkzl7dwab7+%bV`P7*+xa2rL_i3r$XySg+D3q#jE zdy3)_HZ8OepVnHKkf1kn#$en<&9`)M?WXiybyQ!feM$b1pwkG+Nu&xtw1@ut9^t%_ z;<;M6`UiTm?`ogRf2E&>Hn@4Qd|iM$ZR_mHa5VUCe8B8CR8Y{61Np8d%tuK2#ilW+ zAC(dIq@y)U`Zl0G<=`yWGX-{h_mf5397<4jH!K=s5PG}`wuxp}OUQ{eK`f(_xkrSL zi<5E0-;M5u_9I+<%ox!KNr@8x2^Pgm4Sr%-IW1K5tK{^0bwcT{{@{ z?rc?bbTo=O2y~W`0pL)079?&w^IrEZR6Bb%=Wo3H!4Bu@lMyo>iSK*MxWC~ex{g!* z?9Lh03kysXnV}c*sTw6k{M;!t>iGOmyx~_Gx5_EqyNpMW!PgH9u8HS|)wCt~+ z3o#LA$1q>EP8Pf>KkTtsKH>>1z&@stke;)C6=d7`^=G)5=IX9WX4&KD*TOH+6R_Is z7P70KPxQ$?{iK;8?Y}(5oQR+3Q3C(8sW3cg3VxC4m=CzMpii27TFmADb2j|2-~3|Gh$?FodCS z0-*@{p+Nu8Cp+iq4fF#(4A9gk&{JpuBow#nGpNfQMCJM=D~NO}tm~1qk-&|#(`)pW zuM-9h-pZY(%J0uAs@o=gTN7wBl%SL#d^6en(+JX?I+tGxLnan$4Gh}+Eh%$XK&~c| zgg|6XQMl+9ebTWj_?Eq^*;7{ENI^c5t`w!wFH)~7@`{5?OCLQ?9BDd~HOr2Wam%!7 zlIVvzf3YQ4Qa&<&(>=?ak1L!1N|#GSkLVigp6(g$Ziz;H9*(3JaZ-ZLFK?Ms6!Ekg znF(D+cdv@f+@x=(jMykb=kSmEBNh0CAjT63@=*X{gM?;>6dh6()xQMMqlzxP0K>_- zX4^+`cg2)P1?KUGAKn6|lcNP0F)XK$O1EMWCy~lwSmU11Ue3awWn(fK-4e4wSbBJ) zhY@NQEKBC@rm(EpNQ`9BY7xspYJxT#OzPE0!hF1 zlm7T8J!L1obR}IshI#_S{zfO#XN4W!Mw0s{BPqCMcqBAE#dcp1_b(HxKE_foxT8Iq z=oO=!G$mW|M+SQ&-07m|!p4^~pnH4Z*)OBt$p$|ArrL#}GAqQ>1Q4P6v00@cXF;E0 ztYc9(}+@2&&|_ic3wPDNE2)I8$mk)9iNs>}~!GGTK}K<7!O7a!kQmcfmq+!3I;oK9s0%54mvj zxnN15@WPW^@%bnnt-v(hv*`Is1L*Mkj{Nqms+9o3t6?I4X84$SvUII`n z(GPW_gYDeEFrb%VyJ5+>=6Jbp$s3!2IikiBL05zp7ilq#SC2Ef)_&cSBIYp|EC9=crbb;=m z*djzZW-^p;1;-NKNxxs2?q~UH0579i>-*ukYg(d0xOJ)(J8Kq(RaMH9gBx(@YDx@i%7h|H18b^#YN{M-YOZQZXKLyLYubow zn}llHV{5lDt8;d02VQEwPu1Qt)ZNI{4fRw>DNw^O7tPhU3gsksY==4D`|_g%d97Am z;@2+(*3TQduGZA=&(s|fHw0{ji4yy>qEu0Aq5k$Q+fr=!!Pn3v7mfJbfcRYhJ=4qG zG4BGUu}6-&ud-+Yr4GTU2^iFbl-KmDv-+1F!=N_{=65R$yk^WGG#sU7?7U`Nr)FZ3 zX42VaLXsA0;TBq>7A)b2ubC~(y)CS}E$pu?93-t=!mT_;t$fg+R)M@$q25-J-Bz*J zR&kOxN#QnWqc+*^Ex~r?+Z?X{h#SN%D^&7a!7U*5pi(T$#)rUmRU;(rxOR=*dLJt# z|F-n!oi_ZKin$t9sh4)M+K#)Kj&qK79hQnqtM>4t_PMJBSNLkV-Of+1ouMRM;lf>! zMqQAgu4t!Ll-WcO>Sr6I7J8EIRN?MH?QUA%?##UI?B4F&-R}I??oLV67~!5Wqn?VO zo~pc_n%?(PxVD*>4)qBG2vAft}k9q)jhdbg~M zf!AKL>^|I?zH>gJ4iZuRn%?Hx&M%WaJH7pTyZr~R{fE$?p18Qggx62pNZo0916RG> zS-S%muLFj-gEuULx59&ej0QJ~P|yhn{_YOGFI9pe9Xk5nBQe~z6f}gCKZKG$)K4Nz z+SP|jI*ctcj15w{%IJs7A13Y_Cfyq*Cv81ZN<`#nJ?|Z$C+*He?aAmJp`92(e;8pW z9c2?4<=7h;EJI;53=rxY718$2eTKc?6>ro1;MDpIBTcT}Bp zT#D3#!f`x2cU)g&TzhZabZ!*4rVX&&fNMNq8$4m3KjGLn;XK!O`JjB#6lNwe>1{me z8$9WsKN;9J8N4_7DR`0sG(^MNN*6o=QEq4Dl^C}D=-eo4IV;Z!aZIdYWO?TL^|6dGTUZ6+Yvn5l|S3l zH`}*2JMee5Lpf+jWNyrOZX$SYBzSJ-$LwXfnRWim66ySk$o!h|eAeI5u)Y3>{1)Uj z^!>jsVCClc_x?`hmfP>$k^<9LeG5N8)6XO`8zAq_WOGc?#XrG|Ek^CFukE%do&CM; z4L`~nRP0zO;=``;n6Ramh@WZFv*s&MVE0+mhnTD2@96rM}@gywBQFCbmJvz z(G^;g75ai1q5S!}-ubVYXeS&P$Zdm1pk_B{Dsr3n!fAYSZd^CZ-h$ZM>Qx;|f2~qp zGAKuVP0nRaUKAxEb&hm?)~yA(^L9v@?!+B5*%UGG{$~AHYbF(K0BxA`7n{0l z*zFH(yMwle(5*w(vET3|V72Ov(Z3g=9VBla+@g8HZhm^(3?KwpxtQmnf+h z$4DUiTZwO5$zqyWKHJp{t@}VBT95$h2`F>j?rwBuH60kuRpd&VY=N)P&N-SrkfN6LZ;5= zy6gHuQK|XD4JT8_CnEn&M8&>Intl@@Hr1<`KI#k+tCnGN(TDD5K@!5 zxmB5&aE1Cd2dJh9rIQ1t^KjYZ)0utYnd88j^TCM@VRS&JAE|b6h;~DEnRT1zxT%+sC2 zZ-CDjh>d7Rp^B&VplYlelXSFiODNXjC@2qT^`R(n1818YpayZ&DNWS&WOEZ~^e##y z!Bk+DI>@aMZATqNuNY|n+VpF5;B2)Bi4_BPM;)nYh>rKm*=8uRr`Y+UIGRM*FFh)h z@g{WiB;wejUr7D;;fI+)1E&_h(fXHeLT`aV4Q5|MQEP_oJ~Se&9iDTZ${Y+KSKV@% zG?>~g>bXLfIZyXNLohDl=Mu%Bau}po7*uvM6vjoQEEo_L^sajOkw=aCt2nYg%-;6W z?@-JekDvGHZr@*go{Fg* zdH)pn2z_jXKAS;dVA)9o!r@V|aif>aM~|C>=yh%{;KH(6|Qxe&`Dsng5WxZ2EUGcHsaMLHU^ zPFyK`vDnD$uQ?tk&~33Pwh+zhAmZs*YU^KF8BfR)9xbBd&IB1A^!dNN^w07W9S#P- z6KupixwmM*wVKd;yD99L&R{ZYm_*p)w=wU5NyTB>wV%95M+@Us_mN!R?gJcixjr~= zv_l;hJNV)^*mN2kHTr$pANZTJVep8(=l|U8cC<2it(B`5a8zZRxfPPV`mVRhlI`P~ z{(VxZX-KG`rB1zb>JxjSsy7kyd%1Tr8(o78|5JR7MedU&l7R6TMUjqPrAiRkD;mXI z8E^n&FdtWqq9MwSa*STLJxe19CX!fpbfz<&HCsbsFnXOgx-0M`FsqZg@lNvUW!)WHh~gRlrDk4Ci0R8F0V5WgRziFU5sIENh5)8i_ly! zQqKg*2bq@&0=>U=;nmU6vuW4SGXwML8vLJ( zns-xNi5WTHy3XOgk7Je;e~vpwhTFh;l~vckDo^y!wsombhoNI5m~Ypi-Nx6*trwuD z>^lCIx#yn6%WvYnnek`OcReJ_#Az~vVAu0|IlpPhdB2}o(EjP;+>RJ_Oj(+yr9*j^ z`AfA$6a_@UG9O)EpX_v}dyB55j);!vv%LiZfwAL}OST4Kvn@qUUDz28Ub;9S*Zl`$ zSX`f>pemMCx&^JR3yK6?j@~h)bb9-iBOsnlx*I^C2Vs)IlpysD`@i?AgVd!xG%A#FvR*P?cj~0eZz{7tQ0D!mZ#mb^ek=PrxA;F&>tg&E~}Vgj5|{N(OB_E zw=PhAOadwre2ZK>@K29JOdVi^2I#C zjxb!MQCvC{#X~@!0|PTY6#PVsB!_h^urbn91fH&A#;uLsqA~#7MLm3el?J%eAh%A)Y2oIDGO~Ivm5GS{eed zZdjmIYMiL(SYhxS`<2wNX=#qa02>-C;x*7Bw40#OM7;dvEbjWF1Z#ikdB>+|T{Bnn z&!z2z{>!L4m`P^M<9=`mF7n#krT(cq7v&953t92{@?3ZR5pbmze(Y5QWV8Q>)uRsP z<0(Q8VU(h|QV-Tl|AI4aFT)+Ek>HzNN&%>nlR{aEF#PX_>7}d&ibhIBTRAIT^%EBY zeK^&aIirTch@mED;h(k2j{rw?u#k2M{zE0M(N_6Rv37!w4NguG3cL1lx`p^SQ`wbejji7r?Td^E;fyPa!g?uRCF}7Pkx_gvy{#biUKR6;K_C`Ei zVc@a$)dB3u2_Vns8Z!-X#1DIx_SR3#(D(iN1~Vfr?`1VW!r#6*?)Fk71=m09zPh6w z2WPl9bpPBgoBFgz&!>DIE8LXX`0u=5WQYPP3!?% zhj(m_NEae?kbRI9{1!YZwjE#FgF*(Zfzf zR*6R7@%Mn|F_*BHD`{k{`xPsRV2PBn1f*C|pVn^+Rmr@N2$F}1=BQgn34L!|3g_K} zqsg8G(nD}K>?ghgH^F|G#7LS@_ymXKVUV+?1#R6js<5*JUVA;f)inLrLSz-xmIuuv z(i8}in5?*W@(~+c{QH7FYLFRhgyR>EtaUyP$6CNR%MWwFIWkgxL?|Q)bZ|>9*qJ7hd0OoH9Suz6f6%dz($nKe^Kar`|FiO&Y0p?1q|6yuRqg91~D3lLW zrZ3hc2`K?*0RbS(5y_o)!hGI759E(nC{$mOZ26WvQ1y7M2)mFL*kY+%+=Q?3d&5e! ziegx-io$a_t%z9bh+3iEe}c4uleUB9YpM|by(5e$|1qzJijF7u$$`v$x2S-_1e&fB z;zj>FG4{LUR)=r&9|FR)K6z$%y;sZl1|ZK<4qPo3^QqP=IMu5ZTy0*suZPb{%L6r7*&8-RoN8B|b2#p- z5BPR;?pMm&Y$@jkqD{M4;`SB;UcE>2G+-3)jM_&@_I|`FL=K}{6pfe4NbIszWuP_b zNUlu$i50=l!{#7~-%ZuvwJ91#?INsYF&z#UI}FDr;^+rTFUK_>A7dD2uN?$wKt^;o z{-o_oGZaf8Ed@e59tSpMd9s)IFYKw%g|vVaedfFz(j|COFfw*mk^yQ}>zDz>^#n~T z3Ko7}UcdU`cRK|8{hR%W z%AW)LcGPhjgj3uMCxuii;a*&x17y2^AIG9*iAI=dE$k2%7f1Pcn^uXA%O`FRP*n$F z;STE(4&$r=`J>sz%;6Od!>t8ADESXJ6GLRUBHOoe(7ywjFyS3rfQt5ER!u;{R*3!- zjFo*c>urR!Jni-`arEB)l^{^!uNO`ObGSe-WKrCXZTUj{d&O!%B`5U5%WD2lLK^8u>@!yXVfc=Hl{JFhE+`t}ySZom>70<*5iBpwrS9 zXw=vg;q+9(+En7Vsifai$q3UaxYMb$3fJ~X4r8^kP7~L!Vp)6Q+1?`z>CyjQ*4}5%*RzK`8(4rt=J^3)VinG&LhsSHzZ}05YCAlDJb0L)!REZ+t)V>zr=Lf zMCh&_l|dQn)YW?|*^oF5G!$>ZFoY;C)wsL2>NdeiT)=5OMNZ_kH*9fem;>nC0m9i4 zRE}``P4Fu;kl`W(DtEvEU=IFmiBu|L9A91#DaR&5DJM;spe0*)&iZjFQm`mvad z-+!L`Htj@u;hXk?#TEjH6`?-`uoSzn_)>R4i{S4FG>#^Ia|AGT!49p2$X+C!KGDzL$j>#EPi2xE(a3K{by?Jum%=5Cv@3#pjg_{cjCfrQTW*8L>>9+B z8JWUD;87QSNnd_ujnqX#MDAU79|DtRG$E5fY%b!(iu!OQ0hG?Xxb-<)V~tFdwL7u! z8u~yjdss_-AfXXNzYC`05CBL<7xsr?%3J2hP&1$`@LdH6^F-lho5pR!^e(fXsRENKxI{=7E-6>*WwmO z0*muNT8I#?aS?>0!(MCQ#aDsCn02(2RGcoT{*vq6;XrLVhzcn@Lsg`EGPpEGjQ|B+ z%&|qRYe}sORv-aFHAUL#9x2f@)Ym0a3mYk9t~uC}({TvK;z(p7hHTHtIbeo~tirv} zK=kE9Q6wUO=4x6xT797;=GC&+S`f$IkSB)(VT)W7%Sj)BNkdC)-`_wTGAuZx{3%6kHn=j&Fa# z+bN=N1Jv=m7z6ALGEAm`W24m|7*0``XR_J-;9My`zp zoMXcDnceLXhkwMz!cQev*Qj)XTM0WTO5kO?zzXtkS@~ zhXkxaNl}$u__n9!--{{|i%>EI2BPI6(jv$m77KWDTM-V4QOZeHwXj;Y{BcCx;T#a9 z(UtjDQy#X&L0H00Xr@slA_YS)=N`c$zl_SdYr}{jDSm{jYk}7gL7@X-5P>!wKjt`!<%;Co{tX(6eA%&zs8G|(P=k*~uG zj%)RZ(-Tji{siD4G%1FS_{$A6)?egmi-7jLACVoQDGtxFWlkH6CWHhidB4tzaFts# z>H22aWhuJuwQ7eoQJfW7WuQ%VB!jyp8~Un^__`eAn+@ga8zHYLvX@f7{BCVRbphHAK__FPaX$(VFU z7(cwlwLKrlI>7Z!!4xV(nPVzIrJ-Ki?2xN%4<}kP+2Bb&&Qn|7JP6=v=fDJD7eweT zH7ZmSqt*?tV~es3UAJ4f+=^ZQGR<3=j?@)Esq$yOVz#xNA-Sm}jJDWDa zsC5B2t@$S{VWpP9z$G^$)rr+Q6+VH59o<`i-7WAV7MCZSYBIp(Pz#a2_DTS2M*>!5 z2+&$0ehWbrT0w1jW0p0rhpVY3-d%|Me*mCBU%$0EZQDK(2Oo?|AR|IR(+NLK#2AJ*lwG2jh9@wh zt~wjPpad(JgX!i2F7RyswhoI|Ab~-sg+vcmyUC0Z6xTSgbg-Mh72Q_ncpQ3~1Qrv*?_Xr5jG-b(8aTlLhu(_pQz` zu+C|8VMq2~PxfF}_GV}HXBYM`lJ*Ir_G!2FYRC3#kM-cv_H6g|ZU=X0clKo`_i=A_ z@G9E_Tnl?M0Ci#*#`JDFYl~9gz zSb3r@3s;z)t^k=*=!%#o(Lo>vZ5RbU{M_nu1T7!~??ysi@BlB!Z8FH#<+BT-_~Iwf z0`7ErEg*s|-~`GP0xP%#RrrG-P@Uv;`l(kPT2TA7XZyBi`%EbG zI#BGnztL!L0sshsu7(RO0E6oe1f(ybUe;YzNZz=ZgQl^Ar$0V5w*s!Yy~npbzAK$k znEd!Xbp8#527#M3etP{vg*AQxD@cP&fQu&pgHDZ_#1GN5agnIcngHYb8(2fCQ9SDI zU%>B~4P(>);^TYOgZ$qIe#-h)I3P#L9R^kiMz}!wFkovd(gG$`1~<@x6x9SlZGz`t zzSHC1Nx1$lQ2OA%y<5-^Cpc4Ch5T2T0u&$vC83=Uxc;vP8yQbtJ(6+YcKX$#o!-=f zIY=U;2M9W0Pz@WVY|@A(TC}{`epfSTqe%&k`u3z5+Rrir3n zfu2}llqt|cI)e(*tZDP6%}NXyIB643maJsAa2iA-LQ5Aqo?2Bwu~17GS2bHXda|&H zmylM$P!ZLNqLwOLYJF-lXlOEC4W!a+WoO|NMH)*!8Kmqj(wRi}+PvlWuU}lPRJFpD z>>A?##MiW`GKM%CVsE2dsZs?jSuatzT-~~s4A-sCsG#AZwb|I_Yu3DpN(`+RENiZB z;licrmNnADNTa&O`vBUenldSdF=txxaH{d;!r z;lX1kAN@Rf@zNm|*N&XMa_;Sq!>>>OzJ2@e@$=8$|2}}q`R8AJ@TFH?dLOW6X=mKr`cvvLUxl zHsI*E<2dD%V~#oJ2stE?MH+b|l1VDLB$G`#`Q!mb=BUn;LKb8VmRJsxNha6Ka|VghBxIlmj1r!jg z0YnsFK&%BI0006y5V3-&A$TxC5jvEhX$P$ei>am`P^ts47z`V22rIODEwbjwB`e~-EmT7T z2?pRwgb5jQyF$GC0xK#8AvD}7xgprB@4zl-8iKRFij1wM_+A=x*>AT`o2uzczP!GzO*~>odV68?3_#NxQm&z1RNQ z^RP)AE3LKBW<7SxE;#PO6J!Wd2qC2~!ieRVUtWmjn8QiP=a&;g`Q@d+$q1aLgN}OU zsH2{V=d71r`Rbyxo;vM}aL&2rnOpvQ=fDdeeCfLr-+SrFd+xjEurrVR@ytuF{O^P~ zPkr;zXa9Wl*As8L_tQfU{P^EvUw-hFClCJj)@%Ph_t=Y1{`}^bUqAl;>+3(h`|%II zz5MzY!0@e4fa!A{oC@IvFg(sxu5ujXA}GNLQm}#+ydVZMsKE_#u!A1_AP7S!!Vz|` zSU}T)8wgPg8bJd~;Q>dEc+{gG0VzmNx*-m8sKXs9DM~|92M~*7j)JHrOAs0bEru}) zT%?IiPIO{3vZR_8=7xncS_U-!^rxEqWfWR?!V_9`fH9J>jAbms0nnJnHIh+{W_%+Y zBu))l8}MSq$Uw5NJ6?1l4lg98A;j6Py(`(mW1Rh6&cI_F%lsOX=5cS1zD_8 z^6`{qJR~niiAi4`a+ZmVB>7*%23yM>lvh$=o-Kjr&YSA%5G@y|p>QN6+RHY{Mrs-sAJ7@YU zgHqI>LbaAool4S?a`jhTh3HnnYEg+wm8>@vYgoCORl7&<3Hr;yX4061ou)Q>iC9jil9h%{tYfDcN60d^nWnTXWi6}O&2qN0 zp4BX5S82%4lD4#_JuPZetJ*?JvIt;wgDO~_(?IA&Nw9`d%gzWwbvd^jZH zsDrrb7~(LBNG2s_f)-z~?*RCL=tNrd9O90;SlDE9(JuiCG ztKRjpx4rIt?`Opu$C8b)WFMd}8Rc7F{f_Yi2M{lRNlRb+rWU{$2rq)a3*ZABxW4~| zFNFOV0?kf%!uh4}7%jY63@|@v$(}Beld(4`O!2! zp%5~v(QIwYBOle!hQR$Xkb^uV;Rna-64G>PM!X%w&d#AN<7s6#F4QIop8 zPjJI-aC{sX-Zr;929l6tEoyeYZC2rz-=b67!XK{e9oo|D0{pp)rGuR)z z-hyws?433Hn<-sJLT8)7YSu5?yS?XsbDiHpzdPRZu6Hqm0T9NZk&S5kaUIQ2%#;;^3=7W<#T@gQ9NPB*S|mh z^RNH?^S}T8|33f*;HW);Q~;iAtiv^UU#o$i`Zb^fJ|F}}paf1J1y*1Ko}UCl2o<&8 z%rP1K$=@v$LJ@?R0G6N$o*)XQpbD-a3$~yOmRgM^!;QHRd#uB4;Z|-Ho(1k85B8uB z`XB~IU^cXfgcP9>9w8F?MJ+7W}y~tAs2R`7k**$ z=|C5_$o2(Zj?^9wGT;xcAseuK*p5KAsyBsmBC1{8CxyT0u=Hb82%w32BIJi zA|V!{As*spfk8pcplk>p8s?x5x}hXaA|;000YD-qVq!UDA}4mDC+6S{vRZLekqkzN z@*yHBrlKmYA}h9{E50Je6#-3@;bYVm8m8eV=Atg{A}{u$Fa9DV9)JuMpA7y5 zBReuWX>jS)~0PXW@T&w zU+(5^{-rAHAuSw$R6rhd;f7|e z-llhcCwMX@Wvoz)lqVkk-7r+f9v*-y41=#-!!1C=aeg9a{$%kf;d5H2e(ooK_NRaT zXN#>SU%F;s4klrSCxRyEZ3-qh*uy?J=!5P ztY>@99EW!QC?_T-IJjkQfadY#CyP!gl~$>hUa3*8W+`yVU%sX)*ajcUW{r+1nU157 zw!<}412O~yn+C%(c!QAI!E*h7w1gELHOFd&07Aj6x!gPdjpog%4x;%T1tB#!(fl+waA5-O^us;aIk ztMZ?ga_NgMs)05ttsvxXhJhX#1%tA0Y zLp7lPgEu%sF#LioJm{8S=#dg@C&mG`h>O6s%D_61wuBT}Wy-gN00M-o!#*s;My$ks znW1iJUzV$)&Z@d@ENzZsJDfu=u&Fb612lNUGyK9YH0;FgEYJ3=&;IObjVr8r>7u&AW^gRhKIS;8gS-Ahy!xm&R0GN)gE*)I%Vwyj z{;LLA6|~%Jri1_ilpfHIE!mc>*`{j64()4#sbGp}(!MQXj^jC$gEzD(GN3Hp+5$UR zXmhn}okH22V&cqhkW6_k!=5eTCa&TxE|wZ9Yx*V85~hs8E#(@f+?K;N^upcZ?bIg! z0}x%U%K|RULL$Htu1MW%$4~&{t}g4guIol;+9K*}QU;h-uI(14+?vBW=qSoILg%i7 zIqX{BVy(Y&;^1!W>6%Klbd1ivuJb-G^hPg5#xCRrX3^g6?T%x}fdjqzXf^Z#I;_JC zf$rZvS>Tc`2NmwAEN}Blulv3){Kjt~3a#u$;b2ZK_QI_yxB?{Vh&TvIIqaAc@oV`; z*ZJn)@zQMaDsQ#4ulznR1V^w0n_vl854lF}6XtK_Rz@=LByN4M?Tv#qWH9l*tk#;Y z%_{HLhV2BmunWI13_ssqVov?SC?Ddl1|w}0x+V|va1?4}35#wgCNKu6uL>XkZVV@} z5-%|m2i>b)Y~*&Q+vYIGTCWvLA#4_A5S#Dl=3wa}ZwfPT2&irom$4b2F&dK@{dVbV z-Y*qX?h-mCaB6Yra`6zS?*eDa*E(<-_pu-UF(9W`#kxfG7N}qz?HeaDVs5bkcX4ig zu>yxNvt$Y%2eKt!GA3toIF4g!aO5Id5eJ5{D33BJ&m1Ecrz4L85nqrIgGT$=g@GK{@GA}a>*YYj92#)#WE&eh! zSMzb6@)I3!ZmqHfwX!i+GBby>IFEDdI&(VGB5@2}2wO8dw{s_AvlD6m^Eg0q5$EyO zjxjmsvp(;$*_!hwb01`|+Ag~@K^OEmz%!Z1GdEXID=#k+^D{(8v_yZaKl@28+u}eQ zv_@AmLT8CQ(=#jEGy6_7Ntd)q1L|H5t^FD%6DFZc1ICyvDTKT zmMAnHOY+yg@<|UhQ5Us;uE74DBU)@<#}S7#KQ&ZGwKRjnZlono;t32nqEv4+S9i5n ze>GHl#x-mrPg}!B|8y}sG%_1CTer1akERQtMKlxMIWTRU3h9JOs9x_iU-vat=jkw* z!(KyZUl+DvA2wnqwqolj&w{%xGbzir2XE%0lw{~|ocYn8chc|eSw|JK~d7rm= zr#E`9w|ciXd%w4P$2WY>w|v((ec!iz=Qn=uw|@6GfB(0C2RMKaxPTWpfgiYmC-|u7 zKsw3@mgsUh)HP^}_FY%Fgs zKAkFN$GD8ocq=maP;B305Z-4`c!`U6JGcTaW&+u(m0h@xs`XJW<&FX*A_UCLn|1V2BU|h>JKUhsXvey&&pNG#wmEEg zhu6BU*Sb7}0~vr3ux|k@?1O0Uy0IVovD-tXr+Aa!v1F$T`*J#{Pdl|&d+1>RATWY( zaJEyY`l`43s*6KAz&f(mI->_UEs%S;%Q`!J!G2JA|Nk)^g&L zGqgxIu(Vsdzz;mZV;oYm#VgnWOAJB+s`>?V`Kq&nI>^H`*nvHaJH}_j@ooG$f&<2n zdpY2`ny356m%PcFJUg%hj$DH`ECL9i0ywOLG6(`0bip7{L%YAiuTw!Jtb;bBf)-eT zBEZ7MpS;nV{5<6Qk~90IJ3BGAIGz{0)K5LtSDXvn@+%O56%>LUjKCmdgTs6K1&9MX zNP`Y+fjNBqJdDFAKx-Tnf-0Ot$)7``yBat=>e1&t#;1JFKY<}ogUs6j6)-|o41ze^ zMN8O;HcUbcyn!Hq!4~X--0OYbE4`fGc0B|Cb+lJK=Xbv6e;NW5!5t{WA7p@>;KCzh z05F8Tt6xAnsJiMiZOLClCUk+dWx)A@M8Ox71Fr3Vab*HPXvvgKT|tBD%DDnJj^Vg$v<^m;II&MBq;%6mohY1*0uZg3B;*(>Xg~xLXBe0gYBRVV|YN-Fl#@71_gQxT0^7b z;^(<~@nQK_?p*eN7fd_YOP8&;D<;<1q2tv`OO`}9* zi^)aYIc=$K>?(K88=9Hhg@BLdz8(u(wWF3pZpzb#q!z*tbo_tDA zsP))GD!wbBlBzzduEOuZFTo5`%rVI<)66r`OjFG@*=*CzHy2x>mRoS4q=PV2$*hHA zL~8&R({v;!mIV5chczZ`!%eq_z;UHSM1fn!Bqc<-Wf)7Fd8LRgD#ZmBd4N>MB0hu= zr4>7@h@>4zg>w>0DW@!|O82m=RfqYuyeca%;q2AdUx5u)*kOq+*4Sf_O;%X|BfMq8 zKy+APge_nxO&TIvAV-=NS`eqWB7QSR+;Pb*cicu7YA73AkTcg^chixEf&pAmVTBW# z2<;UxR?s2Ua)2xcoNG@1b)kqg~)$?E-N>=ugvK32QbG?tNWjXHH%yPF4^Rh*^F?`VQ^8!WzMq62AW%p$>y3{d|AjEoyzIi=bwT8S<&4d3fkzS1-1qk zXKPtGn}L&Yc9?9+xh5H4k{f3otDUVmIi$hv*_?-?jMy3~*`w9s_%N<7s}*=fS?;;% zuG{Xr@y=WCz4_*^SxbjW2E(7O$!49Wd-M^Ub;c>D%EygDw?$Rdf!y-l9B-VVbQy2l zai1|?=WEa}x4ay(%~o&Xqbgn-zP9b#b>qHiuif_BanD`%-Ffd_K$QXKtg~whHym*v zOTT<*b!o{w`RASgPyX}gOFvzwCm}W)?W5Fo{VCXEkK6b0$uHmh^U+UV{q=*jY~{cQ zCqCxm6Gxu<$XR4aU{%h!-~ays$R5T8O|_q41q>69QP^$uFfdk zLm*SYrz@>E5Q9ZD;t`RUL?tefiC=Ob-~`thYg}V%Bdj3+!4WtWYB7La^y1~NaiJV$ zFJc93$N_&SA1!5Uh)s0k8{rs7InI%eb^J;Q7?BA*K4%mzbD1ktL5o1rf{=u4+945{ zNJZ9ygXuE=N;WuX$VE<)l9jaNB{69!XrxPr+T&q+(wIQ{xUGS9H03E#nMzfzl9eD^ zfy)R9IQR{2ii9Ix;c#g)UFMRPx4 zf#PfBHL;mZZElmB-DC{#I2grSGP8c0i{2OYr@85^Q=RQ(=R4gQPk7E#p6xV>Ght;$ zhWK!rYjm5&yctk|4wRq;HRv|MISk=Vv3Mc8B03>QPl?uZq7|iRJ&%GTKSnFvn^QJKz^rtHyZdN|6@G*VM`D)s44ff`hy4i#7l zU8wy3j7P$nE|sZYyeWD(D$SjOG<-xP>Q%9tRjqE7t8t>m`&wGOq?WU(Wi@N^o*Jvi z>GX%-V<6nD+EuyEm9BNQYh8^RzlM(RtbO%sM#-2@Xm-@2O5tf6@0wV}E|#&44Jb?X z8Z(DJ^skjIYg&Vn)55AzfovS9V?i5Q(TPqB zBen5OLB6Yw@Q&9Yz?U;u>?6Hr1_=Ca~w(x~9oM8=bn8O|R@P|RH;cL_)zp8uO zauMiOT>;p@Eq3vXVH{(}Ab6J6VCFi8(F#~VIKmSK@jkxcDSP}Q#6>o;k>~LZRfvKb zL_V@V{_&6!pKY*gO>uKY8dn)_naf@F@|W8}nA<*4%aR{pJ~mcg88MK7As1l9p1vVwuElpq8kkVP2~ z@C6=A*d0?q02bZ>XG;j62m9y-zd|sACd^?Mcz!ZEKJnHN>>v>u)(0;*(C0V*KRL?y zMJ`UOOlTDYw9&;j_OX%8SQk730RafW0h}Fx1XSV=0#JiE)VvQpr{NSGPKPB1P-<>a zAOICW00KDB5?34f87ZKn*%V0l1(z z(rp)_4gm%rD@K3|l7SK`KnY}_75+d0%s@scK-cW7*90xt_)EqA1P=OGumxT41#3sl zSONW>MjQSh)8+vi5MTm!0pbQg4eY@b4xk6#LED&({l4w+#!Ub^VDbWBL-tPqB+c9` z;1sx_0;=#I_F?`AUW2BGztPdRc?%J?{`g*Vo`c4RmkRSBn2>IdL z*024@&Gn`Q7T7^v6o3lq01)DU5q4qRTH+sYFB}}90tNsCBB2|iU<4rH9lpU56rcwh z&^ftlW69_k_fW&#}0p%~a< z|11FP_<?^{62n(7*x7!QNVe3`;=~ zsKFn;VI+59AJCx{7y%aajl%eFhyJh{0}gJ&@g{LHCv|c_60!Pfu-d*L2O-f1fshj2 z(I55^0Xm=vC}92e!TrL{ANGM9+zkUpKw8Wo<<`(203;{?4Q~w=SD*wCKm&H6 z7k`lgf|2%SV%OrO0w}Kn*pd|BZ|Y=$7uXUK^lS?MM8FR~r3@ax;`A*Vi%+oj3lPyR zc0zyvj-Up1GBPD|GAWZV;*J~}u^rNp2OH7v+L0gj0aVby+%SLy%-|^#Z}I*t$v%My zD9|)7j{*kr9WJj5=EVzBQbwkL06bs|NTCir0t?_T7)?PVoh%byVKhe(6~qA-Kfwh! zuob322|mRnKp+(CK^YbS1O_20D=a2GX(kKH8WEr}&GS6bGd;shmMo=kM93PTfg0K& z9c-)!)8QJ#!5_A!Br9wm4u_fAAvCW69FFqB)IpcPp&hvLaNH61f(aaK&mQDqV5p|f z<{=%j!5jn>93t#+n)AZu;iU+aA3*a!IaD71o+i{#6hi;O9z;kSUeYl8P_q;>`M4wm zC_p`RbVqsgJjDz{h-bUhfgLtY!sgA$o^jofG{lnB!(KAOz|;7u1jW4Pu*$PXu{2Ay z^bmg(8sw)(d}AIStj8$qNR{+V(G*Q(R3^=?Mi*$swlq%VbWY!{OM?_l)xp8CO)As0 zPyKY=q7*Tw6#3q?OX&1a5j9a6%}(7D9DGAh$@EVpby7oYO~bQIX>u{Kf`J?pG8Oex zK{Zqdj8PNkQO8umC^c18Rm4b48ue>X-PE&0byjJ$Rzr(X5yw>bbX9p(RV`IY(}qxU zB`b2&R*m&okyWc`>=lRr0}uvJ+d&@xuEhhapxY`;T1DU#p0roF^~eG>xx~|>tTb84 zwOq~Bq!5f3Fn|gO0SzXgTE@XQLh%E(U=z?F9>xF_wOjqwNyqLm!4*@-6U*+y z25jJ56?S16wv`g@43 zwrMHsR|Pd#V^#SY^D$MRX0bMFwKjrWATu^&89E{ZiXmRr0Um4s2t)G`GTY*iz|^uZE9WY@Ui z0kk!4Dfhylc3`D8Q*D%iaFlNkAP0PaEF^#jJ^*k{_jFOWV_ZNw3%411_GisO96GiL z_2CaLAncyPR%KyTbJ^$`J-2l8wkwW61t8ONQ@44Y_j%id2s|$XWC0o| z1Pcb#H@xq5?O}Gy)NLo1cPaOBfj4st_HOUPE0*^wSfDFRpa$Rw_<}LmKy-j* zKA{9E00j);8mO`g*`eP5N&o{ufE4y&*K#+371(6Smu?AGTm!LcJryhvwkw!7gL$}z zeb_PXmxJKPJr|4}<^dtfAwZuoG~1y`U)W^lw(KZISpVr7fB1^AIEx>nOQ%RkAyvYh z_=(3iU>i6wg?CtSREyPkjoBD5xR{)DHB!Y`fundD>z27R^}pJ9kNLQd;ev}BHI7kr zj>R{IrI>rDSoyBhj~Tg<9oZ{%U=#Le6#593R%;j@Y>)|=ckB37r}%-n#3mnklu4P5 zbs!TqsK#6>8)_kw&2*EU){yOZhFR7|g~&0zq8_r~0B*RHefgK6_mpoz!4~3CTUm}_ znQ}YX#De#HHy2L-6BY})VGnv4n63Gm|JDUEVVHq*K%w=RH947MnT*-gd};V@iS+;y z)(q-F3XTAq;W?hOR-3umO9MGi!TFWN8HyRWoLMK4H+5Ik`2eJO59Ilv5qe?iS)9B% zaoZuE_c?B5*^?0&lmogv*IAbndZRhoSQomRa}}RmIillsnf-7V{dJ<5*_>;6cyaj%*m;*@dZ>vyOK18^9U7u>`eaRd&@38n33{4~ zda9`!J&(Gfjd`S(`d@YWq3a9DK)U6sT|fo24EYuE&Iyym{Z^RvvE7O z2@a4KY&(p2S5=!=C7V6Wfe>Q*xMh2`YlS>@ySbga(MT0qPgS3T`%hVWvXMKxW4p3p zfNcU!te-o)#aqU3Rl0$@x>I$ykHWRJySYYFnVkyT0w)(Gski`Fgt1+gHi? zQjfwMUfaD1e7h?X zOdwkShEmy0m{{Y$o9b8}!NGL= zuX{Yef4s~K{LIlj($$;*2AZASInFUX(+dj0a3K|lpaMqV4y*wju0<{#@ad8g0Tdt+ zF7X2JJPHB;0YIbEJk}mKvIKgw)mFlTNx;i9T)jKoxE&qD(;Us!+yn@~Q|(&QnZ4Qn zwF$vK;Z8<@5*`2%vOyOT;1XORf9Y%=&0rbgQyv`m%5C5dnxPrQq0@j+M3mqbq_bPF z;Qpt zcT+AafB^Qy;fp~W*dZ3UuO80U$r|@|v0TgT?hDxA?{K~XvXvtr;0qJot?#`d1bpS) zo8O1r-~WBA1D@u=KJ1T3a4UdQzKUk9od?T79)O-2j(*B79?BCT)V6#I)LVt?Xkc>e0ze&aRG z9xQP*_<{5Ne#<$&9e6Lgf=b(qWtNCmrC+TJm|n_swSo z@Yh-Mh!KDx?LnUHx$hDi;1XKFF30^I9-#p`q4|^EALfraaA6ZjVIGv>65JgPx@GE@ z8s+te_G`c8xgMA6TB?1&{oP-8mi5z77#6@m7vgb9V?kq04Gl0L-T*?Mr5^A0bwh(e zL?U-p)cD&M&Q1voBoeKYMx;UqC9wYa`v@|m$dM#Vnmmaz<-csS4yYRcW-X@7nKExd z8;3LJICE=c`1}bpsL-J@O!zd4)Pzz3M-Ch?bAXT2sZ^_4y^1xf)~#H-di@GEtk|(+ z%bGolHm%yVY}>kh3pcLZxpeE=y^A-m-o1SL`uz(yu;9Uj3mZO+Sg(#-!-heFb`4xM za68qtv$rqvK7O1t`{Vra9lwwsKb9{2abL>StXsQgeXW*Dm^5o!v#B$uIYLBx`wp74 z=+dS&5*t5`Jh}4a%$qxZ4n4Z`>C~%Rzm7e-_U+gg4@>sgT4ZqG%vqji53}mm?AyD4 z?|Nm+m$qx;&W*F@@BP4!78O1mcLEMbV1Wi6h+u*WF34bm4n7F~VT2L}<{fy@h&Nez z=cVTvd>(!XB73pTRv%6GAlN-oKyX)KXgVof*U#}kWIBIRO$KyJxpmtKAeW|(4*NoJX5J}Bgc<7s## zhwC*7XPhF+MqiXMov71pR$iHg~<$K%$nddnvFP-Qi^M?Bi4!Olqhb> zDN$G^6)LO79*bbTJE^6-Mwuy2RR+6X za4`#_-h`qQTX6$gl9ETb9Eh{iPkV#QUESyMSIlb%~SQF=Aw+HI~kj&h{1 zihR7{3kk?Y&D??$Uz`}R8mPuZDsqvGY~y_>m1+xMB=z$SPMoc?CjrA{oR;#xkJMm|N)Jt)wljX;16O z#eCueVaNm;ED(xpl*2so;Kc{-fQv==?IE$qfH5BP)WlLss^4_jJU-Kz4h^FcSk>xf z`M3r~xZ)O!5iM%3i{0#M_klY9P(~RtKn!SfV+wlH&^?-Ft8hdC3lA~H1w>U zc*F_JI-|N7swNqg*u)sLdIgrsK!pQd!x&WIiWO{k!3=J&gW=|aR!o5l##qJ$Cu5Ft z)FTRCz>Gc`ae;lv!xR~~MKh>j57fjLPQ)##!^WWrSrk(o_q|$vGn0*5RDuuy?&J$p z_~QY~-~}?cLJ1y>jL58A+qO4v;tu`?jxXy=*bVwI0VCNhzIGJpfvfXRd|w4o18Di^$> z1YR&kGpJmQ%D|%pYEYd2K3pb_e`q=#(kMX>?1APuwV1vyZnK+DJq9?-Vlp(|O!or0 z4||~J7Ot4+531gbPg9B=?c6rY64K8PU+e{kunjK~iQ;&P&ZZ5ao&Kc`d zvO^u?cxadCN!9WgaISua=2 ze)5#ByjP<2m_|tk9P41m)Gl+dhX9^ZP?wSv!+rSFlUos$7zQzx@p_vM!@7~TyzOs~ z`?6Q)vzq^?Ha&yb(Jx8xQD?L2kALgrdzBE=rLJ{z5B=y%f7l+yWu$^Hd~Pqcm*6Zs z@;T0fQ-@!L$sfZTIHBO_tAG9Mcd!m>LEZ0!#~MV+P%g7CDdL+RKU4p{>cf9)Kn8Cw zKmhG$fCq^GfNrG&o3II^Fbb*wfwUlj@W&YF5mNZ~blWFTI#CX&=YLfPfIP4PDl~%d zCIJJWRtczrE69S@qyw1%fAXg$M6wRqPz(2mfhUmhsjrhxHg7?CWx1aiJ5pggcyZxXc>rzg^Ji7ba+RE2Z>ZSen0SI8_u`sV7=+_jf@4U4V>gS(h>XeTF16T3xAcZrn2Uk8 zgWSh|ir@oRaEjt4jJOtWCy0c~2#(<>j*0e!op^}Q7>$c)I41qa)Zn9=N>L61@Vhv?=Rz%R2j|rKP867&H3JwT?sz3`A$QZ-03`}X4?D3Rr z<^!WSn)28Nm2jGsfC=X%3PxR%Ufpqa~TSshhh=7#=ka=Wq_c7mA;G z5_l<^r0D}WfSk)&nyH4Gl>nW-;0v-Kov-JWoYfe!hnu{~o!#l3bCD+WmreadoTIpq zyqFWegapjVo}{Uq?b)1dAfI!<35p<===YuZsh|5<7UAiM!dadyxr@b>8yN@xp9cz` zKd_P7cxx|Ug!~Di5h|fnQGNVWmjSvOp-FfM%Aw1tpbCluZZ?7=ibxY`q9>Z0;YlRE zN1hn!8pcU@>)D|Q`U5ktpnJHFJTPx4%A-BnmfnF24(JNT@F?jpRGC=|wEzt7;1B7L z4Dh$4A0ZDybqhq5ZSs%|@kb4+u@6p4UB$qp{xA>dFbq~IJMpEVRMG}B+Mx>S0~@fQ zBRYl!a0K7zqj!p@veS zGXjRH1iP>g?%)V@_XJ#!ZH(%uPjGkdU=P|b36I*TTe@N}YKLsvrg7^3W)gq{BG__y zYOA-Zr?>D4ED#2&KnV#D3H#Iz>(Er%@ChH}5A|RJUH}ZrfCevJDfCZL2z<>{y^{Dz6DTntK?hBFFE)We-5M@*L z2pNE38zMi?^AX+pt;%2rTu>13zyfR_3d1mQ{vZ$9&s z2+~3ZiLhes%7HHXvhDey__zT=ID$K>vvW(gE4TuS)@VSBaFWEWQqXjxArHFn093$l zr0@?AK?i!*1l%$jB&;r2~U#$AB@w&Di zdZT+NjILO>t?Rn%rvpz$VUP9*5Rh>E6u4H?J%qXixF87L`VLIG5A&c6Jx2;=#t%;V z3M#O!@-Pi{@Tf%avGNcNWWWZk5C~6z2dA3Sq9kXsYb3AgYHA>aqufD5-Ux%N;GHK1jw z(KoOl4(Y%Peq#?sv{x!%w&@TV+2E`#P`~m}Kc6rJh_DaI(*g;n4T~_Y`SVZSixcWe z!N}RR;x>Y+xB;vS!d>je_7*ZkU6@BpL`rUvl@RFDZd7rOfJ3U9y& zf`A5>x)0Ov282Kelb}Rh+6sl>2u;ujpDHq8Pzu?*t`Ho-D@$r>TE)vbz6yH5s!OXK z{KcEh$%LkMcF+WAfC||_4zI8U#c(9iaH;tv56a;G2wLCQDHO4 zdF2qC>Oo1Gh8pYP8BnZgTqHx40usaNL=v2y@H)vpFavFS$s@{&*R0L^%+IE!q8UPk zE$X5fdY%NDC(t~}ABv+JfCD$M0XLw}{VdTF-BbQ~O96eM16`bud~vNh&-H50IDi8T z?a(b}12;?2DXr4;RG}c{&Km8^RQ%DE45uQ!0Yc!=FA&iy&C@+SP5;cI8LiPJ0ng@w z(5EZSI4}bvEd(Qd0}Z{?J}uQ#-AEQ4)G9gu)FKhnN4>W7ywpoA(qZk;8(`8@ZPsVK zNZ!#4nUD#WK%^f<4!!VzmkA4viwn5m3b1fo{-6)IaG9b|5KijXw}7b+VWfDyq^dCw z-=hk*0H$bG)X!|X6ui_xfCHAz)DNA{nvB++?b$rEr-s_8L{b^|UtwSPA2_xVIm@5K^K(OXOtQS(eAV3QC01q}G2EgDAL|4D{kOhcBtIpa#3&1D$6Z1^ z7^A0aqcfo3&u!U400hyk*)PDs5^m&2{yRKd0pF^(L)#|$KnX?n5J-Cq$^ZstkRDEZ z2A6;e;K0AFTnbpb3nII%D-H=F+Xp7>c2F!*k!=p0@SZQr;|cEL%^l=T-QZ-6Pmly;W)I52u+qqJI}1=4#8)N2Kb&Udu?R;@ChJ*2n&n`OS}%=Fhoo;j(fFY~)t2!aPtSA?`al2$3I6pU58Yy~*|nObKvb?&35BH)l`vs$5Q0OsPR0#f~Lg*6dldY1OV}+t%${xN+sqRjcFHuw>AnUAvYI z+_-Y;+Rd|PZ{NOzh#M|u+}QDB$Jc5}q=?b7HH{uUf)puo;4w{XShi$|Bj)LuH*en9 zFo5oB*s*2Lrd`|iZQQwa@8;dx_iy0Ag%2lA+%8_d*0N<=2hN;e!i5z>re59p^@R^3 zPP}Y6v*wSTJOA^?|F4*$Afwfv-Tw%+>1d6i8M??B)qMU|MGg4GDJ_<2!iNBXR>MF`KosOamXW=d~(Vw*UyD$IN-tbmG$=hAe{H)^Y6_F5?s9Uf)?#G_=sJt zV9TSIetPPwxBhzUfm-2}61?Et^9+gs=bUreDNG(yAdq#Rcs_t+^;HMj2c8cSdFLN; zcJKXn{s-b)c+3#*UIjUxcn(vH!WqpyD-wd2viCp;Mo@wiq+kWhqyuS`U~`@OTrtXF zj`EomcC|n$eDaxbufTb{D_?{VsUIv)4xuQb3^XqcFf&UTU1zI12_*h(jb| z{}GLN#JISi6;o&dF}Q|?7WidUg;Con{;`j;S;0~?@^E#3J}c*awn^OTVehB1s*2*M4FKt(pv|B=33 zcuYFvXaykNpt60itp{);$UKx$h(aiWgek;kyguo-P=7r-b+J4BL=Vq`-c)EEaf<}|i;oWmRq%Em1eafbM?^QCKLYg^s=R=5Ji zO$)MVDNrE}Zyknq1#t%>CTi4*UQ|Oh9EWI90)!yUVF_Mf0~<6U3#tMG7_g9qCOqK@ zO@KnPQw4`OvJq8O$l?~4P^TQ@dRo+`R<*0Opquyt4!;B@uZmI3P&o-$|7;?4ux2br zXuNP(l>nEqjs=A#ENh6y0>LG7V1p-~Dhp9`;u2m!s{>hkUF>F8yW4%5Yy0w-Db5ME z<28t2yHmq*fa4gIO)jC-1BJ#K*SME$?BST(2~=SAtVn2}TDkjQ00&sW1Adfim(!f^ z>Xp0;_J?lIYep#j>>Ok)}-Fjo;y262k@d}&N)TGKC%af4<| zD!lz!j9(UXMg=zz+m^YqUT|Zf3YE@u3gHZAU<92veQR9jTGw#Ra<@P&YNG~vLxb*_ zIKV-TY)}>!nw`TK43(vTF_2*G+;z3BeQj*R(z~8caHxSj#ys_Hw;3IXv5`$xLu-{9 z$38}dJJDD#1R)IlLR32CjfyRa-BCg7P9*Nagc{xLb!quhCX(@=Uwl6&yUi#>}|AL z6e3I7re?~~_LWfG?T>!7iBzOcYV%$4lc#*;V^j8}2OivnPpaV+;dZIR9omXwpmi;O zdeo<0^;jAcE!^kSdBkg zT5n)l;74Ej)0cefe@%Q(4xV1)2G8M@pZI6@YfFk!|IxIme}43*|LekcJ@#v+_JZ^F z^WV=fmQb`fo5;t%>gRv|{eNxiJ304*m)HxS*`vMW3%^4lJ(^&VrTISyj6eyzGxoc_ z0gM;;d%7o4CHhmY(|ERkS)jQyy$LKq6Ffly3&69xz*;Fl^g_HLOFl+J5%&<7V%a|w z%t0O8!MLhG0c62D$w1lbzWI~71YEu?L6l*MBOYu*Cw#(`Qb8^QLOXFm2#dNH95O7i zKM!n=CCmv|f<7o5LozJGBl5u&q(VCpLId2uBh0V_WW4uS5!S##GrU7Q%tHv0LcmkQ z39-T_@xBfm4H_Ihfnl88(?dmEL`IYxG@L>||2z^lM6V*8I?%(CXY;~EVI0O0!$$l> zPz*(d;loI*6F__tEQ~p~qq;3bjdVJx2NXqFoJCq>mPhQvQnZdqgfI>q#L;NQL}|eO zdcImLMq@n2NFl{sOcL!Aw+9PE7zDri`@jWELZs=h$U{bL+(vH9ky~6wNi@E~^N4b& zMA9(A43opTQzw+_Mt6KicpMOA1V;)vMes;P5A47~oQWE&2@;G)fDA~16pnAC#|qg+ zFpq-jTr97&Qa$+RfQi^L9u zBtnJ!MfO;rFSJ9GoJpFj$*Zu)l%$S~|MUoa%*RXoKsj6>IJ$wmvq_^oN~A;zl*~za z5y#Hcj9&b{BjiWb;KVbqwWQ2St<*}KWJ<@_NsbUiOH@7@thau|fi2*KPSAm^Y)iMS z$))tl$5=_vYe`IWwSeK0Nb7{VaDlh{OTd)Ku9VB0X~vbiLRAF4jx3b%6M`_{%X_*7 zwhT*g=T;T(i{d?2my~vP2dbpJ;Y4bWQfh|h;kf687vew0EGp)2HhNnQHTRi6i(~B z&Kz9L;zS6r_AL} z2`@keZhV!`NJy7Y>&iQl**BnRWguypdydY2nU+65dl8iTq0TS3y z0yu)-L{Jb7QQwo#1vQBJ1PpT=L?K{aGHf>XW>(LVJPO+3msSAQj00wc;AyXO#MxcTih=C`CQUY*O zLM>E~v(hU)(d6tv7R?5_|2d>=5QQ|@fj_NL4IR({T~kBdR8G}1I9<^09Ea}&Jw*V9 zc?bzTHHJPlfz$F zhke-8D%S! zg)`9F@tt2{ja|7#R_xVZ1zzAYX>CI(~rUD&V9;WLh7IleqBma)v^ViV2MXY9T&X5$+!;yDgvL57PoPRUR`13$iD z3m#-f|8C^7@L{I(;zTas5ysRKzF$YqWKEumLcYjDp5&R8U08+VO)h0qmI_GDNlBh$ zB1YijJ!M#q<)!FkgZyMxj@w0+WnJE7tEppd8$LYFW6qOdGq)pm>_Gp;4;)u@0P;K2e z|F{HK00)yM=)=I)Y#;_>Py|NcR_lG~m_F(w25EZCRVUs7DxiWixapi0T7&3mJsqcP zxQ2`N6iT(^OGaw2*5R2hMLF%`j(zH=#%Z0d>YhHNd0>YZ&4y+$hFcf~Ldeh!<>;{9 z>jhS7aAfMYRa~@Y1W%Z1+G%UBItLidYSO#~RbT`;C`!JbZ2TSTNR-nce%%`wY)@DQ zbtokt#Gqb7<<^Mk+IdBDHD2LF#Q0UxE$y9CN zPG8IR!?K>>tySF3hH9K1hQHu#Xqc&C`0e1H?&M|dTvSvHqG*`Z^*UoQUvTI# z+w-Qv^iJg1rP(Ghf+mpc0*`Q<#qUVeZw0U9QI>EGZ`uO~!UXr@Y(`)s-f$A{R0{V) z3kUJy_3C9VaTg!g4rjp+SMSCZ@fW}Gd_8eBOmQ0bT(8z^91n66uj3Z}K|G#uFb;7w z6>=u0RUM~79#8TWN8lE3aw})k7{5Ryhhim9;4A-fDSdJvjB+lYavKG5Fi&$3&GG@< zav|>WS5|X54^c5^K{9`HGw0BTo^w7&O*VHwH^*jN_UaMub3<>-I={d>{}*&`1ylq^ z^FxpH%KUTe3-l0%^Fo(&O@~Wg*5ba!<3+#pJpbxVFZIBrbmFu03C46&Z}q=S^Z^X@ zRUdUocXeB*NmPG5RVQFpzja?fN?3P4S?Bdpukv3%c8bh(&D-_)?R8{-_K^&B>>KuG zr}aIDc5K&1We+@NCtqjJc5shJX(v8v_x57H_Ha*kQQUU4>vnY>bQ@Q9dEdryf4y>l z_eTG5bf0&A&qH=+I(Hx5Z|`@455;=dyn7e;b1!&?2gQF!xqyG&fp2(<$HRjUyo8r{ zYp-~Yw|FA=bX<(n7~W&UGiw#E@g?tgl_$fCN4t#Q=Y?N+nQy{}{};H3hk2Cu@|oZH z5^Q;}bTJ9=PC`l-+PIJbJQ zr#`3`IH@1vjsJSHk3OsyHLWLmuFv$dfBUct`)?cjFs4@)-*>pr`?&vjz72U$9eKg! zV^E%Wy)XPK?exA6W?|kwlAqzhFMGp}{Jl&2KU@2{e^sWJe9a#_xd%47Z)3Zsa=hPs z($6=_?=s5=eazSS(r^8c>wHoBe1#7EGar4|zkOUg{TfUC*@6H`xC(+5h9a z4}Rp=H{EA2-q+}OPk!jPw&Cxx;-}<%e{|cAe(j&K8ms1nP7% z=gyu#8@*O*YSpZ!t!@4K^$gn9uF0-tiz3F`xCClE|IV#@H}BrQe*+ILd^qvq#*ZUU zu6#Me$T4TuyqR-n&!3>LW6ypas#L0{O{Z23R_yEYW@FQK3zvjk=I-Cak1u~d{rdLr zCtp+9beLJEoq-1;Sd?g_eV0{u;<09)ggcXwrYs*<=}YnI#ybjN3)UV1rt5C0)D=nWU0S zGWp?(lu374b(+msrIkx9=-rK0J*ZlQJig}Rg|=tcuNrZ@W8 z6`rgPb!`26Ccdos!t|Jn;IkVXY&j%)eB#p zvTP8ODz@Bn(_OdSck9M<*>;}&wA4MTHt*HHjw&qPha;Z2;)^q0^GnY`*|FJu>zsCj z3Xk)1!$FhTxaXgP9=hmW>-{X>l!N@Y+Pex4bk>EB9=q(b(_VYIWSfpU+N0&Vy3cKo z#d*Y~+Frcz$0MISo29F(yUwa#zIN-IzaFge*JGc(_S<)ed-KlcZ25PXYfi85Bn-{H z`s=gbzWa_bPcZl&LqERsR=cjU*7&~PzyJROFn}fTp8V!#F!7y+e89t+%HSq30YWf> z5}Y6fM(~?xIq_kcmpQfpa~Qr6noHz!Y4v8ic-Xz1t-VCT50fwyBdc* zg7S}l?1LYgfmRrWl9_$j12fGS#xQPih9=BrJ#R7G6zgcmJK`~8DzxGiG37!Bt&NMG z`N>aulE!wN100v=0-@p(w>&~Jl9HU{x2kx$K3*z|fZSpiJ3~k`_GBLIP$U!569Wvf zjFPHcB`aGQu*U(2Qn|xq3wigh=y7t8gfyf&z`=+ch_H!tbR{v1Y0P7$$da^-mL{=+ zxlVHClRat2FwS6v2FekA|HMNkH@oT0Z^~znmt5wZ{^-m=LUS|HRL3x=z`*pVXL#V8 zCq3(F&)z7LoS14Rj&kWqLaL(^RJi8DP&v$dA~c~2U1(jzsn1%Ov!A<4r&9>o4pDR= zc&~HhK^f}NkAgI$6v^j9@x)JS`7@gPIEO%k_f89CGkqeRDNSoyQ-_u`PZ34wL_K4V za{Lm68Wo`Ws0tyZFZ3a~;SG(#}SK_p(nX=`` zp2?YZ5aS9$Eeqi|`qj6>HLg-*s#tGTqu$}Nr%t)(K+z(mm~K<9f*mYj*%#Kj&SmJDU`H zj6)HR^;Kl~huYiXHn(8Q>}s{cS#)Aa5mzwJUkfEu-6A)+%59lydpj+%PA#fM8Ra;Z z;R;2hVTerdYi%F7-0y-ny!+y$L*XkS6k&{PjN=xfcmob+`%Y7CRlNG$ zFMpHO-11_lwZJt>J6zG%v0Q->u4o2WZs7^~9`U72v~7PYY~c$-io5{!%x~4}k8yyu zHSK*bI9$;Q>=KbJ=@D9BG3??O!<0f;)#*C%r zaI>WrDlp;_w;;wcM$zR`PPWW?-ZP((!(=pv?5^nDpg;KD~(TBLPwV019Xj{3pmwu@f@BwaG(;69@?a*3u$=6CRSkSSHn8ig!wb4lk#No z;8+wnG@qg;Oae*EI@rPkji-I*sd1m0iRMN)#VgL|eJ@;3{{FPd+BWS_l{?H9A34cmtniEv z<=v|p+`Jnp*^GkU4Dkiwhd+zh_o*d;tQMp&jSL&9p?6^N)I@2#p zbAH>r<1DXG$Wz($t7CnzK^HpF*#_~pzC7z5P$^LY4$Cm!&@ynE+MZ+a6>zSflwc+S^e?bE|P_7VI%zeE4^?p8qdy5D{OQqO7C z|HXvR09QNJHP8FwBma7|Z+F^8p$ced@prc$J$sa%{OeKFkCS3v)qtYiJ< zUB9*Lqd)ziTRykb#t1S1;`!p2zPuyu>)fk9|N1}N_R*|5LTG^&5W+Bo-(m$0`5j&H zvEBYLU;};)`zf3Ik%1d9!n-KY^vOn%S)T)PUfjE(ps~#fvI*T%{0%hRLNW;735s6kEg%mvVH1)I z404+7-C*^Qo)cQ(6&?!+(%9;uVBjqw7J^|IvI-OeniTSy{WTu`iQyWup{Z!$|Auj4 z63&M4wP79FA)JsQnwg=%p&_@l*c}35AS%fl0$3bk;2eITAS&V_5=kC5*&eoD9~KoO zQeq`0lMl+u-UOji7~&M}Tq0UxD2n2KI3kTfV)^wUi;dzcvLb#EVtIAq8Kxi|wqh;X zqH>hthMi&p;-KT*;x7VYalE2)#UdZhA}9u9GAbiu?1x;ynUnKzhVGu2wwqq8EOnKq}-yPDDQT);{(KI!+=(Qe;Io1VL(+|3O0IJc^t} zdZb4>qUHZ^8tI_5P>PO@nuVs52kuApUtCJ#PlNk!&)1g1KM zW@=iYVLlXRwxwsPW^6j)Xg*YFvejg6pls@91G1(*xh7!3=57k7{|C~hKG`O0oTeHM z=W^~}Z<5n*N@j2}=X9!Hagx(Pj2C3SLV_BrP=L8oa-XLph(?^)+EVJB8eVpo=D zd&b^((o%Td=6JeieRke?(o%ZfWYWQ51OypC+6SYFak#>CiP?UfG~50%?Z=YNL{wni^1_A|zEhYNaAsoPy7s z;v{NXYNx&!q|T3|HYufgYN=KjraF(N@~5e?>Z#`GrWLBjCF#E*;UTJEtK#Z@p{nkv zY8vM1uYwn-f{&;wp_2mZv6|MdqE4@xDY7~%Y6+|J5G#(7>a$vFVJR!+Fl(J&Yqt_s zwCc{Z-m15ft6*ho-!Q95mg~B96}X~~xY8oK%BxMC>+bN0!(j^s(y5isYrn$Xs}ky- z!YeZRYr!g1y+Td8E~UXTtUb9a#BvF+FVGL~OOj?9HkY%7%~19$~(EVwrL)&I&Ch&FtCK ztXU3i($2`V;v?4Hh@J@A7+@B=@L!!;O#D=rL;5tR&j>9no zZ{6;v2KJ}%T5s{>Zq8gTMJdJL{)6E*L*mX*7qsd1nlEM{uZSwIq28<8eg*e3g*075 zGq}PW5CSmmt6-k*{$elXYUUCpQ5a9~<(}~%V{!n--vAqM4%4w6 zUjsBOLmor2B%AWw{PDU3GA6Tf5yUVQ(=a&j#1((?9gp%OpK>mTjSABb3#+aRvvM%Q zuq!`t6sy8AfP*4~GBg;2Bi}+P>vA+JO)A$C8Mm-kFtIRea~iWTAdG@51jsT&11U>$ zIU@}(8;m7yvo@=-3%IiufI%E=!t;f4Bjd6;<1@`rbF{4TI&bp|xU&m@K_O?tCa}>x z=W{~83_2H#I{WiB2lNU^^a?yN{~Z(pBh&&kEA&QV%s$&nKRGy-JxS&z$8XOJ%owRl`| zSflY+C$&`*z!9)CTI02}3$d_Q-6dv}35_}DP_$IdFpdBt02wsAN1V?X$Y zGs}SoEZ_#W0e&@lr#DHjH)nHrijN3?V^Miqwi%N+faAA{(>N)5_}?C>g8w&z$99eT zIDfGCKDoGX!#H{axPbq7lHZ4QTZxVrb$6qF|DO2wlViA5&-j_cd2oPvVud*7V76nuob$PGq`665Ip$b6 zo|`yh>-K>6d7>A_oXd!qhcubLxuQ$@V*L4?tofL?d31C6q;onm-gxDXsG~nLq<4C$ zQ+k9S>7_q<@zxu5MMx|egs*gIWBRQ@EJ72^)Yt?xm-8p^d zc~!T1urs?|=(kk1y11+R zM+`fHcsoS%_$=qr5@<`*UG;TaUPr z$NR~r{LCK!$R~)%3p~j;_OH`?&lAMTYe&EfGr0SF(F=slZ&tK#(X?lLwU_+08-39O zeRc>vO_O}d%Y4)uJklQs&JR7hYrWJ@yck!#QOA7P`#jehh}T=a)9?Jgqdm$`eSlf~ zP&fS5H+bC7yxRMg((ek>@3_ue^~39Z#LxY8lszUBec^XJ-)9Hgo4w$hJmbs#*iUfc zPxaYTe&eIM<@&u_-@V%(`sPFY;e!U|i}k>BJn7H774>!!? zJ;BpH|G&Gwd9}QGGraDL{^a+5zngxi1^KC{8OF#RYy7_Y$>}NS~%Q*e3yZZx# zKY;@Y78H1`)&W(+tTlA_(BUm;<0w|77)M7&jTj+9dKGI{ty{Tv z_4*a;RUNm6C4&a-+O=%pz?oCmZk|1R`}P^MdlzqBy?gog^=tQEHd+c9LNshmqD6~< z|2#H!tTCiWk}FP{ByglgSk0R`clP`lbZF6|NtZT#8g**bt68^p{krwovS-t>ZTmLv z+`4~x_xAl8xIcu14;xOb_~K*bA45(aSve(a>C>rKw|*UacJ14_clZ7se0cF$Wt&B- zmaSX3a_I(l{~mttz=IbShj<)0|1PaC*kiY^BJP^SI60KF8`Of}t<(@s78G(kZv91}=HO+8c1!q^-Uxi=wY4kYI$jS|#aZM_xO zTy@=**Ir=~w8sm{JeAlW6;+i{R+W6UF-ZXw(AQ|CotD~at-Tgo>qHgv#|(@8HojDk zL{eEdnT@nL6=}_u-FDr57v6Z~otGtGxh)jjeBC>CT*S(C^jugad(xyj={*?XgcV+x z;f7n>me67Ko!B>V$89vZfH#s9N|YS_803&e9+~8lzp^*tQYl`UFMcon|CgdiHFlO# z%uK!+=bUxknP-t97FK1Jg--KBWbMPaM2$C2cQWXDej4hirJkDVOi>2f+o824$mLZ@ z97pDWX*LPks?9zd?X=ZiyTG4G&3fy&E%us3S7&CLV1wD-oA18;{u^+tu72ClxV7#& z*{{PsckFcoe;o42C7+z~mE7*OaKne5JMp@eh79lL=&YRd(oH`d^^ph1T=TdQKN@DR zKhLP~N>jfb_uO^g{npFzZGCIbVgK50u|uC#Z{C$(p84jTr*ZY)ffxGq;*egP*~ZI$ zp8M{-{~mnpe3y87p@p|T_Tm{o-s$k&e;@w%Eq{;Y#roV}u?=VPHU-sBHIt5-3gBjFd_@YNX2kNVO5sV%7UR67rZ4iYi zRN)FG$3VD!5L^&6PWk}IvG%bLhdI>Y4xiS+2EwpdA)KM&YA8S`ZI6dZRN@ku7%vxQ z4v55(;eBX0I~%U3iCNU*7P*KkAHFb(rV=6*iD*S57OabDRO1@i=%puyF<(=Bhy;rm ztN&QAjd|4L9{Kp7FG3NHiQ?a)hDRb2Ldt}e>f<6A*+@rL=Z%3ZmK;SyygCjnZ;#aE zCOO&3&-_u6#2VuqM|eqf1;~@BROKpJ>6A!@(o~crmnF?;|Hr0bv6Z>h)U=dE#VJ9TT2-rF zl~X`t6>%ESoPG@tpW$CYS)ogcmblA0wW3j?) ztb4kumsfGs_D9f-ZeP;M(X~?cquN#PdfAH< z?#9*{YEdqDp9{wE_GP*iIV~bn>$vv*7r+6w33p{XDEi7py!X{hdH*+0k5UGm0+#TE z1#DdN#J5KW)(s#Pte5;|tfTatR9h)rViUX8|G2T`QDU2mISzODE(~7QSCMyO8{b&C z7B;MR+j0&U!&tg`eOXG+D`ITo7|BTntPYX^U$rDQWpsHlkP9N?#Q-pXlzk3WmE2`7 zSG5TClkay!Tc{~hnIIod+9e-MfXjXv&T-~x5#SqN+h{n!Xs+^Zhiu*=i}}E52 z*~)fyw4W_)Xipp4*VeYRxm|5n$s|#i`qZgjb*o<;>si=i-t}(xOvs@NC?LV$2S0+s6P^TyC%obh zzj(wmKJky2yyGd~c*{q=@|eFo|KvG8`OSM?^P%s2=12c|(u2PAqDTGePv3gezh3pO zk3H;DUwhWm{`Rxiz3pYsd))V)@N$rQ-}zpA;ve7m$w&V3@t%n${2uzd&%N)Z4}9xK zpZeLK{`Rk5ee84p``y>R_`&ae^N&CL={Nu2n-B-#51;wRAI1FXUw`}GAOG{uL?+^| zeE;_!0RK+_1CRiXj}}yc7F@vt@Pd#Si_sX55gC(F8JCe6 zo6#Ac5gMaW8mEyOtI-;-5gW5n8@DkVyMPcBkQR1P9LJFy%h4Ql@fH~2`M8lC+tD50 z5gy}F9_NuB>(L(T|FH|?fdA|+9MQ2B5D*{_P#^=6AP3SQ?QRn`;T#u|Asf;m9}*&Q zu@^1T5{KaukE_X`K_cSo$=0H|NM*w?Fa!IibG)hpo6h9`1VErJ7F*IKUlJx`QYKeX z1w!Bn>YxuP@c}E6CwI~($>JwRK^TYe9*fc_j}j@9QYn{`Dc>;$_>dNWQYtNSDt(eF zuhJ^BvMRR{E4Pvmni4F-QY^=kEX&d?;V}l}fDrgkCwWp5yAT)Vk1MsZE9;Uj?{Y5l z(k}H9FZa?fchVvu5EG5TJZ^y_DXIno~QslRLZ9JC}0@ z)N&J|^Ah_pB6o4_u2VhNlRewhJ>T;>o6J09>lWmT6T#sl6%74^%-DltCBNK^qi8AN1*_&|CC9W)JcQ1Nul&fi&RRhluEBuNv$+Xu{27#R7P(!N1u}x1hYdo)J)41O+EBX z)ig~(bWPWk7SiBLy;MuPbW88lPV;n1@pMo1v`+gJQ2$g=>6B3UbWjboQ2jJf19edk zRZ(9QOy?8@1g{C+06L?RA~RJ}H+56z&P|g6L_@VKL={v=)l^FrRY_GN*4|DPE)g1H z|H~}wwO*m&UiCF!_thAdfiRch7B*o-ji5wP6igGgMHLod7uI1L7Gh15VI}rqDK=s! zwPG>$VkcH(E!JZ@7GybAWHWYTH((LCVi=UGM}XB6KXF(wus{8?={|7hI@fbQ{}*&a zS9C|0bW7KCPZxDl_jBP@GDkuMwBQASwsB{dc4v1OE`boJfC+YBQr}i%dskwAS9lS2 zc!QUCkJosUw|9|ud6gGO^Wj~I!Q|5%BaICbAH z6Oii~`ej_w!W9UX2@G~pi?esNIE$B;i&5ZZkN-Ja`gL_6@q=iu>85FM6bVdZ$TR zqf1(-gPN#Ax~M&RsEt~wk@~1XnyHuCsiXR&n|i9Dx~iWVtEHN!f7+*$I;*2vjI}ro zmcfN<*8$Z6t*=?F)0(Z<+O69fuHRa&-c z9Ksbm!Wmq0|2wg4*fyX+v4Yid!5MQkup~Kfu^F43kB72P9K};y#aH~qyPyT+6qd%e&mmx7@UcJjunJjj3Q0mZ7iN!p7Ge$J?CE-yFxYff0h73Ep56 zZlM{PAscQ1cd4KYe*DV=UC;-e&p!KKixJ!ozq3#(?i|VNBz`G9o1J|)id4I+2U8rp&X#W0&fe!zS+YW&4)*P zX-eGJe;wF^UD$`6*o)oRj~&^QUD=nN*_++jpB>txUD~64GPhtFZLpaC~* zov;hrut$=R#)+tSz1OGR7O3zqh9KnoC-!^83McLvtH}Bp6k25>xUr?sQwKu0naOB7&;+$ z{aoOup6%P-?cW~m3;qrAn(p2DxX!`j&B5#Up6~nK@Bbd~10V2l_~Shu?55d*Anc-yCFNM4y}wJ>lKk;_MkgcbUHS zo8S4LANtw;4b*zCHJh)kAN#9+uc2WWSl|1dbg9#(P@hVTN_DE$s#vdTO-e;oHve$yQi>f*wxqgYX>1h{6Se6L zl`cE7>fOqBuiw6a{|XLFc(CEZhz~2)`6k;s$B-XOj!b#-iAje4K!*ZyM5o=v;9?c2C>>)y?~w{L&{ve7!AYM8a-$de<#1#O)3=gtA? zm`=UA_3PNPYv0bjyZ7(l!;2qJzP$PK=+moT&%V9;_wdWR`FJf`In(&_>)*W6-n^EI z*o9YKi50lmfd(ds;DQP^$l!wx=EW8xo`AF8g&1Pkjwn>Db(4f?DB?<7*|al^CyY=* z1rriF=puwLz9?giG|p&ajfOP_PX9KL^|)h?Kt9H!kdHx=3~CuBspOJOHtFP(r?Dm_ zYpU7v+Lga$spXbjcFEf{wGd~Va%5V=9CXmd5#O3@w&~`ZaKu)Zp5tZTgi&aFGHv*WFf<;ttBz6J{pG{&s9>9NQrtL(DOHY?~g zR$l3vm(*5k?X|N7H(YULl6fYY(cLNTxa5{=?z!lut1fyjOy|O$wA2Tvvs3P4<%xu- zxazF@(%SF8{s#OnrIf}%MgJ$(j6?6H?R46ggl{l%%Q4xEGmkN@%n=6_G7$*y#{!28 z^2j2`3Nfz0;;Qn>EVB#^G{!D0^UO5Y9IdpjL5n4}JooJLmtk_-ZF1j&tLC~$C$03- zOgHT`((pp_Rm?Qc^+p;T8{u)uBzMjA*Isu`@Ys1Be2v2P+HB7?j4XvzO*GXM>Zm-b zbLu5_QK5C%VE4`U-+l)Ul&!qByfS3JewFK2M&j)F-_WPoOiCR zm_rlY9Ju31_w?zgr>^?ytfQ_4Ae$IxG3Jj)Yi6nglCAshy!Y<=@4yEy{P4sVZ~XDd zC$IeS%s21+^Sf)^RsS*O&@MSKZ^R9KUT=slVns20HM85G0QqVs|Na>`z*# z%G=)F$H5MI@Pi->p$JE~yDO;T8sfO1YmD&*_(_aM?YLXsSVY1a+VF-r%%Ki%_=a)N z?}sk4p8$tQL@oKRh)7K0Z9XS710oPQri-8yr%1&rS`li5s6_=Y$Pa(;V;{G0#Titz z!5y0MjA%@w8h3aFSN!RV`Wr^}+}FKZ_~I+=z}OtHMuj!{@sEHEq#(D~L+1eTkS|lB zA{XfoXfg7UME@jU6GQjJ=P2-sn9QUmH_6HK)S(bs%*H&p$d4|D@eEiSq$*d*%2uk8 z3L+YZ{`ldFKE5w*b&QKS?18ZqsmhhW45l!L*}g)O4m!9p&*O48H4j)LZ_Rw?(HK{7J*r7(>t4z*@N6mH2Low8vaDQ3Z8WDIM$lc`XLO4Ri^ zRH8@)7ym^y%GBQk=bTNADsQf7zyp31iY3jeR=3L4I@N)K*??-b(&>*=y0oZhO{-dy zcTa1G!;8LQn+~tQh)Wm)k1{;#TKCG=zC!GwNe%2cmMYc4-Ug$FO>F;y*3qF=(m9vx zs$?fi*~*G%oS_u!Sj#F#z54aDpcN`j@u|<=un>(q%|;4+x<`G5_O-B;=TQZlRKhAY zu}{6NZmC+;$Cl2rzzwc&g$sx*N^Kt4O6MuDM!wiO_qnd5sT<3&&)l5$l>#LdIAVAU zym=P7;0>=CXG>d&+E%xPMJ#&L%h;-#>8h3-u6*Z9-;%zr7E)6fI@Rgjpo;gu0M20- z&i~*>byU|j#z?~&H+Tj{$RaMXWGx>9OyLT@kG$oD=y})6)ZB8ou)NLYF}Yda5}WwM zRy^r2&Zb!|mC`l*XsO;TOye52kFKtG>uvT?OH~GRp!Ue?jBQNhA{P(C87AF^Kb%qZ zGFhV>b+2zDi{dI<`O2(|16W(^V%gkco!>RGn8z%vFYb38SG#`ML1&`B(t2! zjN~MvX~|Efrib&a(GYud#8?irpadce>gY^|NDN{aadl``h4VlNLY; zjcb(Sf7Dv(|72XoXS+MRlXj~=uKUit(G|#^{wb*6&2O1TyVR$~wjxz6a7MOT#H6Eg zxEIdwhKFa|o4AF!(VcFVg1OoK&Uk3sm<>6;^w@U|>#|>hagCdtnE$qOzzbf)J+u6g z+U}NbN$l{N+x+I%ft|#!UGYV;^W;F^YZ~Uj2n92g&9dOpy%@dkpgUcVDNpjsUp_>F zQyqy1|8v4|&h@V2+}1l!w3bTAYo>ST>1aKUH;-#KUX*#|J|+dihk4bS`D2YTH2JsZWlr0&fh zl=ZGpzTK}did!^eA6-o6u21#l>RbQ%u22Lgw6BOuC}I=d-^BO1|Az9L|NQ8`S{l-D zh4r)F{q0}B=S8og(AR(TrN2SyNza7*BVYM@1$*Tsd$wmyepi4)6nNgkZ8Yb54)}m5 z25}N6OV*-!Uv_)|n1OaT2P+1Bw6RkB@D8OUf+0A9{6JQ+@joDVVE?<;f-d-i|F93u zPz={_4aLw5Hh2xdP=hyk4b5rtaEinDQmR;6dzXxxvxw4|T>p+ZNx4Tl4S0*(*o`AK zZnvO|6j&|L_Yd}PfnnB+>R4lQ;3tY#h2_AE>zGi_h*YdtjlHpp__!rkD0o@ujQ|;t zBqf2ucP*uKj!ZX?3Rz(@!3gb$jENYJ3pr2qXkO8{kJk8(7^x)+s2qbQkRTb7-&6<@ zcZuk<4=uq?XE%{7>0B{j1P$g^9!QE3*^=*6kr8!|8;KkGxRd!Pi;xIXA~}>qsY!)! zYbIH7F?c&?urW6Il%K_RozRmnSCdc~OgO1w7wMB;LXBL>k=NK*SO{oES(au=MMoKq z*IOWt+aK8-(eR|A?B#d7Mv^maEyA_V9xS6$j0g zo6^ZjbooLvd6{`Roock3dKa8vsgd4E8yzV+WQm;Sd7en4oUDn7{?HDN_jB4ApQ~hy z*I=0ihnw;_UU-*xrq-L`nHyC3pTkL>TZf(odZ6c$mb!>7Z>SE-WlQ-Pp=qQw^l6{f zhMy9OL)__1{`sG_0h%5vo})R7+K8YgdZOa8nEwgGmi}-KuSs_q8lxgqof4Oa0*9e8 zN5t`kq-0vA@KFTn$)Ntgr0-dVR{Eywqcx1+3-yU@I0~m7gr(Ewr2zV) zTPmbhWte6hxo*AIw38?QSsHEDfzWN=&mkcY) zo{Z|G{xz$}`a5*_sy51DvYM>rQ>$9KrT-vGts@$gSoN#gx~%&ePD)yF{s0cE3b6_+F~`t`iS@7~ zdpr_5v4H8ai}i?FXEYmIvm9Gow6J1|8nR(D2X+yREBmMnJE<9^vO!BcEeo^N3Zxgi zs~KyvP|K}F0DQ93nC#G`i~yTQ+o}>%pF~?tM!U7ale934tKPYjef>#N>6wc#3k z47v~E@Pp^-ref=;FCa0^fU+7Dw*PnQJ7hbtOWUJO`;lvVxZBzh#`UpYvQi=|3WP9s ze`~2G%eNKfx0CyNn985FDwt*)oM_9dh&#HzsjTsEV7jj4Oux01k7JwNFaBF&Z~RYfd>Th8=ccDpRkLAUzo11r?`<1xsp@mzT z+`GTs`?lpqu>Np2@EgC=X#_7obm~h@K?Y&Pd%Q0py#%}i)w`+J8=Bcmv;3RErCVI5 zTY;_t4zd855j>p;T&Iv!4*wZbR}+&B{Ll_`JHQbk3}GNLERgH!yUg@L()_weM@UnJdHATCw=6yV)3t zU|h(fS_IIbaW73dHDGq(rJ#*&%0t^lv=`!n(Qe{JE!P%I8o9KEjV$A6lyJ$k`H zX~?KdsNVVn;YthTX1Tx7MJgD;_+l6CB*{`6 zw1PaAPn*ilOsJ;&%Krul93AHggka0K{FH9Y2(EClMPv?D8a-@52%H?n#;e8;52f$1*{@}jEOtR}7$bkHx z`HREy9MMM_yktzST?EPH3$*)8h}#Uu|Li3JeLT`b&QE+t!QoS&tj<;paML=U8rr8k58@-Tk?9H4L(#uoFXAp6~z`_U(!>qc{4xP-%Y{Mi< z$TeNnN9wIQz{;86%GXfOTmr<`yplgXj0Wt_n?uyj6DlII!n7<3iV)Vf45v;lpzZ9T z?;KxNo!4d>&HuwIh8@=lLOj;ZxXrTA*VKa6+q20}Y*S#3&3HQ3-g&=IE!Eii9KEa8 zn2n%(?bW>ahI18zc#?VFMv zo)6v3y&c{t`UF})2&zB})?g0U0)5pz7ffy3$tOJ#v&&vG4DVBUzdSLSXAUns+Y-9n z*n8W#n%iQkz2be~CW_Ty(8|lu)hr6cn<&=s9p7v*2Ogbn_WeQfUCwW1-TJKEE3I-Z zjm!=0-T%v6;8cy^DsH0fV!FwY4c9Wu*KoYpJ>kmtl0n_L84g1Dt-^5;h;-Xp(+S`f zEZ}EL;Du@6E576=ss(P4MK7+Xi~7Q8V7@jUc{$EcJ8nZ)&^@lu$&F+TfQ?F4ew9Qn znB5)OC!XXf&g5>6piXYyq+;Z_u~N$x;cdm4vZq1IZ=W5r{e!d(00O&VF6Ex-Jc9eP7 zKn#HW;WoMG_6yayOW9p)*^{2@2wDW~@;X}`<JRo=?f|AS={Ir{OAO_+q%B(2dV{_1?(2BjLXmocw=S*sisl}d)?VzgU{oe7%+3Rk=2&!<5G44h0@DDRC3KVbfCztM{9*3sB@NALazEJ4b zAm;Nvj26F<_|DyH4(Z_S@k0OcPp~JMp58m#>DQgzEbnYLpa>0)W(wa*sJ;Wt{^i#& z591*5o5=L7xAPl`@qc;Our~B&kDTo?9plCbwU7+pVC^3m8{p6kC?eWT(DeOg1pk{H z^)N3_f<6b$SMy=+3Flhyt_Sw}*z=*O@4S2Vj&GoG-u7?bGjo3n6L0u<|7dZ;1WnBM zQ$I{)boCD34#Ez(m~VH8zmH;{#Tt*X+Wz>kkDA^Z`EC#QhgHjEp81c)1l{AcG4JtSJma9w$9?>V(kBQLN494Kr0P%)Oj2#6H9z>W> z;X;ND9X^B@QQ}036)j%Gm{H?KjvYOIgh++a93vo2o>WLB&74cOe2w#WjsMuKPG zrm;?n-lWl;T)9G@Mx8$gid6J;>ea17y|(ZAcJAG+UaMsmEnD)|+!~E@S^awU?cKkJ zA7B1_`t|MK$KPIy8$z{`fzxif0F^SYrZ>7+EOT8ap2^A>Tc@-o{m{mC%fZvVaP)*o%hC3jn@_{mex zbnnc@mp=W3H(q#$VYFUFT|sU(QAf40)K>pJ)klB_7LrI zw(rn+jY8_rAz&O8IHdx@n=5yt;714@W$4#TOT>2)VMn zrE6meG)5Fc-XMEz%{S+~^E0V+vu}d!X@>5)p$l4c)&HL=dUe;GO8Vfy6{eMO+i%A` zcinf-HOpFtd6~K|`Dv!|%QN>pdF7X9-n9vV_xN>F(WOFPpHFu#b?H?Xc>CA?UYcpz zha#MJ^Up^=ef8Hb3`_omC3ZXFD>v?nvYW?0fBpAYsHEpF^d6AFk*`o)4|_$?UI6*l zIt8jOc7Q{e;DYir_Epe=7sOx&4d*zEVGI}XyAElHzXWD5g{eOG5dwbm zs3Si>CJN&aFqO}QW;8Lf!dtW>dbyNJHfBl7Mb;3Tj@;Wf!C4mBMX;AX9A-MzxlVRk zt%HpC;E$|B8V-qVkJ7|vKJ|$ZD_TpOP{~I13dl{NF!G;4!sS6vwaZBsMUCx*XhbDC z(J39#gTpw-5@+U*X5^6&XV_;*MHF^mr;hFv)p8)sZFaS*Cd}G0p#M?L$y5~?+~S5MwB@DFR*~CP=eF0q?{%XbIYv~Y zZUVd8#czHaM3CJ=5*%;9iEG5$Me?GzE5tSMaAm5rh7tv*@P%-MC9J;v6hg7c4Bi?aQ?kZa#&VY3>4rFDjIp1zBS($;Q6QJu z%pMVO3pZQhL{e3+QWndK;jCiPn(?$+#&e$a{4gRQ@pr{Kt94OyWNBTVdi;2Y zZ`q93yjEH?a<;WpT#RWLd)n8(2KJJ=;07G)xJ#sI#xO`o1y!@!*&r73Er`55kA2tC zZ65ENb8Qt$ZyPF?K2mZu9c*%!+uW16v0`zJ6%2)P81{U2ya~-4M#uut(j&2eu}xrY zdz&ij_BT^@9d7oX+u#RBIAfmB1wjyEv7`W$&mDHDeJrgfyZ z-R*!g1>CX{cfwV^a+U`MOMr0rs5=JBQyT~4H~(-N>V5CN(Nz@9{>Y6?_xu>T7oYKTXio~Z6H&b6Lhoy&sbd^6;%JKOK0Pdc1sm&(c4lIf?n z-R%h{LT0*P2S#k-7Tf|ehCuf2%Wd87meu$z-m&PR^;Yb_B|F*$UUkJQW#A|;_}e8v z`EsXwvGUso>BfBDzjr>V)p`fx2iA@rvqtE3Bf70gUUs!7%*vF9ee64(8H?4y;n(Pn z=Jn`#-iuV@vM{#L<}q=sGdsNdK5^n39~03l{_$(?wd|!o{XA#Q4Yn6GcQRjdfdIYt z-s*=mcZf3gR;k?83Lnz}Lwl{kZzF@||azrNE53M3WfQ#|-9Ir%#y`uo5kBtq888Xa&g z9K${NnFs5_K^BBU6XLIWJ3t|6G=sQ-G-#6s%!YR0J_)1<9kiR})3xS9I}Mya4lKeo zWW(jM82-3CFjI;qq&S<4!aLj_7yOq{Y6uymK>$oPPk6$J5W{}qLA3M1fCECdYr{r# zM8e8HhMT%u@V|}$Kx1%)W%E8fyDeE-B+w8gJ-pGmAl;fbCmd^bjTgH9C2&RL0J*ayPfk$kg_9q>b0Fa|*UMQ2I~ zR(uW%oU=sqw?$03Tja)W)TvzD1Y_(DRNTE`G{>~Lg2;IXQA|LK$igjjKz2BWR0P9< zpvLTR#aM*Jqm#uu^TvM!$abQ=E>J?uYlmX+s9-$Dg+!SvNP}CD1*O=>h}#*BXvP{$ zKSm&+d-S4w{K2y$Lz7#ua#}CJ3doa0Nnt92H@v-FT%vg>252b0O=QTLd=Q6(NW9~b zu;Yk#R0J+;hhs1lPhf;gptV{HN!FRjfa}NTOUb8%%1eqwL6|ymtRp}q4vnjI`$cCe|MmWPpZ_`F0jLNu_OE${I$XQCN&<=H&$4<~nuJlVY z!O4i!N$$`llz7Jx83tldOOMRJyY#lEjJ&y&%*hlYEFs8n^p1A8245)0zw}H8NrQA8 zhIQ-?YtxAvn2>cShp|gav#UZx9Ldt+HMpeA+O*9IDuN`myKETDF7X)6^aZT@%;8*+ zz?8`AP)3w60wdr^1Y%64bj+fwGhT|!+qBN>M4y!;gE;7qVMr!e0tZ9UMB*gR+%V4Q zbP8o+gw|+IqF75QYs-;~O*`90?6lAO)SaKo#otLLrC^8R;Y(>O&jD=>uLMhEWdApD z@C2Id3FK?C=kzxWWXkDmFsH%K3&qgf*-!60D}PXj%@l>cB+wDv3DkT@!9-7g;7Oin z&su6tk$g?on@{RA$qcp88$BG$ECkF$d zrL#~RmC`A-n%un1Tj0$mZ3^&QhM64FFYO4GP{*(^O`T}bf?CpCi%&J3(Fz?LDuvTH zjT-H=J^q|I07RAm1=Bsn2ouf8-mHq`T(Tq`x-`u-360PvEy<;m(?)evhS5(gAjrs( zACEZ)5EW5A)zpZ<$(YFog_J5nMLk1(KagzAx2(}eRn=9^70207`B92;*#AsD-PBrb zh%BtPi4=!RFg;OiKT^FwEuAySq(xRW)?>959o>Xvs8oLths{Ja0kzdy#R-v!NHc7Q zLkiW91J-La)ucpK2Se6zC08o3(jCRp{)EO(5Qu4YSA*!f=4%I6=v8ig(WXGu$5hlR zE7o%L*MH3qI@J;c{R%HRhcKblciq%a{0C$to_b}?dsT`xRlPQa(l-UzjMZ5Ba8=7B z1X^I${yc|vNmzx|)MA7{GUx&=X;yJ)muNNF zP1U&3EHXh|KVPlDZe`1F4asmNpPPl+sI?6J%-PEfS+4;^FAdr+{r|neR8JN~+8u=1 zmvvcUrCF&(+q8v@mAq2kyi;(H3BF{jtsT;Mjgxj*P?kkJn5EcKohkaHO|=!=!95It z1=(gbhYgckx*gFeB-#}{K6{1Pe3j0mThu5e+|1Qn!uY8t&;l}mr(tkO>qy*?Q9#BW zQ3EU;y(Oske6qfkG^fSb&86Mi^^2_W*u(9Pa@eq2h(OdW&onrLEn;16a@{AR+(X^h z+3Z)_b>8R2izm?89ZiPO6&@Rm+ja%s;he0CKz1-P#;UP9(7}kOvHQ_iB7xcRZ(>UE6-qamFUKUGU zTjSp}BH}EDUff+cH(-QYXkYFahYgz)1%_fFmEt63F&}6)_mq+Rbj|uVRiQB!DVN6 zHbJ_A+gk44dj7t9ZrXD0K{saJ^8M$C*4&kZ5?|-lSb*3R_T>y>6UismuBhDfa#g0>6*6bo4)B=*k|agPKowuYxZ0(HfCcvMt>M% zYnYUS_Gp~jVYsc6Yk2CY&IYKSYN@8`tG4Q_uK((-#%iwC>aGUsuNG^sChM>+>#T-q zvsUY|UhA`V>$Zk#wwCL+mTN(NXgL1qyw+S8wqsSmy++PxZ$_%6zPKGOht)jn#8yqj zPV916>~Uyp$3ASxZtTa7Y|F0f$-ZpO&TPh3Y|j2{&pvF-4sFUV?adbL)ue3G9&ONW z?bIgi*Jf?WhHclT?b(j)+eU5Nw(Z>ZZQC9PyI$e5)$8I`TRP_CcK+*6D(ZRY=20#s z!v5&{Js{OS%In7N?AGq>=5AUOZhnSn;}&m#PHw-J3$yX{Ek{9282ym!b%+na5#pIUjJ|QE;IM0?*v!y1!r&tx9<%MZ~d0=v>j%l zhKT}>o&Y}v-vws_*DnNb@DLaA5hro%dGItO?g>}%sC5Cp&V*6OhGU+?f*xfL|1c2G zhGfv`THx^>_wgSG@*o%TAt&-8FY;kXhHS9zMFLA&F!Cpd@+g<`ARmTv0*7Q6hAG$b zE$4C{zlCJDhM+j{S&Z-%H**#@;!H5_W<6>GxAE;l@Eo^>asY=qxAQy4^E}t{J?Ha2 z_wzq52WVIZB`>J|`13$~26I^SNvHHmzwvb%C2yjtW1SWWM+(K|`fd2-2$dFi<^;xI&TDSFE$Msy-^;mC*Bp-?-hxJ_- z_F*UXVwd%D01cr4hhb<3V|VsvhxQDyhig!nO|MT+$M&1;T+i+AVKA%j4Df8&XjNbJ zw?c4eNQP)v_jTX(#S)5g0AqHS_j%`aR{#fPcZFc5_kE9cYXF|$mf5=|mELDGQR8!q>yLhxls2793RinsWS$M}rb_>JfIj`#SA-v@UW3M|dMk2m>~NBNYu z_;yeQ0|EzCD0!8a`I)DAd+>Kn5BTB6>w@R`{q|fn&(dVFhcUi}OGtz0e)woQcVn#i zrgwUe7x|#T(x<2Ts;~HYu>W^_p9ibwdZ)j6fR|03ANZapdz3wmx%{y@+`f*Qs ze2RFc@A|oy`KSj9Fy4B)*L#y^c>|KEyx;r4=lHL;_P{Os!_U}IAB8YZCZG`aRDb(t zI`@ee{L0sOyB~*I*b2+%{EDB~dj|?ShxyJYeZtRq@a|v4SN)oO0_l~5a2%?R*@tlV zU2>27KZ<*bpNHM&{oeQe-{*a8cm*)ffhPz9SZD`(0RH7?{^oc7t;hVSe|~w8h9q!- z7T*F?5C`3V{_gkw@85lOXnC!leq}&|6KHWNh=g-ce&q-M_lN)9xA}iB{8U~2`~O!i z=H!HreMtnYMZ&=H7N}3LdE{QPNB0WM6Dp{vW%usi|2#&aR7*DhZ6^;aAfN&c zINemi1vTgeQbi2#$(ITkI*hPIT17l@M>gWLqs=5qJh25Z;zTn9DI(s(hZ!T5NCJfF z7^vMjs*q$7IIi6I6Im=IBAhmlWUz}o-`rQk7O1qdPI@jh0iQkgC82{AgHW?hIF2MC z&IX})L*En?9r5Byn@U;>kt?9WZpMCoIC!m1}Iw+xq8hR+A zi7L8iX|KgLn{JUxira6$i4z=g&}q6Ur=5EGDX7m$R~@M;wbb8_|IHJQBsY*UPCIRm z*vcq{fd3K3Fq2S0N;~1$!9_B!H1S3zU?_nKJE`6n;87i+&Q;ZNsCX;xe#yQ_m0>VywWPt4yShUH_2Z>aB!zQm((SkUr{>PP9 zJcjjSI?@Q)jym5YcnUhakT6GDAV4gQ2xnwsM-gU}la4Z@WD>{|hJe#b6&wblLK8dL zVFfAWglB~!j*tOis&L9#C!Key^cSN+3q3T^MH_uI(n%}5G}BExjhLgd(Kad7y6wY{ zZf_>G+=0Hz?}0ibJfMOUOuOk=hOM?zd!%| z`~N=x11P`&GRg&jae<=%v58@{qiPPc4c2}$4{>Zw5pN(H1~aI^4RY`}W(KcWxK>x?74kea^ zK;{VOHxcxdO`yR7)%(U&F5wD&-hvwLC_@;_LB>#s19lh4MjCf<9yeY<9O0-}H-wZ9 zQ&^xAs+g!Nh=@>cjw5(Ha>YSsny^l`A`l<&7&)Y&0x!JurNEdTDcCVRSVSXbXt7o% z!Jr0pXyX&*Gvyt;@d*$p0;Wk}BSO_N%Q@B3PPe?@Fw?5mwX(IXZhb3UoI^3KoV!^2nd1Q-2g3AUuQlX!8=*1sjJrE*eI2Y_y|~U>+|L@c$}v)FTR5$ebxM z@QDUcV;s6j03^~;5^#WZrsW8v!D59_b0q8pLqequK_-PTuEVqCKx!pZ0RmaPf_mV< z1tqv}4Dco5OspuS^QuY}b1(?DIYsDL%X%04p#*4h{V#w6EZ_kXxWEPu)N8;X8*|*% zfxOWxU!^J72~)Vj6DDk7RdOBBPFEYH=&C9vu^xCv0vA?|ggSi1fhL^;l_Hn}Oo@13 z4u?~;1Ik8X$8ovfNaF+`iiQ+!APQQHB670L25lW`+iQiR3>pxHDy9+&bC@F<94NtW z#ZiwbfWQ;AXhqCs4A7eHXt_9@DRrYEB)chte7itp6>EVDQU6eb9K5h$!|n`=9(!RJ zEmSWk6HyKl-C!5ZLxUO8F%5BDf)=Vk1!(iDU;ds1e+RxarZcVSO>?@_X*Hk@5-gi@ zG`MP5gK!0nVBuA>y47OCaE4K`VJg$Q*0#Pit;gY>DwH4uBw$Y_(GY?Vcz_D9_%1J4 za0hDG4NWB&0T*C_>uFQl95!ZLwP~G>twydK?ov=TS^c}>g#{u2ts-m3KE=M*LmI$vX=>#St5fK#01@j3j zX5UDK22N2`6%4zIpL_zlNOaY}aiOEFAVaS~fLVZ_L;uocrL;+`0gai{yyiB)InHyg z^PTg&=RW^A(1R}Yp%cC6Mn5{zldkloGrj3fe>&8oF7>HXz3NuKI@YtU^{sQg>t6qQ z*RPR{aR9vR2Y+TW(ysQkv%T$Ze>>dcF88_9z3z6uJKpoI_r3GI?|%O~-~oS)&c>QL z*C_|$6R-HiGd}U-NXIpxk&Icj z25uk+cAy7-AP9z_2#%mORo?*~-T-!%*$smZ2G*AsVKk8m=K5wxJuoAsoh`9M0kYCBrZnAp*vrO5oxD&ERO2gi-LJ z7J^`pyjI;5Tn6IX4x)r0uEZ9`Pn^)w%m1Af9af?xULq!Dq9$%4Cw8JIej+G_q9~3c zDN0~DT!&{dAcL$T1eOC0*23V;A@vE*a#`RiM&ST*ASQep12h!O0W>5=4umzd-$00ELu#W*rlnf0C0n+oTfQY+#-&`E zV|mo2yWOQ-<|SV4rC#@dRBBo*{CS#VzIuPa_G6?H5CS@+B zWmaZlzSaR0q)-+WOcm8uR^(icCTW(YX`Uu(rlxAHCI(Vr5I&)6>L6@hp=`dUZPq4k z#-?u4=5EerBLX3B2Ip)J=WX_8aSG>g5+`n!iU}HLZX)M%DyMT!Cv?UpN*sV^NoHWy z7i)H>cYY^$hNpOrCwbCibN?iAo+oq8Cwtnbd(vlo>L-5g zXRHNbe%>d44yb?@Xn?8&b}piCmM4QYsDnNzghr@@PAG+PWP%!Kg=VORZYYO#sE2+i zh=!;DUT8`VrDvY#XQn8MuBeK(s46%mcZ#Tt&M1x6sEytzj^^kaCMf1LPU8INvb;$$ zWW#UjsF5Bik|wE=E-91BXo5n+HQ2*GOevLCsg+(SmS(AzQmH)*X_I~_n1-pCjwzXz zsYxcNU2LhEt|^;VX&{;@oW`k~&MBSNshw(|k`O@&xJqHJ1e#idJp`(t4l1D*s-Ye# zq7v$x-YKIts-r$Cr2j@Ll7fsKr~nDTN10_(6@ zs;(-lwyLYn<-17&3NS(-WC4f}o|3@KL81+sLW8OPDzGXlTDsx8F#@x_DzYZ4vMwvL zHmf$x#}oL0^#lUU5MEVLzyM%?61c)Eu#yMt4a2=c5`4g=j$N+?E4m7*JUpK`94e~D zn!A(_b%2AOIUqSC$S(A$v+gUu_N%}CYnaLxDIm{1iBd_l4+;zdE(`-MECL8@LRyT# zAcPwlY=J&42soUpOt3>!Re&n(4S&FeOt^y`+(9t}>O6==%DyYTmVn2002P>8Qqh=5nolojAtpsBy549 zQLPe?*Ar;TI@DLM&V)Mf0zRoi3$Z{SP=i&7>^!&wA3%sbT!l=qtWzk$Q;7f~m`)3j zM@gI%=%mB0u7q$rAUd#u8VzmI9xmc0uHr7PNTSjWoPs$-)gUC^#ktBkpob%DK`|iD zCs+X_D1#(y2%WWHuW|=Fyn+_+%{h>)&!(6o5P=80&^fpb8f4KBwOA^^?hT+qY@q=M z2!H}Co2>lAyKb9;l*dW6z%hJ+2!z6x(5nbUg66b9Gw?zQP(TGBfa(;?I_LuAWL6cZ z5`>&Y;s1DS2Gm)%VgL#lf@e9%A^EIV%t!5xKoU%VENs;-n9-fR3gh;#|Nbuk2XHC2 zkHxHml03n})lK_YE_zh$E*S7Dpa3cC-rI=4#HmB+9ti3hLYu@ZDue?V(2T!u0Wfp} z7+CD1frGoa)7$uLV~N5o0E0O&jCQ~x7G4g6ur2jQg9<#485zkHS;D-0!!6vx+cdz> zmIUpGPdX_FcfFh`ZC88wSx_xgz+v&GJFE%Py@ShPJ>i| z$)>~R5azu`Zxk+ZHaHfOUogAm9}#U=OIcw91!0xiJP1o!F*nK1&? za|dvNFOb6|c&x`FfCU%=iF|;(c?B;_0Ri;00`!42Lr6}=$|#pIkFWv-5C8=rfCvl@ zgYZK12JHm!uDi@jNr>^X-Lej2oyw@#I}*ZB}5rjFi1J5 z7O+fnF_@7hTtG!8?_i_E5_eQDECL5y3*mu7EYuEzSQ!^crBnigHv9nyTtY2;f(0;f zFyAb`237RlSsxd*YOgkHxAxK2rC;+1cb0=U*a34zf2#CTf6u}_u!hN{|7)+d959?_`T9di*<0T05B0~JKacf~tO8+eJa%BTA zq;WbB-V(FJI9yZ<9II!AgKx3m?I^R63^qrfLNu2_5Ksd16scH31 z-2!NzLQqwJ5^#blJVN2#s{*XcI$VQBt8sycxtNbRnU|?kPuvaqDI%Lw;;q9ynM^s% zhX@P;f_v-;z(<>T?3}wB#8H3;kg!u95_KouIkdR(Vov6;f0GPpR;c^mSD+x?&WKVW6)R&S>0Rm_%Befa!V!$PV16hQxDrL{qmVp}io-T+0 zB$PR>=en-%x`|rkZr@^d`mMD;o-}7vc2+a5$Gg1GJH0b#uNEnQRtJEe zggLZ06aHVH8etRSVfCd0!*W}i*So?mJi|A9YWAv1@N&e%``MI(zZ2_bx6%afyTf<9 z$A3J?=VO8|!9CAF&?>x`J!lyz0n^%(kH#rtHM^|{Leo<)JMJ4$K{3Ud;(hi)MvfcZ#~x+;{gN&03rDV z1quKM04x9i001`!;sXE({{W#097wRB!Gj1BDqP60p~Hs|BTAe|v7*I`7&B_z$g!ix zk03*e97$4OvSh=C-5O@ErOTHvW6GRKv!=Z!h4#5@Qi|O^aUF2kW8`Agurw=@wdCnj z6p?jH3F#!{BGau}s+Q(#d2JL*H&1jn0W<1Wp$^058S8K$*)p60WjdFwTevs3+M|2;Zr{Iw)5dv%tJZEHTWr{FT%Rqe zTE*H@XUxu@LyyLMH0f#AOpT2wHLvT}us8FbP0QHy&=8r1(K;|s_0_D2T^C186tduX zlPg~)n%OpI&+I^p|0Z1*G2zrzpKEn}vuAssKyg{~It;AN?3SlH?n1_zJ^udT#2zEa zDaYJcWevv{f_kN8k0?4M!kQ_0mNNr*MB4N@he$1M)Hvgjvc?{rM(bfvpR(N(UNGg|d z1wHS<;dBI!23wA(WN6;SByQtq)sm#V34Giy)HU^PDw4XZl~*RFBg^d-IT!R`$^Q@z zD9&*+EYT~>64+xeNYq_Wr*w|(qD-?078_@I=7>HY`)JGOOjsPT;_a0G>c=3fM&*#| z&oak)ajo}Eu}y5!JPqLc_#IzjsN@0h9Z4>KRX^QSS#J-^OpK>1r`F+t z&D$BP0B%w%`^C)5C2JYk`Xzxf+N%{8U-WYQs@vid-&GgNG2Z~E{eO&$HeSmjRZ;S8 zNgIfkY2S@hcYM9gp*`cG0*y)Aiy{_wRRqK@95Q9-m!GnV#+;%=g0k|5vZacC>-ytXm*6HwVbUc|n+1EcTJH(TF@eQ%Fy*we>F?s*-^(B5+x{)SE3KL<%l;ZVh zOKAR+e&s%a|HId3Mf*(I!^BKt@+q49UWyBh#+qf@P#ib*OU_iq`9YZ(uuJ;o9wy@7 zD-_U^`VS}yoFzoZ6flsBsVJ!?#;2AtGYk2vs9Jj_eLJval^-0`O*~8f+M55os(47M z>okrl#D?o|PRX!3F}g9?j?Sw|&HU^vtsQF58-b%PLkCmY+O-sx7Okbf8pzPv)Dir~ z(P9Vd&ZG8me(0tRO&5x%6f=F<;%Q(vFd;ZAG4|P$jGu4D2(FB(O(Z1cipx!>qdi~sccwn3bDS+7c&>|7W1Rb`|`sWs*BT%Y(=Rs72X zl{Z#|9i~^+>7%9gBE$1}SBVAshou%xQIhtlm$k(juEhHs-D_4?;B7YDV)1@yvI zeN~v9rh&)jE;@$);p-76*4$nGx{dXm#v7?izj7+%i* zURQTmT<+JewsMwv-Magw%*|tHalQGv?IiHn1DLgPyKvn;oWi4h*`oKb?pvg$TjXxEt#?mC5zw~#un_oBczsd-S*7=S4jUE!s zswkro>qY8{5Vn7NK@N|4eV@H^AMhAjJF!l8che6e@cfYbR1J^xs*XzY%ss7ill8^l zLCsi!60QIQ!(BRKEYq5g8x7C{(J7X1Ajqkk`EY zVfJrNJVj)9oo0u0_U{V%reAsqjwfMb(4!F^-T`XAswcf|+-7g2p!g8iy!h|Pr{g8Y zN9tIvcsUxqStkL|@w646HQD|XFjIJ^Q>n=8j*Rbp)iGmuyAD|a+1$d3lRujYpT!G406k|KGkU90~iqZaX4FZac)tT z8|9haO|#{Pv3#lHd%M_ibcE{apX!VzVaNd)^AU*t@{K3*t`Q`tLV+}b4G>iX`9S<_ zOR^41wQFrG06Yi>hP%NRr1FxWf)5PL0lb3YV->%GqywiJ5ZC}hLIBPgGN?WUKLrU8 z^n?D%AvjVZ_@<44k%QUGK(I^%2J!)z;Ml#E{^U;pkQ{(nB_93t2L&)889WHU2W+WC zWX$>&RR;aefpCbbX)Eh8L?Cee^tHUgkJG}rLc*OK2?Ufwpq3$`js)TZA<~dgIpt7A zM}O=}f(dOf86SWFj?3~yt@Ii!Y(y}J008&^>}X2}AH?W4t6N(NbRH3qp8kn28GjIF zyjB$4O&OIZ8U-_aU!&lBh_VPhA$&Mt!L}r8$ibZf1U{S)hUFLzpFlus*j)MeaXA1# z2K}Hy=tlrX+8XY6OGvf7$vHp47{tL>iNN<7|B}+9j1-?9j@^yID@KVkzeJ4R#4!I7 z$9W>8<%5@B>4C7M2#x1!APV5#AkbaI23f@#`{{2I;o+dL2XmkyD1nNX5I4SfOp|!9 z34}|YAe9f`93P*W1NejzzZNxH;|qba<87|Rl#vp6BXEcKz*3dLj6}F76s{d2nB)&Z zfF;&U4%88m2%u8SY1CT-5HfKPjiMP6s`LpNVYnKM2{Qf&W){Te9BA87A44=r(jWmo z0C-Z8u!c;a!%1XRNo4($D8qqIvj%>ygKH$3uyKQ5mgb?}1zkvkww?e!!HtG5%w_=i z0tKHu#nM`mpl<%UnsQO^n$q6?vFz>lN!jvgVhraA^DRD2Q-JbF3CBAwk8M?eWlLZ6MkRTaO_! z2axs+34DSCcgI7&F=SE2LrcW~stkB2IG{fxd!Q+MXg)hXCrJwdpY#K)!oFO?0aN~f za+LTSAF!8CZGk9@5RHt+Oegql0^ArB;86kM5aCwAgGd2*n!S*H7zAZWo)HhdQ2AC< zkcdyE_FDx=2*=j(`Ut||zRt~K1bf% zWAHVq!1^zE#ShR708Yccd_;h?Oo2Tn&uDX-)Sh z3=dl@+uT5tvYB^fLk91QW=IBR&BE5O%;EUkFo<_NiJLZLFCKr)H+qJl$SWQk3BWHz zVZ$*Xg*2;SOB~8dsJj?ZBOGtS5@a0@jYEPP zU^s**>>+I|ZWy%L68QB5mj#ZEeS%Gq>O{i1|yhf!@G;Zo{tYKj)%6#=ip@m zXNmBrw4sAJZu3YezBZJk#B#wBx^RN6Sb|3dgPJ;3Bsb3-S3yX89$1lW}JR=1&@d1Nc(tdD+rgj4)HM$9^cy2Nsxp)u49dWpm+$gx~n`x58?X`cfW^L2RaHO6Ok zm}TL6;{kQmaA9=_S)6#Xk+xa2kh7dNt|{3S34$xm_PEMAE)XFX0Ed=2VQ;t{y-#ue z^ygwgBhebtv;?b_0V8}ZQEIJi#xgCVrAhHqm>i9oe5qxEqA{ii-o{#~`cjW9h@hK~ z=<6;sEm@MGWDl)+k7;)AtM|QT2fgMoy_S-F*01_ryYyMT?{m)Xb5ZYmbI|7+(+8LA z_k7jw?$Yn^zW-fz|9kcRfP?@i)8P;vs@9Bk8{P!l2?gT2~!C#i+;z!f}vgXj2%{`k(+xS?CoI?hCWuquh{$B5;^ zgtaOn$*vwaAQjmf&sj6bH;j#Ja^)ZHQP=H*kMtir%SUwVui@eq;a|f>$s9*vSzSYw z5E{$cOv${spICuukjzr-HKMUeOJF6U!*sarCade1X8c5Qd|n$;hrq+;BdF8H>&^*C z?PN~XfzWOe*dYMb{=m%E)W4A^T?Ax%w_zTM7xEMjA6~0u@-u3GY>2rD8(z5Fg8eQY zKMNZ#@n@sG3A7mw)Ta@eM^2pGPhLRB_fg;>G^$zHd`i@H$~>N6o`}Ez0Wp;r>&-%W z++xFr-Wlf%S|BG)_n8ec3Fz<%{=CQCMBz(O{m7&c5_q0JwGd&k{LAd08Jr!c$ybPS zi3<>KT+1oE&LSv86mpXifIkEBsBkB8#ym_bCQkrNs$a4fWqW_RO(20}$e&VxU*v(X zWj@SYl1?Kj|3uSN{mETi)Lk{Gc11fr_#&F%UV8$K!1)FzwJ zMKL0!U4%~y8YRyO{v z9DZ3j9bMVRUp;bNJquht|GawfW%ZJF4IsUSHeY)PT>JNB?Y?d8Zh7tY-x`M78t%~= zaqJqD;5Vk*Z?dnyNn?MLeE3bi^7~nA2SBAPZ;l{<&B3$q&0()?xi;i22EM5_q*mLQ za|)^%4RNN1P{E<+dli7El?%Rw*e6qSL;y?#0D~H56p+T`q5%SCRht0omOwpg6_N4K zx+uJl@tfXdwd8kAjYL_hDg^s`q;hcYsuAHU}C9 z01gp>y)^*Qd$sXIp^wqfuh9s6d;s)2`P}zksfsE1uYWpr10XS$^pBjjTX>Yx=>ZL=n?CR7ufc=8oNzo{8(`J81VXd&+r60PV%bdgegW6d#xfDA=%1v znrwaqL4aEygKK&4`j8hNPr%@w86J*cX}Vnq3Lr-Kfs1tK_m?y-CL*VA(2^Y7R6hc> z{$)>@YheMx9ptCBPa{tBE5igI0_oL0zP=hFxC!CCv3I|T=Wz?GxQQ6Q`9yycdwd;D z_%~VRZ|dqzO5EQx^i3A;-%Rx1Y{J{G^tX?hy@gsgd2x?@bhkxuH)ZsHOX=^*dG9J^ z?&@FPHGcd1^W$AJ`nFB$uI=0L`V8|FZYr|q&7r;|j;*bm7(FLHZq(M`o08}cD5!(! zn0rZw^DRyyI%BLd=dA|81HD=zYc3vX4o>YsqJ<^&!TIq>`&oU0%{7%Z2h4R~3NLuncSO0PbCy{z^Sb;cDe<05Rhn}}f>2g&URU<}H&?Vb*9+or z!kQcZcp48|u||@%aD-|zGrPv|ty%d4OH@KzxpHo=iu+Y92<7JMrkT8qlJ#ZBpzkfs zHG@OZu0!<{H6);wmFk256JoZCM$X?qTHkcX7#FB&6^`^#sMXXZQxCigWfAS#fYjLQ z)f?ibvwyuh}JuB>cHJ#j4IjcE?BjGcA;;udnW9cY+T&}S*P0{R!TY}0(YXMfO zSE%#?vR7_Yg-Y}vANBgPh>KGIW1Qfb^0OrU>Os~F@Bh{7s+<))0&3h1o7HN(9hm3J zHsLCY3|Y75afO+d=dr>pS;ef@qW+ zSg2MMa7{QoSU%O9|smZb**r%}kA~!o<|J(CLJ}sg=#g z_(dZLqj;qqRA}y)oPiOl_R7hQ$einBlVSpE&+5qylxjO^Uz#`w-&C;)OgZuH9`kir zz?#PsOG3FTfI-&;mQ4&HN^}DRfdHP_JyA&~!Lv2#S+sI=!ulbRSfv2c3HRvDgbz7B zvoiM1fF+q0*A)K@3LPt3PmjDhrZyG$gF|G5$zfY>+AKGKw&!?Ki$$$Rog;!PSzA>Q z^q9~+8;zLg3R71T5ba}hW%q|An7z}%Y?qC(VgXs2I)|5S`YA9TI6R5HuY-j!TuY)}`fF zYn-o|!A4^JCJJobHn7v!9nn~hIDZtJ?xMh`J!p3w4YXodBpZR(WV?>P$T9BQqnp6k z(?60&=41+~+Cc1*bFmlTV1DPwu+9v8${Rff@STkyn1Y!~#S@eI0f9w>gJWS2n4IC6 zz~xwyrBbp4@vtWVG+yaI8*f0AiTt=m$Y{LQbl9HX1R@gOCQL>gHYa`>MM4%!LiMDN zHsCQkOo|coL;Gd=yMj=)i)Wxeq_&LYP0EVGlL>L5w#+~E3z;5xSY@HquEmC88jO`m z8PH5Nc^p-&M9-v`oGffgB}4joXUX4ew>XXdsOr>{q}B@Baoaf!o2*QxwPCXIhBc{K z?@gvRDcEzxm5kV~CuWR$+Y5da8?jS;k=~1T*%qwA(Qq}a$;we+arG8>g0!`veGfGJ zAHH6%XVgnF!+nrT;7p$QPtTJQ^h%U2k2UEMn2eOlIv z)R8@I&3f4nJ?3~NN}|d9@o>00)k}PAAOL`P+s24PMg)LBtDv7fz2CX3eUc;QlX|TX z0wL2z(A#H{I5v7Q9GYedxp{o96TqN6@=O!BLSQ#0;+0xFHc_KsK~X#*l;lsG@De8` zixt<4LcpaM$*>qL00oHKSP`w3n)_KmeMfXOk`9B+63bDUf_m7|#gcbdvoUq17A30L zlD^Xc-G%3a(!UC@KhuS#KYN+E70i_=i-Svq1X=HLnbP1^;Ob95k!c&n@BrrsJ8sk- zGAi$gHcuxjFyR7WNJuLKo^PE?`Em+7hVmM=qcZ3RVWa%2oZ3uvCM8e}pVK`*3erK5 zhPRUd)+d^X5xTYZ7IAU1?9L*Im-Bgt+A=U9e{Z<`m?Jvzxz8J@y}WPl+cFTQXphZ+ zArs)-TM<*cTPDE+jcF zy9XMvq1&mvEFBNh8fM`n%{u9q5q^epQYrVGat;?lq>9LtfVVt$HG1#k$8#L(B zQ5FKP#t*HlysOt9PCTbEtJxa>Y_V>ia*tAx$DVn@zwJI?^J@9)9a;K!6E=(&&7A%K&af}F`?G#PR+8N$7~)2 z*8PW@Zo-GtfK@~T(Gbv?KmPJ3{XdY{N7jL!jW|8ehhOD7b>`nbc3*!~|8>*>xaa`( z$OMb#-IGRkOFX7{K_$xf1c8SarTwt`ObY#7~$G`nOg-YdE1f?Z$sh^cI0 zXfGz&XVaaW?~%Of-$>qfJ*|~xx|fxp=>mny1|eZj$$GHw<-ZJ-m?~ok!UYC~g%x}1 zl|m(zlY4H6ag}O&UT(Il_4KG__h`2EX!R&)lfBep?$r_O)m7-#)9=-{?KSZ3H4N=F zO71l-=ryVBH7$K9-&(@7{_>f(6ftJsYcj>x%!=Jl6>YfsEYEmg+n^$n#Oap~MjY=k7j#H<}WglR1yyxo%h$41$%L>jq|q7R?0EW#;h9Jhm(+7H73Ivfk^MyGj6n&n zqGy9C?9U*gLxZx>Dw#`zGZG@-?gzPp64SC1-v%>%X$}i{-&5kEpgz*0B$(*hGW27* zM`vkByLG6tRJE#BwOm1_vbFc|+pDu3uJazQ4;^ku9&RicZYtcSCZmIGSW*E`LVXnv_&X*DSJ1oy<49`Q&l;0iqluh-1+?S<(pGBFK8akM9$j7<1+8f;UW}p_M@CnB zG}bZ46!3u1;?b2DoMjiy9jNBU=IBoH*haSI294&fdhPnf=uyw;?!9I(Ky$lP^Mq^c zID71^CvbfvWlwVK0IGE^IDSs1dFnlWm#uYW`D9*D8pZpLf|j8Ozn}q_3s=5j4-ifEbCTO-MXfG$|z?1aklMF1A&x9r!UrsU^=n`&e9>3S> z3!P+t)a&0TpMS1p9MIrmfru-2s6CH=1Bh^W(hhnO0fN-&WC?MWwV^+{j0n<321`=^ z*-u$(s$Ct#j~G&N_G*)VGs!wSdMJtdO*Srjm;(4B$h}N1zm;;MKP}_>SYj}}ZZj>5 zuPy&YKPz(juykDRP*bi~U-{oS)!?*tUCN1|fsz_Z*JoN&%0M@8+Q3!IIOP}T=)3?XY#Daz&31VKY0v9K6X|+l>!4zyeXA{iP;e#2;p~Xfq{j z&_1YNK5}pLxXM|BRE%=2UDCiZ zSljGxBww%5H}l#++JViGsZHGh?=C@2T)K#1WV)Zss*7=c??UOXg|aQvdD8iet(44v z#+A$DRblfMzvtqG=4(gEQ-v0NR86YC%-6A)eXw0@csbwPyVxqk*-X3Gv9*Z2G&7%H ztV&sIuv@HrxzxoH*~8u57&u>^vNZU8X(+IEZC+{Eyl8Xd)%VL;#qQcsW=NNWT&OvO zk{vi|u>8wzdFJzE_piBT*CpiPTz1%!ccS@%&{B%fVx!#>dVs}b4ZO5~Z-OkH&mJ|4 zGgw*VUa9F#sSR7%_OaOdV!rm>B8J?euGhG2bouadrP_QYD{LiEV`VvP{*?T6^XKIw zpXDo`)$3m-;_M>#Ft%Vo-3#)%v0tnIwpJf5SJB`#0L9t^xzH=IoMGGAB8~b9u$-BS z`AygwBy|nPP;mRuqRD(-Im>L1Wi_qM4Eog~#g(mr+=?W8vT191kJe(|Zk2r7vVvvF z%*tvh#j4iz6)Ee=f!)eeLn}H9D_pE~1`2EB`(U|ZC5<~lTnZsCWXcV3>>*;EJ#{^e zJ=6M*1D2ewV>$Y4d!6TMofm6^k6`5)mX%MlCBNbZTF}sD;i;(?^*YPZpedk0tZ+lT zenX;fLn1a+XKh2{NmvNxCR_2W5bLI#@TR=trh?(-OZ!d5nO7s^de1D@RSGv%>o?W< zHr03{H0UBUu_CnkAn|_ncE(gYKAU=qTl$7u2KHNqZ?}x>ZGi&DBK$?ltW$TrtLigb z=G$8qS6i>KwpCU(&F43*g|}@Kw`~=-HSM>x-r9Q&Wz#;zlJg734&Qpyx9u{s?Yh0~ zcD3!kt)xw`?ui=k6yEVt-0@a)FoJ^(kYQr=>C!8q8lnhNz)nEl&ik32!0nw6R}Kso zL2T&`(y^&xg5Q|XMNr7aMzFABsPIk{^M1APevRUOt>J#1 z{eJ!1H}w`jISe@qEcTiW?d|EX9av3uQnzmsX3MY+kQ4`xh3G1?E^bE`!<3t2QSgVr<>ivhf|7&(}st?><@P?_bR?_ zy#3&iFfuUo*mBZ$So2^bXBmo?TRW7q#FV>nl{?umJ(>N}f@NU2H@59kL?`W7kE82$ z_^0q_um0$fuP19BguFVKQ*<;!g8SPCmROI^Qe6ZVA}$`VKh9xa*&hcQyMKg->4>`h zQFF5?e6y{&SI9FJ1kvjl_)Ix+1Y|qG5IF%U!THB9xo6gclpT#4@y}CFaJ2T-m5;AA zkD>i17h|Ef;nL9)?%UhP>ASVJQtOyXr({N_5U6D&YrAvKZCvILaPs0-`v?oN#`(@GPKp|L;;mkza%RN2Z8HTNb4)dyv@J~N4 zlp>YTviJC69|mp)Sd+odVxb^X|>zhi`n zC_q&y!UrDy8t&_rjvc^$g}{f}D%snuYD{|r=R>a?`>#G?-ykS&f_#@FTrb_yPC+@R zp!iET{dI)W8}zGhj^5}nXXA)@__d-owprG-M#HsD-?g2R#)pqrL^*)qN4{?KH^t$v z&#x=)xKE*MkkE3E$cDc)_L%u?n`*c(|F+d!__aUEZQO87XMNcgyn z`nNdkw&anor_F;zZ>VxTsIh&oTK-lvD9brUc(F&kBD#I8?CXmT(|&`UUvXX_tZi*D z+tfjx6#n*S|6S|sUE9vx;@sO{M|iNY--(;wB`Bbh^3F>;!p9HGmmcCv82%<*$Y;P? zyaT@g`>%$1(Ft@RMe1)m_CFNmzX>CskcN~n%J;bQpqy_1|x{hjoz;`#cvJl=tpNei5(#c~Ayu(nUnSzK*`$)iA_f zl6l)Wd%y9>*Rjzj=yOB*NTe@3w9tR&q>DdN}lgr?iP9=;nNja0~|Me6J0;ZpBYu= z^(TT|{tsVwJG>P-n0suMFL%AWQda~U;Pqq}2Zcf(wlXxqnNb_~GgmEbDTPitUNn%q}xT8N<@1VYGQAU%4 z8G^vnehk4l&l?#+@CDMpYJg5z|17f>1A|*tj3vdu z)So5Q#JP#Zm9vN4<}(^)o3bIacCgE&ul%ElHOsZxBsLL?ABWM0Eu)v^tN-5r&DWXV z`A5eHE=1D9_hyYaWRU@5GRhHoEeM=^Z>oM^r~il3ss%l$qZ6~Np6cdv!F1Qk&z^jGh9%W}-S`ssd_6yw5@W>fS-jMGsNS^l_tUydR*9YA>T?^{$6|i(;P}}p zFpTDIxv#bmN0>1ESWEVb6+fJ-IhU3?-XKK%4_}vKON#MUy6e`O(2)2iIIW|`E%=$S zNUfsoVcwr~}C`TAQ~fpN!;5{H%2F-eKVjq`Cm`9QT^%VkE975{zOOK!uYrPofj zc+#T3!=8Td8|FcnI4?-8FKI4Hc1wwErRc@_i2X2b7u)#~@F2E(SG+E=jWF`1T`&3B zF1}yZqWN|G1rHNztkeqBf72~uMQl6s_(9^N(@46x^iIf$S7pAvUGjWX0xfyrG2!S^ zEi5BFE{QSkg;-n;Kug`^sr4^jtz~_bzWwvFL;6~h6g{8#J;2WM;&Sn$%me!GzLuT< zxNPbOIGqq{wDgL5NH^6`Ww>B#F1}Y}H|<_!gyelLVF;w>8E#dif@B_X zQe+Ry^Quqk@AF9WA-x=`RZ;q_dE_;bz1+@K(Xa0FD7ztj{83dgwvzc&Q;|SQu0Mb^ zQKaaI2f$Ns9pfCOM7ye!aCBMD`@VMVwAP*k0}}fAPJ)?{v}EArTYNyQ_a>%o5SMLP zxBVVNKNAm%Akg-Vc0LP2PwSWvko-F#_C1VI|Ezy~;(2@!Cl1&UIe<2qtWK?O{a%g< z#|n0pBik0IsCF@ob+^@}$*yI(N-P<%6VS`J+Es07@5-{*t;zWF1S{8VB8uZNWc1g6 zd_7~t0V7c}xRsn|s$|Tky5< zhOu7c;!qewl4c(uze=lH1?jP|ArdQNc;6<)B#zZfmo-axZ4#3-B*ajLfF1q`y>sF#ue64S5& z0TX9QuXbH#;3S77h;y!!#E=IFg8={x050}?D5dC(5Z464`u_Y|flH9+Lhk&ivmv=R zD)^~lXDkR#;Tg!q?W`AV`W7Andd;UKktwe8Ha&z2N3@r}H{pdJ9EN{j86o_D(wh8H z->gt$Jj zseig}4Q|S|g0|WWo^}ZBVSEG&QO@gsGmocP-66+xCxL%@9&j4KuArK=bYp&!Jr&3o z%Ea{>$6Wys!jQ_JCks4c9j?#4aq!!pFuO=>>_P9bD+#E-T7TO*%h{^KA7c}<;+<}d zQ54@V24y!fp&5PBM|2GCdu9p9lBdNyDvU`|x28y|u^=eqOU~!o;*c>0__ON^B=d(+ z2r@l&uk-Ljs~C>#3HR+l7-CEgU@SEz)NOXy?>s0BTed~}(MzuG?utVns>KG??O8(1 zRkmbFn^EERY{^(bTXq10VufBg@pfnwZ-g~Xvo?a#&2Z;Gz3xn*VJN}9r}Hf&*~O<< z(@`e|uHK0emGhF5af09juKzc93a2?~CxPyH^VrAmZ)#7MW)q0cP<_(E)k&Xufk

    ^}2iPHLe2rHbnA2y^g#KJdIU) zKR~H|xwX)Cmf9h?jqccpG98#=7&J|Vt=uTSeTn%TyD_Y>Lx9UI?W=h?W#s@ic{ve-Q7?|}Sy+U5IMatrWc=-<8f z!`-1*$KA?D9OPp*W)OLd6htk(f08#ps;rG>PF?1HgBKn7SUbu0>*4ym0{!oNm9e(? zWfdeey+BQvD|%OGrKXmCI`@mw-0P)F`v3I0+?rML*##_D1qYX1Z!S;D8t zC8qnGn=lMaN8{Zi=xW$=@&WOUD$mF@bIA>#QCQ?s*gvCmv)T*lC1U&^zAl$R!qYvV zu6x?~wFag}*`7<;mHQ~zDOHu8q&}nD&ZWajCBaotqf%G}=Q7~_o^Jb6dH9TxHIH#c zm);_W`e*=#xz3=Om$~$t@jt!3ehz?kzM{M($70_LWq()=PtM~I4rg)BdtT1SNf1j= zjIr`->_?8#=8Zb)9>lYq$8*HU`~TMKx7N?=86Wk!Kw%6X(mI`HS-dB~UL_VqmM>(% zBy68AOl|W_7jG$SO&~m9G}fk~)tZZfAuhW+@V6Xid>4vrL)uYZVxe1j2AwbU5F%ZR z!E_)eMaLxezy!nEEKJ{cam66I3FW{+P;+UZ;JW62L3||XfD5DqY*Wg@mj6~>N*n2V zX(KW={0#Sh`1;;ps3ZnPdLokvf-5;lPT=vikSAk+;nD#3jzTy9fR|k%QeXri21yZ* zq1ctrQ_Kvo?3B1z2O{OkmMCOg@?}yB^fg%wG6zD9gPU0l4XbUbpa^PYfyPj`U?@;% zu7LLz6!d3Pq6Y*9AOSs30nCqAI9u9S8^GPJ4~L77Pvdp7RkFx8d63sPWU-X6bCbON%c#|H}Z@tq-4S+=A@sV493Du%ErC zLXa6VF3wUG+#-HIQ`z_v&!1zCVMfH)HNp-aBC%?_ZB|6UhG7)>6g00Lq=skCeOtH z^IGYqXJ^*@u{FkLFY?<6kj|>KVl0S4I}kD#JDh<+O_4k|TO9ZD5(Bp8ZQatlJ4^tW zOo9Qx5-5=_m(UIpruieY8w@Lc3V=E3=(4jtgUOieaG>mjtJz~#IKFN>y^7rV9KT~* z7b0%SDq{)4&}QfG--^>Mkl77k+1->W_@0od3s|Bs6Hm-sq0qBnV{6({nFrZFbW8VO zq(#YV>K3G2v0CiSw(B_N>uv&*Il@#qgv%Y@T4*Tmag=ZWD9`H+9br!d|4{qDQhJ18 ze=A>N$o!#fyUNfxIR^IRpi8>aPMaK~?kKZR)zr@` z-%60SLp92iK>#l8^5WVdio#pj($7VA9X^;Nv+4mteonaY`|rPUVj$Rgc-R1qPWh8* z>hD+|`{XE2Hh@h*+DGz&C?Mk|W7!y|vY~nV0~ZR*_2t37^%ZC3^MV##MDE+~)XZE{ zjUmo-0IY(n1dAOR0KW0#p#?>@e@9B^>?S{SE51YEX>-fuWCdXXl35Q*c#2{RIeBhF z(r^Kvgq?yJVdhm^)~6xeXGI?#fB-?ZFY9?H=eV@ml_Vt zk}QszovsPG7#FPh(y*yua%^p8o}&Z$$)DqlKChVjA<4MJOM}$4b1}Evx`Ih;tT{REfV@sjL}!!h#2okA)p{12I2i zckmG}ZV;i-){u=#65dnBy%Si>S8>lcPpm3fEu8pu6~;I`M~9Bow~F$09w`$Z;p-E! zI}o`IKQ*NX$w&UD4gC0faDfv!FdV7!8MOHr7&!pqRqyl;=jPd~3L$W#CKTXzKHdCP z`IN1iaW#kFTu!?VgL=epk)2K0lA7mURwT$-w6y#e$z#j;1~qRrd)(QvMx=1EEEZX} zyCRTc=@hsd06SX_q&Sgd`zXN6X~z>Tz=2)Ew@B*_l~1&m&A>F0c^Rud zBOr}C``1%G>PkRp@%Z$Li;}QL*!_GtfPoH^1!`f9kDCDxhNXg7L1_ z;B}oh@uonJ2Uy*Ky%zLYXBW78N(Mn-LAJKnz4cqpHErt5Ixe{f*?~uphUL?-V%~03 zUZM&gUM-=Ap%<^P>n(pK#jHTYuizLO?pTz(uj#$b2!(Bx-d>!PaM2Z*a|#2G*NH{Y z!W4IPWf=9g5%rFXveqPOX}(UO(bx(p#qu5?-Fcvtn7TQ?knN@KCae% z_1Gb+HjrL4*cXqB4#}F0i%Sm+K#RP`7Ns8d4Sp>ee*H;Iz|T;UH}rLVsNM}*gb3WB z@zXcaVi&&+&N=Z}EnkycwDc*_!i2nu|V)zmaT)<-85hyA3saXHI=vSRr1tDpuSf zUb^$rYM3!SOZ>;{Tg2=0*W+S&l$bx?yesN&t|XK&6ZMFNVp4(l6IaEFf8OS@^;CF? zL!XdT8MV~?RCuCfUA-t?S^s182ka){+bMnUAB4ewA}|W*8R8tiFN!eK?mS zOm~M`Vpk5s4}*v37iBUh1x)^hHb{K@Y+W8C6#7pl-T=#SDm4N92XrATuqNkuCK)Et z0`*o{BJA0vM^5~d9L|yzRqiA{kva%y#(85x*hp-0i4fhz(AzPTnnR4zlgf+~jV7hc zy#OWShMs=IKpaZ$%J?n@^e(>X*?lUtN7^$)51{bwrke{q@RiBjXbA6J{J@fOble5c zl=BilI5z77>$i?ZNNFBXVh{l&&Wka6xTMZnc9YtdNHJjpqI@UFgdqDpyJwB@R`L;q z&lHnI6RclGQ}WwSHzwF9#nH=#lZhqTswA=L6zVr6+Nq`STJLRanucn6_hw=o%^|9Tm14@>Le+nR)6 zjV`qKo)zX&X;Zv0Z}C0d{?(G^{<5w9Ojwvqb;&A8CKxlBVdq@YjZF zufjfeU%Gd9POYXkMtDQUK>NmMoy*p1OSXKPb-zj-b4DpgK5~S!-;ewhm@Xu)}K`2D4U*C;~&-6 z`-e;8Tn4HZ15_<9Jc9M&(wgCK>-Q>k<%a*}*?t+6Wu?#`VT>BgHs90Kw$kEhxJwOE z=(;~+6wxr8x65#ynRm$jY`EYgvM-oXSKfpr0v~fKn%1)m^O^M+WSKRJ7~!m?u~N(9 z%2O=)Y_#J4r)+j5;B?ez6{Rn>X6jfz$g01*fX?XG*Y9PS9rvWVDxdB2yf;|(2^9R) z7EvjhGY}|tG`A5aOJK5@prTm4Y73cso8z`4hWr|2>2t|zQDxfrI}0e)kn0^%=2!3% z`$y?!?kApw-TVYi(?8$Y_C)N02pQ(qKv!Z&`e68&>6;chRzh=2e_JDF8y2RlKQ$AY zW`}k2Zi|O^*>vn{KGhr%TWLSr-{qA3-8ORw_aj)`iAQ)}A9fRKy*llsa$h=)T$g4r zgXgtpIsdFWGV=-pg`{iy^ipu>Skv<^Urgy}{a*lHK%u`~_0=(r{2CW85a)n)*omeJ z3Pea`AAW4!-1l7nUMO(%1{a+@vsq7G`Q@2!-udTy|B5@APf7@&1#!x0r<*8*5M_}E zAgS^9@&D{P;;$zT9VDTlZ{Pj*;g4Vb`JIM_7ZK+8qXlZz`OPVQDs+K&^p1Q51W)i% z2DbBXqIm0@%ma}(KM78df)%vj1vz#yXe{Fz+Rz_0NGfx&9&V9~UG(A?!MK?pc5o}=7{^$8AP%S`@f1#UV_sM&F?Gd^R{pT!N7#3O z2!@f5ee~lW0U5}F)DMUslm|IR_>NP>;)HK>|D3>RvlGOC+12P6u3JtdG8f|{Fu@s4agLLm$s%P34att$ zp&+ zp~&hmQ=V^p=I|7gPmNX+o3MIetYWo^D>@{P2sP@!33RTq9QLuxBi=q`Z zAUy$R&vN8*AR5)DHDUJARY7GRB3(!~|5ut+r7o4JO)beevq86V#MEG?!dy*ls=|xv zl&1^vX(z6T%@@`ZqVw2<4E6X;r>>Q)ZFOr(>&FnO4J2=w%W45}Dm<>@^C4g5L`PRe zwTG%x9kWbCdj!(051nU?u;?psVbhPFeNH(%%jb$8Y4JEJvbJ3e#^{&@w(&I%11ONh3 z9Dp5D^9?Viz@;|+V;{@_z<&YI{{tpYmtnb$;>74k46t5AyPOzC)V_OwDY?~ zh~Yw@aexZzpugU3_OKvRdjzl@U1^SlV!@Rf&6vi4GB7kJb}KQ@ zvQ;~t2tHphO&KU+6U$i0g_9g-InSBS`H@XDqJV{fePe{;sA@f~{EqT#J!v{}q7&F<$O{Gn?H6QP z2GhO*1`dGXQE!{u-S)OhWFrj@pgJ4hSaqvU^=hybIs@-0&H>W#3JRoPAH8l^bqh6Y zeGj`0ov6g_kUeHv#%dp&;DoaoLhWfYW&qj#_QN3_afwT$Q^qKYp24w7Kc5QFahi1^ zUu8mS*n3xB#%N;popOB_dl|fQ`K{_m)OoOD7@SZ9LnMHLYDWMAHJJF%fgbd2cWM|+ zc5*hLyzzYm@E!Z;IIjL74^zO1{}~`&(1 zuJ3+V0@;E+z&yH(8*&H+8gn4T733az(T`ra1{&{sDFA{{sDm7)aLQZoD*z3UqDI}g z-2g^l25~?=@qxlOkF*|<$p2vSRBIXS$}!w*sO3r(UIFQ$AARXJ)mqrn7DK;fDlv!U zF4mDy?{j5xod%yG!~a1g_6cEvY>>jYaKZH9AAk81bc_Pa&E3G|QSfi=_va!1Ma*xz zENvky>;Qaj{tz$$6|j?_>Hx6MW%4g!_OD#TPuL!>BO;Fneqam~K@kpQAr5c>MQ{X3 zaEDHYAQtKX|EOxF^hRbTkYV~yG5*gZG*AP7z^6R#`ATpHd9VlN$7xhy6BtAlh>#Xs zffkUk7KTBrUXTJ8?|iT>-!3pDe&7IZa0Ae6nqHs)LeK}j@C(84bev`r{smwHCL6W| z9BQEjoA7305ap)OBdYKKG;r&901ID00%D-y!mtnh@DJU_Kt_Qr&=4HfVK*R(YSz%M z+A#c{u!Vpx4r$P|C^;#4geG-t8%1F7;CE-tquwsPYRQ<74NX84&V~`kQ&u-9obPz3dCPP(HdUr z0Pv3+8POYO=P^pQs@VGP=UA3=f#E|Lx_Q5HRNCTX%JNh2X6 zhH~h!A-l08eJ>StYmQr{vM)~ZJd*8Jh>EC&Qp}3-C{wZx7=kG;(iQda1qdKMuJSJNGA~O4Cv#-7 z|3aSiB%IVt58xI5 zkp~9A1~79_b#+(a?!!V1@9OJinELSNM*X!HQYR7_p*3Nf)f2?9`g^0aNz@O#Y!BSRi~7CRKz(M6lrj`eYvt_7v=4>Hve* z1}v*ubzMJ#M)hr95&hVnjgJK6hWhG%r3@g+PfR01f;DH4a zK^*czA9MjzFE%V*E!Lpp6h@>BuwYg1N?q?1R{1erUD8%r_G+>A(+s32%s^XIjn!y& zX;T0z{6QXgfdg&;4IqG0;h_X5AihX}JG24;j#XA(ZP()GIH-6-DM^)+pb!A5Cs4gr3O~5Kd!1zmH zX$)$k_9OPxU1!w_f8Yf+;0DrhemS^<*-9vuVHtEm0k%NI|0X~~TyGang&P8xY_S0Y zxWE@&p*6)xdK{@`Z2K@kS8@D6VuzTtFPE$U+70s3GWUIAP?)}{tGg4xvyopd3p z@CG)3cyrZ*u{etls`~1#0=Q)L(n0T*$R40$iRwZgOcekIKneOpA6TIT06+n5pilfk z8g5Sn?m*J?p%LVG5C%*is3+IBK*n&_NQ1Ia2sb1u(G@c|gSpUNwK$R`8JMi38RT&t z?ytVyVIENBR_p@iu0vL+!&OL`l*2*-RppfB^NpI=i9KQl2*L+800(ejmT%wydJd8& zd6#+Flg21uu#aZz&1xFvvR1j7Ab2EVm6m6@mT!3=|8%*RrFojc2&zo99_z{lOAh>6 zxp(If2WFs|of!w7nVQY{oclSZizNcBQF=@a}QSWH7!Ou-okfPj_{KnMEDqI1YipDRe?Q=#Y7kew5e z)%TTwV4qD|2sXfC{uaLp@AA0s@gSLAAp=hNW*4`m$m$qrm_t!wWPQ%)s$9lKRdZ#7Z87VrYjk~?w8)>%o z)Kcx-!gegiHZ05*ZPk`--4<@;_7Uh-4eZt^-a>B$%@X?dZv*#%b62M-VWcU-yh|Di zO1hs<8l?~5r{8_+ZcDRQP zujzug@P_y|j2MZP*tS`eER#*s{~1Ea;XKYQT%R`p2o|Cem3-B;ecK_$T29Z4Rj(b= zA%!=&j0a4s)tHSBz>VQpj$zx5DPREb*xmNHkN-H3NA;MS2-C$((wu!DJpI$9ebhr; z2rL_ZGo0HMe&M5}{?M=-%%Nahrjwx#lzAsrs^e8&#gto!QXZ{+da~CW;S0bnp+4=^o;BWa zA!KWI?CYv>zDr4y-;=YLF?;O^zwlARx#}jS6I$p0LF*%} zA-cZkiJahf`nM^%mJvRn4S(}FpQTbp6roF27GF;7{vjfbAH04d#2(-U|IVAf^I<>s zal%bQlcVF5@$tg(@7^IIpYH*FAjY1uCwi7=Rr6*4_>o^GiW*UEUvEOS0v_NFfL1Te zHorh%zaFymBjWT^zah{%;V=90XVvACzx>TVCE{AdNGw=|RD?jl6V7#sYo_m3tdRm! z_bDRsQ-1I1e9i&lz<~`yHr&`yL7>8g3>!Lp2r;6>i4-eZyofQQ#*G|1di)47q{xvZ zOPV~1GNsCuEL*yK{|Pgu%$YQ6+PsM~r_P-`d;0u|Q`LcF+R9`ocA#4nEa^;5*mZ!P zKY!RBK=LOq*3)}`F1+LS@1MS|@BGz^@&#4FzUolMOkKWI&BP z_RP~8R;EBe|4mr&e2@rOQLP1!4QeoF$pzw22V#gK+J%>1*6`(*c7m;i(RYX`R$gS} z34}vq2My3)jymqhV~;-m2xO2#4oPH@Mv@lWFw$@^U^d?zNR2%L?c(d$7N2>NKT#vY4ovdS*YY_rZj>sh3-6_o*jXJH`@ zgT3t||5a6_0{7Hgs+#(otLC2jkDDmcS}R=>5oV9B^{|t1{LJv)J(MAU;Z8FOoT)_Y!gwhT>pYCF( z#0R*81_d2pE7l`kt%cPqQy>7sDJGxIs=9EpTNkbZz06R|Gm9gRC%^7VkU|L^&3E5^ z{|$KHf)7skL;pbo%{2sqQ_eZ*bofq#Q-w8^#1ohC#i|`!j&|oDqO7*8ajHmI>4dRm z|9W8x!5vj^xe9cSCpO!w-VKG{j(hI9@6LPgzR!1f;@PZoz&Pf(v&WeB_*Qva{=hSY z*>IukdG*qT-q5Ua0>M4^Y<$m#CYqQoJ}~B+@6Q31yDm^W<$#lo-Q(GK00zI`kAMF9 z@6Uh#{x>9)WFYPuwgCq?)X@&Qxvp}Y1DodDLOttA@Ks^K9z(RJqV8#MgW((B0mQdK z?ukzzzR<)RJmHB!bOLV$Imq7r2g4Z3aE3Ijp$!ccDS<%a0M`%*IL2{~c4(_p>5Cu) z88X2n*2RJg!Ju}4p$RsGaEd?>A9(PjK~HFcZYZ1#5O7AB8;Ws^WGtf@&xpp%{|H4P zid#oE8Ye_fsc()HRH7Z-1*&J%wP(0n8XB{CIylWg>+JmMKmHQpE#0HdQxW1gr+^Kqq4QpDs@q*CSv@U%_-KX z60%4p9L_KqMa)45?QEz+9}3ZkO4KLE?4dw_7{^bF@}3-J3+VE>$9U1IROlI+xsZnQkw42I+*$MdksnH z7rzM3$(&&honYuruZq>IYIUn-eCGk;2~>KnZm2{3Xsoh_%D_x-A?J(Y_ckbyJaLa+ zK-d5aUC7nE>UFPt?Q7sFst}CMbB-G&D_M)m!?XgXbZr%1`G8SGewfd(;Nu;Vj4Xwegfn1dHm zDw({EcDTeXu5pj6pPqs>qhc+rYB`G7qXH(j)Rk@cQ0NI+_<}&$|FDKDM4?bdbO5>J zEw6dci(a636&ychE^429Pu5N|gVn9?23cCmGfY*XM6dy7(hJ}K3wXc;&PY#_DOhHX z6~52~scUHkSMFsqpj4#gQ)hQC^}Mja9PY4(KYU!}zVWp6WbiZPtIzFquOc#P>Pnw# zugN$Pk|3_Jjc<(Ot9sS6?k%y2?HOIg{zZcx$x~zEI=|rJHOEYDvXh@2%+j`Zus;5= z9Z?)o6-yYU7jY^>(vxH;i+RjsF0%|pEKdbH*UEPcGP{Vp5yf1VM)Rs`k_}?!JnMPS zd=}h#r>y4Gvbl3uez2BXOc5C=#%7JFD-;+lTwnHi(v+^W|D~UGU_b|T(9d);gyGB) z#*D|QVWbS60d?tAt9sR}J`$QqykJgCu+SG2aydZFVugqr$xodh7;g~CRttOB#4a}Q z9+Kcq%eu`DuJxN&T;xVermn!1u|Ya(>}+d$+uY`il#|_DK`$F!v~HrUaUBsvFJ{^{ z0~XFSyWwujd*1Y}w@O~!<5-Vdf}TFKy3-w3fsDG&?bhs)?Tzq+D}3P-`7^lRyYK3i z`;^b#a-z8`?b$JW;~eie$20x#Do4C}{id(QA@c8a)78s;!n4O;4)d6+8sAjb_sB~& zaig9a+7C%NV}QHpBlD`%@s_#KkB)RE?^x5}zB#{}|84GypZwwtam+%-Lp$3ged}EB zI)}dv>oq&wTscpy)T2Ew^8Cuq2EiA$y$<)d%RRI-5A@hc4t0uudg{8K$gb<`tH$u@ z;Bzm$;SaClhOjr}HotqT$}Zg@^Sti>S9y$l6=t3xe)F8~yhA}Ac5yqNO(oY3T%(;? zccX{!o^QSDUr))pD|_^0mu8Ahp7I&>9Lc&r@~_eZ```n&P8~Mo>5#)D%^4vea+IqUzK|+B2^s9gUev^IEyN|BrPq+EG z7J9EAqhu&lmHqthzyAZ~aG?i(k7s*XhI`M4|8ae1b(v)^<8%vF^?wm4ffHyfptpUZ zH-OY3f0D;{8WAH4K@ef!3CS=F4@iM0h=M6NDDDSw8K@@TcXsPWbwDR{3ZV$surwtI zfhx#@J?MkUg=_-og36b7Iwy7F*HjKMYQEwHvTzN}01dKXfhJ=*oR5s%Y1Y!-)kb|QzELX^eZRm!e!Ga>kg(9+nw>Ehgv1^M41gHQ%1cW%l zKnNu8c5g_Cg=mO05r7vshu&9!hIW9IClM_cBVM2m;{ZS11r4e|1tcJdhvUuig;8(MQC&j!guU1%z!-UU*nyGA5Sm~Q?a&VDa1NGu3n*ZY z%}4?SP>a&Yj_r7eS!j3GC>>sSXfkLK#%K@kFc0Bq4&$H*F>sC~5Q~=KjsNED8~knbz2M4 z4wrxeF@TZgD3Ahi8PE8UH;I$%H;VB%lGlTc;1`D7SUOY^FT?N#FbR|AcmOkb0P2{N zPYIRRmyo46k|k++lP7*D=?{eQ{~P;Y50|h5NSTx|AP`JBh*61_X}NjSsE9r3lV{~@ zUl^3*Q#w)F`$=7 zc>ph2mV8N&f~lFCnRHWWn9@`4dIv!WDKd9nyV=gWVw`>c^R^4oX1&jJ6V{v85g+uZ(7Nfkm;MMc>uz>5azfL zMTeZ*$(^m{nap{cKN*ABM3;{_6?i$FVHuVUA)HLvo$m>stHzch37!loo{Kq}yD6RN zshaD_5HjhP@hPAKx@Uy>|9av^{8v*$(yH{p21n2?0K0qX_Ewsp&5!}--)1a z;hX{io#yEeV9B2gVV(bpnF67m8p@(AI$*T9oCs=_%m;1dDWVWsq7r(d5;~kN>Z3nO zV9I%*9oiPS8KS(&pF7|XJIa~@sgXbmrBRAp97?1!I)7DEn){ifCOV-E(VoP4p;9WQ zW2#s4S(`+vpo*zt`gxu>I-L-~qymARdPAmlYNuOepe7lirGF8rBbuZXL8uhk zqm~h-o64%KdPze1|EY{xhYvcb6=A7!s-mu{tGilBiz=ghYJ{{BsJ?jslsXZo>ZKLR ztINu)T@{3F$*8~@jB+v+Zu+JdajTfxtlP@1F_forSf8O<4!v2c*xIFBnySUwt?SCJ zzvHWDT8EQrtmf(vxcZmvim&;4J1{z=pen7|xTP6^tmx{V`f9KT+kOl|Af5`YL>jNx z$`RS>qzFr~6+1NV3ZCK$u^Tb43Sp?KYOx_Jvi@SGF$%BuDJR7G5!srZBkQs++brM8 zi_EF9DjTuq>aofSvpdVPq@}RSMW4~ysPm;AHro*r8=yU_v`bqk{2Hs_`meTTv>c1G zJZhG!%CuRl|Ft>-s}0+s4~v>0!LoF^wPkCz{eiJG8@22*wHnc}R-2+{E4Oo7A0^wb zvWl`Q(zb5<5CHn5bPKqFi-iiyV?n#8LwkEgo0=3>cYrDgXxwtD4Z|k^V>buL!y!ZC3h8wN3%0TKfypV~ymAbht+q~P$y&)m9 z3Tc?aI~591y~KM76uP>p+P&+`z8V3%;8};4U<~8i5bIOEBYM6(+7N!*zWwXJ65+I7 zYnwH@{{xsS5%=4bn47+j`@aqRzp)Fx%n7!>X}}LrzC^ho!=MQHE2o_6z#rVd@9UNX zoTL@(5Yy|G@e(!VFb=n%2${gTAS}b&YqwA9u(TT(Zd=pUm`jY% z1#vsWN$k7dOSODlT|#U(7i+JeT&bRs*XgKrGTkqg01+>;YLuVPH8=_#27 zd&&joT)O1!$-k`4 zmRgxl%8~4h&-lv9atyyX3>bEtyAUz4Ae+wx-L1RKsM)N#5RtS7?a6j})=bE~sL)hP&ke27BfY8OJkFc!sA?L|hfK8<&5ZX-(lL#w5p9hh&9@=F zyE3iQcDm2kyv+Xm7XVGK4q?$-ywgX`q6m$qHZ8D?+m|_w)KUGTG(D0NeX}k-|C607 z)mt5(9L>w{thn;L(0vQlTy53^YSQCu)h$iben|jEeb#Xun^bLzOdZfTE!TP7)z5pT zc+1JbTFzp9)oq>CdTrRpsnnXh)=iDqhwa$1N!RkY*iDVq0`b<5joE?e)d>yOIc&~j zU9V-G*`xiGX)Uyq9ne_Kms(BQt?iDHJ%@H}u8r;5wSAL4-O&q)+C$wCMQz)^U66_G zuZU}aVa?Kv&CsF^+{=xNu-%KhZ4vbBq^r%`)t!r*z0{rk&z}v_$!*==-P{U`VAXiq zKwS<(9o+)$)^H8p?frw!J%qBI-n8xB_5FspebOjRw4N>4Y~9;0&D!=Y|KKMm+`mfP zj%eJBOWy;|;64c7iwNDes@_j}*$r;tD2UyPZQkf@s!lDZ%6;J>-hZYYy&KNm{>>26 z4bvjd;{5mE87SWpzThoR3s2+8xvO zOWswk=y2-c^$h8m9&=xQvVT3TE3LVA9^jfz>f46s$;akS?&hV=|LXE4=jH9`04wN} zP1udz>bLIdd_KBgJ>)7q=Aga5Adc(9E^MbhfR%3PqE76~UTjou;8tGTSgzn(&g|7* z?Bd<$K5dxDKB$b&fw&=dG_ih9_vy&>#0rHP@eAduI{=%>CevX z=u7SN&hKS5?%kK~s9Nja-tPtPWX>++(2n5JZshxJ@DHD3oPNXY&bIH)+bIs<5U=qz z_V0IB?$~?o8!z$!w(elQ-`id1wEo`|?&u@$^28P784Kv=ZSgYh@Gp<^=+*JG7x2ld z>^Tqg<%RGv-|J$|@bi50L9g^MkL|mT<8+?o@V@f4zVuZu|5`imbRTc&A#e3vpI0T{ z>0u7opw75I@AYTDS23@)ML+hx-ra28nW3*p;x@ArwfN!gy; zi>US8&h>wf_z)%WUkml29`AUb_>r&pbbs#&-}5!;r=mhq6fAWEz@=}lSEWi1s z-%e^jz%$R`s-EIcxT>Z~MYD^lPv1M1J(Z{-45r`@ug+i$A**U&l2s z;bq?P!q5CQ6#FAr_)B`}BHjGepGkae_l$4+fgSZ1&-WQ`{o(Jd3*l2vpWSSq_r3r2 zp)LOHKmH0aJeUlTYRpq2ko$Al(RjgUHX5F{X*f3(l-k>mug2YO+Y1OV}+t%${ zxN+sqrCZnTUA%eq?&aIp?_a=y1@~=9Fk3d5GHKexsT1jA$dM&a2FlbaLa0OOm++g(Bt!!+3#XAh9AP-F0G*s*2Lrd`|iZQQwa@8;dx_iy0ALlz#GZC$o=cF_6Km>oX4m<6(vudL84tV3d^8`wbAOdXYZ$l0{^zcIvLlkjD z5=%7kM7jPu0I|dbWDL9nW0Y~arJA}9v+Nqg3c?4CnQ(_4DilaP6pJ+SNF5)pb{1d-e5KV1s2#%HxuA@y`NN zRTe=)S1qVj?G%M5R#|sANK#?5)plEMyY=>4aFf(ipi-?&c3E@}be14!H+vPLH>$N3 zAvIZZEnIx_)puWh`}Ox-)+c8c?Alxto6>S6kv=q)_7x% zJNCF!VyQfqK!XuBIkI&JYL_Z$7cxd(AQiIp09-$|`DUDR)_G^1d()Fof=NDk=%bol zxXXqgY>3)w519Ab^?H_iYO1TY`f98<8ns0~g(muIqf!=V<*EL0I3cDTZKz&0@6Gyc zxZ{?4Zo0h<+1Rd61$*zLYP{^w{~V*`iJ`P(Zb(v#Ev{pXy%$DH~n$XT+Gx$6<(y@Q2R{Jfh#$h1b>M>+ zet6=G@96HJ^_Kl|u@4~o%d-pI{gTk19$htijn{sA?z{Ki@tt;-#seC8bueMtk)K+^VxOBmxS@mpJaXjZ@dMNonh zq+kW@guIa{4}c~!AH!UwGy}rSQSMtH^%U|u3#L$oD`a5{KQuZ2d2NGWYu@wJ=dkL@ zY9O*gpfS2)5BJfkAZ%-s{|k+HL?k9riLEOLi(;t38K$d)Nc&)Ocqcl8$jW{5m`6K? zafvjPW<6#R$idQD4MK>w{uWVUe>#X%xVV+yoETx0S-lE!XN}- zV<8QBNJJ)5R4x&p4C5$8znyP$>BCCltj7>Doo5q@$i_9U;R;4{A!>>wWhqU0$_Vx^ zd2oDWy5>kpM&VH+)}l}v7{Q2TBx4wazyJhM`Ac91Q<&guVzE|vu2w2*iUV|&B`0#p zA*qK1j3C4cHn>=_J?8M|aI>y?Shq1tANkcydw1Own^JKgzCc!tY$Ph@2{ z2Ng*VYNwor;|Q(V|HICB22`K}C8(y{SUF_cQ(5C|5X?eCMm7~xq7$WPMUNCddL~q% zSz6{Ky@bV%l!gRm8Kp%{dQz08bUv!gU_CdgC5CDTq$2^SN^N>moaXd32Zh~BQPok~ zrB8<-5h+9~pi`tKRjEsDi#J=UQJ-chrkWY5NFZuPre;;ETjgp+=K0O21`4R`qN7x* z>XD*4u&ZljYg^gM)BlB4RRZ*AL(NGNvJk*+ZsluV{fbhIf>o|q8mr36T8^`ZG&M%u z>t7xFSje`MrEi4lU=uV|swDO!SM_CNJ^NYEA`-5Sv@EmmNky676|IXMDa{%iTG+-` zwnlU+Wx-im{{&%nDw-8ZO=tUC;0AYpUw!Irar>OYj_t6#)ksV{Xmj@i;G>;W=@jZwJSeYJJQzbmAvz%Z+)jWS%exFz0c9D zS-VS9`vzFR1J;;zUAkY$B-eS%{qIJc8&LvBSi%$LR&Dc(;LB>4tU_&YNWa@z3Wr$4 zBgPbQZHwXPDA44c7Z;_U?WV+mBOfz`QXe~3SUHxiUW8}!BF11lQ$YVnv zTGe!JuAN;QYhVXk*a^vUTxL+`SB7-B#Vr&SFI&^_z4N;5eQz2^``zQ#uwgm8>X0ZJ-vcN3 zfM@OQeg7oh|K@d+;XCDmM_l6dEjDQr9u#u3_}pa#@x(p;@!0D7;y_tAcLDBjlKvXx z|0`#CXu)mlkyobQ%4ImSTYht#|FzvPkNH1J-rj~|nh`}pY=ak0v&{&lcdwBpxQdZA{%;F_OA;9+Nb+a)V%!Is_U)$TD> z&3%!fyIt>l-{#9LF87Szy~R=Id*KbQ$esUvKlV@YnKPv!{LjEU)y@@3!<5>3ZaA|9jvU z&+lYc`s=sOk+lb3`OAk~;)$Q|-1`^yT-P@9t$+Q;-Tv~%$1CBn|9$XV4fN07|9AAu zJ$=(d9>(EkfBSF7dN#ZM?AR_z^4))b`~yt;SjT+Rf&S3y%Rd1ez<(LO)*CtQ8wt)L zKn83;aB;o^6gTtJIJ{Fo2fRQG43_;Xy96`|`^!KO48am(BtN^nxl^xvYP{p)y#N$J z7kt4>fj?=xxDI?M?}I@c%)uHn3}ZU4%bUR6n~2_9KOHPWBRmlUj6VdNKY8=OBYZ+A zM8YN-7$1~7AVfbFd^k>vLN4sW4cWlrW5TqvsvGn|Gdx517{3UdwkupgA+$g=j6*pT z4jDATo~S_}n?pU^!`%Qw=<7d!b2H?QkOWK710P{dlaMP|}GwNplEoJN+I!bT#$cWXsW zREKa@YF3&j6Zz%u+sblgQXtVA{xM*34MW8}nioJVzRB2rmJ6C}leqep(^ z#c<3 zC+tb0G(w0p!IFeWf-Fj=gu$8Ix0Z~(muyO^3_+1Z%77e0ldQL@>`Dh*$x#eSXdFtf zEK34>N|MaVj#SE%G)uS4zn=`tal}NSv_V~bOS}ZXqx?a&tV_1!%DfCr>qAR%i^`7p zK*3DR)VoT)tjWy7#chN*#hlFF1Iv6AOUNX{yQECc^gP0pw4_`}IP6T)wAm$MnD1{L5qfP2`k1%iKQ9 zyh%6A2*gZI>HN6dY_rg;GeVqB?JT;}WX{xlM@O8>?Ho^#|AWn798Pj9PSMm!@@!9! ztIkr}&5ejo_pHxn3(oU2yYCc8wyaJ2{7-dTPQYtU-NQ-K>rDVnP-y!_TEjir%*?Gk zP6eINVC&8S-A}E|LkitcVKYw$MNhg^PwZSu4lPkvgHK75Pp(5y6K&Bn!_N=Z&-Efs z2sKW5bWt45GXdp50+qh!#0dJ#Q6U{N6wR^g?6vG1QYA$*3*}J^^%82yMe$rxDlIY( z?K$&f6sP%7hZw>t{Zb+;(l#TvtS|=Z;nIi*QZQZ90E1C1eNf!liZeyif;c@ky;Bj} z(J*|{D#{71a32FjClEiFQPqr==rM>gJyV9TQ&4Ty@H*5aBhynwh(B$VRUK4U&DGCx(@~Yt z6pYhLT?jwDimnKvvKUQWP1aDg$7@_esO-^l$b?J)A&3}{(3poy*aRU$2v1d3Z*41B z-7oXg0dkerU=`K}xe0-22XQEeTTp~BGKeDjR(ka;N$ojuBUgRZ0XLXdhlr4YP=|9U z2XHtHMu>x`>DGE(*rgKH#e>tS*jItj*M1!apGydU6$o`OhjAF2Yk-Djpe7O^q>f`) zlSMiPML6%I)DYDSi6w}A%>;`*h>SgejqTVK|FH&;9fo1Jg%H@ulMULW;?;*GRU3NQ zfw-mvh*^Kd)O00?n@tF%6S^f)HD>om-~5S8-(7Qgzw1RokT{*NUx)x5e3PxDIGY2D&|5q;go%gIKB1 zTE1mkb@%%M-CIHjfuLN~-CeO`))Gv}to2-saDjm!f)!W+Eg*!#bv?W)O zZ~+xS-a^=f0|46Q-Ck6(+a=^v?SS2m|5$+o2muuc0R$*n?p0{VUIfcm;k94>RVvnfUthgNs*qofSONMa-~LVDQo7o^{nd!w-}xoq5Fmgf&|U?; zVA{&u&;wxomEMssVDe30^~GQkZXxg8NbuEL4<-rvrGOHCVKj2z@?+d`AmEQc02t2U zB*NeQ>fou>VIYpD|D9p@^%5J_2m?L<1P)>*UOnH%$CY*9#)V*y2muMEU<+0<2i zVLlGzL>l5c4&Y~0VKDxPBwk`c|88X9Vc_rO+}CYmj5&KG))Do_4kOAh6SzG%BCWrL1l0oLY31_^Y=XpyckST^ON+aooSC)ahB1u|Df>(PxRIVLZkNoV<>kuJpg<@)Mu4r%OYr@VGjRwYpmf{*#XlKsq!hUSYDQTQO zX|ujz$i8e7@oS%|Y|QTL5iAIxne5g@=}J}UPY!6$PVEkv>v!X9XU=QYj_v)>>~I3? zFc$2mmTlekjj3+!a$e~wcI@3A?v;{k#D3FYMr4#|Y2t3~;Gpe|a&70HZYc!qW@X2< zPHxktXeFj@@BR(e|1QkmChAKz>hC^p+koy?vTcA4;lW04_@0g47VoNF?7I$bIF4`q z=Ck6U!sE{A@uubd9`Ho0W@q*7`fh6iU-0-)>$KGFq2_KzW^f9}i}0Q{>AnbtHt!1W z@Dwp{?0#_4ZrSZ_YTWj46bHpVGwDfHYz1Fv;ZAWGPesGKg5zpHaf9DzR@wHHI zd&+PhA9BHP@KR&%okndUU-C98=>Oha7iVmX*l@jOaw}g(5Fg1SXKN|12&cYsFh8Ed zzVTCz^7~%p7!Pwbzlg5R?i}yjGxrGQUUNFfavr=fGKcbxwrb$6b3cCzBL__`kMoRp z>pwqqhq!Rv{|xYRhHXTDbc6u%I70IAJ#k3Cbb^>~3}^I_2x(0J^fni9A69EN{j)pJYOhc5F{{SI=`;=k(j|?risSTaQm~kKppI@^J6)Uf-Z! z--s_y_b?~+TQ7I4&Tn`Jb7mKGXSeS@m-Bm9^L39ST>p1$4|G6lcVY&2g1_={Pf>cu z>vLatCJ%V>LHI%sc8T|Kc_(*czxKwq_l(zgvtRIycleHdC^mVC@yG6ZRego<`qlUD#gA3aUuZ|4ed;iYXa2!f)}U*Zb#R@|G|Lf(Y$b z|1bICm+iLZSb#a<*xiOe(&~o|J@lIfH)wq z+<|uU>>b#5z@NYa{~kh&C~+diiWVfI z7~%khm^N?X%&BuH&z?Si0u3s3DAA%uk0MQ~bScxOPM<=JDs?K=s#dRJ&8l@P*REc_ zf(B02f;=Fg)~ zuYNuI_U_-qk1tkL+K}L$i;RxlI{*H9wa?a_cegneLU;!da6}FAG1#Dk4?-BBgcDL& zp@kRXM&D=+m7`8b`uP{4h!n4^wgxx!pX z=6D#AKXmOkqLD{t_mONT(v~8DP|bA2j#E-urIlA=nWdIna+#Pb^^w*Pkf|+1B$8+P zSE7>JHCdaAUBVfsoO9Ayr=54=siP{;jMi2;=csc~LS?RorlI|r*b<6v|2~RsHl3W2^fkkXABENp8AD4?oMh1a63%QD-nv(G{sZL>PmGEz3#taHGaWSS|gw|14fq@ryS z*633Nv?{H->$2OfyYIs5V71L1u+DRUez;Jf-}1{*q9QF?u1ZpsPyu4`B5V`_2vmT< zcu1|V0tOfiKtKfpATU4$1YleNf*K>nvB4jYEON*olYDZ?D4U$J%Pqsqvdk;ftg_87 z&wO*tHRH_l&N}DZGtfQ<{j<{29-&iu-A%J z46?=(yWrD!1|ER6+Gn$!cH3wlaQ2Kk6mh^U2V9elbDS0=sIU9>8~8-wvWe=k1;%Y4 z++Q=UQwWcTPzNKp9N>y7mScXo=9zQ8x#qa2B1aq{jX;7+B#h7y>Z+$M(CV(Ye!%Op z$3DC5wd2mZ?y&Dpd+)dZo;&Zu`%XOY#tUD(^2aZqJoC>xAARuCBTs$v)blesc_A!{`ZH3|8k=Mun@HHT;~c% zzylgEfe2in0vpJ{2X=0N66{f~4p6NF45J~*;M3jMQku6M|3FZ4>6YM1NRfYqBw#2x zTvQgvz8Bi01doe@AY4(wpU|R$xuS(DGLeQZw2Yl|aAr}o<-gcpY?~c+jE>o{ZQDl2 z=-9Sxr(<@|v2EMQH+eH}-kX}LshWT9sav&g-Cd_@|IRvV6}gat5x)#d43guqM67BX zJ*R1iQj?)ZO52cO=4uSl=s8BJt&?H3r|~Vt=OG+<{{;Sm9bmI7b}bGfhRaY0|9L-3 z$^CanQN>U~SVutsyGjiv>|dV=PLTZK@%APx8pW^QC=OH@1Ur!jMZZ)J1TC^meiFgJ z3eJ%_LwHcofe-^pfmoquK+76TpScUFGVHGIj*i15?#zNNM&asgs|A}1TkNH z=vEG|FI|_~Uj#*d?iOWC#+E*=L&cVP^4DCLEn_x|itU05?T48H3CLh~j=iD1b?*6F ze6JP-x8f*)Q}v9FGTiilfz((!UkyqCml^bxnmnS`UCwKhndG}i6emi5@+Co;{I*26 zPtB~|>(AqFSab=YWEeq@!DVu2(lb%4VkuYTgZSd8{|f%1V*kE26RFcwijJ&Hb~DIEISFpjvdm3P28ctR^U z>ZBc0A8c)bV3iT3lvCz}&OyO;`xKItbE=H)vGh_0Qn{T=E$_yK(NgCsCainon(nn< zYS)g~l?Sqd-c62r_lfJ3*TLH6Qv+wueKwQdMdjA#$p^ zHnd1v?^uYGYt)JM_T^%W#Y;5@8{#OEaat?!ux%Kx&Dtt(0LQZ2mgV2+Znhxj@IrH~ zlcv@z{uRb+! zZ;PY&&{yPf&UsXfLEx%ouxHi9F%u4Q(fd(fGTg@ZU37n0paV(_$u#l0!n@h}bDCYLHlsCtl&s1~y zEv9rTm#8&c`sq@^-hHajsx@Cr)LgFm<)FQ#wb&lRUTYnFrhkUF+%4W*8&s{YQW$_5 zu(>UtPIyeu%ey+0N||7LB|ecsd>RGiUeW zZCd}QB@p3bMJ)e?xxM$&646tue&@OCmG>s-i0HZVs{7hs{(TRI_+>y|;4bybXOENk zb(%@wA(`ppO#R2}ioTx@lfTVkA<4VMzh^3(BGX?C<=pp1Q5+M$oRKHV*>?%dr>7B7 z2X>L_A(U+Xz13o1iz1Su^s`rOMQqE$6O#1i<+3a2A`)amz>6YUWJ7jfLq$SD5(Pkt zV?z}LK!rj=TNywnq{47O!pd#Kb_B!Ok-)bE!$%rGl^D2(kiaAuK#p(2^&22;Zo?mL zLtSnoxEUadlK`Rffk0AZtbAl5Qj|pl=uZ-)FEJ{aA$kW123|e}t0Be|2?8A{mX_g{ zn<=v2HoDV}jK_9;yLtl)I9SCNSj!Fwzr&EAe}`b0)Y)bwr9NNc`?i}RHk1*GX9N*3 zJQ)eF;1qS26wiokc!>;}jEvQYRG@&Iqkv4#h(d{sLd}TEXqQTwj9Sl#I&hadvVbz7 zfGX68){BfTr+_wwjK0E%o@^KK>&jFlac)^!B-H9RI~0-|BgRKErix{n{T*hsFGIaO z7BXX2x;<7_W46P5NfU_F1sM(x&5=I+9z?kKB+U;`gwJvXBe*Z+p|MgM0ASU(?~uM( zW}H@K%-c{X*tExP5=a)VFOx?~#)=(svL~}{Om;~AcKuz-n(@V=Ocp)G9Qr+x8*@{v%@IWQzKr_-*%Z*ag&s5v%K)Zobr{F+q z%2Y$oL|$Co-PPd7Yw&!!>h~TBOUXh5XetAaV8i}B12QT@q7ow>GeZG0W8p&+X){wQ zv#;ldc9G6$(BIP_tOkjNf3MV%U~JpzwBBF#M$jvVdO5izKpDN7;fgu8PXeHRaTg7p!L zevxHSaOq6&DU~AE9N`d^DNvOmG15rI6a^(1IN==!Nz()>(KyOk1RIrwSXl(Al?CdR zh1t=ByIF*1SVR<9gjUdm)zCz=&;;ciM+ukx_M`b-LKC%H7Ijz_tw!P{T^toC8fUc< zR{<3dZy7HfL>C~^!dxD(Dx=LztIa^`vx<-`XPhiRo6K{PV1(eaIFZCro-BOgY+{*c zgpewJk}6J{qI3fK(uk(%m1oW#3bt*@hotj|mk7t2jX)PfsW{D@q|!i0w|P{l?AxGOWt|(79X` zVEih`Z2EoIN4_c0iMr8|F4C0}8CB<`*1+#p-&Rx~($&GA)xgu&;O*Ap(bwZyH#}O^ zG14~(Ti1)9HA-7IE1fmJRy3Q@xA2^`cv-gwp4D4fx6z%oM$)$uot5mGl#Um8y@o6J zKuZ0kwS_*k?V<3UD)Ch+^jkdh*|hdOtSrAgD}Oxm{j~OjKIcTTvF#t^LJ8*X(&rTv zu}F|gx7Y)5Jkn<5nZbk6S(}}X+=_Ci$l8!qSl$PZ5%qHAF__y0lHq`r1Tu7%QNt%~ zss0w3)Y>k6EhR&Qs0tLB7`DmuJyopBr%N0DSHe(Qc0NmG%gsPr)n-|FV8OR zE)E$%*Pk_4k2Mz^HP?@qyH-&xUAa7UwrP_h_p3qdgZje9C+oAe8}JjuIp~|Ag~x%l zvPrV*7!_aYSE+`eyNavV2K%=Ldl8o!9z=-!ew*jj@lrkEu(qquTYFFg6R(c&huQYT z>k%cQ$PxHBrA7NY8B;%4+ehSpng@ zauFvAnOh2FCra&GN@FJ~>jrpE$eiH|_{tCj1W^t>hT(DM1cxg_PbRd+TbbYXD`lco zCV@h*P}IbtybSf7@J=Lmw~TL2Ob~ZW2+qvtcg*=h^@_9evgA&@BSo;N@wol6cjWE7;~jA3o4DhfbLL;W zqaFxGxC*j~YmmvhMFi<&EL=Z%ISUa7NGBOHmSu#^T)xj+loW3q+thl?|5 zvt#HtvJgP#*xlh1)XOWwOSs=>K|@tNj{Y2Q)tPwEnRC@$d(ho;)mvi!X<{t9^*#5{ zrEbPyCg0UCELgfthzc=CZ?BpETtw5m-f&<{Rryg}{X4oglkpO}nG6eVlqg2j4F=N< z&((mWj9b-DM~ud1nO-aD+9v6spl@Q~vTH72!wv@aS07L=R*(0V_--Htrbh&rket&y z%C2AHZ!OuPj$+miib)(!)KJd)kCdY>n$%Cl%ukBFbl+y&+`XUNgWNr$o;(uWJu^9N z5#U6YISlq%>JT{!m#_d+HcRYFmstoO7v1EV5KwW}Bd-yT+Xe2O|pv z0(Yv3`%h-uapCIZ+Vk0QkB}LUXto5q%t%3Wx1?MSBl^c5@2((u=HNtP&V)qn=q!&& z5TvEqkQ0nYJnu{7pO+YB&Wh)k+*FZo9-d0N19{kscFs2TS1x6FAj3I{(~yeRI7h9!z+?X?%3z0_#KmS=i36!KI~GdDuGq}{ny;dk24btqPG*POjJ z8HX27ywqZQYq-3Ynj4o{zXg+cH>AEc@V;4YZgs#+1iRb#q`vu3b7YIW#^SrTOm_w^ zzpyX8()hn=z;;Gny#;0Qc7WPDIy()Rd^pLxo}|6|Qro}uk1d6uPB|U#Fyhw1%+BzU z;2(nA#uhGZK^>0H@7@G_{e_YJoP2bx-V@eUmDqBFxm_j@PlX6#?($xfoRYPF2IJL- zdlOlI-SK%9b&b2jObooIW4z81k4Kj#c46~}ng@16K*ghU_Q?Bsqj=J4`$*CwzzYd=&1T7eV}I*q^3MgGc(I-w`^uGx-l*9f=)A%0b_yH z?J{;SUMQ5#;rfbUHJ>0hq1x<)X{}bRX8m#ZifN-!Z#BQ1{EWf;aA7v_WG2oN3y@@<9>q#9N=p==oe7=LTb6j~f8;-$&$~w^&Q@Uo*C! z4`8V3#1Dnd%2-g=?*`p;jsY`}M+jWk6(x+d-s9Q8kq8@Vu`XMnh_FWKA3IVxu9A zV3?7l{t#{G`vJx8Bz%Bn1QhAJ)=By&PPh?1F-zesU&2h>jWPF=oHeo`bRKd>PF8F~ za+=@y%y~uyTSsX@Ejnnn{}6*Pc~Q$&7nN6vx|*d++xKHZdd8xIqCkEG0dv^|m2P3a zTEP`_wF5jlMay!lfO%0AMk!^@u6qNK_oD4=s$1_5Kep~kC}qoXU6lyOhE}@mW3Sc4 zMf8IA113(j_2Yx%0Mz zsqgB+3x+}Qt8AXR zOtI`Qs}^|yt&xq;tmot6Qbwh})j3jEC(WRLSB5`e)^+9MzhazU8>Pc$w+aP>i~#y$M`vA+IVdf>_je9zs{0jNpat}fSU zSGq-_RO6eF+&I}8@5li=#^V594;%?muh03?8MeyWf3K*&)6FFW@)N+lXh-F|nM!tM;)w0-N01AaL z1srPkb0RvBHbhos=5>Cw2wQ+D)HG?205xzZwn~Ebt#FUX`?hbUE{ejatMDt-PJ;Xr z5D_3{jITZt-8;;X{t za|)n%6(=1a!Wn`3gih@f8|M#7NZincjN+0y_s3{o=EsFt{-srF;W6yd{4^K84yCAw zzjS)}Y50ml%MF*a0dF}uO~4YbC1uJ=IVkK@!^|`hZ1i5k`oq3Q*=xFQzi7Of*Q4jo z?8o{T6S45H_bOu6&fqxLbVO|+D_jChya_Mui+tFvUCy_@1Cj0*PTN~$($AtY(eU=n zAo1{IV%_35J?f!lTa4nysN;!ikLILPwBI~^$60|dO8Jl~c{-@H332UnTNLvo2+fha zwpuD<3%71u!4be{E2*f3os|O+e5PIDJFF?LpNSXOU8_gj zq-&*SNR@pXo|GG~Isf+p!;G4A&0kgLM%3T5Mq;CCbv$ZWiTp7-s+}nvo9xWgNEbHT zQ9rzP(VChla}5j03hho)D!3*s&`DCwD%g?dQ9GG9S*C7E~(nP6pkrL8`^h2z7?q$QD|)Yx##UStLfeIVjn<1 zba_T!1wb7x6_ME#K;~>trrahKA2JxS!hQ2&ThtHIN~<|-s#3>X-wAQ$AWy=p3iIUL zD(M{r)k)Sf8PZlMBQ_qiF}Yz&8CuNVC*X`IH&%O>a_t~4<|PPhH2gT)%}yS zLM(iGxTVe}y3q%*LM7vD@a^WuW%iiYBP0N_n1iB zan<}wUviw6POynnnLb&Ed0ix>OV4nLOXe|eU?(HX{F8W*N_6m^*wxJ>%;|L|e2QHQ zjsHLm^r}|+s1)0bXp_w1Asa=A5~P~N?Xl~%)F@=(e z5fwDhvYwG~c2-RXb2N|b?o&T?q;IFRmL2-E^HOwJCPpR?>!oVv?&6=S?}dXGD|`ptG-4^9pbmGO zXN%U4A^X^;eW^ds5NYdVOr(!XGSdZ-i61xESKg5jdcxE0S=U%4JR;SbUR$NG59R(> zt^V>QzAzk*TYukkxtaRbj_~eru)0U1^nG;>=w1*|S#GNRDWUN<#9MDV8|$_2L^rd# z+OMuIS=Qbz|NIb~vgFGyE|*#y*y5|*bbf}r6Z&h8H?u$S9tZoOLjTHO^ICB^d>som zX{;SsOLl2i-c}2yEIJ*-`1X~(W@hJ|6T3Pu|7W?jeZ3Z3CXSE9f$X%1b#@ApfB%gj z5Cm@l0Vma8Fam*a0eGVa^Rx%ko`I=`fcj;*;1?&tsPHx}$JQ1~_5JF~1at)Ljs!V3 zeGNdo37>&49r#Cg+^a_=*LC?>!z}q*p`MkQ&dl~?W(p3b&IWRt-bvw)Tiu5j3gS^6 z$G*I%9c@@o9MII^!~hb`d;l~R^B(XM2{{aDfDC>>2J)XZGQJ|uHuUkS%>#iWPa2Z! z=*&;Ex|6ml6!{~RjkvCD2grjsG?{odvVUF_Qy4)ekFU(o3#OVxp>QyYHaW~oXsGR2 zj`M2q*ev7-gwqG1b=clC{GWAv%r%ci!&t6%s{+%jX%VlXig+Sq9(#mR$Vird?ptJY4@4tJhrkrELDZ!qAGiry z7h$*#qEIycp)v47iB;xW@%0|{HRm5$;SITY12f`ZoDh^P3)XcbI`P##SwA!y^b!iG zTZ#vA%C~{vM7KUv34f?&38WOL3ma$$D+t{wk&9;+KJCvDg~g94Bs#9?$;oI&oCI2C zsWi~QbZ=*#9kJ_Yzx@ilOp1g?y8YID@Qh_tBE8GsJ3BS1B=9qM zLvshnBB!HEDkzhwII{#c#_FI)8_Y46)=gF@@C+nUEZzWx3UUU~mCMjw{Lp#m$azsM z+jM?j3;vsnON38G=f7j45Jg8nDk7(p|1lxTzm&-DJKXdx%c~f{n?1`bc0mAvA6wdIyE&llY*U$g0?A z*7x}Llm*CHIaIAV4Cf_;`nidMK4BX={akpO8^~#tJ?ucUBIr$N%W(oocA|tBbkXzD zv}BBDjQF+lQ1RcTl3keVoT&v=o;ujZdG5&CRb=S{f1ol1;n~Rk5M^Z#6d#!+4!&c^ zo-fS%E}9-sCL;~Dr=q}AAe%df0HZ2sk|fvHB%WNrzJo4-z>GcFMD|aG3KdhCyr0T3 zY?+l^@Gyz|wCNJSCQr&PK#AEkHwv!JW1Sn8xo7=r4Nw5oR0H{$P_ArIIRb28iCwI@bo zWXaSegnvS?X{Fi-xi$%DKWMKlkWzhzavs$MW6>D`x$3aM$d?MsS6d0Z&0lC>@*TPA z)&AwPl{HAL)3e>xTGjs{o% z)ETrVYkGDYreseEbu~>l&qjBOsubGZ0(-(mS2zc|)RYTAi)iUQEePAkmy8Q628$og-#N+hq=oVaHXiPizkDiR z`$D5yUBJpyfO`RJiv67(w$Ow-(gUaY61xGthl@Ou7;(__?x42nG8qpJHA5p2xqB!+ zjt76Mv#gr$hk9uA6Uk#rl@V7sK7xZQ=%Mx25-Sr~tJq!3Q^k>*%Oy6=S3O0iE*`qN zZJp+8w5`X)b^1kUWKxY8IHwe7oDkT~<<0c0*>`KR(niYj7zLO5yW5dbS2V0tU7}PY zx>6%%FV)2zDl}d-#&TH!fs@p}%{wS67>UIr2s>nnGcKJ|k|oVFx-Ef4K2c&!u~P#p zT|Rh11NCEBX~`oI#EB3xuhH)AL!bV5K5ucA_Lvo&L|v(cbRAaDnM}V73^NQkatgZR z7&=cf6T%IKLWnd}zcy)2ja`oRZHY%-8RUD3#`R1mPY=s}Nni1Zt49oL=Smq%mXhEa zYDo8bTJm~JP3=sNVp_@I)eMaSapPdFWD&2RH?M@vJtu*!WOKeGAeVgZCuiWY8eede z+d*f)wR!zw2ZC@5E|}3t)Q_vuayI_O;o{_yD&-QV<+lky}(uu{USMIEFERdNq{ zwVGk`n9Jf8eP|YeR(kb3e($v&^PQ#r*iBJ>_|0}#xWZjz&QlOCok7hU&ZPA`zC!M$ z#bKybW|~oE&XXr0YSmsAn2h&=!ju2R6&dza8pT#7g%MtwQDMDmQ_Ah_>{ThVP;87{ zG1ieinNb0u5g_|o5``V#oL0%wU%o?^>gbsomQi!^8pz!o=jc_d`Rd2%MJvnYM%`Y8 zklC<o!JJVgb@EW8j7p-G-;J_->%Qrksp&exz@vk)y&3K zTb|OY(OUecvvAJ6Y2~2@p^KD4t9#(Z^5II*leVYTxyLcKt9Z2+DXWNuJII;W^x?dP zaHaK$rAo-9SGleK+j>p=V1`)QA133*&euN7@BJ&)Ju+FtH<@cR9V8K&F9PqBzusC$ zGW`!ax~#i~m*SJzK(y_kms)BW4^r#l2!e5AOubmfF>lW?A>P3==RsQT@%;CG-YzlU zpIO}*=_lS_8B!B-T`i?L3`?DPo<83ib);K;8Wz^4YS%(0(Ob2BI>-2ie_a2SxS4|K zZj&dV+{E@fTA6OuObF6xfg_wne$PbLt=E5-ntKT*%DgQKnR54~sxUlB5z`M~fwsI!Qx#&*URPI_w`@R_Vk*clv$2~g@ zJ3D`2B_GOnIk$V}A6{RRhM`*4{EKVufOhXMpX?Bw<$S{R;tg{#Ut@3GN;ATm9D?n4Ime<91}C9dx}N?3^9^ zoE_D^9df;0>YQEroL%HRta<*eyYA(9pFeBfvBm295;^-aoBQ&5UhIB*>OCdA>yu&0 z{fGqwXhw&~d56dahxU4h?nIFk#cXNJ~Sy& z%9oOE$U(Vxyjyo?ez&yx_qN*83q9=vi8qNmSSr6Bw6`Agi64#iAI)em-$%BHJN`UZgTL43zAxo6bpCnC_P<}-IJjUD{P@ILCI)@nVom*_yCf!g zha-@z%j*k*MW@pljobd_d_X4NwNO_u6orGj*7sq9~&WFnpJcvJaYsY0Q2HjnDTuOyyz6TCo?AxB823Sk0Rmir2136f+6Ok|@JRv#-OXnLM2OS#Tr%@n%Y>_jIAsRp66hiN98 z;mK+``4Tf0rY*Q;3DQ%g(n&6hmgY&fqRLQE5WjnecwyFQkMn{TagTlFu)K2l>Pb)n z0E9GP6Zw&9Rwu;~bXxKlV35oJxS%ifVOi0vRCy8$QJIFcUCZfdW!*5{S(Sw5!iu>t zP!q4ZiwD*`t8Q{^j_+<60vQHRr(m4ktVsm3Ug^^m`RCvic`PluN1zP7DTSc4!GieO zZWE&_?{vN1df)^FM$@$%?|u#@V+ynt_nuVMW5rd^`{UWwA0j=R)lh;^sB2JP#Rq(q zbw%3Q^#F?c1dt6bt3Zx-7bO!&k4Z8EhP7>Q2cWq4yElcQQHCBvh(VJ#$cQ@fehs$3 zL)+MXs{szieplCM34gvH5jvt1ZamGOpwfGU6pUCc`0uf44>-YyP5zaGnEAV5T;-2X zV>^e$Pv_)j-^ zcaUJ@Ut@Hc+TWE0!Pomq>UJ*&Y08v!8Bpez+{W-s=V}A`BYbYW>maf0pY$aJT_Y9OalGQ?oF4s zDL+!Xtr})GO&7uL7ypIhw9Vs87$rkqwZu;Y?7pa#Jr(wBAK%L$62yF136Hu-(__8@ z792SBvZR@aOQySJDPFVDn6JclaO7)nW;4ku+|5En4U({_vc58C1rcm?E-2o=LiNgn z3ZayZxIfL7V_Xm&30Cuh!O;wd5ETkTOO{v8duD**y4Uumf+Rzdq`+LoZ3MJ+P1M-5 zK}wFBh;RA3d_~7-bp6v``YIT1Efy%I&pH@IUW(Ia^I_#tVSjVP9e1hYBnfo>&Z?P#lhM&cB>SN<-YRBZ+Lg*HLf&CblDJ5eWLv_&;86 zQ+w|Vc?N}I)boVEG;k!=!WF)f*#N(m%a%!|__SokNBmAc;F%~&S87XClJdI;94lNK_&>^|( zW3&OO<%Redc>u5)+yI2Xdv0+CFud>S)XWM12uKuTjGnxIyt8-ie^GjQXh{I9&~uqv zKa**BY1(yG?@PEQ%jF=9^KXi1)w9>i<=n?)0L>zVlCl*brPT3x2nN^ClklO@y1rj7 zw8rrK%n~nky+~MsyISaRL(D1hh{oXq1V3dfwX(ff94cJP)ocRj9Snt{KA0f}C80Hc zImWCk$Pvoggb5HCPLpQr5rq96R%3xzt4~;{vhbx>LVisxly*xSK^yqy@e7P0??J;I zCzNGe>$jMh3gPFv3bcu1l!Ss)k;MZwFLcx_49RZ&Sf02^X2yKbcoLJk_O%`GlS*|89GF(h1Zg2_JZH4itc(wI-NH{-F*{* z;1L?Vi54MPA7zzlJ~d^I;-35_bekSsVMY-}?sv*H5;>9z)TJ>%C{Pfia?966%_MJD z9PRyP$1<2$j97<>zVH9>7Qn4zj}m7VQ6vMm4)RVmZW9K!)P>2~=&jIE?vqN#Ef)0~ zk^dfLQV}bO|9N4h-MM;@28~xm%cX*X?g+pMfceV|bbfvc+#9_duUY|P(|OytcB|vb z`hMY&E0VCMU4TLjh~m4j1du&jz4R!=IDc0p{QTJPISc)TpGDSiv^m5T*I^gizP5Q= z!Z}=P!%>t$jz=JAwpJ1l02UB1-%2jlUMLmmA{hj`bS{Wc#&R7v;WqRqab$<*@w*k* z!zzs6ZI^#%!Zy~!v7~&*Z0gi~3Gc^=LTtx;soX<__Q$ElbjM=r)I*K;$C&|g=kkbL zL2TT|xrKb^>XHC49s38MLh?4^Nbad)4di=yz;z!%NDzNMMaYDL8@7$?u-lbc*caB_ zxr_bBoqFu!l9<+K=BNhPpQ}nJ!vMoOo)7dy`K-H$djlKaaCgO6?+clJ;}Wp<82piQ z6UIL!u?u`dj}jqFG9Tdq*T0Nv-WyD2lGw3D2JWQpRpq3H-5~hwE>s#5phi@2lhr;? zkK`Pavhb|6PJdi_gWk50|2&V#f8J(--jC(~ye>_DK6d(_+qv_sPb;c)1yH=AjDd71 zjNHm|2X1On{oh9XAF)wYlmh;R1(?BjfVDA$p0Mwi0;uW(Y~8Uj+Pq*!{U^+Sk?*>J z!hFegtgko&DKrA9JOXLb0_oZUK@7`*jL(70I6sm2LM0|*w6uHL>t4Xws1V#wy188FB3tpP75Rw4aDsTrs;EG5a1dyJhfD-w{#z zuvWrjt}SA2aboYeVjW6jPCXFLm$6nXVjrGkKXKx&!((49fcTC`u(W7p9)LxKI6RMN z6x?_;?syE%cr4F&ob>o@_uvao#O8q5Jq?7nvUm#31S-!2n)C#^_5{_mUyPOk5M==@ z+=)!>{_M1goKlGpu=w07iOeU7950E&xJjZBiOjUbH!w-!nn^rkNzyAxtYZmE+{r4M z$!ea-8tKXUsY!gx$;h5b2JMMPW6Ap5DSEgmHNOH3rBbXtQ_M6|Y+h0N-= z7m@0q=_WiDul14&3cyVZ}}kfUGAKH&78Ssq$C9}RdOI@JTLAxd=mgM`vtG}AF)awnX_fiYkThdO77=NE`ubn zBn}XXBDgY>j-%>xCzY$%khLY{2a|{RTLBRPJ`c+)A15Op&nwe32x^xZNET!`qYjLK z27p}yBCef4i~H2`Bpw^g-`$mg&PKVC@xZn^1SCAPziX5(leA@+2R15(CNB~3*5Jh!B#S-WhP2eXK*oXt5GBKqq4|0gPK*1d#`s(m= zwJhefEDo=HmJ4W2;c?K&r~F#v873OjWDw`T%HJDeA;LfmrncJuZIhLaQxTcnfum5m z;#YsxwgKFVk@*HV+`$}pxRwD)P?_aPs&r|Y7+v|GR@Jaq)u?pHp(;z*qG=i)YAc(W z=aMd{697B}NL$TVVgSH{;*eNhnQw;J1kj-b$-j#lf8Xy#Ae;lcZM0*AV9OMigP19y zRA$q~Ri6g{ck5{RN%C$*!|z4l;b4Frf~EVx1>{zG=n9D2d7NK1Fwhp+uyJ5R%ucW* z;9daVjcfZzbkvg>Uf64ZD2aT%1E8+XQ^UAutfPTpt%32a!Q9$}v zpTXOumPZ-!oEez9T8Fu9B6uVsJ`jF6{*Hc#@L$e+25}@FIS7iZr!qopqT6v|+7zOCE(R&vVqg=%oFZV>tB>qpg_VIBHiWWy zD7K9_(taFb5;Guz8Th86M^XxXD6WxnRtn(--!oo*69DEx;z5Plj<%#uv)3L5={raL zm5!j_83#P1ly9Gd*b|fwIIPUj{`2Vl=XtH+kRvZrP*P6??cXXelLw$($AGylwxs}H zP^U>S)8VJmlrlq05G)iV z+>_PI;1IJ?fz<)f-~mtx-@)<#NM+^Cz4Z3-uKg+3!&s0A=jEzW2o=Wk1MjN?0$p|6 zalr9j7|a>)73KmbZ=p&V-db)%7zM<8NN|L|@R*6bcWXT{7)BA>@^s!q4SW+#IunDI zK;qXRm^vWZzp>6bAQ6pw+fs+5xW@=R@`HlpsP|~6f~{OL(6Jc-bVP|fuhtlLU_h$a zb>PsoEvUcQF}d*ohb0K_$yxWwE?~1Wk>d@_;Ten60qT~Fm17t0)hS{+Poa&BpI@7o zDCn=iRkaYzfb-8lPNqq;<^AXi2!6tTz;f9&WhbdH-HWquDS>w%297(xo!-Lm&Y6t7NIbsv$3G}u@HLVR&+LY z|Kc(1BjzVvSsDjib(007M((QPgvbLcQt-iCvO84BrYHq~mZjW5M{dIioqHsrw<=R9 z*F}M;4l5{qV7&@fz5dQJPJknr@QN}7neZWs6>1pZIP-TOXD7SI0tQv~l2qOhTM=0N z34`v{s*Tke*?6hYs6L}bY7Vb{^|hHNpR6#J*)Z=;Y>(D#kE1+ADOGp>kGLoE0P(h& z3iYP&3@_g&gJ21NuaO`ah3@faY#(Y=kJLtTI$zWseg5tC=8x4w-_7IfO>FMqmoY4> zv5iZ9GT!A)z85#H<4p+ge&o^)d&^< zp0BV1skejWw}T@W(i(tW%oRzLiZ1z+Y6? zk5R})WAOQfvtX6>MdC1J@hHX=O@*RqbkRgD70tvmIG|?FEpCTH;W;!yzqj`t1wins zzIOfE0sKv%3VEK7P^O4MVyiS7)M73lsT78Vmn~1QmJ2kP##%?g3e#$`gX&Q*7zovB z(fQSbiSsBJ(y9*g*+sv9ibTK}lk+vmTyJLuISlGnXqc5kXw2oXyYznBY)e)(<8`pS zhz6H%QX}&yv9M?!1OA00O`J3h#CKqBh=7p1LUP8~&~g)u|G72#cDPA46Cy)8x&m~` zeD<&(4k@ji--lx~8-|fv0$m?V%?(&XU{1QNymbhP6RLp!`sB5HMshABlDx!k-1|cW z_7B%712bgV8d|8HSRW=hB-fQ@^;;MNddGR}<9OC*uG&Mxl_*5DAQ~h_V{DHeXlk5* zOQ&9_QZwd47;D$=k*|vON`qp`ExUqkB{D2IqXf?vrWure(1IOiE8CprD^m_d3RFL* zOv_=LI!d7**f+^_nf%_UuJ1Rcf$}{HH7S}Me8^3W8(cRiCl_3H+_J>dM;Zl=Cfw?@ z941dNFqb7wtD>x$$VKo}aPQ#0qN1w9%BrdnUZqmDwWdS8D!1pAws!cFPPwi<(u$#U zbk+;2ao`lbQm~sSuS#aVM~tC#nj`a~h0e8dvDGhBySi#jjvl4v46BpAF&)ob@xM^)$^_%v0!=e!Hh+13{}p2b-&`e~L&r!Y=Fw~tpJ-BC<0A7E z0U!8{w?YS>j83yd0r{SgYnggD6w#BaYwbGkUnKCVV3zN4x?2Tv3wAQRsi(wr$Pqfx<{Rx0TAo|%> zw=+Qe1n=XN2WvbMjZ6Mtn0)hZ`<>v3=M8)?qE^Gv7bdUNo9t*lTdGz+$CS-%+Mgjc zINO};Y`xm*4MNZ_e-^ae%ZG_%6zFQdJDMq!$(8G7x)>g9RR2#*KJcYo#_edkxH+Dy z)c@k--t$X8e)u))c7MD*-<@qu|2TG?U8Pkg()z%(*!~4eRb~)afH_Yh6vsZi9*Ci4 zu@i!0wyYHl%^$k%gBMD(8%~j8L8gt2^?e%bkwI-Uf_a!`@AvmbuDK|rLoRKn_Lbwk zSV3soqBzfNb(FApRIdGmpByLqiEo4wDB(rffP-WWv+{$Kfd!5&y`$vbgEW&A%fs{# zLYUnky1bLaOow4wb2VGDRI*^_!}6mXpGPTl)f?RT!rWjitKEFHD|hR&i32<#u{fniooUT2_?uwWpMoRGd~+{Vz-o`r_nGi&kgVZHEOV zXSKc1^yhVhSk~wDqg0jW4SzY#&KqaM=`Wh*)vPa?m(40KTGrjpE?T!k=`Y*%Q>-uB zk4q{qJI-6qE<3M>>94x(7pt!|f`e{yp3nwP^Y_sf@~yfDVsp^V$_nT4b+V|VPoLBF6GZIW6_w(xZ9}mmswI7e`?pGgA+hI(f&->vRHFJyhIHz1vTkmzYt$o_F~ zK)&_hNkC#D$Cln(<@tl8(2+u}AA@hze;qu(^Yfj5HnN0SZkQsHpVHce@K>_-@LRD~KNG z{@mE(f#f{sbcqH-t1ica1q^Prt?y5;Z|$FLtlQ1Ojx{Enm4GqXcqV$lq!&hkJF=GRQuwyYaG%t36ntFYY33&aM!R);GhX%yg zmjM>+j-T!6D9Ho9ss)No#0^h1o39HwDF7f1P@A0b$^swqo&{XjF#s~_8Io_i(8jJ! zQXqW|&4<}d{j#d(cY4h@`OAKhxuN~=1+QP_^P8Xi?w4(Jc=`Ws(_RkBK#D%OipyYK zSfDupv^H$v^I&!>sOGYE^lnrZEQ(r+r9eS%>#jnMb}WrGtlM}Ct3R@g?>hp3Na6`k zLuc`2mc26at6DL;^Ld*;)RR7;fsF89G12P52v^cJQn2+sC^@k3_TV;%F>FG`NVepG?T+zndn7TvwA9OX z$METVbhi2lwMwP8W#s((0>2X~!x!FmZ>nb+lXza;*K5V5-^onb}lz%n*M%TG^*KTzsu}hac zMHwr}smLa|n)Ou1XKXfAYUZ`%)7Dv|*5lqhV0Zl^83`z=pxtlx28F0HN^i%xBo=JqnX-Sh> zo5XwPuZDdu-`}sGFX(vGX1i7k{j}2gxbpjk!pvi^`bkE(@g19G{0+9EUQfv~1ZN~8 zO77OB{FkjnbA(*lyDoUjLSV$B_SY$^Rk$o+U3gvwa)?CI4GFmoE9%i_m|`|ISt(7Akt_lK)fw z1?_3Mke=z+1mI3AJP8%r7S;|@n&KH@{Q?RJxOnlO=677 z@OY$eYEAM}*}|fcYr|9;(nJgKLLs`eBpYEobDE_F@4zh`%V&Y0P{pin@p< zQSj|^MyGj^m;L=3v9f_-9K+AnQgDKWCVM@yp1RUvG>kmujKx+@(e+`|E*6)U_VjtY zPi#+%nH6q2eG7j^@2OiNk>YLkWyX6Xi7}74WjHyn19U_)>o6kkO_%HXK1fYpFiNA! znL@V%CRe7L9&p00maQN#_a?X7_8SFj!(23vL5Kur^6g%FcGu{tK|41Xr(PSLO(F;r z$3#vi2(M{X)XEjec7? z;Pia^zmc9t_y1oa%HV&J9uw79j2*#avcTzKW2JqQ@8{tshAdS&cef6A7yob4i)9dV z{*OSEdg<8O>^}lgm!wy>^`4}az-8Q8|BpaahU7c;`P$moPQAGjZ6SM~>H|NGjXrGh zpD7%mxC}%!AFK^t2BOCPi}d~-h*GcOaJ~oHio4*x(b;}>^l#Gp{bPU8Usb^bBR~Bw z(mQGO-N>07BRlvv=`H`aMASb>FS4kn(MWoLzxS4OZ!jxwEN{BrY8+q5Wy!K|)wWB5 zP=um^{PMV`>l4MxwK7Sn-?m+!YWx*;BWlxlxh3myy>xqKB)Q|3VyZ6Uo@#00<(_7X z2bo}jPTQA(s4<(HkN-(}p5|$z%4;w^WacI5{pV3nA>>(sQyj_bT>x(9;c4uJNip=w zo}>i9;j;WEI+P-$EJxST|LdsV^%BIo@&12FuhjW2^^@iLx#HaRC6P_CIk&sU+5aTH z{>@#F*Z)O&R6$S&=`7V66ihU@x{{J7DxjxvA>L53c`Z8OTgztoC%=}Ro_BujUs?_Q zVV^c1YIOcQefRy%UnqRP3&>)$-wkEqknDjAE$sKw=)w>B=xvM+`Y*>l4+hxpj~sN} zU_=#G$)y>Ms|u7>1nKT(x^mb4ll1Zyo5sjCEgKL22kE^pO_MVcT#^48+{~)V*)VCL z;3PL?e%rWV#`^A`1WYL}LI!GLZ*B?t_RGxc?0%oFZMSek}6v=u zb9ABi0fC4+MnIkz#U%wK4!#U%Gu2h20boI~%YdnIHr;hi;uXXo|KZx;vM>^XDEfZ; zpQd$Kf!3`-Y1KyV z;?L!K%1)&2v(>vx`j;72EI!NVIxm*GuVi$S{wQ<6X!C1)i;vzO%CP8OxVEK3cnUe^6CrYvlnwhpO$h51u%Tf=N!n{*Q5j{aiT(rW!W z`W47?R>0!n)^zzxX|NaKi_@03O{<3#LV)Pw)SG5g`%SviS59oEpxm}WUcM&jiMX54 z7waMG^xD{t3LA^JFchGtOss2}$@sxLdVbB^1IvxYy_b^OTi<;JA2N;)Fb<;DaI7F746z|>t)c-UK{Ef+upO$!0gcHLd>@% zuU;dV&8|Qzx4VQJP2=gx3cxv;k>r+|uJHQR8~mma3hxR^*+dM(eHAScsp>fXR3uw% zY!t6fHAIEf?KRvS#VN@HW?m=&m&3Y+obzF5FrKoKgh$Gk!4RQ<3+h5)GCuGDg_RU9 zA`8(+sY3_UnboB8?7~Vrj>JhmRvK}Yyo;P5ZpxK5_X#J}#|u$=8Kkg=?}4>;8wt3A zf;!kkf{^!CoZK8`5A|>G3T3bcjFS;X{y7292A)X7?KhIQ{PKf_^AIhNO@iU#gQ^i< z>2@PDIrgiuuRDC=q(kbj01sl7`NOcTvj>dfBhY$U;?fygD*NX@8obrXSW}K=+Jy*k z_1Jv?(@)JS+kQijj(o&?;97wfqfMPZIGKFFtTtfl>MnAVef$*;LA&l=vS*rcAS~^@ zIXzBg8(XXLXxo=e?|=4Zl^@IqoK#EqmB;8x9zJ`Ywk~v`(BfcKwc;MN%v3vzl8MGf zOWA_JR;D`Aa2}v+Kt7uRt2Tp1HG$p}1ja1)N~e4PFE#52zG&o+_==F@2*A9GQ8r5ZezpWc-kc<=Y>}3&Z)}hEYBluTqf@dzH z@j4jlJBfh3cl(gJ(Z4~C99nE;)jGnefFEx|?rn&?SKUe2>e_7UKf-r?h*ad30=b`7m?mBf3PhUD$F>J5oS;`) zM0mwG;C_lS-CGkhK)yoT##%syN71m_!mz9U!J?ZLYg3^3V4$RDpoC(ilwKsCB0LpC zJrqFEG=8@%0DvUI^AHczgs6G}KuZ#36A3IJ1)J#tzT2mK1faeTqWZWWViQd{-vyaL z04qtLlyTWu1aO>0eIG#01)#PDPbpxb`WyCMYTM z!Od9cIFa)0IAtuB%srHRbf3)oVlX)CM1x+n#Etsi^lY{$J2wka;6 zbP51Gw^rF+7h1h5cUW&y6r%FuSg5`Uby`oMOr$txl-rd@_y?0MBdFYiY3|A*U?iy0 zn%Q7x;&5}~JI_17eCk>fElqRc4vC7onre+iGrHk3ew(6a%WM=)3Az{VjYPC{`7WGN z05$d2Nq%3Ku_FMoJ^=hwigwC9akKi#+zDAIIC0)RX|F307?-$(p;;rEQ+iUr9;X6@ zVrkBZkW6@{xxT%*#-t+gG7!bylFTue%ypKGWP8S|^z6R}qQvK(NuE99e!vvE%w7@z zU_#tNUl7o(QHJt*D7jG7brF=>oEBS2psuW~lpem(6<;TV7ivze?UPeGrep=&vX%jx zG^!LJZsUqk)l8DL`*JFbwl#&+yt7&kAC*Z`@IVNj)h%7*cChgSO)gz+ZbsA?KR%2i z&9N`Td0p-yMP~S!CR3D2&ZZahj8Ro{*i9LSwkA}qfJ1|gN?Rx()|9*JKA?HP!45$2 zR|v_X^bDL#vx6}QiBJ!RB#sX}xmyGs45f9)LRJH4e(aNbS3l~UNg^jbuEs>zR-4@< zI_`GCLywbI_nl_$(M(8@Z4J_lpF+q3$SB+&^JK9ILufAYv7ir><>N%e*^6Zn{ecSr zbw&Z!r$FHWS;}rp?%rJPx3k=Rw!A~7ykomOVLPUhaX@wefJVna$K8ZmI6Wi7P=_&t zt5gfxYNS7;{9wqMqt8&-)}B^0pGBL*;GNGzsby810b!Tq4p87pwY8Bcu$#`nK6t=e zO1jynQY(|M&t`ld5-%<4m1bR-vz^D~X<*71h$dK>6@m_mKmyhGY$ok<29%T8RMOZe z=DOgWdO13o)Fni+T8w|)gJ+-*;X6visbX@bmruwMl;h)+G-<7iYS!5pNG-oz`QgXaKqLg)KaPDEYxH z;<2E3id0!!CiUME>_-HRIhH)zo4TuvVmJU0Ms$jhg6AQD`Iz$geV8qPx*20uBSKA% zA^akT|Mj3=nuSxssO2aqKbV3%0;p>O$VN>oGR#v($9;R3DYJi7jI&oxc#Dx^DI-bX z$?VGc*2;zX%B5eG%j{LF%2n(3RhwZ|+u2pStyNjS{F|j|LJ!JLm0lm)zdj9n{WJUZ zuhz?IW~QzHK!S#z<1!^xZ(&(|O7>u0I&-|3ux-{)eC7{B1x9Zv?HY!*4A$tHZ~-~C z1XOje)f=tAn+#Uhk4cOfn*3k1?CT0B+2wg0w0KksI1LT2P=zI4Oh3qusViU!Q~p#} zrxYUD@jeiE?cBolp)KX&O`FMVg)3V0`zRrkZX`JTwW%Q2l!v^A7@Vino%5L zvOyw=;O?AH@(9O-#HACswuT-*fMSp66p{+t+^41%0+26fPjms}u!(*8)ST|-J6%*X zF}gph6AY@Ub`aFS13;W94KLeE^0*h>&!~T+%RDh<*~92O%BS&JH~Vf& zTneNC71J!4u?cRl;9jxV`qHTS(x@5rW5O*kd#sxQFXZXPUu%Fp_bJmXTY^S9y6Le# z9BA~^=*XeAl`8>I()FH2V!s$0B{Z%OgbMVatu9F9ZGc^N)I2( z%o)mVAIe!6$~_+N*BYWzAKiPSk}#q!=F***@x7> z@qume1JY@N|HXu0$HW!m4|n$_L^&tL)h4AcoF-)-P0GKRRP2~kUYu0@GpWuwrJ**3 za+=b9G^O)m$_Mp+w{OQ&h;N7J^{tah4lxCu??4$Yfir#Yv3FpE8s z@EO-9JsvM+ZdcBTJCZd{%>;d&@id+h7N3zc`WW!y=pP6sJKe{;0L~zcrf#w zLh?Y0Lvk~gs@Xhw%4u=t(cDamo&6=h9 zhH36{1AzK$;j=Rhn^&TFkLKcg&d(kZn~Q3jo}HV%OPhXwHv_n~g8nX%i*Ot*zQ38f z71p^GzO)sQJ8j!NO*Xa+GSLM2t?^&{U5!iHj$hio5wVfzx1J!m@zi;Z<=a}O-wtEa z2GMULU2+}iyi>5WlT@|-kEJx~YbJiX`C}_t-*z)PcWTwYWRLCIST2M`Zax0Ch2hvd zdeQfWYp+Lrug`gJAYyMYcW=0JZ)9n2?C;)@F;$_|*Fp`d@rbXpxnJiyzb-6&UHbcV znd{qp)t5HsZ<`U{wsXJjR$bq1gX4m>>(zG;)W0K4zMn>X|C#&!SLgThrOWTi``^9; zukVBXzt?wdIG`@qjc#--?bBTBBe)OfuOBepJYar&z?yf!{^o$rpBg(3x!e{zv;1Y% z`B3ojp>W=z=$k{K*ZWi#hf>@}(ihi{Dl0mX(%X={BeJ|B)z3%j7e^X5R#do;wQn9n zpY9hM9T~hiKD$Hn5ed5&Kn)o^w!C>_{rJQ-@5KJi$)gY7nmJYgw5KlIr*7OUe*0jz z>l6s*)63N)=;hOUrsOWKVYl9#(n)@KEd|thjlMyGfc|=g`x{`!e-P%>BHsLneT`;f zRxgn~&fffCPx30`J2O;2O@Duyk$0B){?s0Oih1gtee+gH5hR9o-`MmtsHQ$lv8r zBw|lfG+;M~=Xg_CFzMXd6n5icoN~?_h6zYWGzAakL6tS2!+GE&Oah%cg_kMi-F>i@ z2F$Vx<^TZdFQ21LDXXGS0S85TBi+)1?7cH5H%Nm8*d-~4E>zB@=6_V3e13)p@^9iQ%{urRjZdF z==4Tj$*@lBJqd%ICu{u}KgEBq)tci9+u=GdO2$6b@hnb9S>LjA$|c6&qfk;F@d59) zn6rZZY81FotK6nn`67Klgm;kALxGt>DU?qIPB65EI#Lf98Neuc8xmsNsbd+!^#-LhU8 zsSwKDn$f{n*NZx#t^lJLejUEv8pSYKznXsMdaW2mw|B1+k_S-llvrl?t&A-U(I=uR z@@mv@6_b?OIKf>}pb))>6+I%qx`)~#J$M|bfOv-aP~f~#-*4gUS zE}w$DTzQgB!=Sl=4aA&Um~&T(s*FFh{;RNQv9$L@&$HRDR?i(5tx32dVDFMF+>lY5 zC~VLm{t)yni1AC+JHNJX>~77sVz{FfUE+jFnq3mE4k)@lQP^yDeM(y)<(4eM;htiY zDZ!ga2(UX$iE+$wOErIHDlo_Eh!eh<;3R5#kcyPD_|O9{h#8))uhJ?W+}7c997~O=*1R;1BMHl;N&&DQk0kFeS-Tl zDh+w^6Fm0QN^Tvsii3KENjY?p90+M-xo2=8bh91NyFWIXM5nRE;Xg;$)`4)l(qD1n zxt420&bU9&Mx_}a_Jp$iX5k+SCHi-a{@L`?n!le$eD--|FF|Q=Un2>xN3P**Z4?G9pr}b{J&tGT!$9R&yOZxp zUAV0Qbmc3O6F2SnsrfXV{1$YWAF2u8Qw~^()VL2|ElG;L7KP|Ch-J>V)$~XM%dQYpJo6NZ9PNo>YBi0PpUS5tcxnqMo5hO;r?9AD#VqsVjn|*uo7VP#-?Gh5 zPCAYjytl%MqcC`SdiZ2weM8cYz0b8uHoGrz#~@Paoh1Hl*84gS7B73WkDzJR+>4wsAJ{S4C_;((^7{d}-38Dcjl=i{XuWmwoZ2Oh1YtyGIZlitdr(3NX8>cJ% z2|kV+$~LVt(^dETeVk8PZ8}eBl!0kN_-16?1M7 zl7eg>fL${M!hL(YX`=(81XOQP+RXN_3r>y<51A&Ql?Q2)oLi^P^51!s0S!Ja<>(vr4BVip zO?mF?Drop%z*4<7t!BYR*rDZ}(rGR6LB)nxhTU5;`M~tL5f}cttP$}NbkDGznexZE zvHJseb5GiDtN)mL{}>uff~a|-o?B>LK?fID1tz#5hquVc{7lopy{da1KF&YpKfZy6 zR1?(p99_5AFYAl*(>i=T6h6(pj}ECXR=eYE^J#w1NJsi_%^kn{4?oR?$SP~9`2}Ts zTG-NQDn?64?+7Zgb?V^CA4z=)y{-wl5!+NQL-MBk+4{LQTBFkJkN<@&EgoJqhT<_X zj`3@^XKT-m>bg@I<#2?9ltTN;&yWFPvJ2DA$dGdGv0d{ijp>GE5T9irSik-kTX_kj zJO<e8-nz5UATB}Ep@pCii~1yI6Z51n*UpxtdAD)U$wrIbf^%54^R zZQh2>G<4ppy8q%!(|*Wo%cF#VJekGYx)0~4O}^cWNt~LI8lVgB0&)E8f?i)HqX-JX zbDsks>ZaYa;azx+LDF~OP}FDg?;y_gu5aqt?w60Sp>5B@4s~O3i~dN6fZjQb7o*w5 z1HkjRX@HTekC=6?h9O9Qr;wO#awHNz@ks;B&WZvh5y@t?E|y_sHXW1^kHN4q%<*Nx zI7ox^Yl7j;NwxpkOMf#;feMbx!G@km$WnmLLJy^`Em}HgDM4Rjjk(lATd>wNUY~?w zEFIIiT05R#ZJW<%m)SR3dOgZ|e}%b;6>l~R(kUbGZA0`mltHOrbeFn?VYD+5?_3QL z=u(#sRk8p@n^yx*+SJ9$pz4Zp?t?&Jj*>Ov4PO^QUn)9BM$S@$um@_fF6`oKCYZ6} zjg~?FT?FyLC^am>oE7L#1lkB|U=-z;HDdHlv-pGwmKg9}AygL=rBCXHs^aa1A<9H3 zh!LWUX?fAxtqDN+SCg3qK$wLI+cI5VFwlh+E6}V9B5A8+^IKhZ0p!IR1y}%?0eUW1 zw_EVN;T*Xv=K$Fb0<|?7T(-5&KS6#Qw({+3s1HW*E#ut=AyvwFvt^LGDPCL;#k@?g zsKa|nHF#kmx}n;(dIa6@2JteySX8v@bD7tL{r2_!4t@QOQ~gfsXb%fW4TFkRXnh0U zfQ#%vy-ypZR}-Bwo@E)wT}{?`L`E;wz&(fy)gtRwAzOKervX3|=HmzNK64_zW84VFkj*u`?<_`ZC_>ZC}o zYBF=xhUiJCB`aPWL-2z|X3J{C%QQGE;uEe!vxN6O427uAg0!#@i%6)Y&yc2+oI^m= zcd9o(K$;d7c=qvV@#<(qYLr$rnT>F?eL|bXT?0!}q`0U4ejP4T74L>1WHCTZrt}@h zhxkIf)wZK8LmQ5KS|mq+Ua?U;0hdn_YVoky@u#}Q!`8;4z9KP5o>6Pf)Vp%ohWhnr zzGaXANl{--aMa1S=2x?t6c}Q14bmYd#J-)hHv|gqnpLuu5YLBQfXo6%sVGzAhtEsn}Y7)__|ERF#V4l z1{n}TGb$Z?KLNA>9g&WMAD=75%gWJV^r(^Q^jJMM0d=O?rbSmAJp{*Kg_}I;i10BB zB%v%G685xW_(;*0d9(*aaEc1hEE8;IYaU39@><4=OGVq5Mr)Og^Hj%Zu7k{N%`GOQ zXQBuf=_=&s4>c{sqHmXxc@x2s8Zp@w6O|RiL5g@^BGAm%px4(JQ{5Z_8&e=?2M^+d zh~!uti(+Z4B=EG30wHUK4?`xNF%aJ8a@ej&O_-XC)tVjNyYt z-mV6whDY1G;ygkLJhm~}mQmucDeHH54+(O0)+m)UpmjAqs9Ev0V#BuU7>_B`ygG(Y z3S?P_S20#LD{Hw+1mYs6_-x7ZU3&$-Dhb3|qeGQ8WgCRlfDeB{Zxm?@q%~ZK4g#5D zmE9uWU)C!poyVFL8iiIIXC=X-3Xj~pXNSyzW$!VZlK0j$70enn{&u&(v-Pu z+~$*=18CItsC~6w*NVy>Z_$uP-Qs+tT3Q71gnhJ%gm^Y!Tqa@~NQ?7UGSHW4<_jZorB+%sCvxzW$a<#6a_aX*_moAXdqa-;jJ?K7*znR|;L35&DtLOp78y>g{>52L{QVBV;D>sb5++>^k+kFN?^ zSVgN0J|Vh?D>xGI-fDOo4KU>h&=KQo?%uK*>|pU}-qlpjjCgs@L9UpBEvZ0kM#{RT zpBxOMtge8^1q>VeOl< z20^zd(h@^PR*%o{K?%B}9FU8c!kd^cE1V(9iBHfSX^Xtk!ZXG~{PL>;9;<>OtKkKU zXZ4Fg#Ck1Rv&!hOMZ|18sjQzIO4~1xN48`;g zif=T+5moz@x2DFU0p8ZbWsB_&f6rvws4C*s-yc{Pi z0!fChv~A$+U8fV$qI~s~&%Z!*u!fe+&Ehb0rms=ymFV*qN+Nm_`bffQL-W`O-iq~e z))lBtm$8E$A$u=+r9!{b(&22)eIc9>ZD?>u9q5T2;ln~42Jvc_H@xG9d>ql)+AAw= z1aT}OI~8ony8T@Z=<7#tQO8@df>qqz8m8Y}tgI8x)q?^v4=6}1( zC6_qbqylLJaH$dbX&yW2Av+n-JDKS_StUE!jXTc=c5-HRUTp5C>Bp@A(@=z8%?H0w6=+)NNhg-f>lkc4e%PGhdIqw>)HJd-KbaPVr17=ly6C zMq~02{ci%(;>gG!h7gh23Bo&IX%6_pn&g)KPJKE;+kCVo;R_^NwLx1?nStwO>4A-_)$)!K6l$l4g5)ka1+*HxF!&0&liC&|=pLJqtz+Q$m|_YUQkp1ae8Qmw+bu>OCY-&H`;>p_Hs^ zolr8AF!)Uf0j-BMAVHjASa<-$F*FKl3Q^9BG!h2inB5!rx<~$CO;JbRW^Jg*0@L!< z#CmP18m*}P=YY#bZoI+SI^{aEzuZ%Y1}EwhtLIQto3CmC%QnA15|31IREM^Ahm$)S z?B6X}D4bfaZ;OZG`Al)V8HcxHPCYYDy-H8BOY*(np85(Et_3h&`*G?|{v&|pN1)J; zAcY@gf=AK{3o@?>^6z1iONrq%2||ikgNFoRPcp}5f^FH|&!hJZLa~byYvkKtXH%?7 zXfP$h*F6&t#{_p*9bc?=9D@dr`O4;=s)vmIx#uW$is9QyBtIjvJRq7hJmFqkQN=O^ zklnd`mVW;%BjzkKS3UqoY=m;%@usx^#-Zt(S30Z>nr%At@*3sXX(8QmUV=Lrq7lP=Ov)CR=Kle z+LpnL^Wpb$HmZ1rfYYq4^RXZ2@5%pM&Pa>?IGa%TGpYM$%H~lW^j8nlFMAS1()zA^ z%#SuC$e<8n^E2v#5&?4V0$gn-*w5aT+>TnXiZYhUGPXU|c}$?eL`pB?(bZU!<#KC8 zl(6E@I^Ex{IX~lXFYzJK{!-wNxnQ`?*SwL=O5e*DY+NM=kSaR5Xl+ToYfL<}sW>Ob zjTJ9&=M5hK=BL}`uHqt$h?lvj^tibFuq*P_fT7(y&xcypLr-LcDH|f zjxO+Hs-C{P>5#0*t#&q5=_6RVS~Vqm)IDmUyljJ7(r|6*bh4%$|FrLJy{X=)b5GcY_-eVXA%#m#qI0tYW0+=dk9I*L0c1*K0hRv+QWVve*N;}>T(yJ zoI%p}r_}02Up$M9-`>x_C0_J1BNLZ1>CKUBg}dMO&SbX73v^Q?@BEV8ohrAf^ZWWs zZf~~MF5}gm%RPRNTkjujR_=y;weRuq`tU4{Swg|SOZCHHlv0*ZpeHqVgy9?`!c#D` ze52ed712o_^>nyW%fR5H(17}{zTAs5(g6>r59JF&7YV)5vGS zHAxB=T6$)a_AUjyj3(u7*Qi;WI98t7dkrZGy|@(!nR#(_r?CF32n|qyIm`F*McdJP0i?ClJW%+_+3wK&hLdyN#kSTCT+`BB_ zlPDMdk#l#fWj;@AhX)H_nVP1jhB$^R^n?7RE+ex?i!2&c&HJb>!2NN&Ay1SWJuKok zU9&{fV%R6{$d&l#q)0@VYb2BG0U1q7b7EhSwkD_9FoFP!j2DI-1X1w8@`Fd{h{Pd1 zQO8vCNMT)8akMmKR8d>RIPDo)BphyGDKa?n<+U&cx9lighhmT0)ehlnfg*f%y)jG| zbVqIo(UjEHgLaA^^yYog8q;{jj#+6B^AwUanESQ3Y)ziNScmMSvC1FWJUi9ECs3c%Y0+x5XnFY(l=OOGDMLeG>JbZ?s%d$G zlARH`jH_-~t{nsg{B#-szhLc*U1r6OFE*t)L?|_{d5>XQbjA7fsci&u(AynR?)`Ea z32CJkg~!kOg&!&w4@x|!^-H6FS*AYo&Gh$QmHlq2>*qN>W`CGxhs55f9*wG8s2&sI zM&(bY9UiNl&iP!;{?w2~+2mj3GR7_0G<7HR(e{Vhn^m2yuk!*1UtCxJb8@#$>F>q5 zx~J*(jT4jhn4Ht=t8~>^s45ajn@JGmSOG`IbAkDUyD7}8@yz@q$Bm`k)IrseT<4hE ztu{&DaaXNY>pnl;mA}qdTTRG##|@_)Z*jB4QC-jKL#ASr#Ent6j03fqm;0Gq8C_r+ zM!Ht<2aM9BB0-~Tkyb(cOcn5aEz<%96mgaDnq0A-367xobDaKVa4#|vz|Jxl0M@C- z(v@5>Xie(ECyhtZ)IKx-FqFMjI}Ch^4We?C6du&1uO&vSt`|zfdeG9f$w}dEKH8UK zj>Dt!lI{G0GInoRH(%eSR|XF1+={09%A?B{{}DBn881Gr$tb?v&z0Ime!-mMg$ORA z;Ps1(Vcg6D^J|F;q3K;c)pwu@m3{0%zutnvv@x+I(WLm zf(KDo*Ka|PVIWrPS$bs-GX~Fv!+UPC#S()ULPL=Yd)#)0=0Z)Xre0CZBvRM7B>9PW zDjlcI2=EzWG=hJTo{24NfIoJH=fO!$0dt2i8JU3aE1udyu0O(hTB7DHrUv9hRS^S= z@(F5#+Nc$WG(lI<$*jLIDL=n(NDgS{-;#=>)x+DQ$fgoV{E>7#33MY##N-nG#JqVu z2zP{j0be~Z@l`AxN*_#%p5kY5Y#tY@4Tz=nT!VQZ7d-zaOQCIfQKRp%y!9N>1DktN zB*;cKC)GK`c#WD2&Tz0w7k^7R99pa+_h5k2+jPJx=L6DQww&HABi|W*3pOMyW|*X5 zmKfAnm-{tkD(UTq_z=l{CDA#BP!>EL@0GP^ow)s%?{K|h$M|mRByX`y zu9n2E*?XP$sf@Dam)FczwAte;JuexfrKp*WKy(JP=2s(tmL(Mgh&PxKRo%lZ4S5b3 zppvis9Yegyr{d=nYC9U3KVe~W#*VgS(-2zKCig?X!{&`L<` z5*GnHHz+#gVXIt*UKcn9M~vCCxws5lh6N_xUUOmjoyO^Ca|u7)_8X3RtuhUcb!4$w1Z(3DNavi}ut!xb|&AXTUtLtCVIlF>CMY3FNE zK5zIZz}Hn*J5(FWueBc}JyuRs;TFTb3Brq-l~r@Aty;wa_pM<`=VaT4LU`_joc+Q0I*c)e5kVVJcxM_nLL z?6$(RD<3Og5ePowUZrpmE#Vk-*44wer+vug(6r^$G%@ax2xYK_&=m^gf=!lfSZ~Ck zxu6~-s2?WZD0kx#5*CKo?0>SAMxw|?ZcD&S7P+z%`$Ztrj86#E9NqB0`jc*C0*dHq zk-37ean!S8Dbv~`UJ!OP62iqp-}xz<^MZq1KA%CIhw&F$pMYetzIB?o{L*uYVn#=L z0WTWP!y28>n#9AFp3j!c!(Nilo}G^?Ls2r%|Mf)Yt|xO;nH=!n%303m667g?m^1$6 zK|)=SCizUv1w0Xy%%{=Jxfp5w$m{!&*R>1yO?U;Y3j~~b1w9G`{dk2!T=?-zQXE(% z*}=bVy(Nu{6rIG5xHG)K=QlcTj@-n2uVyM~A|& zbSXi)0+Th5d9xDr8`Q4MQTHIyA>*t|T+Xh=Y>v+TH16=c zT)+!e@u@Txs&w)Rbmsrnh>g;_ARAn`yeCiR*Z5F1tsyGhjTr9}m_jA*qgdVgvZj(4 z;h;`75LJ%W)mRkmB3>du(@6q69ETEfBhz!l?@aZvG3hgRQJ6FjNzLNv6SXBwXY}A& zBDUS;{ex0&I5{|oYNSXQ-ish*<)}LyB!yhgPqxC?pBkr3>^D_>@XE6tma-#0x0Od(``i9mfQm zW{RDb1e`aEoxcg(Jau;*E~NZM`_n8|iw8VJXTuE8GI{A3%o8P(h!c3^vIBpb&ca6xumA9XdchfdprIUsF}P1}AH&zQri+4;xD#b_#`$31GNj{*U53m_R90s6LpPDdGtu z93@J^D@*}otAQ3!GdT_%ill{>2eV|-q%NQ&k8#?tVvo4X$56yC+=FPv?}X9;xX8p4 zwXc29)L8(!KhhSF0%wh`Ya2!JV;1QadiaG=I`CdA{ZCxYQ7AY{4q2+Hfk%OhbTx|2 zYZzo<7u4wXC4*W3S}HNewlKtG2Q6U=igOS3c$x0!760V+g9xw07hBhx-6?vC)pA6# zOI~JIi9Bz7`MgskXW(Vd*iN{p-j-?Pw{v~w94(7kt%<<`G4@+|>iyS#-7qFyv5Z24 z)w8=oGnJ$Ik>%1b35ba z3l=?-Li(C3xt3^4Y}X6z{(Cxu7E)*neF9@QayBc?uvyq(0iWRpzOm$1ty9tG+&>kC z#UaH8JSqm*=}YBby)7B7YaQhS0|2SMLzGzdOwfS7ShhWWC|i8k{EOrsD0?hY-4w{u zuBFoMr5dimds&HVssTV^fqMYny^7|}T~#R%5UB?m*~^~yZOMIw+h-P@1Msbn_w|`0 z?hMkI_MXvMIE*s5hoD(CK0HpoOtPX>aNS7XIO(#_=6zpPDL&aJ>M_GWfASqAMi|(z zMv1m$0mgVnMuG&J{=wozrP=4AmMF7X?2?@TpRL7JOU)G%@lB7a16$wweis#65t7?F zv^){wJ5|Pmz!;^_NU<`YfT{-fw(hmEy?*^Ks#8_+NZl{&K#2vQ++c;;l;78R&?v9O zKC}PVfygGwuOL>SWOWrFTvLVh^|8s-6YHz{(!GaE_|qQL<um*k1i8;AZ)37p5AR@f31=wj&Z2sL2^`|+h+9sYx^AvN8jySDaul*qhQ~i z#%iCOZ+8-V6;mTsrL=%Kc%?)waicDgiby3)WYdfmlO^DTD4A63MI>BTi^){uG9xaR zs-=($V8-^sGbr~PLCjabQoq+yDT|bZYf!+G7(Rg-y}zg#p;*PR{|B8wV!s;9LpTJE z0wlo$B!U*7!aT48IXnUcP(wPr!W2}12q1zuw1W~8aRwAaG)w`}_CW2D!zY9>2#~@# zurV4C@c<~nE<~>lpF;Q6ZaNqU0UUrI1oDA|FZj;Ge9q8ROmJ6}oI!vN3shU^1e>=_ zMHsE}5hOye#d4J#*D8}v3wGO`NI|t#=%LE8E!$>79a~fMP$~+uF&lHCG7TLs<1Y1GdD|~vbr!h%LWXS$~fr44cCS=a6lr6131LO({cj`c>jSa@Noka!#G3( z2W){WyaEMa!8pJJ2XKKnL~HRzFFR!N@3MnAC(9>r02a){9bZ5@xI+{ufh*ubF@!@D zfWRfF!Xw17J!CQ`Tf)=o!UNm^F0?KrD0BkQ4l2|G-wXpTph7$7gC(@IDj*Idv;#cf z!9Gucwzfkim%}-nLpvO_0)&Ap9Ej9{@ArxW`98=+fPpnvwN*!~MwxIoZ#7qUb)&Fw zIEVG9bk8JJoQ;jcP?rNm_kcNk!ymMOIB5gE|1T8n8oTw}Wb{13PHLA84ywue3buFdZ{($r^|n+`|FDbvvYkDICBqEC?yf zW4T;JuO6PDUbS;;ZpCV~S5G%}S2v-6wOBLjI0HvHpL00~Hw5fLJ=lO6j6-dwgF1|M z3yk*A?g|1tZ56wXDh&2utAj|hgE`2oI>>`5z0+eh3 zC;%4}LpM->;Ot5OXsdpU16~in4WNQJoI@s`13U0{15iV4voF%*Lrvw4}zgEH6w1+)M)4E287`7V^WI#79G zp8`7&^*MAy6sSRmSGu=;?*Y*Gxh6L)Z-oRdH;}KoSCX)FA33bYx~v06k}LTKZg&h% zc5RG4)20F+_rybD}aB& zoXdkblY%&?1A-@lP~WgQ6!n06wzh_QnU{mimj6SU&-prFFC?foQEPczd#gPBu(@Zl zIg~j&xWfVT063h3a1%GFm&1*l`Vs8-mQkRpv%17zBcNpStY19FXZ&8&x~+>EuHQyl zUpq4lKn0X{lv98ZT*7_ua5``U1!#aMs6r{gf;mL-6vwysv_nzvd^uz?z{{)*yLm*9 zLpV$U7N|o}d$t863opd6hoAG#@AnsPLCj~uF02F4pMyKlPD97re_hy@$~R0Af%tMbI}J>P>^R!54)2fpABK1of6Np*Y( ze*CWMx@~y&1i->T!*dZ-fQF+&4&U<<5C4D&K*B!1g9pp0I%kd{LxT$)3LLj^oH%vn49Xj) zu3STN=PsI4H_~B8j|WAzYbTOpM~VzVHUz2e9K>?#LSi&&@Z`sf;y(K1sO|u}a|e(n zRl1aE)1)p|tT-~2YE`ROv1Zk}mH%s3uV2B26+4z}S+i%+rd7L^ZCkf#vt&6E;(!Ys zck$-cyO(cYzkdM-7Ce}6VZ(zmoaD7yqWXiB1MvbPBNNw zY15}sr&hh1b!*qJVaJv|n|5v52yv_Wx0`qG-l}j1N0@Hdtxpz6X)MR>0i<;$g-1uI zPEY)~`{ zsjSk_%{AF<)6F;GJTt~Qo0^fwJMqj@&pr9< z^DG}b*bmA<6Khg1LkUe((M1_;)X_(y1Z~PJDXrAfOJ~E-pG`UKv{Ns~4E3N}u#3~w zQ&CM-RWs>q)lNTQjaAlJX{{BlES{K4P)K?0)z@Ev4OZA;i4{yrOp#4iSt~X5)Y(lz z6*bgkh5={QYq8Dt)KgnUAE|W&UiYEN8wN)S=&>TRQ+#p{x8CU`_=dSm~vi zZu-QEW4yTIsj05o>O6f6VTB;;B^j}uZ&r+5u!|%+Y(-Z#yRV$p_ObU zZrF&vyELPZ_9tnl0S{boX`zNu>Z=h?T=B)*0yN}7-(EYi$XV_WQOXa68*-O1*NgJb zHJ|(4eDyBfbkg`f`tQM6Z{79i3ODa?#%ZtJ_S>hzb*{&|#tU>qQzmlWv2{2Z^v8xb zO!z`I!yNd%j{gr`z~?>BJg?t<4{Z6~vp1eVm`9HOZ0fJKK6|h43cmQgNI%_uWm5-u z_1EdIKk(Sgn;rN4`R^a&xOT@i=xI-RGvkc-8biMFEs%M?LZI}Pq`n~;a5E45i`py* zK>`AXW@eLF``#DApvfkF&zhh8P?*9{;ZH_U@!tz!7{gk9>;$|^-vl?fz8j*ffZUTD z%hDA-AO3KMz005u|8qnQCebf4lUotl*24jEkV)rTBF>tKLn=b?Yf{7u2!WP25k{zl z&N`tA(U?Z!ASxNE#sS{f4=tnPl z4Up~zpcWHoK~b7gInt1j4|VBFVH#7J&eTcglqi)b>Nksyl&3xQ=}&>$84{lVT1=Jv{hRVt% zq#$6eY;EgX<(gT|hKrhY-RoyT8(Pth_FjGUD`0o}Q+>Pw4G2KM2)3{be>~PV`mlrm zQZU=z)FTQ2z`{Frvkzt=$9J&*vDisZ~z6g)uids@S`DpC#DKe#Fe)6r7@jp z!;lzRCO!y?cjFIm0KyHWb^{>5p<4~zBMJ!U!E!@AXdd4K!fN0LbOlfW1^*-h8(_{d z7HliyB@aLiYz6=VFhGF-Sl|@&1%LuVAc9jY*B|aELjZCsXaG!L7ylUUeuF)LVXHwO ze?Y(&=o^3w@I%J{9`i;6J?J<811St5 zYG~AM=z<`?aZ!K3BMNKojX!jp0deT#$F_#eXQSNSONjR^=P~aP12+s`rdB6 zF2Av!^|y5P-vsyi*TEikcp2PMo;C=mdoyZOXSB`(NQBJ=z2hEt{QuTHuX33Q%@1}1 zAOHaXGXNSujh2`D+|I_reKi#HUB|=E)5iOLb=>#A2cGc_hz0^G@PJB`0nJbEjkf3g zVCo)#0#(1T)={5&uW*;rVt4)PVIO;!a+-t)Pk3OtBe2LSWaldqr1L7-;jS*ZV7e2$e=lh-HO#IY&@Qp`0lE~x3#b7cv_TaF4*{5s zu6t-_4j_=~yi~x)*5&wV-`SuF~HP9c{!Le}8 zwICoIrogqF&hvN!^x!Wk*sS#E@9OYx2#GLvL2LjM$#b?z%7Po-DttqCP@5-G6~8|9n^umBUw zAMRlih=2kFpaYcP6!xJT(0~Gr%nBf342_Qk9cxpdtOT@71R%lKz^x6vj2DXR0aWnf zL=F_`kjz@n%c5)+Yw;gwZP&_7?m)^AdvNrc!XKEa5&s{t8Z(TVO34znaT~d@8xQ1I zGBK=l%g{DO?{?$(I7RPN%{Nr79m|nZctah@Y(xBEA2b9W=P}goQMcCdqaq6*bC2E_ zQ3$QEAR*CQ>c|@vav>SAAu}T!4J;xh(x)QJqXshHz~TT5awC)WHKw& zaxK~NyS9=mnadyI;Q>y8A4)_b#Zsfl(k$OYBmeo5YCN(k+j1}ovoNRXEe-6sxNXe* z3&6sP!iY=&Mt}>bfjOqF8?1m7@RB#=;Q*#!01f~weWU7(3M0S5FBb;a~rvHI%~dNURU z00cy{9;!gg?DOV$;S-xo)q<`E&Ji8wa@yvy7Q=zaj4ZZ%^QVTY+WLKG`Tv@1%qME_G$JHvu1)3Zfg^hJqfJ!$K?GC&!o;J0iG zz--F`GyxYLf!q2^6^20>%7Dk{s{vf$7GQxhW5EKH>*6f)9SW2m;(-J1fEHe13ZiqY zM9Lo|bkF(=DaMRC*UI#+^E6cysZexQ)-*@j6mi~kEYK1*VYE)|^iGvTM)flOHVVN^ zVZWr|0}??VqRzj%xtqjX9y6&e5F_rhwZB(xXl>j2(ixxV!s z%oJ7S<3z=RRXJ2utAbYZgf(lG-{duvVvN2kW^YU|eY}1LTwC9v~8$ z0UDs88K^-Y8UX}EVHtEG0_D@@Zq5`I^WrX5Q#G}}wzbN-mCSf+&z=k^sI5A!4qdkb zUc+KuGZLCclwDsnD_j;$X{2W9BRg64J;;+^efDR8b}{@_to(G|c#8l4tV(UIH@c8y zu_3vlby5|J0&+0aIF>G{lrF1`x2iU%9`p}-6DcUvR1bhmE$mF^qgCAlXGs)Xz>{rT zlSWuHXz8|Y?N%>_R;+0B75{+~0d&+79)JyQp%)B+6QL6ol7SbBt1&J1$tXbpl%Nx6 zp%va>7vO;du;4f|l>?N(6I$U9GB&t$A-)8SbVpY-LyF8qjsv^^7Y=~i63oF4jRTMZ z4WMxv(Uv3OmOb9KWp_7C+tx$z1SwipD^4_4=k#uscX@p_Z+mhy6D(kt3qrY%96sRy z0zd({fcp{@6)_+Kc8)hEbvNWe8j=7NA3zBjmK6{cTR8v*DqsL^;1t?%9&|z4-a*iq zjURxM*&38Lh6=&5l(N9GGm%0XU*P~kM6J$NWzphysRDxcWJ4u*W_foiVih%2vx4U} zDJIw}{4#?h_+70cF#nnNgi#nzomZ^Pk<4nYz-DVx1{5D<*rRIh9H(=(F11rGuH>90 z)GT&G%Bmj!S9PUPAR8EzDmZSl?ln{RiJ=%hR~Rk_t7D6pB75>wnRtt%sb{13i@|s> zrCRfAwj`7$g$C!-4svMaMjWJ4%*?5p+ zD0%bvkP&$#_n40vnM;N$8EzqxC3%t~S;COGq^OaQH5qYCIFUX1lf7|~8+nugcsFjr zBs?OOZ$ZKYd6Qk)cAOZLWqFn*QIs259&n-1;Ru3}H6DxYV z8LYlJoXMA3Zed8ZR62L71}H#U=@B4R5}q+io-di6b60qm`CaRkpG|sgM;M@MWP@9p zD>OK5PkNx)!lu(gZP&O>4OyXm`lm6Cp+Cx@*I5rQ5lqyDiu?mL0ph zy*soZo1==B8ltxMfXxzk%pYQ5znH;EkFUK?AxBq`wf1Ml>K5FZm4REkmHSokS*0KR2t;^gC!E5uo5JauJCl34Ex4Fly16y{ z!v6!ixQY9wP29pi9K$_4ptUo_kC`jH_`7Mm#;Gd2IVyVJfpI<7=brWyXblie0a+1% z0O*oX*DcM!nM-`E1v*ee95%Q9p$pYudT)zDF^=2xff5FQ3Qz%LA*;8!3o*Desd3U%aoUWIc;&*-F)Bfbqbe~1uM$}c|1>2sLyX5uUEdRLs<@J8= z&nD(E3Sc*`Vma~AtIWUn-Kk$|&(i%Lx?u_kpaX(zQ&Ca!0D$;*!{4WkGci^c${+>o z;mN=@$0oq#ZV&-T;O%^q*1_J^3EqK?UD^{KkhBd_I*0JVdSfg%u+e6KdeQ_UX&V^~%9eMj7 zAeoZQ-;&{4ME6=F&t6s8|KsI8f?@Ta(f-(R|MibO#QS{rbN~JU;>eK$2Lu`%SkPd? zfdUsEdC;`JAMo~VwNl% zSGZV;IkV=?oI88|3_7&v(WFb8K8-pxNvuz!R(&n?Dpsv-Yumn!J9pZ)w(I)-Z5J=& z#E}UnCSE+b^5qJdJAV#6y7DYlj-2qQI=lAm+`D`K4nDm2@#M=dWepWJY}rp~>wXVE zzI?E}YXiSu*TvlxgONk`FI{8+2B_SC1RjWBg3e7QMMsyJ2mfJ&5>7~Ag%)0jVTKy+ zgkDpwsb>{y?#)MHi6)v=pIi8?NS6r;z6fKCGR{b2jW#ma0d^bi$YYN_{s?4{LJoOh zhvj?-Vr(Lw$YhgFrkECsQW9i>i#A?~WtLiQ$>oe1RrV2)Vvb2>nP#4eW|}`5iDZ)O zIW?k_a(?B{H>m8h)|_KOdDfJETG?fwf(}Y(p@s@HS!EBZ$!MdFJ_>21l1{o3n@NT^ zo1R_CV+jDBemZ~}B<>Rn1k`+WPZ^&AAb=YDG|8t~eohG}V8|ILBXPJww(Ft(_1av4 zTLRnHufrW!5Ovn+NNKaqJ_~KM(oRd7rI#w1siyzXp{he1*iDa4H^^-&;b`L%k#<< z6^M|?KJvs800IGIaOzg6_P`HSE~6}SI8)pV!YR7dCl5gt91yfW(Nsaf0S|a_z&iv5 z5P-eEnSiju7abSuLv8=H(A@nUI#Jz*>CLO%|0z~czJ4o)BeNDCj(FmVFV1**7+_4umOs3jASgM84ve3H~%e(V_a#S$lmb}c}Rl@6~F)mQs55?p5j&a z_(Km!wn3!TBML=B00jbYfpn3OD}8LiFdhjEe&`X7|8R#LN>G6cyb*@msz+Q7d4TH? zM29`RSHKKJL@sLad~u^Wi7MF z7b5m+e79^^b*{s|GfH!s)U2j8ft1Dru91x&W5x@yp#U!!19>Uf2L&Oav@-nhV;n3U z2h6YxXh5SG)KKKQ*2$G~ZbcuB0D&l$p$p3`uai;0f;{J0PlCV;F5)O9aDJG~UIKHN zZnGOMSt&(~0uy}yvM4eK^uCQkQU8|2d}3n?62FYba+MuDCNlrxFw0zXrZlaoO>df- zY^n!=++1PEM&=J)OkfxP(1#x<_<&QukyGjlBsEgi0+Ow;c8g3W)4HO^rnw^uU)Yul zFL#@^K(GuKpyUd3xDSWo2cjm;rACFw(OCX+i^k-oMq4?)y52RI5^W+#k0mUXuGEMw z9qcRngUh;gac+f+CQcs<*~m(EvNh4^dbY_%H(Jdf*a+P?%Ya9HevBI&P=YL4F@+3> zV;{Ouz!p+Bic^8p3%3x3I2h?ivmzCp5c~rOKmiS22$UNiP=i#6D=L2=H!NZ`nF0;~ zTXW@5tv);@Vey*Ez8dE^CI8)*VM#jCmyT3?t^^P*1(T4u?sdJvIt;2JY#( z{PDn!wJ}~^;Z#|tGF7j5tSo3=VO5&eu{^=~T+HQ)1M^HLAg@ixd_{;zizv~O`Z7RP zj`CZz``!7)SJ6~H^8b;aZ0Uskm5T9=bl#MFXon~Znqe-rsZWjSNsSp(?dd6Q+;ItV zeF6inIuW1WGcU04STrvD+~n5Ks;5$BSEt2mQW!A_%%EF!mnGNq;x$~@s%-q}d*6>q z>0$X@Z7nsn+ypPU!4JNjb7QO3@?LkI=iG1<-NxSc{&k~wS!sZ4{MXDb=Ee_wBmNo= z;Uq7)$xluch5IAj5pTJP=sgySAHdh>P0+<{{&51Ox7k?EIg_`vWpJZ>=tM8N(JNKJ zYb_j3E^qqFC;u*Ud}rI|RIj?#uRfSjkNoId@4DAXu5y+)T)8UrO1EGEai_Bd>J*nc z$gvLhxXaz@-~PJY?~eCWhaIz;A{7MyfPfBAffV-GRyV9b3OX6}s%j?-l-zNEKfY=o z-S8Pf@EmpP&VBQo@4Utbp7+p;e)N*vd$zPiVN*;16t`#v8aN>Nw72mdjlgH)*S^nJ zL?QAl`-dk{7Z*~t-QrzRZ**=R(qwDf^PLZ={)r~iDy^m83&91Ig!QkH-WSSUB=bIwN@VMKiysDT@pIM&B>9FuzLl1^o%M@E$a zG}r^T zr4OS-fCsQpZKruZ=U#(FfjCzn?6Z8Ib})>_d@-VRj>UmtD28LGYDuSbVmBujB!Y2d z2^n-wOCweOuy_x|EmCno8K8oe@Mc@}K_Rn8K4k&B&@|ozR{rM|ODK78@hWg(H8MAI zLN;k8g=sw3bN_}n*+q%SH*65th5Z&7bw`GwD2k(KCLXvkY?OT@#8lLvNA|!A6aWH- zApZ^!RC|;}d1z2a6o54H@CX<1DvOtjT(Logga8C!Iq?=BP_l%f^ba+}jBqhBj_7s^ zsA=0aL|F(}Of+?JgKhbSjVc8{kmekqCXNj_QMW>EZ}&x6AO$%BhNK9O@hFcKVv3TJ zS!$RxV?}}$J2uPz3dPp*~*8}rl3L=<#wqp(QWDU3VbX~zu z>$Hqp;fTE!g-fP|_yuL^LupO6URdN^n-*}{c2NP>T?m*yz|xW#hcFmXlIC?+6m@0x zQ<4YqeD64qK`E3&nQ&&9F?^>d_-H}8Fk_OGRAyy5YCwa&xE1=8F7LpLR0)iJ*#AbZ zqf~ODjE|6nag;;LC`wVsafPKTm7*jxuRXGwD+5RfTXFY~P4PDt8`J= zMU`9bPzDVUYpOsE?l1)w;0cdO3Pf0hhnQPy;Ymv13OOWv_BM?siETutOoAnsD_KkW z^*tSBWLwmYl!%voS&2Jol8}ac##t;D1uS1^nAxeF+sPD&sYa)#Ktp3Rfj4+~f>fvQ z4UaHlDsx*dqkcUg5796M1khoBG?gG!i7372j`t;<3P?WfrGRfko#(Tbgf)fNSZI91U3STqk!F0e)RM^=ohvGm z^kXof$el4Nqcds~^_V~)NEIv8MrzhZ+=6Fzc5DB@X689(9#dxm+7Z_BIdd zkO_p4ma0UhMHW#Kx{X&Fp~p9py>vglf{w(AaaPKrTIwrwgOfhVj_ydKZR)0PiV`+D zc5rrk@BwpT!E5_q59N>z*D$4RHHlTYoC4BpX_`dYwV_ygsJhgXOLU@Js*O^Xs1m5C zkZKS=38$H=sckB!b?T|Lai?LCr}m%@;9w1D8K~YvfhsvDlc<)qg#V@-)u6e3=p;hXlA=xk&$Yq;Kti?*0o%*TCDsjCbXnJ}MruwIyD6P{9ozyB3*lDcU zs;%*etjg-Gea5W3W)9E_le)@<=4!3!%BAXht?Y<_+X}Dox`EyLtzfYa(ZGIXp%1Sh zJ=zkgU?Fpxpa{|Wfb43pTL?IJ32>k%uMO+4qerjxYIZ_ZRbX)sT*Wc}`W22S0|)D| z9}BX{fvFEmvL)+v5xbbCuqpr$Rk^`h8N_D(5Dxp<0pfSDUFEMfb^uc_00&Tr9NCcs z@d6zivPEmOM++E&X|hYpv?qtMP7;xtLoU0Jptqq&Y?dk_p#KQ2&0s;U6vAGrWXMe<_ zp756l+@cFG%N6i2V?x?77ux|S6S(_yxIiNn(O_W!sx!#AtVZ=_o&>gBu|qsYaWZfK zHjs^4GMt>)g~0AM-raQ^^m&^vwPi+&ik^-u$zGeT{& z58N;Xt_2GV$yF>vT96R44D2~VwF}(hho0+rTLBL?Kw}Ac0T!u4CJeOAibIO92A;@` zi&m!Nh=r9}fj3O4SrWgVH?sK)#6fIRy2~UNWIK;!4DWyq0`)N?^pK0xwwAwIzP`sbOJxaVGmvXcar^M3eOj$0Iz%d3 zuGN~Q`4T909A)i`u6o>sN-M;LY{=3?#3vGr4Yb6UlZsEw74r}anz;&vJblfHVX&t$)c49(HZIEh>$AxJ|0;J7q~!0*77mg|fB z5XxojymGcxJ@CoCC(8E;&Z7Je9_&?Rw;TKP2cbK@Y!(-^OkHxU4%vXqGW^F$)}_ZB z$jBC^nZ``M`Ji~2U&$2ar}AK>rYEaK6;Vr~Qn~b)}OnI;O)+(RnOi0WHX_ z`)Fl7&`mbcP6nyP7Q5j{jltTE&+O58t=G;1(xU>&82JfP0JwtdpSZ}Mr*IFHPyqli z03txV*6X~MbN~SWxQJj6TZOarAO)h5*cA`}jg3ya@Bm4mep`UHM~&KO%oYE)VF=)} zWJwUy^9l!W*c3MgiXa89yVlFxmfhI8u8NJsTt(N#UB$eWJ3S zx^t?k+x{%6)Oek=o8duj=4Xx}Lr&zm5u}`i;=IPT<~YN7d8@n)<8%$I``un}rC7sV z%*4jqeIBb+3ZV`Nn1Q6dQl@=dxFSKll!zxn;? zq0Zx1^23jA>ZcAKk*;?4n*Xn4v9JBADZFtDdCI`+M()BN8%NWDj1uy|8NU!-W9sO>GsA08$c+4{Hw(dx9sEXjN#+U zZtmv}8qJOy8?>@5yY5yTvolKpfoHSQ9_w3C?PP)NEv)3=?(hFjbsLTD15fZuq3*U3 zwZkyARcjkp%SdIQwOs49UmUhbn(t$=@4T*7Dh}`+@A3G<=mjtGBOeq8ZyS1xXMOv( zfg3M`YbrE2Vwn4~CjJlE47pMvxs;oDMRmD}>ouD@0-b9cvTp5Mk?}Ie0|!t8AJ6nn z-zB9^@=-7KIAQX&!T-Cx17g4{ygFD0Jm`bsfV|4fyo)=|TNS({DO zqplUx_HEoK{mC)<=gC3i4&(QQqIC9Y833;sL(1auC2713cvxy`j0>X z15As*x6Fc&!KC&h5H7B|LeMJ=FO)E>rJgb>izkitg_?~FNhX>a2x8^| zMBYh=q&O~d#Yy4rDdUTTq|+z?Ex80q0WVy6Wr_>L`G=bi)M$;*lOF0brS;mo?LCF& zQi}G~Uq%uVH z!T-26oY2)%)k1K@EKFR%g&l(xc35JIHTGC!lT~(EW}7vw$JK%ia!A#RJo4Jx_UVn9 zl=S&z3IRYMC86ukr~m;FPPvDY3IG^D1oZAfV}j}wa>tGX0tgood$8lK9w|;*w}JrP zMNgLplAu6=E$RjI&p!VYj!>6ivJKIH7S-4$eh!$&QEMWFs>7pH&GlAY54?0iQemCd zK~qOvIpzdWrqJY+ZHD<}tXO8%LXkNXHH#{aH~~dxlU90Zrki&9X{e)?dTPs{MeRpv zW9!jcY`fO2wV0rD$l~8%`&a;%zu_S=$$oWi*n8>ZM#T*`+H2s0Pl@f^hzEY3kVX=Iy{-XwUKUqSXI#X^ zKfF0A$Sd8v!v9bfUFE7kub$?`CnT9xmvarjXT;S{zx|W9I^F%y4_F;9y>QomfByUT z|9=1maCW-mUGJ!s8mD;4@YB)tXA4}6+i z-}c^@veAi9gc!6QhtAh3w~)wJ`4eCbZFoZ*=1_+_PZp7W$gX3d(| z%%+qGiag~M)SwK(2Ay#6hX&NkAvQ@yG9n62CU#V)LnUfaje67=_G+0YWolEM`c$ae zE~V01sZ9UD5A#6cI#a-cKk88h3Jf4!-+9M%Owtf+#MG)@TaP{ta2&55fK4m8NymPw zlU^cKuY2WdU;TPaQywj(Q6+3)4SQI`+GwiN+Gj!i(Hsb5V_W>thbo4lj51_^8sv!w z1$yufjVNiY*lLMaDWVX!9$-uky{mi#Nyxv(R<^UHZEdHb%>Q2{R=2z5ZEt-`nZ*LB zs#Z0v5eBka=wQPFr-;XSkXM0&6ek6vWvfEqVT0l5!xDK?$vtf1kJjQfsI?-hF*j;k zWUlkPa=BazQ;aHdH)Z-Vw`bT(zw(g=ULBt=Ccli z>>B=B6&@K5sK3gy+&w)Y5E&4ME+Fs-0blt@ZGCH5wM^lRiMhn%UGWBQ{N@)6Epv0; z&zji`=VO98wlBnDt49`C9rsz*v!->eqxR=J4tcai4pebK019aEBBp9W0GsMTf%9Nm z(zhw?KCr<7FW|x^yFjQ-91;&rix-241Z7#qCrr?x)6L^FVF^oSV>G|FqMr_R8Q%*b z^QxOJcEPi)?R{^2=X*!E_D7&)I%p05BOGX;fB-O{S$@1}IgsVnvMtOIdE5yB4BfCP zCP0&YWLv!AjMTTy?CB1kPLik66rDN9GgqV9-2bKOkgQV9$p?*`bm^8K$_**%OoqJ7 zI2X%1*Qjrx2VLkx2Mxdd?N~7}1UCFQ;@celaE7SOHVx4@PE3qCR-4;r=e1hb^32mK_Xr=^_%Nyv@@Y49&TW3~IJ2|lkGHuZ$$R7Ub?VzJ07|{{etOiWKIlgG zd*EF!_#_&h1hXfB321+N+~;2RyXSrHegAvl2fz1JC`9p%Z-ovdU-`>te)FBrd=h9u z3&y8@^{uakC+GkJ+vk4wz5jjihhO~TC;xx>&3}IMr(gZ+XMg+M|9<#mpaR>MJKa@( zfBfhF$E?TW>-`_R!OM-Rvk42@06~%fLD~QXRKNq+fCg;91&lxmoInb!KnuJ;49q|c ztiUih25W$Z53~kXpaK*qK@&Vd6ih)CTtO3L1V(TLXox`>1VI}7KpKPwRVV~PSOFEt ziyq`b9}Geu9Ks(gLLoFlB0NGROhP6^LML3pylBEDd_pO#LMo)fDa=AE)WR#|LNDCH zC0Y3x+KkUOl z3`9U2L_-urL@dNaBt%9$L`8hWM*mzyM~p;3yo6%N226YuML>ZVD8Wu-K~N0EPxM4j zOanzwgiO4KRK!G8%*0G&1VV6wA0$IstVLVAMO@59UED=p>_uPvMPLj@VH`$cEXKT; zJ2gy3Wn9LlVnYOa!`pBNM%aaYfJT;x!vVC34VZx$0K`4)Lm==*Z`4C^1jlkb$8iit zax}+vL`Qa1M|X_Jc1*`}Bu6ih1#v))aTteTNP`&oM}Q1SfgDJJEJ%YC$TZjlMHq&0 z&_{h-hjM_(aaf0SFo%7-g-qxI7xqw9MNRSLkksL{qEJ>3rLz7HNm0U@dY)O}V zNto_}$3Nu10{Y5#IYT5>qDk_TMa1;A5?=0Xo^3_#q-#yRB1Zq!4Y2uFAn z$EYO7sf0>&tV*byN37h+tL#dx^h!?<2YYA-vTTP-0LUGPfwWvpwQNhad`q{COSqiN zfn>`VxP(m@hO%sjdDzRoBujP(%z41bOyJ0vJWRw)OvPMG#%xT-d`z3vNy(f{%A6yf zye6yC2nqlI0q6iKAce02!v87ieoK^Qp%f{fu}rxJ*-Wtw94De zN~_e(-IPk)>`mX~&E3q+s2onYP2g-$2YpZojZg`lPzu!q&`P-SG=}ZmP!8=-5B*RO z4bdF{Ph%)g6FpHBHPK-}Pxx$67kyC}?H~Ef%-+xwv+9BGh>j=-0C!0Qez+G3fG%o? z2M!2_xf=$|-(%Pg@E4@-I%~A(dPPKWBHxN-U4O1}{)9*9} zI|35)bb}aOQ#Nf=H&vDyb*v<5I5lYj4m*yLz=9a024A}bTo46u2o5i}g*$;O|I0GD zLM@I_2`RmaJ^y4-+SF1>om5H%PEAl7rfUsj_|h@$R8Rd>?flM5I8)eIQ8j&2R83V? zUDeWv(}J2)dC&$*7yvc6(|71kg-8z6BuXej9t+roCzZ7IxUTHlER)>99GQ9*d z?bg;v({jC7jLq0LJy&h2&jyeMW1t3@&@MbJ&5E1XqAU-!%2(6cvefdjM7fDDgUx{r zM}j?Aod2!VX|2}QxK@b$S)dJ3QKi_{Fjb8`TBJ?doa9(-n$xyHE$8@AlOPveMTyg7 zI_1Jw*IQD!vWdB3twx>F1P}tREU!}imNt^i(Ij# z(#j292|e3|^#@MnT;xsO9q?SZWl_?7Ug(Y9!!lj^EFPu1-lb!RH)I}vkUHyt(y*=B zoBtJF@(st!*wMP6^2&AN|m|a%Mt(725w*nexv)%-_-P)fQ8fmF5mNAShYQ14qo54Rbc0RU=bc+64svx zmf-EhMx}gI0KQ<#9pKFEU>QE(5AN3ZEnytaVI5AI6GmagRbh=2Sm1Txvd!SMJ>D5k zVgpWKQjOakeqtz&VjSsVYutxu-~zo3y#2L}3Z7gd&e@$^*aB8!GVb6SKGSbKRViL$ zHg4mh+dEP{Iv-Yu2g+h>d5Hg1iG9!pSa3S1Yn}>j;V&-Oghk&CE@MQN;WB;S8~=7= zM}A~TRtzdO5^yjQZ2R=ngjy)A zWmKB|-|-z}N)6+*O=MjzV=;dN@n>;Kh?I>6utI)Qa}(G>7wWAX_yi7MlfG>MVt@vboivBgGDSTA-e>^7*(oU%;*?ft3Pops7-N{eYeep4J96Ti z?rXoE+nk;{H|PR4AOxM}jgIC~lYVOpmg_5JX@+%ayq;}Dc4s?+=fBQv-A>iOwho@g=i69o zSr~?4Fot(H+)%FUZAslvPyqu|fazH1g-F+R1%P%vZncW$dL@sB9_>~piGBa&Fc0Ho zDYdKCcI~;|SpueQ_P%Sq1|q)RZTX&W7wzqp*l9uVY23)$g}|!p-j?N7hmUW1im1U)b4o#rtxJK{YgzZCaZxMfK+Xf=srf(Ea z@np1bmGB2+4%Xj5U55yc;dpH1SlJv6kLj?oep+sr0FH?v4ko=??yl?{{qDZ)S|`PD z*wk7F!UNIhVDrfH!@0}A@aV_6+yM^O3mE+*i?|cq$)NYa|K@Y*Lk}JuQE$I^E z029^b@6=@yqds$bg_0sah&M56RN&;0?q0>kg-4(le$WML>)#Al*bV<@VJL4<*f!oO zkM#C_@7{@TF28h4*Ebdq9yw=@Z~13(aR+me-GOlzcp;8?sh9ekSJe9SiN5nwc%bTt z<|rXJ1>geJ&W!+#IB?N`Q|MlspoYRLZ-v$H4u^7F)>KJfb}GN}tjY3Bk9KL_u}$|H z<4Fmz0qL=Mjk6h^+sJl{LEEnx9)2h*vyQs8X$_NJZH+5-ML%}AF6831Yi6%^_Lk}9 zRpV*jcYgP+YIiJcucewHMNNsS>u+~|_eKxLWRGookN8NZ^sKS;e!qB(Z$>Yd zrPiBc{N3Mjr>jH$d7$4~ubkNhB!dCPx&*e4du&wN}0;voKCAn^RQe|ymr{oAO48Hdmyp+ z*iU}tzmeIe{XE)ygb(EL)qS_8e#M8@3_cqmL4D%yek%WG{ZgI$C!iEncPONw_Ca3<%@ zo((!U-pq;FCv2fqZ{z>Yt$TOWskpfU56;!@fwc$FvSD*z zE_1YM{n>r1iFsUL(D~t=t=AY|$=<(%4=;W^`SRZ>U($YAAVJse-@}hDe?I;C_V44* zuYbQo*f`be^b=6F@m8RL2O@}+Z?_58po3STr3oUBwX=AoFPiYv0%;&&!mMq*|I@mHgbH{zJ1jyv+$qmMtj=U+{-sVCq~1SXiIl1n0nrNB^Tj@*QvEugc**77KL_wNS0gJ5hdenC%TxXnrpJzreu`GXr^YF09mJ< zcjB3+o_q4yr=J`NSq_of8EF%eOd^`-l1~3d6{VwDfwi2Z8j4k=msi>~p_cx9DP4%y zjc6ujXu4Udsi&gaB6_0g#NMB;!Wyfrv(j3tt+z%L=%BL|8kC~H0(&5%P(4~KR*_Pg ztfiNNI@DcdvI-!nsZv|5wbv>JBdc@b+O458|Up#TO3+uT%2Q zYZbEig1lje{QlFgjQAofFHI&KPq0F+>Q&SC@wg&%ihO^dNbKSMqU-Kw&k+uC?w!1+yH8hm;PH8XF z&5i6dfO0>*SJYMGowweBxojrPU;`ew;DZxhxJhCYO19aH|BCifYDdYo+i%a+DZggY zUAI4X@7=lQRbMS9jfRt6y6LB*&b6-lu->}suJ_Ei>`XeY6yyyS{W0Zn>ASS%nVZb{ z=fe{}aOg5}o4WGLGvB=PeXjnx^sL7|yY&dxp49D9dVKWmV_6Qo=KhE;s_@05pFXvH z%lP;6@53Lz{PUj{{q(O_f4%;@WslVM+)wFybomnb$~V597*Ja3TOb1ic03X#kA4!I zAO$OEL5$e%eyz*j{yIpN{vH42f50hPy#zR>0y6D@b4%c;8tB3o609=Oa^D4OXu})g zPPG5-O|s)$l6MVuUU5V?~# zuy-pU>gU2LFG7H%~Gg8NtIx$A) zv}Gb_ZZn_yM9eMKLql=`G@t^#q&e|7%yj;7okM9SAxlUp0`5eXDw8C4@VU>6V)QTF z)Xp~t>d}vaw1Nc{=713DNrnD{p@f8IzB;rMV^}nOtKyDCGiuW)Zd5z}3@J~0>Qlpw zbb|*qDG*Vr(%d;zE)Z=a6ldy2l|A*QQe9C$IhxC#Vl}H;omo(+H&mjkQ;-ZLuT4#f~%`N{3=-YXH=EG(~w=Kohmmngoke zMB(b#mdW*HSH=G;Wh-mhAL$jHeU;r`+lf?oniZ}4w5MX*^oBD%Hnk|K>TEiC+1J80 zw)4p>UpH&L&W<&(Vj}EIr%KJzwkSR7F|2BfdzhSJ# zv-%^ZZ>8v3%OhNW88^IAjI7@#>)i9AH@zZ(?vbQBT?XY=w<5C(Pv|LL?h=V~4ea3$pBKTt zQn3CQ++eTB^Q_v|_|fY$hJ^0eXkTdA|6`f%$EizsqDXqnR-qUQdpz z?B+M?^2%Aht&rPUBOvAFC8{Cr#me{L??Q2TOK2C=XvSK#5j$w^z*4PEJ;>v+S9V0HR?beYAr8X zgm-TBV`2=;6t0@r!X8YZ^)hH$BRkn&v-Pckmh0{D;{aa<^RU&tLQ1o`+WyUSUSh56 zZ-e_`%x?C@M*Y8O`{MxGUJReFt;TGxyT7l-8p6VD?|Ua~+~hvnvu{^lb;lbq?G}}) zgBSnsgYTf&c{w(|8}9Hw>3iSoGPl2VViklNrovAvIIG}|aq)7yC*FQI$x9wKUy~08TsHVZ~2TA-tY-R zJmiwTbel6CbBu(%)FrQzwO>BdM8Q?6OfZ=UX*SA4)LGwIO(E|#PRyWdYQ;MM;F zKlljAJnRj`d9`_d_l>zG^PBJd=9?(`(w{!{8N13yEC1l8_Xp*L@BOP2zxcd4KJsaw zeQe?P{JWpG=m7uy_h&u);@1uNIhK6&uk6)P$3Mn<-zuxaUjTla{LLS3)SvyCAO8uA ziz(pQZ6E3hU<8I60T$o~$==Z1Ujt4J1G3EiX`uSBAM*U31d<@9QD6l^#R1Ao27Vyb z+*m~!Ph+)U6!{q4w+p`yLlWCLKS(5p!?<1=H*C zpaJ^e4;o<*N}2}-R|{3)8~NYCFyR-X*A7PEQmA0Du;3Qf(-jt>zzr7~!V&*^fZl9$ z9~jc%Pl@3eCPf*VVFJ3L-ss;N3dY@4S|7sE1CC%FA|h7ZAs!xu9y-by65{Z1pm%j# zB*sw<&S4^IVlOQsBNl}tJ|Z7lqUTKFc^KR%#*rbi-6pakICY{Y1`>6(6C|Qy`n(`; z^_q;;Vp<^~6)9mW0wX~=ArCI3?|-SFj`{`y&^1v zB9zdgG%}E$E!n$y<0Bd3FJ9w0UQjlA;x=-lGLEDAfTLjeTA#h+BZXl5R3kd-qYe#Y z7uA+A_Qn(%OE=cz3;m&A%phbp9;%C#3j@{j*O4x~FSWCN)c z?ipD}l4CF8k~v1?NfM4aG9o)V2tkS@6bYB!)lD?MZI!QV;}t^M)n{w zCX-9nqzgG6IjMQm|_9_9p)=h2?A-XOD;`59;Pt znC5T}%x~siaDta}x+Zk~Uu+&{cFIR`qTq5eCvQ?Gz*y%ZNhj2VXD!v>&uQm+ss?vf zpm%0PbDn3l2qH)#kW3ope6CD!vS)v?hIL;qyr+xlfdG1AlW|Lj|=Yy68 zfX<(QUWI%zsGA%pf(|Ad<>!UkWQH2sVnXPMx`c#^AB9#ZfqLkgfT)IQ2Vr*TiXvve zcqWP3=th`m@lmM7si=%b)AIpokP7LL!eL=epO0=+dgkMeGHFHRDD3TMeO*G2B56il z4Hj1ENLr_QHffhW#FJ`Xlx_!>X6aP@p);0gDv~6C)TsZLb}5(|o|w)C45sOQ$(54T zsWvI8NxEsD76hEioty#)o#ttA6%3(DO^o_zIbx@ujwqmVoq#?Ko))TV9V#vgOpGWh zl5!@SE~%p)C!`h~idw~_Vrr$r)unD~wk#;BuGVXoB&gb`sInZ2Cf!wxXJWZ(aoyso z5{B6MYL;%F4K}K*<|VC49H}ZEte#A;?rIv&6Pd1-c|I#-jVA;e>ue(HzA5X)jaiFA zowHVJ-dyRbPUpC$$ew2FXKpLGb*o|2V6=)Wy1L+QU{ST`bFD z8pxVm*y@w27H!kr?7?QNRTXR5rrz0Rnbpb>+Zw6cj@EZYmET&}+|n)92AIU+?d9n$ zkfrUK5bWj{F5ps2lo4*nO|HX^?cFXe`1Pzop(W4;C44ay(VmCPst40j?lz?dW5hl&Y6t(#u5KLdm+Q(H?22r>_G|4bTjP=#-&QW_ z2Cvo*FFejhsL*5emP*c&E%VNr^D5ZmI*|0vDfMb^J;@06LgV?GO4NFMj}bZttq?wE%DVZgBq|Fu^f!Va;$1T`TR{FoB_PU#W2M1Tki)ZW6PJ{(@u-hpZKg zFySt56XVqrgVhDwA_QNC@NzMVxTycr$>k7pF!ypU7>6+qTV#Um@aR5C>HcuN)(sk` zF?f7!)5WkGhwv1WupBp+7!ws4!w?IPDboHi8?JHsJ{=*u@c+g!B8QYBn^Y95=}g{l zBnRRo11Ho#vM7tK8T%X)YjRIoJWILos#S2H>5^M^)j zJ|DE2z_CB`5lOjLP>Nx(pcpBu}Xu^Mh|g9dh~FDbWC5-On*{M+w_q|E~V=9-jpj_ zEi*P7a<_4_P?ru-e^ETwSX4jtQd=QDpNb%IH2%h`&Qi7fSaneu^@C9KV`()lb2Ta2 zt3rdvxu$bamo@yH^$%h7pUpD@zxCc+s$4Iug=KVGZ*wN!wb$hJd*!hnuNz9!^IrpY zGo}dJ{`7^8H7h4J*ev#fr8QO}bDkY=6-##2!0mWU>Ra3OW)Dth`_*TIcI1sVMwhm= zu(V_pF>U`bOtZFP2lM}J>h4}298T+YZFjU94)y_s^=_|rZ{Lh-2bnP+GwB(&kqWkP zf3>|Xh9c>laU1OyJNKV+r|Hd_76mc8&ci0iM?}hYy*GhfQPI)WeeqXkF2lfttzgBPxNthBhO z!M0>tB5_mrTWg$+M+<-Jw1rP~kL$;eo6Um9sgk0%wUQd7jH-d^b6qx94yF zEHRt(GCDY(`}rs@FrO3lqVo-)d%2*yhMYUwn9rVDg1C}HdS6glmY0a4WA}FlI;DGt zrDM#YFXW~dIT14+sQ+!J6Pu))`gRh!4ij@D2KjFGCacT3BxmsvU-YjR2B{-q zyB{r%%RB$>xh|(Ky16I3!r%HZ=X%hR?ofvIN9T5WL$$zf91B_ex4ZkBXFNkJe6Xmx zjQTou59u`9eDt+a&a+Y}LtVW?2FAC%N4z|+^t+5kZixGQsmxnNT~pGd8cMT#!VkUC ztvd#W{CpmL$~*nf&#cxbz0o3k(0}R1+i}O|VZ(pt({{VpZ~gM!cH47(ifgvm|0&sz znAv-LV<)5Au6@DNyya3myl<_w)4f7Wy`mI-wf;NF!#!>bF5|OFda(V|g8keh`{8#T z+Nb^bf;hl8er5kRR3ULW1AWV5KB6SP$g;ZNe?Gf)J?me2i5xWHpZn?0UDZ=z2(NzY zLvH`qPww48KKmZLMnlt1H=x2 z0|^#1co1Pig$o%rbodZrM2QnARU#3iMboBK36KGJOLx~nOdK76=rAwJMb@~))RH;*`R<(N7XgRH0x2oFr z6>QkBs<>*c^$%@YwQJe7b^8`>T)A`U)}?#RuG#~8`S$hu7jWPMI|j=%d>Cj~x+;MVcmXS$o?0gz^YSorMlfF4jCsx_BY1g)W8+UHq zyLXr6>Q!v;uVl-f&3hbqa^=hI;zcePdi21AS68=w9ecx?t|5oc{vCXH@#729d^|ZN z#*y41ng2l+!wetV&c2hp(-6cEMGVnA(A=A-!_r1vkwy6Edo0DA@)MB88g0B0#~gbjupHnF z9LqNa9~_d%BIk-QFA9|u%)%C(e9}4&W9;Z7D6PB_%fsj+=|t_Oj4Zt@#T@@LvDRY5 zPscRXT$9Z<1>~{EAH_m&Dh)ow>C&^7VHfZg=7vFrd;&Iv^tG!m+fCWa2+qt~`R@QhGwi4MX z&0QGch$mXN-45TC7~}XbO;J;QJ^mQvPDd>jtbYeS`Q(D-I(Wj44lw@)=7ckz8AB#)TQwxhIw22*IU)y8aIj%Q>V?zrWK%4w2Ko*M5|tA^|9=t|Oh?Z8#@Iz_MrKU~nr z%s$(u$q;{>v5h-acJ9h8zuc#~OT9bq&h<>LZ|Fz@9P-lHCcHz#OCfI&8dyr^WY!c`>oIg^Jg!@NUxpwnA(o<*XE`FZc5l=pMCo58#KPw{8QAFcnN|Ae?_k804!)2gAEe;?U|2(f+^=F96c!C_IKBUI$9p6c;t;1|!r&lKg-Lu11KH9-7xoZ} z+QFfHa27=?#_lFM{1OkX*gP3>Cxk>4;~0rz#5ti*iD_I56W8KICUp^x2|*ndIT*+H zO%aP_vmW&92*ED`@oi)jq!`Tzq~fR%k!xh38~@TrM;c^~>`~n#r-#Qpnq-ge;vywY z_e0kNaFC%SU?EF}#zdx(je22ZBRSbhPjY9Htt_1-FPZ;Ew0v!ovYci7=#>dk{*rg3 z9F8eZnZ#74WtFVdr7L-Pv;8geaI~!D>uzZ=Xwq+j>nMC38il1#r` zbD7!HJKy)p$b_+*`MlRRktj|TlJg(t{1ZKw`A7EDk)R8ECp_6B zPn$e5q0%$xJ-4Y(i-L-u#PnwZ0V+_wMD&`GJZLUKTC0UJ6n~jC2|`O+I(53Hq8F8^ znlc*BjT&>20&OWeMH)1c?sQx*6RJ>AdNzl038>k#CuHzBQ>VU(Urz&Pf^MqBj(T)? zNu^{@NmE6wKJE=+73)~ZT2`}a1g&XRD~t}6*029+Z=#Wj=~L;-o0?L!s{hQXIp5mO zrAEf9eYInwq9<6Taup|_tm|TLbJsfMRj<#%s$uE*QdmNivQZ=~W;0v6xF)tzY`u7KV*_Eo^tmR<|u{w7G3cX{~iy)b6!~qsuC7nQ2>GvXi(l zdu@nVwDDKDw+n1`R=QsRqo%cxfp2{4I$!z<&%XD)VSSi; zU^x1BSQftEc@2!1`#Da-@`edoaM1*F?^E&FZr-ADr{z4qhu(5C&8e_ZIFc=)u;87 z$S7N}8#h!R9A6oNS?$P$CB|Vd$ugCKuLruEXavD{W&9M z?lrOD+USQ)o7!6gwo0t+AzWuW$IbtoTp*KOxn(muTh4y=rYCZ1aBsNV1%5Z=%*5t` z7`I&W7LTg!Jl%3L?cC^ImAXR*?Us~U-~8kEwG)0gcS{6|-)^{v#oaw}|J!2$7r5SN z?LdROHeyG`?{>5xj37mkGjM9%W%Yx#v22 zvmD{s@}SR$6mi4D@@TVho0TX&+m~lYyVHMXQ?(C#>c-Q#Wvt$J z(UZ+jS$O|RkS%!sr2X*2OMK4VUZ#^cbf~FUed^WPde@`Xtg$C+ z=0^m1*~OjqywYPe!Jhl;>{{t&_x$GxPd>wkK2JC&y=w4%)XV3Q@4oMh?e!ad=~qhF zC2{`su5X>qcVy|q#|`L_&miTqZ1I@E6H zM%5kyPyh!o0H^A)%8%pNuI;Mh4PZ|Dc(45`=Kb`qGybmRD3DSb>i&QR#4s>5fDim+ z&i`a%WC+j%?ZE&|3jw800q?8yF5{ipF9Jzp0zL3FERff1FmYmJ1KTD4bkHK?4?nhS z1gW9~PjCQJu(wu_1ttGPr(Tfp9MC3Ya0X4H27wSYKoIVJ5DPz0Sg4SKx^Qsl4yJ^! z2$|vtk+1*}q!#9337ODH&hKE-Z~9US0;}*Qu22j=kPI)23-=H+q|gp6?`*aX5XVjs zDJt;JaJK+Z4cBlh+MylZ5Dtk%4(AXG*(MQf=??MGAN24L$FN-_FBGrilE5%%O7RBy z&kPw6DAG_3l@PlsaX~H-R_HJb4Fwf12^3XvHK@--deIjbL+`j_7w2ghr>_qwiU?gX za~v@MRpA7ustqZT79GSEZ!r@!qZoar2YE3WMMVCpFC5$J`Ht}d%dzT~k*P%R3}Mj? zq>%upN)oN{8qNQ2^sWXM2PcQV@oa=q9T^Z99R(l*5+m>s9p}#={f-rzaroe|3*=D% zW$_+|BpY94AHC41{LxSfav=qB6It#fBgYdTkP!K3B)O3tL2D5o5*p{h4aguKlaLMF za26{PIW7`mE~FbVi6cA2BU94*R`S1uGA4R5gF3OwjFKTk5-0kP!60%bClW#G@g{LH zFLZJz(QYA`~G%=DO5+7U81vR8Aabg$! zQZch5FxUSwB{#FEs4y`<(|;P$#9&b_sWK8L@hUCzNb(W=woxw`YAwJLH3KCyJyR7K zvoO8#FuBAxcT$&u3!-fDN;6<<1X>iHlySmRjN3R6S{g6J5?_@t7ij66FVzH z3&Ss;m~$Fy(jK3)IcO6TS%fsxGJmc!Jok+(XAJk|^HO9_Kg;U%`g5%!FZJXTKT}ih zpi+>`(*)@eHr3NE*|R-Y@$^hrG*0c53{dStJHkLm2^wP&J!5l8 zA;dwwMwF;7!dVM0qSq6tD&O~cen!*oo^v`rI23-(k_*_0rf zKoaEiOZn7RzqCvNbs&sjMNf51ztmLAbX5<6SJO03XTe0N%`IDTgphPHwZbYNb%7!k zBd3#6iwe%B^i#29ART2}-{ZU{5KX~!706UZ)ihTZLPbwCOkq_Zj6hb8bw^1w7gGO0 zL`}3!J#jH3XGLd6=GEVHB5iOPIWcm4pl~!)77L!G9M8ImDFL~0%9w~S|=79JtN67lw()1 z8%eQiIb+-MR8VymY2lR&PL)OzLSMbKT*1^`-LzHXG)T)s``$%mb+!pyv}b!YT@gZG zQS5Q^;-f&_a(BT<=As8gVU;{NxRW)sK zHHGEQ*p9|XGj36vQ)>G+E&kVqBv-_g*9z^Yc`sIhS%XurErEylA?W{O9#C+~@^)?W zbbe{HWOa9Z(X?Gx6*AVr8=N5+oS_spfg)PfUxoF9>-YMs6n{TOf1MMDm&kaJmxsBs zBNu~!kytZ((s}JTB(`H8E@2Z2fr81@3Qjjxop@$3SY)gCgUb{|X;cz=!5h2*9n@hT zN&+3Kfs3m_lF^|QLiBoTlx^eJYpga9NqQS=RW5+gOL$XHgn3MvfR*f>@7h z508cTmKOqEHz5-sxf+ncXoIwS2SSW>)^=AnZijZ5cUMk>0U4ellIP(oeCCofIg+=S zi;Gr7-*+Iam`nk+l+D-%e|Mj1_&ggIhhG_%7e&Ts86n68Y>q6hvAt(w@ka>bbB?ChZJXzwN}S87#g~ZHF+H>`5!JB86FywodKhrp`t_A4)&HH zK-Nn~mXv2zkO^4~l{SqF2%QtOmDl-=mjroNM3!9xo&n94@i{{@*B=BEr(0rF3HDgY zlnemDV>h9cCBaRTS$q*XeuLUvB_S1_L8DC=qS1nch1nUN0U4a38oIixr&?q!*mhfZ z6~vmX$r%t07o%1>N!7W3*?BtRxOHeSbK_^8dm4Iw?mqF_A=VXGgBp}~z&tLwp=|+a z4LWW=bbZVEL}zvs(7_v?AsBuE8L9yt?7<(5MMDVDlW9X*&I!k>x^7fjyiB(|BbVS`&q;V8Z`Pm!R z!CNtyefxGrO>}&XVICk`qoLUw*ufqM+k~A#k}_LmGp`pF|5@MijpIacx7Ole( zrC<9$Vw->4m|$KSrfvJSZ6deZ(yoC!xRuejOX9Bo8*o+jWc$`_@3c_RAr~4tZa=!1 zcYq`yTbO^L8q{ICF`BZg!LvZ1Y*kOw+8m-GXwVBejRarM)`~YKI#v!-Xcx63seC*)P&3{}X>{*vF*L6jf zOLLZyKa|f!`4@7*7J304)?pNsEc>>*ge}|~GMmbmdkQssvMqZZg1L*mp%kQ>b}2Zl zX?MkqGL?zXX&0A`(OfNP`cU#VzE0uWx5!qDxR7`0#Rc*mzFSR5l zJ<1pTnkzk`Pj4Nz*|NQXyyFy_D>@k57O2IPMqk*|sgFGWFVvxS)JeU*)!gGyy@RwB z)-{jLdHY9cH^O6eR%cyAZJpiclwSwp4MzWg7%)3D>f^(w+Op?Ci@BJq)xjq2U6_v@ zlaYbo3!d5kTA@YMbi;GZ$B(U_6~?vwA58sEyuF6%INSyDYwsC5NA+Giy=T*X6|_LH z_q4cAo?y%MUS(E-OQf3aJ<2b8ynms}E7`-L+`>mVvN5?Do`L6|!RLb^<;^wB=d;C0 z@ZlLY;v(J>&B_Qh1tk#aO62-9w3%O+Pf#G2KK#RBgW=PluaEQ=26IVc)g< zvoE>3C)vZbSeS!hxpf}0>t2%Y-W!;G&!v4n8@?*cTm>b5;%9t9Vw#c~5N6IEEmjX^ z{L?@8GxnlBiHq3VR9zKi)nCJTRgwQ&>uvM~4C3=YAF&Jd^LIcCPPMGHfNwiuAGn;- zk-;10!5{Vk%gbAmshRcd0oj>7_HCXdd_TM+o3k_Fd9Cy<8}Zs7G25A*@C)DKdkBa4 zat0Zn`e8fD)gpQ@TOYyBHaw5ZXeNRujE%CxD| zr%<0>i(2%6)vH*uYTe59zz+Yf9>anU!-x|r&e%kYq*cFWNs?rT44KN0XGNAoMxx_clC?BB*o2HE&5}8n z^2WNFvtYrV2`q`un=@p=oUz_Ltr~3E=;C^N77SUnb^GShUCg|>^XJgdUNQz4|O0~TC^XSt@ooc?T`}bVGMxRfAFWRdisNjMOHmJ~NzeE_>Dw;_s85yHRWEy0Wh?Wo;6h;UdGPea2VQ${6V^2x;tmB%A zzc?eKGZH#e&5CgSL@O25Fd_#t*;C=WJb>x|7`s1INY_{pn zi&&nIt)lIpoOMQ#V~<(J(4l(H_)Imd%@ZCnO>6DG{L&W^ zvHV@fWRp+A8s7g;Q{t-d!VK#gRj&|Z^=rQrLlo^>`5~*ZNfmeOv4TY&tMA7om#mNx zO*E#(p)8A5s6;3q+JzAerM$8h=;WO9I_k2u&phj_qqELDudCKjZUwzFq;IWh^3zaj z6!MX+mQygSveHB=!(4Zrp2JW@EVfr*MeXs$#Ui~ivI&~)_S<(&eWqYe!)`gcjjvTJl)b>FS{+tBV;_0>>j9hBFUS56h!PmK-n#EVypc3c^+&0pf3 zmu|X4|E5Xz>8yADx#%N>Uee%hjokX}9j6Z0VAN+{ar4l}uJ)PIYcKw&jkCqO!95{7EAi~JZ+uh8^UC@7c5+Ye z^WBR||Ne@jdZb`&3oI+f+d3 zAuxZ++Mo!b=05`gaD*sS5WozWwttK+d?}1!eNqQO->FY)70hAR-p3RSc4>Yx1X2e9 zBfGT)@rV>FpPaCV#3mkwg-604;+#lD`qU6>H=LXfw}>kqF2#pG)L<3IB)TG|Nr7Wb zBdL@KJ{YR;jT6}$6wxHb+PM*qc=X5>BbP5uY zHLJPFUh?FZ!3-x znv|dTEZjbwxzQ04G*$*ps7#fz(5f_4D-Ug{UDRnw{Gm~&Ks5|T^`p_C8ucPdM9}|H z)A-W#jc2A%HA+p1a?`Bjbg5+FDYA-UjGtolt94;xEWHZWvhF~MMK!BSTLn2!#x$yM zo$64kYSm+^)gxNf7_qi_*S<>4dTCOsU+)^Hv<`NBO+DCC;Tl!B{)4Vpx$0pvl2JOov~UG8La>)GH+*Oj$p;({otoa^3&xQjJz zLRs5dvUyh{&6NvT6@uCIo_DZAt~2Beu#h92VjJfH@UCP@IsU+y8Rxcy&|5hSWQUb z6eAO}CN_(Oa~Wg)ZWxCh7UzfQN?;eCcx^R)7GTvBWFMn*#q(^jkz3i@B6DQMX>qc2 zZ>+@}2Xn_f4)Kx?BGF^HGpqN3@Rq;Y*%xAX%z1R+f@NHtHAk4rezfwH1)OCxGxu0| z$*!HvTIT*JdC!c@?wQ2`<)#4|&IgsV4zXO-9;3OrgANOHr3`3PQul?GMx~(htlKdo zTG7B{bVD6&=gLx=B62fqrh)2Uz_@wUO`LF~EmCM#Z~4=p2BoM+t>yn!^YqjhnKZ0< zd*JR4yO9&7bgkPwYvJNL*MHn~F-Z;RS^|3`vOcy^TOAiMYx|8b?#QzB^J>^W8`@ix z_OyFF>;iuIq6)tDx8I25jFx-e_8juP4KnW0W%%6a&Y`*qN$pJAZ$aV4_eT3n)ITfS ziE4KEh`YCMzXCkq6dX9g*{$u@HM==_ez-*$E?hhNlPvc-Lc)RuMrc|5U=d;{7xt|Vo5hnXt*JOD; zi*9twAsvHCKejTpo*0~0{hi!K9NEvlI2iZ4#64ds*Sk)+uY>=6<_cf?Vw@g#w&OAF z(bK!%;ifwm`jg1!W^3=T7+$&)&+fgR7|)qd`mCGZ!2rRRS`(mVlpf90our2=?OLv;`c zdr_24BGZ4!M1Tc&B?p*1704{yV}B0FHX&##5@<&nc!K}r(^CKiec^{h9N2+X@_``8 zf+*-ghF5}~g@epfY>4NB|F$Vx#qgEaUx*2il?2rNTHf;AS-P^5-YwoynZhUQ^|85D=4 zqE%2Bg#pEf!9srBwtRwEVb?^52f~H|bcc9&Ib>)~@^^?cWFUVSg_Kw=gqSQ8n2GiA zcCd4a0{Bjj_=w{aiKR4&o_JB~q=?YBiq^7!%C~~B$QPh!K#JIj1LcJgR9vQbD|)zx zwfH6nCW>>!h{L!TDcBa~my93>h=hZIc2rHJ_>2Ed5sYEvj0Ch*(kMFGNHNRE7J~JS zdk2juQH02dJJo27OM#8qNRDg*ga@>Rvj>mc1BByfkG5!zWkQeQn2x8jj_jBe?r2K- z$U$Y)jYo2j9aDv_29Tb3i-4$p5V<%4Igkp4im8}@3|V3F7>x>PYaQt^n;3W_Sr!t> zkI!d_B6N`$Sri579;$efit&*rVT^4?lOkv^G9 zs-%WX`82Xvek^&ADG8J}$xON!Lyz-?IpK>&sUAofA4>U@>4b&}8Ip5BmQfRqY0->o z$z{P8m%;aabh%GWNsm*BSZu|W_TZIYi5~x9DVA>;BsSTP{+O17X*O($5^kB8uT*>; zg(~57 zn)bncp;MW(`H723W3-r?0TOX)beUi1ny-0^u{mI#>6=1ze@3C2%DF~wxPH%BKl+xH z1Jav^A)M$#oW+?doY|Sv2{MJrV%Qm;Y>m>I{qo6A&MBgX%gO+ zqePN$1A>MM`X4C@9xKYCQsts!)0QXdqi1o9%%!1C>ZGWNEE`It^l^0n(mYdY7e)FV zM~bAyqoiWfH1LU~!Nx)&3NZhPrVg^B-PfgVDpZv>ALBNp&+(-^5vF4L5BGT$a?z%9 zYBBj^V*VqjgDM~nDV1lMs5=#JjfxSVD5qher#r!?V*006F?Ej07vt$@^hf%8ea$0+dnT^+{ z_DQA@6IiNxs`99Hq1vpv8Xf;p8K}Nmt9<9F>6x9yI-JLftPpyfH>EL%+Ns4BQ8ibt z(+VAMs$bW7s@WPhmW86-x}Dz&t}QCARkeeG^{$RdVm(+G(YmfbXr<~(u#yU-V^NjO z3XpUi(aL9upL_wS{fGhm=_P*mk}$mV@k0%C~=Rn@sM(X_Mo zxaNsA?kmEJy<~w_4#-mE zi(}?HvFMw=>ubA#JGgUGzsV>Prou)ttG~~&vz(~FXbLT^xUCWKzf~5%D?7mDRlo%- zy&P_Zx(LJW2Zz$>b`?%4?*|3$9R{$fT?TR4gZzoXK~_ z7Mv`}mFu&YjI#twM`-y%gG|VyT*{?<%5bR4?3#wH?8*q{wi0ZTz8tC6A=)Iu>V%%cmr#T*#2oT$irONXf+%WT8V?99%*#*Hk^OsRv_Y|Tuky(`S5 zj(n0AI*(}*&Kx|>>P{LYL?!lO#L)uD#=9KiUT&khaE80^o> z34nlXK=DkId(4Ub9G(cxAL_Tz=G)K?J<2(y)sM9CLy;(cY zL5V;{&9_J$F-!f`(aXr>`qWlzy{*{O$V=5iX4N6v(L}w~n%mV71J-n%9XQRYYW<`d z6U_gxlh+JE&<%^QZVg3n-Mn($D|MaNxBIy;=+{}bHhlexjy*{!{TBHd=1?bNnyJGGU&=XqWC4`2KZNsi-_#Ycze<|8q7{V8_gq8@)S2ift-#4Q`o%@7e%;e|CHgIlZY=uDu?gYv%{3(t$DQ65# zAXMTj-|c^(jV0&Jkf?>Dmc(b!mlcBHS^jM_uXTjZji#*MU+h{wu*L~HYq~bdJ8gEr z_YphaJ~l@u21yy)!px&9^;!btjXiC4HzIav09$!kZ44LN-EaI1cI9M%DJh%1frvdG zzimFoB!S7G&+7CSzmXKZ7Rirv>Fj-k&VBy19l>m}3%q?V(u1CuLba+ijo5>4ojYp$ zTVk6dcgTmHq=zVisiq$(=COx7ox5{mhk#V{xcOcO#=JvNlj}#4d+d=+)xjXahFyiPA4GjZG+@JoTtL4F0jIcTt~t zew>?<9+V5QTJ>eH){}bcx4Z^WY?1gvP#o)xn#q}jd&fshN5tZH+ zWK@-n7wE2Zz5N z80TCf65pa*Jj#SWdRE`-`Tw$AZxLlZ`^{u0GL;|f?-!~V6rS^>)AbbK-(P*(Cyf8B z$oafi6_c{{JFWWJYU+8F{P8NB)1K}j5ABXg@npo~1vd4iEa%ZC?nb!6@a6HY-e9xw z@;)v6^`iI{SpDoBM~Ng<{|HGhDD>9zkf7w}G_2@5+Vxg8_2OK67wh@XLGw1xv|$<- zvf}T(HuVm?d{5Q=c#Rsk%K3r`Sg*2oMDZ^L#BDUJ)j|9d+ZGOlMI{nXRoW2^MI{sr z{`zybKQN8;xi9tSo@6W`n|@n^*uHckg?zSnn(~2cGJ{@c@HZ9kpCAE=mrx9mM7rvUa*=$NU`W}myi%N6B>?rC+L?NlUPn4Tu6l*0+QWFZM3nl% za!un$M+m;gg>IWGXmcP#<5IuVyZZAHTKLMaHw2YfQZ9AZXfTFQD3rkSUxr-Yht|Nk zD&h=Fu78vdmx5b zD!cvCU@sy|$emH^#pQINQl-Mj^T92zt-~LlSpRMD$47J)7l?_`>j5Ov8AfdIQ6ith z*+KIc4vhct{tiBxA}32HsX-*Oz>DvO)?)qM1BGg{O92li4tD6dX6$F~OEX$ytY2k^ zVd*dMAVcQf4#tn-K2SHQmB2kQs^UI2E4U6gv+HM(A|$OZ5xc0vV38&bBTuZq;Y}Qq ziaXSTC$w)brIe+~xiic1d^nlTrYw$d!gHCfEiQYQ#6L{7wDBBF)`y5dFN7Sa5yRj) zi2j4Z(4bk0$grL1Jjr`W&#EM14^1OL!Et7%BmqmoLcb-a8pVZeP|%?K<393B4IY=g zjg+DgEQe~K7e5x;JdOm1nwnbHXc>9Zde{h6mLpu6p&csRHe5`Ptt-i0lbwj2UDXPNk4|vL!ZMoN7_MKjF)0SUh#bgWm;*W(bMo}t! z81*f@HnSP#787b3I`$H9D<;(_Zp1EmD1(|NGe5($ymRRnm#xkl)T3;gH#j%4DQf3> z6CTE!*4*L_pLJM=TUsoOjmtE4=K_4%PD@_iaSgEs(i;q`yA&=AJFzI&2E(Q#`E0|f z>*cIs1siznT92}6jAOW}%CxAmdek(`1wWn^4FW|LM-30OJRMRL;c(d87E1@!jpGJd z3!FwY2bOcX4wCh9hX@hZ#$zs26kKC)G%VV{8qM5R&F?%(t}Bkcc-zup(0uM2keJ@p zb=c~B9y?*xC7`9^Yyr=MoF+cDcCN(xG$VJ=y$sbqpCVHeF9|7N+4Ap1`yPW>El#TX zq5BkFTB=e+zS(!2q!SBkHeK?NPrf@S2l(On)4f9-Z_bY6>O(t>`gS`1rU0f7iVJ2Y5v*l-c(rapPHT_ zs7Ri(pryYXX>8W)NM;_ebb*+)4(er5tR>2|f6aua%;5l&B?kz@?R127rn6a(Dsw?3 zaG<{AHZ#XAz9wZceILTFdX|kWt5wkl$9Q^qDWTPHR)T$Y#tVxJT z{F7$(4W|pdHS^r`m2y7xDEp`f*W@~BHi>Z!k(;@utS6SrQGCpS$A7~ysAZvCZD-T? zWJ=p;%bb(sbj$=hRH%)6<#TS!3KwCTegxjk26h$9Fk`nVoz+ZuJC833QSi=Wu+OPY z1!6oZ6-iU6^~EorBLGMrC$7GHjz@Ts72Fjh%@{#~GC}i;wC4^As+5jNSAYM!pKnt- zmtt68!CF~Aorw6uaVSBC%riJ^DHXMqqSjcHS>itNw(@uG}8 z11TMM4$9xWk_NoCbl|9ydGANOo<;YNC=Zh|Ahqnb6$N1I1k>)dp>%_P+3$RARmP-JLU_BGrxBTHW42;${6 zk_G?WAsxcgY4O@8_GT;PGD{Ztk*#8$Pq1zH8remN4$4|oK5D*0(mrIpEtl=paPHY# z#za-ETT%mCs>XwG zfo|LuiEJ|MShmDr{ zhGy*aT3!jRl9&6DXeiYu>X%WPJ=~5bq`&W3qj?&#d*2aS`>kc@xGwjlQ}EG9869&O zfco%MoS0T{3#sn zrxVS7w`xps`f88bKO-t-0YZ{8vg&Ar9|&`ZY2s@*RnTNY3U|oOh;=VeWB5v(d6Vo^ zRX^QXBUl%98%05t`2(tcWB0CYrcPF+Bgz}n-)=$5Sk_)^ri)Ic97YZum%0YxlkI-) z-5fA`1hMqmtsEd!KG_!YV;s#ePMYyx`lUoQnv6o}yn@D!%K1|Ar1XAsftg0eY)iW& zKTuP*8USnNfo*{*NNI^pAFP%x1*yS5BbPCI;>F-B>PrZ_Sb;a ziK%m{$Tl9#R##_Ea3=Eru_$PhaBZWq3Q*S^8R`+hpfp<1Iqt2SofdFuN`YC%K=xX5 z?>mJTb=c$_;+x$0{NLhn{gO(dHj|9jy|;WYFJO{7Ct{+Ub_ANNw~mq>vntzPn17}& z4_n7O^NXL4?#Kb&20d>!M(t~3w&P1$CZ}y%{Tj_d2=U7r2-|)6kNBb65#HvlpHe5< z;bj+mdsP?8)hccd|A~a#pH7z!?V09~ID?j1$JB(iHjdqRc9$nw!0@0R)O`oV$e=`* zTY`t5B_A~qqg9XOr4U(npG$Df)S&Em&>z0J8Ggc**t(;u@G%my6M~&(CxdLaz6)AB zlCKX;t<6%P-@|+Lg}rz#d=yws^-M}23eQNINwpLHqdQajjCbPm>;pN=KBIIuGEZ@~ zE*&EmTU>bgwhoGbzqL>3eXWb_tjqsNXbZEOh`u(*nhV;ehjc!oTARuBnA&(Hdp0sN z5*jo1sTP#b^2Ezd;M^2*#fg5$AnPm;*T+Uhafz`~*mGQJ6Xb>$J`t37r#yKT$a{_=OILz?pBk@_*U?pbO3AOT6Nj zLFu-tv;$TD_8l4yXuu3zMzU#D3_9(X^34SP{0irXz=@62k2Cu(e=aG0B*_aa(^k6e zG=jk^b0~o)Yvh_nM!1Wzt@x*N4%`}KCloUoDM%a@aq+cO{2|hi~d|2*ejZy6R(d_kV`_gfD;L&j? z(H3KtQn@}4C){1pTvO=&mo_4)U<}${--ODtX)VW^gU6cBLxwHW{$vo}{b1~39ZfW> zQRMy3*8kmXpN275x{hDCOcg_*fVrZdqH=wd=e(o3Uv2{FhjOOKV6;%y^EbzDh`8S0`PU=+?G;jjBFb zLm0j;AzG!D@ZybT4#iMSQPt#KMnv3OO_u*2!S&qqo!Cq~GMp8m7DvR?GtH!(%?2nHJdu%`wj63-lRvLI25 z)}gUrU8TZLo#^lYdnV=%!t1nrD8BiuQGm2XHbb#XJ*4V8eDLdIZT) zhsgF~7hKDH&_~40Wj?KZD?0BLi5ZR%=SWbcwi_-Oi(TX zLXalJ6a1!T-J0xN3$0TVLdC)$z`wFkubHAe7cMdVJ1Zv8wJ=CxncYgw!FD-Ek6O!D z?zmv(Ca)Nw6*8BEp&}}2-f1b$VmQ?zuz(|?q^G9THis~GHIERidPKk^vhh7@V+B!p zSsQw_9#vcTowep*RT)@cd=OsPA~|fcmRG1kMX`#Gu~xg0Rj0?+0IM54YjX1Zw0PiyoXnWXjW-=Fk|X z&~4Jo>gdp|8PUDiU0=a23iDN%r{I{WjI1`)U3b-0QKN@)+F0VCwr^KhmDn`ITL)jq`pC_S$ zl5j6Tn?Ig6OE9)xL-G$m=uf6w5u#fQx%#u9tppc?@ounIRKnJC<=+NnSIuA6lg z!tFy0y^{el;La8zkxVsg8wz70jQTe2uWbXbZ45WEwRde)Gy1QXhE)L+XzDvws(Qqh zn<9`q=ynNT%*Zege{szkTo`VAoh&{=GV1Hw#=+TD%KUX$sW16Ymo@OS7M_}|w@lPz zg!-~`F0o5)mRsExkGpBaNGZB)+DD0#h@ZTBo@Z3wvCBD`OYgVEjAMK-LdGLW4=ml` z=~Tbtz-F_nplT|lRxp0i+v{@O6Qj&VxG)r0q=KO}x`Z&644s9#*h7Oe`7Jsi@~|no zs4M=kza#QX)!Rfyp9F~bw`9av8Anr4;U^yem302$A_7sZ@Zv`RAeZbFRe`M10iX@kfA#8kuqJ+fgO+aZoacmz`lK zrzPO~*3`zafMnv)&su(hKdH$lwu$ z($zG$^7X7U*=E_%1`gwxyEEP0k6wh)MoaLVQ2l(`Ew$}9lR86??E zzTlQU!IHFl7Bg62w2NrH;FYx&=dnw2uxk#z;7q@`#Yt+Tl-Rzot1>d(-MkR9yySbi z*aBR_<=F!E&e!x~*VQfV;2eJbvO&xS+y9QT8s+=<#CZl~U-)t%e3)&EVc9s*Wcwj$ zwwE*wvE-n14T3kna_4h^@kfT8+CvJ5#BeseJLb4GG@ zC^U1fyKs(FwrelM<9$5&FqR-1zm=T&LMc=vlEchle*%+YBZF2Z^k^=QYbjyiQtx=D zH1tKf7!_gYj?~VIP=f_o&=p(=c8T7;3wpSdz`fV@zr#Da{j8X3G*=2!N$6eD!pFIK zX1i)P-y3(uvgW86Zn<`<-y4`eREb`Xe|@lHe5ewCu&Is}z&*F%qSbfDHehnJ7oz`N z^%F7|&>|NBy(;}yqsTZQ(of(g5o z8Lr&?)po;aeN49YF)D`MyI$(GbBn&w;GxxkDAYaU%M@)7n7&BSxNgf^>G5?a2O;&+ ztv`h@Lc_r-*?SZ>ziq0kX2`owGIj9LbC}9E0{!J+(r1DgqdCPsLD+m@iE1FlC=>I& zlkR;Djj20seLn0R{g-c`0OI)NyXt{Y6!@)t@$YK0@4C5PXs%a2k>4Syd`&hS|6MAP-cs45 z^)IbjS>4eMg7%n)woCwBr)1 zd)mbc?Pe#?={?j zwLA2O$^L^M{Bn1?RBwOzA@KHeQ%YF~yyNiel!2zY^ndH}hlJwJ4S>b)$o(A*!qxOc zZCXrIjz$gEP=+G)_!aooDwQ-0-)osPyo+II)_F>zdDdm6wB>sg16(7a((MR0Sq#Uj z2U#r7X$x7L0HfN1FMzjYD@-EPqaZ=%duu@=JVx5z_@6l9_(AO zjaq`09Lg(8T@WXWcank>qot5$CK_gzk>&MbsbGIoKvi0p?nPTxTBd!f7g2|^Q&6i+ zOIKOH3SRx1U)7nOVc5Y~v~8ui$!k+NfZ<(HE2EcQT0~X$m$GC=He&-)sM3p}X~hc2 z(7e%9cBa1($;a4wkcd>J&%rEe zV;yH1M_x2{G?*m-EH%Fl5v{h|1^!XcZ)IY$ZLYj8}mKZzKp})V+6& zCPb9{q)77Nz%O+*A&fr%?qySZzg3}!a<-EKoWJsYn?w)cm?uRKqV6ZnVfuAtxuJ8KL2I zA_~tWr(`P~L07*?%y=WG7Ax&mSpE68h@XP?Kx$OAt}dxcb&J-3W=w0=$*Z=4g3-Bj zY;(gYrSpw~`Nz_jAx3@bAiWXs`_r&7Ykk^e{~B`+&4i_Lz4c55C1-u9e1V>G#^xI( zx7Ol>Lt=gAq1-a}ROzH^UA^9k4Hf?$jiPFYbM`|!m7u5Ul+R6l&WFusiVRFM{TsuD z7LtKl6q9#4h_>M$Ad5a;=JA zZuQyk6|=m^t22oYW_b(@Rw{gTb7f79RTE#W4d~WZaOj&FIvDJBOu=jGH%-kOtCjXa zbh=)woRNhDj81>(n73)0TPGL3IOou9oQzVn&37=mJzHr0AmRdUzF!bTl@DA5Hn$&6 zB)CqMZ{8HScU%nEd2i8e9Syp7K1kU4UY2id9=dmZ6x#ZO={}$EJi6g1ZGWRxY)?>n z^Z<%%f{5vN`XxPjaXzd=m@0m?n|bsR`B{ev(Hqr=dh}C%SVbsS7?l@!3^3|jMH$c= z=M8!ca&B72*jE^*9eNB2>RZP7)0-r~c@9fXS|r3(m_$%|jwmQt{K=s={VnM^syO4bcw_Zd990KtCs=m8OP$GwRX>-{3@~3)djxlC zqAG0+iM+?g{M;n$Q9+i9^(()MIGgG%K_=$FHJYTR=04DvZ4_{w7`C}}?p@ZY9JtY9 z(hS_|_`K-^Zl(t}cia-n`kVo`()OFXpaC)g$nD#~i@5eX|6WtFoZ@Xl56=N8>2toQoA=4PxeEdwyEx5ES1fAbG)_w$hzz! zl1RR-;bg8vB`0&dt?_KB#&|4S9@qq0Yq9m-ocKHkp2$^0CRS)~x!&`2rZbrQuZ_w7 zk)x1xe|ffCZvcqZy`&b+Z;JvGD|WVzo*vJY8%%X}ygpv-sVpjVeb`NdZkqY7_LGx8 z4DTMd7$7$>dih@{{)=Odw}a3rTSl1ENWSibd^IcC2_vz+5yc@+lNWB-$zDWJom;10KixzQlcT(Wu?TIX2v`r-r=iHEbig~``s}W_hiBaqy zRrUYan5tBHe3bJ)Cdr0^7JI2C$(Dy{7Dc6I>by;9WPUHdS@s1!ZOoBCpU<~{d|L5N z--FMigASOZOY&lAqfsyq^P)LVk3+W|MgsWHbDxew_rm7@eCq)o~(@jaZ2f<7jyjSGwa9BJL|FZt4ysG_lFBa#f;SYd`f@J#lx837bnw)seQ4+q| zyIjkpkzn{3q3Ln9&n@ds6*!1(%I%}blXg}K2to&unEDi6L|ZudLwGdg_y*uEcM@|h z6VJ$Z=}9UIl-&N}dvVBai0|tns3p%Ew^9&LE;R#;B)wuH5ZekhQFS{ej0`J2=@z#;0kfd-dDF#*&pEo6D0IHClKkKuIXnW8lu)aLHe7`Zk8)N1g{<~_JSS~p zwa|r_3`+_#y5$J2$DBkj4)6l3JA{qioHs1ly@FbXjwRUI*|(!OX2Q{tju8UTBTU=L z4ZTcPl|+Acce5KnLZMZ#NL>HZ%%7lwN9hh>n)YG!g&W~U^L1;iyA{uBeOSL0XeN({ z8T9fKlYvDe`3|VRU5@Me03pERQ5*hN>W6}am|p&?TmX<95Bf4a3=@*OBP4DKFuD0jh6C?x7_ zB#RPZD6koIoQ0f-Va_foEPJRJjEQjAcc&muR+a%;3ve;KU&tN?SPQmwYwsN_aB&{;x=^VX+82Xgyfr&ui(QmM9U%!W6?ju}r0Vt{^2T zdPb7i(X71qo%le!L>NvQ6g#5ZwGfCeB!S-&`+PJZ2msi*jPKm6A{jmqb1PL*xU&D*X9RnctFH*WuikQP>k>InVRT74}rXDIDj~C3~x)WM)1QHj$M2irCgRS@?uz=yT2`>HZ;FN6-A0* zvIn45M~WPuYKcsL4I7Gw^{+TSjI(M6RmP1T~U!MY9ohsQc_Kz%jBm# z92-V|0aOfkhNJo6x#)#=yux!`6-Fg@DXrr~SrKfntoC#Mh)YRQ&gvk9vm+?fnj^Vi zCw&hOE}C`Jcbsp9FDej*)sBXBKK|Z?v6 zH-9lo7%dSc_Yet?_Kr_`95^&B;1U>&{Zmbk0DGCO6$(L;yNruYg_HhiyE$|+Iw50t z2P9{CN1mY^>k@8t;w9*#5Cku9j?98BWg8mkF8 zLz+h5znq(+_yyToN_$I!=y4Q&+Q|X^?FiaEh_9jcfYHA7Sf>iQE3NQUQ8yq@pysjh zOKzxrcr_FjLg5#QZTN4Gh6D%9^n8&%vG`KFvt@ET(@R8G#^eh4b<EjSA^OY;_{~Tzm_vav z$~-Qn&1l8<(%Zp%Gu(UqJbteAc}372hGF|!T9~5Xs<(hA^;O1e1Ds9Fa}hb21+r#( zJ)`~FgUA|4SjZf(`yfu@0bzH}%MegCN}NaCTKgJk zoVjp&lKv|32Sq=;Sg-8N{1fL6KmMb9A@3X@Us}q3K;((kCCgs6%Kx~{w3hhS0gg`oh zRr9a0H6pjAaz|jWS#U zVE){KfQWr?hJ0j(Rf0vaN6;W1Qi4|sJ1aqkCjt1iBA)gQ}6nc=h@su7q|5l*9~bC-ei{6<%f z;GlR#b}vj7he+^!skQLbTx65!MwkRcAWK!f^ISis8x zus)#C}VO@fX9k<6~0&*_!l zZ05aZYG72GpTweX|C}#qWx#KRstub0oI$bIGMIS8&%Nd~m4a!>h1F&*)D|XDD}yye zhtSn_`>SjSlj=m_nFag6X`kmKp^MsDiS0kcEqVG|NtuVKCYphV?RUGgTsVuCEaPdKivsZCqsodv4kb~t#n~^V zx!P`)vH?oGc7rt8dqpL=fu+;94mNEeN7KcR%`{nfW!Y_LcDU}3Qe`fuMPcOS*@J+& z@5Pq1#a&jJF}LOG&qYfSxt7|12;MS~A>hog>}?Q`Zxx?1q7ENl6y^f4$BBLvkiV~8 zb?8+^?aX%SMX1PI!fpb%VFuh7e!u0F$~G%+8ZCNitIp=Ni!c&F8Lf66t$@}k&++;L z^`jUjqXuQHdVjDS-nwS6tp;^W{U#o8O>iI-`yj zSjSRV#dzjZrd0L^sSr}D9vysE%Y9aRN+OarUCZ-YFO1(H%GV$sl`E*zAbnO#4{VTI zYfu0ZG2u66&Q!_hG$QIagfJsXSvTsgHR``M8sayhzBZWXG<^mrYe*ZdqQ0rpH5plF z>YOz>@in{XG`mGrTVynQ0h@i!u&rO41@P+K`C5W?T0*^B!ZYf9fi2N%EwMUS0k6%r z87+TxT9dt7Q*|2SfUTKpt#SCR)_kpLd~F3fZACxYvNPJsfNcuMZOYbcjfVAge82`B zV3RknB?H(71h%gMJ70m_`0c%X?fp9KgWm1KXTS+bVHJEQ9{ zqwDRp^EIlgkr`zpsuM=H8_uU2A+sB)q8qf<4S4GwYV5|~@4?dT!SU(&n%M(H?jcz3 zA!=u}!t4Fc-%GCBOX<@~o!Lv<-b=sU%lOvIOwh;5-^Z@o$LZ6@o!R$EU-*4`iQoE! z3Hq%?k;QfUC4Ks(Gy7%R`{maA72f)l2nLk-2UK+j)O`jtGY7QW2Xxm5^xp;yqx(hq z2TgPbnUuLLG6${N2W{2|?cN4Sj0Qhbz%KlR0zN|?nL}RfLq6+6es4no1jAmsL&3Vk zq3f6o=h%VZ_TlLD;n=s~c!H5cf{`%Ykz|`;rgiK;?IW4%BiU~wxdfwpJ|hLXqb8Xn zx}>9J?W3Q~-m14zcbm~V{xO2{-bj?O&q8lo`&j$>NWhqV=S9&*Yu%)Pv6yFUr(Q`xG_Zl+HhB2*PP7foT}MX*l0$gsf?#j%k#QX~6q5 zI^hh4zzmk&436*2*Q^=5ju`@m>9@BT65srf3T#5XSxVno>a1DXj#>JRS;qHS0>W8V zfjM0;&#V^Y9Cy|nZ^s<}#+=~$9FP2*sK9)&`J5)?ymZ#QY{$IZ#=L^S8IG1%LLXM7ziugv1+r{+B()` z^wv7x*IFId6nfVB_0|VbSGu#-N8j;!H?W4@*QW_LusYU1hrZ%w*5ybyRy#J<<);_H z?;G2;Uza3z(fd1o}IY2|FZ2yK)md zk%DRHcPK7+ zXmzn-x`}D=ame0z=tQ()JBjJwcSI|A!WJdXTW z2+2kd|2T%}{4Chb$Hbz?`<*-soTLlRCHbMJew-Y2oaBAXWZ9wT`kk%|oR$Hm3iZ)T zK2B#kPU{3GD;3ad{LTgi&f4rI8U@i?KF)w0XT1tz9gOJRe&;m;=cD?g1AY+0ALoS~ z=d=1F69CZS1Z^`8tzUrl8JBnbE{ypv4mvN~VlFN|`c5Y=ZmJe9 z^)DMUhYeURUlcAMHZMW=m#;)u+Mr9A>P`rzD}>8=*siNF?<+*`Rma2?#$_u2?HXrm z4m0OEL+2WI>zcdrnq;bl;PRT>V2{-Q#*6QUqU(k#=7!O~iFWFS72Gw$WN>>OeW}lK z%UeCmxpn&k|CW#V4g+*6o>M2xbSE9RB++$u;B_YhzC)O}Q)Zgw-ojS$zn2oc*9Ipk z#NF#xL+cPfaOmCZUf-Kdtr+DzcrV|ZgYT@s4<$nnwsCh329E_)kIuw*Ze5S9p`RG$ z)`$3M;^5Jr={C^+X++{Fr0XVp>#4usDN6AsR_M7K<~d>O`ftv&z5D~%=h?RUIai1; z`SKZ^_@yX^HDB=s(f_5wfVH&x1#0W1&Yrd!?e$ggwS|ec(f;)|`?WKU5;*mG{_)zc zNZG^mcA)<@sz^2z_qN&jHjTELsW>~Cb2sDvelzp7U=LabZ@pjqdtU>eZwh^!LVoP{ zpYP{<%>Vj00-v3NKc;&=K>lY}2H~cF~08~umqY{!fpStF`1gz|7&Afk2ipx@CJjKTDNAOHb(Z- z#@t!V7Ru*He%cuMQ8xzfP(qyto7F}zTh(Be&ZFIChc6h;uFZ9Rsp&sBM)!GZdm>9H zj7aYj$FzruF?8y_x?OB^FjWxgzj@poOyo#S-Mq}5Z*6pi5$8C2z1)MghH?yq*6%%v zN8y=;A>q%hgrL#HnMGi6_z}5vdBUNZ^?InZ;1K_LbP-3ty^5zetgP=>{l@ zvq)fTn9LNTkbQ9~;Br!y=C755qd#<3?U5O%^9!*GiOvQ71!{L(eQj zQ(RCdOLwBJOhetgU-u)b3WiONWr*ClnEuZVt31aNdx;#^Rxq0a>lA;aJm2NMvVy?l ze*F~oi5wE#*DLadX^eMqcJNOL+)A|Re3JkyWsxZ6PaJb#%&sEObuiBhKNiWZDg)oq zpsJE^#;&HOVXDR=MU2g%{tbrWURB3_qC!p2{h)EFP@h9q{TEplmWFZM!kC6>ifNNp zS^$M?D0FCH^0Icq0Owjv=0TH=eO3tPs?|{AgSPFIM9M$=CDUd-g+9VaT~7%HPCf6- zg&sZM#{*mikDx?1{of}XxCTMCAg*5_xRN&p0q~)z+kt3BUll`{2Dy!~2;pdr;!G=> zjS?2-TRx|UHsg$Qpgvj-G+_yO%&31BwVGx0sd$>ExWj!jOY={@Hv1Pw>D8R+y~}g* zOAM~f5-KW`*Q%6)&kIbIoHW>GUfewBVpZJ*$5&NWIoWnz=zGWuI_Nb6+BSbaNmA7x zRV77v&tD44PN<&D;WvQA~z-^^iQowc59_(|oXz<6<+mQ; zDW$KsonroBv}3B=;c;S`%kFtbY$fOoy7wh|Iq3@P2{{|Wwf4T9vTu4#?ab-)y4g}h z@O?g7QhQIyGZ(tK+BqU7eF4Mg7M;6yz12?ozKfCkf@%?lyRZykq}e|0PZ35!D)^1t zznv*qh^62I1NQ$iz6wc~+KrMt9jxM&EBm&CrtrDW5QzT^<9=3$gDwEE3%O5dha=F`TxmFb2##lo)OaT785F%AZC!X{jg*6+017eEL|= z8WOC@KZP{pjBt{M;|S}fqYMhv(FeH2**Xrk!fnBe0*4DeTJ9*o4;@O~3Y@BHCJ=Gi|n`!Fmd-$odmc0*q43$Qp^Wz~y9 z|75-GQ$2ni!LFMj*7Y%dRsJ@h{xF;J&+|aq!y!Nu$2qydgbWQR&98c)oYWO;#*T?8 zmw+{wo(<-wWJo&}n^K!iBmZm0JwVfhN@*J6P0+`&a5DTe(J3*|`j9J!N5N}xj((m$ z0B@#L!J1e3@2V~-?!=+IXW(2myacuKmF1WqhH=~*J0*+730f$lv-vgsF+XP8&)5f( ze{T>p(w41?;jF9~7dE>?2f+)TT?#U#&1Do67z|+;SJucC}?Y=i+CIVp&d~1 zmEtKyMIx1GV4tcVv@KKxE>s!FpDK@yD*5jI&B=+fRNFN^q%SnK;YaCQtE z+Xr}`=s)3Twid+{u$-4~{kU4{0%KMVy+bOiIToKGy^rjV9bE$PZ zLD0QzX#ALaEbrS8db#q@G#m(uZxeT`p?KmIEmllp{<#yoOX5RFHO_lymy@Sws^SLQ z#F&`L{~3wYJK7jstRm@H9DgvtG20+>8UM&*2*h9!pJBBxCAAerD^F8&mV2UT&^AX0 za`~+~b*eVhHlIRtU#=*Cj}_u+_k4X*+s7X@aV5c4K!3n9{_ism#N!ggcqbUya$G3t zwb@vFSNXVc>2L0}T`1@wW1V%zdn~%s%y?gYxzNA@-zYR)_0ZV-4(eItW;jxKq^Eqn z2$}UhP8oWv9O^+jVGJZpH-zVs!$mQ42qHXZzOMxS1ISPJV0NR!6OMyB0ZE$zh$aTX z+*m!Riqe6*Y1u0gTkRO^?ml-ysHY`pZK=f5l1?go)xOEE8-3cFIQq1$R3y#_}$q zyQsc(A<$>t?D0N9w>C{*c z$xaWSTqZ6}2p&m@>UJRMFqCu+ED3#xC<&}2ccA{)UY+GWIc_Lj>JT#NP-2@ykkF;b2ng5a?kj3UmpXVJP{6PyvVthI3ISfN@oJ&b=4Z?y+6#VYb0DXnQKyh74g-2_00TTtk|IU>>H32T057SW>TK zl`3u}hzt_-woApfPCf;o0;T8;1@*-f_Jz$MMU!Pc^jMbyRigGXKX|L=ed~=)?t6Qu zEO4ii(AAeUp_-`JS+vuw(ot@1qk8Gzmq(GAp4C^NsFWI|#GIq_CA_~Rxt~n2{UJ<2 zN)(#H(0?e{Us*s~px0lWB_DSe@;R&jyP|r$O&Dc)Ee)_fXRg2gxW9RVrh2XC4aEQ? z9GTFI$)Gau3pD6F0eW>-eP<;IBd7_AQD4m&Kze6C?;Gd^b-X(pK-3Kmls{`QWwAy; zJI@C1=%8JLY7C|tgC2w98Z@oRg9WA^_@)7a;X}U|G`{l;j?`&(GE`y5$Tab34#9>N z*O*YfrbBH7gVUl~-zEkrcLrx|hDYk4zrzJ8_B7i8!#k$be;Bl4`G!~5h7%^9Svw3L zxeSlS%A`>AZ-WSS^`5)652MWVF82G(y9N*(Z#HW`r) zIeMY-@;CXb-xRjLslRAO)Q(^m{yv%*nI8-X#*fC8j54{V5OizT%&8Ewk3qzKe*)`3 zG{@M*blF^W*?n}mTy;58bU6ygSig*YGE|Q)t;MSN4W%5J3m;yThM&&;jyn1+`jQd_ zCekeoABoQycXdOyxp_yYYhob$){lRx9KSfMn3a)E*xa_kd~ToVdn6KFa7vzHS} zloKO-dJ6MUZF=ld$rq8@;~JWj;;!Qv-kLJ(AEYYA6G&fbv;Wb4_UFaRmkC^dxYoxg zrQs4+xC&T!%Jnamy8oCIzD(+^N}z$or?Y5MPFiZ>Y3)zM?y1iKz6FQ=>5h`IdOztv ziD&&}@~wvcpByg7Ka;Mnh@2`WZQCZt4fWmFr#u;n-0vrC?)1EDr+n+lyfqCt2@U)T zrvm36`G1^(WEljlPrZEtSst8fn=^RFJ{@XH8cbveHZ=&dosJMA4cDAzr7?^woJK|S zlSFAwf2g1SxNf+Gn1=tEj-&jWAVvrOI9*_BnE3K<%D#Tm6Qc}5qtukY8E;}g4NavN z{>}RHx1;*6fA`-nSTi}VVzM=-k|}5MpUu>PXWZ}q7Wm8*Q$`n7OcuSLDXlloil4DA zoGDwMsTAW$dt($UYFx!WTYEqAAPKL2X2c*k+u&o8(mSIyKhsz^TlR5Q9KFr?V^aKM z7R)&N1Ix5>--K{z79lp5#W;t-Ki6qHm!fHUX*!2YnTvZfcR2^|>o(1;m|KpW8$34+ zn>WR@ogHC+l}hxgZ*Oi49Z{al6aJX{^M3xL>#L9bm< zr(6QQRmIdd04gnE3n*hLAt!v6@HQlHQw;z`ON1M81WNLFlS?EA!o-sX*x1WtOj3_H z$muUpVsPzrWQkUr)gyg)v7S@DoTc6RZxFL zoVc3dv_>)l8%$m+UAgKah|lJ``ec$PPAKvdO(YQ4MwVj@N1#|IYYT+z-3!(>e< z!e%#cO{HjUICD)6xyCHJrm?X`gx*wP+a9;BX>+WH)2-_&*#=6l>)EYe+^p$G*g{R# z4U5p%r`L^<>yKO3O*d?XXV%TIHxz=_EjaADZq}`o>{Et_w#9b&IH;T&5NbDN<`4$exm;dTx;v|AAo4jxilsHh@`*V$XqNC&T< zTd^AsJ_}oM*p7Z?Tk#x@ADOljl^j3GZYSG0CYXInjc`o+8JAw<7=5>uiFAwz*vi^) zq-fdB#@_M$yPd<~#7Mi7r?f*QwNqfX^YMDSC}M~C%}zlhb2q(H ziS2xIwNuTp8}ntSR>_&jc)QNdS&??PA;OtmYPYFqmo;Fw1-U!dwA;4fJTbld6MN6= z%PxXrkNA4GLun5wxz}aq(q*`ZjM!`T-|H=MX-wbiN4gX;?hS6Z$js~wW4mTu?~QWo zZ#C_WDeadq?oZh5YZ~uQM!3#N?oSu(rw8uOAYI$dcIP%+QOyhc3)pT`5Bp0TZhwF7 zuPC`?KRH;lb9*p6*oZjDeRHr?bP$wzu!B4>Z$8-DaLZ5MKd9V4#6Fy+Iy`pUM`I)t zN{43x`{#CtqrQii2YXkkhl53jHr!+W>Ahl|55>>~hl4}nESMB0N9yO&N;kobPHy+g?j|ic=M4Ly|7e^$AJEYXdNp( z4QJ|y>l#yMrWGf&h?<{FYV8@ea{UJ*9_CnHHyxStJX|< z&Q&JQU%9WDU7jmqUsyobEIEB;#V@S=R&5M?+3hauI9Kc=eVJ1)9DA0X8hvSz7cTb8 zuA9E(7Z>h0%O2EzL>!l%#YA4#FbM+B57k7Cz zh;<$RbuNMP8Yy<2^mML-2CH8?;2|Pfz#(AD{~CoP7N&Xc1&+(KcPXKX6z~A@liKVp z1z<$t^LqfZByjSeH<<76eIx<7%#nrmpNjkfi?6PA3~|2L2bSTuq#8u_9|eLU@k@)Z zYs`=Km4dRguIr(*4SqpY?{Ax^P3wzqSsQO#4NlsoZaFq@e@34C!nxz7zH4th>5#bN zQ@-okJn6Q-gZka|P@ndu-3b@p^(&ta^xTO}-3|Gj4qx6$;@poGpZ?~&e=Ko7K6N@_ za4&0rKZ$cT6?re0cK=u6Y^L#EvF9E&XMZ-od9QqVznFHmME#(~`LNP+wyOM~Y4EUq zdA8yApdI*5Lfzv;0WopN_#BSF9pU)Y|5r8!IFP{Scw!@!z++JBvVFon zm@aHTR_=KEU)UIar!xojWHoijf3Pvdx)uM4jVT*1RB!(;Y)q49P4r9YOM!pbn3Mh8 zOXw0J6z8x!CQ)z&)fG)G;8s6hsix@BJKxwQfFIZtQ=qe1;@-Z zdbyka_#bf0=H=SHJDARoe?}L;mPkvM!Iq>ceZBTZU0#Yk<)v}Jmt+H{X7;pKlc|MiD9dOm zj*P?*BaTeR(&i#l``T-ctk?ZUDWARm1;;Gt6=%P>x#rBFI;Q2yeNRWXl@rO+!j*p(s8Ak<9>m9FWgb)Mry(g)oge`XAm5$>~$HWlvYevw((kK%77-0Fi4$cV%V zjiccho|!C>ktab--$&#Kh*(Ay=-<@ApRuChm<#TC(FvWh%esk|CPR#W4A5|lw~^Pq z*mP$ABN~pG6>s?KSoVc(#<}%g+}^bl4aa=ydnK_DK;YZB@aC3?f8ZT~tfXr&y5()f zoHiTH#*EW8ttP0uNvtKAyuDsXu|~5o@L#i1Te&0k=-mH#_|bN8+0PcmZ{N{u3~n>i zq-2BOfo%z=% zm*(z^Pp+y;l4afBPv=e%In9%Qmalf6nlO|RhvGTFtfAr~~ zsI4~ObzvcNJ@23yJ9;Tn&O)r?)5&mh^y2Xz3#rg~Czwn~SAh>gM(NYVCj3Yz(-}g+ z($K}F`&;WpIfP2#qKnV-cZkUzgogd9TQKo=s5KueotQsTwDxzHvkNQ3vn!$7{&N^HhCgk3&+f4h_d7xi0c? zN^^=1d)Iy!*+s)KLZ`$2W8}i8<(#tAUT8SROYnA&6LxM1Ewaz8y?TLWW6p&i^YiG6cuo`ur$E$QdGwf1(A?llmKPN~`UIYT z$~}F`OuI`BeyRPbj;1WN;pcrZ60KiQit?#YbS*Op!Jle6@vijl{`TrnZM_4$+g)PKtp2-KjVdp>f=>Y&V-)V>`yI4jZjXUKGkW4x zSI}MT_*{KtqLeDT+?D^aIf03Hzi-1@d4+5HhuJw#ug13SBKLRdLreJ7nO*z>BA;SR zZFu~eyId;0Lh$CdPCQ#Cx(j`()CcyQs8i?m1$ciEnCV6PwH5GH1;~9^IP>)UvDaM? zw5Z;9)lZ#xRsm%_j4@Z-@%t6NSM?49-5hZG8UaG)hmdIWfOu)*2;BtfnF%dL)%-hb z%B$bEM=cY2z3yZ{=0!f$=q8P!iAJ#r2$4UJwPGvv?^blFi3!17r8)ILiXwAAx@&YY z?9xQY90(D-BebEw59np%t4)xLT4VF_=+i*vBz@Ir=TfH))vFW+R>j(aoB{?wd$nm8 zxEq3}?t?bSuNfm6zeLMu-@3So+%6E>pY;U{ua$lO(jK`fJ$vzp~Qjx#P#(zU{y%WNUqu^USV=h}(3RK2!Cld0lJXAdf+}hSNl% z{Y2TInZUA!`a;fq7e9*Gxop(u#$T>K&~QxNvOwd^@JF}(grIq%myNBR*oXc>Rr6;8 zTWyCG^})L)!50U9Pp^rNO7Mc0Hf|f+ca4t1SzVV24VXKa7qlYPWgIA~nrgY{P(Pc-epJ606bB(pjPJm!`$?+h1wkNV$kl*-X?$R z-#;-Ib&Y=eE|FEUi?WMN1M@$AZ?s)loTSe5pIRMfHpjvtvuK*S75HM7HC^Xj* zT>>hBuaB{$g5~kRaGa8M>0ltAo`u4k0xd3rI$c3hBLpj}LoOC50tSF6!lW3&ZDHZq z9ibTb7Eqd8=1ZWRasu~mf3@*bE z{&+BlF5W_CLV+S!j>5Q$Xv0F@VVOD$i2inILZDbRi-JE3O*9K_CJS9@E;D|YYj;Y}D2Q9E=uj*_S^!faaxM}& zSphJDwnce(7#do_v_JsaLLu^SzBonIf=<7(-4ELfQ5(&APzlwh5D;P#`L|lz6+!A`BAOhKUd>N~dE2w3ns3Fad0EVqy@<4Va=I zWliz`7VcnCbm(OBw-Wc16IWb)awi9{0RX7NrA#3T9zYxmIXMp?mPH7+6^MifPRj=- z7q_7p%fssJVAi$-3A0h@tza|(nF(2ij6+!9KuJDp5m{EqhBd1^n+y-==?yC$pa4cz zAlG3bKfJ`q)Fp9;foah$(FTDkSx6{iU`~M5!xbn1FcJn9IT$;UFA$3j0Ez>uig!u& z+OS~44WkP&**YWxK~ilU6oRX`b8_MiKyBo*WD^^K5)cc309XL1_N<^x;k*%+fW$C% z4Fq?2r(#REMChtyIFQD4?XnpHFojFTzK11uYE!XGrYk@Mtjw8Us_`fwI~XB`4G_r; zVJz*GXbYvT&Vwngil&B1S+G;jh4KVrVs%*=Fd-x-fH)-~@_TmfYT;6XVTLDpHo{ueQ*xAZ3b@`Z~+y3nR z-WJOR+nUmaOLYO+n5=0nSS5>C9V=IiJiB1n2&_?NaXkb{CQwlpz$TLyoz3!0uUIa= zlYat}e^j1VLk>vM8R@1d-LxtOfdgW>ghN+hxLo%cn3y!EHE9{84U~nkT`5y_E|HcTwoMp&-6qUi!MzqJmEHkD zgi5LaaoFSy>%V?8VFmQJPq`Z*S?Tn7lw{%uwWE;|;Tq#4A zAho<|=?Y3Df2NZir!D|f2Ej1hPJs)+h3Ci>u<+?B05Ll;dcgn}K5AHQmppISSkC7T zZmN=uXDrI2oK zlX}8@bEblm%$kb{z?q8RJgD4~E3%1pl#1uZ!iD23@q@JOX#sG|a5!#Or~m^35Dvph z4}r>WkfZ`1rvqJxxh1O|ZvI#S^k7&vaB3?{VH*bmiq5w;7R?m`+V@A-uuz z3UQsfR_**p%hFt7TuY%3rE-s(a#1IiNIN+199OWftu!V88vvJUSq8xJjFeV8JGKSo zH?^_h0Pmv{;%`CHRh3SKaxfc_{xbA4`hF0)8tRBlw8L7nlAW{?Xt4qq@<5RCz^x8Y zdOJrjufog{1ciE@+<;HVEFex>B1K^WYmoaw7F;fQ-ee5Q&@e&r??OQ} z0&FnOk`9PA96PGxBORwa@-;B017j&SykCg%6EH?TbXETluOtMbe|Rp>hB@(?L#drX zLyp7&#UU;OU@3ujaCiwZdlj06@z4_i5zO*3jm^PUy+;zcbIUrSzur8;-$%xnF(@`>`cn8EUZBS@!}ocOe@k-V)) zrGlt{tx-R(B+QP{eh+l(Z)&0K ztS)lQ8!WIO2M7m%trv*WMNm(;-=H^mJ@Pbf_Z6HS4ZdO$_U|Uo3KzEtNp?OnV+}xlksU#59~vP=R=%lhqXVWcmt2)a$+VI`x&XWi~3;g0A3&iTrc? zE?Z71O8ND0^%9#CJMY;gdR@tTJgLIa0$w^c84CbY@9qxXp-m#FGmZoIT|0ZKg8HeI zT9ftb4qHHPo%@!Z>_%hsI2$Nck;H7(%$dU=&|TGm9{@ihH#@&$f=dmGur;wH6cut> z0k8~x^rpV9&gAizIvB`vP<4d@9AFe|0FFDk;9@A{$-37A*gTNMdnT9o6FZMNLO7aT zW~V-qRf4Lc8Z1(pb^#M_s$S}FbYzC5=T$yZI0p50uyRRI`YK>?*%>Ivzr?X2hHzq% z!ug5aU#4PUAj;j8I&s)K96kTf`aYz>Ez+dHsik4!CF^1j;IESwKMpb76nHUIIGQ|*@?turG;H2SwDPEl zv%vza)2@~;+9WNm1SZTGtfi5WjxHQGd1YMt{k(PZJ`@&?s;7s(QABHNvNg z+oB36rzTWr4CIoL3A#Vd(f3ur+sYUAgrg@SVT6dJ{{^PJb1jL2Fd>lJmwn}}FNLW! z0ilhKS#VsxPboFw2#p%g$;tO->k=l zbrK1;<3x%42J%S`|G0aO*y!BcU6fNKc?zR=Ea(B2Qm5ic>C@hu3-PJp*rSseos+b~ z)6!&X5;CO#nYZY`M&;)u{VAB@SClYVC0%eivOEox5Y%XLOaop|w%U~j09Yg|S;8|S z=rdRxs(HT@0{DBM;E%G->bTlsTHqdmQ3*(o7oZZ_P2tTNLl7n#{7e|~TzBQ?JszB$ zK~oGTQ6S}Ve>@rR>@lPXqlDB_cZsVgh7zurjMq&y0OvloQF|Q&4Nk&`XrVpvm?Re( zJ5Gil=?OBUn}_E@yo>0x=_L-#GN>jj4xL`LJ`;Z>-95A?bg%(bIniQG+@?i~)PUdzeEAb$eMp@Qrnq0Ge_NJo}qBNkGB? zr7Z7QjAGH6{u*2k!|A@F`jDatEDVff_nP5>YjMaEOXw|Fg zTo}d^zLm=KTrJI)9c3H+b~PA1p%K46+TlCJ+f}wdqwq+qT}m!0N)!VSsL*nLami_2 zeFTbUET$K}OZUoYa-%0v`zxR;q7#;iSxiril*}v37#2}}HGynb!Vnv4fAIr90g#13HCzr@zPyq%1w?zJn#AZy0QkWyyvp?giJrYi!-%Nk23ZN|U{lQU%jn9nY$YFBa1DK-?wFDq_HKZQy2G%e!nMh(BTTXD zb+Q~gy~oj=1IKvLY@s8%Y7W*1NQ&lW^ypQ6k8e19O-BFiS6)T~cVIl{qD^6ig)3pe z+kz0QE~zE;=;arB^{=EmLOW)L%g*39_4L&RZlauLLa#}aC=;%=1~?PkN`AQX{$}lQ11xf zq?>+3z|}!n5fv^)QNZ-^%o*S$s4R&&ylH2A+XoXbfG7t39bkmRyQGPank=_N z;n<2xS%fPcHCt8y6VmrQ!ZieO8o3gcAKn`iBZ!FEAl@pEtR&RH9U&kjNAr%B&l=~G z{B9d}D{jmVRe%wvtuPaoTSVwJn_ZBOe);Hv55Nfe#CB*!eD#P&b?K^~B+MT_;7&KF zG&uFP;YG*%Pyt3Z;yo_{FP2B3n$p$*z}KadhAlXnWtvDL7A`{X0#_3&wiv>wJH{#0 zghs_XOlvl*6}_+t`%o+cxZ)A~nX>f(Ja0A3+ayTeC^eq7cgOJ4yCV)zp$K&6!{Spa z{vynz{e%%C1fo|Hg#(snz_$U1qacL> zaw7X%`VliBtUUMbO<mGRk=mm@J-PHg%I8xJL6Pu5vW$v5TgQ14Vxwq_1)Xu%*BK5&g%iWVdd4*Hygb zwLXZ;f*?VyNA#}Ms>)|tObd@XH^(P>@{UMOb5P0EK*L}PK~rJ&BGP4K@*@`1kY*wOc zeQzO4^k+1i0nSKawa-jexQ;Ogr`P~b=!y!*Ip~FOLEv4Ey>w>#(p>m#=>3i&JZhaQ zv-Uo(BCJHlK{u<@_mnm=!uK~(6+RsFRuTY}1y2+YXHM2PoL9X5;`|DAm^t+#;ftz50K^;acNsomnD| zZ^rSALw?YjUwqOaHSx&(HtR)vfygK%?Ch7$|M(n(=vQ6@UdWqwELFqmEk%(WNdps9Qh`om~m+6{? z=)-~O?;*%fw)IcqM(F37KKFLe9(edF2Sdm?hYgXhU$58%gJ&`b< zAd=wU?95l4)VwEO%!44a?^Gb~7I@4aD?G~CS#r=_c6ow!G%L9N{4InxKm?++4kzm*!ih0{B>wg2$ zxsoE<7o%~)wIPqTw7%Vqe3K@f(&8!-kH=8025BCFbkM~1OAo9d#T!G9siFhri9)ti zdq3GDtk>}n#Z7FlYMeJmI3a?#?>%rs>}QHT;U);;rFh_FRO5X)!pj}S17iMXr4kO{ z9eNq`zbcjFP5x8gxK#(bZ=BAwy(Yis6IkKjN+rrs(Na?*k7o%L{&DAEO>NtEG<`C-IVx&#EoZGyW;H=eOl+RnZ zVlS!8mhmic1X`I9>y1!VW8lZ1lw1!r4t>E)+ zO9sbN?`1EC7(5)VIXam^H$>CHF6m@qt<&L_)+N?r7++7}`PyoUl0FDX*lkNzPtC53A-HX7M zJ_;d?%>i+$wBs8eh0+Y>U`zD269*oJfeCYQl~p>(GLOQ!G;;9`dOOh2&wIhxTta)5 zPP&<+2ubw&48Pt^rkkTk7-1eMDpI8jLU$acqLD|I*4xD)ef&W?HjkoMrJKk2INES9 zkE*e^TOjZ_#)2@Prbh)SoOvAUppj2E)r%BwIsWJoo6oSR(jz@{9Opln&ve<_BYSiF z2~JorTxt1Hp6(?6eOm-ie|xWz_(^!UVgVcFcCVVg6`|`@2!}*ppH|>WQqG(W3c}r| zpj(^x@htM`Mf)fHlU16Y5=Bm)*L@lhC#hck>$=zk z9``-fJs6|=p~x;+{I}mq%PYOh#+KJomC(4qmdJX^M&zqwuY*2WYEMp)bQrgWb4%@) z>AA?KrhS?r!Cr)CUK;{K+b9+0tJANp4q+0!7y~|Z$;?Mt_JSl!pF-+HzOHGkLEad} zy)!<`qaoUY5d>=c9E9b9#Z(kbQGSq|*j)4V)RNy%qN?ME477 z%?b`j%_JvC6P0T7&%E$_sLNB(bkd5s8O-N7|HfmxBl|pBt;9H`Vf3 zv2~}XKb&4xyQSo*uQ}E>(5rABa#H<*Z%|nKC)o|l=~YtTl;?(6MbOYTq1~v# zhdi-r=`R?haBagRCaN0VS9@0U>IS`LdNql*<)&|L3pb2yVz!{F%lz|I zfA+?3Ae*W_nVsJXCuU|4g>0w~dgJQ);`6URE0m2+h5K%5uO_M-Qk-Baqpat-{#un!gGnN<8?jmYGxk>X=*a`9e24<~iM@uYB?$+qnY zGQHV|_BE^Fem(?1qJo@Q;&_4AKk4H!gJWnT_%%2Lnd*y`6x zcLr-etr{Ot!{(>w7{bI zG3m`9>>9pPf8K@BPfl@Y`P${qyXbq}0xH(TGArh7Tt21EmC0VDUkf>+^rZ_X4(g$o zGDDi*TNYSS8-MZtaItIE9S0Skg`~*19B5@OWr#PG8hkm5XuN!Tc;5hZZkvuI&l<-m zZsKU$pVskWXi0W!ID;uU{fbQsUgflRFR+$f$QYmNcPADcbU(02WKP+XG?2*hBR-p- zY1?WYzHHI?;Qff;)ux7f;FwUheV+QOTIF9iU%oNzmN+x+%A$6spbICZL2veqrUGXQ zD+ekKgl)!UEu=ugm(9h3;Qz(y_|FJJ{$EBAjjr!YgzZYpnig>xT^^q41f5i;K*Tg&99L)#E>?rmp=Z|GU>;LA$EW>FXG@r)4VqFj-1dC`5i6Dz+36gf3MZ!hgfSwC&nU=QhGyS}T2p}tQj z7-JgtY{^F4m2}t4O;w7ST;QtL-i%I|IBRN1)*bW1IkUx%jTD%v27<%CsPHr77zbBe zlMP_?>pjAQg1~S97D>6?k}EMwsv$}Hxre3%U-(I?vn>b?i=YNYJ`;)8(QS`vma5ND z(RIPmNhh>c#ES{#hv3Oxy2M<;L3Yv~VP|jTBd-%(uX^qsLt=c*Mx+@5) z{yXew^9(yP?^t7(=K6Snw<(2#6ck(ttdAhG{6Rg;Sj2l{3Q~A`&N)9SKQ^}w=D}@; zt0=`?R%!Oku@IM=);z7SgY&CGXX;CE&5%XCjp9)J&fa%>jIwy6X>l8V&A+~_`}Oly zxBT+Uc8?F_)}w>mRJZNw(L!qBa{;+yaj`>K-$vQt&%2A=!(V_?`iZtu3YVjHT+Z^N z4nm2&qfV?v-gqer1DE4&8vF8NB!l1H>u$0%){|bgwEu2(z%Q|XHm;pE=slrl;OZmw!o1>qlG}dhe9AnC z=wezwM)TtD^UohIW_ZhnE@nAei7w|1)yq5Q{WmKv7lJQQ`^Hc_1s!Cx4nN*$MF|8Pb@&|w9p{jL3SQ}lGT$5zTQ3Bkg+71&W;>i2aD5Tx zH}d0R#t%w*xtK)qa6KEg*mAv6e0V=_^#6GT8UBAXf`D;Ud;b|h`064^DE}%bos1?t z4lf{P&rncXL01TN6%dITDQJz2CW(Lw37^p_=yr@ILlp}NUjCKW=kQFZcCq1OmKso* z^h|6lw-JCg4`^I?CjHv85qv5&s7>XS+{0%p{JeQkPuweI#Kl$=?XGq@`7cM@A^-#M z811hm0aW4r4{B$D7T&K`%iLPo$P1PY&w|*-^Poz|2Mg4ca8?Gl+}~cE?)I3!`H7x`vALGu zzC@sG|K$XO-y}UY1&@^Xo?Sf(q0o0g%WZ4*7T^9`ZmavpJc2FNVdVptF$Z=io?7@U zNy^?TIGjw$K{r}*qhvKM*_CGH6AYW1&4KmAVJ$(0!w3>n$8Fe0V!fwi{c(4`WG%(e z?pvXzEb;bwnni@_yphSjVz%3JyIN<3e)-|9PU7v^E`Y!_wu-h9oKt&>82j?nyDVwGJ~x>H)A z6TMwljYQ3)6qQdp?N)rMP+bsu-m$f$wDTpCrm~C5neSC)f9YQBp!l=hno%X*3Jtyk zX(Y+dVVd%4RwJqX#-)hQFKUNUoh!eNM3)`3Bu3lwH@NZvIUAz`1`d8)Z3F?DH!pUp z;YUJUR>AZjZv5 zipxD~(rx!n2AJI1P6kB{kQ-um;BvvXfjg(2KCUUgv(ap0!qeX>?>Iz$Ye=~2DY!22 z2{-&qC9G3<^cZ~%hR}UEo3e>iofhLkFnP~Ls zoW2~{^W*Mp0>|*~cpCLN_4 zw^y6LUft|o{&Km!A;_^tE{h~#XrhxC*bn^y_D_5`ek|CS$p(?6icVs6#6ZU0b~QP{ zFmO4ZdzarYQgjk4b2P#+@UJ1s8x3D!T_mtqQ5biLe=m8KNZ?EZyFErHF})!ol$VMk zcwaDT{4v8nNo<0!CQ3V&HY0Po6Nr}E8uAU1=l4FlXAp|<{0{yni7|28O1;vs{`%7p znfY5i!WEswc59!B%{-EJ$y!B(V<|sDC$ZPxRvB^nvSctljf;7fS*ZJZVc7}s@eGM9 z^vyg{Iwy(gbunPpKGh)&;iRzAM_kIP{mm}5NhK7s6zZzwxZH^;)v@fxS{ePu!%iu+ z$$BZCeFJ65p&0NJGMTblvp zBihkWItq^avtkj9z|pV%pbVmqC5q;W+V8QGa>-Nh6h-=f$5j^OQPs06Jy9D=%=G2} z6FKrI2act-OcZdxCihrkK6 ziXmC`$^YBPO4SW-Gu_XSQiw48@KzT~C; zdo$TGLmBcq#hC(qdG+T_eQ>}Z=SSB!Qyp~rej${6kMM$~kL|$f9T*LbCt5D*cXjuj=%46aaZ zs(0)9)Wq5cLuq)Ek&?qgtuA~TjJH=kJ1fW9A?Uyy8S|6oXLLf^pbdKW_+B%vHklWD zndJF(zhT^Dl4{zzKoG65N%lcnkA_|9OQUjIt?!vbZ4|kc*Qg;6)6lBv<{oxCH@Cmp zG%)0*m47=wPr24ItLg67dAl%ayVSNjo`s%XcbH%^;$;j#4hG;jSJPN(PyBwpWJ%4?rqsTXhM9N zIXlNCG7?blK75+JskjN-Y#52uI!giFZ^=Vj#@yr1iu{7MwVyVR7i%4qm^>LhNC#nI z1430C*w}9^umMP7I8z&t{b5UqLcqf}c`J;J1P)Rw(Yh=(zdvwJRpt`~N9*6QU=(Zj z$)au0R&1R#6Np~b9ijL5)r{1GkA|EN@;HM?e)yK>1oraT1&0ak098}E@wg{w?O>IhOdgusaqJ5#_xRJ zArwFba2$fQw{Xwthnue99~T*SW$&8u3GGnID76JM3=kKb;LtzvX|+(utKP6{oF*LR zp9qre7bw8=$kVdMk$0^08@K#0qSi>?hj`*PZHy+pRWP7j04MFh zZfsyx5*fpE2ro{k{FXJ!gXA44ytSR|0US)mMKTH?n#>{k6pzteO|ob~G&D*$b_9qL z452Y}eg-DvtqBnXgcD1IJEU8arUP;;2qO&$akNQv;8=&G#IYU(O-FbPaI6cDkh`O| z1;u0+%0cB+5hWdDPaPumQzK#}t$9&202>@Y!4wfY9Lv!FYh4-BZ|QyfR3LQ}S(rar z9Wrcpnarjn>hV-m>9kdeA3)V1umU&c0nA$CPgb8E%2VSM!KDUGh$?A%S4I;%=NBU; zWT_9ys(9p{CrMfvDVN>AF9L_@K&HG}s$y%#I7Un8SDHGNbglVUJq zWi{CjD|3!3bJ!wt=S6M>#FZ7+n%TIT*({m)uQlsMB0n@sU?BDiMGo_mh)XeR7y+{0=P_L_vA zB)kq)?&?d@dubX*S`1cOE+wo4>i1;)F&M(O3@E}p=(TJzDIqG4{8~~>8rbBYuX%-% zxf~X`Y#z*vJ3lx*3JM3<6KmkPxdFUmFo4tikk!OG^>88Xf=GuviMB%H1zxGK0@<-V zFzQ03(?q&jBnrVibxjhnu|gXUN!`;z;0z2CauMEZuJKsXuP|hD?EHb&qKDfee;PwK=BtWtv6q6F?T52w}r?M7UhD#XLGU$MKLyf%ibbW)R;c4r7tHL4U+kpT#;y{m8aao zn`>3dMgV=-N`=-k2&t+=iz;RJ3WV0GcMrkK*Xpab0@mn4YOIjSU5LVdIL924Rttxjyre0t>$@5 zeBZ4>wVYEby>XJIxMQv1^SXf!r%@2L)PcEP$+gj3nq9NKNh`hXwygAbTgKy9Hi8w2 zh?eKqk`(T5@;WO-zp2E6YvxZ+fiAD%fGLj(Wh*IZj#y{%erxd=Z?G*dgOpB7K1l|L zt0T>gXj*E?@??m?X>({R|8rJ=O_Of;R`MKHmCPl5A&ShCMyN zkGpKXb>HxGLwb=uruRIZH679<>byYm)PULA!3_0ufpaFLGWLAww@@3s@ zC#-e1?|8kQ1$^?iUY=jQDzM2L?Y+3?y{s~XZ+88`>5Lsh#jUfDWW1eAR_z=x;nZF* zbY3uP;Q%JuesZ;bIT=C}`+jbZeq~ycKc4VB)&S!7e(&){ANSr*I~c==0m=Uwxbhi8 zw@fwfzXt193REKcx5EYp^Z|)8FeDR$nn3Ajjn7nsgo{!zU&)6$WBO|aq@s7Su zj61*&Z}AQf&y4c%PULFO5Yx>SdyTZuPJA)AEbz0mI;bcgbC*9xS2CtwL0+Tlyy2Yh zWf|7P#9nkHAM?LHhRK1LKB*(r2$OV~3qs%LW$0#~tj80y=Qq6OZO#cXXW_f9hkbdW zv=J6`WyeN4COBGgf;>GcycQ%X7c3)DWH*;=@Ti$1rxhwEQ{j{Ky%sep7j-@s54~m# z`2>s+`mrOH5IdKGK9FrQSHghP_6Um@7r_A?Q=fkpH7{U1Kjz60l8q~86jrAKBZq?V z)~IS%zHr;7n~}7bwVs-_lBX5l%mMXHcn|N@!i-gg)>RSj_^glBE84YS;93uGjfD}6 z@;msD_l9*3WNGDE#l>26WoIqldff$FQ22UlI?cuUEbhh@sB&e{dt;YxYaao8 zv~weEW}}L3bB)USV(U%0K! z*0-sRo|I`MYzq<6VLFuo(3ji& zr*r7Qe}q~EQ*?$jbPWl`*lS!dX4!T4rTCt{9wH(hIQblhfaJCq#7 zM@70PC30nDh#OxBMi>1-xQ|E96pA73YMjqman@OU+gah}S@-8T)#XV9KWcQ>)Ns@} zX7Rc9*m*eKznRYqO2o5biZgMd)5fm#m95sbs$5{th0VqJ4*u2tBxG+C0Br-kA?xrs z>+-Pa^1CL?Wz@C;{S~;tRTIy-y~0JT?&`? zR$VbnUnvtLAlN^2{Gd+!gQMB~h-7oC3%cNr20-iK@^z2BA>NsRVtsNS6K5`W?E(IP zXDdY*(9R>f0GOlvwY2=@YU~r-#myI#gQ$U{rU&q!CU?}qr)6H&kjK&4es9?d`6=J7N$t9fG|17<#o4B!J&CU5_^VGeY2F2Jvyv zhIr8CLP6ktb2_AB?!7_q4J8*)g?BTqH~Q^gbsUmE)E``tl;2+yy$E>xftU)!!m{tQ zul;T(Jz`OKd_Mm_Zj0)E62}xlr_(jSNvlMT#|GRQNL4zL%i{C?!fhKUr1Jg;w^c0q z4{nRCa;jYRzi?X|)${)sw;gYkEi`(MQo)w^eW~3Fq}ytIz9RT9Zaa7utydWOU);8Z zSRmPUj-UR;luTxf&SVZX?Z3FKyU_o_Z7r87b-Mq9+s?LHf!4bsrJE!5d)%Ks7t5Pn zZGF>_zi?YGVjO*cE$nol>TTiJqFLKbhRzpmJKO0CMezUOw%NKLud_}EYc6of`i1|z z|L!5+cYJO~4kd!1u3H8%$3yt4lnqO{Q;hqfc%TRZ?I^$~3TlMl{s*_M5k|^%nC5%- zS)cBDm+P?Yj-tI~_=TZoZC*RXp8@-2;$~0@;klkii4lC^wh~0a|HW++=mvhC+(ix` zzX&o(p>gb%i(*!T$8a4n`Xfpf6}1D3&fG}rzdmCTmM`4axL)=Pw^d>zJ29NAM*SYn zJk9f#H^)Fz3yxa*U2Bd~F24tU9#qIQY1}ZI0sog(QIewY3%6y^v6b^*t10i|OJ7iu z>f$WBn*Js4UBdN)$pL;o-dcvW2p6w#Q9;dikWKBsxUDu@<(=eq4t%3J#TzY}iV4n~ z!y>&mo@5=kQD=p!)np*M7O?q0xNUc$(x}|u!D)5JSns(76EM7nUv`2*tg61~olUyX z+k+f>U$||vo~`hHf_B#gnYw`Aq7H_birIa0zFX;JfuJYFWvxN@e{kDK4%6vQeQ8?G z{dabUIuZR93CwZR?7bEeb)umN!&E-2FWlC4h|4UqybP!vBMONv>Hv__=xK-EeEDW^ zFc`9xnvG6vQCeKo2C^)F@Rrv%3^;rpppd73?f$D}nRptE;*4$C=-t)^Y~Bvyv0*)$ zZ?kH@BWV)J>kkTv%x_J2I}j7;QvN+!#0@(8Zl5=2(=558?4w}iu0ONjV}yB~yT7MBtW)rHS---IEIaLL&$FqwUjKaXE^vvmfy9f*VJ$Evbax zGIzrbOoRT*De{He%C?k>;3Sk3NF|&*f3j$NQ)}t@(H0X%2cG?$p&}e}97DqmPSU(~ z)c^E-)=o^s2z#+b?6CrZ-uh&L$!?G3b5c%S9d`$<@+%_-TVo!+8s7eUSG4@kY|JrA zzEsL#G(wsJ&^pkVl#FY1&Ri-qW<0(o$E}ZFF7Pj%RL=c-NSP_bFu^o8EK#n5glboL z@S;TlNw%1z=F(hJa{=s~3}=SS?qC!}puyoibnoEKjnpnrEMa2am`UAS>I-aEhY#h~ zK=@qRGHAe*oujTzhyUtZCpft-_sOV1*KZFdRMZmvKCYs`TFR-wqt|;jF$kuRG^=@2 z{)g6Sq90binr{a>JuhviSde~`3jY{EN>WOyL78#}MH0JQ3b>Ebu`=NYd=x|SQ7#Ml zMd?a7axKK4p;CTJS|#`|l!F82OacZT$4bPO!eNT{hSd#nSZv(&(T@wo0xwF4ji> zJqJ~aD2q35HI`E9pzAc6sddQ7SF1LhabfK$RzN-?YZrtWsA#cdD3a$#uvr$MVQZ{N;us(4u1P~HU{pXPVyiG=Wf*P=D@+f06D=NQNLkA6Poq2uT^X%*^I)bY=S=2}k^R;z7MX~qFA2N8|bpqnXbHW}Z^@GI9$ zN;q?_sI_@fr^ak{)?E@sz^u41_jH1obJ@%2K8qf=L28jhB31v12m<;-v#xfgj)R%f znZ#l@Bs-lXw7FWbwMkmiLxoYMO7zCsYHrZF=wG!{-7CtKb{ zafA@x`bLqJlXQsoMVQI@<`qAFaBC)W`)k0`j%j@hm7`{A8ctRT%GnP7gbfJ4cYOy+ zEu$!e&(@@JV(ay*F#W1>VsQd>XD$eH|k_*}y&xlh~L_mqSwX z#sQ7^WhX!fJ3OC$Q#QY8h+yA7>xtJ$3bu8mR@t^E(bR%k5NN#-+L6w}e8g?rJYC4| zY{SNNEaV&8Pi2#qfA_{CUCh-$RcJL1k9*2f?6J1^NyB1K@_?@U3&F;y)^%il=>)d2ISHKnjw;h4^E}G94bv zY&OxUSvJ-DTJu|D_eZ4%nx1TM^>e>#-|f}h`;QQz)N2yj%#Vb9P{2U+_un7F#qd{YOIqmx0mextGtq>a;3Lw zjyb$npdPO8hNh2hzb}TfufK&U$vvJtBEopQx1gj|ejIaYo)APk(Fb$h$BEm=KpTO% z(Z-YkUjP<*7T?Ii%Lkh$^m{!81^kN>gXa+5;h^fY zJrk}`7j9I&g>fQ<>c>UJOtm_S&CH6DSJg&9Dg^R(=yBtm%I^Lv!c=n4hy&NQeuUVY63I za5#y>gbw>J)Z1!{QB}!r6i0d zKaVKC_ookxwtSa>5bOWL1`Wlg16(mqbe#tKBalagr<_ zkSgMm^29BuqOBM*82-AvswV9GxeDZ{|b(U0i&Z~7kqS3;B;#Z)| zV_Qo({78I(OnS@28hGwezciBn0Cqyy68OL#U;?y?i?>cHw|~+xfSb3eJQAiPUNk?- z=sxC0J9WaE**8DIx;B|ClTF2%If^<3ESS2Ez-i{;HBBHLoS!Nq5Cw!RwV4a%Ux$o|ENrjZ)-T~Apal@m-HHe*pQPsPb`|C zT1Axu8~hz{gW@EWayu|BDU`5y&xdaX3tgFW2%Z(^L;#mL3Gb}n{SV&=HvR3s^r!4} z+@HxVS_RaPu-JWcG+@6=#|#FUBJd^+L6$|^iS|dwZ1jl2d3xBRhY5#bz_r$0Ue>xXU$nW-LVRWMhu25OoEsWMlVt$!%dI zV>a903T7QxRx$;)hxvsvDkxNC9+VOE!g(?0cn7K^kU{CU4!Go-*%9LYJVGhl3^6Ki zik=OO?|3t5b_X{J|@G#2Oiruuzd5pC+Kjv0&RWiPP)dl@r`<~Xt{MDrS2RVZd z$3T^zZp=)jM+;#YS*zbtg_g)f8JMW{I8xBw3WucwjU?MJlJPaUD8ZsEiodDmvWZC( zsl=7J9EcY^8mc@Co87Y$*OtEI!v+b`1z%aPl4G+@<@j4=y)XF}V)gi^Y7iPWt>W(x z)aBt_;qXl+r@^`oPj*PhZ_X}Oy5x)L6ofh*XQ^n>(IT?-dOM9*rgZSWrUja0eX0gj zz_Q!L`e+-UznnD}YTGGLq+UAiXZ}G;{|)LgSa0qkLQ;1YPBuzzgU@72u8kyaoFi;4MIwuP^=*mv z+)pn4^j~k#mcDNkc}V;%R=%PhYuRX5w{t`kGYDq& zLl1==f0lNV5Pg?OtaYAsH%W^nX>S7A=AY#R8=gzUk0^QUB(>@B`0J05t3Bkc^EJo< z`d~HPE zr{h=ON!-8IE}^lRfhI?V($y8IGNM0}f}rViMl(4W-C+^iQ>v0Z&^JQO)vNzwm`wOj z*2l!e1V$7Qjxtk+qKZH$2@Q)~U$<#u|M>vrpG3oqVQ<)8l%1Bk+#y;OtXaYVPn7B_ zk%^9rxFxyte#ySH3#_?Mlmq*bFyv9(T^KIfk*LezE0+#cmZ6L4Xwn#pTM{g!>ADTR zx~G__7rp}QrL1#h4hT4EVu5Jx7bGs2s`pp-z`SGD*5=qSD@?9jKlD))G=c6Ov@bDa z&cz#H#jbmeX-eaGV1&PHvT269sd;&JgmQ5LlX*h3ss96LkxU=qirAUsa*T(k$1N9= z;i4FQxsc6ofnhTwlZ5uC>o_kl9JJvWabfv5tQ1Fr*>qxNPcN<59}D)V#Gwb_Nk> ziUlN~x)@I?0To46)YIz$wB#eaf#`=;z6vM&rWWguT&As7M60IrOXn+>XVQe4!S^S< z>^4DSm;I_o&Zd{8`5}>yaUJL~HxMW3h9(I3r`LzAUO;O$CR>lC z-enQL|vOVRW^(rH@^muDii71VvXGi$wWC!~2n+b4BRTpKNe90#CEQo3j zI^S_Ub+rhnn0UjNfAjv81YNS{+}qc>wKtKzsf6dTgB)Rm0Z~~A zb4_=jikpihYccVEcGC6|P-|5alH5l;93XY+ z?8?i<6o3G50X?`r#1 z?qalW_-HEsTnF)}#&GrrYELN7HNFWO^6(n5+pTWW>Llu1uKIE=z`F02DY55vZ}mEW z;w5f)HQv|3Slo5h;~BcTw5~NUg}@}B*_^)l#hUIZBYBVVYB{R=?!coY2jg}B#bu4( zet^iTC1XW3S6EM zFAoWXdIo!GL%5F?c(q3lj%P0ysJ&-)pV;|G$Tq9^6}B#tc<59E7ob!dm)}9gjnz{E z{kq0Vs|0ol_+x9$-iSjVdW+uKw#LE3C+G1G*^%C(6qnzMj_0Obz2!d@7vDCMzYawo zu^~Qq2tKC_zIV2_j7UzcTRxXacaSdb21hRnJmM7_E-lNKZJi6YMDKf0(0EXg|99M$ zSUm0vwl`-fBcPlOq(2416vklSxlDX9k`+9Tw(6 zc}YEtDp4<0AZT@Yt+6VRb8rv+Z`@Y9QS)f7((3=jZ9^nF`5Q-PsSQB`eqXq)_4VzWM_LkUuzzZy!`kd+;;lK#bMLdhW`rq`C+xo z8c6}w$xCw>bHUM%1mD`_oNC8G=m#;hNbrT*wh#s&a38NYJ&-w%dIVo2uLNLOvSE26 zqnm2zylA))Ibk0@XgK6ywGfBXru`SU4J0Qyw zW8*;5HlYVNqKF!#%ATPwzf-KDEarSi zAvno0o$;T^v)oTxDY9Ymj>tlInqIWB*&r=UgUum5j2(X>tQqA}45sG&anbZR(TKHd z`wwobxt!f{(nKj1o%DR-ADo9Z|CIn7GtY-jEyFA$a)wC@OF8whsO)@w{labe(W%W( zYdOkm_A8~-%O5(+Oe?@A%QWh6H=p;-+bwxa8aMxg+p_4UTxA2W) zn9jEaSBb{&vL7|QG)XXYe=K2EcC$u>YeyaOV_&Wvk|@ZpTKa2Wyml$0g*l(*n3h4linIHnS?Viqm~}2QxbWDxce*4z{+UyeCXwDsrZH4I+8nnWX=Rep2jZgWSNh3@Z$^YI<_<#oPw+jdPO}Wub`GQ*?D5}5@pke^j-JZGK1r4f2uxXpaQQ+ z@gg>$yp6iiJw!dpSaab6MhX~V?0K{EBWh{CVt#RI2>Z*Fy)B6&jE>e2umh6vyMH_ouJ`c?O7UmRJ?Cb zDT%D7$0XJ=AvoI-G*I|AuKX272jEnaJ0ifi!;`(>30Hn;LozvIa8g6eBSBFiDSzI9 zymvw@Nx8Z>mN$z7Pq`Cu5Qxh%z6LjpVo@Si*oG{&0DJ|EX%v;a?AE54m;CKl$b>qz zybuF;;agH^oc3HD;ayw^gReU^>X3u+f_dFibRI^>K3vL|mzI`|MB?X+OkM zWCcq_B*x~WW@db)z{-fus0NaU_S2a=SAGYt#mC1qe>;af8LDpz(6(zo;sEtxC;ZhgrJrMS@6D%b{#{(IMfI8i~i4QK~eRTLqL_ z>uqWl^i)+2566aQ+`k}y+?ZE7mwsnij{iT6jp_|x)t#0fRIY0AwOM98|0eJoG1sQ-8kvxb$UGnp=V8AqXPF1<{J z=jQzc2gzpTsB1jx)+hc>*E5jPW8PD>vIn4Z38XgMYp3~PWY>!*cqB7+hWc^Y%#6A; z5`dAs;{<$`3jCf*b)8t7>GjSVVv61mIaMpbIk5+j)@Y2ErBJlu+9|h5(oyGkU_L4% z;FF>q_za;+FxxP(AwKHS#J|iy(L5}=M(;2xI?3uZ+|NCsZ71J=MVpYn2wCp@!x!)BLH7O&4V*|oQydPhZL zI9!IK0^N*mz?&I4!mSl3HOZXATg~vUZ^XSa_qM=an&jaqWRc(ZFT4YzEo5h3NL}+c zFPc4ywKgYxq}m~}kd@xRsyiPp=xXWAfjFay-CLVWG9Si&+9m$kYgNv{PoWx-ZtT(I zI@?%xN^8T#?GP1n>TC4x4s%~x?b5Rk^Vr<_6wCJG1T`|bAW}OSy)LC4<_!>Sb}vo5 z2M~zAq$_0Jp}};T(R18&nmBwjT4+9P349Hd>blLZzCOhhvrmEh_}yvozO57;w=8e! zQlYoDZtvTic+r0l75CvMskY+x6qVh01zgGPeOZTdat)mPpsI8@7A841?*~g+Tjb9L zf>^R&mhHRlD#q!LO_C|sVX}JH0yidYliV^H@O2_xiT)DH4}LOhb9rXFX7y^~tUk#t zGwFW((Ilu^eo85;tImq<-MVhz0e^DuQkcE-exGX8dFWB=xGoocACz>Z(u)4L$&}YW z5cehCy<)ys`Aojn;&e<1u6d{?cs~cTdTUjJmNS5Je^hf=oYU=ENhKJc)Odx+QT+uu zSxa!ck+D9iH#9>~_Gd$ZO+*ee$m5zIJ$3ypH0Ar}^tU`cmP9>;kzf=3oRSCKEm=7* zZbH{zImHt?P`8_i``covI}=nJkUy3#ymJx?^-fH{xi1JHgMM}>3=P%lFSY0wXoGa% z<1ppV#SqqVA_sLYn7)c`bD|aIgJ!_3CI7+b$^%U0--&XkDF06z!2=ZKkQf+} z?;=orj%2wLOKXS{Wo^-oMUp+rV~-hZ&*mDfO3_3u(=_RQyD^}%8DcU5scprq+t-^$$LON-| z{(-S+?>~{ceM!YNX=V{6cyTdHV}Rc#U~B*S+rg)CP-)73oaBM%zWxf8dQD~8<>;ib zTaeJ>9^Q9SWlLh!!_kIkW3<9TG39^4=!N;-WY!nUHXX#8_W3^w_cZFh-flyO)yX_R zOvD!R4|KBBf^u}r7Ise73Ac8-1XV$$|MbNUF+74<9uK&YO%r=$K2Jb;S`LSzl-U<} zhw^DSYS)^=mC2icJvNO)c9R?wc1&yLJB#&#&e#YU#; zj~t7*GzI3r)0xW>{J5^ffnR#H4`CX7P?2|&skpxBAue+FI2|C@Gh02pd6B22ue+O^MDvLe{^l9L$xsKW4Sg$ zZNvlTqFr4GO|P;EuQW6zDd~n57~JphF+*W#-xH#D$V0^nL;FBb?oyQXt(0tW#1_m) z5l#EQPu3!bup8VKT zE5`$0VFlq*=J-mAbh_7V4bHNML7CQQ!`d86v8Pu2D@m z?~VVVOmQi-*C8VbJ4p$lq{FuSAS`ozRxPhRaW6Cppx-T4JmFl;UemTTaKeeh)YST< z^8JBhyc_BoMOm6uR(hG`DHavXSSH$ZV(DO7et446N6jp`ky#XauVKc86_ewTkb47@ zTBTo;G*~k=6tlWq%bZ^4AsIJh?iocRq(a>!dlt_;lw|`7iZP_|K^|)o3oG%lat$oE z+9-A+i*iSnX%Q>knWdr~rH-mJul80oR}}3uCCT2k>T(EE`e9Y`dS>ZHEu4~B))q6g zn`_`u=tw-zO1>F5b|R&Y6nr~;esf%^Ok4I|)_hz3E3l&D(qgzvJ3b09g(#gNWvS*6 z7cYm~uV|Gt2OBP0(J5CUHdayX^p#XSn$TujV*Ky|ZJ#X#QGN|Pg;l>``=MY9K1WqQ z581v)Rlhunymm2QnftwP+sI=IqIB4PjO|UaR^R#4+*gUMnx-I@Ro&xXdn6S-+ElkY z+lqNrlS=f_zWYN~_fbbw=lEPvo7a%W^uD+#qXgDK7T3U9U4LKkL%$AuTkEAZzNVcJ zf{OREeP@7`?t^QV?{1`*Nu=7uXEY*ZWZMD-aqC>wG?mRHRX|c7{53qVIV6_E54gLU zZ|k@}g;&mQX#h}SKN!Xuy+V=GEiatu(+SV-I+ftr{ovJVarLfIrEf9jwQ9p;>?G3zi-H;*;P{e;fJq<*)V#au~n|wj|j&Yp|$*ea*JxXZbxPpNI=>d;3y!MZHaf6<9+aZHJfcz@o-P!_kY7aLqr_&#V1|!u1wUjfwT@ z7s|UWgug$W~C@ zjw}BATUjmy!8crx5T|s#Q1uU*WW&nT+wXyP!r}F(dUjuF5|H6Fyw*K82>y1af-YT@ z_bAE9Fy1R12y_q%Zeu2rw#uR4}>Ke@&m>Yst4@pf`C^$2?n>X92{ zJ5Ffr*FOGNzcTLRzOkZ9|B&DS-k2XK`J73TMD{r?`H~t+pHVP9*;fv-Moy)^T7Pl( z)#xZ9;!2KMNP%xtLZW7@!fF*CY2tKdE!H#9r*{tvTc-;Cdr|H|=YTljJtDNp?p0K!d)ei?_d#S$|;v z?9mai7D_{)eZ&|i*u75iBmCVp2){=sn*}Ib|LM=bUD3}y(a&E4%dITT$Qi(q(@$>Q z=f2l~j``hCx{*{}5T5nXjz*Cz>l_;9<|jon4`4xXcfiKD$+X*`lj;^Ni%nCnj}hF3 z9{!Q6{Q+cqL#tqDC+|@>{p9TIAg5ZzOorwEWjUf*^ACsb! zSz{{kb46ji(#au}fGr)lwT$nz^jXZ~4u%%j@#n}p~5#5mks@onC z3XD0Sg=0k6^DTgbvp-o4ER821jRY)WyotlN`8UV+KLSmE)=^eESwdf*`-oy4d5Jc5LEUwb437{bVCkSA%)9{{D_}AS?p|tO zMagbyB>fEFV0zhiaSTmze>gKia{?|+vX(_zS1&r1v_zK5T(5cT{MTlBB`Cg_cE#6* zSJj_b!l@u3`jyATXbwRMXS*|7@{*QP5@EI+Vb6fJB1dlS0@r4>02a5Gy82qnr>Ec3 zFSic!QAQQqOWe}5Aj&E&2rX(tsn^%uv3tY6wRjUZ5Vl;b0uOke?hFrKZ6@sZ?X`5j=e;FJ1T5!!z4FcR)@oQ;Ftip;e=tq(BeH zTz&wbTYospXUaJEF4$*tHh1y5KVE^)2*^LL{hHYYpjywydu5|UY%ynLu@<0 zGOY1U062k!cwcpV?_i_5VU3uK&xOBAbYnue=RErbI+~N!ga=t5-t^j=;ssuWSz}p1 znLGl&j(>8-=nDow0mzkGVhsAgkch+*IAaY(!!ejl7g}PC#G?rWgHXBRj3whK6pEBv z9d;3u84QLJ+)t22(wOZJ7qH?@o zZ;uZjD!|NU%PB(fAeoj6+7{hX)1{8oGS%s9L9N1V!Q(G{Y3 z=MFbXBVPjy-#_JUbdJ%lZ%?*cZDu~pFIExf$t+H1p9W=JZ$3AN0=7S87<+X)?8#H^ zC+3LTV5k;K+u)eAC0h?ugeN1Hf59t={AKd2`R1amm zkYU;$uA1RH;qp4-c_ys|Pe9Eok7e=PG?)>1uA~;pXf-hQ4GYqs&i#gWACF~461QGZ zSVD|co|B}C{CXcGNVDZP;=EXxm**>#Tu_jtdx%t0kX2b!rU5Q4?%FBemu_#xgv})D zPA+nijfTO|hNSI0&`H{)+!FKDCBWrXb%5Xf;Yc7xN!8D~F=gN)IGav)e!LCF8}`p# z!tre*o6H*ae;F5zv;nG#>HM1I%sd_FZPoW#HxFsE(lVE1;QyeE>6;7g+9H4=~1J8zm#4>}|w#2uK zEnWHrUT%+N+LN|EjPv>FKTjZIUq7>(ud?>@-@M}Zvc=EXD9zJS;qsW{5Y`Vf{g77v zXUnqQEY{g7i?T*>S665)U_`{PrOM_V%ktG4W(O^ekcwZ^l^VKPOLS(KG_KQ-1n0KQ z&9Hk(!Y(r(X^;V%bw(L}Of68+YN~x+L_&-vRY!^O>)&cZ;&P>1WPL zLOj5w(!(;N@tvmg4muX(m&@R|j;T637_g0Be5rBswWCGet=QlI(B2Hb0EY09{ZZL? zsLL3EE_XZ<8qdx??4-Li#~)oyW-d56F>X9 zVcvzCBA$y+wKC>x$`HKDF#@~SKQCj>uMUo3 zYs-c`GpCRmJlS(q*NrWmh7fL=t}Bta@Qvtq%s8gG@(5EWkSs9~mgGzeBZ&-_vBf^8 zc#)k#T&9d9%mXwoKk`_-WqUZewBzWj{Tycysho<`DB$S&eC4jQ4+(0z$S zc^K1=o>aM5ToeNnr9ii|MqLn0H!^vMB7;_w6&lGai%AH;;zUF+=L)71pW zv9KJ3%@Bc;1Ht%_sa&Bnie=<6+)#An*!X=JQGz}>p#O9dA)5v1;A*4!50)Uv@;yld z%Xp=@i!8ica~Wyy%J3}u{Q5E~=Mwism`tany0XG&kX@QGYg0T^P4z2y^<{6o8#S%9}=Ht59=}_`vD1<1ELR2le;Gl2XQBb$MUQyqPfYEU7}P zC^@*&4f@jv)Hh+xN0pLOE}QdF5088uofgLpm-=t8wU_}JJ9hNyfew81!ErP($kUu^N~0s* zTpNHYX)~hQBE5nuCwJ`wExPP}PgLG3gG3f!V#PVF7)IRh<$%^Ibk_%(X z^d=T2jeBo^)$v&FIu`-3%5RRO4YHT^x_BG8%+p*o`uosPN0JRB`L3f*QN|hRjypsc z%hN#~DIwwcN*`fKX*QR2s=X6)Lh`TSa!CiK3ZwmWz8A9zO(Y?X4W_%uYxC^f4JCZ} z$Avj-MNvz#Ho5N$iqqVlB)#>F9J|~|pvTlDb8xm`^$!5^6Sn9k9J|8xdwOqM+OnlL zQ*EwyiIyt@Y5L(^dVc1RIu!OKrh#pfyz#jW1>Fq4fs0uikCk(h#+?!h~2x& zqx4z~@M(!;!gq*G4&1}O7%k#@w@(!I+6NT@m#O(@4VpLDA;oS-J56sA12PWzo?iaO zVkHEDnH`A+k51pH-_AjMOkjw&Stp=7GF2&#iitnX*Ye*c*m? zHm?kSI+TWsoXDTBudoHUwBEIYE?#tt*Fq6p#i#iujh9O{)y|!|^vF&*pkRs|>8(4p z+`d2uw&Cycw;?^|H~y|(3glb3BA#9i$-`r*qW;e=OAWX7PrRgw-mgAj>Fgb`7AM{X zuQSHF;z10ft0n}fGp-`{bH*6wve|EpHpp9j)$X_!^ThbGu+OthKIY$a-gebCZ>QBp zOEp$K>tqEECcE1n#E&0G0`!Cn{(YM1@4jN_^u0w;bdPVFd7hd*eDDF9MH}?Ao*O~= z4-DJeA4sQpW#NW~Iw{ehbJ}n7^q&(php2X>mkh+WNXwc(zMq|a=c5>5yx!)%xej;z-o{*fsSu{fl^FAvFP+z-u20nd2#XByHZ;8E_n z$!;79c#&{B-mHiOnHde8A9R{xXHe8fuUmbaWyhXZ&B|VVa$F6|BSh6fJ)aO$(_&|E zZwtRC%Ay~98!-i6S##la`Yu-ax>8ffd=Bj@h0uTfE7d5rjI>L_A;v0`G>Fj7vdFGhq| z#_q(2iP$b0`sB+$;VMA0uLUL5iv8?EVD<}&qQlXGL8TKyjf_PV@UPBN0Qk*d;rv7f ztAPN7VNZ?{i(F#|AmPdz6SdSLDM0uyhU3gkrZ|VH=Fo}D{G>Zq`CiuayI?-Zfn5lk!h)LG z(T>`3jKWuO2{EiZVV2sll5+5hMvIP$!Iny)6kRWv)~v3r=awDYgy5s5ZmTZs#~eum za#hVa>9zwNh$n<0|Aw~KnrdOr>KT~^8nLA8ryjE(0mm)nnFHkvBk5QFHtTL4@g2px z;`^EcI^Hx|ssp_+LPO3R7+oZIb`Z5IB@5pvy`T^cTpS`yD4X9dY$P({B=X6xyHrEw z9dlA9zT0DCMla=g7z-389VJo``!;_E)@Vn{fjR(@(#=NgfeTC9aotqSBlE)?FM74BOZr5-{{+ry9RZPf6 zRHFfLyz;MM1B+RL*x;~OJ&S}1J#2uqs>g!3Y%zc70*Un+yo^%EY`4aK*Etvv(SD^>X#Z-08${&T=v;*FO=^R7A*rOBN2T zIeqF*La{6`InK#%-^tNP7J4KQx5q1jP=&aVsqmBm!BKKRa85jD7$Bo?`z!`mBdt3! zl&^BkSm-Ewqe`Wa;5MU7a19Auw6dfl&!#fGQlpq!;&a9ox2T+tw4?wr!goJ9$ptcki$2JGK9>TEAAUsyW9!?rU$|?@`^~ zfC;E{!iT-cbX%vUFnBGk(#L75J_OFq5w988$Zfdv`=m-CzX>9g86wgN;D-8dd65F` z>S?y=7o;=0rLtlrqs|pGhw*)Ztnmevjn->2$&W`=XJ@rP^*8%XC~8;e7b;3ZkDtm* z*w{}*V@tntEo)k744|8d;aCmG9-bW*kTI9p*Cn|t8&%s-dD&_WG@A70W?Se4LtUl} z`JSe^RkS5s44!X{tU+$=?lrEO##(3Nd!1!pABpD_h!3NQAXrTW1T|5Y)Z&|r80?=7 z3ZF%rO_Awuo@`*Am2}na)#qR(lun4Pp0vYNE%?TS#bzu7z%3hGF4|M}vKBU#FZY0x z2qw`@DzN2E%wuXgrh4|v)(rbn98CJr%H+9E_dl#;bSN+1Qq*bD>~>(R2}eklo6UOA z?7fMM@KtTSUEuLuDP|d~N0mGyVqia?7>-z}_*Tfw!h%4bjtkJ71YAV^Jy}$t;%m@T zoRhm$qFx^(n7=ZabTBvLnCPfHAF`)dZ>YLT{8B4+G?Q|L3rr<_N~S2gal3EgBX)IX z`NfRgY-j&$SDs2##;WheN{nVj(eg}^_3YlI_V3rNb4RK!X1rS$vq!$F_lg?P`m_G$ zisL_2Hx?U`^Hf~p2hTqA;G)KAxEI%G7Y^bK_z;gcqpnyvl0)Z$`O_xM`KgjB!6rN| zB=neGBrVJ|f>;UtxOOF!LBV$-MX7WujPI9sAaOW08+MhNLbiH114F3P9h^cfc+INA zKyoM|(#$S~hc^m*9|ktC&hK{L+xyuSh!~ye7)*!;=8qV;lAxF$8L2kA3%C2@-|8ow zV(jOhk^qrUp~I;~f&Z9^{02Nue5#ckir6!i2>nnDzI&kkYM^;s?8$PJh)S||rE4+* zp*5vDP&J9|nNq+`Ocpb_Dj{4$eJ2M4Bc4d=M8Y_-CDC#|PRKllgB=dIP>Y9;Dd680 zrIQY;GL+dw73dVTwUW{B45_P_`DaBX8IwlkC3|R%$pwVO zI}rSSR*p11f!aN-%`RfgowaK@g18|?z+LD4R=x$zm!l{#_9RdCkK?F19b0Pg_ z2IQG>UW0mC$16uqTYbNKexD0?cL`&Qs1y%KuXtm|$!Y?KLLyIlwq`mI!Kui+wn(Nu zR6&zK->kT8o(iKvsxsYa<@J-f4K5HP3xvIh!zm}ZrPRM5-=DK=q1EX-T1<(W&4f|@ znFgAg!R(PJZoZUf|B#r8wThA+ScOG=$H)`fP9E{5PTCgU$LSBmmv>Bd3KqgB{cKE$ zM0F|0D!+Y=reUf)^Vs8U&JBDmdVKpVQCD5bs3JwHqEsm*jwro&tzsjpW}+lLU$;h8 z<7DwDcZVVgd%*CL|#*bS^(?>l=p)xs$X_gaq0svlAtOWll)-54iz!SE#dBjJEI#!Woi5n`PtXjVO;rp5f} zIYk>VM!PXh>LN21&(VQ2iLKR-sNJ=KeL>}+LZ(?j_@=~OB=(bMvS%p;Uuh=ai5V}P}L1ZD&prdPU?4t2Us37mQg@=UqXTM6eE_bZL^^z3s%oNrj zwN7LDI$Xz0s&fV-!A#d%HOWgg^?0t@I z9%Juipj$~A+#yGQN&?!5vDT8kClNBb9}nIRrcX=wXAf}>EIHm0+y3wl`L@Qw?u6&S zgxayG&z`{7W-v~U#FwV-^`Sc+F^!KRy5?yMqZrEA>CD@Kdv}lR-@S5dnmU$qPrQ{i zm8>e>IIf%PltRM^p4F~yAq6gMwxCNMgL7bc>v{4&MlmizE}skY?qd#~8A#met8NvQ zzw_l7r^ajtp;$yM1W)SiDi}b^Ak6*j%huEcHf}HjJ?ECv1*`jj>#wUohs;nOg^;FS^LWt zd&py#7@m%&1XyG8(6!oj$<0G+8@^cHuD8caZ!}+B)C<@3qK%E7+yqY?VtD-@BBYBFSQzyWAhXcqktw6NDVfrChf?&F#YR13yrR}W63qs)9mUGom zsz(hXQOK0@1rL+O4Si;VThry}$kYvEdA}fx;=tX+jf~j?T5{tg-^l)2!sFSE#VE?Q z5epvmLF^`I(mfEwFp`ENCI7aOFiAJbS;LGM#&bP1(<^{9&B94{@ry9n4llI;1#2}; zaY*6N$^2S0(aQ0~i!dvQC@Crly@PyP$&8fsFmVN8Nir>Qdpaw1{-a1`lxK}3sZ^4e z6Jb#i$_lkp7?)6C0U+IW>*Z_yGL)`vzaF=&(Pd>GC+mmfx}<=`^}NI$r<(xO2meqE z!ho8kRK*f_%p!RP45wmr#oEAXWL5yiBG zBOlSq#v%}cn*it>|4E&gKh&I~XjC;$Q$sWMlb)?^VG{gF$}p8(GA*HmA3xe@zIsbb z+c;Gqqi|jk99&1B<%`%(>Rz2&hGm)nS$egPfY^cM6wnYmh=AKT!wo@vKk;YAtpU!# z5?h&}zi-gnkAQo_C}=tXP(M!7Gsy_O$3biqgl1G5<#yQ6N&|_xer@;Tm}QUo5x^EA z?v!@xBI|Kh!ZrkSvVU#Hd^@YAUM?0;Gd!H>n+fB2TG0n0MKMjgA=^t?)i6afc>?$C zwm{I6SUHz^r#hy6)fTI8gRyhm4()4*Bqo1nd;WL|ho^&lqQ##b6wd02+5215Y?Cl| zIV0!$Nmwkqc`nv(;R`hUr0(#;9K<_k?`7IO?g%2B#3ls6W}GbPJjDPt>Ua<4U!G$K zxIEC)JJ6wb(C5fx7BCLY92y6`YrTn<(*hCDc=hSy$u0&s1Vif{&8KECyv7O?tmA)3 z67}Fh*@rz0>=-?`7U3h=hx7f^`(Z7D;KFWe+h@1R3s(#O%YojeM`&aV=8hHm+S&#~ z8&6>Ki3J`AMvO|>7={J~J}|CAqGhB$w5O`i;m>>>+;fUIGv5MYDPiEbb)c-D7M6?W zVJ>{bh(d%9DdB^uz$hA^xkwZ)k<5Nepa!z`XH=9e;7SM=!g2VIa0r~IIDN$Q`})uM zv`(16v+kn=T3EKH!<<;tv1sL(`>o)-=-YD+`{SE%jkWayD${X16C|GNq-Cxw4ocI2 z5*9UYS$h$GlqmmPCos;QG*&1)0)4y4?=rX(*aIFz zBfCl*WE#N`kX6K3zs9ix1ae5OyvQIj5+QvGgCG>5>HN%vM79-T=2?b%<-(3KF+R;g zD+^?x@IOl=ae?-+Ky@qse3CTK%DHLfYNSXTu3Zp(6G=}fIRfhma*7joKi+10a72|o z#%K);MvQB8cj0tg?6+BdJd}`O;R+GCjGQPz@o-{DBGn!!)u*sUDsi0k?*53eB)CKT zC;pMX>5}nO^+~t;hvD@P!Z`O?Buq@95$brc78oo5Ru?uV?YlU5B4(e5J*ck#IR={q zs7+8{kj0EV+Ts|8lYp5@?0YN66qmD0W0CQ+dby%RnSE2Eka8veB?G+kPojCk%+2gWS0HAdJs(hyNA*7GP%&Op(8?2LHQ0q z92m=$!chco2{GKyYWJCqv<2BAa~H!cjXBGn3ev*}H81h?RegG}fM`7|(6yCG7dVGw z=30<WEqjMBN{sY&J%J<-le)+^_&kjutl$>sDl9Qhofiac=^vR3Yc< zr#rKy2!g~he`FjN!cE!{o|afu`ZZ^x%bMn-q)rO3hV&WkBs8g`AuaDe8Hva1&H06v zAod|KGZGtqn5)T7O2u~07P`NIY;EuYVpNRWJmkkbX0Ubs{DF1_7;OQ-jX(E@rXjLayb#Tqoz1mE}7@kq?xoO60k9sbn|E z8aS7ira--b-E#2Ly3A+(_~Cg*ujK+Zm8qqc6F2+1KTR`!{MGOY5{iyyZ4N(@SnEZ4 zttX1U3DXd4){H3ACjMN~F+t3&x$8US21-&m6R*ubfZ{YPboxJ}H0_vIL(3r$()EIS zQ;(X?WOx#0Vad9G0pFoX)EGvQq-=Q{w9b&tN}OrsQ^p65k9`7DxbPDo)Anpc`I)ls z{cyC9;;gFoCMF=Q@9yF{vjBu?oW(T3oL28}t#h`<$=&+%XBar!+RjHxZSOt1ld z`!eTge_!fAu64GB!IN7Q`S+3-^;d@)+oP*$$BX1#S~EB{W5UTEt1FlEGA*I0{MFjR zN&el{ms?h72mfVWbwM95U&-c~x<-%_KzSMpL zd}s?eb#CihO&fAJiKb~MIW`8Y#>4x;P3M|aBwN}{=TSF^8nWe$;*^n;gmPp=&n~&t z3c}#{c%9tva%3Ny?H|MfEp0wF45xe2T@biH_4V+aWPO_0&X2EF$@cd2%cI^gGr0tXoKs46C6868;W@+ z@p6^=XBf(pK)9hg2e6Ei1hd)GxcTatg*+k$rZ`EMwh~epg1hK(01J$im0{8DCCNiW z-5_|Hj7<4XS=`G)!;sl}8X36<)X7MK$%*CTNfB%x{JDP0tEh{&rg~bfV#~Q&7^#M& zjD}|?hNOVHXSd>xHtG<9;=U8WZzHgc%KKp+(ATu`*Q5bOSxOmfRMcu;B6RM#J(Zj& zK|CRvG!#_r4qStWLc|Elf>HIswZ+4eDIz+5$`m3+poUt{m_>^TdEt^rGrL8v|8$}k zLfm~om}p_cOw>ECg*z*Yxj0o7S{6CAgR2dWxoC~ik%uUbgML(oDvqN?iDz6j20sN? zh%Iy-ax?aA;MhWvw_ou22X3dk8r{v{+py=!uN;jS9$!E2CReDrnHJxp;NuY*#X%u* z`5^faA~H#gFoG(@Nx=Y)NXlg=Z|TI^`U^c~z+VVeyeLebAdNThknyLpJu|UF!;cuk zr}!Xn7E}o&^zNqT3Q&P zxSg_-XendmZlF^kE3|;Ofq6hlixtWof-yRbNGW5vUQ(4rra(fp#b{EKJH}Cqat|{{A~M?)xe`;c;{B5Ymm8&Gilgch=raUst0RxA z(+}qpk3Yg;kfyvi$2#rdxM?qLb!&(XW7!AggleWZIA?Tt5;-n&t`(GF#|`Yoy_TaK z0>k0yMjD8lYWjYK#^v;^z}IvHvN*0+_M<|eT~L@Ype?5tF`5@N2Zt~RnkxT^FnO3Q z-(`>e_c%|i1XzkAi0H27c(CLkDy|`<-Do4DojUUGy%3r}m^OLX1wXiSdMIf%A%qd)eUMH~;b{#F(G{9Nl+t z`FlfHMG|3ry-s`=6r-bS}$)m-eRG`U!=29QH(Zc`U zQc9&6C)LCV&FOd1K>o`vH@-#cxiQ5OohlPE*24gVx*ckxNeQw|=B_qpqxI)|Yk4Ia zELNkH6ltSY1Hhu(v9g1LDCFIvrAMp7+_FMYt8K8OF4(d(w6fEnj;2izcVWMgZ1E!Ce1>Biw{@BzE)KLSNE_- zBOtSe(g^>x?>qpi5(+eH!vKr#D z4C=%4g}SeByi@9|ld!Yan}G|8q1R9!21~lO8M|*ZvxDrTYj?u@NoqhizKasjkKqNN zi)vl#s87o5aWnQ)|MbKIF`5?^4FmZ;B^yQ*n3YW!pJU~RJHeQMKw4EpD!ujUlCz%X^f zfJY~)s|A5N_cVri&d|uv{U+jm>o|t}^l9f9wEqa%<|zH}NYDAm%SU`EO*8~9Qi5kU z*4zx;;|$o`m=e<1$OlqEXD|5F>=wp!%;ub<;xx8BOM293_#{FLU=RbBaC37C4R=21 zbq))40Sj>o7jf=fd1^&_cmgn$o;JCvy%5Z?u*|yHz&X#Jy#S6N%RM!He>tsL*R@Ig zJ+E1Wx&jKR>a@JWAW8AiUwlx);4TsE&;P|(*6d1am+t>PHNm#E^!Ez>XY?!xPnA_R zqG|MUmBu1}^m4E?5~9u=ebo}p6`4zRQ(DSOd)vxR`iinupY7JTzYb}*H)V`>Q$%NW z6700Nm790=B58cTZ1hUT=R#EWWX9B_#g?zo)iN0(y^G>xSvCMpW}%d7Bf)B*L}#JO z8fmx}p}-rv1s1!pYpOrGKGM6BVQNFC3B;2Dq1Kypc#3oowl;)z%X)IHn`>nPcLuEv zCk<(9g=cHZa%-Qq^brufu{swcgOp&6yaT%#X}SGNV6}9w?;aO$9PVt<8gekX4eO14 zvjwDlu|_D)-UQvQ8r`aN{9JSVMeu8zsUdRLFnSUqXSdCJcV==6`sZ>$9Zn2a6R7OU z53OZ1+04_aotw^iSh!g_M&vKTrUA=+d4sioUOPpJ5;-YZIXsM|mH8Ey6- zaVd|Y4vj_!Ri3( z4NG^U?9yH~g{?ci$T3L9M#BKg)*TBQ> zldTJ#-cgnAFxSFWyhHB9JE(!X+LArPUa3GaKOd*A%A>XxxFztTtJt2t4$0YSwwa{g zI|orjS)aa~+P;2;s~mvqW7zCHqa%Kh9WBVeUatHH-cvGP9kM9f@@Bt!QjPLta}6PP z>-zVsIOd4u0>OrL*IxRj9(y14&z+z2d2!}#3iK^-;T)Ooj&`P~ar=LnP}n$G;i z#q}MBTn^N~roc(!!bdvkfQEg39C$ivq)7>?z$(| zGtb#W|DbjEc`a|`Bm0$lp4@7liJpi|`>A)7x3`SgYVp@@ooJ^uX^;B_O& z`Kqk@n!<;lF83A{y1#(;k|Z;fYb#n1OI!^94tRXx`g_@Dvz9A2h5U(3t8dST|K9V5 zC9~&v`|m;GzwxsVg=9S7$T``k^0=eNE9ZE&0*SY0$&`VNDK+(-Ht>Ol!Obnp4Es{8iVn4k;a0F zObUnd_2KuCMlMev7>-nP@l>HmBAL#3eeq1GOx{_#Saa!I1)x!5GOj#-p_Y)kEljGl ze5uiB&fo*O;X*Q=2(4z~W%(jP!pZWW?H4zDDfX1 zN$s^e<4G=Zu@J8xHk(0?)PKjd)|sa#%T;Pjw$>jlSL=*tcsEv`tSfBV9b&lCpKN#g zVr`B;lXp$qh{+Rpw>}!}PUni{O8;)XIbT-W+nNGAS9|uYqZOwA0=K_=#D@DlXZAS7fkBzN(e=1F{}?sKyZ}j1&1a~5Zcm9LIlTg(OwMC^Wl~VQG}#U zBwqI8RvbseN`dgu0LEMtyRZ{cf~vCdPLieplx`HE3nX?lZg|0A@+*lZKA%iTDMpm? zg7{vB{UFIvmeY5iaZtJ&q+zt~{DF!6+k}S@Wf3rFkU9BMc2W?;eei>3wYn{x+u56V-oMaNbcJ3YCB9F6JO{gbxS zf=cR~rM*(JxavxBi_+s00HP6ujC!Tf{r&M-*H6jnx!F}Kifz|9k#?HMFpAKu)8x4c zQa^&a`NiN8%!Wo?Uw{bB&MXOo*;JW^572ifDM%8GVBm+_- z6g&Xqh|(I(!>l0E2Fhd@itbjgP-cjOG0cW>O^GtI`ON~*unciFlw=cUUWM=7-Vk!L z|Ell62kU9wykV1RS=C8*W7vX=yFnWwo7q0q{{HlC3ryV`9-oLI1k;}D*ia1XZt&)9 z>mMLa^}2KaJtBD=(^s-7X%s9{HrzF}<>fRlb+U9<FA2$TzU96)@I97dgk8W3O0LZH&M;UUEF;}##tZMly_thwWf0Oz&h8*^SWbY_O%>B zck3O#5_s+rUK*qBdAH#T{539EqVVf?+0QO{o%ylv;QO3 z?{!Q!4YZ#xeX^RAg&OY%x|;xuN!%YWVFKHtQh|HsT2uI-JZV{!gg_01AZjCh=x8Fo zTkA+?x}um@QT0Bg;ULrRvMxw+Q6T~_g)of0JYdc+oA4>gbqH`mUmEm|Gh+%N6kX5& zwaQH-zz)H~^Lx!xhl!OEtteaoc@%D7aR6j>DALl17`lm_$=9nky28IetskQUhYU1= z@?#I@^JU~2GtQ8y0iOU|Nobu5hJ>CQAE;(7EQtdiqf&Pl?k$bz+e_klLT7x4<=iS3kZf=^$FV&rR=S5 zP#oi5H=GoI4pTme%*plB=(u9Ae70fP+E@K^` z5Pz&(dRs|Ch~KVM$SptuModrW@@_kBm8ikwSv*r%!SZh>4y4)tlB&HVn$&tTz%QnY(?G z>I1;5Gdjl(eK(iO8nIyNJAN;N?EaSgn>YH1P^N}vB4K7UjU9}!GXor5`61V6yBKFd z{Th@e`7_e==-@L$5@dv4unYTyo};Bi(XdhY^1ArfV4OJgrX4ki` zVPSvgta%cVC_6??gS#0DX=TQYiJBTxT_DoN(98th3rUl5$V+9ixnBZYRcv^h@Njt$ zASBWk)oh%r>`PA@*4rm*LYx8UY!?(~nyW1XO$MP`lybT+>~VBtwWJ;pI39%>2ZMSM?eQ0$POwURYmPkbQ1@WI8f8h+2yAr&R(k zYZQOiv?4S3-1)e=%>moLTJ4GcCWddMFH)4ck9%*J>bKz37B)|eE~Na+0OvWlv5}|x zQ+2<-y+FsH+cKMd%@*z1G~pxqCYg2M=#2e(ru8q=wFi33m+PZhgH5ZLf>*S0y%xsEtl0^amOhDFv7JQ3i&E6b-3OmydKcQ@U4<<~%IR}4jVfWTT zUsh{_S2?;+U(qU(AVn0~8MPn`w;<$NI8z}m+D~kPD8WCIsK{AVC{};K^l7RJlX0vB zF_L=!SPAJs3Vm_a#lG;NHFEK+3;sP9WZN8&U*pRHVdK&c3vdwRITR8yN*#;DgY#+- zc_XnH7eWMb3rnD&vIAHxJ-I{k%98G=lgud7Glb=>k|m3{_3ueu38+3K+vT-IB#nBS zwS;LBF~Ucw)(u3oNKlDTgv=7jBJ`*~+C}tmk||MyI3Ma4uwh$PoAtDZ#W07oxtgXL zAhPsDEiQ%B8U@q`>-_H^!YV~=wNYvcS(huD^a7bwK17|gDUy{24IUV5sY@ND#oUDl zu>iSNoAje&kfiBiK32n)jbcj3*?ftOJ~ZMUlZ^)*%nu7N3QXdm+~POkgf5ND-k#!- zN$939JUm>jk(Z;+-@~(shT%K$guzi?niy6@40oWQmgmU*n*?NVbb5XJuMrx`;Ea^kCj$5kH3LZovK1iJ0f4A(9Cz!G>b{%^ zRiEg3km|#k4EP~^V=2`yEnVO>R)Zxpru@AF=-_nNNChal`6E|O(%xKVX)yG9rH@2GT9x^|F=m?F-s(oK&3O@ z`2U!+ENA{CqTeR1R5M_$;r}&h-Ga|oCt7NDdi+43@iy6N_6EXkyR|z93517wJ9=N6wooT_vk<0==ii0R-%^}^$|C+SiPp1cdP+*iraC~U)sm`ksr*Xm3 z*LrKNs4giv;RNod@O8cEgk>Sx(Dq zyK!#3rYAXu3ML9cl9FW#iB~#c+b;Vun8&!P2H%}yaozWFLho*r1qG2FLHjOLcWVZj zc_CEiWjbAFXXR!8F=+woNhg)i%|NP3{>ZL)qdY03@iP$&^Wm+K^n@3}qQSd+xw>K5 zH+@!Ou=lyN}dDE&%WtC!y;>CYVTIy^4+LVix*3xb#>gu?&2$C8gOhlRK zv?>Qp{mb1w1#nFUPkUkHF`27DY}YRbJf)vhhrf}GE;j6>-2Ap2 z2aG62T|F88ZoBr@8!u|VT`@NTAf?;1BSz@nFPj*?-mY3tx=Rn;&%bhq(@d*LPP1K~ z+d_(bjX2Mh$bq&K{u9it|19ThJ|9hdlo?b^uI<9RVX&GUaueE&s_H z^siWE>W8E&r_tJsyI%v`oL+Np0q9K-g>=4}Y;;}Cv5 zkZ(3zh?d6SeSJI(h#cp|_%rU3mXQxB)W*h@ zaFIBxili|78HUBy>!ad@4@i=YqF6K&h(tb$jp9zZ-x%xz35}*8N?RnAIq%bdDjU<3 zO32`L&2uaTLDP=8P1tNRrXp+}1ucss7DFa7*f$b`zuHg21~8f<85~ncK~8zBJG#tI zmhe7v0JAMwLvyY6O4z_9jfr)4TluWfyOqNApg6hiToFP_t)v;FlQ+X`gGOm&X7gweSTd5v|gd#@Ne5|EtcBcx`jPrZELpablJDMCe_GSr)sR4CKj(1Rr4sK z4?#cc0Et#eUFXbn#&J^X&zvuPYaKN~(CWGoGOc89Q#V$x8#0?;AiXS`v`Pv;p)Fnp zyvV;sibYL!?_yvYqY$lG38fFP2A=!bOSFR>y?(&HV{|kP6>E3BizDVTL%7a@;H7Y5 zscVZ$WINqTiU#U&QMobBR~(C2Pae?`(=~C!IS!Ug9N=ei^hi9~8Mi=#GSGaRv~Kc@ ziE;+}l+OzRo5q5dT8^ow$7HxI#V5Fo~l+_%yGCh0-~YJA-@hVtmQ4^tj!K> zh%^?`;GPoxY#E{Ofz6N-UMqh}w~X-HXH>*AH`ckDscF5-RvAA4X0#!-4&K^vnvZIN zWo#TQGZtLF8cnqTE7VeC6Ph{AohLHZs=Dvn97K+Qmd^tlxmqON={|+{b8)HE_gx6J z`ot5ee1!afnQ5Y?+#fuK9$Fv!{*7$iY}XA||1x*ps+wNAac@4S^&ky^KUn+K;7)=K zU8>#C9(Slf|0x-M9J7y<4s%R99=hR-5X{t!{t>#vhu*9c_Y=ZPi3#Pd{Wz0yd7Z%g zBJ}lZ|BEDtHFS`DU+w9=!~^eX@8h$VH{)`e`tv0{c6*hS=JU$VwS6I<&dNgi^BM)f zS&u$+nY!qeD}wN_0xtIwq@r~h#wKOZWbLAf4MWv7M|5OD&q(-yyz7N5&d z#Oo1<6IBCBFykClZk&1BKCl1m4I#6fHpP1&K7H%lK@!=*IERhKWu@_ z6jsP)UdKYRQThJiBmM#}!Fq1kLgGP@q{_cu3@OTj1WeuKRznm{-9PSJR9>7U$-txt z^ty`!k>=E9SOa)5Li{koR2V{xUX)DC0>%8J9j`)PdqfX?TSb|`bF zb`Ae|%%4WeGsceQYZi415jLtG^Kc|L`C@jo5JA;y-7^wRr|z}#qMT?JJ3wx=Yo@jD zhB+3eeTjiKm=*&88FHZ>chC?OcB&pR8c~fAU5^&|(dw6f1GhH<|Lzuly5iJHp&|4H z?>!o4VIKpTo zX))1+(#yaPG)YVg^hD-MBtbSDgQ6|T&D~o@Bb5Ur8QBCbksdmL13Hl(Vq_P71_7qe z4<@oat)~})*Y3A}EmQ-4dL;sciAlUArWdJ6G`D+X=4+yDxQP&^D3Vc<7YDXPdMe=6 z!!teO)Io;(3EICFEa4S;#t-hx53X}9bK4K5Qcv0c20GF1w`?s~B7Y_pYxLX2$VKN};(4Q!iM&3nnRKW=~y46=seu@Hu09jjBG~Fi}rAxfXs20cP8d_X#0) ziXWn<7Azh!&0GaM**)7_B?aa*YtaqKJubeMKf3_Z;VT4juomoy64#Y72O-1pa4pZ} zPSP069P|lh^d=|vCyce-Z-9K3=nzz;-EXrdu!df!*Wz@rH6Pk^ibdBM;G)o7U&QS^5AA7#Q`_T z1LnmILs`rj;IrxAwKs6T--^>(KtIAmLftW;#|v%VO87jA#%}Y3HB0YJiX6rXBq9vo z{orQwpr_?ww`UPZTz^-_<(N7DPDCh3{LW;ht`$d{l}MqNl7mCD{juIBRcvQ@Vlop-ihYlJh%R|Lzz@FZ~OR+=t>E)UyXI1hS^z1^^4}JR^ zup8`Hi++%4Sgtnig=+mJmOm<{-vEpR6_uJ5xM3B`)Z!Mq7dU;_-FI#R;Z zU7xDvL9>S6y^w3IhIXUA(4*m(U@3D)6GBK6Sbr7AG3;M+WoP-i5Y6gv$+T!xn1c(Hzjuyk@26hv;O20}1&0_NQ%9tUjp59_! z0*IbCs5Gpae0c*oPk>pwHRVK&yH=CPO?^NmvF3YANr$#SS9?<`KSv2%k9>N=4K(Tn z2t`Dhc@vnZXITU$jJI9940Q={hZE_OOPVFXQL7~;q|mjaKKH$*!jsI~vwfaRz5Kls zoWGSlBrB2=GR{(Yw5>WCNSdA)2UXq+VIvjYI0}y?0ozy>j}y*l@78wD*&@}_*02l) zt8b~i(K%z$<)YZWfZeO3(#00ph0F?9p8|67o^{qC>AWI2Ux&i>5_@?5+n;!orNaH4^r*#KMKN*i~mG?w#$=(jguIT&nXu_qT z#>eUB_mU%q$t2B+m}u*L3QM^i^?4~sK{xL+aT&k_4E&&O=b@qdfitM7EhjV?M>xdw z529QOJ1_3e4_TQ;_A-9VBVa{-m_vGKdVE0blAf<~$i+)iM>}i}c{t`b;G=BNWHZ8y zJKNH|hCEWodUlu#7~WzBQ>w~6!j(AW%01?nG!owOot4NHpNxgY866R%ap*`V^&FkT z5IAn=iS8_PfEhDV8cF&Xr!pGD1|Lqp1o;Y296A}!@uInx%2tRBiZ$RJj2q8|0*Rd* zk0Bnb?VO|}nJ^HY5Z!diFYjmXoWPM7HGv%B4ax8G!kmfy z8<8lf9hnnKYJM5dvS~KnF}izMGE6i5TX_0-bEaH4|12u3#5sTVJyS zGhGRofi9Z-;+|_fnAAs|6}=q6)0j2!nx*BOF-aMv_DZ8*b=ODUVLmk*?;2Kj($hSdCd{dDADj!d=-v=Zd^s zUZoNz^R93^vj5>wY7?yFXL&*Q^!4loyI3*WS*Cal}< zizS!OCHg5t18@EF*#exch*gZ4%<=`(lF@2)$U(g&zU&!CTvZ|Ol{jyDy(vMyM8jjf zJe;bD=2j=etf>ao8Rj*}?B&@(nw4l;Rc+k03K^=ztvKWX!^QBFk-IUO&vd($H9U^- zn2^5E>{Td_?`+z7&EsmN&L$vxgt47Ld!#;Ea{dEFedcK++j3*kgD0{rW z%O4bIxw*T=Qgy{%)3s@$;Wf#acl{n^PP4U{Hv9H_J((VC;}xFFdp>_->sfSjZ)?Yb zaobR7o82S@l&bTHc-4J(yB=bG!z)eQ0cMqFU9D;-EOq_MdynzgZU`vzao60#`m}mN zTVLs}9K=r8=CInYJ?mMR2=93m*$}jtJ;oS(EWAt{-ra8OaY^nPB04XU>j0Q){ku;P zHo#Wo=l(kIYAh=yR8ke}~p*rZ4)iALBsU z=eR@Rpv>U_eK@*@y0ft?S}o>?7xR$NbQMAN5XomgO6GXG{Ll>Vv_1dWvHutuEsqH3 z)8-)C2c34bWIlk%48~WxuYW!3(_LXgcbf5+YE)+X=+}{)x>poji7M}Tv`>6c*OZbD zBwyYMW%HKZ=1FRGtzY+9^E7JEHc{^O9_`Dqt!rCvW#d!p@>17qg6vrj?n;AASGv!| zG;dgTHB(2-0nF)zlxv#`?+NYcsa@%Y>GAH$*14_qPOa=vefK5L=H*QHwL<*GBEyyS zwBN0VJM!j%-00O~W+(U7xpgg!ZPd;w?@H73HR#Uu9Ir{&z{MZ4f2o#7>(>D<-AA!t z*Y2{1ucM>8Ue`Z&R?q+5;QiqTDP)D3X;g#@Ub~Lpv^gQ?oloFB`?_u$@4lS?^4{R< z-V?~t63JbW*q-;=9I=;!^U>YLupI8k@M6eKV*R;4-M(ejy}6b}Ph`5&qXP7WUh&HH zxaZwz$DGja`~!YVEBH^`0{1eu_j0kUkgN-cL9N?ynnaBHOPg0`ojfl zseSz=vAa$-KFRR$%R0AoxdvrfO{U@x}Mj!BFz$6w`u&GJ|1N*PZ&Jn3F# zT@@&>GhFq0pmYS6e-y__{vQYl)USshWR*UqN~UUtsj?`(P;3txfCVHXKJ(w-dr#b(V=9zQl||42}H<5Xj`#k~}Mo5iE+4{Eu-7>Oo9Ra%n&n6$syHt!Iw znzS8fMA-g6vhK0D5@_odaL2Z7Cp&gJwr$%sJGRk52OZm1$F^QQ9=%6@3Tn;rfzZX3I=0wC74vI74kQI33^MJ5v&M!IYm$$@v3`^v7K?T@E*SdZ zL}6UUky3NYdjDh6x&_T{mQfO_ZUvMELKq|~Z2cal@V(K{?v(yKQ-yvmtep<60{b>; zJ&xLr14lNwEdPd6zRiO14UJjQ#craTl_)G>0hkjc0YE6r(1YZ8Bbuc1V+27xQLGNw@cThxUj2Wy^8*^0^h; zu*Yo%hKc8WXbFiQxw&C3BVPui?dS=f$*0fz^{_xdg!y%M01&8<_{GoGeao=xdn`kQ z5C#SRkIfQsA~{Yok5ga}dL{^KfEcm?N)XX~1{j<$mgf(>(s4(C9C!*AM2WjVtN`5` zD%=xj$Tv%@rj)?^2xo-o)+(}McM~iCZj9{LCvqEeW1r2s`x=zM&xOBF_hmVRug^7T z{&Gx|Rl92((JBUTzjgdTGsYgo7G-oFj!>X8LY>3{=Rz+CRQj_Acl@h1;DrngloHLX*NC}B^_y)OH$Y#DIt%0e{=vDoSjfH^uy2y-#}BWZl#WRO-h&$E3HGseJ(lo z0}~sLTUr?rAtg(SynAj%a*mY{5YZ(ax;;HiK#b~%S&4SY3_F#swqt<_k{E3 z97~z*5~&t9p9W6}wqrse@{yvLwl)i?81PphA%Tgkz59HY6)FYuAompGt1|sFwFsEI zQbIs07y^c855d4~e8>eEu3BCX^aODn*a;bisGuNJt6*#(F&a{ZX%S`436df>33SpQ z5(EuPnP^iL$n613adw^}!=(8FqHG1m>DO>nS;K7bwqYW{ok$JE9k}bfW1*d15Wq-& zk-<(lzy99{9p4}@&7E*T<+2Gg(7zc7){uDkupu<^Xh~?9C*nmsYUM-a1;m5a>S`wP zev0`J?TQw%5J9m}f_+4H5us8j_3@f)zi>YU>A*{GkhgKLPN3qfHnErHA`lEeo@Z-x*M?J^+Akn9Bgo?__Tc>1U;&Kdrp z`RMy6id--GabHYBcrkT-&r{0-RN{61{yqkn$@eLb5ul)^^!rmsk3VdiE(ExAc7i(} ziSAkFr}S_y zX)jGMT#KbaaA6^hz?b04gcm3sDkfxBH1J}hRVWUw+BFV1@=+Oa6D5^a#Z~cS1p5%v zh$`7V0O#6l{FkiXAfFXtkTZRfTr~n>Pkc)CLopLZgyuahlHG$b3fPH|{$?+<#>O6o zO6xDKp!PP(2Gst#m?QXc&$;2`p=66b+6-J(QC83mwgr!5>nF-_G56X@=ZeIdJd9{#+p{LU6W%V!l~ zfLNnvKjEfrVGVl@aSPk}df=O= zAjpWojwgf|r0=%!KdZ#{Lhi!+-D_L)oG{~eiCS6T=Ui6n#L%)~@53y^b${`$;Ol%; zPC1g0@SelybNa)nC(EO8Xfp}-V9C=Y6xAJgqiX3?#oI{>Kss7_S?b@ZI0rjR$u*VRm{=V$7 z&w&uMt=ZqtUk4l>GwWCG?)$$2>0E#BiwSreo$K9|Xh_%I?m)n0A>Si9SnqE4c(u^E zhT02i`%C`w+2RD^-jzc6D+W!vNXQdBAsLX=SZ&+4S&%-bocTQzIT+7FZNIU>xKGCh z_^y}xK8-tg7-a)LaOAc>j*l;|YySDC{aAmrCh9y&M)G(6_qR5OIN)UVU%;12)7wQn z-!p5jPP9PZJ^!0Yiw9cg$9UJ5OApjUDG*FB{=LcBkTPtXZv~A9+?9938w}D^5E{J~ z<%8leOVH$!E|}%&yu0F^A8`X@qa7T%vA2+<7k{BwB&i1tzS^C?4_w;SWNVfqo?K zMmARx1xwa|5n%z>{z%jTX>?4HfdN@x0#RAfD=kqhSK2@(NGWgu!NviVPEk44K{fh6 zycYu|E^Jtp`GFCl%6|s5g$H#*_|*>v_0jRi;~!5gU7u77=PB@r)%BfzC1E5Az{r0D-j#F!@fh)RTgFL>Z{(Zh|Vhh!xcj%KDL zMT<&3bNz5xVTrSqipS>)yphNtA7iZ>EfAG{18w+ok)$VFhhaRL>pB{UJ(k}%_DgoG za$(GgS+dv`1z>~hmm*7Rv|iGr8?fUk&yf#J-1U|iZ2shDBaj7vuQHkxgdj~ zGu9G<0LYSIFdgpb9P476=sy@wxfx&jG0~IK+efh5EGoFs*ENzd zItD&DgOBv5b0T#_c2bxBosNDwMrzh|a{0T5fPONYOK#zy^LG~S61ddL!Q>V^(p<_A zaII0!y?@efVbcC#@<4TJ`(kW01ZEdseuPinUU%xOQU1np94$nC{b1r$bm|;@`sM<0 z2fl{^Pkv2ha{XT341M~^RpEMMs%u?-vNL4-F8py~@OfeS^MPehcHnhEHkeE1<3ad~ zZ3ZlrU=^PKhug#he#8{{45-))Op)RSvBI#i;_$#EWTYZY)eI7Z(oCx&7VGrAENWeY$@S~dUoTY4upX5qME>9uW8Ye z^&qsiACgg%9D1y}Rkpef#Ij=-r78rP-KIJ&#-bj^vYXj*c+b)Tlg2vvyes>Xd(*Oy zT!filqPd$o;)I&mqk8ASav+6fpy#q*>Vp4ce*nUY2mMMog{EIur036Rpf3AVn3zh$ z;);9fO7V_H=%L{I{!;Xyro+ZcGQmo)-&8z=R)F6CC%sm<*lI@CGD^{k+T^1B&p}d2 znas!4lta}xqt!I_J_J9hq|ko6puoP5)#5=7n9f!INv*=BUeek)TW#%8*R?9YwLH6j ze<{{D{%CV86szxQRUNK1HZ2=Qt)&sH<9%e>3hOi#>9{i_HdCy%PzY3PlC>d>wnJ?6 z43^er%XB@a*H4n-{0eM{mF#uf82&7jX$7w%*VReU#br=u-CZAm$f^vL9D&%J*~}09 zvoU5jGCrtVUIaUExKZ)A9)P~NlB)OFtBXvhH~&+7p-5@bY;%cS2l(sH<_^ZzN}1kV zk?w|>T7PQPpcB`mx^7DaH0(b~;zR z{>7l~rJ2ap;9?ns!SQgwHxY6sQ?upwj3FY4OFC*iWT_pFNv@Rq3AtQn# zBcd-O;^J-6<~_Qc7&6E~a)AEmPyI>XKuULGsxadXmfdfz6$poEOmDu=aRtqAw8LGy zg`?lUP9V=rxX(vvL?{nQBfbxUXnf|nFGOh?`OAbMZU6Dim^Vj;Z)#s+%VfiwRvvms z;L8X@e^+?vKn@Tg@^m0tY_k4oEC9bR!Ewk(2qynh+sBhmSZyjJZp4mhDqnoa@pPc$ zPNG2RCIr$$cnj0X}A6lzh{B$See=@O$G|>7wax6aHr8xEh9P8=t5xg9_ zJsqp+n?HMi9?On~%nt zPmG5y*uG?^!tB@|FMJR$*TVATso_V47?QSZfD4o+i|VK2_Lnb@M@uo6`y6wt?&dSi zmq&4k8{Owcgs1W+cH3K46M9xLgjcU57dc{A*N94oLuNo;-5TYl3!j_c1O>j!|{qy5=vx4m)L^^1P`>y_fWy5sGD1H+QTSD0f^ z88}eCbQAHWF6`|2%L>c_n_KS&Nnr{yd>1PI2KBciES6OOv6X!KMLlM#A2PJvx0H&c ziQIBKgMQ0K?u2&i^djUmq36^Md6MTlkhc>r1lDhP>J_w`&r=;m$?p)p+n6xTl$O;SYb{uL)t(xW|BXjdXV*L%RyP zau!v15QB2lw{^vedQd*TosGK!LO#q7JqQKd%e5THKfA`mJZf_e=rnKn_`9kcKdy

    RVu4pMp|dnY4(S zVR@i*ZvCv}G1zITxe2{3esX8LH>i1loPDxBdU{^6$4hc?jPG|ke!j2R3Ud*Xz=v+o zeEx8M4(4lRSHWlB{Jr0!@!<)H2Q?#s z7uxdpt>gCxtAXcyvE_4ED@KwNJk7_x=*P4~odyqF;%Up!ajf}GXxVcJw`bm{$EW`E z`(KBIIwD7g>A0z3g_&hP;1;f6s5Qqt)K@KXYYZu+<58{V3V+B~ zcpCgym;c++*XMPyIw-V1C=}{}$Ieb*05ldRdb;9nU&K2l;Z2Lf?m)~tJ%G=>Qn^Gr zb*S;x=)WedM!oIn9mTgvYY?ToG($A?=ZnV)w|}21UVgw8bufb_Ij&Ip_qR#=K(kP) zT%ufM{rGLtDv>!~o;}j7)EW=}-zM!wtMmVB()I*Fp#f}PnD&4JHmg7GmlN_dB24I- z%INEphD{7vol{Dk_PYZKg`&v0@7c~4$~6iqy&9-X1WnU=%IE;v#qGah7dtgGP$Ld`fXqj*3F>O3V$ z8c*^hDO#AtFgc!A@)RX$Zi>|ZnzVTC>6j6^k(#9GK%*ee97#eqYQ<=9Ia3rdE*w`u zpQ7I1WZ7I->A8ZSUoViqL^0dQ^8#VD4bwt#y{YpfY1^p_VtL-E^;Vh|DTEE8yl9F| zk}_5^J}S9UOc|@G5+qp1tW2`Ya+(Wrxj#>)6GTzDsH>XRXfX=g&f4i}{>P++UB|$) zwREOuitQ3R1^H-9q-mT@lB6^rcFjBz%&k79EF)^O$SmK@Cm+Di@tmWTAIdwQuKW)v zTh%|t%h>g}=EK@%DC(@B;0@8Asd>UTJSc@CC=U^F|Un zKaI2PGIyiR$sGgXUGo+v7UBIx6@ywj5Z(Z#0}p<+k@CKz=mjsm{s^)m);4&XX&MPv zc@bWMc-nZD*zMR!iAKfeDgO0gXatlqXmGZ9$dQuhWb%%JQo5vsZd8Lm@9N_HKgcHR z-Rb>*h@jc-YW434xNhKjVfZ4#~9+rv|+$jb+z-xV<{V-4cd7KyD z;qs5NF}3>o)at_RHAt-yAY&#+d3B10Q3Xu!o-}f0j_O5`ht8i-@KBY{qo_UP z^J5$_C5K9}<=+&zZs0D9m#ZcfHD?{MMw*{CA7XLK6dUtFvm`auhBdA7 zLQtv>$0(~y+0mJ5a4e51H`k|$ElgfS2@DM()ap>+n*3Z(F!6P%Wx6;uQmI(`b0`%n z!E9z~5}h|b*WBFP#SmgEt|rN!;+y|?=utlwKNY23TkN)Fo!p@<*SJI^w5L+3{iwaF z?9trX1#oYu(CdHsM!@=MHX`6O0YMtXdyC~x@j9Ffv@Kl%X4RCz1F8H~HtmaDjE>C} z+n;wW|3E2r?TawPd)}5B`ozv1<}0?`+FN?B?W&j$;4t6vZER`>8N-_Pwh>%f`_~|Z ze-*jybYXHO11aQByeQm|AsD%|FWi`7*uzI%|3V0!l{-qZR+^N1whr@uIjNp=>}}_8 zb&5aOMnUbdwKcWcGyB)yn!{H#uXyU&Y%-@+fgUipw2d#Y8F>ZBB%lSTHq!8~32JVb zqE7A%D*ChHW%|Ihsp1UBPqO5!9v}X^Z=1%)UrQK_Q7@pxiRIUEHe9Z(hyNS@u^#R!J!#|aQeXnV{YR3EF%gjA$G~vDW81#e z+}$*u@;gKCzI{0tv8fcqr;!w^urUe}sa)l9M{U1w(Jv5CNyl|=wcozB)Xh;7=SPFC zHLm?T14vkc8+5{4va(Pt*Id6jegTaKx%Qa))Myra={4W6r8d`m{4gf$B7MF7eetbs zKeJsqaj_?PBACPW?ePt`wzQf#2gm?U&@j3KZycPF@ZO|>Eg3tC<`ccZhTufJ@ILMF zx_&pl+th~6!{IWne)y={8_mU)^m^_GzAq=FNZ$i~3HfXV`O}o^l|yj>p1EgG7r_q4 z?SzMlwoxyQ(7!sz<)MtifZhA5WIk>o1N^bbxZT3!t_yR4@wrP%)bCmHDdV6jU>={L ztE}xzU4VWG=?=2`-VbWxwLP~F@bsS3brUAwvnCO);V^`MW*EimI7uTeyZU(*I{6L) zeA;^M<~?4#wtv|f_J5g8Cfth*$dRczb1!+%>m>5xlYp@C!p8fM8(QJJ>ezafk<@O# zLG+uIVf@&2czgKTZw5H&lUBG>O~?`|<>B$XLk4d=wf*bfE@*Jv4kmnAq~L$)M>5?X zMt-dfe`kgz@H!UQ=1tA*R@j#v2(~16U#^*Y>fQ3Y9#{YP0s`HYk^n{7uXQWj8Nc5~ zCqaTzJ$ej$jPyTOiJq7xzfdAWZ;8@C@*wSZOy!cAeoakWs%F6N+!;aD^~PFQ1%c6G zflKGXnHvPBgC^AIFRKFwvN8{LqlZQr!jo6Vh($OQq zANq?vs7OJcCyYa6k(jOof{7ZpE0($ovO$Q8n13ZTf~!1p-A3XzN4~FVdi$3sF5yFqh{T^1UOD1eZtaU^PnnyPwmAR#LxDU>-SX9t!XE>a1H4u$ zfzm$zXvAPCkd!gZI5dXzIfHb!jFcI3e?>9uZtxF*yQ(3D36B>pLy!>zu2J{{3E)cx z?#Y!sVmNdxxjLT0n3cZ8M<>KSkRlW&KEbwut&mGWYuq^l)3q%M?0E=?PSGl^Wrci_MsCO{r?u6Qux`IpVyl#(*#XLVjmU6#?W zgOrgxh-M?HBNb^v3T5%g`$iCku-y`Fgz3Tz*0oqUL@fEeLU~FOlb%8W@(sryMJdol zCKyEslto%OW+AGmN!(^7d0K2o7;^SHe8vZA`V_dAg^O;au_REMs1hVwgCv*`N=X#7 ze~XL=&0Q1Z)iTpn+7C@amU!1DLBHh=<3q6=82w^A{wXb&heIPrpq>HvksUdyQ5czV z4y85X@Ckjf1xcoO+>%6NwrLKuo$@&JldRbq8mzH|Imep0e7FVV(9tIZ6C|NkTCrqN zu`}S^YJX^+H5*lWL!U&bUSkr-j)qzFQ@oMlBMBEASkdxGc zkh#RCyF|BiQx|qk$P|)=XCJ3c-j>va!t7Wtj0$-~nWQ(lCvQdz#4=ba!$nHcYbg{Q z@w?S)(W$=J?~dw$OV&+)(ak?Rz@aMd7cN=VVG~ zC7I1q8+p&@z*7E#I{s`v-oMNTbj^3oA~A9z+=Kr^w9EsUfW+cz~{ zLpm}w4uX+3Otbzkx;qVFU|AladC4eR1|`j_STx0!X=E{RP|oAnUw1+B!_K@=SF+Hft2fEDNdAqXAkE`LpQiSdS!S`5zH~*{Ey2bVqOX z8>>oc%N6S4=*S4q4H?QZy39pvE$TGU8!?j_^;Kh}feE=g)_;E;HV0A8cvYlA*t8lW zw?SSYWL7}ao|nL=@sU(URhM>HtD5j#M7xuAS8bc&MEIEkyywv?DN>C3ftqV4<8(fR;pE_8dcw#Yjaoi(th;O*Is%2 zsU`>Sr{qh=_*0LYlFapB@k_|7`cKxe$?TGhZCdM zB8fVp%iMZ&5@ASGO|aNwwv5HINntq@gq&PRo?T*>#Na60nPCj@@PV<&ir|uo(2-AI zRQBRVFnLm6)8p46h14JiOS~M_{orLH?${>QNx{gi#U-f!Wm^|a&r%Xaial*e4n|J_ z<)Vrq%1-kwAhJf*nv|u*W z0QtFv27kYTpN`; zk~{=&!8AYt-@Z*&BPX#4Qv@SR?E|vRHErW9qbw7uDI*1VKX@?9$=y9I_`@l)>!&6& ztcXP)xNkG&~-=fzPGE zv^&%#7~nvdDc$+$j`bYWXz*K70uxI$zUW% zfu&F~hs%)n%1|s|+d+CikEaMbJ$LdqVr%)rdLT^mr~YiL`fKAkvZh~6Bbe`GKmxgz z;JpV|@Y$o1B_lU8R^VK)7T5KJD*;{n7d02wa;bsyxjwkpmh)voM|9#d_bNS@yk&^k zN&{!5R2UhUi-8c}qmOl>-yf={dSeLGhfA11BAV7Wdt`$-H zhIYAvlWl;lVA1vYKw&06u;hD>+M0fWJdY?S5n4xp!0{8tK~LS!_e*h~(1+1D9p1!| zwy?Z*ofSJn!$y4~w^k_FHVfa{Uoa$^kE%Y>Ng80?4exvfU~t(@VI_?nHLWJ#ElG6u zVH$1CIKI1ko?+B{W&Z}7=56x@`LsW-41GHW4L*`AJ7iz^-y z%sczMNSur#r*nCWW?U%2 z&NkBtga4Sc=3|AyMk3+=ze$UN6!L$Vv`J<%|21j3lg;I_IKNHWwq%R{ZPHpQ6-Xpf zKAr}Do3sjl#oe^aPzC;D(jH1Q0b`NMzZ%1eXj5&q8u-nBD0QUS>3o074yE$`2I$DC zBjBpEFPHSld_j_;^QAlX$~e4GZnXtF?GsQFNTl&)u$Tyq}Kh%%cZra2e;FdmqRE3 z$Yw#rm)(9oN=6rsMdamfehI<-Tm4^-pU-na$MA1~Tz|j!=iB4ue+K-{K*h4N*w)I@ zeCwWyIGC${4S#HAdZAX0!Fc=&_v35+f%jkWUA8tTmfZ@%C-SXLeE%0dE6OSjVl3Xz z3}P9@C=Gp^w6jB>sKA47hW#H8vd~r-FHT&MQEma)%MiY0Mz=DE+)_M76BSB>SrE{3PeDu3QB^-D#BMhI<7#JyFY^gdoXz zC+nyXOjGn|5OQ=fC1X=^(%2<>lhn8rO>&J4Z7=%$gdF!}W22-Hg4%yf+Qo&{AB(s0 zo1Xjgi+dM*QzODwKkopr2+|J=DcF7svl3YwkL1#kpZ48=s&{1)g$%o;)tHc2^);)q zs--m!gQA2fO%1>DVcS>uhe|CQhUGS$`|lzn{Xq5;4cgc`mM7O$5r z25umTnmd6oK!9hdfC0luxn0Mjx`Lx08-Uh%vZ}QjW*#AZ)1CECl8Bc_m4@l?4H~u9 zW!j_0VJav4%HeOLI4yH)m(n%_StcQD<1oA_7lnv`UFlemJ1R;C0Q z0+BBrf$_W#AW{O^CkrlSpO2SFQQ6mub}gTS8x7+N&-b%65igIc4%?sB$?*bT6Y)xT zy2n7DbqSio;%?V-D>u4C?EP=Daup9bT@V705UA(814e=^#E26d)E=es!bDvlb7hHh(fvcBfLI#*LgU3`)~@f<=qXD69kk1_yN^J4zmB_1KZG3b|pz> za6HJNZwJKzs{kQK!hqP7^eqTmj7B~&s*+}eAJ#d>WCuQ!RyGIDz>?$7D3i`h#cn_3 zz`w6oNNnKzUl-4l{se3?Q8m#~WTbsc@~c_#7h}?;9PE+7)x?BQw(mql5SH$(36bUl zFq{nN6l3dHhhSHWkKLahjBS42Hk*ZyAUF28w6dRo+IP1SvYs5-GfMNG-*cw|)E$5N$@LTG4jlgtuj zFdQkUfD*P55YZ(Wjk`gfhWy;q>K%6 zw#kUJrUXDr{zEKB8~2Pz6@XkB?bx9GVJwen><^#Nu~_m6`M{>K%GHBq!x4^hVjP=c zDt!WG!=fbYWpJWEM?UkbM~tyzeeS&vrJz)cTt^{*e)vz0I`W(N1&OsL*}j=Mkd!th zR?Ssz$a`MgZFx3czR8Td=}fJzyj0<6G)&NkT>a`>t(j^>rLMGE{mQ7VY-BFAEiL}6 z-kZ-gF7hrB(GY?jK@G1*E%Q1Uo$H1wm;UJ%IhI7LhQeE12}rAp4V?{=#U*AzEKS#H z%kOwOMq-##jo~Ik)a~z6=V)Eb)JiA-p)~;A+QkPK4*0;XX z7JX`>q^hVYgT%udho@)>wK8_ttsvc<`rZB5h2S)8teYZCpPM#VQt;6T95lWuz|IRb z*KNqcxS|}*3jAJ+L9%KB^n%waps9Onu;%BZH~apIxei}8F+hn=A7Jmj&TjSA&8vIp zSnJ_RBLk zXvQAma%Dy|;akRGEE(b-f{BAGGf7tU6w$}5>_P<-EvjVYB^1BQ5|}sTo?fj}Y<5vC zlr^gwaSPBIDpr#mJ?uhZr!k}~Oc&|vGE|Zo5yMe1Ua7U9g zYtUX0o8hz^$J#M9b2Wh9Ekqe%YoW0{3j0n!e$rM4;n_5`h4PLFY5co_5q#y4!{a?H z`>JH2ihEd`qZC1R#{4~l$Zo+Z*lq*YIx9hM`Di5sO8oo=m5%+AV#0nn+tE2UYZn14 ztDWQuOuLPD^_KFn(?s|BCxdpEcs6Oq=O^_)RM{Oym=bGv{`6i?VgDT4X}HPi#}{j5KzeG+pHq^U*ZIGMRT(brM?9Tv^%a%( z6JzT9{JHp*W$3Px@P679j8eOX{YIPZZKtsDZ|l2+C1u-fz%v-PXq|1nH7_{G9ldAo zm61-8IuUDgbEI5bQa$YE7QYQAkB@yDHV^9c>|W0rPxprT=a&yZ^FW8?9VB6Q8}_$| zMkzic%E^}yk(|e>>G*@&ar?0>IBec+WR%l>uVAk&H+ejtm2Os<^*{bhWg33_dbz%b z#m`rys4wQC zP3bK>@rUwW{-&O4zsZQMuZAaoajAoK_~;K!#83E}AECmZ5h0&zH9}hov3m{^M@UR> zNbFbFs+5Yr_TgtwdGoL7UwdSy$i}D83CqYg;7T(CK=c~{>{^iZ$&v~B4>mG=TBZ>I zlj?_X5Pn3EXDyW94OAc#bZ`Qg4U;y%xHu!~F(C5r0h35smHunxj7!}bRpHE>-_Og%G( z1GOvJH5q1?3JwTBw3ZXIfAtfw>pA?zNqu}0WF6hm^VjPeY zCy<41Z;@x|(VZ0cZqkWSC`@aaENl76l|pW)G3#fv zXtit6PxsIlB{4Nfv5<`6u91;YXfU5arD^Mqfws4pKSgn7O+GwtC;jX20vWKQL$DJE zuwS8Y4Ej)7`Vl)!to>ndIb*ITW@pRm;tWkO)a3D6>ae<;h_c}Ev%f%w$JA$0Thpe1z_z`?uHhg$mUlkEpNhI28w&N*WDTLv^406}ts zcpczUnSp$u5&CYgs~s~p0S3Uxq*2DyMdX=g1Hf!`_Ic#_XdlK4WUTE);q0l6vk%R%b|XdUVryS7)AB@i%L7UYZ*g z-Z-}V1me4zVM%-V%>h0})SqS6KM@ve^y%qxEbb1H$4^uWSXl1|RHzl_{0zgvJ{t^2 z=D&W_Qn{*7W+VvyJQI{!Fl>aQ1I8H%Da3G4xex=5giZEE?t?fj`Z(X#BrbxpmRSIdAD(8aU}xZG9m`%0%TB!DY-wriYpBJ$I8@E{M=mCQ8ttlY1v314g~%j9&*s)|r<09Z9`Q&pam zhaoOjPizd5ayGVqkP0@FOMnnGs0U>?DHS_6aYa=r0Sr}~I_;cBIhzMLsIcZn2etc2 z8(lXV17&7#batyI1qXI*;PXE1nCrZIsz#Qo6(zE?orpA9i9lP4vB|7!?|$!GjrMs(A3Dsu`u4z_b!CvTdU)1tKdu_=3zLhW0wUk(mh{ zZJCkUgZ#lF;M7gG##HsR1~YU~H9`&SIUe|n%1}<&zz9b2de#sLQw4*=OwFWvr%8tt zlkOBl0PaYG#+{jkL$xQ>1d8m$`e`CTv8Je1Z+2qg?1=qT;UWS^+EBaOr{u%tEm6g=hbjSrG{W|uI>_g z%qv!k6z=dfmFyb-5ZMAL15i=e!N-Zia=~l4|duVG1MV0kdS$6)zL!4laS^ zIc?$Dm+QOjQ=p|!m&#S>!v>aFZEQ~)9!S9IXvIPH};^TAdqwt&N zfl7#QiOyTZcY2v&4y*Y}!@ZS*>f#9p%!Sc3+}(58pP3@yvBl|S*%n09j_fy$wi!Jv zwx3VxZ%Zr}U=5Oo%QK_)Ex~J?zg-=_I6Ez4s}C!eQS9&F(R@^4cw!0GsU(h9VKkFNG`%r+dv<- zNEvZgl;ucf?5M#70eEmOa9Uye(C|Z*=(;oKXf6Q^b|f1tRIm7$YgGm$sMy6;+tqZ@ z&0@8S%c~>oXdTxOyo!)}Y!2L&K${jnq&&SJujCSF;P=5Y0WArB#|eunz7$x{&{0Iq z^r^wp#w6UWmQVb&ZLE>4);Mm-;rYp3m;&{zDPpgYQrv)TuDr3JL@&!k59n9`sacIs#H>;b{PrWC}~_+o!=}12=va@fSV~={fWGX3tIim zDr4;|`Wj~g#0U@V%z#MZnAG%Zr3_18S)rg)&K)BJLpjb7~`eNzUb zJoFM-jmzLEEzgZWil*H-A>xA+u`QmAprqu&P~ zd52PMH$OVCK{keDE-6>>a`s<)V2X$LRapg=dLx6zEl8{4@ke>ZM!Dx`DyjPa@{I*F zuucut6dEprSqSy%h?I&%&A2@J#G+Acb?lYd|>@uOrd_#y#&AG)q<9F zDM@n%fqGS7`kPStQ4zB{^Y5sfrCqN-2mNlBFMsYAMWD8+<2GIHLAcK*2Dx*0?_-?r zOHmW69Jev5>`un)PAVL3`VOx%$D{^b|N1Ge-Q})NHtqDK<+|nPUVqHUYcE5Xd7QmP zz`q*!v=ul^5N=%7xdl3Ue*@oA>c@S?>UTyn3~->Rf#Re1m9uKrjR!pMI*IkCAKaqq zdE7luSrU9c?RcMC)$iWmcP?hVVz$2ug%*+3CvWD5$ZfmuBDkOl&zxkw`SGvp4{bKn z{RR?IAu5qA?gQXx^42K-s)67zAn~N5YvWkz-pTljK9`+kmc!WZp||6~>_}E=ds;O> ziP+#gbn64z@01MXo+|vwB8W-i8hXESe$iy?;k%}IhPGry{30W2a;M&CC>2UNl z^u)oQXb*U;8MARy_3vk`fMNYhqcz8Q088t1YBwT#i`)C;|7p_pg~H?U_(C)1iv~IX z^zJMsNJRqvYtq*57e)TZq+N9kA4{eGuSv^#B%Q)0qs@lNQu0qWW8>uI|1oK^c>Mlj z(&n;PXm>@iS1eWOc6fina@dLzn~rDxjOM6XYqDLh|AgYa`j=>oqCRk{P#~1y`~LO` zhi$&u8v^IkRl#a8#2Hotd9}_}Z`v2ZI>+G2TxTBto65)ig^O)xnuBq7b0V>1y6oGe z^+(`swp}f>S?`YJZMoW{+I;&$;CsJFtB3P~G0oLhtx)Vac0<`1p!0(-wVt=EpR*&3qiDB|jiLeF&;@p& zQ)%yP ztV$BP2xA&$&FZ0M`6~>W2UYJ@-`hM%L84`)ztvCki&5^ttsAEJ&ogW0+{`L3g_pbECjZTM4oo9*Z_VKwrOLv(-Z9tr6Viv1{FqRInJ-SBK;#delj!CjC9m?Jeq(RI;e0#${h`(@3} zi|PT9u1neyR1FhsHC8SGT*n_sQoB3{4YE3943C~scbQvjI&Pi2!-^b!yYt=(tL|yk z1_+)zkE3#)yTNXHH_L;em)k24r|>A#utfyPySDQLNn$Z7o{fiybO=eC2Z?1KrzWKB zK&{B2nkjGFoPUTu4iN?wp1MOlColVEyuQeXL4$~m_2PR~SwlTkA>1eVE?j1(Q`d@= zXPHiG-j7QnZoW@zNNl|2P5o{i1w72)uOdnBUvp1FG68k7*$znFn~CCO2lvx>w4K{J z`qKeGi83U?em5k!?RSY6X%7CoOLtLhuhZ=qPZ-gX#pb3FCz#0|sfKf}JL&~=hV-V_uS+kgCH0M4A9S?)b(_rRc)WIN% z3WS>xAqkJjKN>2rTq&Fpj^aYR1_4WQ4}qaUWaz*puFr;(iehfwx3&xN5H-sai54xD zKF9y44K(Tz$YTz&MuBiKCsaeC9jkZ7Jc_D`0eT{v3YEJmE|4Ht9E~2gIK}qCEpCJ( zlAi7a$w<}-gYXiG7lHS?lVmX=nLNN7(O9|Oi7_>QyQ3)qcgR#OiI2kZ<6J8BhD64R zBswdk+B&I9ibZfU6GRdib2*Ve4Gkm4_!BVQm_~^hay!X{4l*}MkXm1Uw=E)qvfHeP~ z_cZ5BJjs%fc4wq0bqV|YX~clalw}&Nsbmbw7KB1kTHtI5tyZF!ak81bm@My+{H6r?|E=}Aedo@NqNrO7;MNT@f{ur_O{Wc>memt_(4mQ^nFGGm`6fTeYf65K`5x24*iQ-RDFHVo{jxPpp*n z6kjiEt+Spbt*<0kPkT2m9$}27m?hI36(d&){t~l(O|4j56;Cl$6|0TqYDwv8SaLGQ zlZe$Vdrk|Im{xYUD=MvV9irKp9W1s>T4+xCy2rgxiGUiwbSt2rr_ zez<#C(Q3CQH>B8NK^e!9QP;On5Fy-bShhi!Y+4U6fn z;T5lE5X@HvVC+i5w*0 zg5KPGfr#U2^VYG77IR^={Sj_^d*J_S_x83qZqF^0+|&ka zo#%>egS#6_@cz!S%L-4-jPc$r$~SI9Ibo79Ix_90<9i8?@}WpPcC75C1w-B#EJHlj zD-ZRvk!_)ilQrY1Zg91b1>qp3*f1pz$%RvnbfMIoaC~(632FaM@`tB{*h|+B!1v5? z!}v(Wi1FdZ8#VNxTS@4jE{vW#a`dFDz3NCy;f+?s_J^u_=7^4agU;TOyz2EiD$YzL z?OmoNTbb;@=Gc!z17>^U-f+ABWzwwhh;gYPcoiXG0TjrZ|U|5EWCU#^&`dK!2z- zUZ`ptql|-iGkPdl&q#3FNE)=WCJeWY;use$sEzK(5LO6PIdp!pLyVJXjF#kJ=ZKE{ zaee-fee4)%_}Cbzl5h+eP4UApR)i2zXgUyCVUhxY5mxiBjh$E*9jQwod4pTVE+naML1Kl9n38FBlUac# zE}4`MC6NR%lZ9wMO&Jla_z@M?e*Ks|oX7u_n^$>XxhEPzC&*YRLWzORb&@9Mj7KSC zRGC>b@^;(emN2O_1`(AEXp?hEXE%p+WSKFaxN}lB5lx^4WMBt&V3=f}1x>IJMxX_U zNd}BL5RYjGl3Drk4<* z32>Q&u}KkpsTl}SHj5#2wpkh)sgq&>jvFRy5YYr=APKAR3(GkRs~`!BsSsKq3Cn4j z1VIMNiJjR=osuaKgqfVPu$<1Rm6-|_5B#7Bvl$%U z7oScUlfCFra(6%ZX%aEGkH8p=#3}!n2vMHQxeDOPoS}&jWWb=7c>@Ar1a_dHtAL>x ziVWwe1=gvYztEfvItz9XoeX-O>8YOUc{=TxhVL0)04kIJFrW0v2EKuxFe;9@=sSAB zoAm;t3+Rj9_>DYSRK-~k$7!CRsRe~Ooxkv$589+oik{thoxcE@gt?@dfDY@h2?-;e zvoH%+TA1Kjod+SE*mZ7%Bc`AnwCcQrm>1)NlB}6VXOCbr@@-1@q(9p(We&KW%!zIz)7r(L}V5*4Cqh_nUDrY zYN6?R0FJq!i#navdZy{>D)WF2$bbyF01;;@vCX-vW1@$?9Nrg#-a*`g;)S=*?xW2;s-OP8aAVt~=FqoK8CyO$Ivq*Yd| z)@2b+n+sq%o|f9Mk$I_=inLBD36+VVxlj%0Fb|*V59?43!SD>;fDYd949GC8iyE#} zilKJEm{%*bl`^um5pft&vH|zCU@KF+2q|P6kA8`xXuD(0L9;j3wr*QtxG9i23#3&DU4QHu^7u@27wwbf7!&fp9h8w|lvt$+KZ z2SBvRSazTBy@AT2u1UJq#EWi_3BwR6s9Q-J`J-_d67pDWqOrEGmuRv}9m8t71dCbM zik+(31l5rVcU%9aeOtWYIjv-n3X!Y4-mnh)unyHrz0M%L-cSwD8w|N{w2fM|1EIOA z7Q2M8j9tN+*f+Z6TSBoI6zH1?rz;oUQeeSZi<)s_3-Y>j$F=xN5+xjZG8`5=n@Y#& zoXG2(;M$$G0JYwr5gxn2$SIy38o=lyH~is{99B_ zfXL?Rw`J^{a)*$qfW1PC$lQ4e|Dd?P5DX3+!OB|=hwG_c>$yrC_uK(ZS}p z##`~PuXX=;?;6L~Gsj556D=&THw#-4Q6<$es4^SKG;xsfqPklP#Cepc&w8nf%BY0^ z$j{L7Q0zod4%#;lx+3Zd9Kt(7^g$~g@C@B7#nOw}n2p8f z`mB~S*7;o4|8~}`sn#m3!mi=gcQem7*@xzm8NGbJc3m2SEQ4@eJbNuS1O1$pi=<9E z$-h0xRxq)AdjNI-rgm_&cp=5t>kWsy$?*Srqjj10j*+_Cf7 zC@LBUGTJ6gzNPIYY~32EJ!q@FlH=Vor@_b%|%%2{m>{;&_=9L5jq4_>^uVJwRNK-K6l3hG1OQVHMW-HhmMS*JZ4Egg`F z0o!Jq&QTaF>dc1nmgkV8K@$ zwGi$P%T2*XZo!<44hxRB!7{y38!0wUDjWW%weiL%4dO#4;`71Y@>ky_8K9xV;x6Qq zSRQ7>Y6tsKH#@1DoH469dTEtVlhrA#MK<$sE>H znw;0`=h3~bTCK6m>$qEd=+oc~jf-<8G_qmVDz7Z*^r7DNfxg3%5weYLHgV{k?&%mb zxX{s3tnJK#8P|18!_nR z#oiRhUg<7PG=~Yz9l`9LGfxy2|0N_Y^gv$|wiy2}1OG!*Uy+<> z?Y4pKCq&yI1MNI5Ph^LPgWU8^uLDr;De24d;nnq2-*Y|xTv$J~THjaqjo&DLLO%KI z>zDLOfA$*!$CA$WHgC&FkM}!ljc;G~+WPeXtB-z6pdG$FAL;j;4s8yOe?!o(m(Bn22e7Bb-|PTr@I%jc zmLn)IUU@DKNyAb`WG^>DX(9AJ@obrt*`N6BUHVMs{3Q+$Z+8C-Bv{bkL4*kvE@arS z-~oscB~GMR(c(pn88vR?*wN!hkRe5Sd~?Z|Ka?p|u2gyH(ny#wH#(#_Q07gXId$&j z3Gq$IODK&QyY!~#QKU&b)@0h$p;D+8U7loFHD#tuZggzr+SThc~cTK8rSb%z<~vCEUDM9-hYW(9&p;&@#BYsB~PZDvn18S zDv7?Vd=oOl&Y?x?bcxbs-_fZ(e`d{8^~kB2Rbtgz*Y<7Pxpi-S-P`x;-NDD+9rjQ5 z%A&uOFK15r`16#BiAHQ)-TIE^*|qm94c#B#?H8|O4`2U&aQD-rQJa@I-aTmc6=Odi zmR0zD{Q1+y=ieWse*LiW&NR;aGw?vbf*MdZ1;KmoL7EVhkiYJrORqooCe#oo^a`9T zD3>sVa76MDybQYfG68T!7KPjJMgLk9PQU>}gz-ikK~iu*y$VE+F%pBcDMuoEJJCBE zMYOI+CNJtxGR*w(Fgzhg-0;ZbQj~E^F3W22OXa%6?XCsE1M^H6cjOT{`Aqt*s4Cw> zbI!@IJZ>`s$D^~!C;y7lH1p!L@Ntg4K#2X8R?oj_nYjqJ-T;H;FE*g<+HCJFIQ*lzFuuCSZ0qJ^|%X7ZLL`YWld5k!>(0MSy*wD^*P#h6?ZOb%k61gw0ecERCC*9 zYgh|G8py^@xqZrAd_}So+F#4lGvDy6?N_EZGMmm-dj}=*+04R4_hGOAmRKZ+%OcJ= zB#WJRW0ByM&6tr0IyTva590V_jrL`5VC^zQSvi4sDj3>rOYXMF`HpkAVsu~j86%#@ zQujG+e>Qp|j}43IAbKycxx}NRX4v55{QEcR)MAz?=^lN1I!G{cmaV?pf_4;Zv=1;l ztfBc$JL*emmIe{=ySkl`i z&YUNP>aO?Z-jA03Fx3OSu6WellyY-SYecomMUT&m_S|=49{22ZpggnWx5t%h(&cT) zMv`3?AM3ph!!yt2*N5xG_bZBi!SeA*$U1hffbP>FCN~C|Eiz;xkn|+L zD7lgf?r=$^1j)=)vdBg*26Uth4K0(hxWia7d#rp}3ZsZeUQX;Y9@>mcjQJB}CR3Tq zL}oDCB|`9ZQhBR%rjrn(m{=APYqlKBLg0eS+5K;A)kGN-Bjqb{>JKtgO3Xx{6Ol#^ zMV|AdXF3n`MInY!jLw{(KVbiP#)I9Cn|`_1Tky#e>{ZO3<+Nj&q`A;g4U;1O9FRm} z*+GaR2%N}E<7+M$%znNSn;h&Y$_Cn&n*8OUED@);GTKW`-myk|eCeJfS`mLT@|_U5 z=w50%p;Kz+p@yU;EAJ;8isEm5Crye|00T|Kv@}sag=zM7hfbZb4%sZNh$(MFau zt40dyUWRJKLn891&>1N(x5w0-I7To~)k_?=G}fwSZ`(niBtA>gTkXw5m+8y4xHL^EspaDoxs*S^-P zT|41yaRR{)Dc2vl4Gwa7o4cz{(YrUIET`BC+u|BGFXQ!AS%q@emO1x!(2Z_jr;A3< zGS9jpW36owi%_ZBhP~g--CpyO$^rY$sS(kxW6>*{(mFE1?fowr;hUY0-mby1BrZ#| zDZc%BL{6eftyL0AmkATNb_QluepAdG*HC1`IlXUY0Q+K`IZwQb#V+V(+|v%rvWjqR z4}?-vVkN4GTsY1vczwHLCi|-l1pV(0RCEC|~lq6yB+|_JVB*ep}5UJh9;~pC}Hk)Z?DfjoP<>(r~ zwPE(JyBA)_cDpkM(UEJ3%Q8NTdpTWx9)dF5*J;;!$WLpIdxv2Tb$eT{=UkVt^S!h- ze&pEp#b)`I{qOB`8Nt(xwzM0BX}|azv?bHdDG`oBV9)g8*{L#_jU#VR7klH|Su-jj z&c=qr`{DnlehZ+OMel?=dnF^sIA?=RbL9-YgU(yHMbeG)&>(r|?jAH%yVLWQOE_1r zD-SM#Ui04aJKRq{a&#q9A&^7l;8cGNyR(k+l;id2C+CTWCB9n3v1dM9A7IA&&2qN4 zrQ>0(h^&wfq}LHo+zS7C%}|Y3fx$f|Rtcz9^B(Yk#hrULcdOz9qjP^~YDd~UJoVIF za-j;|?_ut1;MCp z>R)VnIrrQ55r6cj2j@K1@&4Vh-*De+Z~L02j_eyLwDTpT{N4|L!c1gw2WhW;*zkzC zSfBqA_PNM*zMoyw(0{4)by9pO&B^@P2Y-U0Xz6Fy-;GGpiTkxa|MGG?%rmR+izN2T zDF1^A_;a~00YGxozwPrS@l!ttuS3DZ5y6F;kE}Dnmf*qEz`+NU!SUig{973$ zoiGahqi?6>^x%dC_ z5Xd8tiQ~gQR7As4Lh+NsDrA#7F$svcLEgi}Hn};XdqlB&ICj&$39-Z+Bt@#yL{o&t z85D|fn-?EJ#LA;Zsc1eT1dQc_M1L~0U;GPKv@>4pD_KN6UIY=*FbF?7ykx`(MzlV! zp+j;~kSkl0=?lSQ+_Y&_Mqdgpe z$AwzPIn&3<=p4@2jD+#Wjo3kWyhT*}!E4ep{!=h~YzTtPDt?5ri0nawxD*&V0O=^E zR_jPsV2271=V&wIrvs%)h@R zwzhQ3w*(25P_IlmODnX?uydlkT#$NfF1@vJGoQN4!h|Cz|wM|Sk zP1n57&j?TbG)jh~$^Hbx|8ycb>b}#=P>sM%n0QO?C@l|dM-#k5t1-^Bnb6@{$@oJg z^DNQZNl%WFQSmU)m{86_ltRR_Q3mVIZoI~!%oi3NkRW5wmx)my1)Kn#$soN zNsqkKSj*F+qBSw?Q>EC@C5)ys#Zkmm$u*r6C6!J%Y&Qsn4EFzOy#pXnKb=&Fpi#2) zQ8c|y3Z1TuNL1&PJ(lp!?@Y~9{6I=Q)pL=_O|(%$I48>AtBh|6$5J}|_ zBt=!6+t4yqtqjdntdz_}Iyp}TPB1;Q`wAhP6O50 zkFY^w^-D1YRg>%4s2DNt`XQuvG^X|0iv!qM#8{>w&5l7>Zk^fKWY{MS*L=;{lR(j} zp-8G_N1#>9wS2%C`!b{LSfqVZTCG+599cU&*+`wswEb60wb!u4#DH@ziHlj8omU^N z*_LEhl+4?XLQd-HTfbG+tF6h=Q!W&Q)WgM4N>$o8UDmO^)w~rv$OTr()kj|q*lqpV z^l~Gv?OMd8S9J|pkwva}Gqr3w-HQENKx19)YzxhmO3v+EUzAphd|1&f+o9^Isny+o zTU(+rUj6%>zcAbzeaH_T-jHJ|h#bLsy8J9Y@ur#I;PC=CvD+ zja8Ry3ZLso9ob})D?a2Y&-7%b9n8dmxTRBE+VEdKVlzQM3_TQBaT-9*e@p6eZC8_t_U~z+9 z!Hh@+@r?y0VQ@6z6c%5@Qe4mt-P;qX`eIocPDVM>%p3N{3MLH^_F*1IyfvCF$s!N0 zoyQD5-|$_Q(+bNNX2~Q*T^m-)nqk63-gGj`#$w?!uD>#V z$~-m}jC`*)ZD15$!4ZxOvwY*zqTt14Tqpl((TmdCJ_f%f4pc#nWTg2MSOSTCV25?+ z1yA;5T=0flFa~1KQ&JvynhIQD7_(X?l_=R7nhEgbIgJ=Rtkc3(Ig#(y{Rj>nH4&(#a z=YFQ=RgeTbnB|8!X6;QeA@1S@vnTU~=E#-iX_O=Hq2%GjXs*d-iC713aE5gb24pyC zlMZKeu!kMp2YE(@UkHY3c;~#>hk5^)24|q>Y9NDrCId-Wg?qFbJRi1%NJUNhoNd9%iH_gH`y2gf40_P->w* zfWDUMHqPQi2GV6Fs0+5CNpvu7^lG(jQftj);f#o?bm@7PX>^zed-w;_W@mA}Yn9js zdq`_uMI@GbU?^*v+(dhH<`Y+4hEK_yuGbXO=K+WFYBv zcIUe`=ag87Y6u4V4u;|W?d1k+qb`V~PV4|Dg9A`(qm~FG@M)qpWcvNdEf#Bup71W> zZr1ef0|sv;-ecss>`#r)h?woR_6BrNOnE*4WT*y4+6Vr2hWM@qXE*@6?#-02=>w2) zabD+Di0mCWaDdi==^lsypM{0qfxixDidgOlCuAvB*kQA3IiBPG-5xH@vv~3FX$EoA z9bohRhjl;)Z&(L)Q1N+I?|E1Wbx`LPKLBqyfM7TPnpQ7+kZ1q)2KN?j-`3}$7HE^P z1A3N(flzP)Z-R+%@>&0ogd0e1>P}(w1JWv|t;{~1ESIjmoOCXqG-@{BtF}=bI)Hr` z^>XGZ#TaRS_6C-4^Jnme*_QKaa3_>l2NqXvv|i@`5Ax!kg#teaG8pt(KJvj%^x|HH zUVro$Q@rcOW31NhyxHm?n#@n%bkYNBjs{#2|4Z|p2z!tRGJgh>MsYJD^E_XNdGH2r zo@u}mX_B7lJBR69*Mh`0_Jn}$<_>bi2IycW<|csfS%B<@_F~_Q=nGGFt-f@_s7Fnw zb~>|mZd~|qG;ezl>1pr=Zf^ILR*d#u=W0NQjkoPmC#-$2c$xMF)<*Y5@AIH0a)dx^ zJ~whZXzGMkYM=jZ>Y_gC9uDL%B|R$N5Elj=Xg9Z&gm{MEGKUXs$t4`Lre}IC`E{@d z{l4>Vc7~PqhuQXK{Ei41uZEL80C|82Z$NP0mUqA==9U+Gg6MakW_pCqb(@&#hfY1P zCHkEBc`-wH??5!VFM1r)XeJiKq)!@lKzDDZ=N2z>{pRobE_0T?`Z<6498YU^X6b(@ zh2oC)pl$+3_v?9&YD5q2MR#h&mINTj4!=a?fmh@qzVeL$3OqGsdeYC)LSnwh#G_xK zzV#Rw*K=`x1{qgxbTAH)u5UVLX@3}bWU%quPG^i?hmCI?O)AS3dC zohCa@a@>e=Cd`;LZ{p0Ub0^Q9K7RrYDs(8(qDGGjy>y8o)22=tDn%-Fs?V5KuVS@H zbt~7dUcZ7>YRsRpOK-rUO{;b-+qQ1s!i_6;F5S9Zb>PjbcQ4<*e*XdvjMq)3r-q+K zwX1kBISc zMr!|YY4w0bNe6b=xgGIl6EYT8X?%HA=kCYOpF^js^e}bUm!fmcs(t%Q?B2gq6-(AE z`10n@qff7XJ^QVK-@}g|Khv;()eo0F+kQX){!*tuMOiSvJcEum2ax8>GYeMZ%w_{R zlDH&EZ(87_#ViM4G|_L((Ug^cH{uA_ z8vx$tRDL<;#GQ~d0$Jo-;{9l(l1nn#q?1p2C7+a2N|{MvJsOr6lv{EMmliCJV$W0P zKzLF$t8uoPn!yZ+W;Nby#+hiytTvKmBSAExiXv)ZRTFlcnBqxx^f}W+E`HPCph4LSu?V^FWZHVEM}ZyM;UvAxncl7}cZA<07@S{2erc1+~k0g_me>5MMI2!^7K z)F-3ZPQ@u^X?v^U~WNs`uVYSbgU*R93zJ8mVH3y45P+FV3tp z**d$Tvv9)&ITOsA>mW!GM9pKMQ z`;dKE#wacH^(AfRxr0*w@Y4%2vvl~S7G&5l3-Gy}B)ZAM4_~#(CK;+O=+jRXDd&~; z+_-ks^9LaJ--91Mdzq6Tn5vw2zPR}7^Yrpf?pLW#6Ew5$!0BuGDF9|e1&vsHOcN!r_91v}`$4}$+tROK6CU-YH6 z#0@Qk;wz4ajE5)Sd1!M_ISK6Yw~o-9gi`(!2>>@@gyH34O~L4p0%=m5;1~~h#v`H@ zMy4&4a7TqwJjn$ol|dtI&_+|-A{V>p#psYQjCwgA=dSq0$7vx}%aWBu4zMHY+^Saz zxryrzaJxf!$Zs4ufDw);iBzQG8Q$>5DAdP5m8>x$BLY|So_IzO9`1T(%uyD#_{d9Q zGLxDtiWoad#-~kklSYd{P7v3WxS{eN%!%SnNJ+}wjYo1-S&k^XXuYRlPlJ^dS1o(# z%U^D>lVKzb`o;rH%bBt%JTb-udveQAN|2Yw?4Wo+nL=Iea*zMh+$J}>`8i>d(1hr_ zrZvV$?|f93en=Cee(Js-Ol%2{T#wpLUY7CyWFsq(U{SQjJnh zGuO0nesro#5~=GD>JbSFpED$eHFBZ2nEsg5KoTifc^lT_8JG7M-|-+H5h3e}Qn zDXLLvY1e;2)S6FH>t73N*qg=`a~)lkzYdF|b6&@!Z2|u)Q^o36$HvR0D6A`v2#eXz zg0`HAU79#?S=rEn$CQnPCtLU`l(C{VR7ypmEMrR1*y1*~njEdtt{PF@o+mO3y{vRl zT3epL7PyZx>wVspF3&1Ay3*|+Z}GKQD{^+ab}?f^7312VBv-pnVs3TN${)4PRJ`h4 z@8ha_uj^tdtn78nS{p;z<64%r^Hq{&8EfACpm)Cl9`McFi>lHJmcWlm?{mHjl<+F} zu9uM1Qt?Ykr$#u#8or!?nKoCCZdhKXM5SSjVd4{`7{v!jF^ZMq;upg>#xQ;ZjcaV< z8i&{|tpDWWG13Ab{>ad54*;pZm)F~t`CjbA6c`hVRmaFB>u01gfBDb!^j7cV=fmhE&_pHlx`Mo8{G7J4a;7w?OFb1x z%Ll$alCP=D)uT(>k0+Ww3a2{_7>u;ZMAwd~;Da-wAI^Wwzp;k1n>uvvVN5fk%@~#f6558T_U3w_|M#&reU1(DW zJk105Pk?$8%OpG82X07Qc9}qfJj;pO@MtpZSJEZazs%o92u0Hg!mR z6iu&usMdD*y#EVend?01`?Wb>7EYapD;+I7uMR4I4x6Cs)!i9q3e-8y?x=&Ey-ZIP z&T}4i!%dy)aXZSOvCd$FZyhQd_jO!fw+x1&-qBj@j zNB?@?8z0)d_r>X;c6?X>A85fdwD3<=I^w6iZpKqS^nZmsUnF1Rxr^Q>Y5#ND)}CL@ z*Ei~MUr5(?UH8=Eo~@+c%dq*L`=bA>zB)9){7l-8bmippHEcEeW`lr;M`pJ(q_T#1$*l(Wuf8TbKIzImUXSDq0 zFZ;{!zZ2_UUnvEZ_SG8xC7-$t7Sj3O0(O)B>A=WM8UxY<0EXL5lvJcp5dqqt{~aLe z#T@8KUL>o<#Q@hS7mv_!(gnK2i=knG#Z-4=R%z2}uhQ;ovx72J(~?vWEh0VHkRl z145wL86brLp1KHOe%zB779alwrr#2_p&Qa62ti>N@?hvuA??|Xx?tfP(qUlHRUXtT}6gAEonngAtA`<4>mTVv*Vj}gBp$;bA{ZXJHWzipA3e9wv7_Ofe zuE!;2;wnGfLYV&%LL;I{BRV?dM}mqX(qH496H%<$5zb#6_F*`ZBN}>?G0LGN zg5*qcSoxJKy4J#OJfrW;enq|a>STRuuxF5(T6B~VP| z_f@4EQX;FsWP5B7TmoiX>fcSS8e8JtUjkpPsANzIrAtQO@|jy;N@kbHWf}El=xL8p zAWkav3yXQCiA4pBWnhfmSZUsv0s7!qrblE>W@{#;NSY)5xh2~vS+Y&aOr&6Znb>6x z-7aF~LAqve=7|3=_8w6(p!EF5nAzrSHd$^`q~q;nG5+S;31@XKi9fy~K>FV(hR0!W zCi>u}b3O%cHsw%~+~-+mdcNj0Mx^&G;J;~R&n;(}HK%hr-zkcvdg><^Rc359-z{#% zv3)1!glBGgA{?sbek!OPx?;X@zm(gH>&r5NUda%c!)r-Nb;dFmWm zPDR>LD8CfwONrn;zMP15=!=R^e;ViSv1C`Q-ie~9g_hS1;wOyy=o7-`j2>p}3EI=( z=&GbBkJ%%F=I4((Y2^^-KRzfw0^pG%sg6R0UYh5WK53VZp^ToVI{KiM(x-(ssrqdx zcDbmRvg!ZPfaznV;~vhZ@U>1IF@!Bv()jggoAPOlvg1;&X$Y<#Ly+kYrYN4mU%4UK zp7v>@PEV9(=gtHw1Ewj&fm@k2W1?CdmSrf{ZK$JyD!mBfFt%qBp6LSa;VI3jzGbSW zD(akdYQKDHsM2ab1!D?LqW?hWdssErE(tWj2*v>I&1 zYRdn;dgZC&-nvpGk8~rVMr>w&oV+5S#hNTvz9~L7A;&reyqF8bhU{$89LW;w$=d9B zU@RVnAzm)oN7A_TS2i zCr|#w;s9;b0_V(DYSvn9+1d-%7G}}fow9Q6EIlpEf-UaRtlFAw-9DPJMj_osotQNu zJx+v{d~M9$rw`g~;jYK14r8QZE2UDQLdL|~x~tnAXpS0gq}?D{UwTC4x! zs%$K-%EE33>q@Q@^2qNpFM61+Y3XfKV(M00q341ur)g>PYA^8Ks-!X^oqolTATP9T zZ~4;ds1oK`X{^VYRojN|rR47Q`l9*LucIO^HfkL4qTgE7%=j8&{Q|K4VlKngEc<3- zTQpAm{%-&?FrT6?x~40`GR69OqtEzno;Gj>J8;s@<;KEBT!f26g5=nVUCdOolXudoDWljppcX(BOH66p^! z@nqhw@RF@MD&z1GAC^{N4sqRQvY3o<@w+5(6N9l0)-a&%;}qWn@jVSqFfIT1hH)E< z;26_xHJb4muPPg_v7x$g9=|aMkK`&A@lMn+P$lWU>Tw~%;1efoVN&BC;{>4wasXnn zcpCB~pCBBMQ}ohkC1udII++?9C?$h(2wHL<*I^DvGQU3Z6`yj2hH@)2AmXNP=3=55 zJ1n=R@gOs&E9>$rKW~N2vL^FOq4tO;=khKav;U2$NuT52L=>hvCSG>;!Fqi{A3 zF=iqr1qw6kS#cdn^EcxkHAAr?)1kR7yR_1k^x_h6OA9p52C_It=u7LgyNNSK zKixGaT~6E49WTUuR zURU8yk~LKObz%n@U@!DwhjmTsH4B3+Un_QH50paVt7G4BN=LRzP4=c*c4%+XR*&;p zIkn^QY*}`8G<`PtiuP+`5@WX`A~r1hsW!SKV{4xzZ1Xk_rnUe2W~;U)=4!8&ZcA)$ zBX=;>wa)6|Cu^oz;OeZx`Lpf~VARcX}fxd)v1cS#&Hn*J;0_I`7r|MFoA+^L-Pzb^EhPYwnfmm{YE# zfQNK}L%4^!w?x|D)Xl{$t)PQHc!YEK2jzEQdn$h$FgF*MzP+%9cX*0-(TA6|ETgU< zFNP4FczUaNjj#BGyQiRvl!#Z~06Msh1G#|@FahiMctXbx$av(wYmhVf6n(hm-Eh*G zCy)E>GJbZGW4RPr^hIO$_bvpL8)TASd6tv8gyXoWa^U}$mq+LNxZsxgo16KN|1_Al zT9oszRfsvj!ug)Z`RtOnf@X!4Cn}#4I)k2h1Oxh2h{YR{CK5Zk{04NPOL_%uIahls zhblT9s}fRFVNa--7N=MjAMvDxKHP}daio= zZMxOWxO#2^wXi$;)gC(f+4(OXdru_0#4%fLy6>}d z`@C#Axnz#JPh7iDoV#|bd%dqCv71(KzB{~^yHV(~ zdE0xyiz>c@60jd9n+rv}_e7`XbMXrN!w>v&cQF58D!Mx={Hxox!$bVWdpl{{I+_P& z#T&)NcQZTRhrx4v%6~_tgSf1sy!eUy$oIRilXw!U{LRY?%R_my<8Vx<=CxC9!;=Nh z6MejV`?bn6NX9%;pfM}g>9!Yr)RT(NXSP-@y;OYk5BjRqbN#DOecmGF)nh$X^9zY~ z{n?xAlQ;HE=DJki8~XgK*`xj3E6LHfIE8;?+xz>j+HQ9nG~EM!-G4oEJEY!YyLXa( z%d+-Y2Y%yUC&B-7IvT#Xy;|ab@avVe<7@t~V|JI9F$<>Lxg;CZFaFC9eZ}|+qrl5{vCI4@#DFIZBEuWc=gG~^=^(0(!3;Irki!l={1C+61{@K%;UbhS#1zx= zh#&|LRM4jQR)di`3{|`l#~gLsk;fkYBN0f-Ogzz_^n5&$r;ZA8u{j!XqOeE{AF2<@ zDy_T{%Ph6ra;PA^gbXaPh&=y`%Q7!wk~AlES_wiUFSOCjIOUv^&N}V%@5?;7Dv-z` z)x6VAH0P3%Cn()~lP^FOU6j#A9es2#Jte(r$P*8RbW1_aI?7N&4{{Au2QeL$)KX17 z_0&mKCGfI7FGbZyO-p(XDJT4ZRVNM8zzA;zc1KwyY^qa+a-|a4 zXr-N&+G>vzcG5~CeAU_vm5s{Q`4D=Rrf$tW7u|H#RSR1^wLOsAb@S8oPiEWn^Z;`E zl9%6p{rwkUirUT7ygtbc7(X=YeM-h-H+mM~h$WtwVsi)nlGriDtynuK{aIM5W*-KX z3OWm4j^gyq9_Y>@Hdh6ImcQhhCcL zrk(!IXCMpK804oHs~WJH6%^I#uD$*mY}ld(l20Oq4m(yR?|Or6w$XkY?zrVnYitsM zZtm>4Q)Kd=z75nH@W2HhT&KE6yqma#3CB@TzZZWT^2jAG$Z!EOKGEUHJJeM3&OQGe z?aBo#+tQgqPuQf>RbQQToJ9{1@zU~cojVt4za977{e7Lh*h$M=_wSesp7`R8kCu1w zE-(G~?o4kU`sk&XGkNiR&usSTwcnom?nAG>#8x%-p8WF7Kc8vvftwohjnRJ}{`lob zSN-3X-}d?W_22)W|Na53-#6F8O!oX&Km#5Sfhq!^ki^$MtR)bF5tQHr?X$qiu#b5Z z)Zhj=*umsja5ALBp9e`;LKB{FF(8bL0G*RR6uuCKF_fWCR0tUs$_02c)Zq?!*u#m` z&@1gkDOpKmInpY9oD~)=*-1}+a#xtFiY7}!Kv13%m8mR~D0Ps=ph;4d zv6SU3Z^Ye70ztBUwAAG;c>rxdlE2wAR+17yob2T=iCN71*bZ+=rS+3Zt=z*$ano)az5)aDS;*-m%9vrDXuX5yv^PkY`I zpOpLMI?uz+eEt)l0X={?$7xD|9u%R~ROdLOlu(C0^qjW5WwEaKK!{!xqq-!ht1OyP zkAC!%8;vALNm^1>suP!pH0erNI!TEpb4D$d=}ZCnQhvUYra9Fq8%3JIo&FT4P(&$3 zw<*k^9u=u4v?)W4npCGgb%IMRXg!e{5C9?h1O*BJ2LLP<05Jg728;s$2>$>N9MD0q zpuvL(6DnNDu%SbP!~Xd*_C}z^ixzii+=#KG$Bzd#iWGV2(#Vr2Q>t9a@{O^7|4gzJ z`Ekpgn>cgo+{u$CEPg=wWrG!|r_rN5y-=CC@{+%&nLtXNO0}xht5_du-O6=g5v*Xt ziXBU~tl6_@)2dy|wyoQ@Z|iKzlV#2qt-@kwZ3m#0ku;IgnIZ5<~xUu8E zZ#X@kOu4e<%a|{}S!OpG+|Qt|&I2Q`&NYiV*7aLmWZaW;T6Ey+=dYi=CoXhka#d(p z!EA1z6)I@%iMiN1p6tVCuOEzS!&O16Q_7y|Ugf@yVst>2wL)&P5&sHJzP$PK=*@Rs z&%QmvOm;6-J(;$pOs4qrGky7wqJEE5c+m$^1R@2?K0swtRDlc{wS|5t8Dp0l=~Z}@ zdl+V@gM}P+=;4PThA85QSjk0~MEpF3mtL8*=%QtdN%rE5G}dV2jX3h9m|dHY=;KuW zJRy)9rwMdObNw9h#5G#%^TZ*m`E$rWMd;uHA;Vyqn-0SOl1&}Ifx*uc1Wn1@A=fZM zkSea|U>j@g2nh`tMW{lHK$#5lX`zOI23n9C5luATNcFAs#wBk+=;)&wy#Z59 z|9NCngP7)Ypg#&`>gi2NK^m!q{^;o^dV;3v(5bAp>gubo#{X)SiOHa-VqS#2k>jqE z?f8$3yap@mu*6cfS!Z>~I--*T1ybYzZ}uaD4&Xdt4;c8&#!nIcRH*|awe(idbk_h< zP_?(|P((lfFlWscL$RDiK9g(U+)7 zC5b9AQ!c^eUw!}z_$j8547K3Km_8`6Q&1Jm7Q!eWWb(=^x9sxESJ7&#KPz^!SFyw{ z_7BcH_v~}9grxYCzc8bhjU56NvW$`atm92T_#Cp&A?uWqZ9nhmpbnWjj53NK&=ho= zE13{fggr%A17^MWl#|IVs;rp_)b`TB0y|F>qKZKM3jaiiXGI4t_{k|3o)CObRn#y| z52v(fqZ3D-(j}AL$5c%qXG&D&nJy)&OHU0$;ox8yj`CNer>^?ytXF8_CUyCf;xa4V z{PT-D`UC9ky!Y<=VVv0IPqMAUh0ESg2=}iovz-IAH&6Ft&TOh3Qcf?290J@E;Al}q zlR9Xz4w-N3cFVe|^&^h=*_f+JFWLU1>Lhh)1l35p8jZ5sU&H)_{f< zTu_8zlp}~qY6lr~;D&0wFMjjeTD9=!w}92~j3(<~$`m#c#Yx3sXlV&W8kj)IQ4S`S zo5@GKK*0hyxXQ4G}{LwNZ}plcr3*>fjJ$fMqJLX3Bx0vY=6OrP%~}h=S$-U?GZCRMw`c2nHj}z)f#L z3b3M6&dGdLBh+7I*wGr`>0?cG)(obBx65a zX-ds7Ae_?o4t+?4eqDM8M~Ifb`DLt4M}dl$h8DlJ@PcA}8b}Kc)-I+pDtOz|TJKu; z!mc&pQ)ZVJ+wQ7`yA3fWHQ5=iVz??MU?><4@yYEn1iMct!dv52CbXs!y9J5sY!teo z6Z`l=6V?hv$4g$m_VOfvwWmMayI!W;ky0456oKx06a6xnrHZifAVSOFJEYMe%yn9!KMNSqrIz^7PrmqtFa0+Xy{CO6ra7Be+U;ENQW z_Ms5A(C=s`yNWU6^reOPg-X5ri#x!g6rL>vG8ns3FjLU9k3wxY#kpy&Wcu0ArsZt& zY#9*$`Pw{t13d+uiQq>2Bd8q0T4kA`coEkG>MCnLcubIQ)4ACR5${Dg($^i3TFFa3 zHH4lF%=b#UL1hlcVi~O8Dl<0Csh}@UQE>;G4*RA*RqSXv7gR_MwW!R7w^rQE@s8JU z+LCmPUHXjelH2I2S^xFNR=eu)jvTbbf=Z<h1hBrK44RqK89rMTrHDG}ZnueD3H$nYPH2>01wb|lt zc1X6@5YktG2G}xpHaothJHgk0j$wC#mUjn;5vjCps&ZqneU(nW3> z0(fh6Xk4QZWOz=Srg#Gsf(3MM+LvA@s1k(L9}x0D8{<=K|IRk#puIEtj`CwZ3%b8$kDL|Zna zD_4YeLc00V5LXwVmZr3i}P)oB$qhZ><48c`CEcZY41hbXZ? z2Xr|eAyS!R2HM03rFRF0C_5>F4&ER<-slbP$0?BzX4uFGt7m?UPzvYB2wi3rWCtNh zHiaV;ie3?n_?VA-a*CU&Ug})2Y%s4K@;R^+Q^M5_YXnw6kM1MR0mD0Hz2MCVEBg= zo&PA0w0Cy)co1q=kw6)g7Q&AwvSD{oJFX~@*|u%6D3k|a0z@ECY*k$hiHq4IOKO;W z6G@Ryxj|^Kl_`@;E4YzlVIPgMD9UITAQ_TDmui-G00F{HIbn!FQI~ef57e+AVy6={ zc?anTkN@{5pU9Iv$(3Dsn26~*a{)X4Ff%k$Gq$6Ybw@iXH)x4@0BFTxQaP0dMMTNB zhWG%Mz<8Oda}N2C54sQwi;x5zq<9kpbP&^Tks_NXIFb(ZZ*qAPhMF(p=FsU7X38p#Q0S ztHPYAbDHQ0Kw=q8STPfi!I^vXb{?nF#7FRRUu&Rs`3DU75*Z;WYm?so8jkzKzaw+(3|u3F@;K;`TwzJrNT%@ zillTpsg&9lO&U9^7^T8TrIBH!%YdZ|h(Z`zVqOZSVk)L(TB%c^iw1#R@zR}@c9n9b zssv-F=&1`yuq7HojBEL)ddMigih>@6qdE$tKf#i|37mxrDge4~0&08=X9uw!AZ;A)qR*`=krn5Rmn3~N^!cd@5} zo{OLhD(a#bQYiU$ug|EjBs(f@Ns<>)tj3z3og%Qg8IR6dGQt?G8vlEEACo2-~nY1Kvqi-pG%X$+Bf|rUKwRa$-kV2$2d!#=Jv|jtQ zU@IbM7q%dR2CNw`9?P+;nK1Oqw8==D^(vplYPC4gF#$`rI6<%!17SrfLXj$|WE;4G zJGkZXvxJ)->flO5P_!z_wmj#y3Iwc>y92f zx@BRwrb`|Mv5RTDqUnmXZo9OQE4M0pd3cKxumB63%T0O)zuF5(x9ho$%D2G#w_S_CB0R#AdcGta76`$*cly2t0lTpa zxAppDCd(3g#J|3_zqgCEf(gJG_qQkf!$7>GCLF|7kq`@fnz%YBZTrFy?2NQ)xtD9h z8Jxcq}^}TDkjrxzvcaxl6?m z}24}cJ5Kn6kXAT=F7T_5aMO0-W;p|9ndGc zKq?qHnA=CxfY5ch4+wIInybN9`^+g}$p?6Q7XMw-Hf>=T-N^<4qo2^vgv6E~?P+S9 zuaZ;HoHMm8d6!S&vbn3yb?nZ2`@3Z5lQ&(}R{dJ{9L5EKI197JZ@|&toQI3DjP_K{ z`sT=xQqum4Ao|(XLJ^Zd6*-_=ib+t{b$tLyaMgOf*XESdpqvSlf~^1O5B1Q`Cm7Vi zW7enU#*kvvN8O`!DcE*PPwidCk|L9oiw}*MU4Kz`zDT00eBH z39JnaPhqEM?A08F*kv8k$(+`&yw<%b*>wq%=v*K=9H3GijGkTG#f{gZo!rU|Go&4iQ;@FSPoBY7r2?7h1Eti8dF*1#h zMPS_WJ>Q?b-1dFnuF~9m4BgY+-#{=1cDmZFt&;X+4BO3pw2g1zJ=?eaC~6%@NFCXC z`J+Jk(C%r=!5H84z2WqY-1zp zWD6cl?jw!tUcb=6h6zBtx+_Kk4OIIaPHwtKIe3v6-^$*K9J`= z0Oe8M-!qWn=(*xq?%yu{;*mWmHUEC&2qe-?j1qASq@(m4fPR`|aN@6i?LYtwtgQ)#4it#K-Q3-M zXzk#SUZ@Ann`s`k!L5_|M>ia(GIbf%2-~%~; z>Hsg@tBu;PF5ukG)%K zY~lag=J3t-lwbKm|Mr-VzHuMMbFcJuZxK$9p7gNqA^+@Czw&~g`i1_j2QS+ik>dm% z$qnt$ku#46S?rac`?-Jlncw@QyZNHN^n8B+e4hg&ucCU7^v~V~l~4(OpZd_Rxb_s0I}uHK!ODg9z>Y%AgoAz`Y41LQK1(qJ1kzrm{Fs}H^%&Z%ydBH zNRlN@o!%gTCaF*-nG4z=Rk= z%|He3polgHFY*Ya?k2pdh~h59FhdQ4D~du7KLjyE5l1AkL=#8ME=3jBIrhlxS7o(T zS6_vdr8{R$F;-il!^SVFY0=w+H2wP9Hdd!PwpJQf*dtWw)_UzGsbH3wepn=vK zk7%hO+F5^~Jz6z}mWJ5rjkfjYVzafX8f(cX7x!_?FULIda>wRe^K{o>3GHM4`G_B) zZ+ts$)q_miGareqOy~N%=zDM5eFmB}YDCiPHiaW%4e^MYRve>>L-o8W%9m$8Yc-RH zK6>e=r;hWnsgIQz79=d3U2RdB% zi6k!mBF3f0o>Q7PKmuwkfCofi0u>k)>xpfFqLN2oa&Qv$@CaW{0#x}l=z~hoP5(1K z0@4hS&@ai*E`BG3U+oO$8NnHCVfsr5r~1c{+aT|OM=4+qbr>$K-Oz_W1S0erc(NeA zX&mFo2R%&UgF$uAN#8S%_%^6IUVSEgK^ory)(08))eePUv>o7{c$<9;4i>0Tn(&A> z!{ZeZCXw4=9OYQ59=g$vcf@15hG?=phRGa%5zJkhc)=%nrWF~S;>_6d84x0BFehO{ z9>6%s+ljG|EcD>-gtw&`?%;oYR0$mCI7(8c36!TqWh&jYM|Y{xM1Rp9ubgn8w6sK9Q+RpfR(V|DlE$ z1xL7OriPO<{3JO?QUnW$QkxHjD5?}XQHoZyD&iccMYmHgLjH4|HM)_G-1(j=dWIjs zJk&_)c>pBj)1@yh=03mZ&wpx$8j;8yET}OwGrll2GDN7etf^6kCc&W*MQT!i!cC1f z)u~TC07hp8)##Y#Wi|DTJpE)IX6SOHh3O?DwF(~^iDa01fN5G`D$~8u^q)7CUrtxp zJGw!WX`Q@C8>xztqAJy|fAz^;1v^+(O7%{JT~0aJRz|Fj)d#nf;Qv=e=fQiSG)QG# zf?74ZS!4o^vdx4A80RN6y87;Z5yNXj5u1{}0@k&!t;uR-JKF;q_OP_wO*!ac)tbg^ zG4%QiJtSK}LWvbvC|SZiH@jSzQiHK?jf59PySKl2(6pk!>kg`k+m;mdsIUcZHkry@ z@|G85wzZRa-*S$7n8#kt^lf24Y95igGpr`HERasp2IltnrOvG>T=^Nl(eCt#P;#1T z)!W^MhS$MJU2udYygBr$Xu@7G$3J!p7=7&HlJQ+k4uG4)kv7q|^E?R>#Nb~R8xz3I zylFBA{KdW*qCbU1aF>L7;hD7d!9T|4czHZzB9o}XD=KnU{{Nv5_kP&1gsBl^>svlq ze&(e5f@F)e{NhW-*rjZp@$JMgnMge`Gy>9yUXy$j9|PIVb6j(r<-DCETX@b>*~dOM z{Fkf#2gL6gv2ZuoOJClrkti<7FtyxbEycF`mJEEJ%0jBSE3VvQnq!lEU4=%2kRtoKx@9~ZEu_6TjZKWX0rQDX3r$!*$!t4!3{oht63Z7 zH^vnp&@poTVm?vj$y{+tJsB3l!br~W1ighH- z1f1tm`83VNUh}V)J;FM-j@eN{m=UY{+-(@eB{-poS%);^@R6mjc8zG0$h+z=l{(C* z{`a&Z;qE>lVPzWiaM~!zOt~&&fP2w7F?x&pU=4wo zL?G6XbRX0q5LY0~=~KT3CLY5Z)tCnEtATrOxc}$$jtE2@-jia&Yqs9LB6jiBDh3}M zzA!bL4A=kR^2~ch=8?xfsj9zya$X+unJ)~wgS(h9$X)KDpSuqxF^gcVg8h?_@)~CG z3)rNj7E}*s z_yuq9hcfzzG9rXu5Ck8%0vxozUkC)kAifB6sc6Xqox%hrd?_(7ytu(N&macS0YSM4 zI}Y?hGx5MJ6hq7rL6iZ%d2ug4iMaDq!T7dWxgiQoTaO}iSJVm$A zKvG1<-w4BUWJf(p#k0sfamWX++Ql0&4{3j$94>h zb4=*s ziFIVlxoi`ftVzoIqkPE8o#e|Kp$B|y1J?@#JItju*oLFbhgm3vJnIpJygdL+hQbI2 zIDA2gl)YKdLY7*<2z0_wh!#lm$UG2(8o9M&psY1W%hXIwx?IV}gUi0P*&GAG@7nn_|aZA`#PotQ;^K?%Usm->y&7F*f(TliFXa#)a z&A$AFZO{c8e9B)ChF=HX3hkr1XB7{RhBtXJo1>lkc~KZu)BiQa#{osmZTJOU(8*uGhL5O*V5kQ7n1pAn3;CM_T{-|341|$j zL0izyN5jxz>&`r=!kNLf@bpkERZSQ$Pcd~4QT);`JyA>LRHq=*GF3bGT2mBM!4&+- zO<;v!2!;XePn~3jU*Lw@K!#bszo$&nIGjWAIDkD}g-KY2_7k~B)GS5KgN=lRDa}SJ zG);R$O-UWk5bady@X}0m$!N9Kiy~9XyAc>=LsKPH^t*&jc!gX@g;XGfd#DHSF%M@z z2Y&z|L70SiwaPx71lltRcuj>@U<8pnK0?tcLU};v0?lX%%SrsseIYa~Y*uGYOG>>~ z3Yk`FO~*}r*#C+Zixs83aFYga1y_#!R=FdFJZmqVya!DoWTD6*+MNuCHqcwUsM@|QG?Ifad>K5bV?MGB+nY_?vXxvoaoorC!r2wkw=Fxl zJ0!r^*#FGsSXan~f4GNu*vWbjy7WLO|2+ke1Ywo!(uRl?FWUFU@v=v6+NMcCKXj7Y^^O*Gr^)swXK z-naB$QygEO6TRO3i;YEE^XpuH_*{~$gwfsGkw{snYhL-Cy6COCuQlA#Vb=W($NnAQ zR_WdVjy&)k;cF}4n?pay0^Un-1|-V`pE5;kGTQ)07QVVFZd1kMKq{?_ze-+H+RVmQCjQ(me)fJiDnYQS3gg;@=* zy8qUdnGVV|Z#?2n6yYa67bb3Eu|r`wp0Fr(IP|+*z<5yx{)h**$9fP4S3o};W{k5T zT}2yXVnp44I^zhOUPNhwYv`yfJz|H&t6Z)?66%V&#oM=dxuOLu10zWnLUVRa%Y^=t^c0< zNyyTMbm)eijE8%W=DGD&S;OXR#ws8#K9H`myI z#-5jk>F?F*cGhEo)5%!yX`VLgp7!ZjhzEPfhFdV@7p~@zCOk+aMw9yIfAF$J%w^Kl z7hKD=O6UZ-F=Ak5>93|9hVJT6Gwg1P=$pHdv;OI{KI>M%g-l?CpL}8T^WvrcyHG%< zUIE;Herm5(Bn2G<)68FBmVv@vYy?8=#C|iGZf!CQ>u%HOzbNanhHPDk2LD_b1wtSM zIUt0~USK|^yByfzlZym^g~X1+>wwN>Ax4y`=7%vTOH2mgte$O}c1_qG#qIu~##XqZ z^@MCt25I1h-Npu=W(HiS>_R96K_~<{kb_MqZaz-#lk@Bt^JiTnR*y94zDDUE7@gE6 zZ1C#CD(sV->HgSD%UUF~*oZ+h(o|FIl@@MMNL%}9n)fbT+32KPpCT=0fW zfN%MZ?-3X7;=Y6{xsn&RS_p&%NA}mvvhsWzO>eHfzy1L>CP^DlT>sYgaaY=L9(OR= zPV-n9Wm48Cd9VZkuyX-W1CrQ>SU`XPuyX)NfK!+UX&?d$Pyi*^1%D6;X83ae=z({T z2WdC}LpO zAeri80KH{UX%I&9HwPyLXLFk4b(Ilsi}DA3c!U;M24jGR-5CkyOon6_23+`q3~;Vj zP=s4}g()}yaX5fIhX7(o24eu6dSHP$paqfW0g@O!Mkoc!_ViomgNbt=5ighg;=ywwHsxEVcPU2t}EdO8s^_heCco}w!x`#jb z0zmwSlJJZJUY=w7jP0!Nr%KJbb!uQi`|*m85N zH<37hs(UB{ED(ox&C=C8LB2KmY~cf_ET! z&DaNB2y~hk3GZ14_wI#Z=!L^C@>i&L`4;i{76dsc1VSh}p(pq&Aq7N`e4|J4Vhea< zVvT~)GN@m!FCXF=A9D|Dcyd<#B$Ig5pSG{R|L6b+9RdduENJi`!h{MD9%$(BA;gFh zCsM3v@gl~I8aHz6=+U3Qefz#qQjmzB!+$F8mFdAxrAm3pT9tu7?Ip-`yejlic|abo z2asN-{5K9)tzNwfF%?wEDbuHfnii5%RSs4~pdxYQiYk%Uu3YuxDQosDTC|ZurOg8i zmRq)M=bj}?_iouGKKAnM>z8jEko@?K`O#(>O#e`Zes>vS-t-ZTmLv+`4!3?(O?GaMq@W6EAN3IP&Dm zmrq>i{5f>!%%@W~4in_PKMwr;YX~!*P?-Nff~?0ujZg0TOxgS=Pgep++`D^MnG9E{ zs8L@zh5D4~8dY8Oh9O;jC0197gwhpWZAAi$TxUHPN+@tONS9p~q9q0rIsEk@V8{3~ z*fBpCwhv5eM7AP}GQi+Mbur2~BaJoMcq5KER)$(|J^J_~kUcj%#XBsukjyg47;|iW*=%AbRd`BONPt$o zF-I7E2Fev!s6_JTfm~_$;9L+^$mm=d7TO`CAGRUlV3nA7*nEm{I`NCWT6{6a8EYIW zs;_$dF~}i{EZfE694+Rte@U&1V8FR@c>$1yke^$xCXT5_&qOXBs>3eS^gyN-WS_8v!3c+m| ze4!W#M>=Vxm#RdJiW76{Y0G{4{Wsu&U&P~TBO87=;)(kftKf}04*1HENBMZKHlInJ zcL&hNB}@*HHy%h=qSO#b-f{QPEmTuI=hbz>%hbGKFyciRUUx+bA`0#+)`E$^LP{ie z9oiN(Yr%p^+iowam)w3WJR(01n<%1666?Jw-;`^=J@?&L*|Fl`i$A{N-kX0um6EG3 z9r~1uhmq>4v+m#3axhXaz5k5Z-f!5EKqA&T$TK_%Q6oZU2?aIs0I=jK4{iu+9$zFy zqDr-4AM@G7^)^+p_HnR-9{gZvz(>9jlCXrSVjKuls6x=JuZ0O&Vf*5DiBVjFb#?-T zfMS zc*|gmvIoO4lCg{_6rl;zsKzz!#*A)!BSc&%$AZ97dorXNCu%4l915sjvg5)Wyr77# zK!SgX02{twK^`|Lkst49WFz;XMCdh=iAQ{k6c<&+v^)@tTAbj+mJu;9vS@>KJS8eq z={Lf$v6ZfTrE5^A%KuqzZ;rMU2rd71N2<|Kk9wNd92fz}IVi$wheXg?#8OCLd`@(Y z6b~e$8ObFYuuz*cOWd%ym%u2oQe8|DDOUu8T#~b#=A;!GVX4k_j!%~7e5b{3X-jyP zY?pUrgd*lZuX-t>55^oDz6=RAX1d9lgAo%+9R@JW7@$V5M&UZ%pi zA~DjlqaOX}jMB-@k&;woAU!FlzBW@J0{>AQq5G*y4l1UgHZqe9P0JM{I#DiKYCd0ds$)1B*1;0Cu!BoY;j*gO z#R|!=j`hq}!TMM#jTM>uLd98ailE;4$%$`;>pxxsO}Z{|ifAzy96H&&q*BVFZ6HQs z0P7g2PPVqTHLO(`tJ~e?W~;aTZ5$)3KHw_Jo@M1qA@lX8wW{^9X;tKBf9g}9l6I)3 zEsMd#aMb2KuVEJLD>!A#m~j%fyym59Zh5QT^}^=7zZLHK+-svd9v7L){UJd6btT2#)eBmC`Qp1uX z@^Uso)&${~Uu1A^YmQ$006y+ddiXjPFm{8-;wzhTh z90lVT|7FHsHqjWwV?FVbchtr{_6If1>1DqX+2{+ksGZ#z+X>2l2jX8^!Ddsiz+y{N zrvI*>L0i0All#^O+cmHKqF|+d*HSQHuz1TX?RnGtaX)4@zDerodT$KcD&se1#!;YD zTQ<2g{nP)tB4z0+6tq_^H^j@G=(cFrL%W8QuiJf?8#kD?0RK410eA0wlU$u4FPXn{ zb#ls}HN^Qk>+S@FNKz2=+o28WPhp{li1VE11@6nmKeX;&n@GVb8FRc>uJon0ZbSI@;XAbErul^q3wGKdS7PD*Xj9{ z(jLD$-t*oor$fE(h?BbBXH<1u1%4t~ueR9otZGF5nL9`1ia2aWS22w{?Uui_82^Bv z`OO1i2{ic2(7pMvw+>sj#V$PRQ;$x>`n~mORK1M`KRMVpwT- zJ1E(3T1VpY#y@lrIL~<+&;SWQXuI6o-PZ*pUA9HgG3~RjeU7o-_1-5R;J5!7+0P#K zhi7s!^XxydK==2^Er*KZ%8y8#{rH#9yz)061mTKd3;Mzg;@If{AsVJ3j*MInwxP$Up+*QH z`>0;l0g+fZ*@3);9Tt)y_yHA4;b1&m6J6o`ZK3i70Vt^89Ef2H&OtNGhd*S3L%@Iu zI8_p09~@?)CWch^xuGYz$`2l(96kpG?%Dc{O~1fG2BIG#7=j*9!tb9 zT^1T5=dpqRF=7kKAS4dML=*uGWRMMRA~Gi9a_rzIHsj(TNg9r#bClu{9$cSALNRFI zF(m>b6j~BVVdc@HE#4x}k)SRDfhH(X7&4+G+6x#(jt`wxLMr5cRbjbVAw;U37M^1|f*~9P z0S+)CFmlI6UIsDNqew0#Q!ZmCnj};Phw7>1O1k9wU1cPYLN=OW+0-8_+}uCR;;ltO zt?eYlnWG_6BuKDe5Cj1fxL`Xj5=cm5Q`V(jmWn<`rCzp1C^{QezEJ83WLVH#Esoe% z)TB*@W$~5UgFK{J8d@$&W=@{MW0D(MZea@A%nG_74zy(pHUn=OgE5fDW_l)aCg-QH zVQ4ldtkhd+8U!77#alSnsdeL_$>zgB+*|0uYu=`z^<-L3<~p_@6trbVk_Xior*gKZ zdx8pcI;VWbMqgrBbkb2^X605UUfGOgbvmZ4t<86WCm!Tx3I60-`XUe@B6%3Y8(ac; zz~g&PD1}l9XwGLzTH1XQL_qFmbAg3x-kKh)4ITh!c7_6hLZ(EjC1v_z3$o}X>;Qyf zPKDN}jXKGNV(32Br)_O0E~y@%cm*P0=R;0N&()%dLjPoB>LP-cCs7K9Kg8&af&@q2 zsFhynlH{n4I-`C1=yWC_H`eBWawjCDXo0S1&9R`13W0DA1~9zA4!pr49VeF7shzIj zQ*NoA@~Bk#s15|AT7AWklADpjCS&R(c#3BUQY08IqKl^Ih-iWk#J~;|=UmDxDj$OSgQL1=X0pLW#(7xoKNEpKoXr2&E>CNOSwq|RM>?*JJ;HRR} zucBVobt8b1DB7(}fmDbSF_Gl?!#LjG66hkMQvc?w`eJ6r=(GYsW>%@T_N%|jNPKpy ze1cTC7M?i>D`Vo+TQHGeDAb6&D;D~s2Rf-QLaRSG=nm|_4FCZf%;~>=EXa$P;3Oehf`U2?SYsPLYFn|u7hOE&Z zty7LHuNE1~x}>d<lU^u&pzrR0sk%F$|-La?ct6t=@LiUDz58&P}8Pf%a$d% zO)ky_mF42*cv>yRc5SqNE#PLX)!J(5{x0wy$LXT3-?8n*tS;&uQN+n6<=SnM;-;c< z-rn-95X9xh?k?a?X)^>b_ja#w3@`Ea9pxZz;mvL&(5;HiuB|Pr=2Gu3b}sgUt+h(1 z_tvldo<^RA@8bFm`Rd)l^4$5xZZxSc^66$Tx-Xj!r|!n@{NAqvKX7S)ul|b{xC?G@D|sx9q&kDd9hw1@opD&SF8fVG4{%F>D)0SN3vxUu^w}pj`;Bs12FmyvKgN#8Z%Qv zY%brD}Um2{3RW3XSroC-G)}=@?`!s=`OD+75nlpgKaPqGdFkhVUgr9M`bKugfcrV z+JPf3elmH8@+gaNHplNad;haM&of21aySba<3biyit!jflk1+PqW+}KctSO=X;J>| zJHzuL5iUJ9v_n6HJ>PSMbw)X7az7JV)^eUeC#ViruiqxL71ydiF!V#0v`HJYM0;yK zbHqOX@kIw>Mr+-0ijwOhaS zspPR%bLpuNwM&C_tsyF8YT>+^^;!4wTEj6_!!=)G{JH#6jtn-`#9StqhJ z`|SY)HXK{4=oYqSU;p)CBX$c1m+TcaATx8J#cN+nwn2BULs)hXWAuX3-KEU(mEFK-BnK_4803ZgbItM)}?cX8V`etI{3H*{x*x5?>q zv@Lcs`$M520>gj=dr!6kZv<;wD^EuRDb_cG({pm;w^o&glsI=o!U7^pu7LYC0^ciT z1omK8#Dq7vh|BYXLpYFl6=3rB>kbWX4mjUhtUm;|Wk~ghH^;w?IF5I7iJN$DP{(|u zUe6)I(2$3VTmN$@U+iXpv`B-vWaYS%3-f*RI4IU>#32GH?82Y6f6L{`|MmB?aLl_yE-#IJqxQSD_t*tqh4|H{N?sbpG zDbsn?;W?s9vYsP0pZ_;0oWd^bf;|Ak91wJ%KPh?0cxk|~Wne+l9ieR zq(_1mK>vgg8~{6$vKkM@=0Ylx$B0fpL?n(ohnhRU2l1$<^p%9daYR`sg?)j>IuUh+uP<+oX zIM7#p{SN$=)+xx(a8Qvl=v47L$GWo9sLD_M16n=WcdyVN@r@dN!vUB(OZBF=HrboK z)ulb&2k+VknU#{=D_97hs&)YrA6_XumoFFP`o zBLDu8Ek5UyF4hmdjRM#vUq|3mzQlKUHe>!sYkqunzUz-}j(eY#{L@3zUYVBslV(kuH*x0Fxszv4pFe>H6*`n?QKLtZCRMtWX;Y_9p+=QDmFmqRMUrII zx|RQHSFc~eh7~)OY}Tr0(WX`FlVCGXzW(u(D_3CMivEmA)Vr5&--mDR`Wse~aACuT z5f@&&m~msrk0D2vJehK3%a<`{*1Xy2)v}*KhZgOXb7|9%1N)m>_n*Jk6)*XfJ)3qz zz;_2H*1el|?~kW}2Nyn^cyZ&$ktbKaoHfKDv2z>n!K;tH}EG>w<4;hZir~ zSYS84(Wh5$_`TTOzYJ7RjNB~L&_fYTRMADN zQgcnw7!4B$Cgt>mB~MoKE;T*->@=cF{?zhD7+@GQ&`42DRn=8lZPm>o9~H}09+_-w zj+Zd~#}_+OyNgp#fmI09)VNfy2pLc!wNz6joYmQ9p^aABX`6#J)~%@3uu_@sv=k*? zdoAeKV1XSruwr|IL56kLRSAY7m{l*^dFid!-h1(7%F!b8^^c%iXPTp#mcaiF7q2PF z^%T^T8bnWBb|FUA-DTrNtlx_<&RFA(@7;Ggj^i8HCSL${so-$OO&G?7QL>1)h+$@z zB~mLU4CI?}&ROT3&9oLYo-Y)brjvV3S>*&-PRSp1Njf&>r`w&G=9)bM+Ul#Z&RXmF zd=6`C`~1O)=uHtm8fk)7Vj84}p>A7ZsVS!V>$&N!+wQw5>sl+kPg}+BN$7B?3%|QK zshL~5n8a^M+)#-MNBmv|a2!tJ6`g9Fai$t?_NmBdvu6u6CAB$X+wId~dbeV}S#RC- z*I^Gz&Db%UWtCZe`9+eJR>|EB$^~|#cfWI=1SR2Tu^sncj6WWCWSsx`C75Z7E*tdF z13QUyj85+!=9s4blJ@b*FW>z0(O1hHDo*M``o>jqHLg*OJ@gd=f#?t+ z667L9JmMYSmc+OvCW?LZ;~xPT$W#fTef&#_;sW=-0j|OsqoDsn7s5Eh15hp{bHIh) z8YjF-bODTzqyig3*+x$oj3A$jV~l#m2|TVcVm49TVFVdVS5NcBh)cl1bmZ3%})Nr7!v4=OjQH^RK;~DIm;xGT`Km{D&V5c{o=u<^W%7ew` zlrP{xCjvvxj-E3o%F4(|!5UVvj+Lx0pW-~Yg=$4hdC{Z2z^XiOELQKbk7RIktE<$B4Bk~%&2E;nosA_M zsqhOd{?C`C9iAj0={G8Pq8UP%!!Uy340fm{JA4)GG;R0EHM(yVhV?BQ5j$0KHP*4k zz3N@~Az8{+7LPW88L2!QUFlAjy08PSXklvF+le-tSCr^KPO^?)IKv+304i;@gO1of zQnhS!-&%hg-!%qTN>sHHagA$S$ohjAts&y9VIF2`y%}2H@}@A zMq~-X2>=J!qb#9dffXENArG0ziqb6=aJOP12zHH%eCr%~fed7z!yf)X#{s=j-snxk z9&x$yhpz$GfYz0MEjF`@r5fY#FqXz`*6)pRyipzt7$vJzR*~_XXFczEM50|@Z@GCw zfhBjt<2C4qtE^#UNY5FI{;)dyQDNK>kBVouG$`q-Sia2I&7IzFMLIXxIgi?indS4T zQJrd4D<^WRpu6p~j_8yQ|oo#Jzo7-y{#~PWuP1Xv89}M${J@#6W1AsSd>(i@zBA(E>kC+ z>}5B5Sy{~VmcZQMD2X`5r5<;RVtoHDfw4L#vd(j8hurI7_dC(g9(chI-j-)pJ9b<$ zpqk5_@e`%wJ_cm>tLMGrAm{hU{~q?D6Q1*(_x$;eop4_?-0f|L_*~%Lc-1fY2d!^? zB`UFx(=)svcc*;5eXduLXWs9d|NQTPAAGG<{O~DZ`_pN@dgZ&G`OJs?0V02w15Ez* zAKyBtbIkj{`(F6n_x|_sb#u{^9{THcyIhp7`sS~{`OjAg+Gg)IVKlg{IwGVdi z@1Otur~aQ$FU_D=5r?!xxwkN%{MAn-5$tPKWS!2dLG138dU zRB!y|!tEBX01Yq!O_2Q-@csWDQ2yp`?~p6UzRm&z3>2MU0#puuuA@L3&?+aIO5A$veI6;B_@Blag^8^v#5HS=*aTGbD5l1Nw z8_~BSaTT}F3+t{DZx7m%5c@XD6F(7RihvY#aTj^9F;Y=rP%#y`=@D767=h3gB@Pzz z&IKdO0Xy*)#jY2naT@=r(J6$n3a>Ggh|w6i@fh)t5{r-pJ&qY^@fpt$UaB!2)o~qt zA{$4E02^@|yKx@9aS~rK94&Di>#q#WQTyN}q}VYa1#%!$A{)C24zrOS6*3Z$k@gBg z9Py1D?XMOy&jo&iATcr{rO_Z=%Pmq-9v3nsTk#w3u_7Q+-%_Jwu+E5Y*j(vBcJ0V-|o6n|@=NY5+{iz?lc8yhk;eo_LpatY6= zD|;g>^>Q!Ct{MM)!7l;RP6Tr>n}PPqvhjcs=Trjb*m4-(@-e$HE(2pOwJs>lunBF1 zFEw*B1x~680!kF9A^`I*|1#kOa}F94xLS*w)N<{D(YK@$GG)^aCDSLdvc~q&A5?NH zOYKxR^EZJr&t`7sKyx7A&tL|oR|3;cP!sOZ64SWlw_* zRK{~a2~@03ZPY{}G(aYl{LW7YIPMP4*cWHba>qDF6YOKmhqClnZ9Vm&wKBs6R6~_LO7&Tx z)oT9^6jdXR+*Wl!TGdrylv=M8yjImrD*;lEAy##>M;oTLH|@$uazHwAzQT-Rs)tnuQXg&q7B-BQY#@+4^}SDRaezj zQYlqUh4o$CGF~fz2V!7Y=oL`z)mitoWKA|&fWS~AmItquU`5OCzGpl&^2A)@LUcXe)M7i#Aw~mKBjPdk)|d?skqW!fF4X z_D-kvZvnSVxVBrbR1?^MOI3Do7u0L#0&HtyY{@nzZua?fb~t+$=G699RT903wq55| zQ)5s1%#9!@LT~AaZ~L|*0(W&;w?`BgP#HH+3Drxtc5oTD5+e5|AlC<6Vs{}oCCrvm z(bo7fmr)0#ZFRF^D}h~&_H$b=s>tv?MK*Owwso!ddjI2f1D0{Kc6Ql7LTmS5BkmY> z7bnU$C4AR+dv|PuH(b${XDK#2kk=j~6>i%#V>>k5=8Nj2cY3K8U$HlU1^7B3w1Cm` zfDt%>b@WRact_=8LJwD4UDZo>Rz_v^7!DwPb@zAESA$oggMSw#CO2o__jv!~cP?~w zS2@>Anb%$266g50e^2*+EoOji_=bx^f^~R;Q)FNxc!yne27ni5AGU%CBs3?Yft9w1=g7=13_~@9(bx8z2X} zv{~1%Q9GScLa5i;B`Eqz%~T~W+M_!dgV*j0qzB})X|UV$BI#l7Ee zP~L&S+-)Mx)BV-OR43eBw&C56tsUSCwkPY|DDGXVynWw;-QO|3|Kz%IHfJFfSUaAC zhd1UDp5>{%;a~n`d-4scg67Ly-*0}Vb-wBc?^PYV=P9FuVNb__RgZ6$iXZkQB6a0k z-glLL=`p$K*8=JdM(U@Yw5@*bjgCv>1epH|TkE$Tiec{`V2{U{xrmXz($ik;ZB)pO z!RZ~t?VC34{g&<_pWwDMapwZ>8`?BPx$9xCnT2|k8}_mb-|$a08I7Sb-T+HT{M*4j z@>yTowp2!a_`xwB&NYAV(^segpYQoQl*iTfeL(aH74bFW^zps%9iQr3Kl$_QMuQt$ z&pC)^pPmyNTuE8;bKiFvTP~0u-6_3^fuHH+r1VXL_*4JP9bfs;U&w5<`G<30)mZQM zUa6;l^D|$*uipoxd&>#lN4wv50Ro7?fdmU0Jcux%!i5Qe`Qzu$-=zZ-D_XpWF{8$f z96NeE@aB@Sh$Ksv%#_KEj+HE1x_ti$Gp5X$G;7-Yh%=|oojiN`{0TIu(4j<&8a;|M zsnVrPn>u|8HLBF9RI6IOiZ!d&tz5fiG^mN6*s)~GniZ>w4MTxmgZg+2H?G{dbm>;A zbnIBAHg)^n^|#l@v9n|E&aL$DY$dugW~_Y-IdWu&5GA%v8git`&HhlTvy-#&j55whV~sZ6h+~dA);N%V8vaPuZv`4i+*HS0s9;hKF6l#ph#5v#8;O;5 zAz@W&SP6()YRSe};Nf^;iYKMyVwq;Lw_}=WuE}PbZoUa;oN})AnDdlumTKG?+KOO+wmXd1MWo0Dp7^avJ4MXOco_^ZWoT83OYN@84 zifXE=s>X($ckK>Nq6f{g#H?rp&L&5pLDXu3SdS2L^^4+3ROx{ zcx`5?DW{)-imjQeZp;5|x88mWZn)y+2ZTi$9y=?oNm7-ou8Ot66R`4Dw`;m*p(|@| z%A)0LzhH?)(i@^uE2g#C9_-?{3NOrX!wx?Tal{lkwC`C50EsSuc?F7~y=U#ZA;%5Q zJFj(AdJHSR`C5E&S}~;{N^pt>BaCx;67S4&&p!VQbkMP(Jl3nUmX%jtV%-&? zb5RlPF39U_m!PPrKWD2A zI+}8iPI~F4pN{|fjmPqK(OJN}o)#Ny%+S}~%2m`i(|_;YG`u*qdo;ji?M39`gEsE? z<65`;-^-M1XSp#AZ{E4*D20ywOsQ|refQpf4}Mno5@r$Xva4kf?L`)E5pp=?&h*BC z_f8S;!G8>E$i_2?yp@hB55RvguX)ddUf84;G3s^hbJ=U4OTq`i2ug5*6bv8a_+dWT zJ;r^uE6zsbLKOJ@g>Lu5pVY9kzrGYsQ2}h>%BJJI0xD!g2<({xt93mG>QDz2?4b{T z2*e=47EMrwFh@*Z?K;>IClcjq7$YHo4wt{?U{Q-v?4lvZg0eb- zQH*lioMtq2Ml@pYjg+jUB`=A|t(2obJ~E<024y>{DX}PooFb$ANR}ztNeWN6b z{Y-hc3T-TJSUk=(A2l&KzV3CzLZyYya?5^Isxp`8^YeCl(b z{G=d4ej}FG4KSdh!u< zrBnY>(E8E=;wjIjpfsMPq9-KLcF#%nbEY({sZD#P5RXQVFnaM|3X8JP;5oE!ixc7B zC|Xe_VU%Trd1gXdCC7~l1fWtapyhU1k(DZCr6@&}OU1OJn5yljWG$;%&q}Jb{AQqL zImQ8ew>YC*RH%U)974NUmxso0Fcf|0VU}tZwxSb#92Mt)fI!uee(0*1+lW?)!d0%S z>Z>UVt5|b}*34>lvz#RtWOUk_z>v%+7#*tbK8ROfiBM_$h~?1)+ncHu)_jN!i)?SDmCbwf6t> zBFkV4AOR6}w!i79KW^)x-0BvqIq_|KfeYMjk*A)WGA_=Ti{Jd}cfUtD>|;XNICEJ< zwA5shPbieP)4FB5-7IAx&3QERGE+cl(ZqQbo6}R8WQ;s!eG1xm33V^C4^z9SgH!>!p_w&XE@vw4`&s`OnxW0 zMr_6sn;2UwuCkS{d{%VEa7Y`0mp?pm#SY$BDmm`vjx$QDtr1j%k^!hgVE0)gm**0^ z^@(ID(&RilIb2Y-S$(HWWh@JN(1gZhZ^R1(E_=kwU`8RI2o;qwcN4H;>GA)MGT2d& zzL~=19dAzM_z9u6~H{^s}o!CqesIJ){l!;aKqJVing^4v9fvF zp5WG2xgQSkh>uG*&E(D0KGJS?X9V7m9?HB^SZ}U58`@xe%=t9UZ;&B!-~`{ysdsYl zm`hCIn_*zXKPB;;>wM>PO2~6>tza;(P$L}gxKBR5KYN+h2OTQ8I@SNX-j=((&hL%6 z%y&j}li2*`XX3fnzYca8AtYD_aPaWfEp)CO03Fk)hBKZ~jZ$!eIF49FAg&;nHB4d> ztJwP*Fmi=J@O|%hw_PAsf%wEDeiC>``g8oWbjCOxX6uYP%cWkDmv_YKoKGp%%jjpA za=q(eFTLqcf186C6gvI0INCXK7qNK58OR7m?QQ=IbTq@!Z#n!gR?&DL1b!C8U&SwG z(RW`{v6uUsS^z=s<@zf)NbWAP-;GQ$C<~zwrMHtPp&GFblyD2x|a= zfpC0+@D^8Kd=Gd9SFi>bh<8`;e2%aNP5^-#=mgo9LfglExV3WC1AYW2eoIz<)f zM-u9{ek=liIjDm>xD*6JD28G;gb^VeA%UyF35a12>rf5I;0);SWfhSOwvc#}fPKO@ z39~Q>ap8f#kcB=_gjZk@47du|_XCI*2qw5)D42qkvw~9Bf}JCNF(`*_LxUv2a5tzk zJgA3z$cG*=5UY1Qc!3c@_<9E*2$N6;6;TPA;0;WO4*Rfc_RxrMhYSi>fr3|saN!8Q z*Lz%;cf^N%9yo?*h*xU3hKtpPm`4(CIA>HRhp%XUZ3F*$l_h$3*dl$1i@CUi0)a&r z7ldLFI2G{&V0aOMV0%tD7PI#Z-k^-=AX>pEeV*t8b?|%8czD2PfQXlgq-Z>*c#7TO zA5o`@o56|&XA!W7j-xY+#8r#7_#(OpkMZbrfM`5U@`M`EP`FkR8n_A$hy<~xgwEg% z>(GczIB=r%7Hc4eRak}&*m!Fo2@aT$lwfy)M|jZ4jf3)ylM;^QIF766ktBkSBN>Zu zvyPl`hwivG^2m}cS!==ugd7nO`#=$UH+Y3t5wCy@)qoEF(2Tn_lcSIdd)Ieo2p4NW zkv6#stl$U_X?%(YecPCk4ziJw@*U#%k)4B;nTP)qB#CgQbCTxqYAQ(@E@_r$xnhpz zixn}G>);H*fPkz}2g-K<8z>2Da2K=Z4C`PIQzD4~NPW=<7gsQS)%SaW@B_WK3RoBj zbr1-?M})trr4yDaGL~d18fZzHrHNdmcyW;E5A(o`ZRZTm zPzroOn08kYb$|@WfQ(*3klrv2&wvcM&@_m2x40laQFt*%#9JA-Pl; zHIx;Ov^lO(o>Sp@aB`kvDP`(e8t!SLCz?qT>H`WwlLrtH^56`=z<+O94b$)nwjg-N zHwkwaWBwqYJ{q9Zw+{OdqpiSu7f2j}P>m`&7tu+f%H}2PwH4H}p{>!OPQg;65~83v zq9l3~C<>-w8bm4zfrShxm10D(Qq5BsnVaET7~kbmAVfKb8; zzhIPg@t_!~qE7mx3$acnl^RsKnM?5onr)KWCR>_*>FK33A*P$kso$fbd>5yM z(g`s-kj!YR%vcS<;0)8y3!Fd*lR*Co!IvQDKz)z6rvnHum5_gPsgQH2g%8T4abc*3 z`czTcs9wRSQo%XLdXAJD6!7I$B2hixmZ>G$sn?3FZ_`>sXk#BYeb@*W#`p_H+6@0` z5Aykw{(uf|X$x9dnB_X4dkKkk+K9nmq>jL#5$c7D*@eM6ti*Z{SH-NCaU#Z0rAxs% z*p_6@3Uf?0S<<>dm|Cqdk*yVLu{(1Xb=5@MwFa}mg%9YM#;2cW>JJ6Um;OMIwzq$+ zPzqNlkv`B0wYPu%H+wtTljx8Ohq(qJ+jk8rng0r~x)C-~DjNlRutkxu=4fXOyLoyh zTo8*xT{^Kcaj{ivwcw&L+{*tEiz9d*OMJ~2nRAgKt?+hED4zmKd$wnL$nXkt@D@41 zd`$S7HVdHM@CT)$k0h zK&U_4w~@hE_93`*_7m5JxQm;mRri&R`$&%)x$9ZE%gektf(ey?31(M+TDu^NBb;wB zLZ$YfkZ2KKc13?d5&!9@wY=?Gy$0yv$zYNSlfyHCc!o&>9p-jMB z+#3g+M!H&J?@O z53SDe{KxJL&l26j&kMsE5)t`m#`|NB8UxLW*vilG&j1_Ha}vK=SbjLBDx)mjbMS4$EC8U-E!r)naRz#>KNKJ=+`D3-S=IZd!-?%%^R!j4~2c$ zU)}!(X6@ZS9mvT%$PqH$Y<)7*A!@JOBkMaS>&@PEeb?X&-|=mp^Svqct-tsU;-qO* z%B(B=J+y?)5AV<@hOOOY-Od4A;PDLJM6K3&^~{A-Y!42^BeGi}_NYG&7&&xzK){e0shr+u+uPZ;0K=3kIghoBF)pW z%4C6PkE~0W^F8Eow5p-FZeywR{p5cw<#}G3RE{TCo=Wqnn)J!yT@L194%B0=+X}86 z$oqz4L12Gx^`xeb}(w23~IHFD(Dm zqg>-L#^65Y8_9Nx*^HqSl);qF6NB5?3B461=_YmF;pR-*oo?)&E>Tr(7NQOj;yb>L zQViFC*s9*xK|Rz&&B$-j2B7v}MPx*@?sT@kMj1TBM3Jy@-dnzI74AeT!frjp{@lkd z?U;@TK3+lQ{~d_-Ytfo?-RJ}%Sp+%f;$#l*%# z5!wO`(_5w2I*;ij4DV3>^JTw>9^LUk;^(O}%LB*n&zsmYe(lc0Y!-GeYSv;^U%?8S zPhqk-41W<#PU&3_Sq{4`PYjwD{}N`;_++)uSut<*{vZEYD@R}0T@Ag_i|BZgZdv19 zAH|Ux*G|BmOmIH1P0sg2LHKyxWZr`KW1{$Y-1xJfPmhlk@R|1e-5Wki`TkH0b6-Li z1p25LITSJaH(&bFitZROjxdjB6aW0%CSqYPma!iyw2%GcwzquqN=S{=MFc>3Z}pr$;l(@sDb0@7fBo4{|5vvC4kGys_4!-WLgEh)Km`8|Bv=rbKYsoW z9C)+C;X{ZKcPyk>(c(pn88vR?*wN!hkRe5mBsucZC1b`;F1+N=hEM?l%=~JjtrB0<<)#_8BS+#EE+SThsSI88h12wZEESabg@@`yp!FLW#0|?GmZdtHFg2 zCoVkqapcLBFK6D|`E%&erB7!L*oRo_*|l%yPM07XHk!l(^F06Ad}7P#)vy1@FEi)P z2w%RbXuBtM{LWuK?%jXoScxdIZ@~PXBdVqTek*Q41{(~nKnNq0a6$?zwD3X_YVN%fCnzv&8VmD{n>0TvRhN6>Gf7 z$Ro9s)5q5S3DT%bZZr!{0_8+Y$pn*na!^8z^Yc(d6IFCkMjKt!uMWYKbW*xT9P`pk zO*B)*$<%Do&5`&d%~1{M?9a|SY1&iNK1uxw(B6g-v{3(AYsJb{TyxcRS6+MdwIsf} zq;%LXEyeU$WMwRKQ^!25Y_&W~V)a-2QvDItRAZBk)gr0Q3f9+T1OITv#_0ZU4>$P_vO;J44#hHc-Rn&HmGu7Jtu=Q_SZo3VbBye35w_Jz`U3g-O zE4KJziuHn5UXHV)_g;`g{%%=d(tFL{kfz00t$_)a3CP~G-6~;#SN5pk)*g;{XDDs< z`DdVm7Fxo*HtzW7zCIRtX{I%?jJMuYk~!s?hvuqfm+Leb&zWgf*=meb>rZE%%PtOV zw9{65ZMK85D^jH6PMT@D>2|uZ8^!KVB|Sy@x^4fFvd$XjeueUyX22=ZJ6xp9c6_+R zBbR(~$}^tpF1a($OX<2hNA~W>`d$cUA*ZIA&&o5xTJSr!R`sXDy{3F|hZ}$V_Nr3X zeRtk_&$11Z*ND}N&;>Z`Z@dh1zt$#vLliaqw!Y0ueq z+{=f`cl6U&e|_orspJ5EQqTLU_c@jIe|vXpzU(Deh4S7gJE-ZcvnaddoLy|RS?t^ah92~)NLYbuSU#LqYN%9yiveb}{ zFbt3Y1=$<&5wd)pWMwN|$*9X+q>%@3Um7_QNzG9biIyY_CS!7vC6bbpuk?s&G})uV z0T3b*JmqUrsmj|CQ<~GH=7oZ{kwzZoks86J+$O0@yICffV3A|YM%fWNR+A+y0VY>U z2fK)zCMUgWrfZl4&1kAqpZnxzZr=aKO}SJ;o3>OTPR$736oAh-t z8q(pZqJ9gYM5!3KY>ji1aT3dY(1q02gmkGqgKAyvdQuhE*h=wr? zVGP?+!DLmdfZ=La>%|6fHV3ZnR3@BwiV{8k)MY}g?5Mm_8+J|hC`z3xUGI8Y)KYUW z1FcBWD$)iOEhJ5fX-{n_bKC#L5Vo*~MQmb=*jUFR3$l2V&P`vE*|l2Mq`N_GMSyxT zuoyKf_6eA1WkR;nnl`oD!zy-Czzr^@ zh8wy98Mj7b9cqr6`bj-$52J0}C_G!$F6+hwyV;FccOCrT9$vMU;l;~e7h_&DO$NOi zUN1l7E2;V#@4m{LP=bHSSsayBqQ5^4p6EpEk7R=ysL0HE-rrb3zQi;U~ zwlT6zle3ImnH3%5!(a-r=SHkQ41H9r-cvC@5yZW$y%@$ZhUiW$7S`*M7RNc}ahc6L zG>uUN$U!DAi;nzeAvgc#81ZUy=blVLB6xl=RnW9vVC?cN==u-=cqkLqm&!%nTXIi^Z+U9q^ z9c5L<(6UqO33p^FLU4^Nxmf02+MS)9=XdY-(#j{f}OAQ!rmjDB{smxiFSlyrs@ za{%>te*xt+TG{K}8GLxePWvlfCQ?N_*oSPnN3+5xf-E z3kFwYk$;RN;IvfoVHMt;yGLE`=?b;YZ|-IG>746W?z`a(uWGg>KIn^o(&KG^d#wy6 z@`U+3U0{o*gB#o?JFmN!+i9iEs7IOU&pLZF7T>{3HMrW;MX5sZL+8RzH$G3 z@RLOMhmrq$?=3%YgtJ^Rv?Pp|lF#tvPfW`Fy1JhMcc7ExU;q2(KW4G_e*ol-t+_rG z%D&N%zOh@h?qiVfYd{CY2;aN4#Lz9npeUJa zE(5fU%9+2IkgEk`zz2*$+^aB7*|jzcEKB((v!cJ_r?cvs z6jZ_RX+Bg^z!y9l8Jt3*QPZI*Ka7RkJ@6 zED8ejJ2*KBpGzPobS5Z_Ldc;)JrxU}x07Ea_3oJZQ|c zL`)VToE$V1wbPrilL9bwA~jy*Bf$H`@d-v@^u%IJN2l@-Wc0QiJVm}p#r88J40?}h z%#>J6A2e*I0*u6JGN$LViHoXRKL#|KeIhTNwRX~$e+4;zFGW(*=xT(fx; z5fRb^eh`m)gpX@PA4eoXf21bW;76Z$H%5fSdSjoeOGt&ZiiVs?V)_z@1jNXww8#HQ zxu?^PRMe}F5s!|Hk&n!~e5|0-BS~Al#WXC5i(APx47&(=$vce6sh~-$JS0iE$!5vP z%L}&yD8KF?421B=fnzl}EOrvAX8Q`fBoe9o z6~6RKbPPN6}i*s7`6bwMy7d{6P_a5Ks$L4DvY86FCv^ zSWpqOOk#3NHH^xo>_-2izV1QJLgNZ1gioNG&xN#45Cxl~VNEpQ&%Y=W%=k{un302M zGq2Q713l2pNYL$EQ11K=2mMFBD^K$@sqKlkY+02ICA1A?z6A78`V3JewVAjf(aA8; zG5ikOoKeo;$ih@cEM<@N93$VacvM&275ZV#N!57bjORgY09oXk}?+fQ9$j{ zJ0i{>8B@3@RjiYppOHOeP1aUrR&>phNJ2(vwT@TBQ=Oz%BePb0>eOD<)*j;4ItkL! zP_+XR8gez)s7P0Wl@eSstT{CvD^)pp^%QztG0ddD2xUopWuX?cP*J^5(|A3r30Q%> zm4Xe~3R$dqxu1p2(}q=#ho#UF%+^z7CJWV?n8^*WLmQ9%*rxvwS)DBqlI4zfB@x?1 zSv{qQ^$5o$99BQ&)#R$!^oiM1IklC&S8=r2W5roz-C3-4m!6H*T{>ADl-Gje)1!5( zX|mU)ec4QO+EfwKsO_&_+`fy0NpsCwx;>7qbyr;q+OJJnmKfWefY=e7*h&P>$qB&f zQQMbsowkL`6l@z!#J6%4*t(tEx47FdnJEI@+lDn-zdcSX!&XoI)J}Q>(k)%nJzdik zBw94oqfMO0bqTqhTgsi?vasB~s4uTgS!3v2qz%r9%_K@BRyO?Hrd$i&ZO^rNU4Mw( zWTjo_^$OcX#3nmgc{PTG;2YjeE#-w4!4=+;RHwP@UYGyffh;n>+4)^+Th-=$UiSTo z=*5el?HuaW)Q9*FIb6bB1>Ml4uDY5_(Ugdq;9SFN!iz;n^<~xeP2iAt-%5$Ph22vD zCSQ~|0PG!L9#h&{^i`G(Ug(pq2*yNNEZ_w?U`AD76Rs)-j$f0V$ZGXooUq>y7S}U# zOCCjAk~%@H*a_3glg8zp<+R#!Jz*1OU>{K75VBHUo0`$s4GQLAK$CxN+dqADzXn4E>?cS;0$J3v%NQ;XU5j==Ec8 z0%R8vDkDi_(Iq*vZDSk0VO$(19Uejab;&z^iArA6ODo-Jr(IcUhR zUhGSl)L;!w!sxRbN%1|jyE3MjUEFXT&BFgXRH_4LApU5qBw3L@7LtAplMV_QP7MU{ zmv|QCY~IFFmZ<%(P?~n(en!Ehb`_4U%Jt>xV$>>iuCJi}hoN@8=%EwHFp2|M4a3Er z{#$GQGu_jgXAZ7uD&D7-$=I2_X`I&3T|Sqqj$Dt{YCVLht`4rR4(lBLyD-JFg+Sca z;I3YN>ER`&LA7gn%jmo&>H}2NxW($M2J8kjsKIuu!lr6_{$_YnY{rHO@deWzh3xM= zq)?@7nTTp5v}q#EZ28-4zm{Cj{=RMs?XDVa0^?uJlG&M9Y_+9rWqW9Pu4jo(q`{Hx zeHK>RR^+Pw6+L6#&hBlr!zJLJDdGRdP~7f_>6vWQwrEJBVV{8MR?_Dm_13pw=?*S! zipg%yMqutXx=8x&gbMGn7;h5_5-~;Y&&0OJj%ea`H;fgujlFKUHsp1&Z)N`L{Pwps z;%{*BZy|N?(GlU(HtWqAIhRK8MGm87Q(L=MZpNKzhMwz%k??X3;tHp=-}-4x(Qv$G z@s60j0Y7VvlV|3RYxd69)PCx_Mh%u`HJ?#l`7Gxdm$eSUa9zT2)(r}xaGA0`Zr3pE zqTAjpW@`GTpdtq}=sJ$%l;ogc@>hoCC+9H_vhhoya^uwseeQ9Yz~-%!;`xT~v>kJ! zAXF76&+>f%Nyj^XhgyxK8LxzdzKS_0(l+TjxK+J+71>UFPs~s`YT02z3t~ z^}5O>QzsEruMkx)7>qjJYlf;`hV|Fhr%wuW=dNS81@;!4a0(}OlJcfwNA}9#@*P?B z*&cLf2QAi46+K^Z7cVJ*wDu|X^=!WrVV_TL@29wt@+lwpD>3(KZizxpcVn*NAeVN+ zg?EAX<*`8Ov5g!`=62rB_h~w)aEFg%FL#~WVa18$CRrsiTK@? zU5aldRg4#Yr=*O}GuHnhci~-$fhTy>I&czK_q$S(lBe@ua(3x?=#F0ImN%qkY*)~` zc+QylDA8BA1ZAS{E}p;k1h1=};`ANAb6xgZ-BI}%m+_?Up;LrXzleD^g8C_$zE1<- zn#lPchOm(Dc>vdXH)ME{IPP`&_}vlvu?OR_-=UUc`m}fY&0u>f;k*8#`s{PG?QL!> ze(vSU`)|2(E%tjKHv0R<@4=TKG|5P=Mf`zKd@E5&=f?T3e_KeqdaU>Pn6~_s#Qck} z=FUZ*RMqb7{(RqYP0^nl(l33>$Q7WfVTf>iG^e#n*L#Yac50V>k+|5Os(ReF@0DkH z-rpSckkUwm3#p90c0@Y z!iEncPONw_9|#|()4^2w9eA5 zUstAjlxW9-5NDqMyu^BUQ`o*s%SKHzYbLbDk0Vd69PIDr&Ywe%E`7R0zW?}Quhhmd z_wL@mCx$FJGUe%_-$4AyyXeQw=HJ6V|4=whj^$DE4jq3#e}TbOA3&dgGU=9|fg|;o zU`xRbh*c)VEf=AL6DFsig%@I&p@u=xWF2;VX#$>zBa%3nc;nr-p;{?wmS1O=e5RC& zGt#&aN4GUtR7wY4RHKh_Q3Vl>4GLJBS_tll(?YEY)EhxcE~%e|3=T*fg;!#kWmi9P z*`=3XR)(5&*L{c=Fd>$hrkaPHI2oAI@yK3*P`+7bf2R#d+iC{d+2>9WNk(LmZXsFG zQVKD7fRj!C=7gw}8{$cym0D6-DRO>dnyIFKO7xGIdPSC3L?EKMrl}&fN#3Tv@krG` zw7n7Q0kP6rtF5czYFVW80hlD8xdKZNO_2#I9E@)jiqN74A?V&fGA5KLjk}^YsioIq z8&?5^TS(~lL*d83R$Rocb+`=;9712Q9 zR%fodFS9wGswC4Dr?3&7ER($q^XxFqtKK-U&n5A=!_OKwm~*iNBTMn4(pv1aQx->^ zQPn;FLVfkrb#8psgCB!^?a^bCP4a+&nvC|S=9UWcsqFq+_FD0hJCo8X2goy#6v+*2 z*H-DNlEHmj$nf0*G7T5B&sxnal8KW)eYO&`%JAv!3Dln0W6FoTn zrMW*l@K*_McseN_ousz7C}C}Dew)wpASAs9DrbKZoS&q%nb%he}<7SW#z;Ud2j-mf%tirnOiM!e8Wu3OF<(1W%D z!6O={hDuywPcG<03~nMB;}cN$z!yF;u`Ps*86gvW!kU6mMNsf#m<+q{_ zgGWb4?QWYU84@cuXso$FYa~*-qrnU)w{D_lm%W@PSHx-0&j}NeFmM4_jEPKTE|Zy8 z+zSYynZA2YQ+d_&-!=UqyE!5hVXFk-H=~8hh&HmE_c~lfg90V1F)w+wq-8BV2T!kQ zg`O(KC`(0_PbZ$mn3*t0Km{tZEWRw7Ej39<88XqNHFRek-RXvICm>Vu^rH9tsYcCN z6L^6%h#8w@(I{uj&yi9OB2w*)EBd ztOhyGgEERUwca!@&jim~FN?sGFjb7-qpE4SgvN&LiH)sY%TVygkS1us4t9_P8SFp? zBTUQ)xs`+#2r^tUNa6szmBenF&;*TWp|`pvgBFz11mu$8xsJUm^&(rXlv38KvmNjC zhS?C#9#eE31T7Z%fw~cumb^X*V^ck~*Qv_aLa&|UP#qV}{6eL++8ju3S22rO{Nlj8 zEw1CVAcAW&EJ3jkIa+*?A0Jfki>yU zEQwW|_!rq_Ruk+1VJ$P*2woP5B+6XoYNWyuQPYBfXHn)=2xJu#)*723%-ikCvW7_> z&WmA;L?;7!E{TMJN|NJGPwrSUcsW;NejMnQ2-%eU z;zW%DB|;syVxmC~1d)%22GC7d;xU-6FZg z(s{!?_=7imUSf4%EgE~xKFg(L1T!QzJ*hOgG8Y1Efc3umD-W`ICA_8MUT!~C^ z&{6STFrE+qv5!Uop%CUGGWrzkC7}|^RwN!k3|!ZV@s<@%U2$;)Iyl2GIKt!6)b&A_ zH|&EqfS@yIP(+yHFPLH}AcLwQT=*4RF6tsM@uDw^9y9{uFlGW7?cmzE&p!#RrL0eXrCo#Hvl!!ra!HK;;H zpr95w96svNQk|SU@#DuVWFTV64c?DIzMSqwg;F#ljLh9ln#A2ngv@0U|CO5&Xk!zi zSd|T1g3UrIWWrHwWZb!9F#N(agrNsg-b|na2zmoJrXn(YV2DAO7Q$pA+7mBwRZV&f zQO01Fz~A2RLh$@6pPQ)>)8zg>}sG*o|38x*5nnnI*gmog7Jz*(i zCrYZ~I=G|KX<&AqVRU+fgK|$hLXsFhLxE1CN9~YbT_~TurG{DxiPs+m}yfDh-xl*D9E$GgJdQIH*kQ!}U>Lgqk7jOy8|KDN$60k)adWOsYgo zmZfeer#731B9nSLtC%W90F^0Cp{b~%n|acqRha5QqH09-+BH^$5darLyum!o11sh# z`0T^Gs_VLH(A~i6x+$nx;xC$u`zzd=v0Mp8Pm#slq9> z!qTO+-3`gnQ|VC0Lh8oy>&If9$ObIRIvIMl=E(|e!YV{sT}8uYEXl&`d{%6JX{!~v zoog8DGF~moxaj!-?Su&JkwI%iA>r2sU`UYYK`4yawk+b1?X38$vE-(lTGks)?J^8{t&7#J{%Ip`B*Tveb*y$XWio%Zi2si7^Ss6Q%A?>Ozfo!nwKCJ}5uOil#0q3pGQdI}@?o5I%2p@+C?-cPGY=~AUR%%qBq{s@7 zZnpxW3sWvI#;|B?8-Dra1R=3Z(4-Du3J+rx340U5P8AB{OXhNLo?-D{LGVnpFXu*W z|26UdTx_fRrmVQ>*?3y9_l~hRX))ZcXQX;@efY`&+sF;ckih&gC_8S%IwaKEu@zDn&CzO)Kr9#4z8- z_`Ngi4Kf0eGQ`fuRk{S^;w%~?A|{=4rKU4ktg|Tj@FkNk3^%PxTyyMFr~r1IGXFCF zIZJdN1`R)_gg@8EYl3Gg4RpvB^jI9UA+@u&Vlv+e8Bf|zM?`c!mz*z8^BbqJ8t=2( z-OIN|v_763I*+tLmvkGQG%9mw5B|h8zw{Evpdg1cJ_obwW%N+-46zdOPD@ir|1>NI zH4|ltPAYVWPE<+*VcdmVQukCK!Yu4E7BW6`i^@+Knf1OBQolM#4rldOY&BP-rzM-N zd2&)pZ<0VbV_eI149axe*0fD4^6SA-01&OPo z5jJcdHZV^xTT_~m?D72g*JF#PWY=|NJM(3eP-f$uUqh6>=3i|LHfh2qQ+KofZmJ)Y zaWomt^JCMnDAD!r!gf8$_5^kHhvvva*PT`3ZbrE0GjeHKTl7U2VUXPHrW*HI%j9rV zs$DO4b2~TD=JaM8ui5IhPzE%oj`nuTZVZxLIZ;G-i??aI_A;9{Y@_%7(DqTXH<#wb zbypqA(zV3SwBZW+2e|b-H(v|pRv-AvTAchc;fP=)idC~fb5SN4W;_+Cr6W(ReMdrvYYu0x@Ox2YyYYcxPV zc(Wz4QwfT>+4ynaQ;sh;Q1f`}4ESQlGENN5!WKD6G&X$BcPb~gv(fJVcP}k%PPr|E zRgR1FmFqy3Yq^Ks%RMu%kRQZ|qt!xia(3HugNLzFbN2bJw+2_KU%|PY`x2cKPKWV10658T&J%4FapK57y8+of%PUkF@@6@6*dRLT#qkGPlSM(Trc|%zG=otB* zlWdurxu-uGs2fhCxACZJGQO6Lsb9IO*AA=WdD~LD!p8c}ATQgtt*yInj02hUI#SiX zhJ{-%WCM&cGjlT&JM}<1EsJonFGQ?=lHM>cQzLeh!xgm$6zg95jbp8wkBu_>^ecaR zkE^%y3h=9&#KIy4)84E4zBqmJ?QA`{yWh7o7dVVpH>n?ty%RM50Oz}a@4KK-_4kr{ zMJ(_NjVcyHd$fbbc%`IDuGVt^5)9yr2*I$onIMNPe+CK238s;P-TfYaQX6QMeZ`%0_*W zPw#CbeJEe-<*zj~LfOu*?-OVKnVVGS3w~FDJ|U@n(X##j*KWMcGI$YZzT;l~&)6bnyw{;EAedN>p#K3fLgY(|!hH5ka{(gV$3yN}! zm-J)Oa}&4qo2{(tjl3j(7|Zs8`+W0LzCT`Y_XETMfddH^G&t~*KZOe~y*c>s;SPxt zcR(CS5o1P;87+47_z`4Ckt0c#Ja8%DLX|63X3C@kW=xqgY1XuP6Q@a?J9+l>`4ebR zp+kulHF^}OPMk|=y2&)`A4{n!Q6{x|6>Ci)yVm9C7H?j?L{S>^hteU^uPf*7M0?O~;=_CY8Efquccn|FlPNQ8d>M0Q&6_!Q zCRlm0OUNvZUGjVy_2#Z8M~5}t@y#W_r2`9GoEmp--5=q$_D7qi;>5d&7dHvFu+YJB zf!-GWoT72*1RwjB3>y37>D#$?_x>GX_M4)8D+CT6eR|t>mzVc968Y=(ch%Ro4>Y#l z@_>UwzkMIT#^O_MH2Hq=55fNe)U3MJt`iSJm=>In!U`=EDZ-|nifTUtFZ@t1j0$S6 zK$G(Ots#OG1d&Dc8f-1Ok`ffL#Ttu>Eu|PsB5^7Y51cVU8yR~MGMC)Q5Hul`T#`xD zkerFU4x5~^sEH2Z5iFkuRFOU^y+p0I)=KmLaU>w4`w~rya72;Jx7^dQCo>UDGc6+H zGV;ls=-iXfK6lD9rYL>i!ew`^;qTUktW(3@jW|Gg5f*4! z7#-#6VNx+3iC+g(&2HqBRmN;pgV|mGnZ@?n6^h)DZSECj=}JEMW02*{IlcHC>R8yB zxxD!~pg-CfvSCivPU)znwrX3bx}AE#uZ%8=tdlN5I%KS+o7T0h4Juab>EP0@Ua+QauqN)t{eYoXw+kAG@YX?&Lym*|P^4%MM6#C3T4}P>^%*h^otgG(6 zK;_f_P@*^TLkOk%?Z4lC`Ssubpa1^#x9femkzLv1^tb?CWm(+Y9g5r)KJkT)d<#3^ z1Xnh?PtlHoOY(|ACif7PB*iru#LNKQ=Dzu0PlQ}6j{+;#CI`OGcoFt{pc3DH=>!qT1Xg)m%R1eI7tc&+bhR)pUMAL7G< z{$}I|P#z4owLE%e`oFlmCE-Cp|JqTjHgRQaR$~A~{A>x<{4FVr4OZ*-U5R z28(%o=5D-V43Th>AiVsd+omZ>wy`U9NHk>?k6Eu|_Q*46sYo~3+0M*ZQdr@1XJh&p z5^N4+hJcjdJljG-GnNvCI{YRhQ+ZCp)DkO@;^#scniP1xtfBO*=QVZt!}s8mn-Oh` z4C7KUi!t+n110DR4Qd{QW<{ZS$&^M}I>u-gt)(iRC`ET!qL^+pSUl?wNYN+Kk$%dF z_QFj{*MhT~9yNmx{hK_Iij&?Q`}=b<5Hi$bwt{T(aNOZ+W^|1q_7RMuTo8_ySHdzr>SOpr6eS<>w@q#!gS*`3 zNU8R=DDH0jn)P9i^w>jOcC$bbtPBj7 zzV)PWcoYTMjMl;al73@bJtQA@qLS89LI_N1VSCxO?IZHQSrxCCQScp$_pAcFbl=-X;9jqIHK}Z_G23){UbL-g zb?i0gx}^?=$Qu~>;03!5-x04Q@-FD`dGZj;R>8A*osDmTXB#o^hWBht$8dszT-y+r z_{u9pu!8M(KL)>QMPefswUDLRvrc!P_Z{XZk2&5cGWkeRE>4xR9O(kDVAtj|ZQ6L$1 zyVr-F(sC~W)LAAevJ*L&NM{szM8=O53P{`3WFzfn}bA%E4r{3c=qBQVzc-cL;UzyE#3 z?2+xoSG+Sr-AL36%jbYc{``qUd6>f#`O7&#RH=GVg{;FHs=*ls&>5=18~Trz<^dfB zuo}>TB?@941kf40p$Ra;2(&;FBw-acP!h@?aaR@6iSE5k@zYz-UVG8Ym8G|7J55OI{unEBM6yuR1 zv_K6dAs)#fChgHmc7Ppc!6gOmlr-%YKX3g)kLyma7ws}Ag_0=$vMr{p;*9as3b7y% z5gpcH9T0FahtM15K_#?u0KK6xuW|~TumPFzD<#4R#F7kfFD6(2AuU7GB?Uq)f58L` zlAmmmFlX^DMQG^qQZE^YFZ@C+;P0#njD;}RGb>L!npChd@h zVpBHbV))L@Htj1n?^7!hlFE>-A*oOS(Sa$QVIv@gJZP8N2~2_u)XBb0HA_@fm`l8tlPAdtnSK^c*h~ z_so+Fj6fj5QXtx~9ajN7ZvcSOiZ!Q=+5*T$+oq(R&KE_lM&EQOh;bpQE-85w9g5Hi zArc)Z=QvSw9i$LRnX@Ak(HRwDA8dg_xeyJx6GJgV135Gv(UA=gU<1c+Ed4M;F_lb5 zsnS$57f(m9rcYEw)kVi@vS+Q9V#nXCVVWlMK|d48hYiHTA95^Tpg0mbR~d>Zj+7LoQX-TR%b& z*|h0?vkC!lIUzAYA@nh;F;EX63LEq|owWZh!44At)j}CnBkVv7$>0V~^AxQ_QcZCt zGqol)OAdQ8Cw~s9-itkN301!pVo5?Uai}$C3>g!20fXTg)*)V>Au&HT0uNvU6H^_k zK_HrvW7nY+Qj$Bhpb1`f7C;m|HFQc3z&z2iEzz+ZWwF${t4!n1Jr_3UD)uO1!v$$E zVv|-W`sV&1O4tl@37_E!0Tdb9(MNr>5{=MftHEkH(FwiuOFa-wOEe=$6GW%90@n!? z+tDO@R=o7ljEJ^9&$OvnEHCt9z8+R-_x2!IRrVOo3+;dmMu8tbXdk2&3ImV;7gs=k z6i7vuaRoFCO_2n%)H5@s3qvyoK-3gHaHZD&_7~ic@C=Mv`B7nomgMBNCt}ltx|MIg zHC$DfwzQK3Pw*=caTA?EF_{uTn=)3b;RqY>V|h1Ldm#X;b`qMk35=j#l{F*iQCS5- zU#-&$hSfI0lRKleVEfA!N$*o5ip+AFNHerJnslr!wA#4tr zYWt$)qY+)NC)Ef6;2?at|mDEtF10^Z+`XVz-6^S zU-14CivycQQmxw`eJIgQwAGLEo(R_ugbj=iE8q3;#BGkkeiu+h% zmG5uy3mrF949D;QCLt3Tw2N6dNjtKOIg=GpF+&f)7E%FEgQ0fQmNPMML&=Z?!Lx`N zt$XeGj_)dubs`2E){j>?JeZa@SFOKrSS{63aCx>)SvXeLL6H$+B1F_4F_a)g^b2jF z6#UmTDgv2>nG~CKVAqZ=kvNHU4JY^IO<38Qi9(78g^3xe32s132cqTzsiIW4*19i) z3*rW1U~|`IW9FFA>KJJ0*2n<=PI+3?rmh*EelW>{rfpO?pYu6=oz`N(xSZ4TP*TED+*y?A(tBU?L;>#D7HFFv`h53U+Gy;S=f;8I zL!b$dpji%X=Mb8$)xCz+BJhyhNLr^y!lajq#KPGc1rKRU45QmwZzB$#5jvq!w^0lN zr&DyNqZ&g1c}^dgqQlstiJI&*df-s0VWat`@GLOwxpD?ks?RzkcC%Hv7mSa(C)n9h zxVozcla!Ojv3l&O_Y$r5x+8j;-KcoCKFAo{8Yp;6uHEb=eGeDESEEp32C)sW`MQt& z8mgTOs57;niaM?dn@;op`m4d3rQDC}99pthIigS6yHetW^un+?JKYFwnmv`V-N~mO z+c!!ZxBEI=-d8wy~tmX5SwQ0NSdmz->yKk^P zRH>7Ky1&yjS9G$WVEeOa+Ld-^2JKtHAA+(^EV7@CL|90l7C9^4K)~Tmxa<1-*omNg zlEN1p#1Ejse-a0=M0YGoD?EDSXoyN=>}q>`M=l^jqi&+_u` z$@O=x{(C6C=5$XhvH5tQ<#~*>oS?c~&JCi*6|$-&Z&`e>%*}j!fgH6C7M6$HuI&iG z=iJcg+?6Yi2giIMxCh0R+CJ}#z^m2352(-&9n-mc$&0b|vg#my(7!?A$I~3WV!E>^ zy}FkN#>*qqTV2z?+|Je4?()2gcs$fC0?kRizt&uKO^t?D{kC0Q*af1_Z#>LrozZJO z%Gb!xFKp7U+|9EGyhoMVKV{gj{k~%t+5IgU_nfY3lgKw($RT~uvEAIeX~f%`Ka<@e zK>d-MJ<53h9opaf-0Pi^>fG_1ncdsn)@2Lc5u3ebdfvm`-V6TT@q3C{u46_bs&XC6 zgYDThe8UZ%;tzh)@7&vHo#Fq;!gW34y&Bc2yy8b*gwh>hsczrxNtYa+-tkS|B|g$g zUgn3W*yr2N*c_!(zR((?XS+bW1H3%e(5p7ES@KnCC}6Yo!q&r>dStD@Eu2wQRl&(hggT@5Bt3;jyA7k*ITPXJXaixKUKg+h7@C!e$`JU~go&EbCAPxu| zNU)&6g9sBUT*$DY!-orXNSsKqqQ#36GiCC}v7^V2A1_^kNV25KlPFWFT*aUz~fxw7TUm@{kM%(=5?yKqBWbdzb=KgKeD2K~&sb;`XRjTMY6+2vE!g9*Fd z&D*YGW2iy?9J!J<wz6{$6t@_w(o% zF2?Q?C`;ph)61VvzrOwZ`16CUPW?K2kB;dlAX7c9W>9!a-R53j<_+keYwNKWU`p^^ z_27jVW~kwY9CkPsf1;80pGUZPXd*-89TZA9+lU-Zcv6KH#;D`}jy(40 zsjRl@>Z`DZ1*u!4nFi{DvC?;w zSg?K6W>lYsD(p?6c4wFsoaV{)cL`UH0nhuTTX$ERBF-8y%H2 zQhKAZwTY|ly6m)ff=qEo24P&3 zF(cCkvsuTEcr8RZlf3iLL>FyzNh?<*FLpm4Js-d_acXhRG`ECv&?`C}7SwbJj8f2A zhb{KlCns&4!;^YVHhMBg#VJBIqjU+@S+DIC*HMWCaY;Gb?f2h+Gi$a)wRS4u%YiS~ zw%cvOU3E!w)2(IVTlH)$;y{l~`R1H=zUAO?h1#^|tSt`g+Xuzn&>NCZPWqIYmOHvb zeZOw|?YIjFx(-VRXKwDDncnRIs8h|+>aD8@JnW$U&Ufw0M=$;V^vHoOqUe}Yf0*!| z5>$Las=Ju{vf3~8vCATBUjF**x1ZPUEhFoGcc2>d{l$+nIR38lD`olN=|fll21vjH zW(9s|vr_g9I2ODO&wh>2{S3wrQ_AXEqfg{8I-ZY@*^xnHm% zS3#_pP%qs3i1SDSwinv)h6S`<{Cu`R93~}(A6bYBS=d4!7Uh3T>mfsGXv8KuF?SyF9o(WA$GEmA%5HCD1Plrr(k9ikP-tmfNd|>e!c?g* zj(E&t%64}>De6&;^=pWBL^8fV+NO%_L1X6bXvju7l3nosvz7cFX%a+E4U9Gsj2p2= zNtSdmWXWP=Cr3%jR+%wviY(;GZb0!#nOvrUh zU1n_XiAj(y^{ZfAibShP(NdaDs^IbIUJ8ZPtaenVi)?6E=So+k;FM5s#bet>)w+Qk z>#E8FD^Z~m)8Zhtu82)6MDBXhPJ#?^bOYvE1=d!jlFOC@o2gEJ!fN z$%OosJe5tVR@?JbglM+2u#GK2O4_{E`cN^%%I9knq96mMR;b`aB}0uP+u|B`I!zUw zK%e-OxE_imrxhRh<~rEy47YB_&2DEI8`?j{#F<%=+hlzk*s!kFN!MMKcGs)ev4R$q z(R{8-qMO#B&h@;*NiQ7P%U{lNmoXkCCC6I-(yQU%=}!pelTxco$K~qQh5e1Nf0OIS zT@v?@9+BDu`9-G=$0<)BcCZgGYfZyS_{6YvZ-sM-Pz-PDy_eJ&zeMcB^IFxmD9&+l zcgH)j=9I>9WT{@DqG5f>c#WgPZ(eoGWbOXI#UB6n|JN5)Pr87#vkH~Gu4 zeKJg={KVe^l5sH3SeEsrOA?nA%y3?>ie;xt^ptfYE!PmV1k@9rbz^?112}|a4+StmxW_3e|`Nj*IaInFS zwy-ITS)m5ABN~>VFcZS;X1CaeZtk{Xn+Dx zwK7(rw+zy4cTahW=bN{{=}qkt*Yw&H`$s}-R#1PNdEgL_xYNw7Kx=+hDZ=$Eknc5I<%xE=&UbFIVO!VNM~0xn z`;GIQ^Ze*YKN!V-98w#zS+Yg9bJC|y^>x8~p%AU5#tgEjObH~GQLnn#$KI~1qk5k+ zr};&9u+oi_{q1na*3xh7(6rnCZ0$Gs&DU>U$hiCc@5Kr^*7<4oj^O>3gXDW@0nhlx zv&!t%E@$BnUlqL{0PM+gyyiFWD4)}j@H6hIaoWCk&YS-9V46GANZv?<*Ecej$NX+l zPy5;f3GxQNCX%OW(8SN)_P`H*jBx+vXs*_^hl;)8|1JFHJO4zgU+1VF`D^5>iuB)p zzV^4DA;F)0mN9&A^1Xif91HOhA&QU`$?*nyXUe|VKk z1(sPVH4^?nDf8!nD!79GhY@{-rb=sNSgk`}ueV<;c!M~&7Ty5?mhxK(C zRxz>RVQOe#Al8O@lVEUog`jaP+Z_)x!B5cjfbkLGA3M2CQgesn)qs}c#FapiS{NTg@{KSS4ntQijAg;xLAzOr;E1MSmm^GJi#8b z=!eD_jmP+jQbB?LL55vC0YtM%i{B!R-spU+2o(V)U{>K`oFVHaKMIhK_wW7Y`Yc9@%opD01&uSB2M*A@PwYX?q6QWgS^jS+;8Ub3BKbk~Eo* z)F>4#sedn7F~(zlQRi$m8I&pJj+mBej+Slw_LEE`luWr@E6Geo>4(44Zc6D@O?j2H zc9SPKef?B;L>56rSC#LEm1H@TIz*Ay=#r<{CbB1%V_BAPIbj6IgH3meRs|==z6Ym+{z_h#6K-35tQ~Xbh53hIyEYIhkJ-l9O1MYqlDQw|9}* zfRy=}1gDkbXlz*qD8)n^n`D@vxti^zl~$FL-X&uYV-MVo}_lbKhX&`DQ3#yh*{J6tJ(!L&fIM}D@sKhgP}#yL2J z24850NJ=z%&FO96xt`KVl*HDRlk!ot;eX!Ap7yDji@AmL6hpQMf9T1X&v~B$x>VCS zo_Ax}m0aoRTJabMb=}(xBnRp(d(S z1zMf|rvjTJ_CPXteW;n2dwHTX8liuAZzV@_BFdoL>6|tCqbTa08f1LA^%6k?nal^I zN;*<0N|7vTLVMAX7}%r#x1?5@P)*94ZI+X2g_mnr9-eunV#-gud6{4}gH$Rs4>zW4 zx=WT>TTePmK6L<6)kbT0r*4?1c^Zdt*rtB!K3Qs}Nj0aR0+4nYpMRRD>l3I2NK=IR zV!)D#hq_LRTB+>wrf2k3KJ}F%C#jR_qLvz})5EBADN>t?W|7K`pBks4+Nyh$pXfEH zHMBT}x~i^vtJ+hhwI!>XB|LnnW{jAYxH_z1gQ-Tss(&O(i>8rNbBYQ|tk8Npq?&vG zA=QMdbdG7}sYmv#(b}!AGp+4MhLs2tBVv;3=&k6wJjVK=rYedEp=%lmte}Fd=~}M} z1Fkp25HEWfI)r!ue(3q`t`sRyf}3HvSn%CO@2 zuo?@ov?Zvon52TFF$=4zB(kw4i#r9Ig!}}uA)9ZVim}^vvNGE_DJy*mwWja7lP~)b z0XwrkTXyRjP?Xq@ExVH;nsGh*vq}p|uzF+k6sEw)XNpKfOIx*@Q?m!^O$n(?j3|u# zX0>1oIMdljaJq~};gwOtlMD#8VcWJwQ=rLcu=iz`oPsL|>$Z4{GFUs3bcMG6t%zP# znzw>mGJD&K*ZEL>3lcQZTP!=cj@vO~J5kh%Z+`e{$8vd+`M8>!FopY`QMqQ%%D7#) zxugrZP3wx3YjUR5qov!rFcZ1oa=80hnwIFgw)?tpE0TO`QY5cvp~?xo z#%nj7t3gSdMhM5P$NRi*8?^ZqrEH%bpNru;CsHN z6tSghY%yfM==;8;GMzo9yG4n(!o$7ro4@KJzEEkuo2b74tTp@#AnprpGGn~~oWNxx zy>iRGpsK(SJT&rapu6k9JR89nd^7{BpBBs!1)RYkoG7q6p%#q4A$-F1%`(AptFqTb zeklCHJ2Sy5YK7(W!7zNoVY0!oio-lylaaf^}s-`#a@hqOFX<^JjN^d!&bbHWSqudxW%C|nri&U9mvKW z3&(V$lGVg=jO z(`(DRERmXg$h-W@5ckP#+{M6L%$0`A4a|Z80RSQS1O*BJ2LLP<05Jg128;s$2>$>N z2pmYTpuvL(6DnND(4dZo5F<*QNU@^Dix@L%+{m$`$B!T(X7cCn(vFiTQ>t9aGG)Uz zZw|JcNwemTOaK0vMES-T$!2qe2pvkas8J|l{3uyV77Jzo3;+! zFK_>zIa}u~7_3{r81-TFOOc;GebT~ZO4kpmQ>P5|xdXSa-@kzW`pGjG&)dL={bqX_ zDY4_nfnmYg=TE9-ey}t}Y7DtETt$UamEzkcmFZNr?(j9Owl8bHj8b`?-FJ?cGh41u zVZyt&@87_K3m*>r3M5EuE^%76j3miq$ue!qBr;Nf-V#=->fKL@42e z6jo^Ag&1b2;f5S`=;4PThA5(h`IM-OhINp%OhdYqn9qX*HRs%nG;#u?gEEe&;f)W5 z6A}5)KoKDckw6t0NfD7w9?9dBR90!_l~`t}<(6D_*$|LmhAHNlWR{7M z8^iqL&l@(ixe|Yu#AJ}0bk5Y%KgO_mQcphxWz?U4B2^btPF*HdHns$_N-yvD^G`Lw zjO7ny)ga@{Jd|0J$}g!5^42fE1QRMFgZg2}UAqjj7j1~;K^S4I`u_zAHTzJ*S**Ci z6$vbh8G36Un!wUnu)nhUi!GrAbB7|q6jDkdtzpH;DyhZwY%rtsVauku<~m0hTb!{Q zapaauoN_MwO)gZ#pItZ?{c8*aLpYy5Cq9LGiz=29b$IMf((4M~(iM{gYj-EuH4 zZe(|WJrf@=jzD&R^8~~LJ;7cw2Vc#f#TgTbko@j9*z^7P=dXXsi?|qz2`zgWLp~uh zDsf_PH_MsMcy_X>b?t#0DVo!qq$DX(a7Y?~l9B4i!47)xgCGPM1V>215|$}VB{`c- z_|ucJsZeY<(aG9K;t9CfPzZ9X+v4zcnZ4aDZ%;v7B>zffH@Xy&DTcsHGBPxU?icAC}5}828AVx8YNQeSkZj6NQg3+3| z_{Dcu%wr$E6|Qj|uUvCDj=IX#g=`#06in#C6_{{~d5psz;#dY{o|BAoY@!a?7{)Nl zVIP6WgFWmJh#dR@hGkqM8RiqnHLkIr5HciV^E-|!{jmA85iTl1G~!b5c?ZK3bZ$zC#4b(| zI=I+ok-?#YZm!@3HdNFLaPWc?aWyM@WTT;a3@NKT!K-&nGI0E;#xE}A4{!X!Qo*Q( zKYoD@e>4giZ1GDl6hWG{i1doVtIch4p@nqZ2NweYgFM35O@f4heg)~maR$-W{^0Vic+G2uWVQ$Z zVkoQcjG2o*QKg#MY(-L&Q5{NVHE}xDnoBwoWQzn%rAf1{n9ZzaH;c8$diJwg8%YY; z$r3pEIDsm+`!yJm!^)zq_!9aLNJE-ms%L#Mp$p?7^JR@dG+r zB}6*FfIcuJLwy1vL@P0C9Z1miKXc`*UG+-h65~&0{#(Q%&~PE=G(?xeG#~=~f!M^7 zWU(UiCTMs35o$^nX_mdLh=)w%B6E<(NKUek$eAbAmR2G0BuQ$WT$32aiEXfrtx;yH z!`~8yDOCjM5btRiS_RR!Ml?*C=VnkflbQd_3Oz+4gjZDJG#3e1z%vhwDjZI{j5iW} z0~Fry#QPfhF}p(VKZ1b{H3iNej7Ekx_K}S{%(0GmgiEFm?cJa{bg0GqO(4@{t}EQ) zIQw9N92mg_VsL^9R7mw2Sj~hrWTQ8XkOdR2u#Vo?gAkqI#5k4#jY$;_8p*ImGC0w% z13*JznpF_T3i4J+Oxwu(F|oF{{h|KJ?AyA~MJyIE?so+4mxJX2TX{rGe^gDeId)$W zluYj;6=Z4H&bPkzz07+1``;1~?M|qSl7&Q>Byu_c!EIuUoLmCST9$3y+&oY>7mwPxC~)8WTZ-F-xOe~1Xq|_1XXfJh1$-8cjNU*lDooc4oX)vvY-^2Q ztfLx}=7)Oc;SFT?BNC%HV>MDCiq_G$FFwt=)P}Ho(DZV1t83|JcVc=#^P%AEd));J1UgP58nm;oFE$ zd_L&Gj88Z|5CHxy`-874{tS zb*ZTOHV+rhr>;k4rJ@kXSOxzqXz`0`OoJ-tMMf@Cv5IVQsubAj!zHRwienW*RotI? z@DOnvLkv~F!r=!5;s;|R7; z3btSieXuK<&|Pq7U;O_E35Ri9`L!EJr7_1rfL@RWYnXOwvJAuV2JQk4{4hxoNF5(U zAQ(sx9)p80!hx=cGALFeeWe3QuwtJO3m+JQx|k1;cO~s|H7v*>v$TU^;$t~DBr`~Z zthkKKC}PC;jE{vvtVd-)$Tm0QZVE?)Ezxjl;xDqgPg;06B^$l@n4|VCf?ap)|)>O`->#_IaOG^Pc(%K?0|Z1`&kU zIB;y45=NM1-zb+RmwZ|ng{~8w$1?4af<_){=a;CCmv4vGig1 zX(iKnle&~4qNRc{25f#-p659w>_RnY_z(Nio|?6v9&vh2VsB|WsD#QTetM``vwB4M zpVt4FmW4T>D#492;t8JMCt4<#5L$eL;(IsBPe(Lz3rdcDFrh_(p(Y_5Zy+O{a0Nd= z1<>^b6|yDvA{|-vXw1Q)F3M+AAZRkGqdyg1H~LY&+6RvqiGg7V1cC_N#SV=j4yeFH zhJXk|N+5V)Ap39^?*NGwr3h*=47b(=;P3{Ua19K2406y3x4;CQKn!v)3{W}@oj?fL zKz7Zr339Lx&S#vX_#Dakk~~svXi5;w8L)+_rfbS=v6v5ibs?gKjSE47B|>BFVkMk# zc_0HE3Rq3DD8G5^JS2x3$LukXKNEUyC`D@lTAA7^4FUnUR_z#hb?Z7d~nadZCwhU=MK7 z4tn7ae31=(01CyRD*w<2uz(74TMURm4MVz61VRmb`?sXP566KA-~b2v&;`5!4qcFH zyde%uFb=)34{MOFuy(n8rmx639sY_Cr2BWrQGwUXC8(<*U|_&W01gxKFksMCNiYh9 z00vqB21$Sm?vM}n5D&2+4}zct@=yp#pbF#KODc#EbV?AHxeS4`qJ#ge5Ea`c=Hk3X zroHvaBh(wlmK?H@oXH;1gZ}vv7JC3NL6+KRWo>enjY_F=z?USq%6++UVdkKlp|guq zg@aPGMllD?fN=jCz{_BOuZkhFl)zVuwN?tjeQ9O#J%AUYv2kn*9FJmkDJSqp1Z{d;CB{y9ha;#V>}_auvn@94w;Y*K{*UT2?jEd z1oQC6fiNNR;3E652x|}_gwVQfkOb)06WIh@P85R3oJBSriIvvy*A&n^85OFdmFUu1RC$n{OmahjD!Z~+XFa1DWDE71x$?eN3dnytr?twM~O@4yBG#vA@{ z1;fA_SC9;Fjm4h32^5$h$B~LZ4KfEC(S(o;Nni)|klVLw(zwvNw{Q#Da1C|<1ODJ5 z@~{X=;0C3z3=@L9{87B>))0rB$P;@IHSHkPhttq2)E@uqOtT%{TPf7!O%Y3yom>aahn`2*l+>EeZUXi{K9)t42A#X{N-~u2~ z2lG$}TT_+DsP8DxZ-hSR+`Dl70TYX!)b9Tz$~FP%l791~aR-$CPf>kOgdyKp&EFO` zj>t#LS7^(CVyYS%z^kh29b$tG-qwl?;qe|E07+eMi0hlfD|($78eW@zkp~1aXOqK- z1$p6<6Rp!qqyzZwP>wE;u(Xy*AZp^0DPKQ#715*63K6o~NdT+XKnQ*R1OlG~V89MZ zpbsSy58-e=vWwe-bLRvR2;bI=H_~nqkGwOT5D;uwnGnfBQv{mS5u-2+Apa3{&<-U3 zS$E(1SE7tiv+{g?vfaxNFdy?TTYKh9CpM4szW;|&INvrdEOr^R#>dKQ#uQ&|LrM?8 zs(J-b`}A8G^{{@KRA2SKarH5(_1*uX>y{DN&&->}qPB*n3814#YOl6zudSJwtI2a5 z!I1`+*nrKE#medWR&zfQodnsi3;>Y~T#`D&k|epd4jir|g0ewNCnpv?eHHB_QI#&+ zH87j}{o9v~&;gPqO`80aPo>I}EnT*J<4@+yng49^^S6u>CzDKk{sbCS=un}AaBg~; zROwQtO_LVU5mo9`s#UE{eR6Bq)vM5MaRsZRPP;;3&7MU&)#+NcZQZ_w8&~dJx^?Z+ zEm!sK(zJd3{skOZ@LfFnJ`1r>@x(BL_B;jL=hkKgAFgzXpg-) z5cFdxC=g^rs5f>RMLL}PNhXs`1o5s%AAbbWDeZ9iAWr8gQ-|Fs{r5HB?bYCAHL( zs5;YARaa%TRaaNdL?&ZGqZP8s-oUI@T_=0P7@HW|b&EUtNUhk^RwFRknfRFvmfm!O zmN-B1csAPG#DHQsZH1V_7cSpmBD(3`c;ZOyOhq@YIt0;?yz+ALGE8~rW#YZ~=F2c& zefP}|meu^h@V)~Rtj|FN6Y+$$J~UC7-~Ij#*x?CFtFOZk2Ocrw5>K3$4FnAtYDGxA zNO49^py7u#9Cgfu$8=wY8B}v;K2k|tw3`W6wv^206S#ts4oj2#IRIRrIO${=oOI%Z zUiPd^CT6+_dt(0>YXIp&kZXnkBP(!Jal;K&_5nl(RiJUB3pZ~0%8hH1Aw$wyvMHpC zLe`-LDn{5LgbqO3EMly(01+pXv`1OT4ZS*L+^S9olR9$AC#U?bPrG|HbImvByj8@$ z-Idn0-q87^&`)>l4VxC*l?pG2H8ytBlBJzM0SEN=+23}v);Bz`-B#NXdL`4hsP(=}}k;JGxfeeeV;oa;74CG-j(5ak9;xC6;-PLcx5||tL+6=)fTne_Lu6@S zQ9IgYBNC(m5dLsS8)-!=TE+?9ay%ic9eBnc$ScRC!4M&Nhavg^ie2ub z4}<>@$An;E2w0$EVz{)J00&4S6B!UFhJevf5(tSatP(mqL7B=b*fLVqQ);3-NGz1J z2<&(yCrMFHlvd(S8)9jOVM3bH;MFvzLCv108Vn=m;RYWT!5)l=(>11|j;&+@9HS`2 zo0=F!skng>(uW%KK?VOX zB9VRXacnU z17`rosj&u*Y$)i2!~y>b6bahshB|T?UX}Z!gJ>Z;S^$F<1WFGXTt^T&`$;>2qFp9* zfxFC5(v%1qv@0#cuk(uG3^}1n_KXRKK_yHk>`_Fij3X0qO2$;S2B$(?V;|~BMi*T0 z1dDGCy=cwg42OLpiv77Q<#ZA-OElHw_FZ)xOqjLno>nPViJRek8Hi_ zR39_C%a~5ZwNjm8QcSDYX%&%Obq#H7>@Rx^s9Czf)^XCBoV6Omtz=S)3rzn4rz8|% zlpfCE^EN@A8}W6xHN3(bpdi@B7WR9z^uzhOY#(4?s2$Q22RD%=OwJC7vp2EFAmZ%3 zd6>37)@(<8_<_wnprROkC`L9wk&R+R_OX4)W`Ixui#&fXee?y237KHWN3!vgOtgc$xA4c&h`|YPw3BC_ z_-oL()TO^BbZI+z8cyB|RKhSKh(6RoI~Z|*VL)Rlt>-V7o2O)LM`!Oq6UT4e1U zd2rPDOOpGb1}Ho+WVK$YO!TglT;&??3rd;F)0tkTtrytWdD&sK43U2#QRhDRf*RoX zvwiUQk<1PgHn0E(EP6>Ba6GdqDM>S=oSD)60)`rfwx2qA(*! z;_7?;(T<*Pl-rxW6bF2e+V@7A>e+Pdu zRULR}vdVCTvnE*!XTGr_Aqw*P!xNsELnfOu?2GF@EO46Z?I&kSF5QS}=()Pnuy-$$ zOK4z=jSzoOFyqoo@KYa+j+00_7=k}-%c36!_kcCJ9z@RIT)2A?PgCb)(!@QGPt2PRm9Ti}FjU<4izsC;0C!27F%0zu;9 z1chQ6pKz$58VuBfhSSpmXjlf&yM=bx1kjT&JQ)X70KNZ00S6Z-f@^?=C$N-x$OObJQ3sd8FcVb7MI4nhx*WFXy-1WqSIIZy6F#T71es_t zlCVV0h%w;9s_2WInHv!36UEfn0wYKr%b@ zvpX=lgrSdlxC3z*1lp=bV%(3?s5%F#G~jv=69L8=%DNk=pij%in8^_tXo+lif&+*_ z7bJ!Q_ym23hkVcnn-~Y9xdy&r0#_h}7r2HsV1oZ;u*f5ngLj|;A!LMKyE5td#d>_F zq-hP~!4Y{I3@x~YZu1I?s+wEKglfBnO@NAmkV9)o20(xckGcjwRE3Ag5iNL|MHvM) z$%a~Z6PPNCCtw6D!5DyFQ9_Vcmr0PiDvMGU`hsBtVLD1#j7M0k9!v@BS|o^7x^eG z0g6BV*auJm1yqQHL70aHIS0@x5JR}kNGJ!;icDa@34Uk?U)rBY00&Sgvp$QsYXk;h z0EKo4kazHx$jk=H^fLyr2h?Pc*JO})V37adye)RDB}n){2=a+7m`CJH%vBOWPFopI zBTP~e4|yPik|=}~EQEB>#{`;oV1zXw z1}&6@Uz0+DVyNbXp)E;CE+mX1XhX&m&_$s`oPv`9WjxS}3IV0VN@38913d(#LmwK@ zN1Vt3Xxf$A-%GD#F2dL(e40DH^7CG&;mj5 z(`=}Nk^qln$OpD_2W9XHYp4Taut+Abhb|ZcLLdZkPy{9*gh+h{a5+LI*aT$&JS`Zm z{ghLo2pXgSP{M$=S4mZ~Sk-#RjOdBOK}IGs%NhheCTq~g(7-HTnEvb{P#_8Qgg%AV~Rto{g*$0Wv?ix}{! z&0}&6bj7g?S<~W-)1Sb!ZLPxRlqcj0RBCMtt=I(aJb-yPi5T36Iv@{yxCebuHCK=Y zaIjQykcDihPoLlcYcNlF@QMFU$c9@GhbN4}P}Np>or!xDs#_%td?nco?NFi;*_8dt z69YwnTZ&%A5}g6o$Y9IUc}r!z0{}@@oV^2P9VD6PK8(A!X)Rf~Fw9=;D|x-1Ft~y< zD7j)BkqM&#gfaIS(^Qf7QI=Vl~IFJ*1M!C zpw-c?BwD_0iyw`ikgMCESj-O07^%$ziQ%d>J=b-04Tce)H9do>dsmTxgwEYodhIkp z09nj!34tX%C1D1FDk1+RIU#zXA)r7S*<}KhT(+QMyufuM+;v`#>rm#EUVHn!u~f0b zJyC-~+{8_tsZQScO%vg*tWwpZEnj4u(>&0w!36S&)QT_=OG5 zV@dc04ff!~q}}MW-B{IK!uyFQ3yn2RbpjL#h*p8xj5+W(>Q{zV(}|&d1y3x^)=_chM3~ zcs!xtT^>jV^)L!KAc}wBYC^CFeUOK>lZR}eSf3aNh3zhTV3TWLf?;R|HmNd$3MP0N z$;3on4%=u{@#wyWqrC>~%*j=SR%Odz=)-;J)j{RVK;l`hXk(S!T{*I#^}fJHi(U?8 zYfXlb4$>@6OekQ3Vm4;`#b1^-x!T+Z3mK4i;0JZ624|>-)JBHc4hCdE2Y&bkV^E-U zW&-~^@McM10;CS)Sy%<7Htuk7=NnSn4jWW=i4Ezw21bZTPH3k(xB?<%f_%8ao>_xz zsO}d4iZ$@TMh%K_AO^0^*zddtg*=*DxJV{YYx*3DHJIy$o(|6jMi~ZZ!1n9@&LPVN z@WNo(#r7k%Fb2y2VwxD@nT2Iy6<^hO>=})07@O=}4)C zC^c>HVHi@3jd`es*G7kbn1)(F5L-ZoefWieQH51F=ivVB3;u;k0PjCO?jZjOrnc95 z+Qqh=j$6ovPGB1;D{yP|kOeXS2|4(|GS7w^tcQK*86J>>c>oHvRs@lt>YreQW~lQ!SK55; zumI2WdXE`P$9EG;jFxrTelzs6bmblRL;{zL@IA!{&)G+Z^d`1ZnSf%A&iDVnz;t^* ziT4d=q`~j;`Up1PE-oHz(gtHw&k#khg#c0YVE8XrhXhy$23sfvNEn4t802;C=HgE3 z;2z{&*ZHAf>Ur9cbrF^3h9504uPnBQjx_TwD05Dbb7GK(Yv2KRAXs;Bhxt5)@Xm%= z^NC>~?;`YxGCxRtpof28VM0*rHV=wsXw+<|K0AMdjBn1o=CI}6Yl^q~MvVBppNc{6 z_kJs#Uv=dM50)2opKS1#N228izi3=`cnjBiu$cI}e~At6>`>*BejW-}GU<;eb&=-} zM)(Cr=z}+??RP+imxlyfa0W;agz2 z>G22FP??z+51+T)?sSSHxAR>~+V;qXMpgEu&jg?#gky+@X&?7BxOSol^Pq@wR{#fD zxPnU7?t5T{>lX^O?gA++&+eKBgMxS2)o;D#bIHg59(nx7KV`xOhywx#5*+yEQo#c| z7BXz;@FB#A5RLu&cS$0~Eq69@?C9|$M_BwulHBKSUp81OBY|w`lH(R57$aWt=Py&j zoH_^U=;`w((4azx5-n=;JvN;)Z}m9|zV zCllW0s93x4_S;FzxJAsPl*%zygI6%I27A(t^+`VY#1l`eiU_z#T5D{g$R?Q*(rT)K z$XZXVpK#KvB8>2W>?Z83k?dJ(+`>;-cUpRFo&Kn~El*^6J0rK@iaRd3<(g~Nx9O_8 zF1s?iF-%(*ZTTaQZxl2yz7Jh8B)(K&iDfqLL@6b~BW1(Vzb$#8<(6;E=0=F^N-VLN z=URO6ipg!|W|Uxc8mU{1G3VR)|m{(Cr&(eQDK{X zHri>UO*Y$YyG^4THx`*MM)mqgH{BFjgs(;kza&z@1t09U!uZzY&oB^!`8MM(R;)JU zkw?WQSIxO4mZ(K{jn>I2tLzsZE{lFfT376)D4sWWNp#??2X6G{v6o!uKeF2nSJj_f zJ!#WUGqd|^INy$E=9@@``XeviJ4SU0 zLidJ0uaFhZy=9Vww-kvE%y;5FKLFvW2~1D_g<2AOlJBOY;xW|SP|E*KV64R3)A^pjs62tm@NWe$4rLeOfK!9C8V zg)aPKTxbW#*p1L?lqzIC0s%a;Z~{&(^y45|NVGHNBzhYN^P)!p7q~0o(j#D;SC?)wMpg39l*TmM z0N>;>Hr~#SZ{$lH1qBy2=w)+aAsQe1*oh5Ba*&wnriA3c4plLs3(Ekd7yceQ1GvfP0ap*WD2{^$*Qb19H+ z*-MTDj($7k2*ZqIQ!y@1rP?zoQZJUwj;)cK3Zx6lo(WAv$WbtKOp6!tf;!n zp%a-}Lo>XyhPt|gJi0?mLN7Rye>CG7Xk87_j7L$W6d{xNSb-%Ek%i`Mw6x0e=<-6T zuB5WIwQ4geY*Wcf9MKe}PP|)fF|x0J&~{5!{AoxC=2PG<41Et9W^CQ&+U1rjjUBt3 zSZ(LbH}>TYjY_ubtmrf85Jtoy*T!UX7eti}jQV3&zuKs*evWg3#|4bk9&Lq8;y;XKJ1I%co;ZV_n?PAVxOYBbcVjWViJEg~ng`fantsT8U5 z2AK-P#~87x`uIlVj*w)yM84ma^4H{6k5tvhR@0QBTjs7^`I$`sXVRimvybtt+CJ;q zSOuBp)np?M>OKF9qM6{ISapLKSCA_c0zr;&ydodE*pENxfoFR3IUoASN1zLw50nVV zf^blYW>4z-Y*-g55T{Zu^#bqvdB+4zfJhBOoM=p`wc3ek8PPxic0(qFA z@8!cDJemIhulbB=g=0C7uI;uk2R8U2FQWf>bh?_&)wj8u+D1KU)@+txWa<{(Ax0W> zArE=C;uuUwhjzq~ido1*5?zpo9ezQMUpQmEZJNb1yzvSBq3pdMG_0YFIJ`VCX!_KfzrTzzum2davhhs(crbm>Oex+& z;M(5Ii%z8+EFf9R1yzt7S5fUBjNu;zrbx0?SqPmT>}d)oWDe_f7p1j@(xn+EjKes9 z!#J3QD`Z1=Fu^h`RzBQ=KDfeJ5JNT~!(+GsI(!2ac*YuJgDh|c6FfsXxI*%2K|QPk zH^l$SIv~S4>_atpgZEVgZ-9d$WC9~Gf>~t4wpE%*A;m@YgAQmC-nocHd6pQmO9ieW zYe}FRatMx@-2XwvP|Zf-5uih)&k`ZvJMZRQ-T%gVoBqUl;aQG2;rK8fI z8BMmv2&Ir(Xu&W10w+pBFgQasP=+e3f+*TSFgVRnilSKvWKU*G`h8(hoMAuo0t@Is z7U+;@t>03B>HZrseUpWHG)PGVVkjW{^nQnjXsGOeEm0E#OH)-Y;#*O2!;p z#)w)DW{E7~b75dlf|Kf*6>H?AEK0~aCT41k5In}CV-SJ|uEQ^^!!xA9DE|LK)iA*< zoW@yDB|&=NRbpi_3`Hj7ko!G>r`ga)^$>?7Bk z#BTMLk^I)=P2*lRpmEuR;sB;^x(IJp=ZGYmI7%iU)r_VH$fi(A(rM>v_zn*Yq*@Td zFU-RQ1%o$KLp6-T&Der4I1Nz#0$P~nCB6YIS_o3z0y_-D6A*$w*uxX(z$lnQG8BOp zm_$FU!zi#o7hJorOGV z0b8KMFW5shphH_|W-B6tJrvC<#6muRrtS#kK;q{HW=k!a)GZLg0oVa8=zu@;#3*Ef z3%CI^xBxojP%mTx8Gu7){R6^j)QWvl7>bq&)LlcSi;gC0n%t=10jG|^r84qSita%A z{DWPNWFMB~i|(2i$b=v=8A~#%QYb2^hKOM{Vv=^DO$sRniD0UtM(>6v7i6fSdY+ z8^mHZ9D+CG&{hglIM@n>t*K`VemCg{LE^u#TUf*ZKOIvm2C9>OMU z0wat9SY`nXJe&@YL5i8{Mp0;mDx7W}tkhBk!8+M7K59bLYc|bgZLMe(?W_ARU`H^g zzj~@l5|wmT?et77+g=5aKIXy>PdR>ISxM$?5Cd#Le{ z6Wqpa>@;i!E!1=123Z`9PD;w%E(4r^MQUUnA&h}B@WVZPgT~Usefcf=o)A#dq*caP zJ*mPqsDciFLo#SzGTcHY*h4>f!#V&$CS*bpSi?G?!#bE+P`E%DvOpFT=);K=Mj_k+ zmm#7iF9mmt@uHMlV(s|AZg3m`auVQi-Y!JsuKVcHNKna1qy#GTYm(uM$k1r0Ua(M9 zFb!8l!p@}gg4wD%8eDuA^&)A`$53*IfZ4SH8+`6i22r*cAV8=`rgz=H4@P?39L|B!IYh2CM zNKGI>F|5RDB2^{PoN1H^g>9l(M|oP_)zBe?(h9J$=~5gaqi!IRQ3jW2Oo`k_8lVV2 z#N+K$(Md_~_EKNUXg0=hEtknGFSFZr-eKbKA={2_NZ1J8%nm#3Y`jMHVsoQGY$jt3 zdp#CGwy&`T#TlknPvBxJJ0vWJ7FZr?)H45byEaY{6hbDzCWqAXJ;$;HI_erf#S`_| zq=vAr0hbBO4=?SM@Xiw27H={G#sA2&L`%gD_h>ZFP60_9^s*|ME%7BUL!@zYM_#mq zRIxu?ajLyo`-P>bbreg_kPd~?In(CEOtia}L*qOF{JMbzBZW?1Ll?AU64A!IK1GiR zbc#MBzR)oi*|Gdc-cQA7kPxqpKD0U8G*({-kCGorTS^~I3g)n?rKW~Q>&7VbhDf_b zSHs5PUK~&)2x-9K@ybrc=xp6sWC2p9FH;M zK$l!W6WKva3CrOUAM1!8BXcriHg*p zEr&p4!?pH=7OX=Kp#vc7si-}-IP}CY)PWX&gNeIAim!MVWJ8%G106J|`^ogW>VPU} zL3O(~UK2QP<}~~k0xdv8HeCP1CV)XY0|J9x!!-;8Av}Q#{Irlm12|YiCLp=~*@y@C z^1R5}d@IDH?toIy3sZZMQwtYl^Y@bJ4}jOQfcrR{7kHZ}(;9L0gl|V^%MPa~@|^>c znOb<1K||sm050%!PcT9+9=x=xP+G-Lv>-@-Z6?BKo20pwVGe;loaIi)VPkd?U?JvQVmw2n}9 zn;Y+&=eoMfc~=anXJ7yHH-(UC_j%B~_OZWLRY%M zE!2V=U}P;M&W8blD-45R>p&quLxUcIio-e?-~<1P);s8c7FahRWPJVdxQwj(U;_C* zj6#9xfEy$OpFROCTmv9{8l75$4(PN$jDjlDX{-}=;Tg7xemS?-<$dp(7WG=12MFROe)Is!cE-mbX7LdU; z+(O}}^DRKWPS5{CcUwN>-#SY9^Gj6)`RMXT=Ihbpx0F!B(lfma&xXKm3&Bb~;?I87 z&pA_d%Bx1E*5~k_*W4`>fYqyMi9ut1{o zFCf(E-sg}tl-S=(ybjDd;TyhS(tbArc{Uh&a@zwSXhA!ug5Iw`AfUG!G^8r*10ayU zN)0uacR4^D5IB%v!2_4x5ZtklVMB)xAx4z=#@N4qmn3GS;-$|Wj~_vX6gkpkq<#MQ zWkb}FWJ{MHw;0J7@sdBAZVcwsxsxYP9Y28v6*`n?QKLtZCRIwbNKdCvp+=QDm1VI4YQI2f)aCazGUeI{W(d)X_O4ugH_o{jRZ~ zmC40Ae3^%_C}K}XHWxYo4f{Pz%kQPfgECgWoOyHS&!JOAJ{|cJRoC1Y*D=Z-pf2-N zJ<+ae9w6)2v=jlVsylV}@84&#X>4Zwj8oqvRA`@n|AlWX`sWS*7^32(16|7I9ati{ zgCztZ^k@qL7plphVQ`8rD)>0;&_f-X(on<^Ni5OC6HzQtEVA(8=d85WB231@@cL)Q z8*%^4QO6x|d}Eoz5=&7?odf}=89M|5M~6c+v!{?Jis;9m&>XqVp4T$lXPwM46K5VS z`_YoiV-6@H8!*7R&6~=0D}t7v;uz*9;>a zN)>+G2z1b&T(QTEKPi3BjbZS@h{8>G=n0|yI1QDdODv*q(=8%Q)gxH=X;9Tvso2!Q zVffUk(px_avDRIA?bX*`@mw*P7X3kslTLU{mWjjkQr6jLp^bJg!)!{X4q)-rVFeTV zx$Te@n9R(C5lk?_g(6ftqJu z;ud?J0K=GMv;gXfVa|ENy7C;pWuJKe&3GvJ{4r)gQA0K8(}6$+xuT0W<>=K2BZ=g} zm0j|JQ)6t(gkOR*&RHm3Z|>RWpMmyOShI?SQCh&L74Yb#nQoe}HwYny=xc)(5h#4H zKBS0nwGQgHETCLL2N-l9L)~@V6<6#fyX~h6ot3Iu?z!iN8!7AdxdmfDvPlNSOxj^Y zy&?z!hZYyC^GENW`1afGe=p6nqWS1CVrwB+PQvKtA1VUBmUJ{AXLC__qBT(vYLOuXe=XK@t;0Hk%G}{%= zSjf^Hvw)XE6+X*H#50SvLb#ZpfU8^TYFiPccbpZh;Cc8k4wJl<1+r~0IWaWi5w}7_ zhi&2(U0_5qpmB>jfbR*J7{)b{kqI#T2q7blfnX&bhHa6qye#{j)g% zZR&F(=|d`l5sXxTt`NUaghv#SieIdP5iDVZGJ{cy2QlIo&7`9j^hlstol=P%MCCWZ z8P2SX&_%dQq>fPNNOi7rE>M%&3y&vGtPE~l%)8AdIap78kl_ST%GxV+AWwmM5TFGO z-x*DXOa9o>EDGh%0vqTb1C68)!eoRZRx!+vP}7(W`o%CyQO!FjqMEf}L@)|5h&!Z0 znbw4$%r-?cf2>ZNkMrh0ahg+|9)O&~^LrlBCq6>p z$$}=8szEd8RdW_Of6UUM60s1`;@H)Pz>!mP6v;E4`3sg*G^C7JX(~R#(zixJrNDI1 zFspe-Rar2XGNq|b|5a7N4pyFqd{OQIlg^CEnN;EW{HX; z&^E87n-J<$2U{#+TtPe`cZ_=QpcV^46i}C zo8APmnc8G@T%G!99Xkr;V zr@b|fk1SdH5c#S$p*d#A$$Biu2=&1h1ulhym}!QS9j*m%%K;v6SVIMl%a_L!9OtwU8eGV?dn0N2OYrb239umiKIj$fx(7cL>V@ z6wZCFq>TZsl=u3WA(m6^p$|alLX&krj^jfbR zA(&D~rnK@i&PsV|Rj+ziJq?i2)EsNTIJR1lW%U6pc?dH9F!gzvq4U|yHNB^b605g1 zc25GGY@?J`(K|l0P3Y@T`|{G!FHuBFANpuJN|pZ-TjC*u1u8NF>}J3iBK3o$q|wK_B|4tO)A2^Xb5^ zt~)lnNRn?(yHH$kf^%tdhh-D{oXO7Xu8CIkeqKAP9c z#PbI{X|v438}m4cI=tZxbSNGrs9;1XE;?LAFrpC8FGV4S8?($mbjzIg{QKYEd->0w zAf%6a@rqUT)JN;!{>Wm&MQD>&gr0z%*yHX_HQttrU+dK;dZc4K_WD5wvY@?qP{trI0&G?(B}yD8#HNs1H!0&CoCn+e{@OLdr#{8cPrfAuWcd5RVWM%gG`n zNs^vUyN+iO@$eG=q!zi$5}C1#v``cOM@1BUY}%HO6d?!|&JY#(ff@|q1y^SM?BlEc z%GhKv9n~@4oUt8mO<1BX2nDW3c+nSuF&NJV*5k5Lek(H)@z#-i~!01~vIaUcQ6 zM(1Gv>BqE_3Q!yOH5zEN2J~nR-*RdnjQQrzOB*W|$@sH|Y#Ol~05bY5d z4>2DtVjqohEd0?QMe@%O@;z#jux_%9+-|EDk_&&b&;sNWBZ3U^NI@tvC04=>uZdH( zsRlhVDy32fbFwPc%LgS17hAH;^syMTNGAW$DwSs^-9s#?3L(*;2o@n00B9N)k`se+ z2e8p|w6PS0vCUMGbRzN&T9H5hO3mM0n4EhjD);vpq!FF^tpC=whm5@wF;g5;1R1@kon6EbCUHtEkX z%aS(1=^&G>GB2|?ds7!;VG+k% zGY4^VJGqn9Z1cjplba$C4JOk!&C@)Aa}kKMLpt*(5dt*ll0fQ`j#z~sCWtgYBFpwD zgP<}y{nJ0gGe8A2y}lDX2Q-i(@Dt8+K^YV?HIq7wQxoAbE`h8A@v}6uff_CpBt}h} z+K=Cg;6FulMA`8`P4qT7D z?~XYg!a4Vn+%^;@;P8!TP~k|lNu88Mp)^WkNFY^ID5MmGIPOL-Qy1wuhyave;6`^;2f&m#)iM^eltI(7bW$(#6LeuXdz2a{ z)H6l1KZvwQLv>~Uu;~W&(;v9(*i1E5wN+bVwOhUQIbJnxzEy4jO+kHA7Z#xdb_ND| zvr&yAOoNqHe=`$KBBI`sO<61X@U=PXRD$ZXLnq8EuGQGGbz2SAV8=CK74|B^H7OPr zXlhJeEz?$URVd1oOOHchdlT9~Q!e*atV}LtqV-kiR8ITSKK`;)4|Zi)7T@~xVPO_# z8`jHW_GZGz4WL0NhM^FSf>_a2U8koA+7$+FK}n9nTp6?;;4TfaAtDrE7#e~K#vvl+ z02+4S7KrjkgEB}hv|nAuWbc$zRkmfxwrpRvX3>^VXO?Eu7F)un2pUEUvLSvjW+=+E zT~`b#Zd4cl1mR4KLSuE|6O^GhGvW#&f(od>2rfYpWFie9!U!0l8Fm11XM!R=R@wsO zav9=T@koM3_Ej>na$gZd%eHh)*Jax_by1W`8&-9JfR9q6GR=z&Yq^eA+-H_2ffY*z;gffiI@P_$ureKQs~ z;Us!95Mlr#sNfbV=MvK37Ca$w2>~I%;TkTXd>4WWIst1JB68)D5Xx5;hCvoI<;6+SmrrnOqn5nE3;f+d(LUAKZ|b8U^nf_vpd9HR?#fDo<$5OhEb zuAvD3pkWjMVHB*P2;3kWiXamNMF*0h5WqkjZUGPo!5-)#AM}BF??E13A=s2cylzw( ztRXvGVHo0|5WqnYbU`2Pp&qt$5oDoWkyaO8AW0V@4ZvXs7~vQ?;S6p;auvZCs9+gH zAq}WN92R06F5wJ@0cz*K8e+hIci;@(;0&_C6?PyE>>(TY;U79-Ynzonm~TVvNKOG( z^8_~I3U-1a`E<`#gDDvxF*t)OSx zI6_WVBR@1xBRQWVd6F}^pKJ4y#mAqsB<|mBd zN#>zE^+A^J0bN(18AKR4ieOQ9`5S)XV!U*giFt?7l@Z$PfMQ^8v)CcH*o%*0A+Eq2 zcA$)Rz!(^pn-`)JnjssqA)0G?7&L_n?4cQI#3I@O9KhiQv^dA$)LH3Bg1$B+Jhx8k zc_vbJZ1wr8!CIij8uS1RnI!O zRjsV=M7T}lPoO~+GC>EjHyMgx6Kdfn>cAf$I+X#zXe;^?_Te%!S{jbQlJ?=FL0Y8a z;U4T@5%gh)^PwJwSsnr*6Iz<9#`i`);RR&6i@(^W%OR(UVF!$Qo4dIgE@6Bx0ly{p z7F@v>UQ!_Z;UAiIa?Q8d;F*^qvOdu;wqx5LvVpcQR6j3hbV>KOMSR5n`PsNloV$p- zxKBJfHW@kCBRjf49eCCa+Cdd=VHCh2cvHCx>_HWZV1@%Bu`M%}d6*oO0UfeIymR@a zX*nO@K_1vUvF$(}pn+o{0{_#DQ^9R*oY+U-w*+*57Ed7%Ul00bgoov*?lx&aL+KmoR37yh9jNJ*D#xiaBFA9&uF z85B4_K?dwSP4Bi?i9i+_{2w#{2$&uS*gz9BLEuTyCbs)BU%|dX#@QGgtd28t^Bj*% z5!=&H+anUUC!#e8{o~cX;}Kot-5z#GzT}OY86Kbyl7SNc9sm-s!X2WZ1!O@PqTmAF z!RG&nh_{poMnFB*(%l!dMi;>j++7!1VICSB7}%icF(31vKI;7e)ak)RX8m&IuHmhG z3#ok!Nz)`MUJc0}k32k=K-@Lge)iSA?ce_P`6cdu;>7jg4_Y9Z@8J)6;2oNMD*OQ( z65tg6VIOp10%#u9{s`yu;X%dA1d;#-XcTG9ltJ&oB9=b$!5{p`pf~m56bYWzH_;1G zoAeJtLRq^$4*4jF-{MJgk=YMVGmiH4fB%gR_W|O7z<~q{8a#+Fp~8g>8#;UlF`~qY z6f0W1h%qBW9UMD){0K6n$dM#Vnml<@qso;mTe^Jz2~*;|KRw?4+h+;_wTkdKsNtv2 z(uH^a2%ImBhtI8C0n*`qb2^)~#H#=Bsy%4Un;9%bG2Vgqc=mGuUX- z1k4{le*Ws#HFoLJn;nC`nQy^cM*_L0@Qd;jiSo+%5Y_I-P#v!Xm+9B!b2uq20i*5h)WSqWW!)K<0K>h!y4Hfa||w2eewxcTYch$GF$loq7O67 za8`+9&9KH+CAtNdTy)jt*gt{^Bv@ULrG{gUh#BLUF*+tTS!qIM2FpI5br#x?N?NwX zkB1pk*D$PsN2PPeU5RCuT5ic@mtJ0ZKoV7sNoJX5o{46fYAy#LeQv%9=SOSKNvC)B zpg}fq@x*8Wksg_jv?PAv!!^O(q>}Vofqj`4f**@?^4t4lq!a z%o;q%vj$bagrk5+5s5Mr$(nn>0RYB{wAiMRs6VqBiZC}WNOT;gQ1 zk-fp=KgcS(0~KEMv1GMJ&Xr`fOHu*ZoBTj3vaw@ zwwY+X_8ui~zWPFBS31{(69pFURK$!0ySyWhE(x46-<$b8aZ5J0FmhiZ*Kkxvo35xL zl@`_%k_<<$Xyr~TpHh{HEL82o1XZ%MQdL!|ZdH#z|AezvtvZJ|qOWF+u~rVhuJ{%( z1Mx#_VE*_BZPSG{_E^(YXj?63pJhw6kX~@B>>GAvvM;>pj!kyiW}iK7*lMrMcH3^Z zdvDxwi}ZHg`pOf_!j4VkPb@ki9nS-h$Ttw2fHb3nDz^Z5&3$nU(@_yxWO5CFMO@3zj^jbIFS6yJ+y(Ze;e-D26;?u@``R1RGe))5DD#H~?4n_A$`3f)z>!QW$|Fy>hCOP*5n3>U z2!((gM?RsCeYhhZRpEpys!8pyBP9JS8MUv@5aIg zVBl(a#WP-Bke9r}Fv~H|g4VRGSDHxd!$sLZ1htSzn$tild;XXb{HQd(ENXF!T=dcv zzX--Kig8TsD`VWoh{omr{DT`57{L~HvBZk}Lmtu~0ssb}gi{nH3IPy^;SgsJEfm28 z`3Xr8Hj#`40Z4NlNrF?{;f_yGT_`IX z4hEv&5ZaXjsq#mMC4OEfyB{BgfrZI#(_W`WMUZ~VMLn%k&QYeV;IS} z#yJ+32^nN49{S**4E9kKCdi{In@|~5)tjYY?GTvHa5{4tDdHiwxst*K3!Dbt+lbf;{yrcd3( z)1W%UFRuBc4r<{FjzHr+Zjh7?*x{%r4C59asbCTQS*m>KV}qYaT|oCy$z)ha2Aovr zKQNJlU3pHFq^zApcZN!*j^AfpN)vXKsX zY|ts4xJArTw+wPrB0~FEqRo!c1`x$HAEi`lMBiGg15i}0v^xlhGy&YaO4lrV^&v=O zRK#RS>z9cC-Hb}RTNy8)Mp;zcUT0Mz+4QP+y=FVFd*2J+h|o*3^i4^8?~9T8M$Uv( z*~%jLd(dR~F zCK8e0E_kI#UdH0LBJ6Fki(gDGXRdh0H0G&(Z%mRJ>v(?|gvzUe(7kScHFBw}xbx^&iKGp<0KWXT$z?8>!nh{vqIbq>sZS=IIga>t>0DW zTzBNwI@au-`TS$8=t5NyN+^-#Q{WgXdbvq9Wuu{-k1;rb(*7tkgRiVgO^-zrF=}O5 zSOjWk6*0u9z5^^uTyDj7jn%w1$gJND?|9>;-Sn>acXX|5d*e5=Cj+)swh{=k_V(Do zm7$WI!ek%B^|-cMNLpVgANgEcqFBao4r7E@TzwkUpg8xK2}|OS6V?k&^P2Yb9VU6J zeB~;aG0I;K^OfK`*D-gm8M`0|H}tzIgjhq*D;c3RI6($kp$9jPArBbIM-~QdLmS5b z(DbK2Iv*5;_JVcRkm1TD*%L=@rZ>uM$LKJxMJtwFVBvAZin-hj0qxWfOg7SvL{pcWGHrJf717-8 zxeI^z@!q@f?LObU*Z261P1I^5#}PMxW6#+jM9kK34c2)zLh0Z^H2V3KPKpCWZ5W3S zDq-z5jK31aAip?_3!;Zdxpt*L#$3P;=|!)8|G2ZECXm)?XAuN94Y& zdb7fRQ>ZgD@Ol`RVPbHATc`&IXlm3DBMXRjN)mGECV@KQEii?0MUa7Q=!UZ9av&&& z`{sfAHHSF`C#oGbA-@+F_Q`DkPX)$51b$a=}<{S<`3|o75dNy^I&Az z&<6WpWZ-a#PzNIEFb42tJnqvS8-!8fWM;ug4ysTG9kFvVKnU_s zI#uBW))yfIWe;l*XiKz2_$P^&7$TOq51i-&>d21NkON03iazjY^gxRCH!NXz3~jZF z{8tIbrh5JNJ3&y31xbsyhzGgo7%;+%m7#mP*L%wIcJ)?_$Y_xl$!5=}k$BjQ%eRrw z6en7MNC$L{oRAHe*S4sdb{s-Oj0;0nVa11cy3PN0%Z5C~47 z1&hcC*hnf)Fbwh#7}e<*z{L)2Ko9q@LChczPUj0umjjqcX_&x5W!kRdehOI`7 zvniny>SDFIn-|(H$(NhegrQdyCz}9UiYNoF@Iive4&pEl>@b7J;Eijr4E9hL#PBMP z!4Jun1H~W?IOr5(a180dbv(L*Ap)eTr(ko1dg1U6`Dmc?86uT=pE1;m#L|>8v}j8Z zpjV2ecp#tyx`oGPprG~_3Ys+}CyZ(cn-q$sX}Vq=%BFR)p_$dD>C>BU;%|KBh%#z3 z{IH+3qE@Qdb)jgFNeEFy0f1ksdg~c&SNEhLVt-P4ZEnQ|SSqQK%B6UKm0!wb)RTaJ z!GH^T8C{tpUs-djrKY87s*n|@sahp(`ctZEK6ASN9lutmfM#rXN~2RMs7UyyiuRAF zmqD0HXtwiUa#Wc!t-xBX1&NT@YIY6DB-pbW%1El^>aiaiKIhu5BYP3+ z%C02KHt(7g*C?+Mf|s1o2@0jB66K_;H+8h4omz1ZUs|IR^=OE;sQIa%`xmJWYqZYF z8PhtkqKS|SSuFp+iw%k+6lj(m3$j;>wPS<-vRg|LCTmSxt2Qc&67kxy2(?7SzzN6D zNy(b9@|O=xW}j`l6=^#UDdZIKFleTUtMsX>N%@b+y0@kz21iS{lUk?-y0n#QmAD8C zV3@6;_9G9!k-Eu%=YAQ`m}!yQkMywANd=un@jn1`CtQy;La%ue5Po22zG0swj)T>x;uV zyc_K+zqYBN@Ov*kJikZbZ%nWWu8>bM5VN` zE9m!V@jwo>V~M6$JDS)A;1D9>AYtwBN%8;>dif8UVj#!H!P0ABR@c19^|zU6ZCz)j zCVaw&tHMXy!UyODCIW7t_Cph?xi_rCj||DOA;cI8#O^c6>_WdEA-aM`4xF$CxNr;+ zg2hh!53)cA^8k=Yzz!59z~`s`#y$WC=@5jq(+2RU6=1=r6XpxKTnW4jBFEqhNCSTQ z5D!WB53xeb`aom?5t#hBa3GA2nVGz|L%o1}v`HIo+H1nlDw<2+N-?a96)3-s9LeR3 z!&cnq9?n7%xof(gL2@(;8u4vyv& z^>7a%A`6(%%M4wZ&D_v{SqW-!4+>ou{dCdp;Dj9fgUE%bippSr3%IMdu-06-f=sQE zfYOw@y$2`;-aK7b_z%gz&Iv)z=B(3}%fmPQa_YR!KD{RHyvh8P3?jOS*Wg=YzzOV7 zsNetxw34FYaH2FhnELns4@f|M;Gksn;0|j5A{4#LVT}oi2_nAG%T@fZ8?9UWu$^8l z5BpGH{d{fDJaNa0G!%(_+Hd zFbC9gGudfEzwqp1M}1HOXAf5}WKO7=lqL`Dc&LY|Gd;M~%KH^5L@Vjp%VJy!X`7C4 za10Ax$BQ4qhIJ2t<2ZU|3*u2upZL~{ZVNi)HG%e1TjS%4q z+1bt0*3D~`EjQe4CZJo?K9&i@FpmBJ#qyxGd3p>$=mSE?e(_gmSFJPVP+@2-T%IEj zqNs@hy~Sfd-#&o<#g%}@InWCFKo9glDn*#!`T*ABna8$+dJJbu&wGkaIL)?G&CWfk z%sto~-mGkZZLN0}7gy8O4c-fp)7s7Ar<&q%=H1`@;#8utn(c4tP&_Be3B`gm1qKf3 zc?<>qXoZ;I;0yBrz?hH@w~aGjp%1b! z4!H10VGa%%t~0}>l*D7)Xs$DT4dRm8xO4I0aW1J5K0{>je~w|(Gma4}-r|9drakTF zLiNKj4pfEi9k6QSz=lwCkqu+82G2{Q=^1}*zzH|`o{C^(P8W|xHU@BTlTL?9^bikL z=5(W83)}ivH)0E$HK(ri2de(1_^ua_-eJ zr{m3Mf%e2>zymv;r#;J`oJpmk)TfI^%ax{=AwpqI)~~sm4}lQjS1=2@&I$?d1H;M; z!SD-U?E{nW3zN|7!GI3_;0@Kl@zwAQ72oi`APIp$@skik8;fZCwQ4Wo6r@qw*Jixy&;=09JD@9r>l~CNts>M1p zyL}4(N*K~)I@9b|Kr4dq3kJU{!Y~WJ@B<;w>y^L`$9@ww;}4Zk2fuIyK0pbp5F&v9 z_ZrTyE^lhp{thhd@>mMpU1zW}&tElP1VOJ6IluFZZ;^-(l0Sbp39owIc|#U^{T0@+%w)yATS05BRG$_&~>JHZS?%&iK_oo73;1kRK=5zZ~U2 z`JnP5@}BgawAV~8q$;Gge&QKUH~O48b*B&iSHG`UKncXpLiz9ukQVV&)?4cU5Z;3S zq4UR&UmG8jSovTWC|DpLS5_@#SP@Phj2Sg<{+yF)vjgR*6mxkalal&BGv9)ym|HR<=fZqU%Wa54<=mL@L|M>6)$Go z*l}UNktI*2T-oy7ayd2M8KTq1 z=;%|^32AgAZZ~GO*+!R7K4E3IUkE9PpJUMRrW$9wIjx~zRuY7}E7o8|l8V@f?@^6L z5{Vj;Ahk4)9qnrgKmC$f@l%_MKyg%3OPvfs3R6{eRaRSd^;K9EG<8=0T5Gk{ry@ku zbyr?Py!BULgC$DEPe}t!G-D02XAB?O*oUPt-eI;9Onl&^7?os^#fL8$@}=5teK_W{ zFI5`1jdAwjhaP>*)JNTd#$|1cY(BXs9^QOg(@1`E_#_%#-u%Ti=C;Ylxo*xmM!Nj` zsix41R+(fai7Wcymor_IasZgBE&d!hSaT=mLrDuQShx5sgM0_mpJ}mBz5=zHL{Mx5{UaQKag5 ze8{E^u*D|Z2Sq$9=%0J&ktd&f^jTY$Hj3ednrz0X1aD@2kR=-bxa)~qpM2<{FU^+J zWPrXvc=-fRgMZmZ7|E?`Wf*VP;nJT}AZF+n@;(owJ|BJ&K9Z z4%RTrQrsbR)S%QzD(W#wi6o<|^hl;+*oIi{XO{gDRWeQ5#2)@qr7LA=OJQ|VnEuR| zGgV?tZAvSgTn|RsgBt#NGN_8Q!HYhy$58#2H6QE)30oV3IK-8yrkd>~GKq;nW;0GW z`Xe9ia7R4kkwn{YlMuN-tEpT03<3>QfpdgRX_MlBfSDq zK`Dw-gQF#pT?}U^6Hkp)GcCJmV|AEPmqu2ylcg+M=;Bz+qKKxOZC++Qt09|2ai^lu zo@abQS8ioPC2dF_x0r=4l~jVA;VNLc{Dz7DsoIZA_#-Dd^+S()m`NMjS!X+6Lr8g` zDLRAV#60t{Py0M>IQ77yG-tOl6yjB!`U$6v^m@_PakQ`{gQe~Mp)$qd1c#qxuks*U zS@_0RzVdBveJ{gV{0hy!`>l))im(YOI&(%f^2|OCpq;WZu1ZzEh@hm3aweEK4O<`Q@^Rvi#+| zxZyMYFvc5R@Pg9Xs3)j(Yny3Ti8s>!M#wVRMGGx?TQW_X z&2!h@&RNk^r42Pg;=)!Mc26{H@=Zz#W=!`?%2wudr#+3cOouusT_*L1M15+de5TAh zVD%en#8>OOS=J`wl%lhU<9skfC4rtXbgRUhJy&F(0^Q9$Srce_2s<^n-c3Ai#3weta+Pv+wveIy=u(bXQy>i~ zf3RH>#;#lBxAL~QO@4Bew`Ju2m_>KX7qjwm!<*H{7;`~@!3H4YJm>e;cboa`??oF# z*t|YdZhURX8~|I9q$Bzu<*}!L$50Hbq=vdG9`tChQsefiop}?B?e)T3>@m}2%FTXu zw3}t@$aHzz53}}D!}|?1A2UBRp>w?F9p61)&Chjf>ntMuP5IE*K9?@ggrkPxE566W zd0bbHYWM24&Uz`?;MQuJm&uh5JKQ}#tCFW(^rJ`l=Zole)F0FIV2<~^ZI1K2$6oJy z=XAa|F2`(-}^GtRo-$H4v71K-fxjA8JFs}qe` zVkF*3yozW#W2-LZQw`K^naTB$e(1KMmYK_`1NC*|PF$ zI}fz4nllL4b3YV(KiZ?V`m?{NYp6ckzv1`-@4ypMXLlM$(p>%1%s#1qM-DJ(=oj4VN9 zo-1^@M06~C@PLw;GDP9#21gsV8zt60;NA5_4rgT+!pGEKQeK0%r5OD{kyMs_3-DD*{m zjK^33#&*<;VI;|nLfoi9LJGCd6L69ESWltyxzLQf51o=nl`R0jY{YQlu^R;a!INjm3Kr* ztjtOxs>-8a$(H0wBZA3Dlu4bV$#A+!I07;^AG@+cv)tI`8 zWVXK&O8rnu7uvej$hRm%R(N-1VOLtvc=RPvFyU1C`(`< zLuAy1n!L$41F}kVGt%)j`gjR+$}qi2hk59dZe)!^o5)CjKD-h`zzobJ@RPT7-AAfUahB4k4Y!)jy)?2`q^S3VPo`Xr@;U~+u|AMwLL3d#LG;fVEmJeC3&|Wo8!b>V z^%))2xdZ4?o9q%UlszGRQ@n$}|1(3{;T{K@)3&TDJ%CSGz&N~eG>|Y+jS$S#=(=Me zkNmL3CezP-{aAOrRC^uSWlhslqs)9YCXlt2e)Lz_0N9&M)$GL1f`!R}G(qwIflZh= zK-8GkQd*sjz^L#-*GtJ#)o|1ws05EpN5!hZm3>;`Bw4A2OisnJl-(?-ofTztS=pf0 zE=g53kkFc4MmC@gQ)L5~;1k-2&D8+WRU%i`35j!k6pD=U{ zom#=w$}hWGngU!>@j|Zc39mKV*rVC(99v0r*<{Q)O`r|XEY&C#R}`w%jA$K^;F!8a zk6yhGxq4Jc9oBe7T-GJK!F}D6+%LmD+}14-6bxG*?b^mI)!2*N2$kGOyxeLHQnL-s zI^EXQK!VYAABRZ*G9$IA1F*pTix2-URr5P*!^D7^Q_tbohk0!5ERVL z-9^hG{oUUM-V~(V6QtaL9A0fr4WGTMD+P&2Xd#i2UXHL>c0EEq$y<(tR|+g&1O^uG z1z!eExvI6L@m1Lbz7Q`&-}JS+Q@uNybl)x%UJNGQQk~xq{=&WET=W-r-|yU>`0-VT#~l;$Z_(M(y-kApKpMh#ViRz@$-13Wn7L(T&{NDnOkhBlCq!*>Y6zq%-o zxl*Dv2{F#2OXSir-dkd&V^9{B1%6{v<}@9W<0T4Z%TV0*ElUqJRm;`jnv`PqEnD85 zNyq(TWfTKM?qy#t3BL5&(InMK?vfNP2`i>v9x07usNo+l%uiNjX%^)+E@f*Dw+H4K zRIaIMmWA%wv|!;PH3E-te0WvhOX(oc-&St zVr1Nt*(m3NJ?FAC+pr}=SnfhE0BNX3WRc!odL~s%&ImowUzO&FOl}srYUVP=Pc-&v zvgVna&S|t}saxUc=P7HvD2JI0YGuS@`t9S3MrRDZYcCW7Lyl^wriS#*Noo}=lR$(> zIP6HM+q&)Q2t-}Iy&dg!Ysq$*vrcQv?xk$L5Vm%n$(9PZ1_IE;)-J?OMgy{nmQ!R* zRUf@Oy-vX(xC6hAYQU!Iv-H}l&IrWL?Tw&VWo8Kh=7+qkVOr!{8ye`&K5o~&Y~?oP z4MEw>?iJ*IipYgYe`U1$!Q6^o?Z-7C&cFd&cd<*5AWUX{^Qw zIM7HLreS{eXGuNa=)P~CsqE$6?;q0a=N=mTW(u*a?()WNCVpi*bzC6O?nvb2@CNBt zM9KnhT);H!NC<^QIBZftY>gPy_vSh>erf#x=#QJ}06+0=J81r1abFUU{|0arM~arM zN&K;H)8=5L#%o#L6VZ;nc7E`WzD)@~%LzB;MP6i6%I!!%g$ze*_Ra%6=xTEe?#DLZ zC5&+_HyZtBaV`g*%(jac*RL!uimjz_!M08g_HNYn&YV-~NbG1J5Aryp=aPoLzW!zO zMr;gMa+J=957$y=cIGO_VZ5+FCH*= zbm+cy1-;!#=PsD#2lrKT(5`e{-s?N}bVLSqf-G_&bTq%Va7aLGRgZ)wUvgGY3Ha6; z6&3X1E^%Nl_uWbKT~BvcX$oKe^>P<>f2eUGW88o>XE)#OP0zVycWu~qc3+0}?V{F2 zg9X3VgWP6vCfD|CCxug21f-K;j%)*G?q~hj1adcbjPD(ES9gw2m27TzcfWOrrtt-& zcOWxr>SplAy?0G_P^WHof5!uWzhLM8b2ONDXM>M~Ye(!1SM_bzc~KYzPGFXAr%x{t z^f5pg634bQ&UmLs^jzdqtRmts_i9uQg%_Xj*@I!OtN=oO;6_9;??CtPfJH z*AIE;dLZlZ0l)P2Q~8!>bJs3=vzK`+q7<2@Z7#8Szea3^S8}-LbGyI$yB`A@2mfXO*Jp{g(rF zAC-6EC;m)-(;T{$&ryzeMGhC63dn>X#@cR%pXlpLT=*t(ahh!f1G3h4Jvdf(V#F6AWf=tDbuD- zpF)i)bt=`WR$rtadZ!&YnMW#+bAx>3>QyVq{Zr zHS5-FW?EF;TBbjXnhL`I<|lhL5HWf<0tX%`;_rkMQDZy~E4V_EiBKgX37ur5=#fOZ z%zkMJoSFWb&AEAVPU&GLilRsF0yO*f?%%_YFMmG$`u6X$XRCNW|Nj2}0~nxy0}@yu zVqImHpn?lBm>_-+LKq=?s4aET0sLqJ%!L`<#+!!%y;d7P!0g6ah_T@&Vu`E;aR+lR zHWx~9##MwIKd|UQ5sokF@zHbCJr~_{C?$fOb}fyv3{C#nB%Tm+(DV;YZXgANmFb~( zl!RMy*`=3Xf*GcmV|J#WfoGzbrkZQA*`}NQjn$x>bJ8gpnRntTA#zD&v?3dt0Q#Ya zCyuz{YMNXG%xby+8CsARGr|}gNRTE}BWgP$glTXdIrkAHDEWAjbw(b^k}*;;>7)>z zL`hR7PF;zm3|i({tF5=L)0LrDISqf+K`W-{3xoAp!!Jak+)>iQ#Ro_$tq8-P8I7= zv_c!OzylLpu))y!YOKNwGu*Jl4=3RnvlB0Su*C#hRH0}cR{J5L7z#?Lp^Wkt#JAu| zDkDd*@FSu{=HdY}Lp@UGDRt9Thteq7?R?43#_;ryF_%E$WHT)<=?_*#zyK7o7egJj z)KgPk^;il2L!7nNTXWrYU+_^Jc4k(SO(rmByUbz79_NN_$cc{J?QBc!W&JljEba|Dv4mPVv*x(jg{(#?d2ii#mUYc~qL_PWy2 zCQqUYG{2=&U%mC$W51<-ZF%0k_uqp*n1rHJoW1#+v4&{tCgxUX$GOcuQ0=YxhP%2d zbEJoey*C6)D8bRJIytkB;Bxj6>}*02D`82`5ciL4_{=4@K-wjwr?m57FoPQ0AP2LO zx$uGiFoYuH9GJ*Arw*cUE3u1T>#oJZLBWkR^IJ`e?B@{t_g=qZ%oj9oZ; zmm(NZh$9vP5QSjGN*qXxoh|SZ#8?tbAeX``Vlj(aB;5x`=*2IB@mF~=A!fE{MyAZ> zh1B{JM%>mh*|lbdj`|($U;&A`1xH7D{2y>Q)v22Os9i=xA|d5Kh+*&~8_io_6MN#1 zH@v}$XPhJ@D``nxZ7+FYOFBB| zmz?^PJwFl(>=2@#|LnyrdXZNp3blfy8CpUec|oiqHnEDWW>l%_*vAe_atvDkY~>0P zD7J|Rq%B0HSYvk)HP(+g!f>qNR$HeiHB zE@DnfZB!Aorq(!ol+^D+0Sl7|Ft(BS6agdAvz;Q*7XJijFG``rBpy)?qW}j_T(Oc- zY@#&QT`+?ijKSwhH^LHL%=IGUV5t%0vh2&OSKs(q4}p~+k9v_=kyD$B_@k{clV|QA z5fWHXBgXq^Sw!Z062P5gw#RcGAyt73Z|oMp0RHVLXfX^$CX^+^Fsc^+)^p(}LpjQ1 zgYbl_Y-MgrIm>1#M}}R~whmWIWFJaRLDmVJ(MszgCvKU{hLbLkBm%}U_QyWbHr$@1 zq<91j+;y~bMBMV1pMvNuBLM0OS|quV#NDZ5wCw0dL)uwXzA~jF{K-gT8Y=@~;YYz7 z=2Y@#b=e(=$xw>sG-sr=u#hKe&n4&KBCR%cw#b_AjMn%9^QO`<97_mMidy`bw@P#b z5&^MaS1^JQ2u^ZoGU4ndTR79wo;I~1H0erX`=Zs}_EQ9+;Zt(hlxh6%SIG^8la|#| zs7|#lS$#*hTFTC_rnN;#Qw+Nf?~k=j-YuE|P+TwoWI&t0;=f27^skF4|4=3-`MCc` zhO-%68E!*7;u23wCbMmE$4)%r-nJHOfT0ObuWgmo3a>$6bn10$q<4_=A3RZhkUHifm!awSmAf z?~2=Xpw3pJ1QJ@|s2k-m-eKQ1!jO|o3+DK=ju1H|3SKX-C$;$N5q%DbUeKbLNsI%+ zSF+?qBOTfbqB`LVUwEiXJ@H&KJf;JM^{ji=A|tJq?3Q5W{)IiwW6#?y(f;z6lcvV> zy|Im*Bd-RMMv<2gsF02AQ(TN9iE===G8YPXq!)rtjNd))BaV2*{{!Dxz1MO%NCb?E za2N6d5qZZjLRNNWB=Z*8d>&(}F6o25H254KPEjEWMP!1BieL$W6PL_U7*UCY04Oa+ z0f^rcBBAmx|36%T^o9%ms>9zu{~i7N-~(Wr^k0`{SVJN$k}{bf`eg$9l|mc<0wFL0f|=kZ1dTt~ z-~HvDMh##N>L7#tUjX``fLz)RHdjv=-~n3JhD=^a(OO!qjHP5A1d!3lx$VYndEsSYS`w8=MtTsB~c${+lY~6(exMftjEb zMTvpQUkt_|Gx@_XAl)2>(qr^tDym{c<>4N>qF<~cWnF|362yrd03aU9MYPmIAO|A4 zngptr6v7)uG~z$RTrZJ?5Jkckc3~?d11`uyD|p}0GRT55-~ty?qfljn2^v%)X(K4EL_#ss{{uN(IF`{mdgMo5(K)80D}rQG zv5paj*!r}{JBWz7kPA;t-#s=2ihW*1z!-}yVijs%FX7COjKU-)q$~hb7aq|X1lA?k z-UDsIvR&jhUZlchgDG<4f|O)cTBZ4j9FQ_`VJj%4GB6w=tbqpx!UqD^CJ@7&9n}HE;8I>>ViuJn zO{M;EWn@Yw~s! zXC-Z>@|_M+Bw_26S_9HrbNFJqnU{^6m_IUvN00(iSl}ZH4l4K&sTd?KD5N$>BNx8H zUlM{Kuvc(`H#F|tN zD1kC)kNRk>Jg0(I)Q_H#gSL=T;NogLA0E_*KcI^&tyQFK=po9ahYk=pl!idoj7hje zE!4}udEhIIftUg&CE|iB;6l+cW@4_M|NOl{3_OmG?r7)`X`R~XmjtPhYSNu%QD?2s zbsj)=w$9ga=Wxjq-q=uyty_lz559?nT*j4<V4#?o`O)TqR^0ogqF;B(PK>Nfi9tpqRty?Flyi2 z({qqQl-yg*36Ra<9BB{(CuAy%5<(!ff-BrY(DB`G%IKOV6eCbUshX;*r0QeJYPp(g zesB-0KGwNv&}X`i9IefWF@&YSQl?BPMhvT!whPXP15Ln}klf`Z#N7ieQm0PqBnBoY zd|}Z2<#5)h8*VEj!~nQH(*cO<|F{k)yK3ylp2e%G>(+3r`6SB6m7C-xX_+`R3Q~fD#S-iocA>Nqf-<1#Ef9iG{im9)gs3JIsZ#6?T!O_O zz%XF!xQ6W1Qf*gw?8h#QbXINUAcx1nPD*O$<+++@+K?VlA-=loF3DUZ3Q)`e6DqI) zA-q8*w2b*dkKh~l<2G)_UheZkFH}t~<#tc>PEHVD zFDPU#1!4$1j?;=P=`a2U%a~Sr;v zd|RlE2tg1klom&hs1)i(is_bRq|nSj5(&K6j6Fm`AI$IkMgaZVZ|w#E0TjaiF3>0t zgT?y8Q7I}0k0@H*8Pvr$eaTHT<1^Y)7PmKm+arPENX`sdjTMI_qMh(Rh zaX?C2!V>nG9m?d>|LP79tj}+}gZyIeyI_#S&F~ueg zsyZ>9T5%#v@$^zLu_!XsWHA=Q0Y-4Jv|QH5SOhA}$Z)_+j*M0s+l}YtD|4tXs3>bB zkb+0-0x&><4a>0{*D?MUfEL{CN_1oWLF^x2mZFmn)SEbeIGw9BUiAvIM*`9qVuaH0#0@ zt+vjno2Il%FA4Lqv~tq)S1a-{_cK`YN)|hFG32yP2fs6cs2K_a(Eg+? zEX|grio`DTDFwq|p-%az6{tkx-n_Gq)@3WJLt74_c? zq*9-PIM@R=jshoW^i$VyM+ZOv5CSfPszpAm38FM`Bd_uk{p0NE<`*D zb$6rkf>VPr{ETm20wJ9D9LKWluJ;p|^nY$E(wg{*YxSwN_~6lan8$c>%e0t-$#VyE z|AFs#MvR?|=)s%ofg1bDWdkXJbvJK{}vZR zw{z&EgnP!TdXwS^oFjr7AT@QrFEzZntV04KxVu6i0x8^iB7}huSmdc>+wI=5DJLM1W5r?kOadW%PV(Yv&@Yn##22Q!0$#$-e>oVvzKy|~w-)PsB^tUD~g zI;bH*vx@hSKx> zOCxwk z4Z;&W?xTP0D_;7u2lnp%Gy8rPF99A1zwooV)PFm;)4v`dLLvYJBv`vh5j0pZQ7AkM z87@Rb>J&jzi2V5RGRK!Me*XA%{Pz)LNRc6pZQ69{WJ;4LRbI-p=}n9sGilbec@t;O zns5B|?CC~FP@zMK7BzYlY0{$ym^O9#6lzqdQ>j+9dKGI{ty{Tv_4*ZTSg~WtmNk18 zZCbT!*|v527H(X*bLrMKTck)5y?gog_4^laV8Me47dCvjh+V~t{~0%S{Md02P#uf; zD+VV>X3d(H=<)m+bZF6|J^$;-4;E=Xupp@pjYth1NCFQMjCd-cLx>V7R`epo)5g=M zM-~t1%4G87EKj~1wK9!P>C>t2;OTRiQtjKhYlr+De0cHW$(J{O9({WC>)E$gjQ4PS z`Sa=551iP2e*OFTt1VUx6aY6HFf%b+J5V)POylPt(jqwp!O`&WERjS=*$u;8PT7#R zihRRCh!BGtjzQy!Lk^`BTUu_VOsJ?1#u#b3#HXLSyAj9j`rDDm9)0`~$RLFrlE@;( zgU`Msm0XfOBb|H_O1Izu1v3H%G%&&}KU1)y)I(MHunlF3LVUDDA?EgiB- zD><7`Of47uC(O@C38hm6CrkvEh|a8SmtsWmq)j$GaVk!dQc{tnT$785&t9qX(3dunXP zlR4U)wW(S^Dv8b(n@fpTU-i`q*q($X7T_GO9hl&P4L%s*gwca`+J+-l7~+Vn%C*{_Tgxwb=wWm7mnoh{|CieSyV~SeQn0+I_v`8Szw8M z{u$_?g&ta2h8;foFrt+vnBr|YRxOfG!vynb(I7cxAT%p#NDqsE_*xT9fI+#&o;>lS z8INj3uFmCN%F~FO<;KaFvVr0mZ|;`foA18;{u^+{j7FMpz5+kIQB6Cm`ap00iNv#0 zAZOe&+BPHwWIq~WXo;^q_dM+3%67R{nRQ)>k-1gJsb7Eo%^UWl5TBj)+HJpmZ}{>m zoN)Yb{~bsxou+&=NKR%D!cZn>-11W<(tPuU?g--Z>OT+tG@s{q)sepZ!7y=l$XKt_c33S3&!5Ni}eCE^OQ0CV`4}K7YA+*c;;5Q!;p0F{SSpuhsSGnVL1c0!h zM)nxzu?<0D5EFu4^c2WIA69Q{4=heL=yfNT)XahvY@O>i*hE615QvGlz&e1xoLESqXc3W#ROBN4X2mP+g^`i;O2t|T8d#7`I4Bbd09zxbGZF-c(Q6~; z;`l>0%+Vk2g2E^+F$!Y%LnN^Lh(EI7|B6ch5|@`)Vg>_N1Vb)GlED<_Fo}sQM;5M_ z$%IM}x_Cc~kw|T`%w!D51(9-XZ9)i4VCPE7KsI#5AI)f!B2IFNWPl_acpOPjjB$xK z;4+CzWFpUGP)`}a00zH&qB8l}Pk;WCKgX07K#N()(0B`)#2I7us8PnyeDZnNBqvae$Hc)bg!*aE&{`hKGZ?;R7CZz~w)htWVs?WK87PO&VYg`EL?o`2HMsZ2;baDGlHwz#OiVs8WpZo=K$HR z>JquVQm#@m>sD0<%^KhVD;UT@ z7P9R~IOOzkBwSSk>Vsjp8mUppngmg*Y?+E-&<)Zbh82PvBryvwufh!*9YrdB;fN54 zlgnQ=bB8Cf3NO#X5h`YLFz8&3b*QUs?X0nlrGw+5=$OZW?y-QKXkaW)Tr$6{dCs zoN+*fNtD?QZn*WDso-Wh=!7r+(N#V3xzD3}9iRo>>>k6k(2bV%w5jc^omSg# zqGK?(9GpY>Pkp$Jo~R#yQ?`AVU*W+!h$AGd;dHsnd+x#BmX5LNf~rFV?@6$U;Hw}tuY-|_!&1Qwa;{^nYb}XY%$MP5 zGqyV;F22!m;^I+vEskLNG+icX*K~V0-=+|`sF89uF2ursZ7O=%pkekR zy$kD3c+F=K^i|w^%fF}w6&&FRJII+$7+HrmR$=B|2VB>7nEQO~J5q>8{0;p&8Pug- zdCgM2kXqOL|K>U0c@!qJ>sh+AP{nTY-KgqQ)L?m)tqg=v50b;WHTo(fLGzv0y6_>g zLol8Z>s9kiu5)Ef6YROb%)_>@LvR@7itdp<^UKD z;2($&8G@l22tf$`t;`0_%>eKD7_PYR3%PiJ2ReZhuFoGRPy0Ubte~xl!jA+?&;(DA zS@MefLXI?G!Tr(?G$87E7~=do0&?IF4_t1r=r7AAkj(&22xe{Wdd&_DZWbf~7;=lu z)WIJN|8SOw&lwsp7*+v9LWB-}!TEeJ@EUJ)ED(@h00S{l13AzGLC_2_FWOL04cCwj z+weyoEcC!-%&YZ)AlHP2t#05QVG0luD03^%i2q~{7wSB%+_e{?tU-UfbIx|pcxGC5!V47 z>?~fq;TL-03igjpx&R9|@%cK@;quH2ZAKJF5gkj>CuXb+QxOEAixp#09_NuB>(MKi z|169cZ1i9Va@H@RvI*@P;+cN&4}~$Dh*7svEfbFp#d0r1Rv{SBp$XTa`24{e6mT9U z@)74@4i1jyZmkQd5FEp?;g${*W#k;uQ6%Wpv~$|s(NkBJOLeo!5O^48=fH; zyulyV;TiPK8>XQe6mY|y63*=4;P7rFH}Pyd@!^;*Mp9BG?=l0+h8o7VuBt-cmNXkQ~7(C+re0@p23}q1e{3C)%+u-*FXXk}!+Y zIFGZ@MD8ENVHY&SHt(=YFnIQbJrQ&dI!sZ&B> zuQ)_&&;=G|^gx$t537?Qq6QRNPrYIeL*E4_(NCz%^G7k1#fnP<$KXSk|8x|0vp0K! z9Z57eeJl-E)Jm@uOQT3jEJQ$6r8ji(FsX^<6!a(=0--cvDZxpciZnw?N9*et_91)9#!m0_Lp$M>D)cu;)KC2qPyw@0XO&iKb!b!r z5q>fvb|KR;r;RF1n>+&#W)y&K5P`^aAt()+EH#cU^HV`JJzJ)`=8zwtRZf2ZTic)$ zMzvIHa9mHZT>J7|(Uo04 z7Gy&fNSJgN9RB1o3V?8Ts`_^y&)-g`6Lr?{BQdVmL zt6mpEhGdDTa8eW40BqD$ZD*5HpJ{S8k!{^pbKkaG{o!Qh|CVl@v_?{fT=O>S_BO3# z3UF7KbzAo=E@vXlKyh&tAP=|P6140V3T&PAa?i8A%(f#CvUd+Fb2ry`Id>dA*B_FU zZu3-mMbvbg4RuqOC|uWiuNQl#!W?GMOegc~Y}EjX!G;{_F<6vbbno{e~Bf4PZ)*SwIL1@5)9XXJB_;%Sg1xW zBzz)mC0G!B;f62Qf_r##F&J)>cX>G&TvfFx^b~JL|M;v*m}gShiJurtbCh;pxZEN^ zSrrN-9xRqr28Yk{Y`U0&eOQbe7Kl5yPKg*#%O+)#IC`g-i3J6U<5-T3Q*lqhg{c^@ zqJ~;!c!9rjbauFlkq&KyS8d1GkdOCaBi4*57L7ktbXgU8mDY{l*o5cUk}p{vCDnWJ znB~B3s2X>M{kSKd)P@83E$4t;(D#s6`F$TYh?5s|Qx#)zJ3ikHjToHg&4;ZG?SD2O@&7^YT5?Ky%olppe%L;%^{{MxmB z7_f!7V$+eZquN#fi)j-(u^XGWdpnpOn}@6ni%A)b@X;(bn{n3(xqITQpLwk5tFDE> zY@-5@U)#FJIFW_cCuTbgRTXJfdb1E)w{h9G%iFx82)L8dqJ&v&+If730~nH7m`#b8 z>wB5+TbVyQzV|!6n=qkjV~*C)Lb$eY-pz1#V}MFJS+`wwgDzJJK8Wfs3jT(Y%$bb1pctO8*j9LEp2 zpCi1HdEk+0nG^JPi8GwYy`#gA{~XB!=fkOInA{_F*+0 z;iEm;r=8kQL(_?Y=`SARLpruO&`x!!tA;`3NB-PTp6tusNALgjy@DCs9m44}){urKK+C7&f2xpvVN5z|NPB$$?Hc7?8RR6&&TXb-}KYNkhu`QD-Ze&BaL@FREducGLq!XFAB@snTq6JP0>Ueg=@G$=pvsa^8HD6c8r z;xS+ID;UD>OR~N`>_?x~PoMnD-!aT#_1~Tp9Mkn0PICJXUS<{mzl|WS*3mSA-CLKtVDqYI7sne%Wqe`7hwW?LB z4zp_A%C)Q4|F2-fiXBU~tl6_@)2dy|wyoQ@aO29IOSi7wyLj{J-OIPH-@kwZ3tl@8 zQm90T)ELr(hq0c=kRwZeEGCHM%a}83zFcgjCLo|giw3Q!$K`noY^quw%OL+L4U_E3Lj29<3^5^J{mkp5+w6|2lg3k`La?>p4hWv7s6eLPom(# zXF7Vdy!rF!)2oL%xV`)L@Z-y$PrttX`}p(g-_O6l|NnMPCg6aQRkqoIo59gpLbb65 zgl-10;oyW6j#k=i7-q=NKc-1oArNfbmYY8gX~<6-#igiXiW(u8+%XHC6kSQrK_?wc z$G8NO|4iETcvE*ka`#<$MEWz{dPpXzt=;dTf zASfnga4h5@g{~b0%!h2U7UG+5#);dUbk=ESZouTZ5-?}BDO!kgD)$Z+`^>gubo#wzQq zwAS_It$2hv=9r);#Allq8q}bl#1>oZZNT8xr?CeZhn%1V8Jg&{)GE3tv@+hfoJc20 ziesfaj=>WSo0iL|r$K=#>Z$Cu>#kL`#w+i<^ww+dz4+#PTX8#P+(#1tc{(Y1{_=k2y5p_J03I>t1Ixg>YjX*2u~1!|~49r^Cd zFvq;_%rw_*^UXNttnh$e?z#Z*^qF~%7e zgi>?cdMuJk&G_PzPjif1vdNyHobJjkj~esaaFfdO+;rD%_uY8st+%{BPX=_*n{`I? z!odo=^x=pzo$RuxL49Z?1XU8TwADgRxz(6MjJ2cE5mY2lVUO)e+2#7Awn{6jtCGuc zx9+-nd&e&O?6lWz`|Y@c)pumN087WgQtGN3>GtdBr$1Hh?6>d!`|!svzm&T_*1PXynu)l<{2*-n z|4M6^CM4vz6*2EMhLRehvR0_-IdEb#unnE`G#l=v#22Rq87Kv#d!7YZ!NUU3lBgr_OcW#`qo@+2AX1UIe4QkB z$;)2)@|Te8S0(YMAkTD?e=+o=GDlNDJBAWPq%_gx>KIK7t&)|QbLBGKB%(m3ES=SNtSOB_7xDHK@UY^Y98MbV!6^rt`#s$Vw5GJe1U7L4I&|3?P~QZ;IllQ6Ym zNmEn_*`QRF5~(IY-`G;Cy)>$+k*Pl}p_PLsG(0%nsai`V)V8|yt#FMiLrOxBf4rj@ zpn!u?Jz7SBBD1MrRoGOEQ&kOJbv8rXYC#lo&91H}unrO{S-oP`n;vqlm{pQoH_O@1 zdRCH0CDcm!0SZvy?~-U-rbr>1w80W5u^BpSNkFC8lK3WCj-}RDSxXx68G|g9B~k}7 zOWgB(_PEGRu5xo{4#-3T7S!0JY)U((ViGT~tL1I6pjX?29F~0Dy=_2qdnoOO)wgLm z=;wx8-1b&wx$upzeCNBb$ZWK<3z;oH@T%9$!1JTp&8~T$|28eyc6UQW-QZTm%TMyE zXuuXiZ(G!BS@&8PUi8hdhBwS%D?x^ZWCF#49+I+xP&Wvm&>mo;`d0{7h`R@lO(9oi zA_nKt!NYNJXfEWB-^zu;!ad)GhuoA78~MmcPI7xF!z&S!s39EEXI}?g8tGnF$Edky zqF&^YE_=Dl0G)B_GGt>P;`kz11_F=$@rJtq89YW2GLh$u6eZjF&UnuAS@bYWp^Z@? zzXC8Rf7Q8i=*@?;q9Pufd^b*vvJwdomfYPrU8niAscU;i2~H9aewFI#L*EBoE> zj`u{F?NNS62sd02GX zwB1COx5hWl@kin{jC@@dva0P6Y!j5#3^DYCW+*I`vqswjpI9gvzHo3~q=yP$G;wr2 z?T1VJ=k2MuLfMV+jCcI#NKbnFOl(@f@inqlj<(BfSek*PoLQ}ojmakz@R(O_*55{W zR`Dpxi!kt-JP+)+4*>C>yZt>v2Pe^seqp8C|NZWGzuQ4hJSNn#2{#7GioUlwJcUeM zG$_w+YzDuYu6w;=GdJnfw93_rz;=ge53JAK&iRSIC%9;xJKf!z_tKmG^!9oU-+$+K zVvT&3D`U{V2@jhC96s?SlFimZ+y zX}j|~Z=dKBC9Tv~ciA_91XzIhF&o^6Vh2%vZQ@>5J8{r3S z`8FpZqA(Q*8gX)gWZ^_2=vWrREPz^h8aSIPPH4xz=*=Ah4>+CT_}mg zb&1Njj0A{aZTM`l#~_E(T|Fp;|E5TOZ(=Ox$3KC`70(EbQbcj6sHs?Zu4xxQ}+Xi#!;O3*n2Zaen_uC^QC&$?`ulG>5UV zhu_!|*TX1X<{}zFHEp1abX5@Om?KI!T83DS7#U9^C06n{kMrmx_PB15h>s1$k1qL= z%0@`D6^?51j;H}B$zqTU`Di9Wlj7qKjMs0wIA$2K6?viw6^T!__GJ`Fj%KG=EA@eV zM0p1(Rf1mP#g*uyU7L7SYxyS)^M2v~o~O4oA? z{y>z9rH9Tah*Yzfq1l*+C>x_`MjB~pd{LQtVQy`4nMEObn%R<`S)JAiS2M|wSg9H~ z$(QAKeqBMAAM$#}IeWx{d#)&Z6mpwgRezf(8)pcb=@^`LIh4c+in<7y=b4<72^h>t z7yqdi&UHeu5%9WC96GPJ;SUPSmP0vKRI;xLVUonSsm~gE0?SYa8?!QdFX%Ur zHJfILW26oFs%^3ntxB#XDswB5t`_TiK5(v6YM6KmSlu*0O@o(dQa&bIB{8b9&dC=k z34<@2rZd~MUh66oII=it`}ppiPEv5xm9^O8bBJZ6%w^96BPM6 zC0=Q@{}T5XSqq6eOQ)=wfpcq5padgYv9@kYUPx=0yg4uti+Hhg zswEp9m(ZVA;=A}bhxbBy7~bu`nkA?Tefu=8hx5olA9HjTe$vbR=3x|}x{0}8OItGepry4HKW?m>Y!E4vC=w#ibo3&%hW zvAeu$M3)Ot-kFtvB)r4hCq^o5$t$(XnsyiZcU`v)KR>ks<7zf|*s|-k$(-CepWMx?Ykp@;%4~AG5^)^$S)~_o1;G#u-hdA1;0?ck4Co*deYggz zP|LvV13%Eqg}er9P|MBi1IS#+f;`X?fy`@g1$(T}&iu&H%sp28Ig|{h)!eW7ak^iu z&D#t&-rUhLdpM#j&P$Uh|HQ`R7zn>$%pq6}!B7qQBoEbq45?tt5)lZqV9XPN(#HJH zt3VMpy$U&S1+381<@?Mh_t4U8K@$z56>XCJfzjrp(Hku@9$nR<3L>x+OIb>r*N7V; zOS~fOC*;gSg@wwvTn9fu5wF0`_COH(;0^3t4ZqL|5wXw|Q3omQ1NO`c{}jQ~5;4q0 z?a(O`(Mhe;qD#?Dt+M|C)d4%z=wsE8t)oi&kyt9cb%KiGJk|rZ#EbR>(B6e3`&_968i#!Rz0L((Y3VZC&i!5+PT~9nl*oB=gpj#h_?YsaIxSi_Q zKOEV}-IcYIDG}fJk-0K-rJVj^t9W(o!?W7FDSbo#4WwXecZ`C;LKPI25#V`l~-`E z;J>rrrk3C$cHq0Im&=`jmQ5#^Z9LO0b7g%HBLUaH5DclX$S4iW|C(S6;(ZY4u+G7N z42ygPpWw@@5De+P29glle;f$>T;GD762@>)W@QXQKIBARiZ;377Fpfg*Uo?ol|Tr=fYUyJ(sX?g_OK4` z+{(QW5y)Hzd7R6$kk1T#$h916_Dy?Usu$^YP&c#W0Lm5{EJaV=$x{C421w-ya!FSn z8~k+{4*uW?e&Ce8}xY|JEnz2V&&_g;xm(FqsbF zrN!x5u2|#eAs%W(c^rcNU=Od14$i>h>--DsPTM{(?y&9;Exr!n?G5|Dkv=dB!Qkr? z(d&rjaDzS=W|hTcy5CT8>}i4UV6nj+-0W`y?GS%=(taTIhL$E$TKzTgnC{@(&h1;J zL*V;BlfVj#+y+n1k@mQ~M8owD^e(75uG!NeC=!&S= zfC-pzq9vh2ZJa1q zpyT>p%)*fh!GH^2qYkUQ&d5*==umI~aV1cyU%`-7L$}YLKY8AqAqy5P)fFEVEndW! zQR7CA6@h#N8B*j(k|j-^B*~B8LSqM9zJwW5|K?1ZHErI6dFhfdoj7A&S{PL5!b?7l z9z~k8<_@M!mA-5mRjSmdRdo)- z4$`G_w84bw7-!bUDphLJQTA+%IWE55r*NU}mHzm>w)on&LVmf2?}JTS`Erjaoj-?; z5?Iidis|a)S@b4QtlhO+?>jZ=RPy2lU+o@LE7!K|-M@z)U;caW_3huspI`re{{8*` z2QWYZ2aHQJ14ApuH`W&1tQa^BgfK$K|4gH>Lex}aP&3z(W3EGugj>)b;CujarG1J! zaUl*pWYLG{UW5_4>4GBADC{nIW2QIK!&dTmQRJjuUR0%ji{})^_+l&%rv|Jb+^{3KTC*|o#rUx}ktl79XrZ0c z;cH(rRNN0MQIIu~Q3kgXlPx0GT$!CiS6x}T`{!MF39h&2A{E2;-F*Qjx@e=lQaEX) zmu9+Yr=PAhGuD!QxTee41jS)7D`PX`j6e3cLXJO{Gqpag-7wsjec1Et&C=#f!4VIQ zd1kvw(xf+k;)Qibta8>FE52v-+2{J$6*`ln7iU~ms2_(sa>*yByz;mzlX^3mRI-U{ z$3#}?Vz0e^Htc9kADe6n|3l7DC~ViRXj{(stc1b2JFNR|-9O5^x4~c48Sub~8o2Pn z??W8ZQX6N!c_l4}K6>e=r@s0vHTx&?%B-%s;;tFX+F@NsZ}V4BE^MO>(@ZZNTJ}{p zjrF(*Rq1t;_hflNw>P_ew%m8WTknWxD|Zb~csl#tri{11{3K6bigR8BCFmCGRnUSL z#9#(BIF|)!uX|L3$%7z6ECwyBF`y_0uE;kTIN+)nFH9LfGUJcz)$ka{NDU^^XPVT- z>3yX6A^c8bw${0hWcT9}==kR{+58WHGZWz61eUMi1?7O5lGg&YxE}|S3W5^^V;IA- zK{A%njAumS=0hP2m3W!l?4yR+!(k40D8$nAkdPP3 zUx)~0zZS`EkNtz$69E{-1h$HbRs7q#Dv2d6cG6z_!A|1DILc9`(Uhk|WhzxECD2if zCMNt02{rRQ$+(b~ENtNmWw}Qs?nWVhEJij2sXnryj*z91pTl0Gw&k>qmzC+CBzH$i zf%y%S!RwK$Jh{#Pgc3>1BV{-xxJq)C)12o-Ctkt_x&yeh(9nZyMtT{O3q!z?}3g^M;&J=s^*R6@%Vzm^lby5aE~1Ix&(qj?^e?{Gka=d{ky3wbdm_ zipeW(vPLL{>n8)W(yV|Jrgt@(P4&80zV?-JC*0#pQkcS@PR4U|G@no_Mm5ZA#;8bT z19X=9vZi7*qs8H)R8d63%)EmiR!z+yJ4PWxMvJQ%@+wE1$(ro3hOA~)RPS7JiBLW6 z4Y$Q@Zgrbmo%EI^HltEpg@@Xr>^Bvg|+NVF7>E6 z5L%|6|3-~0qb3VGjZ~ITm$gg`r@GMW1#?=VmFVhHlSs53Q8pN5ZEH94TG&2Eww5YS z8QIknD+$-YQ7W!bj+tRKjLVr$moX%KLAfLsZcmybm%N!XA#e=2Ic zWLL$Nn?CFe2+wUvy#=-%rI))l6>U zhN53G^r~B>sKe40(2A@Udo|o|S%VA`HmGDF2RNRQccNsxa0kgoX>z2g1m$n?i^`W? z|B{w9y=hKw`ZHaA*gRo;VFqoj%t@W(Q3ZVxHn-W;Y2$WWz3sh%CVbgz=O4Gn z*vg#xpPK0BnWf2w>6Dlxt$ua9%NuK`rsy(3F^+L)c#LA)8BV)y4aq`6*3JBJqiSBa zp&!MmWN#2(%a%)eo=u==PkJYbtM;`u9x!fq+~XfVBOLSS8-v$yCjEr0e@VRRC-zQ; z`~a~gV3R(1*PN*Xg>z1fp8mqEDh|BM|J zW<#an8XWM%U!qo_Xr1CzK@3yu(#7r!ZR2O>ILOt$cD7G0u}2T~KTvMwnT;6T?%tiT z8;jZ-4s_;xwt3*qn{!&fShM&>{6d1>hKKGN?l4cYCV*XX08K!$zwff#Ts1q&)irqJ zqi|htu&Vf9em3@tE6=59N4;6vzIxWTzF-VG>WF<~`IfI7fKA8T8eg6n?cFeKB%^uY zZ9aHeC)CjCO=!+^vkx3n%lES84DOvS?sC)qTtcZjPBfoE&f5f&UXN1f^FkiIc=Lg& zN5AS_zkc?&|4LAgy@&_RySuB~TrRiFM!Dr1xRZSMzY)Fw#0c{us1Q*J7qhqYn*Xk6 zD!I&wx)(tg@bi@I!yrnL3D4UZ!T~$I7!tlPKQBtZ5EKjdBf%0hLH*z-RGYu(U^-$0 zDbCP8(BZ$G13Uq=!2zVVXF|F);=KmcuLqQluDgp)5-e|j70syJCHytzo5Vh%9ktpK7;8)Au*i52*ibGDMBQ~M3lu@ME}G^)WRLK zmJ91d%CiEMB6q7i&G|NN=*~MMt2X_m_z#u{k@;p-voISjfRAe~gA&ge^hgXEf zLZroR^v3nG#j|=tt>HvutP@`Z#&l#3k8+M-#KgyoyJHkLI+UWs7{$s79B9nIgP}%G zGLj?A#zEZ1)ceMQG{}w%M{(pFT+EPTY($k&$B1MO0CGouf;)LMIDe>)`nbo(0mw`m z9%AL}4ET*%zh40M#pozw_+l%$Hx#ABom z9I=mPjGT|;5qd%0sNkj{A5^fah)5>M_TB#LvnIjN;ASq{QDu2{te|o6$?b zsY|*r%7IBvlFFW;h)+&xPUi#<=o|{^oKC;I&H*LRr70KfEdNH=g00zXrG{}#j_Qc> zI#2WrK%Z1kVECg1@=yHCPq~=STG_1-710qLQEw7WRNT)E#E&P8&Xf#L0WHuNl~G!O z5vEJfIyN(BH(+8hSKr)JUQ%PHQxyt2j}CNzniUCDR1K z7p2Y_)zU4^lJ&Gvc&wA|)SbzquU@>3p+XkRn9v9nku@Ds*eTM=yi6p0iudGD{OHW; z>At_{(7Bk>4)hNe{m&@G(o5sgLq*g9841D!Qzh!J6KezLgHVh>8JNh7+-#9OY121# zwKzS?In5qv+|aJ;Q@Hrh40<>wEx$Unjz9gBx%xvZ@ zw;j!p39VF@IEJ=?q-H{yW98Hq@l==u)qmK?>ljW|1&>q3psdTjx4_S8b=6lD5G9q> zS)H<5CD(Ed3^ufuUY!|u>oe$c(@MqE;Mh$!jnLgB%VqT+^*o7ZbtlsM$SAc(<0PX! zjSH?TRX^<3CL9o`3|DbwFmr|2h^32$#7Id@#!uWGcD)TC?TARl!M5o;dgTZ~kxYE; zh-OVl_WYx4t&35m%Y&^7Ypp<_09c=}Ce4J|n@HH6K`?;SMu(+Ui51$Ry$N*95TqhT zRl`^l(-!_w!^*m$m=FFi zJkn6jOC{9_mL&|CwIFr@+nV^yuC2zj<=H7=TUT_^w{0-FHC=P1Th@q?O9U|$1PQ*~ zh)BH_x7pS0xmV#(*4U+!Jp}71FOtnbzVx4S7Dl13tjDL9I0j;nk0? zrPfwWUg?2SA3;tblu{LyHY-I*zNB85y8qq-CeV>cv)W~lk4hgn^S!Vl-}1evWEI)7 zQBD?H-wkG8-&-c%RSw{_#b=Gy{gB-IRSe5@Mw;#4r7Ru*HVh|=3+Wx*0)|@z#$mwR zS9D|GVUwoVc|2j8;KFUB)c};<4L%a7O$M34CT20jRSx+r2@)QV;@unPg*1V6xJ#K! z1mefhD-8aeVF7MY0=D6B%HcF-N$6lY2JT*_y^TtU!9Sa0kpW>fJe%>voQlQB*;yMY z7P0p1S)JKT&eURO9E$tY!-RohQ3T_<5L7{|;WK_IHMZngTwU#5kRRT$I?gXo&dIeY zQwPmIJ~qctei=YsR6(v1`=#8$Q2$}e!IUnRIEA4`Kc&(}BjZ6eV@ejIO9tjDJWx%x zj5mf6*d-A;Wet^ZHX+DE6c=?PTZoYon)<>?9f>9fYNpdRYkc#Wd=V>Ps_ zUQ>=Xs9k>c=WI#o6{O;VQPPHXX{=6~n9j#+f*hNUWxNR8g&^y)jv%yl?B~+xwO$T- z1|1@%4Wv%3k!9+N#Yq4}>8O_K;8d8F{_9md&aED77cT6Fb_tX!jKuy~#wMl5rft1S zM!h{t$?lK>v=(u}Y`HGa&6dYK1|;5l>YfB`m93#yww0>J({APx)CSFPo}7wvO2dHd z#g^^nsqOAQr|Q$!1E{$@@#y2e?6@x3GSz2O&OgOvR?r3lY=)Y?-sUidZdoDG{MN1B z@-0@SoDDp%$jwaS(*N%5ZXEAM@KaJR7hFW$&KBOjYZP0t4SBxRXlk2OQ}VuNVyOYV*NDtBH1heI>gl2H52uO4wjQ#@3**&K6t@o=X7MXO8Z8%e$`OJ& z@PzL0VY71ZS8HqYHW@RgW4p%9zFYH3X!DGK@4ddD5D(jzo>{-P3o5E_0CCm)h~yOq z^qwB{Rc{(0aQ}57@PtDjiW!%rMPFRDhV(OM?`Fo`^Ca2Wc=JKyS3E=@6i(s$wj2wb z3-6$F4^3DTR&m9)@>F+mR=0M8dG&0Mb*!NE8ozZ$&voMN<7TE*+Tk-cr}5xrllCYr*y3 z&`GJjJ8M>M$W0|q=hk<>+(nc3n(*SU^IRFOU!Bf(efO7sNBLF(cz`!_L@#FXLiin5 zcpz`XmmAA@w&1$K#B}d3`6eeTHgWvbcv9r}vJFXS3wbdf`LW(A80vy9fRL$otXv1cB%K%2?Xh1^gRS_+V8n;W+#v7qPJa2zE0}oWO!)ZeIS-{9LYLx%YhL3H{}-kI{Gjmgn}D7l|8Reb#qtho5WM2m6AT_+*q| zqe8j6B`Yv27fo-jQ-9g~_?p9!#f5A%X#z%26B~mnRhB%!Pouzp zGCk6)Y4Rq?oG97wWCKhl&^HH$5-n=iJrQ+crGhOX|_nuWx_sdb8i*6E=+bKY#%WI3R%m=64{12`acCgAF?PAcSYRbz5x} zTIfkL{Ai^cZ^C)_A&4ImS6qj^A(vco%b7$HPr$hJ5_U0G7bA`T$QL1w+*Ji$cw8NL zpIA9E2p?AO5gC_|p_P@SQu~G1Ux86dIVF` z>E(|6W#WdFnQFQzr;J7VDX5`}Ix49V9_bpHWZqVsK*yB$Cake~IAW{E+5dU#odOND zQJ=lm2x+Oo9_3_s;Yyerk!fLEw=_n`z^TPiaTzi z#D*tksq`wCn zH7#jD_7$*Tgk{?;#u;mTrNbS2{4vNOdnMMOM7H)?x;U)6@(+~|!zw@U&O0;B4apo5 zo%iDF5x@KzBeJk13*0bw1p}=xqei|(^v89L=JaMlSA6NlRa?z1&{=D}HP^w`CH1+U zjL9?xyxo{bapwS&CjP#L8XaB`C$WV8-7iVC< zRoKN>JN~$ocS}Aw<(2b|*R@2V8=J~ym)$PRuev?@=sCxIFG>2=UE>=PTV8JFJrYiB zvIhfxyFY>t%(dZs>Ghf7ZZQry@x^=lI`YXYzkFBp1@G3$LU=y?%Ak`dI_cTVdph@b z&JE-0*WCy)^IATy)$Zo?4elH5yWf6Q@ykCy{l?gTKmPgi_~`5+lW$giLUTT>49|E5 zJYZzXr@#d=kaG9Q+goB*3F=X>67G5z_Oz$L5OuGEsiRx?qSLVdH84Vd`P*Ce_M_UB z&?w(gq2)*jmHUY1ghVO~0&}QC#k8=8KK!BAlJz`+?86`YaR1d9DCoJfrA;NzGL9 zQ;|FmCP!mK_`p$)rX-#uQ>n^TmL`v4c>^bi5kWo{QG$RZoAqeo4_6(smk~)MFsaDM zef^9mgMuMaKFP|{jIvndxf~m}sLB3$C1KRek``Twnl5Ukl&Acr)s`vFagy^Zt^~^q zc%aTsaAKDGc;^u-k;GfF>w>zJpfB^85Yq+IgZb*2Qvaq2N&J-4JlxC*GLaR{AD(bL z*L(^JABv^k(dC?~Ip|fO1kR0ate_tKs5sBLgLJC1q&ye{Cj@sDBChn0^kib_)~3%5 z^0S{(Ox?cFXq00%+rg+mG|JJbVhyNPy=n>1 zNm7$?l?Uu}XDyLP&s=)Mk2BR^O>H{GlH`t0It{2*HVI1CVYQ7Ybc;iw2_!lm^{q>} z>)?XeRAqvOVsMcvRTI0Zx-z!0lXK-(yDHhQy0fJdyd_yXvdcoAHC|~|t0IRfKC|%D zuY`51TA=EWgsQKoJuD+qo5CoGc4@Fb?T%sJV*fG4@>Wx*{Vi}0mdD6SwzwyarAmod zOP2ytkTvlmXFJ=b&w>`1c#08i;X2f0S~R#)5vp9bvpzD$b#{PNYN>2XQ60tZuvF_U ze5d5y`O-I3@^jw~TBjG{8n?e*ZD($1=`OJ<5vCZFZmg(V-C$m~Uz#ax7S$_Zr!KRZ zvePRK=_t^n04}>pn(%sYd)~pkH@+qwP<>OZ;z&7EzhmLAe`8G90Qb?BO3bWBoQU8M zDR{yC)P!_AOqKFJ48%?SsA^ez$%Qg>!y^`0sEi!qNj^EMB|b5hF|*<=b2&>`X>p9h zY+RHQBe}FRqN|$g+?w!m$HM8cj~N`DV*d)zDk_w+Hm?d^A%kYTK78T+I_yb2pY}AA zEMS%sU70R3y3r5H3NhF@1~F6Gq%+8&|U(RDLK;2dW~QpeClCNz`lx@Qb$ z7>HMS7Vh}GAXMAML5IGwqI3NiNAtSZoNJxNlnH_`s`wUd6!l7Ybi;I4YO%bo5!A4;=`QE-DZ zd+0_Ku%;W%vS|z6&4u^z;cb*46c(lN#&$~NCBNl8SN=49<{H<-qxl|vxbvQ866nn? z`q7uZ`@oG1>Q^uR)wjOx2miR;>?@7Zc5lS84(~KgbbQv|FF4yWp)-Pre-z_0X93ENU$Yn|PZQt2>9|U3*WQ5=NRp9uQpN8Ph&#{v{g;^)aQh=Qq zfgK(E<=9NoUv=4^OxW7u83q3doIey

    -MMiQEE)%o}K+^ikh~C}68)Np86XVmY9$ zMW7Lu(_>Je1ukI)Vj%9k(^Vu}2MQg4(U|+;QsB`GjW;~y;oY1$0>8zN3p$fC>9 zB9`4EJt~l=^ddgyo`qW zkdNVzq)FylN`B?m@Q_Q6C0Vv!AH^g)ah2`eUeR5aBjy++28U1nq}7 zm`JkXEpB6iTx1E^&{8r>VNO&#rs2m;Wk}MYDjopK-C;>~rHO&1WqJ%^6hZ2dC1-MG zKW1RbMOr7A)cVcRnN>n3u!~M6U0mV}U6LA5;2)RZWk9_WU{s_>@}(_OB)X;B4>p@U_xE#hGcBXcY<=hd&S;EI5meg7b z7)}~vCI2i#6S2u$(q$z^C4}4+Q$%E0Y?x0u=N^8dZ~mqa?FepGlNX7K;UFhdDQ8I5 zr!qljR@mEg#+P+AD5=EUc1GxS%AG$lN-&P+neD?Lt>#AXq`kbR2Z7kx+Tqd&rSAx417)OI2!@L?h$rnM$RAOVO<(K8}ms7xbKdYk0Y=Q^U|eR5rYGG!=Y zR6g3kwD=xDBFL*MG;Y{ z1^;0wK3T+i{^XZhqNv~{Hu`0c-llNorf%-0Qp%}XG$j!2M{yd{=0!?|UFDIrqEqRq zU$AI&_Nku&Dy}|=4kQJk8mh0dDLzasE zZ7Qec<#wH^tU{n_Wh*GQX#=6CvCS5%s@(4!z)!s@x?XEq1flR~pRERIuFh+Y9OXZQ@383s~ zR_19o|Aa0u43hS;?#;q#EO^QF3?}(&KvIS zXE-MtbslN}uHaH<;kGVn9B$&quIeGG4(f~JLN2~ct12xl=4P%DuHl?6=YAH6$&qW0 zIObl}so!pg>aMP0xi0jQ2JFf%^~%8FYM|=0-|cM#LEvtR=q@XXY3?|bIRD;=k9^U% zrEmMl?dDbz>7K>sCXag*FO)@yRaUO@a;%XZ2v<7q)kZG>d&cxuuk7k89Aa8b2u??k zg!f+R`%X^i67P}t+$cUu+x}L_Laci}P5e$ymC-MaLdXs3DAdN=fgmV}{iy$*QUJHG zW(+U^$1ckTPIA3kDK4;c5Ujy|)Lqf9QTX3fSgX1g6!2!9)+Nuyg7AO#V1d3Oo?2gm zpm0V>=L*Y_3tzEXY;6ov@7I=GDH5;dc|<{gXzk}#;I+=584m8ozQ#}O6}vR7#F7RxT}N?#gBhY@YBK>u{FLZ&TNJ()_G zp&B!V5I?P|wQpVpukb?O8`|+XI>?Tq>r()237as3_-G(=6d}JdR2cFh$8I9eFHo>W zbkGC?qoCw6)(0yM3|{j8xp8pu<_3#~sb)>mdU5@x*Bm|wE4MN@!7?=~1q{z}0dGRf z;_@xqa4w7S7*|{+#&P*XFp<26;|a5Ts@LSQDqgz!?$Au304`zok33vxC0 zGf@^GH2c$gNi+0uzF-L z)$a2&`*S~Evp{ogVho$f^+`uSGH5w4eJ%4t53_{vnlW4SMgLQ)JSWW(mup9(DT9FY z8wIXN=MYI(vq_({ueyN06|^nW$O4CRFflZ6E%S`jCNcY(AA9S!PVBOjZ#b5tSd*g! zV{FF$w2BU2J`;6OAJ9?5a#AaGgfewx{M%DQ^+xRS6qWJvAx-h=sBO_494kmNQ>+;U z3R>qejtCVVw)Gsn^&khdTz4jB*tN6l2}e9`_o$#5r&!YNU$L!oV3*!a z8A!q`{K7A+f*mwLQjmdblL1lKfotb>Zj*r#5QP@7_AktWB*->WXu&G{f+QGdV#jTM zG_Pat5M*PqWKT9r!oYwO#%0$C_e%8_YFndOwNZ?RxBq2w2kYBb({0`6v;vvwZMXI+ zNWv<#_HZ9X6CC$1*!BT5fh4>(e8YDtJVPlE1sTNmdmr~K5O-1Nw|xKXa;LSeRoN^) zw*f`B3r{z7?_v>5iArY$OY?(X+et4w8hE#2Uv<|W4z_8Zc9Q{yj~MqXkb!K+02$1} zEZBij7{PuYH+~-gYs2_Z#K0x=(Ix!$FT{2XD0p%k#f-OhYAbKZI;4&BRGyDw^7)EaPK#M>-T*Z zMON&CHw43c4}}(x!Hxs^D!jLFBc?~MoO4gPTmM(N>jE^E^J0c;ORy1JmqWE?D@T}r zx5BLJU6eRHgXMXXv$T|V`D{Wd48tfq6OIe_4a5MUuL7Rmd5`NkRD%( zDv$wglYtg&33G2o)SiVO?-rvQwWAa6m0vjO4Mn$DHbQGRN^H7KGs@4@N0~o4J)*dp zuQ_?GLn#EqDh&HjC^&E1IiRz)9RRx|lma@~!&R(9u6qMIc!MpJ0&f?E5zP2-({_@3 zNwLd??@EPgDf_ZFdb6ACv!8Ud*W9#Yw>S3*sT1*$l!twQ`jR*}1g5zWd;0JEWufi|9@ie@{Tlg$Td{SskVI)Jf(@5v~+K2(mp>#XD7Cg-ramWWy3pGJ& zyY_tlMJXUdDrCX|#5sPuxXBB8H3UO2ctg!QLondHHv~S<+k$+kyKDow zNmfA+!C5Mkgp31>Xo4@4_K9tsb*fQqo|N`M#x-vSdd3+MJ=DyOCjOIZx1#!!Zz|yO z^QR^7Xspr38*5Ba#~pd>(Z?UJ<4(vSW$^AP9CZ>eMt|V@(Mj`K#3((w*jfyt6`#zK zz6tYVYd`6t#8OMBB$-7L6c@51p(bKzqKOFEl;jsOP$a|50pCCgHe}|p2exO{NeP|O z`t--1L+#n8mtbsRbN|exKq4y4kmBNUycv3;)^eSL*tD#HrU?#g3FI!Fx8dP~E zP&1Wrdx+VE$f#`=WRNMX8g?iI@fT#ADa{#s)Y>Q9Z&51uWQTG+xMWJ%Rru0O0FGMf zsgJJO>Z`Tfm;Ybx{3R@EfkieNYjgb@$!V0(TGAhb)Q-{0u|;iHEibEEdZVkgSTI34 zBSNrQgS4d{Hh z^zzeDPn|KXx9-Zhs9ANjOTSdtRm_CdVz_O#+fJcg^M7JZZu_k1=$pOYh!$@TL!6{P9I9we{|zlN#*tMkfDB&N;eIxajlay?6IP z1$oK#p|czR(R!B_`UyvDr?VcdB9p!RZ0~ywbRb#&7eNWu&V2lWLD!_CzD%f%e-o_F zx{~s_mH!NIJoaOs2R#+Mv~;RUf?A{5~64nROArqGEiSz>ft_&XRbNq15lUk%H4L;U2hI6XAu8Fes4 zHLmedK_Vgs>7zjo7Lbi&8e@!-s1_5ht&U^DVc4KlJk(Wji@B2_9pMH>8%F1k!UdwiI_)9l9vrk&h^}C2I!KloH!7`c8*__p4nazcf zC;xTOyybLYlpo^slANWJ<~h;X6igN~OX`yyAk+CDW`+_mB=Keq;~Bp@vagf65oGN+ z7Epn13}Xf5Qd{1JwRZEiyI+W;5<#ke>?sTKaTv9c8T9}X;a+D;EX|RH75t^a| zs4ZlvCqdR!sL)a}M`h@ImMSCe;gqYLO6pg^sv~!bvS=O+>r;k`n3I&ms*^fvMRJK4 z#jMno!32&}ml7Pa2Bxi7-4ZNC*HyvZ=&gk{>~lB@&%?eYtx7aVR1ffmzRGm55C3r} zKU=9TW!fsCOqroICreqZ0(Pr|H7$)Qn_AUQC9&hd>uQPehL8oYT($}={9wBmYSIo^ zPxYj&oHEP)-Bz^oQJ^?Wds^itC%4UYE>Vv7PRu?RDQTr6$PU2P&{9_-ah)Y^iC5QO zW{;{C$&*}jL)<9!=(tZ??t7WbUHQ&;A+06gUg^7+``u*+qS5YA^DB|d-Z!&I4Q5o! z8xc_A*D2}^(~sJ#%fP~y!p#Zrg<)%7wK90V%rt98u=`(cVt7hFO>kjM+ESCewjr=Q zaf2QFU?+KZB@C?ajV(-K9T!$=u_G&!I=f>4dhuKu@$V&|DddUJ*oxpKng4iyc~>Vx zWVVWpONo=F$j+MWzf7h@T3Pz9SR_%`>F#{a4AQRkcC9!#}# z3CL=OPm0=-y&l2a9pMd2ysF)1qeu%W@K9kK#w1@JX(6g`95k#-J4&=+8Os+*&h9-VRTAX6Rz?v%be=ddv{9MQgx$F zn;`&SQWU|R5+!Gq=;t}Q2Q`gHJWtQykn$^9Nh|erYn|?JOLg0B&2EYtgCS_!uQrQb zSdGsu?@skN{?h98fzfc>BU$fM2A`G*%bmh?x4hL}4smU_oZ@?2*pJ0tNK+4e-hw&% z_OrG-az5MMBc6D2`oZ{mFeNpkgZ2z*eUM{DvU6o_`W8$~I z?H0*3RAjFb+Sh)$xVOH&?#{uWzj^O5{QcTul<(+cz3}NZ{^i2{#OadH^)uJ3Tx#8A z>R0&s_19JAl^=NL!k(Gm_k6S)j`Yf}8xik;&1xq&$R4s0zu{F zHps;EPNwEb@#;q<=x+G*k15X2V^S}GI56BKh~V%Ed(N%KATR<2ivneEOmwekwr|Ir zPPa_(e%h?=#?RJnP}mBvU`nu%I4}h9MNCWyq*_oVayyk z=B(dTY^~U^yKLv4pd+h}tq~m&5?zrx9?lB6uU5jYVP4N<=tpC@aw_A+ zD&dkbcGAisZIzDVAlvLKJ8`v)@+cM3t}rd=LP{H-EFn{bEv3>eb1E(w(`#xF3^A;V z1g;$;OE2@QFAMW8$IB42khVgyDfDvK))FfHtSuEYM;bFV2V-h{EGq}iiJk&4)$+o` zQYB9knDDY8kWUXkC^SV=o=DRlp71nrME^C7(=oqB^UCZsKWnNcrrL;W>?W-ziw`N; zNXqPDH+$zZo6a|JahZa1IEj-vj)aGcZ_l5<5!F)Z@x9qT;-f&}uV2R}z>I2i)q@@$R$n{%T29kw3@cKQ&Y^ z@Xs};aLr62yYe#0v~oJfk}R1BgDk4+!%}*uOA;}bLijbZ}CW3y|?Sj?3hSfA9@L0taSs@i2tZF>P{O{go!YTgMa&;Z8eeFaI&;?_W8VwUYH!>5gCv*8foO@)Qx?zO>Tf6<;70RE6t@ zD3;zFRw_=mrl7E6aaJlu2j(`e?$9+$Kd)`@v+CXz*HE;H(hvb%*4OM+R$}%_ZZj%s zRye_R<#P6Fqat88PwPN5Pt{PA%0o?AZs-`6MMW`ueDvqakRsJcY-P4VUj#<0_PwyS zZnO4d1$I(1qMwXZj~c>lsc~5U6i};Gjg)eY02g!4mS*KvV{goEAr~rkRzO{ATDi~2 zCW4EehmI0AT7}eXJ2lEy%yNmXX$Rw11GQ4*HdU1?a$Q$)Yp`tF?Pnc=SMjQIGj3r; zmD>t;itLQBN_JNmu>S#hWpy9-b&=O80#rFy$aD+KO8IV2w=*}>WoSK7a7nj1dzXng zbE=ruUQ}=e9Z)~%HhImrDJC~kQ})6{c13mYcJYdYj^Nc2`G~a0v?o zBV*Jb&v$^)H+J`zyMA_yXssnX33qK(cb(VyR(6dLjDCjeN9;KeGl!{?hp|{G(w8^)5S7rO*I#b7PRa) zh`N^|pcqM|82=TagI~`mi{Kh4p zZr^f_896DI_s0e|G9{BK1o?=qmuQ(OlBxA*lX7&^jF6jmR1*}D5zcX=rjb$Ek+pU? zHC1Ap0)PLuMP2keEqRQEa$Rg0?aJ7U0U4NLm?1!!@W6Mw8tPk38D3I3nN_)5?N}WX zHg1hrmMwPc&?N^A7keZ4Z8`Zm12dQv&}n7zJdE*}O-Gr{`6wRQT3J=!P?noiB^o=2jB<=H#k&t!5%FH{(X$o7Eo`HUq9`L>XQ zhVd)&vvHB+qj?&n@wR6H(zaSOrE8hd8XAewIFqy2KxLYIZn&nEwJAeWM*w(HjiaZr zx}aA%l*!R)bY~&D)EI_gtjRiJFlG}rVHC&^t<^dPG$KN@z)jHPBjCCT;@Sv8LRgS` ziZIfMIW=^H2$c63rU`JWcciMVct*2&u}31LquLHX$6z619u%iEf&m!{r+G$6TAtw- zssSAaXdl+0v!9_9G@=OvXBG~?Oddod@`f`sgAB9)moIUzI~kM-+vxIHi+I(9e`KiH zYyVgSIL8>fxJ4qJdGZz8<)k(s^Pgmdw{UpL!N;QGNK9O z!2^Y+W;}ZxG+T0f#tQHnSt|_>BVkwv%!x-njEufX13E?P9z~D%H%{)#7r1Myb}V1=y@R_cs^41g_JgEv$aPUn*Wx4 zq>2Na$KjkKMyE9?5y9$eiZ z_F*5U0U0EmLxyG@yaBTd-N-*XTm%Fo?8GwATi8u}%g}4b{E9BODuK?Jvk(eIC|9aZ+P7C`2Hf0m*ZHAEJn}|9sbj-3Zhq z*fnC<;k#JwqzM9KO)Pf4b?T+DU5o)+#;bjPSQ&+$cC^$cbiO^} z5*~UmIEWfPD%hMW^H}1Iz9M{h^;X@PRbn18q%<&lTa>)kt07P-yvQs3*8QOr?gS(5 zo#uso6&hW{&16AToaMK!s4vq*rG459CT#_Z3=Jx*L&jkWe&hrmG)3Jgg6HV{-Xg+1 zZ*Q+x(83$A<+BOh8F+yZ%KVsP9T1^xkW@>{@YQ7V1KCB2{(_`GF zJ-Ls9zB~86bVKIvSs&>sK2q!NY|ug=sO12jK{XI%9){)s?7`_(!~gN;!SanA-`8ct z`TcJe!o6ACMLyrKr1kFOWAr@;IOfU$>*e%^LSL66w_D%1Nk`RI4fpy>4gH}SJe&4q zKK(nRaau$D(|;DU03jM(BfcIX3_^J{$NmQ-?caIm0pftbfdmU0Jcux%!i5YQI(!H* zqQr=oF8RBNF=Iw!m)=bL2=c&=kt9o+JUKF?%9Sizx;#+PU&WUVjmf-3GpA0JIuoKK z*)yonp+t)sJ&H7`(xptBI(-T?DnT7ot6IH^HLKRGRx@SN2sYzPsbtHVRcJ@j0V5VK z+I#k^+PZ4hoK<`FtQxXk$n370b^vePYQcidS|zConN_REl>clZ>6fG(WPYvEVp7Y2 zS(<&^MQCh6OuTv_Q|SO{#vaGiGX`rfl^dB1V_t$5dPHK3MA& zAe?sIiD#aA?nxYqelq7=m={gRXQ2a0QloyW{KBX=`)IV!0pSU`PNW*WLD?*lTp7bA zwgmG_F!fnR#z0yudYB}mCT7r?hQ5lBnu6MP8=XAC%2Y*bcEnO!r(Kw*oFUm-C$7dG zi)^yW;`wK@Tm>pX@$?0XZI#2l!K@NSR&+lo5*+hKwzl6x0Nbi8gj6 zP}9yk5SU>SdKR&+(L0oEyndwZufPVo??n0*%WuL8FU)YmLpcjERw}YM>%R_%7+^v6 zo@dWI_C%`jX9O8x1WXpOIZzBu#1Ln}7vs9|bN?upc`(8+hvctB0Y8T?oVR9JGjBH! zO?1&l&l_>l&3#qzz(;quGq?x2nvkqL3n=WOQFiR;>} zw(U0Kns3f|=QPzF@x(3OOQz?y@h#9LB1dF3Km|=}fe!kh3ttGs2T8D5@VgQxC`z#`GyGEx5jVwNnU9D4 zs$N5Yn8l_5ka+?O8WO|u4<(ZChIn$~6T=9{ILc8cRYVa5@m9n+N+fJY@u5OAs7IrO zP$MHGVa*s9rZg^*jXrZD7y}8(NJ_FGbwtsM)F`k?zUB>Uy2wA)1jb>0A==PnFasAzJ9{AN<3rc50cM4ch=+cx?5!a*u1 zn@zFh%d9!Mbo#DP@64Pz{|V3rh7(W}BV$0%c^XBY<{%gWSU;sGOPS>{U-n!WKFO!h zd-18C@I0tTKf1nwE~l7bp&v*$cs5Ti6d~+%2&T3f$7m9d{VC28sYZn~w1Y6!qdYP4IGP@8VJU59M)YY?4{_9}Tz1xRkG@JuWtkEvz9kjzEUKgEpo_G>$O%* zM%0+Fc_y;vO4o$`%1e0_tYt6zGQVzRsDvykW;KRUsTo#kFKuctpNc@K>g!nJi);#W zI;bus_OrCDExk0G6|v6Lwg*9NG9luR*>}H?^N-a!WP512vgUc)Z22k>vao9&^rL#+68GOM2%> zOZsSe-t$G;+*LnI%`<22$eZRIB=ZU=}lD`RZqPvPRHPCRT%e zi|MZ^T61I*H8TUd>R<~SS$Wp;i^sgz0W;A|oh~h%7;I<-HQFpyHrk@#-7!&zMEf&%-eRW-)c^mT47{#)bNjW$#fO=W}^&eQ^V^Z`Ns z@RY0EH{VXOyaReR*9EQFOvT=O+3lNZd#=|wF?k9NzVe_8oh*4C=j4DsN$64Tk3sWD zi4*w9b%(m$MiIH*9Ov5D4t?ufXSu#5zT2J#?8MZJiMR(&TaRBFkvp4@%kM1}oN z&GZmXdh(NxYwm?i=@C~dzm=E8xoRgLH=nzx_K?oK^{>AY$D5w79D<0pJpY^`W!*wz zAN=!eEjHO@!j7fH@HO`AmBWmFX5zrb-~*&vq`DFNvQ>28+pZs`(Gx?z{@Zlt@r zrMm@b1Zf0BQAyd${oi}feLpYeoH=LCGrxJB@27(6x2@iCqz7ms)HE|ByFwou<_kd! zvZM(D9r(YJ3ys(H84n93)%7P>3w@LI{%2$``K@y8G4z9O7{jeoSh1~=zDW+FKcvK= zPdkhU23L-9eRZN|iX`^23D@cS5XLiXe4Y`eu^8rG9JKGP+g<9d!W6-Ji~#=eH%|#Y z&<=N%wmi}gm5X9CJqf?bw6d~~?6QMzR=nl;0w>W6SMt&L_aXvh7wX3o2`ZHj@rjJh zaeUgU zec$SybsK%z62=CO3~vdTI%KV$h>g*AmamBX<%xJolJEX4+-Dn$=<$=;15f@G>n`<903l13{{;*`9AT=Iy{la`W3V-zE^|oLvmrg8( zS8V48o8zcNJmgJmuYTlEmS>E$`;|dr(t#hq9)|8Wth{o9lSSI`DlgSNsRLg zcBO5vxxTxN*oUQCDQ4KBraUqjr~o}*Ybv2B>WNLp&4SZx6f-@m2p*n$s?mn%8DaFv z?pgMRVNvPI_~~8_S&{1mc7|GT2epSb1%|~8auOTu@vMTA_^9aY>^o@8dg5e+IS@_| zd@37`Y)=6(XXHfZRGmV7PLtf36`0e_YVorX8Kz-(t-$EUde%e*=;E*s|+F!bb&DRYSN7d*?=+E6vS zhg*=9GctP0D3$)HD);q^e44cTsavcqD1^?dE4;D&L*2!KEAv>lmx+vZ|x1>rT5px9<=c;a>Qs&uhtgfL)cYW7!!preSET z&i1yJV%3=LwA9(hUD%*5(Ys1Ix%RHQvAVs15EM>X20h$RK~eP5tbE(ySFzUJNbc|2 zd+ONwp^*xsQR9yv-*E%3ZSBV?0?2d|`?L*?Q~erW^CUrP$<#GL)_v^s$uzweUGNj3JsAS_aU!Z^$F~y`*mL7FARpd!+0`d#{fy-h zTyCbPyv&M@HJj@pT=pAy8K7~x>A&SgfNE#upg1`F5JBcVbTVE4*zL$Ls3>)>$T4No z#WdXD5x(p{Byb)|QCl(y%;qJ*R~^$}Zq;{l7!-6KVJ#nC8XLw#20%&qjnZz*K-PJ` zdIl7nN88gsHIO-oZH=hK>9OnDW-$)v28`M`8$$9*kU|b7TcZ-SGL|a!{LW(^Y8w-jZbO>G=jwIN;$l!fo**7e8$3Q-08&>mFG-J`V8ro#s0(0CR<0F z^Tf68ELO6L&*#o1W$S+I$*tNsOWv9L+&Q6%5p|Ww1$Q9;GI!RwXYMY*u#9cs^P_51 z@5JW{S#STMBT?&(+Ia~3%;I?!E^q-7ia3&5K#Q48aGu7DUrfy#!u2=B+b)f5&G;MF zJe#*jPpR=p(YAiLSo2so|2_Eneq85#oU9=zM7h)p!z=2wpEs{9AeP zuo{cAhRsg+hF#%`$joO}*z}(a?d)21;D|gT}sW7#^CTokPOjNBu*ZWW4Q{5I-%tn5^ z0_u#cQqkrud~33AYjwM*jlDSa<+jRC?-kR5HTE5BvaNJ%ryu7_NVFYIv7L+f>{-aK!*jQ053g z@4jNb+nW(uoxj+%KNv;5m@>58e!=k#Yi{@OvzuMX6jeU~e%{*a%WqYN-$r{~>|R5e zIpzpy_Mzh49OqKm-wXO8dpYp;|MZjTe;>X)UtBwT*sdr|INz}=7CKc|dOF`sNW2mY;W_)7 z-wUT(%1Z^>*1^V?3*%1r!?`l!)l1V} z-#?d!o2x&}6Vx#97-p7L%Pp-2gZexmS5_13eH=hmy*-5%49>d4Eumj_3q^8?45k~u z9hR$f8*If|uAJ7?OSH;2I{&!zr8)!?V=dJ-%?*D3#$dK}>wYkq&S|%^b@w5xsZ4zp z)zf>WW}$6!IWW-CHEAF`F|%{~(f9Z1N`u|koqrE?%ZG&Gd22nAn^%9F&VxR(`6Nsb zE)@U6TN&jA5diCIF9Og*Pi6+G-+y(m3T_*Io-hALnP$ zn!=4aiC4aVyw-|TN%zzkirm<3#~ zthRor+E3@N`Kx-mEssZo5MU{a7YFjkSZAK6VUWpU4)R0x$gC$H=`+`aVIhC~E6e$J~zMImALX9bVl$ zepryPWB)a{A-{AL)iW$Qz-0MX$$il(Gtg_}ls2$&vWl$tU{db~c)Z2vqSxzNtiY2` z{=3YDw_Vx_!gP27N)(<4HOP)9zjHpVe&)}sE5?$E=W{^;zot2Z9?IX3b6kWE3m^k; z_dinpD_j0p{l5A`T5#~wLqmR0nTM;ux9^61kKU31hDKKulSSvtmYymMrBK3B3yi9< zfzmZ~mfP!fH?~_TXvBgwsb~y}gUmpxt}KGp+7j!J+)zp5jEmOmTr3wK843=p2>HcA zNsEq_r~{2C8M<$^UItAWo={gg>$imYf|ZndI+QGI~I=-9GUsvDBKLU9lI&@G~X%z?xCaPF~P&KDC6-hIu+eQH*~+t;X7h z^;N`_T(?$6ODTPqWED*Fi&kdOL0O%}dX3^=t*l`>hP)sl$unZ@>}l)rB!VgqYkuvV z&!y!F#RmDJ@7S_d4r~Sb?h335xU#>}*$K^dQD|Vk&pWoZ6WN~R^?i2_1ldx64@ zvJ8wvM*$;I@W2$X#==23nDD=uy`ter=xe3_VfKW19JeN#O2!kZWnw6*+}9+mTuCnt zy5Q8)nOs(vK2|dyKPmG(GkcKhrO;qkA56;bUn#RC3Yr9_IW0$ADgVdpCCH`N|A*Oo zR`%ZGpjSC((bh~xH*}B@<+Yyg9%<4HGx3SG3-w2 z9Jyy@uRx`%`9I3u&P-R!@w6Q2hRIlI>*?o8WdTt!xAnzfm=Lpysy=t>=g<9#R95r3-mdH8g%bTo)xLX}07D=LLMVw@xkSO;5BUoD&syWxK{A6_ zVnLO5?U!d}&sFUE<-={)lvqg{8}iYq&2yF7gP1AP)Q8?OD=d_+a@E35(GD6Cjml8u zo)}oZ7eV25vKN_Lw3wutw`}{(u^b1H>-RLlpBr7vEDM%+?zdALj4d87hKv3^*-w-N zG9M(#k~q+P5N2@DW#BJsrBvSbRUnMLP;{74)J*{G_!)K|&uf$W>dNXVWjNS+{@t#$ zH2_HSOz1h(b>)WGwK`aYg1r`3&GDZOE0UvhCw7xxgxa4JMKNq-Q(~`3(Z;oMBgmxk z2E5W@v81K|GOV_=cKSjEiYJxN%HCO3<$o)Cefg)3Foq&zDM1=2PJll4o9E=S-1wMU zQ!hhPM${Q`!zHUXVzf94UT)v(uD$IyBYwzaBdu&Wr)jfXpwesQf1qa zJy*;8egAz#I8=abOjtD=qTtAodo}Uv=fmmC_lFpabja)gt9DnH*ke;)9Nx>yy^VmD z!K3Q$*YlFf5fRuI8-O3Z5SqY&n7=#5xia}VCR?9C`YwM~4D9Oue8ElbWlI&{+gcjN zj~sVbAx8J)R~M-3)2<*dgIr{pt>UClJ9*KphS@)xt^%!Go6H{!!4X9jRYKS6KL(`) zE`7Rjy1vgZGAmX8=24X)s*<_i@VQtne$Re?Qkwbh{&ar**`;k3kKW0!>A3i-r2kIT zU*&xJiC~Lt@}IzVH3->}^WJb;FK_r7>zX1Aui!X2nltLp{<8k3b=C%hFB&}0GrYU< zU*+=5G=$838q1GiRKjQfqwM8U1!QA69p4W_$1mqEc<-uvR9rjPkUp9CU+EKB2XenQ zWBW)p!M>}SE|O1^3HBcHsoTz@YyB?PZ<8zB;}&Zv0Ed>xS=+1gZa); zF(}4ppJPr<74y`?7JLj<%yxnLFLF%n;UX<$*tjTgK7s?d*VQig*r!r2={05NEx_8S z2-~LhEp;|jmQsfsQ)HkJT8&~HturwZ_T1@B_XppLE9B|_xk|~JDP<54qGVl)^iSAsfy19n@|iOUqX)JsBD z_!TkV_e({O73cl>6El7pW^t48Ae9*U>0D~*^y=PAE14$qgk*9ROUL^}N2DyJkDu90 z>_)36ukmCMEFW@A^MIn2erFC)$O2=vXH;mfye2O~bB;`vox8FmlNjhT#za@{V zt;D^gz?GY}o^Q_iQ)^FbAh%B_+w_vRu%jk_6R4z7&UR4+5&Nc@vlnaYGer0Sd`|In z2I=RAzv^qAPIL-($TV2zSx$eCP~(z^(uDhF$^2j==i>kE5@9H zu10_ROse}H8Yq{Mk{)Mg)G@t%=_erU)P}nzEhI}jwBqtlxvc&KQ!>X{C`OZ{OPfZRH<0I-k{mZCt_RKQOPmnR-ffzYW9xNpMD(C&@z6$bmGT{V zsk0_6^L%KFaAdab-!qyhq@k?ttWrPK1%(=vbSPNup|%bH6q#0VdFz`f8E7D(YnH^h zNgPt=)X|2rH`Qz=6?87|x5+j%6u-tdr&Xxf#33?;?++?`{~4yy*T?s<($Jf|=w9u= z59<$IX~baXPdQSuS&(#5gn$<)Oi zZ*l9bhiyD9#@oPqRrR-U*7(a9@)Xnvo654GtsyruAyOOMR|CV;mq}4Cig4D#q^L>+ zQFyi3ph2CMoSf~zLlRoZUh!BpKh*?V&gQZ%SQg8e?-!~qO|-e7C-riAkwng8t%gI# z)Y@Eo`zL=JwomJIXp>96+dz$NV)uqe`!Q4$V{`tVhi#X41j^rforo7-4tSf%7u=Xw zjK7mkLYQ4OgY&0n-u+&%)EvEPMg?Mip=HYrG9-N~pDE?xPCII{)ed>7sBDL)SYZwtf+jZ!I|ph@7eJ2=syQy^er!UajV`gEuiiWcWwV~bZ#9@k5^_z1Cg z$q3b3v6qUZ7#z^VS4voDF9ZWSB?h<>(mP&5-l2?hQT3gwF+Pzj6b3LnipLFm45~R= z!p8D<~@HO8=J2CAOHn_?0V|QVPJCz+Ox}`~2<8ns8-V&5cwNqZ^#p=&w zLs|?GuGV&5_Rm`-q`|Hz7WIo>{EM!kBZlwoh&@&rphP55IHp}pL}4_ z5>(cfOmP&@8Hzixi}%Qdvl4>4;s(jn!2Bc$7WC4I8~QLgs!RBM+Ws%|7cUv3wWtK- zZB*6UV7)!yS1$>6eEf@*;NEW%B?p903)rD@UQd#ozvK)cJ~0pUuB?k8@oCW61u->( zP_H90-fws$w{`^Sp|33s`*lQ%h)EC{;9(TV@)b}4W-%P%BV`|!DDS&CZV(Lgy+y@U zvkwa$frJjknn*c>T7;b?0WyI&MvM007C6IhIEaOKBMrpDmEB<@_Ch1JS0jmMvbcVw zWfB?bM9|NRe0B`OJd*ur2i3@KKC3!Fe_i8S>Yy8;|^Z|sx`nyp<(f3 zaV%MYP&ce>sL!qe94FE@yCX2VlO#w!y?5|-_;DxX!mo>RZB$SOqKByFanz)G-Zb|&|(@2#h@JF956d9eZir}fmg$5;l< z=sJ=ZmM9o@jTm;482XYJ(syF6lCMEfMGd%Xt3jx;uX5U-G{fJ9?~w0-#}?R0jaWVk z;7*jxUsr&5FD#R29|i-^um$LR7g*AWXP*sNr-q#-`MOk*h`~M@(PRcrrhm=C@zel! z6k?u5`To)Xy|aL=YJfej>>V}TwSVUfT4qIs0pD4x7!Qi2evVKhI#$i#;h;S+|IP;{4wvPd)u5vP&zX9(ikTVZn>iu5uQ^+%^Vj+qZlmX1KY zG*GaXQLxN*F#_E{fsJJ*8)YWKAhU(Mw>f!Iz8IVXfOEzmPE0;nm8;UJK_|?+iAZJU zjbNz;NhuU!#|1)!Sa_lU!G8hZ2#e4{VvAiMg9Rw;3UH6ie$~kYj?DphQHS430gX_A z;W+?!4j`<$N)ZL<#FZFpR0-AthcyC&fmLakBs%uqmdho5dqp2Zf!ISY@Oa2_-WPLw zpyWYC6tAhB;S2M_57M?OdZ5KZhm2fC7t=KKN`&1?-sF}{BBz=Jb6d*M>Y5#>?joa+*8ESc(W@KW z#;bMcKi}=$NAD};9bsaeRM&qOZu1_fzsxB!VrekyX*0`dyTUAYhL+DMV$?TbBe?Pj zx$Ou#v59Eu5s+mQr);ThWT^+CYS;#ogOiT&GG?vGy{ z0Zs4dWG$^Z^KMpM>U{mc%U%=3X`DhNMO@T_kHOY0LQ4SZt^K(*-f+8~6^=?Wy+;0R>rrX-FXkxxGAby}pgTrqz(g z0ldb-wy}q@x6=(rX?-pm?c3S?%LG{;$K=dP*$@3uK5#>iodkb4jR-7_*rC3-R2~)l zH4v-$$;O-Z%;OWwduAq{W)34VBrD@M%>aLHZOOwJ*rWw0+Ku(tg+4f7k~i)bSBo!7 z&~n#O?>~sI-8vFhD%(^FK^+1h*II9%^XvXY%mG6>(?bKSy*(jdICbBf-pQXv!&jJC zLcPOzk8Kihed{&(!0EpD^u`zD{cmZ&h(h~g$@Iw(tfMQy`y`xU6s(>kaE~O;05+ub z>Um<0TY&(3b?Z7piyBjuFf$4?R0LK*)8xGD`CgB`MSA0W(Jdf3F5dF(4?A^aD`0#}{ohmuixld;$EDA$6vSE2uUlCOp$ z>e`YEA&pnP#U_g}V&Gqxn9GfL%Wi8)?87NyeQE#lqyq41vz0WCgT+j^I^UnvQ0RR&pU@EgfR+)e2Z zGj>#R&7*s5H8h5P%&vy!5B)a%%18kL72x<>9l20JdL-8#w#)vh;;dicdSwj@v+eSq zmldK6CnJ*_F4*NvhQP+Qm9oEs|Yov34HF&N>ZJ#Lgql+c1f*Uc!NQT zPu9jRbJc|17i`=5;ukYHhty49YBvu_u+41JD0W{qFy6(0c*8d}{|76mCG4kna5Y<%k6&`%&1pKNY@p5tTEHa6lep&9Fb>MvO zL#8R4(RH@(NE&s%!5jJ>dpe4Kw?8mPR*nB#)>Rz9ZN~{6BPlxH-(qpDt<}Q6SiD@p zR2g3m`a|J(vD*LX+r^iM7esh+JCE=k6uL{zoTCA9h||-N+syLr4^%W(t!3%va|dyM+y7|3}m>>Qbxf0feEhNZra(;yue zx}LGq_xpq)auIGSxmho{0hR~vYWNr>W3Qv&T%Q0}lW;?C0Ks-Rb-_668kjf9?4Gm* z?`W@I^cyZM@d$8gs#TDhxre8GXkXTK-H21;k|kC7xWZ#x%j;kJ#dQ19c^m`#;xn@E z-%jG6-LE-DKk$v`zGPO;KfFlgQT)4NbYy2f6f*$sbAx=J0+(rk%Lc%@o1niRhfp*t z(I6epJBObHh>-# zi-e$5%5t^{MXSs9v$7|kn8{@ajQ?+CZ%xW`eF`Ive`bx#ZXSx8XYljwv$7W% zPGdH_cJr;5|LD<_a0{}b>`y*rVn11+kL@5OidnrejU!{&Zqs+ zI;6bV{Ot7#Ih%X?A7)SDsVo?I@-=vvG&m<)28@m;%O!<@^SihheyMTr!q_=mE?GQ? zd4wc%rgMQrGU(+FQ`opU=Gkjq+b+=0AT(GBSRHXBy z*@;u&=h=5`-p?c7<63|s+NxqV2dU~;Pk`Sc0l-;>Oal@jB4h-*xKqqxd-E@asxM|v zEc{3z1OU5dd9AloMOQ{7V~18D7~^0 zmXRy-S;2944gDxBEN)VE&*M&7Qal0}j)b$KoUFtQ_@|KqE(?9Sh~(DaLRhsSe^Cdh3DxyfHS{d%3E;k?{L^ZMbzyA)=zSc*r_*QKu%%~+l_ zm0U}K`I)UNue!QPZ83(mVQc8aoQ8TqO?}Uf#~Za&^x+n+;V;r%wz;lUE_(Tyw5@g@ zvG_dj=Oq1?KiU+-<9W=4;x9jo_pqYrYk8M5|Q<1o;gD7Zywtvx)mFrnre5` z<4G2w{m^g5>^gq@QrtJ@V?sLo`nHCgnTI@tDeZdl;=bP-^jn;+Nbb7)f56pvqlKF{ zes{&=C7o6MV!cTFSKi{6(^EOjpziYh9o@(rX$wyQNFYfIWW(;Mkk4V4hzB0SXl1}vN4FfG0;%I|^ zCe#{)vs81DYfBrFp9s#XZ$m8Hsf3h`zAR;QjMzNA?NV+$Wl2w#GTumQYsVn@Ac5OD zPv0zE2obLdJF3pxDQ2#FzEQkQWLUUZP$=g6I~urhDMi#}NF?_2S5*+TT<;Nv9P^*6 zNOdhm{CK+^~|Dz zFWn$cCoGJbCmCV6j9NlbCqv-&lh`+e1~LsB;=477jWP=d8^TF9|OUqMlT1mlYAT~WynrRd_(P$4jRBI6+~k$VTZFI7E(M+y0i^`@d%1y zI2nuz>osSz37N?`RgLMjqh0RmPX-inA9kZZ-ByTCQE0T}R2ACk0Z7=hP55!&(tN@| z$CG*w<679mcI{QhAKcwUa^fD(j$~is7Qr=z6&Hn=yFWlR(MH7|nB^#>O6kwZE+llP zQ$sMr3o$&ENLX8dZYcYdNrEVXxQ!5bkLXxg%mO}sR2=C-n}kCYWin33j5iFHL}d%7 z%2rCS?4rYR;n8h0Z0H%fsqUv`2>g1vPirw**`tlVa z+fmn`KRxD8_w)To%6XK3O;l6M3R%N>PGRxkY2ol@f0UP8kp{M8IBVND6a zg;sJqZV?iHL*vZirm69(VM60Vb?(BjmcXov)UD{qd3oljN7#jg@-zp9jB}ery+L}f z8*sHh1JYcE%?(BlMl^ASla5$avgQ;gJZHiwR()J~_?x1g0_a}`&>=)Ixv_P(&?qe2 z;i5W4rY*1=RhuSe!!=PmVS%v>gpzB?H#9h1mSnG`Ca^%_j%ZETMmbCCkbLX=jsU5U zcJ{jC-(K|HC%uiO%rTGh3UmuKLIr(*xG~oo_yA!3kIR_7n;8v-C1?doa;_EmCM;B1 z=eC4wVxUdn@n@nV0R81kV`QB^KK1~PH2&}tM$?V$+>3D^#>?NiY47s(Uu}X}IqvlP zTiH{i1Kqx0Sjsj>=SPc+dJ#`B!Cq-`f7eMWB}&2gr5<5&z(&dIoyf1%bSX}ZJa@8>x_2Q2D`K%m2fgko znI;?$*QbRfmS}w2aE;JTqK6H}Yh~55h1$F2;(vqBECJb@WVO%UOmz;$FSbt)p$g8kcV{Br;zZj%BJsC{98p2YaqUIhdCSL1?X&o zDV6l`Y;+ak)mFldYV9_GVw-;a8Oq8YRuA3_Spl7M#`Zz`O#8ZE{r51&cyOI;pe_yEGe}aL6 zZ$~A9OgREi(SU8%*Z~$dCSh6HcE+ZJQJ#H{eGTmWyJDu&$?&Z#1&+KTtZJJ6K?zyG zaBXS~(*2@^NpzV)QjLiS?JmpFX&D(HTR?-wIfhIU& z>L&tUDcmDANs0+PRwBum4TpDAvcHT#zXCW?W5A#w{w#Di3xt|apR=GK%>ja<7tM_t z@KytXZUK-N1j>h08(RRjg+pxJ!Y!eZY8Ies0;+nZf|Q!U#MjwPjfDH!!+fIRNJFXE z(j^SBDs(^Uw8^ZlERoh)E&56p5!j?St7F++3h$2=&R=hynY|HN72@kRpVXaLJA?}# zIssL1iMLg(_XZhVi`_lRTx51>1oIuujqOX(59@ zm3$X-UQE@&mAYp&97;E_aGTJ1QZMm2UX_~2mb5iToBm@`BahDAN3r3fIiMYsP|H?oqoh3%ExL zf}LYim?uVbW>Q;lMm74?snPg+F+^Krq5-lp#xdWgC+16VFF(X3Qgo*f%`Vc-%8DwM z5pr2IVrPtCXQq)WArv1gg{_lwYmM7-YiS;h&|Itv)1REHvI zGL}N)13)ROvegNho4el9+q9C!3FNto6t-{?*6b49A_1SKvdFC3hY>WZ*%cjxLMsHLpY%$VCe1OG%@w@C zYxJKT3-(>OBK_vt>jV&+F>+3M+};;_92!#hx=f zSkq$P(4rpsl4V(A^wn%%G=Ktq>KoA)U1vQSVszC)pt}ZuWi50yXYMorl|?Q_pixT! zKF8IGM*Ce$IGuoq1z{3ZWCjMhW&uZ8rl*`b+?m52NsC}i;ohH<$lmCS^g(0>Vr4_* zBu+j{q*qCkQrh$wrQyv$B$4>jQkCoHTA@^%C0tdVW`JivLhZ? z*3<)`YLW36JA6QMI*0U|pQo0=A=W7G(v4)=>0CjmKuTHiD9S_?qnZRY4oaGaybAyyZ&UHugIXq zXFD!^dtDCe@J*WZxG#o*V57AhQbe6<`^rCAp0WC@{DEn#pgPWuEWcqkmCbR^6tXbLUA3Y)md9`bsf6c@u7aH=6$t zKgZ0DS;b`|EqJISf2bR@*6_#NO$?pM2Yx}Zo6EFGn}QMS18Us|B}j^paFd!P_*7-g6u#MdI{2_nUPGQ~-=#IHap6GzER5wcg>?jeZa zfmnyp*v)$>P7Q<#G_o%(5`AKD``%<$6gP7FThzZ8j@xe?(0v|~lQ`9`01a3Rw1HQx zpRZg;K%Dcp-^3>mFtSGYAmz^j>jqKEEUp-?rue1R6qs6yQCf{P*K_eEBvH<* zp-W!AYzrf9jc&G|?`O-@L{5QjD;KQkC<^ zo3&N14Oi=X@uG0(bJf|bqss5@aR()(STRJ0lmS7lN8jyYpoyc`v@R~iEP?VA41ft8)4$i|AU4H)) zxLpL?x02fd1Nh>J4J3=9krnNWVwVzv0pR=|ObU^?!f*s*NVI`quq||FQ15PJKdz2p z7W&h6*M$$d25GEmNSa*TIq%FliMa|WUSoU>5oj+iC4@pH$@@JQN8$kS+l*6XuS?SX zVjN7Aly=b|9Fo+2@hm7j4!N}cqR$i4*?s4*_q1-6EnCfU`6Hc6RlK4Amy~K>^S9>) z@oPOKXGj2i$7G7VruHLhOm70Ciw{6daLuGe^EC ze_&hyUorqiJ4gZ}(zO(5G=9|tK6eESy`RD5B*o&C6s)$laf~`w&2oOB;3XdhY;l9{ zW5n7_M0kQrojW5Oz0qkGfPqOMzgq;?bi{rgx<425z(5R{x0PmmpG}s%+Q8D9o43j- zf%ZxQ4N^st`@IB70^R&gSyB$e%}sDe8RHF0u8ni~t_z7vqCl3c)vXK6-62bq4|zB7 z9=84q5S?+t@P%ZU?e!?W)`mo(sG8D_b$_%Gg~oNQ51gO#Q2i%D@Z+^`%XPF>vgnVW z;^wYRI2KYLvnW%eD83K)krihP+Cs&rl2L$;C?F6~q*MsHzs3DqD99}dq5%atHd@Nq zgVL_T?Ph=-RFH;Cbe&4S=1V{FFShQT-zk6~cP@VeACTiS!3d4?7R1O{ROf`DpP?AQ zEYR6`enL5VtQHUjxm zVuP+hs>Ck!s@^&J7o}M-!UZ?Gr}k?FE=d{m<(&-&TnS$nZthWUw^silAMkz5mRu}^ zZ_mlT%^x?uC( zS6HAc>nlK1Ag8AJ?hlE6*|INniYwFPbCbuSsA0@Fh~TjU;zhe=iUQV30urzpEZ~uI zI^c5sN7+LU0-8npgy6_UxC*+5jk$i52%h9|AxJx*n@VHRZ+1TYML(0pWB07=T{Fz( zF=oOC>bT8#O&Bcou2d(|zFXiNCWlM6vG5-+aF+3}K>`ocy zV`?=2+(lXc;uN)z950oTYgNwCdEWeLtK8?@9S8#va$tA{y($Fb2Rh+ z%-(DM|6%sZ--P$JdV`$TlC3@meTe42-0Jqe9t%AE`f0Pzo4414nNA|8(L(Om{$tm* zh|eP|^4+$2sq>FV`eOxlt?T2JQS}OOF}&YDmqsP=zdiN&n;%dsd z`J{%u(xk{R>GooY=ehEnY5c70Ss3ag+(%!2`0Y*;@zSxACX&+cwkWdE{yiv)a)(=k zw()A1QlbajL&=+)Arps>cf-Jnj{dCED!LH?P<|CbodTl;zEp%tW3t;$NE#a)$fc6F zEH5f}CtDMQ{I9ZSNXUy+v__XF2;U9Y;=j&HQ>C;h)dusLC0ng9T9}9?9a2vRlHR8J{U5VemgC1#9c$Rl zQd38EG{%J_y&iLFnl0a?cg5~tZRq*;H?e+LN_LcT+F_iMZzkK@)N@wt1%&T`?#9$- z(NJKgc{v$G>3`+BsRH}+TzitZH(mUid0Nf88iGOASu6p0Uwl&d2h(qq+<3;4Ch_0> zLqh_S87YK~16Oudf@kbDA?^VMauwkwnMcD$EfxTZCdE`dNS0?1icI~0&-)@ZiJG6D zcO-<4KoOa3QN=OCJuUjdOjJ>KJezs8WQl7-lvr0O&cXpFo707WfHBZ-bObew-{prv z9#`wzF!Jb8=;u`VoXpC4qbdE0489DOb(`Ek{tbtkzV>yqo_}7B?^^Y0>XI)0$~X3% z&DL-?AI*}>8e53^G&K_KC$>)VM_zcYIVfDT9omTa?$3KZvthqxh2OynOa|e>yxv^~ zlwnD~Il?fPu=u{?Yq`sley|qhzG!n|x(bhi%3{W1KFq1}w``jEj}Bmcq#1kp&cu2g zL=R||d2P&_Jei^@G{pl-klmdw_D71{nnd`<7nEVc324glTGh1~A;mGgmy#H21eOd^ zFd8IdvMcYB$}QxJLBSD8ZPO)=6J#>riKe04*U?Gnr7r%i7g-~vJlER~*qc0+gE;RS z;Z%>i6?9BP_`nFhCpT47w-2mayDqLA6m#SuR@i1332ulUjlI@4b%$&jWP-m zAs9@0BZ)!u>Q*vu&8~qdbf z?rx+(TDrTthHi$E5Rj6Np+mr-K^g&RX%LVu6`ddNdw=V$b?=|B*E##_v!4At-_H>o zg`!ALugLiuiw;?{qJK-J?XU8IiJHX?IYxpWripl*@$%SLsdSj3#(avg$x_Mt@@aRd zY{_w03W7eMhZ6;1AC%Ox2R~3+`}nmeO0sGclNf%C@he{DN(OsEHB1xLJNjMp`O*gU z@^cH7uXQW>AqXWhF)>QB{8GW1s~rZskU{~foNqwUmckXkeO2c}3Xk)HBA} z5f`kY^Dr(uCeF1U)`M*yoLKR9Y$k(?eaULUcMDS z6A;f3Mu4eF3?#mU?n}#F!%8lI3X{mAabNzV)8}@jFCZ)P{qrt!dpe;D>8tzMN?G|j z;7vBBb5r$~-qxR((d+|K;ONio7|kO?C?XI}))D@1VTuA#U%6ge(7f3NlFt`Le4InV zQfkUn*Azg+eoU%WG)|BgeW#bA=|+upP5xD&G$w(b+~Qpc1${=SRrM)JB!7sG;6w5NRC4pv^}DEAMte)_Qk zw1$tbTz~lTEp15yfXp{DP|-1lbU8`Av`n^3gGUIK@dTqpeEvb)G-L}~cepkfFdp}? znGk&7l!=BqPJ_0fFAOvYiig`7t;yD%aofVV6i^6<0aYep2s#a7aE^P>@d=V}xcBwRA$czxW-SPt@R$~VlmV-PhQTmOci?!KQk zwvP}78N*xo#xpJ@oOTROY3D;CckYJj5fd`+i`MrVJJW=6ZxkAHX}LWqx-23Xi44^O_Njdpm(H^=$TLM<T)WLQg8HvedIr)~W{b zJg8!Led(QhkA&$G$!3v1LS!clkUJOI1bD;q-S`vu;F)s30hWAR(vU2bB+vZf#9iiAAob5if#Y<`n*~Uy}c7#?4F#$-{ z;-CZV)8AomH$>rN^saFV-6V6cfa0VhJys|294AAr+aS>n$bqvyBDYvVA%9gW&j)9K z&XaN3#rQ*pwUpL9sGjn#1*Vq3~6ZX85{0sq*qk_oFG(&!}V#=|mK zEv~++=gibe4uWwM7>I}13U}DdfndUDA=zOf9aL_VeQvf2D!buB5;+29AeeLr%vOQD z1QAb-2G;@UPXOz0_JvlEfA!JhR#k{MF-dT&;BH$rL>Xf(Yi=(f#O&GHBe*_D>AB@ zL&@b&Q738MCeoQt(C09#r`tj8Fg{pMympzUyq~=Uj1T89zvi%^18d*pj#7gZiHP%< zeUKkOTea4VdQ~V4FBRNM8x}ixLUV=Jl1MzvZwi(}1fou#1G19vIkWe>*o;+%prPNm9U6pgm(MEp- z?mCU-{21PtGWPC1HiHTN5n7*rp$y9|fwH^@-Yo5kfpAbXt1Lqp^MR=yvc068VpDEf zrpa+IgL3@#8NE?b5HlnFkXk_E2pppBlQ?oU5%{1wI)6Yls#~^8F!tjh4y;X?KYDY2 zKvsfP>#V)->f>GGu-XAWxiKo(WLUHzmXmEp8mb^{Jgi1N%AaFHh>}g8Kb&j~lxY~` zwo?!W#UON6kxK1{4jH2p(f*;5DqI!HxXEjj&eSbM^S>zF#Di>63Rcq!3{DUsW*`$A zivqEnE&qlMDKeAY5ZkJPXf%)sG-xS^g4GKL+aZSarC*6|4%L;iC$+K2njPC)(17Oh?&t=dsO~(4A=B1|Pv&aDp7czHKdCa)oP-tn30T1P#Tzls^J8f?1 zFUqMyVIUx1EK1UV;(EguFgZ}@->5+A$xF|_C^a0*jb36kMjWBQkfInz3YHgGHQ=9T zM^QTP@kkOEcRW3>ox@9xg+b`9%x^2X7-4QRgKiooFIC@NiTSb$7vvz(=39@vJ9XZ> zFPXDhquTP(4Cfb(lgG?;ICnkM^I8j>Nos_k#C))l@PYO(7CF)9X=!MZq@O*1zS{B% z9g!+7kzI^&6p+MkP*Sp335<(W|Ir-!vsP4heev++Iln#nh-RU%mKH4oF2(B}l}ZXk}TVfIvnE{t<`*xT%je{$Lx7cMNmTY3hFK z4DE4{x&RzEDY=I0NUA2k+BS=OVnB%fEy*O*|xCK7GL< zPklMe;^?iCGSG(9YUBx{ARKHl5)*TbiS^MQLr9yKV5kyH5Hcr!Y*{;9V?Uh@F}Nx7 zXIcIi(>uBi>US6@vi6jdYBpxDa2QvX)jtqIR zRCxlODh}cymKq?8#KXbDmdkYzM}P_v`j;byfnR zkwTu49fpy&o}OkVxB2*Uql1jf?ivl29k+1gGT7#kxj@3(?+`Nb7j4Erje%#+Lx3zh zpUn5c7{kvdaN5QZ z!0>XUPW(p$Z_dIJo)LC`TotNN-Y)@fYy}vz8hSl;#(nn^lX~iL=uX2G@t(sya^Ue9 zMl&_XsjjmK8H&q;kifZL_&n`S)Yb8SDAtXO*0VF7q z-)mg4cqjQlVvbR+hBw6!V=g)>u3xf(Vih=FUI;|y7vZokiunaRWd1}0hS1Re;h2s# zrvAj-FvOb}M+5rP=G(l6Lc@x)RaGMP`h2+f9LQ83`;9S82?r=MaR^QwW{*S+Nu2-< zo`$($Kqhk^0doZbYB=T9@L3at06Zj3?9^;XB%EeYJMo|v1^wW8U;bLO3|qWkyl8Lh{vjgHgBr|N{>`qWaS6~3iiydUFeuC&7C`io%r6z_X?S`;7KPk8kkr*^8u*tV~ zFe)f2NKJ%_ZvG*u97alwQRtReniw2t11hYBzfG0o?!2qEn?r)0hzTJi`|(0Xfa1sB zg*$~VMl+;y^n%*t!j66Y?YzUrW1jFiy)9Sc4=Q{ohaJo-o{`$SQ-(z)zun@;qe#Dg zCovgTOQgz=5^(YR>Ed*g8YP&e7@6IQbv|%{sxQhoXSzq!W^MqL0i^I?NAQ&JneRmz ze3Iu`Mb@o~1iK;YVj;JyNacP;gwetB_0?Ya)GgG?v#cV4qmg8MahPA!!kMxlHesPa)zvgbmA*f(qz=dqB2`*W?dI*gX& z_P%pB>w01KawYOS-hK+aK3aZl(C`griZI-g5Ir>-P9R`4Y*?OwMUKUbZ}A0>Z;0fj z{#}~BCA6RWAeTV;_t)a*$YK@kF||W2*Kf_%ZQN z>>H&Jit*$mSe)`F${fOr`{riq{QCPVaNc-`|RfpkF@( zK1787dAvUEiX8t$cW-uNoY9vPu!vJ&RcGz^!7)M(t-x|+?Km&^`PX>5N!H?Cp2@k@ z-jIpmFME<3Rjvia>k`|uv>auVBk{Aa_MFP3k#Km9Db4*pDh4r}|3e5T#;pkc6}MDd^E>!U`BPAdxuj*jXj){Co?1j>JpmEX`S<$hHH#T2c0I~{lh75*nzWjyWr&%ea&n$ zo>kl9ItA#Dy0&yJt!@e3b)se~rY!ySsTHZGgRgTNo@b%^aTh3d3R1ip=H3(^R^-MD zT%JuFX(Au4kH|28UMCPqC{NF)Ted$LrBnhCB`Z5Ix{43wBx24BYj!r9vC4GpO{;rU zXRrkEvnDf#0`GXn5t4uv`f6I%jrr&=0&9He6}h~sK>B=paD<}`^tTvuyrg&Vj!xYA6|8hb9*&#Ydd;^?Ti{p;ceL#BC6(`Int^w+kde7{%l)NE7kJ3S5+Y=F+WyC2^SZozin*ZJ zVj6E<1T@=MEdsC`mT_;3ZIZ+BlI0F# z`h|kugrvsTgG|jO2B&Pz#Pw!f*73$fV!Vi=i6L}nql2l_x=5og*je`}UKT%@rO$oS~va6q&88Elf$|(o0 zl$H9g@jdC8%G=1v6ZII9Ox&VDgokAD2l;xtN@=X<8$gpSi>Os@@rNCj$C|VFyX&6sntJJCDNzI zpnX!H-7bDx|2v2Ju%v@#<)7&a2r@(%f|gPU+Tz;Z@;lMUNF;%Lc|6Ct8P?n2(kFcltX}2 z`F=z9KpX0Vph3|7O?r~iT}BKhnXmfd&lE^?P4V+^VhB=`g*wI7@w+UF*_jj#l2?t$ zG}(2>QcHV7>T(#o1(TXunZX3c(@w&$LB|dj;a3U;U5Qn(_l=(0{|Jme^?JbqC&na1 z(RL6HOoXTdRMB!n%N%BhgIZ(O2Q0^2SPD}TXNzR11%NoQp!8vAPzIUgSuvmyZys?l zl5%vAy{A=JMd9H`os`W=BEvKO;p$HB`=T@5cYCGKLbun!#s|%CB}hQPeZ93NnXNka zvTs$D=~|&ZH)4v+1OKcvnr>8vE4I`*v1x0fG73UB>R~ zuS9-LYUBNM?tJVQO}aGe;X1OUn-v_05L3P}b+B!wAh^h}mc%EchRK_)v&mG&zIwas z#~Qbhe|WWcs9Ngl$x^Cg^l0vIZl*d3A*W;z&9R~od=UFV`ztX);)WsPs#c2j-bz^{ z=NgmkEfPY#X%(e^5|1P)w0H}ZQdGHAsfd9T!=*zDXZ#NYKkSa_`e{dW-01IgkL=n> zZrAhShejV7i=IO&0)}P<+uMTb(}8_SfJHcu!oWq*OrYxDov2y2vZ;cT{L52mhI-xt z)BYdp{3uC{v?{gQ{qlpBA!caX9;%unXGJ^PNb7g4S3S14--AYfkMK=i6{j-0RwoSH zUgJ7EZTtc4#&WFCV>?B~fM!5XN)vV&W|g%>QhaFxt6Ranm3MiH(vtfmyZ}_#HS*Op z-k_c$-X!7t133(d#>-WZH{YwVk;C@AWW|*7Wh`9dNZwZH1vm@9Ta$(f*?7JIIi9#R zo*-y-3a+?*JmH+8a3|GFJQ>t&PUD)UIw^6bqFJ7^w`!e%qul;zfR>dtfnp1)59vHCBmFyu(_cCZA?vBOwGI}<`5tQi~R1TJ{h z9vHiBm?@y_e91c?jCnj%Fh05t0QU+|?RG%!ii+wD!fX*^1m~}FeoNmws|T+(%q^Xh9$JV4%-fb3WP%{m!~lKQ8=(WKZ-IlSlrE`skgrg;kt_4S}s>5gnpqay| z#k6REUQE-O)KgX913t#JR&F^0Ix#0?|CvTBp1XgUN9Lm@Maw~$OkhmYAL!eUbR9%KZ^^ISO0VEPDbL z$0F_^Y#f18fpG@|_C=$%?qK>^p-%8|%@NRf4dI*NvXWkbM|~xE@p(kp2-xS5d3A~| z7ExTaR(Ya%u?dS!FM0hBXVAV9(Pc^IHK0OHP+0|J36#56P!|(Dwd$IPLsKM)4{^zN zZ$CiK|L?f5|A_%oAzbxUT<3 zScm?8N?L+_?ffhDJNGyFzJufq573-R!ZzC+E!hPFQ=MyBeLlJ1D|GxSF=cMnpwb*I zb`F;tMrL(FusnIEHI*NP1Uys;mdDmm$G#b%DuKvHFe+!?vIou2VO{12`ElYgsE{#< z<;QS%wR3%dqt-ZRDES*qzE;CkZG=s;k+%@2y%M1HRu7boqqQZZ$fW0P5kCJaq^|R3 zXS&{C7OW=J_uTejvE8_=F7jpG*}_|n@26NQTU|mzA{D< zwyItu zzdB8TVPlTXBS-wX0Qk*lpb%+L+3F38k4IpT$^Jo%+Q=xge$dl9558#hQtY^UV>0!< z@5sCSnQ|1J%yg%NbX;|mb=DH1gJ~h?oqpXxtYpez#swt+oQQUe^FeX{9n2D|Iyjt~ z{1PO6AHMr|O}Y<&t|Wd9$~9RNs|<2!!r>^nOJ?8q7hwuuXn6w?72?RWnGrU^ZHQ-i zO6Ba%<(sn=>Q37*K25aFWBXZvC<~_8F(?R*!mOPCdMEn+b&{8V8EteK)xR9*A(H$& z62;9&(1cMS|3T(PO&I2`(!59koL<8KiL4z?3n;^Ik|QC9&?J`<&z8~kS(6(Bs6z&+ z`XJW;D86Q}3e_cOQ^dDrF`vD+{BSR~TA7E;`<;nDI(T@~OAP23IL){sjfoSD?r3y? z*|JKy&b5y8?a4N`C+w%N38x*Cqd0qzRdq0YB$42K2SsR?965#vU9>e-2@*xoF5SZ* z#r7+53kas5VxX*I9n&cpBZpl}ChMM9K|6qw$ENN9!m$Z3NPyts4bqY~6K=|q5Nnrx z&9tQWea&ckebmKeDc+1oyTgA=Q6UnS{QeGL_~xBS+!Nud030XJTV9&m+Xm9}I#@`C zy?gM^6qN9&;VZ7``dgF}C4Eawp|7GaFvQ$qr~0Ec^cIrwI*GRXW#uPT3xgd9E~|-U zjLJgupQY`|%X3-QS+{DS134!@IPFU^nau$upp5Pui4JR*bd#QF#am+12SBAwErI99 zDe-BI|K{JfX2frOKfuV~!0!#La6yf?rk}9AjqSzTfOkQ2 zX{`?HXmTqOD^Wy8a`5e4+Ib{eEeB@kI4jigZC=&q;6L>oCX@-Ex@(cC)ywE+k>~)s zqyr(>>ed+W9dU%*8?HzHUR`Rs^Sl9*B2XF=Z(pdspy``YDh{{c)9H<=-k?0S-;7On z#VBV&UPggGvjg=pZ1*>OHabUtT(=?-f0pxU`x_eKT2$77cFK8UL z)j*}plB@c1;uDSirGGz+>NWNR1CfC>x!(@8vURt>E~)Y$)zu(v2m~*F5OoEqtlt_# zwu3|Zf+ofQT|;sd2u8_&UZC*OXW<Jb;#jjnLnp6tBR*wC$dFKHbY2^lhM)B&AxR(p)JUj`-u!Df zrcg7+euXS{#otLzNJhSdZ`F_Pcnmmirv6hr@njP@`dvo%a8kg>Cu4;#LM%^@BrV*| z-BbWgnjHf|4lUM{srm6E|Ef^KB9}ZurUPq*tULqgOOqisM0=Py@N@L6#AoR6FNzd? zC!N}>aRfrw&_wl^s(UqTn-|^nWH})J@Xz27l$mf0ezYEbC&;f~;Smh##I5tXi@8t9?lV z)w9Ktp}(Io1=)185YK;!lKqbO^EJ|Z6=`?Ynp%grJ{yq$e&hxc)*9}_3JHla_zTlX1+@i<# zB7-SZGU<|Hm#-23-s%ku@4S;(syF+b{#U#q{JA&uv4nfESbA+L@6iS&#H;Zif32{) z#6Z~0<=MvP44Kanv7Bb4ug+d*`B)_@2-;1%K@|FpB8e{e?=WIHnovu%3{nJdpNy!5 zw4};*Ng`!(e7yULFC)HMG0gC{R9~H&i+CX&Z!)STPDq=%Du%-}RWH%zkebj$rb2RX zf~X(5ni7icw5#rDT7#SzucxJEpKEB5bch6NWLZ$Y3CDEEx9Www=kq*YF;ks*ds7tR zF@RabH$#B_R?Y(IXi>5nKJFM4^3P<8)a&93E!4wKEGs`*Pm!)XT^h@|(((S7P=kNL zz`BY=JSeA1dMlxrJ?*xW8*X@WjO!`MO zUMz9>ERoU)01x_f$DfQnjPrF)`k2}Wo1Vw6T#4WoaDz}3wyMGM=-x|z?IDlfQ3Y}} zH*B9TzZm%B#KKDv<4{QVDiE_c<|1X2YNo)1RnA}&ldTkXwO0HA6~WF{Ny(v ze%{Ax6@NA{u7=K%uNhML_igDSPt-mb zf(g$+T?sq48y$wY=UYXX@2{^JT;kN=)a32ETSbO~ZYxa!Fjl4Qltm)(SqP(lvd0oflo?Q>*m%R{6L*W4kBjpPdsTSUwCWa~%Q!g* zgc$>0peockI0QeEx|}q19wMX~TTfuDiEUKBjpWDNgUjKaq@h8!R>JoFdO?{9qoJIH zlaV)a{w)0A24mpL=yTuXq}VU2iGRq(v820I-(h+09KqIx@^@+_s_Y)l+9wsIRU5o=kGi0gH>?;Txa;6 z;5ZgCFUX|7;c|l3kot*2mSIX#bJW)%K@A_dDKM1SBbr0)>orwYR;E^ohp1y=X{1fw zDPlvMDZcuuTNlf`;c=OkafR96G2~&w4y@LIr7Ei3Ra!9)0pTvLYO%%x+14v>=!f6b z65lcBit=Zv_;_nir#$=&+;t~#^t9JPs7g8AB#bYfFgy4P#*#-k0m6s?)lr4j5Y zW(PKYh8!~BPQNHb?~yDZ@9UXjbXsPA4B5jd?JI~T%sHmsQRe+SKbBly0&|n70(V18s;<*610$jzl>#J?n&BfXJl&Az2{NM=<|g%g^lkXZ!MWx!6o~x; zqVF&&w!Kdn`1zRx^R@6bApq0Kk4U2tqOF|!5&DWEA?L&uKY4C#@tQ$N6h-=L?@EMI z<7es%aM<0KCf@Lop3}r84ksi$e;pB`Th%cZgUmEns2sZKgfjm--ITHReZF5G6V-GJ zp^hPZg=dG~$VozrqKgOy0^#i0wH4hWTVyp-E6oYbsfV#vvwCy_Yp?13cEF)^&}thn zV**wt)`#3iE1y9SUT-wkl<<^alW+O#nEC!9iG~5OKEneN?rDHvfrrz00xe;_HSuoq z>CSapldgSIx3z_=aw0-~0lP>ZsbM08%2p#gRa27BWZ<^3`Mu#0{-w));_US-5t?0snNidXlLituVf2=-N~ku%+vtO6>USB(DC zKHwrB1r?1R8VRZtLqO4a6}_+`1ji5c$pIKzWj6)d!~5((lTysy0BE+ng2#q^KGp)B zG6;!r9xzVigxJmCsWc(^Ge2aRjoufG!MMoc?f~W8$`l$L*}4?g3O&R%IS1R23}PsA z5L?qIKSvWBuq$pD>0+IN8A%3Z$2fMROAMZouhvsrL&&RLnp=98DLwlVls;)SdvWaM z7(LZig*fcWA9OlO#g6R9%uT5tfz*8aeq2}JOS{RDH0L9u)U;$6JIN9^J}Dq;wcLcq z0&$7E`==2QT+|>WvPdU558hQqsAM@(ayP2bb6JM66M&>UXaps_nQkRD&v-9fmA}XW zI}(aiX>d7Y3H$?+Uj>5Rl(ds_hJ#=U{i1O$>TAos0f%folHnN2+m|q`+9=k)WH_l_ z=&3r0CIj+!c1Xj_32RzUQ7k+LGs+fDpPw`w&4dbrND!!(i5Y zqWTWk0u^(@g^vPBGQH_6DhJkeox-xkp0qF4irXzF1B zeva6+Iy3}MXoFD95Hg(oG7JZBkbArS&IrVyGf2cKIb)n~a-J_UFWNFby1CmFdj(-d zdlXGNE->~G+@g!(I%ZgXl2ShC)8ZJ$WkkFR1=tvacn5L2jEMD~P-k{y$*%Ctosdbc zkknz=lSXLVS9pI)vA?PKk=gtC-Z|D;X$v{vGTPxA-Ga2CIQu#%;|5&B!dMTbLi;2l z7LLw0T?BXIw9%@GS7`bd{s6%^8d6bOj0ubwuc!$?RH_vkfpJnT2$P@&gJ=S}f1QNn zXR=di^1dS|`8tJZ(wb4!RKz;EInk>{^i5l$JptrRpJzo~mx;3GR1rB=pYiOUy1-(Mf#O{sG|% zN1>uy5zolw7*F_2cBgh9<6ps%Bi5XaZE!at;nv3D^dVu$I$zUU zFR8#{hA;6ZFCbE$HXMpo56X;-!id+23It`=N8!{$v60Df;^+%M!m!FaGa1oqW9h0$+2@GBz;7%QteY?uS0^eP zuBh`5=IL=G9z-?)Fm@dxE4o;_+E;$+ao_~Ww_`PGm;jAsMQwxdBLT%T)}R@_Vr1(o z^qo`$eYG}bNta_PpGc1W1ilTXw11q@Np^KD1ziZ6F$6ObjlnLGJQ42;arPJIWfbv* zpxPtdf+*HN(nPEWF#hZg?gI>OS%>%=2&df&!VVdkqs%gbpz@d~EU^=OoIm&vJ2&E9lPw&M(Fwr74n|*-75%q^ zd!j>pzJt5GgR8Od@{Pp6c1BBvVqKge1}NXNQUtl=aaLqj^|YM96%TtFP z3Lput3H9jw=lo{ubt+Fd%f8tJ$h7uG7>3Q{60RePG0gfTOpE>!5x1)E9b3q-1`p=? z;z=^t!$I$=A?~h$;fXU2mP3$kEl}f(SrxzuqXCtYFTQ)j)F12W@CNe@&WYNBjF_7m z2Nmk%FieDM*CiTkDr_Q?T6RNs@?GlW`ch``IetYq{0-@sPvpHC(;= zEnn0Zz91P+a#6 z&AKG(QtIU5(F)1QF5C*6BMGmFrk{;$SE=44s%x0_KL7HQda9Lr&L2EiZazoaxM+|y z=lt3jpb51Mq`uW32=N`@U(U~cHID6$@itX7moq>nuIHE10;l^DD0QK$ZlMskc#bor zbUphjd{L!%QN?}vasjc(v*n@0^3_3P1j%GX^sli-02m`1HxXJVgt|0-U1u}xVubt6 zh;+7Vo$$(hO7^tXyZB|JeGA8>G)e3H6BY?9qZWMob@X}y<*&t+kSNwqR_VWA^Y01i zsaijte9KE)0~jqA%&ajWt={}zOmGh<*No&s|BBVSdi7D+b!py3ij9tQp>}PpO>?7t z;#)`BhSTkuDYr-^Zla}TV(8ZiW%GIHjEsw-N#_0NJj5lZF{rh8V}W~1sblTy+l@~& ztHb9T{h7QQGh2kGEMhZun|F2=&+FFbEB_p}&Stg^-)#NVTo$jbUhNNhINciZUQa4m z9pMI%)U7|yuZ#I3W+)T4bN{YfrR`ug$p+$xVR9xX2fnoF#vP}DZ zkInjygb7pVi#(JvL9);X;w_-&1kK@Y;a%+U4$K&$?34665;n2*Lh(gQ@Fhz2TV!`T z7yN0OCgi2N-kEMMS?@J*C%0_v30xd#OY>af9@?k&3)8YV!S_v?4kZRKTB6Xv0IG-Z z?^{wwBHSy;*7KQfW^Oxp3I0xMN*{Xj92+wp`d+{dFL=ZU4ns>0dw2HLzyz_&yArZT z+cYbVTAs|bm}6TZGY1UL$Jtsxc15*vd4`12kK6e=(Ba2#n~uW<_9Ols4#Soo z-B-8!zdK4JJXIplGo!GaXO3bPSJ0%#^3%_H{#oZWoxT6`!}s)L_UVcm!&)C{Y$DrQ7F{JU=UoPY1Z?tGQ{`22NDAf6|(ranW8JH(g<05**E5 zX%${{USpc@fLgBJD@Gkkq@xj539-ncD3zY4$l{0n!-QC&^XhyZ18hFBZtl{!sL)~p z5q1*(z^^6n?;c`|f376vZhONwq&{a8SW=xe9ri|{*(h0q;rqQ;*JQfrf99znSC~YW zcWn5GvirwfF8pn$yd$wV{Zxy>KhZ9n=~DY|mSi&?vM;WjEyv}xsSG|GlJa^_H(gt$ zE5*j-LqMm$J#HV#5;+kb^>{9}xVQW=x9%1@RDvpwa}R0whpv}T^iO94dMNFs?7-4-KN_2+#bO9Io1V+b@|l3HY>?9tTX z#w107Q|1x`%+3zvJ+pCpSGOfi+1 zYojxm&c{PS%PWj}LoXfe2jFmn{=!84EUMI1D#t#AJv&#i)u_D*!|DNjbR-x>f% zR~J?qxs;8Xwr)_hG6`%Q&3}IKw_STr)6_~aH8x>n6!{h*Bp`gTlFk{^*5hNgc4I$X zux0W4aW3Cs-s~dvzslYs?BUvWMx3hQTaEo(Nk6LJ(d&QDxM!;ykCzZOO;V))N7*}B z_^4fNu@y|PyVjA?zPZ&Pg7+vb1>KXu!2XP!ZPvwi$0FL8D;Jd7RTfMy~t-&>`yOi*NiKFC=tiGB2*$9J0e%{}u z?&^!CZCM`z0}c`>jjfVm)xjzoTD0}-kzFOjE?YCNzw_F%f z(khF$+Oj|r!Cq->A!6oGD-Ii48n`tGY8wA#1oe3nR{Qxw)~_1kz#DdGZTNiDAnMOV z;}KbRzlloftyE`LXo&d7Q=*st7pD~N)|FPACc#$cdLy#AL~mvJ03DPf+F*_8Nw--i z8}!iB%!eYzDXv>w7KHbrDaTMHA!%gO62E!G17F|=x4w^>s;+OBxM$?PQ%}wWo&6tX zFVHfgU!r|30!SLPBZLsj*H$5ts{YK#-=d7o?O~0g|M%(Elbnn+>6kX;&N`VQc$Nyn z9x^d$_hB|*God8p)LNaaZMANCuu8STEnh4u4u_hIqAa?Yg11Mx%Z}hrb)y-Z>r{zg zQ{p}r=X&@}+U&pDPK|}7V(zT)36jSzZUak{LII6JM{lDCUo*OQZUp>s@7{m+sUl|X z{U49MTj3gyfvG7J5aPY^59C7St*69dHO~IKy>^=!$CpOm`Dhvnj)dKtbFH6Gw2|uz ziUq)1XA?hPv7Uo0#x#t~x+$%`=wq6wSIWi|-*pl`%!U|fh*(mT#bb80s#P><)j&;L zW<+msel?6MbH5Ml`&ak@RxC4vUE88$=6RHL^)K|Yhb;0%*%Lv8egD0U7yhvEO+Wle zm&1lyJ{bU{9;Ps1C31S=9ik(Xw5ELzCuYd9E)6|Upc`Ht;b$`v!!X4|d&NFvAgqk9 z1K*>%pHGLL{VC;= zhY!aJiW%JPOo+H`czNYCF4bY8<<78gO(Gy%i;FXir-mRU4hP-;6z0gTiDh* zeDWDpLJ=z!bPxJm?Dm~_)^50$+cZ8!GJK2`Wk}987$l5AEGH{}F{JdEM`ixGgEssLnJKlUg0M{c9|etHig?lVYGFr27&$1Y zCKm_@xoy#fOOxbB4&2iWGg|ySwIM@-jpat`cWCD7#14v=R__CfC+Q|OtK{>4=|ZL3 zDwtk5t7%g5dj9@V$$4+1{&t8eHvN z&9+R7^5PE~eV5J5f4b13WgZfJNF0^?o2(z;Q|^ioRi;`2&xIVpYf?~$$S0z;)lKz6 z-o$V$REocO#eONE=W1ctbGqDYYS3UWPUN{-Xt-4MuBqPM-E}L(h^E`H6D7voz2i0s z0n~Yg4BF%r`&*a+gq_n$%bv!^7Xs;?tk5#;8kjQyD5d=NxO3btcD!qalvO@$`L7xk zHkM6NSP0w_pE!(}OobOu$J$*r-9xt|%$~;n2Wdc-zgNCngzbFoJ1En1^r##sHo=Kjv_S@o;Ds_4>{o&OHXlwvZgM@W+~qEI28aEa zVw)>TOG*~IRTU_AlcY=J^)jnkT}^AMXI_h<_eoD(uUXyuV<3z4zC$K*k@+Rgml|2g zbIPw7GlAqn!~`T-utz2sArHfSq!8zjgA4*8kCw@U7d#+D8wk+~dGNpq;ur%V^zjO5 z@c)r1xz%t!I{aZD93Z&|ST1w%IfLltV+_<~tR~oy&&X0DeHs&!_dN}_^{ zXKbbF&3H6k(6N%9Iz=A`S=2#Za;Z&yYBeF*rKo1LznUDsOnk%*j3`8uf5Jvu7l8JM(UZ<-RoQ(TtZG`knb!0jp4hHWw{_I}-gm40{cnJ$&#nO{ICEYN zKNqN@2$QRIGGfxdk6`Bs^`Q?Fk`e66rNx}>lz|h{QMomIgUs?6>^~}z1C;0B6aR8{ zg1G7N;coAFAb95XV;5`56E7CssAP1DySqHj)_XLnp@!Im?uA<_DT>=$YZ3VU^rshG z>QkpWP6l3etaIex@M}jAZV~Gu&_c=~0mnYD0s}^7xk-;$kx@@b#T<-BZL@xNQ$6}TQGqfcE@<-m|^UEEP@B} zfZ#2%fl9*eJ-H|+OAefX?Hmw9<}nw1o}XW056^%N{5bUEy+6rHs#x7VZ~v&aVvJ)= zM*{sb_Po+T&sNcsUjC$Kef{l!Qq|vI|9f*i-@1Mc|5BCOtAjWy0vWJ}HQ0)0O9w(& z10I;Lj%f-f$c6^%nw}B|n)9%~o0S|$s=?bf>6^ag>p&9O;QF|*eMJA2Y!$RU&ufYyFS0`I}W415UjrBaycJpgA)|PK4U>Sggiy7 zp(eSk%!s#oiv(0yzpQG%B*8)W<3U0s#34LHM8q2*OvKeI!n)}?7ylTBYe$4S{!<*|2#sdaB)D}E!3-FRR^~1b7=(Ipoud*_$_$x$e1W-W8J^%DWi@G(z7)8t>q~%Z%D#chapZ(~cn3Kn zHiK|U=EF8|JHy4qGp{6_U?ORJlue1^` ztb{5T6CJ}=M%Jm^k5h=kEZ41YKPfB!H|b>TzKt2aQrjir0dyOd4% zlug~7&)USzl%h{l<4uDJM+hPWa2SWWi=Z_ihID8)PS73QNHBfS2Tl-(95@DX@P!Vm zglwP&PFO<-m4z`7H#>{Y=#$4bJcbqPj9u)zm!nP;{V=l>#_aSyG4M|BhB2Uq<=Y1z(7QG~fL9#|dB94)^H2}-N-ty$ zJ3NLDBMa%&)3Nl`&Jb43)JI7Qf;$jYXpK?tq){6!PaVC3)MUmUO`cpf z2Z=p^b{GRTbAsS9r(*ChHe<6qYlC8t+JRuR#whtQR6I# zHpm0o#e+Op+m9XDwk<}YiCfjA4Nha!-Iy!AEned-Qov2#wyG`VJy*d!3I3FUE0qB# z1*B`BQo-_vYiNg_+6Om`)iJ;XO#g_!SUCW3K&~8^2Op3HbUc7c&`@e{(0OoB`PUC1@g4;2V8pj`w`VBCdK-QC^Y?cHnj7P{Oqp!C+`z2M_* zUJYI;=H1|$eO{6XqR>w#To4usCw)>}V4wzT zyGlp~S-1sqKqXn|!h!8DO#ko&)y)ASmb3TWMS&OtA|8W*m}G*`%6pI}{Dr|f1LVO@_whgg%v6F+^YDq6)+tyaHYbGQ?jwGeW`Z6cWiIHBYUY=K zWl^AL!qEuuOU=Mt%@WIBngF4P|x~2sVIclV;^4lI40{;Cs&H z+~FP6Y0XA0HGmdqoBx(igwE-rsoA}!W>X@S%xuKhQ#2~ z5S(ZaRq9#Ioqv$0jlSQa&P+12vpmJe02W}s#%h94WyL9@c-Vy)*f$p`CIaCADg}F-^}Yz?GfBw&g7B>Ic>x7+=oh##WvUn5rPA# zodfmV^Pi9PoZKxFLeTZm&cv|?*Gkf4) zS%unM4YYTtWN~m``91*lJz6%!o$DNndw_>}@CTB4=wrZySI z=J2hi2Ctsw={9qa6@%|X@qb7LY;5rtuk%r>aXe2B8qag|W>SXkPu&@VTYy1va6@~L zg$muXWB)jY`8@!i8Y*`10VI%zftZIJAhC`a2zJPUagbQAY=dhs!F|vKcE|>g*_e7L z?0nb+JE^B?zrHbCZtlswp~MZ)F%2gS7NMHt5G-o^yw^b7jAC zK5zDn*mGw$AN^GC97iQ$n1@bqZ*~aD&lQLilm#t6fHr_tS^cnE6^KP98GWeQ{EphG zwPL9qgLe>CW|*l1@ltGfhp3fsUhKPia>)w^R>ihO$@b!3hi6{*!ZknmR$c-~dh@C| zc8a9)Wv}?OqT^`K_=SLWjTax@#Bq+yUcDZJdFYYC8dzI}TZv_d9q9@TEcZPdgKS{; zcK@6y#5;h2MOqX5+-%5LRpbZcT7!<+m^J_^bIR4^f&+fPW{L&#=7iXRXYPS;Ziatn z0S@u1e`hwx$3HbH?UwkZqCujogerB%iR>^#MMsQ-uT z$R3C?5B)Fh64qFF@<-s&&&(O<%oRudWM6&xw<3&(eblxs`#0z!Z2OHAYJlJ|CYwKh z|Ngb{!Ow?}Yzg7)lT~cq0U!2?`4Y!aoWn8V4jgE+@7TLG2Rx3+7f+tPc?olr6L;{K z4^Hpe@q4K*o48~7^3{`G zm@9cQ<;s>XW6rF3Gw05pKZ6b}`g4&YNlv3qt$H=<)~;W}jxBpO?b^0)M37Pp*79NFC0fLys{b zr+o#-@ZeO?A3vIk?<>ZfL+;O?YZh1X4?hDkR7oZG| zEcMARzdY!}FO&Gti8Id3Gmkv$$de2qzex2VLxHg9!(?y}R-<5lakbicTgA@HRbId;c(3g`B2LIwmm4lBy$_#@! z1XAIPt1QLJHXJe&2#A&V<4rL0xaSW|lYqF!FaPKc+E(W9((g%TKGv(738RevHT zo7+-{t+(HT8!orwmM5&a z?Y$?^GVTqS5U=lQ=0jEe-6P|0HAXoREdva?8p>8?($a(+r!-H{+bM z&O3{yExF|K9JJ6w7x%N#?TopJM{_H>>8B4(I=OL5t{%Gnz{kTf1qtY< zTzsY|B9H5#2xGnR% z?>tNM2cFbrkaj7h628F1kCxH~S;*o?W5D3PBxt)0%Ku^vKdQtrz%if!$>SbHsYg$2 z_a|ilB_3e=(XNU|l}|)N7Y^bO^ZJvpe9+?`{;&r+elZHAph_vKx`JFNbO0KmZ!fnp zpW>pp7dAK!R7B!L0#`=BFCM3U`5Pk{?FYs)qA`tJGN7B(=*BlDhmB-nT^C=Mr})sW zK1<04CfZO5c_5|@;%I{+G?IgMw4n|5h!6)!C@*^?@*NQ>hBy#qFChj6i1OIipO~Q! zpwz=bT0x8r8Q=tYIe{0tn8n$ehqeuE<0tkI;yzYYF}S=9V<7p3AfRYPyc{kMRQ%;$ z)F(A99)ycsT#pOj=*-=Sv5eB3X3U;x&1+(FGyifVQ#QNl&C6_aJP1tS0vpH!Vi2iM zh{1$X?131290qwlz=SNSR*W3%V=DQSg`eO64t5PlKmyvwJ?i0(e7vJ-vOq!zWx>u) z$N~;)0OCFJ;f{J#qM$%j%qWqt3Jg(2Re@06PZG9`V64MbEBe93mf|XqOehn?ybF$m z8O)jD#h4_^*UA2|iDfeLn?lV@G^uISqf%+8N?j`d!bu*cLiL$WtqvU%h%REpZVdZ4 z2m}?AgGzt{F|fnnVb~!;dCemS>`)3gJdzMl(Z^mxnyWvE@=15L0UXE^hb-FQ3w?>? zC-FF_HuOageH5jF@vNW^f-#Fpu!2IxBmYT0euxZY)UTlRXo2PuK$8N9VESPft|Rc zd>*K;`-}k`h-553`U(d?`r}7Pn1@G{qOba#P@v(R>p|S{$$bza9mUJ%VzN<{d&p3Q zYapvdLpe(PT)|V5SOZH%qQZQ{5-9SRh9f2+h^5rQQgc}Ys$?26Snwlpp?F8)4tJ|s z-Bh)CU@gf&)l+4{Rt8BTZf|Xy+Y_UBH6&g!i@Ri8>$Et=|9f$DAS0|gAquN`8pG@o z}R&_TlGY!hz=ddUYu#Lvw$=v1UL?#+MIv@~WlmWD2A9mm`zf zG2-f&Knohuzb*8kyNy(BgFD=ok+gKgZEk9jn>^)=9UkZUTp&Tx2Sz^3uIp*!M;>Mz z3CRXOn~ds9_B5TCU`HFgoc|AOh(m;?W=1@2t&dg!FU$;)1)Axx6dDH7WW7^~*4W%; zxgY@!dRQEUnceJWKby`~EL`JSTkW0(E5su{w{N-a?VFd8<~kpAx}&r6pP#Ac;mO2& z-tYn@IM7}mPs|u7Ney=mdE(S?NY%tKj%nv0Bfj`*C9=WQ@S?mO;7ABIKA8_rxOX1? zYPj6Uk*{6xbK>3T53m&@q+9o=9$MRUe&jNSk&`^2Cm;OR>x}2|>GWM5hB>xp4)mIv z2IrE;?c*!YRG$gm@|tgw(5d5wVF=L}I~e^AF5w<~@f~-n_hWztuSX>kDnXH&3VtT~ z6N}>qRK)&?-rtQM$^VEC&H*QUI!{QA!;cS(QCs}4Vh-E*ZJxw7pFH(97yawI5%WFA zKKHZJdFg=OAI5kC=}VtSV6XuQGf+MI3zSI6pDswUt;iC)o=~r-AiH&iob|Z-QCC6*k1(s!+&9o)^yE%BwG}f zTmib?$}LXf{mK6I6ft0%49FG-w%GJh;1xa#6>1^ReBTy&;b?f^=Y<~mk=`5R(Fv~L z3QoohxZn#0(*Fz+-|Jl*{z1xOUECeYi}1(|W9iKrC%CWMjEoA8v@8N zAYoULk`vH_4n4}G#9(5G(qZi1?&U+h03ykNM66g5*d5|OB%&4F;(Y`N*nt>qIbJ8m zm=#*$G)@ULTBDbA;WcXG0rVUwhGO}RUI}uQCZr(?PDVKbfn2a*8%m8Ix#BCT6N1oR z{e41&c-0MVlt}PH|LH^C00~IM1>soH01jUqA|U#37_Ts2GBw^dKAJRAV?^eLLsF#o zZDK`sBLBI8;`o8%4v?S;k|Qco20F?`Ikq4>0!ix~Vh#R@6G#I-nhk`^VZZ!@GQ0!c z36|FQL+Z5|Lj)iC7~(4`;rQ$s$-G=o0h-KVB)CDOL^`EzEoD^xh6hTeBsSVck|8*j z;sc?dNRFgerXW~?#46ey?Gz({+@B34NWq!SPXr8A;A1@S;vcqJJN{D1739h72r*3? zBNjw`G)6N5)iYM*qBZ4HBIaxCR$($`n`C2Sa^Q;*T|sbUN1ER_nq(@1WoB9iS>{VI z7GEIRAY2v?4z=Zin9V)Z)e!PZU0BhC2_Eqs<1e+G;w6eD{exgG6JbIoq#b5r0wE%I25fi4Qy;R#lB<1rN=g<9SaN;L#)#p+c=YDcuIC*1bTBaFtjAOYZ6ks%VJF|ubAEh4YDVtv3>kzm^c z`sdEwXMP6fidtiT!szD7QGhaMN0uU2L1#KHXo6DbWHe~u#Tk@=-3f{2{E^Id9#0Om zK|SnVD5)7slFUyUA*#jZY|fN>>fg&%!k%1Pphe=0R$hy`C}N7K7s}|FKAr)2;bk;vV+`qd?WrH}@@%+(9v_THo8b8#Fl)j5V{t|5BWls&| zFKMY_uuq>-6(uk&HqKrW^7zD5c z8gG(n^mVGIN@TV^o~Vwhx9XhHB|wlN=nUPTq>b1MqLSPeGn{S zoF_5WR2~>#HsqOIBqWf$+%fzBI{gC_UhBq6V#QjlB|>eYX>8Rh8n<}t$C93N@&g-a z2FcDvtfK6Ys;mmWtR|eT%(877B0;~xpfUqNCcXZQF|O=)&!m zvZRp2*^wd!quyl|LD=DhsI+z1;J((=LasF`?&4D5V&3jhJ#O!k*#DS(UigV$<)-T8 z%Bkl5XlBmpt~%M;l4Hz{?)1uR=@!UdHnh^%}4Nzb%t$uYK^; z_C}4tj!)3?tzU?5dm5#HDD9=nXNu16Qns)AQeOwBk^G8qR8>cSo@@S&-X#!8=7#N$ z?kErhumFFq+OF*Z?^ZfV5)fClF#wuNa4SL6qS zu;lSB6wi+b>VOqHZgimVjjHep6A22w@SP&44A-jjIvKl`Bmc|JY7V<`+twR<-II1rs`%FJ+T%?r4&!`%@MNbU~wY%mUB!l@s6Jte=!&z1pi`& z|Nid`JFglOunbG@8|Uy2>+1^6@qnCh&n`vx0;Lh_anVj{uSn}3Z?IA_vT+*nA$wab z3(X?yGE~{9Bu{cUuB!5qF_1dw0if}aax#NP?qe2s^aY;n z@k}9cS@NtbXX@eh@`~OvE+1Msw+t_<^H5PHFbDJKk>EjyasR?_3g&7u&uck`?#n*& zGt29o%Im!*$_-nyYqoA);7B(U6T>Qn6DsWwK&(GF-~Vp5^O>GAI;Yr0R|~jG8b=FN zJaa7z)AJY?bIB60K96!5_Omnp^XNvifr|18mh#t5FB=MRk3@omNf9dt21EbS(Ne09 z{lE{zCq=6-NMkf5YP6>+wVHTzqdj#ui8Q(*??2S@Wnl9El5sxoD!sBS+Pd^hvu!}L zw5`_k4a@8j-~k@s3PGxz;^;_)!EP`Cbrc0|?h&<7S8GLg5w=eCjAnFGBU)gu(PJ96 zGgb9~BJbClbgQ~6kGAXqyzG#Ibx8U%S>te8pY?z=uV)*u7qskWzy^ z#2KCO1D#RBF3`1KSW#cTXMK#p546EDJYrHOw*R*dHeplVZ+`~~6ZZfuwpQ-1J>PRl zrr~7oXg-@G+0Ib)zjZQ}%PmF%U%a z0gJYHTljbjQ!<~NK36c0yz)bHX;CwVK^QJj@ptdq_kADLi4Vtqvp8}mx2p0(fNOPg zXR_Kl_vp59Rx`McAG3GQG&x4N0gHhiT=DIsYVgoSxugb4JV3DgX7(ajwe6f@^j??`us9d3PId5Fq)TN5Yct z>4rORhw}x8+Qo;{?SSOAI9qw^0Ct!+u9k1PG%30^8TX@q&SH~!R=aAuRtDG_D6IOp zKTL+3zchAxw}hWi`VIN?dV!JO`H}1So}0Im$L_2Mx(_66p`Yk{TC}8VF{3wn1?u`- zfcdYBj!4URnG5(yTLzlva4A!US~IvM$Lw|k!Kr`usv|iy=<}=Zsh{&ml!G{V7WEPb z=6nk~6!UtokCCJYd$~_~FmI*3SbAh@2CW)6Gz*?w@B>JI`ZNFd*$%V{QoHD;y0u?8 zgx#jd#+i`r>0Qf;L+9+2i~B5-Gyl7n^SPt@{b2dJQ+(yP`x(YNfg}5;^SA*syU03t zj`#S=wmCWmxf#l5E`cAMy?CcRF(UJa4qhafy?DpHjljXKxOaVoJKpVv@MqVdIrB*_?w*k}UJ$>pvi_?DX(~K_T{)?qQ(Nu2J|0Rt_ zHe{cyy*}v2m-QI~#J>ao1PVOB4b7sw(Ib)vu8FXmTqe+*ZyaRP=)u=D| zbM5-#*N0fyXmojzjaG@a`NbUA@-|4}!#yg@m~dgoglvWb5qT4ONou#LCyYrDR&?zq z*#!M5bZF5rNPo21M=%*x_3B-icK;rJeEIX~*SB9EFJt}t`SsJh&AgNQeR2Ko&+my&CaMIdYghB=6e z<7dSgV+1LPJGP4smJAW1hMIk<>n$dJXxeeRB^sIm37~{J#-d}!L#mSV{vl?)ETMuy z!Y;l163j5g9RIVd`~o}^%{0|qQ$I4@d{e6h<($(qIPJU>&j%???G0mI^F^f%yPA!+ z>VV;jL=agj=(_4!Y;ndFAF{EbNQYa(4TyUSRiZ}I?ZkK}h#-JqvJEJW zBJT&H(9=>&F7vz<*Iaeo^-eR{{1w<>h3${mV&kI|**T3}mf2>@LahlqB$;-HH(tZg zn`czH3JOOiapVfC8e(IZT+k_Moodwerc)TVO7x&buY;*NNgvG!L>MK?_eM658_tVT zZQ|6^NJi>($dkBvOIw}YnB$H;{`juEh8>yYl1n}y36NDz zE7_J4T>ly7n8)0~h*f4;MUq*9QO6%&Jn?6pV15br04P>jWs+5bfx^X#)IsJKcKJc) z7i6AsCTe>G9dX=>;+?lq>g>ID(tq*Y$f1a79PT-WOX74Uk_f&n-XD*28>JPh*)CU!3vAAN1Aa$R(fLKgSt&8S~97-<)&PcCh0YEn;}1mtedx z=I3>sftu)~p*VnzTzc8(0N1Knon3#Nab}%=?0E(m5xH*KAFEyh8{y!{J{vcQEFITu zklMx@k4R>!X{5QS19G2*sW(Xsy(3EX?`8rQT!^0u^2db3sY<-__~oCUezzc}9RK|F z2mh@8W;6evLH!fp0MW7oEs&vF{y;}CY@xns1S1Z=*h0~MQHX0G^{ zLVLIZMOQ+FpukkC?;qQ52&evz9;hQ3^NY0vYH4hPPhV#sdK2 z7u6uh?}DMg4*nyXQgfFeW&w!TUB!8t@LH(&fzI71s*$@%$T^jB5#dY^Z;|NXN%T;Z zgm^D|r|<(NspkdZ{LLS1Na7q$`I>-cq7Y+&Vn)eYRMnJQ4NdA4@f#hhu?z*Br=7Pxn0jBdXT3lt@=~f@YA(IfURp| z;TPb=DT~w#1Yp#-IffkSd#}2j^*&M}l$38LZ89n%o8+E5Of6=&$2eMYXEwt;Gqq8d>qy_gd1oJ{K7h6wf9RpT*^nW#?Gn9a&zq@3rW(S(_o) zp7c#j3-0WB`{EWyQuq#zLf0U%l%B|tKi=?$WWXfU2j2I}S^mp;*Bj>eD=xn2)N-4L zh0_X2_<0MxbHByVvdeS0Lm=)P?GQ}TBQfpK^+4%JoWhe!ez?R+31xm5V+U#Q6O~hr z;G2IP>{Wbu%*lSTl)07W$_o41tx^<1^Ssb+KV*v-E_5HOR+112!gdH|k^L%tsnA*a zrlJlKtU4Ke80zB<7_o_y|05e+r>(o$UU|!NZtP{(y#KJuns&8c-sa|oJ34UuBdHApFKFC)KC+14s~32|LtXG1-;vZkPVTCo(il)^JTaE?4|Yp_)Sy@X@)wu+ z%|Cxl4E4O6n9uUOkDhGfr7@1{zVM+M-r5o`NhDyJkfK=RAEY|^CF_e4j0>#4B-$p( zOX*L4T!IRt;KU}@E%_=}9{>YzWtJsE&6Qu0%jL-j6ZUJ*p z2WyGT4A2LGMT`h9|v+M{>FNQE{0(tI5c5X%*LdYoY z5ktiyX5wxxi4s$!vWCPTki^o+iv>fG)9$bF*l-42!v<54wvz7_zY!e4tOrig8GQ#9**z@bEwnf}}c%5d}XvLr7kdw6ufwM5zVQhavY58y`{|k8dJDk|>MPKr(V8lk)67#v?Vy zD0AzD1n~&9FNPN47agzy!4DyfE;^>88G-1?-iG~JqSBY3kTVj>so5$FU71!19X zZi62Il1CCDI>_%fH0dl$Lh25WErmewjKLvG5gTD*9JEsq1OX5zv_iYn|0qvAH#(6jL)*EV#5w4Um_>v@$d`mdZ3$x&loH zv%EgyJ|R&~A7wEW2^Eaz10$hDCDSB&q*MF>7AEoO+D|+D^fn4IEj^-k%B_^r&=^27 zNkQ`xvH=%xp%)%?LL+rjDYOnUR8+H7Tf>4=JGB4}1XM$HTdSx{zoJZKGfm~CQ%W+B zg6_Poa(VWS8jQ!j>i@=8=P7wqA|`efNd%NSfYcM4#wrvt6w`1Rrt={a_9ru86I1~g zynz-HrY@?^4H=V>z~4y>;{KBV2W$V+qJi&6QMB6cmbKUXX+P@W z@gA3ll8Wa5#IO-PP&qZJvdT{-cC{e$l}^EJ$#gP7+tMGBRap`CEi<7OdZ88`bz-Ns zS}zt`OBQRh_5eN>WHk>j!&PhRCkVhIWyy3lU7{Fmvuid&rv`H*f2;wQ2c9^kcAzTu z?lm}h>imdA{cHkQ5du1v4AYLb8k2!p9rRGya1=^`79Lg=rnX`wwL%3U4j94z!WMJ0 zmTS9~>_!6}UH>z4y{K$cwT6^nIny-^HF24?cr)Qyd!ZL9G!-UvJ14b53qfNOEOe_^TQ`?;VeT`))_P60 zY~dhO%Jfvxb|7GcvR>DxUUhkn(&K-G!kCxa~$AwXetQzcD{VP$PLY}{4aW_CEVVi>bW zB@RG{7={XUv{VS@A8sO_fMJ`0ml~}i8;Vzt4_9HK0a}M4QUPINskB1lKzeUbL#tSk zMHPypxXbvGWh{7+7bj)mK!dA8i$}L~Ihc#l4|$AZRhv*N8m%M@;sADZN80#KLF;F2 zqQ5lZ9qj68l}M2C7=RV_f8TOh!QmR9Ra&ccQm-`?Cz+VXwUHh9%gSP8i&=3<)snF| zA&Q}c(=?O0c#!n9WeF2fT6HV1&0m2OI&yatspn@!OGzkV_x4>eV{~2VQ`I5u8lDn9bg8+Qnvqh~VMHoqK zAwqqHqnq828dO48-A0w=_j@eKI7>oR@YjwD*8U9l0N(O5ad{JdI7uI}I{m>(r?ikW zHWgLLpm%y(16rUZEX=5wr#VJ^6FO8HI#r$-Ax@V}!FN9+dL@kdBBT;t%UCP0%>!xJ zqstP%z9%5TX9*~Ruy(RwUqfk^b_N-i4KsldvQrKKp&^yk71k#k3ZbnJI1?;4758kY z``Va4^rtuS01Dc#m!+wtdPu5Ssh1k5g8&o`qMU|AnjQL!)wB>>L@V}gp5zHQOaBF` z>&cV)77tE^vJz5%%i1*z*MA>!r4JRXvJ#@$f3Z zl(&n;Y-2bfwAhlq8JwZiW?o$ zBi)N-Q#P60(zjTtmm75rr5Rm=CN>;jhgMTy7$#BKlL8VEcHuS1I?c6_cw0Kf*V?XM zJib36&Itj|@0($3+aGRwiCsVe4_(+hG|&Y-P1?euhMi10m_4hTARK**qn#h3y@R9q zdn+4k%uiPf6gffMz7R&d#~csDVLJW+&0Bpb`gd7loyFxF#^d|l>HnL)<)9EYp|&B9 z8wbkOl%3zfv)GNDSf<#*`u$73my?y6UZ$MdFR#9bpBcoGfD?%wr_Qtsz|L_^~>U%x>P{*wQ`@1@=7GhOhH-na>37Z9HmhW`}e z1>^Ja@rMZOci{kx0T?h}!0gYRd$`Tt5`aS=*GFI8<^8^|@!q%b!1z1?ZQuMWGWLU9 zK1lZb3FOJ4TlaTA;*-AGmzv?B*%;X>f}n5E>jjFM3c}Ont^BvT2m+vOk)TB z33ZjJXeKv0k}6%ww5ijlP<0%bO0}xht5~yY-O9DA*Z;3z!-^eCwyfE+Xw#})%eJlC zw{YXiolCc_-Me`6>Mc?viQm6~0}CEZxUk{Fh!ZPb%((Giy^teIo=my2<;!k`9w=4} zPLR)_LyI0wx^!qzpiGMf#jka0)5ZL?o=v;9ZGO}uh0>!ZQ6f^*M*gE_@f0aYh$6x& zD6zTogB4Fv6UA|kCy*h1`THo6q%oB!QG(BOl6-iWn{cYvNl1_&IgDOz$|iKAQKV7x z>)*c=v;Y491}NZw1QuxEfe0q3;DT83<=BG|MkwKg6avQJg&1b2;f9$V@S18MhFBUu zA_l>lYo?uO+dsF>Mon(J@g}2;{_I22F2?Ob3jdDAA(s#=kofW3kPks(5h<|DL6s*5 zcr=GE2h8TAa3+ZdUQCymhu(RkFw&lSg0#mIAut_~l2Afra}%RRqf^gIMK>l1~D|Pn1$}#H4puS}C8E=b@KUCOH)n=1zr> z7t>0v1T~ZkZbmC@Q-@Y-?X}outL?VjQpRVX;D#$MV%?T&?zxpoy6C#2p#~zQvUOHk zrIxmaX^flZs|PGB@&n6^en0{VETjTQYX2gkusWoXIFfS5Rn2&!U5mO-RnoFAiAP8m zG8AAy0R(7~QcL1lIZ914DO>WgK>afne$&PrGrBa_Z1c@H=d3ec-;V3^&wUoL^Uy>O zohZ9VgGQoiaLjgeyY<=&qrOzj$S*(t{F|>DkwCHwH9LlF5yA>TMA0d*kb;O8Rn75a z)cgo>fImUG((9H?L}0+)d>2rF$nwS1(#RNJnG!g+P9^i=ix=(q zizg)gW4Es^i6?^r5j3y2-X9kbK>s0u{|eK2;Bx{`>IzCpzdNx?7rx^P659XK;A7#OeU#&DC&IwX_*TM!u;?*a~)>ggHldYD0t{ zdtjSIEnIm{ftYrQ2N0m!biZiI8WN1DK%Bn@8b^3xLD3ilA zBN1$Y72%OAXW5Zj){Bf-tB)S3u!+IF#Gt@2Llg6Fy!!A`jO8d$>+VTLM_Vn@`lM<0jB*aP_U zHjs_%Q@5lg8CW)$d?P>rRv@e_m5>Ue6)kB;@;%hLmrb;duYBk0TG+;RLiEkAoMwZj zf6TA0P76ZQlK*H#nTja5$ko&UsbO45BzQ*3H4bwPp@&qZDiWe727mh)F}F>OHrds# z9@Ah)D-mLzKrRykQ2n;{_^9$ zL1Yb!ilL&X8Ms6Uez4X01;tR1^1%%2QL4Cj5IuMS2w(<+CNx2t8aLyXA$F=ViD{+h zS+#E~23+8L#fTWsIKAr?D~|X4rXlKpPq}MMeO1K#IQ;=~#+H+Pr3_ zin6Jc^%YpzFnC{+X4sArVF*TW7PYf1zRclNS}`1jE8puygP`1>0>`wKCif5kt909%?pd z0vM<6??~9a-Md+d3GoJ*c;)QsO@KDvIL|Y`|IPFMDE#L@5Bh=(&OU?-{pea@I6xQu zuGl=SQbz8pYAT*!7Rkoyfo+XHE?rn}e_SFWC%M>x0F04D%oiy~wJ|QC<{c0ec?V4i z6F>;U6%_wM4iXI(uqcZ2oTs|qJ?Ash2T%CITZZUAGrZz)mFT4tm}&I-jEaoR52=@i z>d3tsIBh!|o;FcbM@kOZ$1e7=`vXc#3TV1jxb`>12YZHVi9s=jJn^u+?|!c_;1^ef zz{7X(zz@Fg-GcZ)4Ik-fZuZju+vrG5zTr$iu(hXbsruYDYo{<}zCf=d(M#mZq%Suc zOy3Nw)Y9sy9!WOPSo7++xMY0Cz5I1v6!5`722+6n415ojr02mgt#GBAWgNEQ0We@an+O1Okf zNEHLv7)=;(=0F2fNQIF!8|u_3sKJ1n*BatMG=u5DacOMSf5Uvk(lazzBX&SXoznMrLVOrYYQ~HbVk_C|Gh@S6y0BezFpS z)`v^qQ9YcMcPfEiJGhC-#CBAnXKr$TL^z68afCe=g{YW{|M!H4p^C&-g;iK7mxM_a zI2-GL49?&U-T;QvplJRu4R)x8a4-qMkOsz>262D{LGT8~NC=9+2*|Jsypam4kO}{c zU<<*(2!Ay||D4ScIjxf4=651X+;5$BGtWkcI|}R7fxC0tAkL49M^d-mrB00EWnb4)x&- zVpt7jhz`L}4QY6bv#<)Eu?njY3@C|`eUKZ95Db6#l8m4R)0hf>*iPKojY1)Uy%8Nc z(rFLDWeEXllwUiC6&zqi_kXU<~w;cI)>Yw^nB|c8^#|TKdQzqWF(qiGNpN ziteS5WLcJk_k?EoXADULSGZfBA(78e4IEjKv;mU8;0^QO5B4CEAt{mQ;0*uO;0<@l zm#aVnK%kP2FbR&33Z)Gp^jOh2q)2$mp}|qsd6f`ei@`aSb3YH)kjmYk4n*xU-_G08I}UcQE6G6#u;?R zcAP!7mNX!Xlrjxt_z(NA4$j~VWOR$pkcJ~6n8Dx;{(uf~=?v>2nBIVk!JwFPXp%v& z1h8Nu{Ll-*fDW*r2B`p(GBOCkFbEn5Ksi}Pp8}dk0+bLTlm{UOO8^C?DQ2iC7R{g} zOWBm1bqS*Yo5hoEX@W+$nW3HdcTdrk!1&V0!kz&Xqsd;5*aZST`&o5xC(A?6;v>XR4@nSM+K8G3$ri@T`(1lPzuOU zhme^(r4WYQS%$0ERF`mj8p??}w{uJ3n;&|p0GSmcDn2RNsE!(Jmh-6c#hj7UY@Ol{ z^MDS>prox)o-Ue(Jt~o#x{H8mBZ7$x>ky-W5CmcH3u2m!=wPbBunw}}56*xLP8tk~ zu%A`ag}3pIyzzm<;gf1(22&If1d0b@K$Ki+j!ME2R1la(pRB!;z z@CGPJ2abS}+bRgZkP5F*3Mp9%D1nWPnG3;S3&cPS={FK=7pPgup*rB9h`O)Asi?!* zQIZ<40{dqU;sOK9T5Cxur)Ge<7+qQ1|ws31Gu&A)A*KnBn47Vzt`!EmA@C^UzAhCD3w{Jo!tpeF{+XO@{*caK%8kWh1eVXf+n#ung~Il$*PE^Nq#>Irc@v| zM7s(&FcnlV3y$Cjv(N=XKn2K<3Rm&8gy59f&5?Ip^WuvSK3IyXf5-fNX z&>FOHIu$`n1$Gb&s~fx3K&`9b2v(5|(;2zy>aPE#kPE4Br^kyOx{|!+SYyoVyw6)B zn-IOzE4^P~z1-WwKK#Q#d>6IIdH;Y;5C;gqumyEWhi(|3)fo&YYpckR3{3on)qoCv zNwNMA47a)tHsUPRi4NoW3%$Ur`NEk8+>@dCTv>Mj)ZiRBYr5p9f}Wz3SP`wiFbmgu z0B+Ei`Nl0c>h z5W6BQ1hm@)Ppgu{z!7fn3yxrQ?VyX*Sqh_&3cp|r5+$aRyw8+8uWSdX_NvJ|FwmS_ zBQ}D=psd4QF@*Yu$`1X|5Z%N4V8nS)g>A_X^%)1B0R^jo46?Bg_FxbD0H2xQ8A$91 zY)}m3DhM_88M)vL>;S+X=?~PIkzYI;J}49$dv(sdDgB8Xq{Mv^_J=~UaaeQBL&B^@ z$p%rv&HMZj)hYzx%n>+1yQ_P&li)TX!N0X?(CTojn~)2?kO`xp2tv@#tNYaa47RBz zwgElRaLogpP|!Bw51*XS3Y`^R+0g$H-PeBo*CooFRR~VSAf_t$3mIt-M3TA!Qzktqat=3;#$!?960v*?I z-3gqaLUqjvYk=2zO%;dA*MJ?~;yvC=DA)}dJpRB2$Os6%unyAYC{O?hKoA;l5C^@G z21IlKx=1%d;i9@2tKftyRN+_)EF*yk)V%=-`D7fNmJmXD;6q}d2#SJL(WU38)&54SoDneYp*umQFG3(Y;_9bp~H8@A0Wf74Cf zac$k5JQ4`a-TXQgXbaxtedI`<8fu|DgG06VaQHo49(TX&>DE!3eRBtn_9t+Uz@ zv8)gL+7~|Kv^xuVJPH4_-4RwzJp14cw~C7|nyQkGi`769zQCrq4egCS?)}8pkPgtv zH0hL1>0`hN!yV;zz1^EW?|Tgcp?>f9p6{zw4x>KAvlt>rgLxaM2k*opX;U2CC%VoN zh{hgr4=iRrm=QFN1I;}L%g{#^E7JU}(-mtY{UY(?9`ciH?tOI0%B1e=p7K6^>2^); zF8`06uJ1BG^EB^B{Z3rbry5n!83I4>{GuZ-@*=yyTxGN7ZH^FfOpZMZ@*>Y2+A-k8 zGZIx%V`StDO@H+x58Z!?@+sf-n_OcDo#`(>_6%+BHGlSKpZ4)H>Yz}eM^++NQ4F0s z@Cx=1tQ71>a$NrkQ|t~w4WaPxsEhR<5rbo48%!_wf^Xw7Tw~Vl^^V`;*Uj?UP4<)@ z^J;(jn4kGLGwPvGp;P`DSFr?<@R@W!g8qOb-FLIX9tp6(5dShH+<48S-#waex)O}| zBcBysP8BX=8&;3|z+W9OJg<%a_>RBwBaz*dzxJD)N`{D!JqqG(fhS=`0S z3;@xI6Ayv~4IV^ju#-QA4EOotv`NN9iWMzh#F$azMvfI>z&H?6H%2ajMquwYSx zwHB~oYFoEP3WZV=5XzM;Q)Uy=pD!VuJ%0urTJ&hpb3FO-N0Ogv$NV^xh8?9V@J z+pbh;-|7Pm84~MsAmQ-g0)0P(D6!*m=FOddoElyFbn4ZuU&o$Z`*!Z#y?+NEUi^6S zQn6wM)!H#wvSZD*RU23Se72D2!rDb`7oxv{0srqWFvASjQkv|t$};QC z6WaeKq)-S?JXy)HIV$9^!_RQIEkxXObF87>fE$B26$>)1A>=q&!#Npeq)~?QZp1N1 z9e3ohM<0I#GDsnZB(g~E&a5lwDvk13)py z3=FME4kHkc#$?B=oj6I;rH(-W>8r zpcGdmt`lNhe6dDLFSW=>O*iGVQ%^qyHB?bYCACyjUpfztVi1Ib1_b#j2FkKXTH>s? zti*CYE$!+uFT(;PGgx2?Gi=SSUVT$NO-9nBPJiwcG+NJ0Lyb3)w%SlyZG`}_P;dWj zJM@5kH1q8Mfgl}j3{Ki~(Vt{E!8BeOi#WAjd+)_JUw!xGw_kt%HSa1o5GNM4^c0tsNDhbFpcqmM>9X{DD2Dl5l|!3tqm7cR-xxTt{yVzzeO zrDDGNitp=<#|E%5kC6@8F<=^kwq=u3Mlf5qIqVi@yKl>FnG$^iZXldl4(R!3 z!-Hlzam5#Bym7}LhdlD9tZI^8Gc@(}Udv z1xZlc)I6;BuEbT>iM#IF;=dB1CUy1wI_ihM^ z{>Foaq=r%NQeKUiS3L$c(18zxU<4&N!IczaJxHQ~R@O5sl30yCh>1%g5HUWl0q9qO zSs&S8fwuRhjVs6U4gT^MEl)IKhOp^h4!w0K5^bejj>4I`*tMjGATWWy8;f|;g7wA9-QAA`S6}d=8HqwzlffWV?_9{@&N^5%P z(?7Zhy7KL1Ot3h`*T{HAGNn3BX$wX*E z6}nJ{Hnd3QU?x`Tl(1-CvM{Qo1}PFDHURlY5ApHl*z_O^%Ay(!Q^UJr|<_VCwkRjX?3e(>uQF8p@}7BW~^@| z&4uU}&uG!_ezKW^NI(l3xwiIhJpA1cIWath6cC_3ol#%^x?8{+*0;X}Zg7SByu>Qj za*iG07Z2m6S9zt2SS@2HFS{`>xa6x_*(}>iW7c(cx1Iki1+Sf0ItTKW*SzGNjW62d z3DV-JhV8WwNmkn#d%D)Xg|cN``IxSC9Vd`6l96tCJK)|9*T4rxaDo*qs^TIHYf~km z#1a7u=DLp`&;5@XryH!ywq$LsVF)~HsNPkU*u)GO;)zwnO(qVCMAfWjv-?^H z3~qFJ$AxhmTWiPwb0EbqPyTlk!e?)x7o&c z#x=figf?{viP(}|u1vnXY*fo)Vxg};=B6cSc-?sD!@Jeo=3*2B6qQ3(SdW64bB41r z`c76!`i*aYzZ>8{H;Ky6T<6@3p$!U$`fL9Y6Xkcw;Tt1*u_5f z2T~D9XGz30L5bzOgh^QKlef~<;}t2pJcWozL?rBU3VX!6H8lqX90V^GIH-*cT(0*} z@V#rlr%e-VAbR9219WR;Qsu|l$3w;yl4BgB5{Np0)1y9maCKs4ThV;xA(B%9LcC7< z$V4W*KKs9t-S)S~eeR294zGk_nO6}5Co2}FZHlSfN?&7%*hE>>Ap#Nhk=Pf%sOLWc ze(HO!L{&dp&*_J}KdZF`b zyaU9Z_Ww^Z-4nn8B)|eB67{e-IGFz!wj%{I;EU7Qm^E=V>~^9;|E}1mexQ)p^!ZA3%}MFy72>o>w3XtX@ii+jRWYsW8jDOJGApd zJ@12-`eAu%AqIjkI=6A7T}H=k(1#&aDvdpsGO!5Vy>)<_hT zXoDN%yw2-E)%%?wbiYG`zhfYV+&ID{yd#G54P&^3O)Rk~tU@Z>!cY{&Q6xp6Xp%T% zlys9AG1Qn95(x_QHGWVG=Y#*gPU}FD(An8gEK&~JCx&%ems_c6v#JJL$*N3D^bXWB#VYbiM6>y z$%~1Jq{xaa#>+4|c+3CFXOu>l=tz?2$g(5}YrIAtL`n7FMr~Y4N_4t0P&gczmKxG8 z70U!Su*px{$-eZ|; zC9ur)keb9piP1bM(VUZ$kUU#s&-Uy}U4zea@`uerPdPEVN+3y)Ifff-O^$rc*A$8W zoW_x0&Dg}x*-ZaEw)DZ-i!^=y2})6h~N~?bv(`u<JOx!f2IYq$JVLn)5gd?E+PIJsJ2NTFP<8as zG*#0zb)s>g4@e-n?)-~0smJK76SjSSGSB+w|e)Jw%w*qqX|w9-b*M&#I;2JHkptB^5uBROM;VMxa_1w}S> z)mMd8=;{9)iXnx?D5Eq&%veO5bZgN)r4Ky#Q^G@-9CZ+gj66F$fX!UgWmVKw+bm_h zj7M#WHt>hs;0H;q)F++NOy$;Y6;J~uNg-rQ>f56_yAbpm4VXMtR8>`09nM&V*LaoJ zqIpwL>Y7gz6TujvbVI(@=%NGBQ(sL;8VJ_xQyWG7Dnw=0g=JWC!Z&GU32Jo=D#g}G z{m(X7kp1-5jpf*H-Bj63n_x3n_R1FDgfmpFNq7Cfd1cv_b=gv(kAY;xz8JZ>AO&ht zI>gADPzWD^t;~WoL13T^W97^^S-g@MREAYrgzdSlgjkkfvqHqriamgfr9P4D*sRrB z)|~%=2U)dU!^q!sqjj=N-#|rwNLiJoy_aR%wsl({iCKz)1dhVH@v+&Axu^-OKqBIz zcj#50MT@75(aKptlJHSBph|^Z+Qn_waY|B_P|G)w+T3_ttF1g8Y=f=U+>RB^_bkn1 zQ8DC0+f`NDn|#~TMcvfJ4*I|{lXJdK%L_FioxD{KdQ_Q^Aho~UQ^5^SsVvkUMOJ8K z+~Ebp1DI0JquP;(T#$jrsjb@Aq*m70ib~kr>dn-J{Wq@!nNU@_(JkF~Ro(Cv-|;O9 z*2RyCvD+@$sDo^a*ZJFGsS`z6kbgjoD)Ua>wM^eFPaO?j;`LugB?*c(iRBF$&lCTN zM5%<#?Z`?xEz^{a>&BTJ7z^6jN2w{ob`D-wyWR51t8KVLNWqsP2S|a(kE) zcEvuSzIV_h-F3=>4FdgD3H~L+)!5Mq)?v$_)Bv7ZL?mDrD#U4=T4`ipGW-+Cjo>Bj z$gbUCWb8^*^$k_k%MCVN5XRyx&SLqj$kLIV;LN)H+Vu5qhc$*Vl8&$M}FJ4 zmLuh>K2~SBgpojGC`899X5`s}tMT-*U z99qsOXWO}k>%SJ$;>_CYf0ii4&+?U+Fd?p zIT@>8K8Z~f=2eP4VlL*cOXh+$=nWkq*qsaV*|aNJAu^`S!*GjGAO&h*GZlS@n=9Br zO$o;Ra{!~DW($ew8dwl&`p_i6O$$zbi!(8$ zc++U?v!W9e&6)U7Rz_aR>W$x?~27KxTNYfNoyu2k!qVCz-NV7K- z7Q1n1=(m6bY=Q(3eTy~rYdy&17{0m8=|h`)lCe1K!X0O;h6zJf524*`(R|vKi0sdF zoj7|5%kB-A&TIi4?g#N9W8jI;-lNbKZHqJQ?dEPubJMtJ-J*sIhz4AVmJi;&IS^C6 zn}Y*TKoH&@iTeC)WSnP_iEgWeiQ`6Yz3qxjT5htY<>!9Qm`4BWTLKD1z63?a(Cn7B z?so78S2DKPYqWrb^W6p4h7Z7wZPi8i`51r`G^E6i|x12 z3K;fqhHMf*lB`&32~~z;6u%Y~M{DU=;Hgbu7pK@Aj9lEk>;M;V9+zn!_Xi+H3Lzin zB5&{{$MZaIsJ9Smk{e~!PM;`;3$E~oUgc(}1o2mcK~z>xE;n35CJAC)R8?DA7HQ&(m=qaPyJgXQ!~~I=6F1)ALkU^ic$w?oIdr7TlH<{ zb|!+0i2f9b`zb$wUE*B5?9*bE%wEG6Q2`OOTTnXJ>F+W_9Axn ziEUDeZT2Ro?7Of~ro8IezA>~;SPW?6Y4&`KG^_k7RVOxM;TmROpH z&3J3}oOc%L?hXW3aBTnip&I(Rr+a#J3pn*a@h0!3uV$zBAty0xsecKOXC1Y9yk1{a z8oa||PkBFtR_bulY#n>#9s72^R*-BwmoE4+E64G0`x0B^xF4{(C;igD7uBX!wm1{} z<@?w6`!}(<_6S;Vb_r*VER{P!agw$8ZrJWiR>^Dp8a#Q*cvJ!Hi78dhuuKVWeR%D<^}cp=KQNA4>||!1sDC=GyU%OeolD{wbL}T;Mvws$ilnkkST0~-9DW7Dl=5U zXMH@87ShJ26KLJV3F@_fv za#WbGBfoziL4wo->GCBIh5r1#d1&({&YU`LzPV&h!77ol>V#t!niu)~s5$a_#E%E7-7N$C52;_AJ`8YS*%D>-H_&xN_&x6{zQ~ z8a;_l?IN`cksea8?h-C+_%Pzcip2zh!_QyGktF$ns>~5s*U2I`a~3)IGB8b|*|34> zQWG%9C4rD8jav2R*qfa_{c_yHV=m$CEE_{yhKs^y=5MZ}0v+{P^RL zS=fUR1|g)7k%<&qW-lHWq>HklCYpyNMmm~^D2X}I=@67r0;Qdm!3yituEiRAEV9WeyDYQKI{WNg z=M<&}U)2ONOd@{xkxDRw=uyfnef~Kvpn^hZsz)$3Dwz z%VLbGG1LZbUe%~*iJPBPdi*iQA&WdR z$t9b7GRi5dYz|&}KmrRXwm1_BB5L3Pt|DrbvWg+(`izIUf})%5gq;?dRcf)hXmm)7 z7D+3`mb%+?p+n}Y=rLIvJZeO3w80QYS!V>c*HpDp^<1CqybD(+rJUyHQ1GiJ@&r` z6EyI?YA2+T+p7Agw8L^U&HL)Mn`W^wDfjf##()n#K6s9se?I!@tG_<`?Tcm3oU4=q z%P!`if=nuk402~F3Sz$VoEYIP&mjhAq8nZ54syB!aK<1hY7S`xf*I1BWNQ1m3cneb16xM2c0n7-WNnp*9&lQvH0xQR@0B$EU#j)>vgP7*`O6e*Ijl%_l-DpRRSset1yey~<8 zNKuPmltK}V;1-?qFbMsb0TF({+!qVuhf<8OPKQy%7xAD6#$3S>&ICk3K#`%`VKOCi zd=w#X<&aB05J~sqX7-v>qDi6ak0rFoAt4fxtT2yYjie!{pclPKs;iPcB$~uBi4rz! zayntz0YLwEWgYPON;^jsB|?v~%7rqtp$>g0L_>C$Q$XVvy&wht%#ey-%!#9^&_iAb zqljPpf)NASC@ymm2}p!ur7i7ZDIgIEI26L8C}jg2;BWwG)^jAKx#ow$>71N+NT{_M zQPMsm8s`|*f=^>f!Vrc?tF&{5ar=?lvi7@3R-_Hndyz=!7B{0&sG9m*(g6Uv1F)!7 zt;W(=K|z_&ghsTkcD*ZJ^Qu?5yet%`2u3wX5sdu&q7-KE14na7m~D|X6CuT1&VGpu zZwSO6`;oOYsKz?}u@7&2_8$qXWRZe;HwzM^sQRp!Q#&#*dnuJUCREr! z6j}e3*jY7HqI%(Qkhe9i`k;>?L=kgDG@{pdsJW6crw4(etF{JoE7W!CvEUk|j?I;> zd;KnW!zUA8D*+nmcK?}i-F%_0mL@>n2h@R;Ib0k%SGW|fyKDEOep%utzKReld z_=B|Gn1^N25sYVWQf~7C#%rCLN29*>cC_o}kua3hS=}&TIK)a-FDSO*u8MfUMV{Ao z6ynL;@u_t?h@rM|saD_v(!P@_N zGqwt8$cM4Q+m4L5Y$znIMNDkG5hu?FD{iA$C)4JYEO)6RS`M7?7LtqI)=vtH=;<#S)6uONbT_E)T`k+x2mFQ)wJe9bpl#p zg7(Kddy66pBXu;I@CSyy*|c2k#L_mwG^U;9NneT2)1oXjzymJuffHOU)9?nEXTsTa z^r95@jqf1*us?1IFw0jCV|>S04P*oZ9W(I;GCcle0{^4csZO;wIGN_unUntwi>@}z zpR-&?#TzCEK$StDcgP({rAB>L9!|vS0(9R9ovVAM{^A#96ARNL0 z7O|mVGZX_H1i>oI0)!mE3m(){9!6!;3P=d zDr^B9n3h6x<4d^QH-aM#YQk4dMsL`}BXUGRWJL5x1v~%ZP&@sc56l2en#KpA-aV!s z>+xehs?4VOO+X5yupp#VP9;@VbC zpr2~)4%(4~A09w#3d%sxCbm_Z=z%992FKSNLyO&6BNjv@yh28HC90*|0qEoptimr$ zLU;N=Ak4xlOhO=7=ym!)9dKwM2*M;>Xha0Ug?i{Dc&K-}O=A+Mr8wbu-lIOACyuVw z;s_wWv1fY{j(i5GkPc~(*{1?6WI-4yk^JIE?57&_=YQ6wJRYKqR@-j!2yv_kNc<*2 ztidX*0z>=*k~u>{09ZAADJyj6bgn{%`oNcV=OoO+M8s)#Zs6wOj8-YG7-fx; zXVm3rjyevHW}T1zD3uVYqAn_UT6Mw|1+yw$EKaDg))jXkJYu zFosS&M9@Ujx_Kg`jH=2hX@W9RS%IR`)k~^2$CX}Ut85d*G~yb}!X!K*J2*o%U>39a zgHB4sbYiFv&}l?mK}r6=!>+;_Tmi-=tEwz3f##pHKI@;B=RQ&^cA?L;KBcy9>$k2f z%eL&v+(jr*!#nKYRenS$fR1b)L{9(Z6e#SJKokR#N`(;O&gW^Oy~0>)fTtzaWI@ct zF^obgOad!l=s?&)$n68LO(bXSLo&QVi&|{NenN)^LP`4S!_I=RRwpZ%t;XI4$AV}6 zi6_Y3W3gH01!gV#+3}%l<9k2JWulVj_fVx#9%c$!ukaL1hqPF+8qXB1F)( zYDYZo<5mVJ?Cc)~jpkx*WmvA$3~hxREz-uLt?VlhvTDrMS>Wwh zT&9@lZCv#&kP0sNhOhX($6^17>qBgaLc9af?2b(|kmVKw=4x(#&M*B6%DcR;afzXTzOaox~11BKEBuGR_b^<+#*@7iQC7dYRzG+10ZbW2fh!XEa7_X9? z;#u&Gb;t$wb_D?Lih2UYW_qv6jxP(hunWUQVwi8doMToJ#QVZ;D8NA|bj0S?uMhvQ zxj05-#0LC=0_X0m=YFo`=I_wLqyK8Ka5RMS`GYgA0|9$OFSJ4-d}$!~s&ae^X`zGl zJ%hnSL~>>@MW84YM+65iiS?2N2)}Vw$Z=YguytkHv7GQsq_7Hi#|!^4AP2HnAV$o- z1Co|2n!PV5gaRhOK_36)6eAZy4$}Z7Q*ugjL=OY8Ci^h=?Mr23@(*`z65}uY!Q&eH zK&*C+@euGGp4zevCo;&YtQuM+bk;Mj!c??B|{7- zZ?ZebrVvla{buevhcXglZYOid*c?ors;D4H1QML6D$D~r%!51_^z6=qg1N3lyuvSt zF)~!csy&8hl|mZ`>_n(&FKetYJ0|yx$3Ur`R#2}8=fnt`^y}>yN%!dNO|ueVGfc;H z3+ur)hgAZlogV+30=f)FIrp?rZ(ozPb3G5Wp!6($T2&DfwL8PX=Q6QE?6Xvr+ZBN5 z6$Gyuk4iJ38?c4e2?oP748tfCLNKstC0r4hC7THTgSDgr#sY^# z&_iTmz8v*u2z6%9FH>UzChWtzKsC9o${NJ!EVQ=6N>VO313S#b;Bg$sJwq$pki?=% zk~sr95SUqNWQVeCTpMq*(!_dvPYCY>K}E@O?{&#Kgi=BaV7IhjkCI_$w{{b$V#jbo z+^l4WHx2)EYB3b`_R(`_zjL}C1ZT^ua&&ekUUqtGat_pY4zvMj&!j$+P0#^HRcGvN zWNetuL$aX*I?O|AW&|f(EFo0Fsu7qx7`PbALm3x$z8?26CpYxo#7gUR6h^msS|-MD z?{@L+bvMO!r?`qwW!gc4VT6=noC0`@cVtsGWgHMwC-r;-@!^@yO>j1B?)VSeH<1@P zeq(}u`{k?hBw~6(GniIK0+?m(!@u~z*KmeqEze^1q+AcB$5PsSgmi{?xMXTYrd4am z=rKT=_=zvYioZFWccBS&w}>9o6E5ae4!%&!4JH_%LY&|`+^#T!rUaj7*EpsOQo+$m&4>oiwT*7?6*^< z$A3J@T&vcNyqllA*pGcfnL}Tw{9P0-VZ3_FTQblp1ifo=%)1f3>x9j_;H0mJ&i1?y z8@kXFJkaOB-w%DE7yWDm1;X!K!W^hy$`GKZOlA*=JI_I^K3C>4QXS7 z*8u*&2Y!7IKH+0RB_MfhM9Dq_8bzPXP+ z`IrCs_yzr-zUr^OC6C1GyYt*fD(*W(?VF1<-9#pzcih)A5-%}8@Dn)j7(aje{QXn- z?^rQR58JdElY?SKixVwo)VNV&n}-Dlh7{m~msrk0D2vJehK3 z%a<`{*1VZ>XV0HOho*Wi5vg6KO+(TnhDK}GuVKfg0q5U9I6-jd*1i9mcW>OFXu9Rc zw3zQ8#r#1n?i)BLSo%{rejV*2}}62qv;^;6yirbh}u{$hxE+cs6G9x%u*%$ zV3Ns7{wncdCjs%yb0{{B0t?2r7z|XauClr$si!1NR8g}2tZ@G>4DHhJ!$~Qvw9!j3 z%~aD(IqlTbPeBb;)TQ*$0}@zHfn^tJ_<=*mS7`uFDIbBXmAT;BO7c16h_f|_=#Z;! z$T>v<1{h5=VMAFUW{@hP`L?79p)R*WD4~V^Ddw2*%CiUwioQ*gqcw>Q52ZKZWJyk& zYO|>lQ1py9UOo%-bJPR{&DSe?nOfA}L`ThxE=ac;M$$?VPFS#j8E)9&harww;)yA) z7^+fDJ&l_9T!l5ZP?nr0lNkYE1IVJX75D$SqgQbJO(!zn=#R6X+_Dl~@1k|N69esW-q5TkNsLrps)z zA?3H&FJR%V0MYuG{Xt-p*U^z4`9j@4o@p6k}62Mu?wcJcbRFrF13P@!WtD ziK-;0OSxs24=Cp4%4K$1pqrP?b7#kT&X3LP4DzzOqWO6T%ZFs?HluLUY`R=G;anG2 zo3h^8cbN3LZ&}kv+Ez%utd!9#xWenF;?njCpd)1l^#QLJw(>g)Ma93t<>T z8BzsfOZZJlGM6}BkNsllkEcPew_WfJP^p{ZWk{)B;*} ztaYtpWP@8t6ITM;1htoFsU{Mn2?Z-ylmcaNhEzG*p%^2)u$*NwYkAmQ@TC>JpiqT< z984Pl8Aw46l8}Y`lOFQ$!=`{wM>|}f56^e9knM0O*Qt$CmRP^vA?sNGiQ z(TX!!odCDhMW#LEflk96OJ;y92v*IEAwgprePWc77&0n&{2*fTI6SG)(J{n?7#=f} z7e6kuFuZi;GocwxX-*R=V(1Me$(JJ`8HxXgko0D5kP{|sMWtBBq8}SL`9xd-Wqv{V zB#fqL6aQW9OGRUdLoksNFIohQVN@qNgBL+;iR6|QBoIm9NKK_Y>X#eb*IPoE7`0IB zQORWHMg5{sjc$~q9rdW!&S4y0jf5YefX$L@^GzQDYe)j*CQ~w*v;P3JpavC4yNq?L z`RKC^FS1WOr4=-KS_@nLcpaH4(odm<#GL5V#4PzCK!R!lmk0HSFgN-}Kq&~TAhaV~ zB4n|OMoO6&HS0&wnpU;0m8~Q)$F9c5IM>i-DVI}etyl_GS}NpNOf;w_`npd09iVCv zjOt+tf~B2Cq^A^$S_4DLzmUw6o(KQA7D>cY38W=ZuS}ICf%aNUe$-SzR_&@sIhfF= zG6@5-csS5}A4IckdHfDsqV{T@h2XI_J5lx^y6<-IG9+a*2qp)tAC# ztz9~J7-L3dQF|+4Z4ZW9X8xAI1vc=36$+%qMMZPRMedZW%MW8|^0@&*)@Y@>H3BK6 zuydNphv5^|###ovC9Y2>O(#$Fs<&M(wHk&6M6dWxRJRPZm%d1H+P3U>ZT;oje+za( z0b>-wMK40PFNF=aOOse1<4fU=mqppASjL>1+@`)$Pn2~(V=Y>suXcBvfgo!(_887+o%2H0S-u+E|PbGgr*?nSPZ(3b+*kb$D%i|(tV*|K!OQ#^u4Vv0hbf^Ct6J8I*``s3>( zcp!{i)e!u;@Mf-*u{-nS42pScGe1nVyRCY(4f1W_{=B-cp7pKo=(F+86wtD{CV!8M zCb!vRaA)ow~;6C?QHWt{mV!V~}*T;nHyxFx9dZ>*4 zLD3$Ax_)YIevFUQW@&Qo( z@PrMpg<$q2zp7&MW(fPd;`8Y2wYabQvgiA-g3rY7Zq6?QHE;uoM@d2g@D4!Is)Qt3 zZRi$*`RFgMl%mR}YfhX(>bQwmjBlrM;{O0J`Ls>|hoS(Nf&#xH^c2vAu8#o|BKv4A z0>i3>e2^q8@B-_G1EDYqrO;uZ;{!u*)v#i()GslXE(N2){?>{2g6IX8!bs-C_*x=A z`eP+*@CF|*2X!$2C^TW5oTBZb4*|VOQCz6L&gN{4;ST{Z5Cw4%1+gUlaQe0n31w>! zm+&rx%n9vg3MFw8De*;m1BfcGK>VQ@Ji+VYLm)s9F09N8l@8Lxa15Q|7@p2u>_ZJ3 z!wr=W4&(4A=5Qepu?L6HwH&1S*s8v6k=_(B317$#v*O<%@d+z28I^GvKZ7@bD4RB z@5(Y!9Hm14;%0yiU2rKFPhF~n_=>N@@M9gj>n+?d`QS14utocrA|MSB4|h=ycZ-8y zQu87t$J!>4Owa95k02=}A&Igmjq)iG*dTJfTY${gr4O@~ZUQ#jYaUZGACgV&Wf6<{HFb^5UCvlFf zgi>LSGB5>G85@q<6oM(8QV4{g6P?BrJi(r-@_r-}XDG8WS&%2P63rwD7^v-&zVhNM zPANiijH={KWMU2LgDF0<_|noT*7EV%awytQA?9r{eht6wkuKZH7ZIbiju5u$2+ta( z5yS8QFQaELkuy2Z5BL^B8WmG98IxGT#223PF|+V<8qG2(Pck{lh}`d{*34-z3DVw4 zDL!-RMsqAjO=?UBHC^HP8ds+Mq&mZ$URvCK4anlqxX*f@0*3rKv7cXR6}= zJeA^2UNpsU$V*;gYFP9D-qSU2lty>7%zCsXe{?hWGskihK-Vg@q+$re4l(x4FlcOI zo^;P1QA!`wN-;H43#>pqK`Ee8ugZ|ytRykPbTP#gMD+xq*iAFJQYf6yoKUnURP-q# zq9BY!74xrL(s7JtltuTHDauhGc8aGW;!m^AK7oP&7XnBb<0tP>KbL|?(+ZEIuPGR{ zL6~$&V@m=nrcjO1Qm0f?#dTaiiX=MqQzfV3gpVdjwNy>@I^iu(oa#(zqJmx(SyG}Y zUUa*LFY)^I0Cx3P4**YnwIzVnJF_dh7H_+T^;{V11_QMvd5}VcbjR?KzVy-mPwtIb zouWw-5kmCFTZ0l@34>fs_GF>SA0V=`ymU)x!b07(Lr*ncQ}x2mv{iiv99v0D&T&|O@c0Tm##jXRy8238X)5NBB7V#5WL1S#OqFT4L-q;G}HWo4-HCm-rZ2QvR%GPZE zLTynub*o3J6t`TyY;N7vLqG9zstRwf1823yDNy2Vy$)`6BUcsJYLG&SdwG!3h7mG|UoB6z{;d7Vq!6+9x*oowf32~mIP&va`h{MiDy#5uTm@cY%{otow!lTi-sTa zDL}Z2>GnfucNAl_f@bw8>{o@G;v^JnSL1?j4a>!lw+v-icgrpRa^r9|gRfJjH**&e zh_TNB3#Bq5aC(rq0+o1)Pxpxhd5}{C<`%*$95X7c*osBigmD-s%J_@XOh?tlbO5$B zsp2bF6^*GPfZOdIc$n6$FnP)pHfGdPFu#0U1OHd6sE8H2%;~{IMQ6 zaSotjkwbW9M+=mBqKi@Ze#NnQ+0bXsC6m)|lLe@g(eaZ(IeHm}hm-VUO<9IeIZ#xY zW9PD!t>=|vnTcz;oXz<${826H(H|1oDSVlI8##*!m@)E0EA_W2lsR8plz;y$g1_C@0J~h`>|ozD)R{_OaYp2bFamy@r&jH=D2L4G1x)2NB0& zuAz1Ep}$so>XD)=I-{NXsj)dx*14Ut^rPDsm`AHk_T*-FIBVBaF2ANQqQO{V=7 zzWg*@ggM?8qBdu12zyvB>-Z+^5`vLBsi$XxD;j*Ey04+yU*>{A9Mh`dSt~p%4oNyO zOxj&+6fT-MJS2-klXoi6@g&n4Ce~V%xi=Sw^oOT4V~NFQ8e%vXPnpB{JK9k9c$su&3vGH#62^^^h(| zn-NVLmiJl*RJ*#%*XySdwa-&dxk@(fDdl26s5TXI; z#bMl{XS~bB*T4l^yK$Vs5BqmK1-ybhhLbn{nsb6+T_T+x8IH~Rg{+x~|E0HVY^%Cf zqw%_!3i`kWl7eH|%LyHIS=-4G+_iChDq|ad-IPOfqvZw(iE_IM+9X%jX>PrS?JR-FW{qGxs3<= zK>pvcJTADEqPjQ0n;PL|-XIlm;kTR7cN~q(Jw=jl;)&(b@ANdcm==wqRfsz`)dgO(BUP-P-X9ti#%KQPCGoCzVC&8GgWtKk8yyHDzUNPR zAf(o*{NZMjb<$oN zfA*6MEyUuW8^0_#TG6fA)@}R$QeM;YZvt`wMDwZ3^O1j94ea%2ZS+CczMn~#hCTX@C2FE1Pp4LLUE}8U0G~ltup3@`1iS+}LJ2Klzgv^rMOIqu%eOX`88@ ztKh%B?MUAOht&Z>hrodZ3mQC#FrmVQ3=cSb2r;6>i4-eZyofQQ#*G|1di)47q{xvZ zOPV~1GNsCuEL*yK2{WcllRIkKyoocX&Ye7a`pkLhlE0xuiw^bVNr=*=Oq(*rQK`~C zepIVgjXJZWkF8w0di@GEtXLnF{#9)=7VHclY}>kh%T|*ntNi}iy^A-m-o1S78p{ee zuwaRAE*Ue5I4H-TI0rlbe*6%zK9nHZWrjXE{L&#YU! zehoXe?Af$y+rI6Yv+muzc@{n_+S44T#D(Daf&53*sdTSavYj@%bm?U)P45afdv>{W z`+EPb_YLmxtwUcnmRaL&^6ViB6%D_rWyzPs1Ma=Ez2L&{Cl4d7T7Uu$NRWO89*AIq z3NFZCgANXcUxX6sX5M8;6{pm3$!%B(G0j<3NgK0WM`DR4a;060aB*i9crNmFfP@du z=w5%5p=V!4ywS*7d_E#JUs0E2HK9&CuEgJE|CL5ylTI#lWRy})NoAE*UP)t-T5hS+ zZ=y9LTvHluNM;-VoqSl;G0(YnVw-M`rDB|Ku}Ia6-yM+GC0zD|Wo=$wmY$Bf_4$&G zKOX8&kV6d_)1EgGD$<|+W#Yz@mR>p#q?&HZX{VlkTBW0+a#(@)CO=qx z_GYZIt|e!!am`hgop=7D=ctW=`dX=yp~t9tg92O98_F)rY_rP-1#Ps_Mhl!VIkM!d zO~`5_sbv3EifOn6ZcA>t=AMggx`JlQE`GvF7L}^YXv| zYO5|}?;3^UMmrY#S!jW#H1G}#OB57vlaU6lxEiN6amOBi406b`MNIN;-4b=cKKnRS z$r$sh+F`5zu8IhlzBZG{Z@)VK3$R{64J`70hKcs@MGFT#Q^iG#q!W6h27Pc*7;jAV zX-HpWBWgI@8T=N0+nCaZ75>I zE_UqRNGg3TNI*T*tD{#(O%#AtKdzAAl21-~<)MC!IcINlLJVSJtL%@OE}uKM#HM z(nFSc^*+78L-ss$!ii)llWjKX^`7o(>L{^}zE`iWzv5f~54n?KdCNF`OD88*?7E!Q z|B=%F`D0|Hi5SmzSxXXSmejliW{Q6dY@h=lI1%efFelj4o&~w*y_D_4AK^P&%*a>1 zlcaBiK46~-=j1*Y<*z5TI~oL2lDxkutamT0h{OIDL7dA`cG031TS99}ZC&%SPux=8!K$BOzh>PKZXga0fgR z`HB2`$P*;4B!=~wAr0l|5W?jUC-8BI-hMc=15#>;M8u;Z4~a-kNoa{r^c$jd2gN8V zYgAOUq9wQ2J;XQ!e3c-bnPkSckC+jCu1li{<>DRT`H?X#%ugaw0z@J0up%xrB!71Q zCqN%9ts^<1Tr7w3EkZW$mBcKjF%e|4H#G8*hqBnPA{o3%>gELxxui9(n8hu2af71s zpy`@(uZ)b6b)_`r2~p`YqiyDmt~_Q*=%`9s-Vu+$tD}1kwM&ouibzYAA!#EQ$!}u0yNYl`UZjqVsaY!WJpc5)a)(J(7_R^psF(74vXUF}$(tihd12glf&wajxVEycyQ2-jys?l_*Ol>OD zdZJ7veJf+9af4MKnu&-`l%iyN2(jK!Nee=Rqn7ljQMQS?Fv^UK6G7?QRJzjtbK+%| z6zRW30Q36fS|j3Cx4|{8>|+C7{=&=N^puJA6e?sb z0#CpJ_K@=VDYkq|l6FE$vCCuZ#(oRk=)UqM3H8rqom-I1x?!`P?J8(RYe|Qgwu)vg z3R<5tukoEuO$Ugr+h_}4VBjSr>v_mz|MA59;x@n2>hH9i)vQ$$t)JT;*zd~FATvQOqQX8r0{^Yn^n(JB($6uZ50nNUJH)@ffEzm<^hgz z05GDBq*Pg3RNR{{_|mqecOk4g4_rL?w3w@uIi^1WcELj5Cf#C9Wi*dhvF1xue>M&sn|LRGY{FzIygR&j^oN>yCfNa zKcPs1iA=PD23N{`exOk)<7A@jc_a6FSOKoILH=PK`E!fxYC)`4rH-UNDiGjh}KE zoWs-hHpj4y@r)PD;-~qvN5oBT?^*<;#2~SWIm+g)f)3v51t-1h&6RuOTTXdtNuzC; zY+u7Co=qLJfeURpWHYn7%chA?=_hfaE3e`lH;u-h4s~QT9U&%Y5c4lJ8x3UXr|WMCp~mCx(Sx;9>(^Z~{j(eIV4BBBhJD zQy);&50Cgh6@DNdSBbbeF=~-;ucMt~^-#)(HhH_e&TD7?yLR%-t44u@?#0#lqAV>~ zpgQ~6A|t)Pw^;Ok6A)byM$Cj4Z?(khe)lw*dgEUr0~tI%@*X*}s=ddLR>Qe;nlEW= zJMZ}w;o3H?FFj&9V{M=7-6vQBu=khf-|$b%V%9q7@d{S^qc#`!PUpS*-+v%)|2`|h z5B~7Qwvo_&od@jRB2`pI6_wBl$5wUe$*9rT_J!4}O|2Gxk^Fe6$a;uYo zwN-QM(SYM7%@ghcS`sW2}e&ENNl4gc6b9cNW)xA zhl>lui|fda9>F}nSR27uf1wt6+94Kf?_lkE2WEePXAmL2KQ;v(HbV!wstI>`jDUuYyJVjsv2qKTd7iKF{ zX8yQA%TQvNBpIZ(j8SohHI{Y;d6500Z+vtB8kr2#y=EaK?x@ z8+kS9Cp91Vka;36Hmtl3QqcM4^A2&Rdm57-H`4ydcYduCK{SkX^WS6Q5Sx2dt6={*_(UdZ51+qmc=rEmC8bXBC=Yq;2t;8EP&R0ulcphA5+7d&;N$C4Nz4O!xV7`ALL+ zhfh^nY}dJ^F-lZ(n<|e$nsZ}F6Sv?enXLE!3SC+m6VA%7k4c`N)v7~5t)ptKJD9CmLm`HGR=?(0g1UXW zRzE*zeK+;0xwTKOgmk?sqemia#u}#h3bK#2qbbp^C99kC7_C6ka6)DmA3~&T*OT}q zIXb0uxC$uHC2SK(tAuJf-l|{~JE+=1Fhh%U5IZH>S+6<}vP;`kBTEt{3$^0umC`z} zC3+XlQL6Zs7jz0TdpEBR=sgv6Vd1K1qj`kc>8%qhB)S@SZHs+^=eC+cw%P`!AIr3N zJ5Wyh5mC#x3mR&fAaX3*YkNT#6G~g33AE{Aw21Q~Hj5dR=CC5lvsxpuhcZ!#tD@`r zV2(;Z@tRmlSEEV)i?^d|OnR#keT%xfX#xWQQFvO60t+66d#x;$kd?!vLDslot7zAj zv$JXu-WW7#D;g{NxI-nhGTLB8yRn@@qjkHTqzk=>WV#iRy44$uFn|!P`?|2}9fez@ z3W%K1)1`PbbiTH{sJD$~%ZeWJeeK&Ue>#4rXS@pok;rn6NqeKwtG_RVshMiM|66~J zrx4rKS=;L(Z@NAfT0gWyE*%@ghe^Y8%s|U35jXt5E?^N1vBM77!-m^-wR=dFI}}Nh9!5O2>1(mh zDMzV~WYEG+d;pY8$$)?k?GO}LJPRjG1`g52By7gNkjfF) zfnQsg_*#|MDN)~m-FVH%{7rw7arfIKIH99WN(Kdx9GLg=}MrpQmaxI&zP zo3IM2&;(n20Aw)5F#r*3+{IeF15IGY?hz!pAQ6(#$~yqbRLsgL?8Xc;w^k;)wJgt- zgQ>ayoVr!l5vS3*mGK=C`n_>M%sbUgHY60}sLZP=8an&CXPZc)Pzt?}8Q8oE+UyWo zAjx*X%9}jR6ny{|vkuPS44~Po*lY)qz{-M2i?B?$aa@)2?9zhMSO)+DFksJ63j@0h z5~#7yR_h&EtH1{3dT)r#4|$46sBG%X$Z`}E!;lNXKn7NP0N}g|CHxECjKz~o23d^` zAcYRdPz~&W4&G1-D9obZJjo_~&VmOupzFLc{L*iYH5wxkML^Rv-K?3q5vW1HmLWUf z8fXfGH+U16^;=95ywK}gLy#;9PizaLfFqIo)N8ECoovQtJPX0#4Bj9Q````1Pz}}p z0MeLk3+xQZrF;Vzoz{2Bk)jd0^$ORoEiza}5i@PqXNuSEsMn;yy#Z5jlyRYgGSt~f zP)IzkllwwVAjQA13Qyfrr4S6ZFeKRQ2--}_S*-=O;0(Xu4ffF4UhNHG?F_--4SIsn zc2E;&jh)?hzp@P5?cFg=q7k%R+q!w%A)y)|#?yHrBwSmElEL3fW)tj`-b-cJhn>{? zQ_W;x(pv1qt6&5{(F@P5%`s5T*31vxJrCW@4n%kllo_x!(Be z-YbqShQ|@|J>OYa-z5&87i$63Km#>-=!CjO+*UUlt%nxJ)So{l3fZ7%RZU?hq z3!5NAJ!Kie5De?k+0|eVL$MF`@C(SW4%IN_qfpIgP2$5!XRhX{;{tUlh&SMUn zTl3ByYqz4#?N~yaDN)zC3>yNX+pCUk%qiFmZDFx`k$$dRlvCYSYy=qpJqr}w1UGQ+ z*enS*aLv>F!T!+YzfcWB;pJBD5A0A40*~Wf?hT#LjU-b!&CAj)-R%`$B?ZC~;cmS% zo)zQ{xO4vBk@XX}1;6eKV87Mpwf^pVv&K_w=%qXnB(3WvJqxMu4B71r^N=X>FzwC& z+L$d5Kr#*Dt!MMgz?0LwlS=Ux&-5Xq@qEkif|2SUZ|;`1p#y&{?>kn(| zSX1at@P>G^ndR$bPe_G zLGGPZ^;+ge5|QWZZdF3VlT6aVNI^|isje^MP zI;?#H!+np7fY18sBKZ9p^{wIY@S)JrmG~2Zr(8e!v+n6m)apWs*tf$~=z1TeA5_b1 zC2*|zgV_4bUoNKZqp?5kaZdF}mSwl!nygAur}_1gOTo}X$cXaz2Bs1#Pbg*%>dvqJ zp91~#JtG4WVux@08!8dq`jvmZ?kX*-NGa=-3lRPU4kTF6;6Z=?5c<1xz~MuP5hYHf zNO8wSj1@IX#MrUpMvx&zjwD&~z?)0P77EOiNykf=F=fuAS<~iCoH=2d_;8^@ zg9pI+LtEGG-AgIKiX}U8?ca=d1uvaj`0c^AX4U!x{BbZ|y(?RGrCizaWgU+-Z|29LAeGK$L9Sx@7&iUXRqxo`i)`ahY9Xh z?6Kr<$HkHUUO8+sX6)IqOXuF*`*-l+#g8v(Ix7tF8?k2^b{k>v^zon1&W+st!1~PP z?=Ol{&5yyb@G!K?RL*@IeS8d~hK51T3q-jR=g+K$56i$T~N)6LG|x zI5hD@6jM}jMbN6Ust6Vx!tATP#)^?Y`YuV1!h_!bxadY8EAnt5zJ$~8#~^#lD?rUK zP^3#6O_0-MU^a*5EHc(vr}``byr?{^=!s60aVpjv;d6=rA-++ zV9&%pC00pIi5xa0L7$DvzfOrdZXi-ief6(KWnJjHTg#=)T6EJ@cU^X6yo@#1x@~tT zBq@s4Fk_}nX;@?DO^r_7f~<2%XR>3m`fRk*R(m2c<6S#u zuuNjMYr1!M8|>w>cBtC7Cqi)Qirh}C?wUcxTOhH^R=jV<8+Y7aj<4o&xmoLJ< zZ9L_JRu<{i$sNLW+GCMJc<;;$2er`ZXjQ!I&|{Z<_C|%S(NEePih8KF@=Be+*bfhj z^bD(Z9P24}MELi{c4hrT*I(B;cj~MEw?0MNC9nQo%l}lGdDVlDI&X$GlpW^rMcxhk z=6U7Zpq6Ttp5p84xBq_c$fQ*L?O8nvqu2P3eRi|n`=my^0r4$#H%r#S2H3t{8IU0H zn_tfGcR>th@K=|ik+5*LK)NW!BLTbw^YAA;h9Gco#$%j7{?RehJ&-=nVjw~!R>5*< zP=`C@VN|lmzaEzFA_psB-8A^T%2`fF5x8(i&^Yq zAq{!R1FR=l()u7G*Rq>`Ohh36A!(Bs&xXRhG%|sB?Ad?jvd6giF?@hbpFadS$Xg*& zm8;z050l7BPpL&ek(5XXC0WV(A@My*SA(mqJr3OWB*uN2XdCDB_aJKyK}vT)+@qwM0BNWWg#`wR|ZinC<$Cqxr$I&qVT7i^rrX#D;u>^OR!xE4)fa8 z!n{ybyyd7$@A_Nd$xgUS(b4IUYfiD2mQdbJXLFsq9qGnbzWl)~MK!qD+Efx|vD{E- z1v=XFuGX~X1&SyC2|N*#HB3$&Rp)zQJ6{M#IDgb72!N?q&rLyOy!?$4Gy54>0WYw; zXobj7PYYi3au}csX72>u>tM@BSjIDs4TZ^vzeg(1UL!8qaS!>|10#5ej~g9YRc6V> zbnRg+9*ApU+!Y!}S<0QM?>2E9C6P{YBOB(f7Dek%;{rFhDY0;8Ny?baJqof<&d!wG z{ARS&R%FEuU57=gxBYfGh#y9Ah$pvSO73*6g!`I6oy=yOz**6Yc8ZO|n88x^gv&nu zF_RzN=j5J`#~Nv(pp}|B!_i(|+~bxAvh91lXt8=CzlkEWm#Q`(f3(_-V^)?C^EoLxuiFgrx~8UvIBC9Mp5)l?VDuiqsCc*jv~Zp1jeZ?rxs3EfS-UtgNq z5O3U2CoZ!9TijO|Z}PV{J`<1UoY5e!E=-4*l4TX~fw}DViSgY_tC`q^FE7aH6b@Qm zt@-90*Ll^aEbt1eo1XBA)a+*mT5_0vVz&2}Sb-0A+;L8K$j{gAH-0B=CW2A7SaT!@ z!TX!pkJI(8nfdcQp8HM;qu>hR05AM(d^{mY4~ z`1C187lUo?_?Ng|`LUh6%9m+*d){&*Fy~>s2k+R6**ooL#C?K$wEP;gLP-qCJq{JFT%L z>NBL>yFQ0$7wy{=7{b3{qBNv{x)Xt{@cX~y6F?ArsPi*AN8&7zP{0LbHdwO0?jt<^ zVwu1OGAhNo3q89)4MY*C^T6>7K^|nL5d^*4>K+9oi2QIT6e2;YnZHYkqc{q?!uq-h z>8ruOK%j^~7Rf;!)RG?DLRBI_e<-stLco&vtQ%yd2W&y?V>l$ViyBPAHVhRk%)-pz zLOLv@AGE+a6GPmSL7{6qzxq6R6FoHqLf$z#KeWMjTM^@fyDY3jN7SM_G$gjTsX!|T zG-?(qbig|c#Au71zahDvKtK6A#Fa}#76CswG@D0UMIG`&Fuby?*`+Vsu1wTKdE&j^ zyETL}z)D=hiX*;JoT2qny7uZo9b`phyr4+bBK0$~rh|w))4vr2L6C8dp(7;39#cYT+ccl}y&2>+4AdMn;lNb< zz;XP?*})Fh*dIm;LcRJsjfh54^sig2#&+}>Tq_BCltM(jL7G{VIBZ0K+{n-=#|%10 z?81+cP{@T`B^E42KMS2}1Br=z#wzTWrdhJNSUuL`NSkCFkG!B}M97jLNnrG_O?1dw zOdBF%Nz+LyPz#rgJjR=B%Cr$k_5h_pZv*XIzyDqwAlePXw)&HNJ>Xp z#D4Tgr%X$r$;s=X4TR7Zy?~FQEToe(L_uUYY=psuK}sWv6tg@_wG2%EpJB`Du^aB0 z4tjjZ9ePJjOvy3Z7i38mc>G1WIhAibKJgPw&HNasB*-J<#gP+9r4SWR$SRZtybZ~}X zsD^cbi-*_;ZwQ88@P-(;2qUnARhWfY_=QRcO;$h*9JO8tn|vk~|p-JW4l& zw&IITM$||m{ZmI#&#Qtd4}l22Q-^A}Qg1+qC52LS5Xp5&)L+2T+i-{~^-^2F2r?+s zHPr%1_ytMOf&*xRPYqR3J%BeoRSvV7znaQ;oHt(rrj@WN=o2;L>22&|t6wa2?ke?FcdeRW)r>aJ3s!RnyuwM2I<*ILa^ zc`Zfu?3U8i?43bwCGiU{-Hf zhlKTpN&N?4MObJ(Bex|3aGh95xYmrAg;i*R7$AfHG+omdodt*8*t-czIyF~cY00W> z*Z8Z>I(@;drAb8lTFc!MUUk59TnA+Mg!JhiSM{dsqiru4QjHSaev2d8lPt283J)23y#KCLmQ2 zuGWhPVLMP$Q2kwN{nTVu-!{%B#P!(!<-H^{J_-}-o=zs-Q#>4Ca$X!dWpPGjAOu1dJ#JWH?s3INg~=T`W!5DJ`K8CWE}#hf)ZJrj6u&-qc@^2oW}1-9ydc#m>jX z--;kcB&%jmCg>QsnFyX}xB%zH8E1@+5j-AL9kPSoEmNYc26fn1he+Fb-d7*l-4Wga zIk1Ia2nK#eQ!>z0&z)Z?e$yK;=E$XFK(yq$)WuBti5=aiH~eWJDINyLECBMbj&1?xTIEU7bBbhr~Ye=F6Ru2fi6y-eU0FVD4}Ydh}wM!B5Le#4O1Q7 zN`tn`;rvQ^1c|x6$GYC>sZEkMnCNEkgl6D}y@sDY%@V*~ZK$4Jj&?^3eYg%u%uk-i z%}ybozHCifV~M!!?Fa@2AvkVNpb)-xs??4v)_!j630s=dJx}WG+CG-J z7CxzJYihpkwfRI%@@>jHDU@QGEurY+PH#_0ZsnFi)W#C%j_(y2L9u{s3>CVdP#WNk zsr&lWE<_7m~WJvX*b@4FGbexW%?Zw4oAesCi9e(&d!Zwim@cUh!4)4i^?>#Lz{ z?^dOF%Wb^A#yB3?vHYF?wwh>9U~m?n1NOGWJ?deqt8f}Ok*J=yA?7D;`S7HH%>9lj z?mlQ!}j`_9q*LP3^XAWN$`JI za5Zmo7grgE*z6vLb4TA8FU;5N?()f|Y{BVnFYhF<_|E7IiUB$iLO1k7SMw*Y6BIh7 zM^AM~=O7F}GRxAG2-m2E&}1k)EF^d6lc{94)^km_4YgCZeB0qAA9Z4Xaor$`Q_lod zUv?YESB9W-M2bxRH^C>(8wz7E>Uq5FpvLq{|Cj;)&y9M?V2=;tej(!~c63j4E7P6y zVRm=t5J45&?Y2J$t@fYjLo*h!OBZs8&KSK^?p*`!p^J|+M|XoSb#0`RcVBpT$JhF% zs`06JdzVOT*Tp;z^AQgzcExdlm$~r>b%PIiFI`Am>e`p4u?|LUU_VFfqvEPqWZuM<~_8tP8y{q?-z;|xGA6@76ZjZX-Eh=q{ zIjr}Ng7^CWpEvQb|9kRC`J>;nS(gZjuLu&&_%Yu1nSc9>tNWX8I$DKXUjGb`=X5@ zf(?7|D%rATPrkWiOsiI}DaFEtdv-2em1(0gy!kZmTd+bQqBOSg-<*<$4X~czvJ~qxEJnc_Jta=A+@tR1&Ywe%E`2)n>Xp5W@)w)QA1Si zHSYNKLuG$oSi9ow*6!Pb#tZYe*7+!f=fs{wZw%JVat9)IpMncA*r0(65h@FKOhIiz2YMFM>it5F9z=%$^2w!|n+P0!xSVndiXj7duqi0dY zbfrrxA~YCbKEi1dm~+xur=54=X;zY(ZPy)>HRf3vhaD1xo|mg-6`q=b-uL2#{%}d3 zmp3wcR(_ElH0XDLszhl^hZbaW6Dv`_5VXv?oESsIxmS_G_$FK3g%-DP3AJjR6iV(8>>q`libVE}ga3TXQX)%|_uo z8@OF##9_Mitt8v7QIl;|yJDYg(bR2Aq>#f-=c|*mQ}0kUa#t@$x8Q>lUieU77u9gb zhEr6UK{>K?qR{d(E|k&kqHM0=THTFz+@BK1_rL!b2)J^Uqn^6zt51agcu`@qrL*c} z7Q`Yo?_xBGM|ZJh+)ob&l`nYx4cj=>M30`tHv|A3fc!>j3-H($}tgOKGia$(0jI8GyP6jN~4+hE~GxsSTIdfyM(khXc!OzF^ED8lnA}GxFNP=Tq@iO3**zl7hW%E zGXz-;@pZ%gKy78C3z!c%h{P{~F^oaFA9t>3GBGmEGfVV`K$`gf8OS}afjA`J+%!fq zHxh44H%VU0y7(hB0y2<-Y)=s%Rl-3Eq>2T3cY0h(^ z^Kh;kAyg zNLG?dAR3{kL2flm7eW+LbgZK;-{8@Yg4Cl49O(fISU~XqfNpB;Gw4AV>e83ObV7*3 zALd4xQE5tao&|yBYV3K!`CW5-xCB+|(6y4}Wss$ci78W?>ePcY^l1A;<4p}R(VhB3 zmi7c;KAUn#hnNqa#{%Besy0r8J~gdsZE93&8px_zRi{$(X*Ic;(QiJEqeX?$yF}+E ze(*z>p2rs&ggiVEA#IVH!5HqD5z0 zVW?Rl!WAI_MAStA*;ov@v!0j5Yye}MlD~G=6M}8tXnX71VwQG}VoYs8&_kujYEFsPsmLgSilSTl$+pGOHyV^x0VjVg};wCcxEO%k8a}h~dui`a(v#s2v$j3wK z{uQvkxNfPoYv22dF}RaFtp|yFo8$Jgn6LdRzt+p%u~uYx@U1Rj154i?;Wxq(7NUNI z`dwvh_BP`U(U;7*T(^?dlB+YSL>9c@23vPp6J9ZkJ=k65a#eyP>=%Fqi;HYz>{VEwK!m78hqYnUWca7%9B_0Cykj22h;}~)a*%}#%ETNw z%wpbMlF#_TD(2;p$BnX-k9l6j4mH3$uI+odOkEV?`N4l2GoSlxIO@?fXNxtQ_|z-9 zpq=fW#_S!i(mT*AW7f_l#Hcb3q4K2ORu;i6C_DVWlvjqil~z` zkSQ(X_-Q)Uvfdh}Mpx_zI&cEvzsk5K$p>X z^D7Ofh@C5q4y4pJ&8U8cz3Z;k`PlGvb)K*5>~o_VX0?VCs!{jN@(u{m+16euPaS8p zwN1g|?ku_UT+Va@JmB+Mx1*&;)WEF8du;|bjzP>%IcII(T<&+dg&^>YV?12YUgpt; zh;Nnj?}lwuh)GLsK$4QQ-R|ag!P%@$ni*T-ccwT$GH&ymhj5)n+>*+pXS=jL<%$RR zXOwPz*D8nl+YyVo%#rQce^46dQlI+&st7)4#&tM}oD=!biO$mw1{>SnR&~U}-SiWa zySh|gJKGrrZDpa!gY*WP_=Nt?T%(rdJ%2RW3ugASkDKCcA3WjhBtnjFYVWE0^-C1V zbv$03b*~-Mz2P`7rUQN>{VqJ`JMSc`*RQTIfvDX*2gtCuynITpRx2}aXMO;~6LXk- zVLWg9+Y9OKhD7>1AGO9tmH!(Q5_WL42L++28%G-0mr!%N-o5tQ1J- zmM08g2zr77l3)o|hxDbADZwA{$kqHALj_tM1ASixQlRnOiCGzj|9Juc3ZVHFAYhqb z5DMXQxSvfmkwh893&Nm{VNd=Ym9>FMxN%Wp=pYY*d#W914N&Rz6;7~Iex-_S`1mdgLR zA&SXiA}S(e6rpQ{A+L#yRFL5pIUyRBVUYMu^XMQDE@CHoB3*Q0qkSRxIFr)|L}Y^`Zl53qQvL%3>`dV=@Xw zBd!wO)L>YoVrxBA!`-1PZs3C~&zAv?GIC=#_CzR36&P6`-aR8UGQ@g7p=-5bbG_n% z5F-3|V?4^^P28d#3Rg3(PyKxeLvYwNmQp2JBgDB!EN;*|8stIB1T%7#9)(|h)L0C@ z-%X`nISOQTNZ~OeWJYSFN`RxFjUqm6QqoOIG%_JV5g$AHqpuVcJZ@x5x@1Mv$Sj&PxjAP&R}@PMcO#(#nuz4Z0KrP9!iwMzZ&~G8Qsu_Uq}bgWh6H3d$s3!w6iQpZ1>I`>!9z9nl?1!9`zcDiRv-r~+VTo9>erhLbEvQT;M&Tm%dWbTAiX6Jhf z=td?d5?N)&j-t_>vMA`tdFY}^WMQV`Ot9x`qUerlWPyIr!hxLAbf_M>nS+Yx zh}J}Asu+(lX^&oLHNGD}iCkMKlximBZN7wrE@_i;DMG5KcSb1-sgH~*As+&1^zdhT zB56wuXM1+(n;xW(3YZ%$5Y!SxL4Ij2;vp|-gfaXgqaNs9ttfC}X`2L7fL>~<%A=e<6fdDk zKZ2@;R?eO}|E2~)XsGm%W~%D0&SQ6KDl0;sl{{puo+)G1D5;KRA_3}_@@lijW2Sy4 zRqf)Y%v);UB(aKKe;sRoMh&GhtFwZuH?rz*u~2B3;{l+fnNHTDl2ENuWPm9tk%jBL zK5LT1DS ztikG>@#rT=UWiS$2EVT2DADRLt_XI1>&2pMGWu$?1`#W@n?s(X!zNEet|-aEg||{m z%IYjP9;~2=<81Vtmw;@kLM)iFqnlV7*6i%kV(e_nXX4=_p**Nq3~Qr)=(LiYyH0Gb zo-EUP|1B-9EQZ$4+aT+IU8~j7XamyVbXDxvx@|4?EDW_Qf27n%#_XqNt3suz_QflL zyzSpAW8C7<#?p=BAPQGlUtSm7lQ!$z-sutJg ztmKL=*fu6IsadWZ5G01w>auR@7Oi(tY}bzN>@K3=_u*0CjF1^lH4jWu2=PK;23Z9l5WOgU@0x{)-~^LlH&s=Xo2X~>Q#8YTjjuL_#QEy)^?psDB`+ZDnB#S?8^NzS@&}Mz z|41`@Ao;e`{yH%Fj;n3H9O*sh`%)&WIZZQ+!vk}$C#LT$1yV|KXz$`n0gqBsU@(St z@Cth{<$^F8U1mjDQ3V6bF$G=gaalaE@D4*T_EM(=A80B19tjuSKhm#m@vi0xAPW{T z4?D3OesFDmk>WyN9t|*&itJPPLPsDm3I`cmG=qa_@Dr19?YgiO3z2_TF%u&t_L&kU zomCer#M7Y|Tg+D(YQ>aPhB!lX|Z7-a#P?LFmN&`!*U`*|1xah zt_$5=x?<~%VoN3;#wxQiU}-`yV__^4GaSw`TOMjAB~qfiYc4D9wG?u4`0^YBGY}N> zH9xW_-)rx=Q9<;YGo$Ub49Zy{#x%b&HlwpKNAO!QXmKqwI7=$Q42mHyhdB>(I^%N| z9`i(kp(#49T96k!Pja{nO463ZH0N_dhq5-SuOlj~qzo;wmfcerv?_bDLSwWE&N81a znX>F1L_8U`PP9{0bT4Q0No(Ogv*><8R0f_atWILW6g2UobWIN-9s2JmgYS2Ip;&}; zOe4%p%dSlmbppm@_J)xpeI&!;vQLe4Q7(bycI_52F@u%7m9}wJuwWnMCyuy>(xU^&YeA6J^x} z*=^eL0G(#aweISI ziJ9Q9(q{H*H}<+Ab7T)oZM0w;b)EBim64#fVzc&cv!7!d&q}9pY{wNN0iSJ~Ff2Yr zYEv(7Gq+L4H6NpsXSYdhN0jg4c5>@>b8ENyS#@*^w*@Xl`C{$<#7*XhnG^|HpkJI0AOJF}1f1 z!MD>4_;VC^b|-j+g`Ev|9lN)-a4<4KE zc;zfQZsO4bk=W*r$E0t$rIWhUId+uaZuPm5X8EF=L*-%C|9SbA`mC2Yjb}Pz<)_7H zlt3RgTEsf!(t5Bzxofw1G8<3X=nAj#dN?Q8uS1xyL;J9w@v`u_xV!t*Vfwb!@JmcKIIp|66Z*UBJKLT5TCy7+ z)=-l7MMO(9&#?Qb?|Z^y+?N9@eAl(|Ji5%rDtXXvzAOC2Qyr#PyZ1T#OuTeX_Uq^! zJep&C$**0%XE?r^^&W{=#N#bp89ctXyUEjh#+mqIuXoGRHBK;Wx;wSVI|V(He9aR* zyc4^-qUm7k4O2@zSKm&>&wSBK{l%gDkUy0}=9Vg0#NFe)d++96 z^Yz~|zNs@jOc8$J8~)e*Q}HOi7d3w7J3gX&WK%_cMl^)iS-!<XMab0(iD~Ct{<6*f@7w&*Z+wQ{KJG&k4G%F%lRoe>Kfnck zV4KtGn`*5jKU6P&^J71{iG9kSli5SUY%;}(i^;k%{n!_1L{D(ezgkCD$pNSv6CrxC43okX3d*9clP`lbZF6|Ntcee z7d1{dnT9o9>@Trt*%c2zHKzFW)v8!`Z>{`$>}=t~i5EA19C>o(%b7QCn;LrG+(2VH zCtka$(F4<8XALSDczEmM$(J{O9({WC|LfVeZwNiL^yz>FyZ4Np=_T%qvu17P$&)$2 z3r{Tj3_K9Q1QlG6!3G^<5Wc-uYmK|=9-Iq5#P*xYJD_~gs+kW%1W-T%g}4yK6jfZ2 z#TH$B5yp%n+)KXPER31%l)nyv6H-yiI6W2B zR8?J-)m9(6RHsb+>eAJZK;=+W{{oHl2h9R&{T0|?g&mey6k%13wLSgnvsj33bu3pC zyFxNiPrhmv+ibPnmfLPOI~FHduVU8QKy`~&S~EQv(%N#}eHY$%<((HKaC`cRJ6h@8 zQL6r|N_R3u{n?k`f(7#Vij+9Rj;lNsAvtG1f!vdumlZL@!-5Nd~s1+|&6uT7ioy6wJu zWv_#NdnjMzb`tNv1s|O7|9ADSu)bg6{@b#`9e*71$XE54;kIi9)o;cn-<(rrJD z>3jC#oqrzs=;u2AHQ1FODsI!I-=6#Ky^m@44Wp)Vd7&}~{`>URU!VPsUS?bLVDx-_i z0|_X%3VslTA^e>GmL_e3jR5sQXv9sH07Km$>+fLRpd7|BR1 zBZdr#=mDb#%h*OYzEM?Cv{4$#vql=i5s!J)qoZ^#lyPDylv&ygm%$X~FhjGuP|oU)rRn8&9J#T8001HR1O*BJ2LLP= z05Jf51lIuo2>$>N2pmYTpuvL(6DnNDu%W|;5F<*QNU@^Dix@L%+{m$`$B!UGiX2H& zWEe;&yA14tG7Q5cFkv2uSu$alBsFvD+{v@2&!0ep3LQ$csL`WHlPX=xwCRB}C?UCA ziSo=#nlojB90V!iO{ZYPiXBU~tl6_@)2dy|wyjc@Eepb(nlL6#fmlm&bvP)@8Mf45OPa8Pqda_i%2G^e6k%>h#M7BBUL5`WO7R(N!T$8AwLTH#3+T_QU^?`sA31N5G9ihAr%gj2@zmy zG712wwJf3QkFv0`vv!|cgQgonZ{86eZW3XY$=&*iyt6$sK?sjhO3+4Do7@+ zzza?ipKC#mK=Yt}FXykx6xC_Od3`0_p0%=%K(DalC4)RVn6N+#@6bmt z{Zd_+7FBq)4&?VOkn9qvHFg|JNFc*xo^mol3$*$?I2984rJuK? zU~p2htF3T@Dn{{yjYUl$>YyLyo?$Cyni<3P6{M=M&P4RRa^7vCUN z@{*7$=H0~~{@?@!SIEK^>g9GYyq;gW@H9d|f*Qc^98Ac;2seny9tW@k`v1s*6UJSm zNXbwIO(uhr;Rq`UxX6$omhptwNswPeEC)_#(LXl`%U*6EN6bc{I@TrO7MYMqq>?}g zHt~yJFbu=jSTjc#3g$)R7#;_|p^QMNhlA-^gf&V5lcu?ib1Jl>A{WU>h}0>Dkc5Ok z3;~IEM1qa$xP=|SLB23G!-qk`$?7&KxX3keCU}WhOh$KrCk(?H@Uq`kP}$0BB*7d4 zp+)GPFb+ZlPz&iGSvC^axFqc38rkR*7?yF3L!FXeN$`zn&TyANONBTQwIOp!f=V)Dkggm6cVYNSRPpJ}j7BM95t(We ztJ*{m$?-ZW!RA)E8dkNir?jY55){NhR<^qKwPl6K9SQ=6g8%g4AbrTKZg;EOxz52a zUI1)3|IwbqDkM^Hxr7o?xrudTLlFn~$2;ut4uR~#9@G#BDctb_q}i$D{SX0kl7yK4t~(dZE>61JlvrV|IG$JsG*26{FOS!eG*EP zdl$&HavcW%qCn1Y30NF}6xprr0mO0PU36F=esLgqk1`)RwR4}Bf-hK}V}h@$_{Hy8 zZEM+z-?G~G#tE@7Q1Wnq{N5H6#USnh_S@S7_=O5W%}s(45~)$VV;9Cy;_n8MK9te# z8e}NaJLpo~>@Fn4XK|81mW-dxju^&CNrDN`%x37w_y4u`B}je?lHb|-VYY}!N+k9n zWP||NzA6gCU6IU$*^n7h?m`JFmOBu2tRr3WP(>!n0S0~)DG93!(>$mJj%=WU8s23{ zh+RyS5}VkuSApu8+sx`#%Z;^b9f*DBEbICXgw{^k2TdbV+kwnguUAMiXAWJENbO_6 zjHa^Y)I|t;fB`1v&`SBB5i>B@<1*@u;bU*NZS0YnCj=!3O71q^+PV7N=#HBZ)(r(O z9Hh8d0+YZMuJf;~=p0NJ3%vA+R%YQ8-ZF%M+iDE~g`s?*K#md9t^FlV--vJLa zr}v$C9Os_*7}p-|3>@|w=s^=aFs4Z_lfOj`C`;K-@*ty_vVn`{7AYN>z)%vXJ_><> z0UViF2Ae|qO(Uyw+b1@Psl^?^e_qz*aF08DVlIR^#9YP(kvFYlTjQJmT+a9QIldVJ zihXYc*9TcpPloPmK^yq!{K1Yx5=-(F14@;Yg(gnIz}SR@r}G;zIb^g`?zhYR^r%k` z-RmxdvA(;;+}?Di z^H2y`mlI(y2ju2?|KV8(fnJ{IgsAN@V0gqxbTkNg8KH-eAY2Q<2=Y)4_vd~hNL(mm z5W|oz>0lSQf;k6J2aH0IVgEu9l6U~iwiE66jtS8ffpSzZrB7NlkOF~<``8esn2M`7 zg-98d10jnOC=g*d5YPp9xu_7_g@y&8cnM($yR{K`Kzr>`jP*wm$T*S>AvI8-E1)0; zOz;L(;|k00f_ftm9F+}gQ#jmW2ecp%@DGqM2SUXN?NSgD zrZ;cE3D9s0#Bcz+CMKJ39(@86e$zzqaB2O7c~pg2BvDWkG+It|dHIPRO?ge6lLRuL zW&*L90BI1qU>BKyLUg&KF6RZYCU|OCYXmO#f;Sv0#d^u%26mKkd0@rI-%~&|)xQpM)Txjf!Tg#dkD!5OjzT>JX*Q zun@m+R^s=Xr8R$jP!)x>5N|LJ;*gRzctd?K2Y{t`jNl3a@l(q%4ssAq{=g6Wun$Z? z2;wjd0`UgRU=Pb6Ui`3Ynb0mk*qxx55x%h+!ZB`(%BY_@5U1E6pBNG4N)X9#tUxuc zZ5FC^2B0AE48Kzf!LSOs=m(2=5V9wGv9hlSu?i%C2q=MToM&JL(NgUcNq)cva{vVc z5mXUNaF7>N?HZ!tbU8GY4A+_oZbYN!S%e4JSRwM52av(BnGcbk zpb4}7AhVuIvtVVjIa_mK=%o?ivjfqKuF09;U;fwx9)Ai;(57P#@6ZwfI7NcLBLrB~D&25=w-cK`=|FqRWhs)Df( zaQ{fS2tiz4Ib;O!3jnLMDABYDv9yqoXSziYoEHXvHM*sXYWNEY`IWW78n$5jx-%Jgjy9U98K3bG0d#SM?0|>RY`dAPs#0fJ?yrt!@J$45?=6Bv}5%U(HI_q~s zyKh_wy%w9oJb(j8(83460|jvfg2jo-=&)1k8RCl&222pakd+(Jx%#^h?wbf*C=R_S z4my^=E`bX6YhCXk4xuIxPh1S6YYf>Srw1ShSKNmOKn&M#4TZ%Boz^bMBwjgzQ3=tB z3oN&vs*nGuikf<6blbbFqNII`!Q~_b?sjVgL3{p*5h8rNx2IOmOK2&aWIv!0K>x)F z5A_Cw^#*q}2aO96z2+1-tg7jo5lhRy29XC*fe7~12jVbW+0eK{w-32BSA!r9ec%PZ zr(wHr3K;fS;@|~SmJC;r3DC6$CAuYjatmv40E|#CHG#(Sh=1qG#!O1L`xv}$43!G; z38(nL1F^3D@Va;$QLXo%H(L-Ij1f0xV`nwU{CWVfY)351}59}E&Ojfs(IZZOrrrpOFY_z86U5dO%_m?^w` zi`7HDLPb5Qvc{@7M|=3C5q{U&sNJ7_0M*oB2vpDnfpG<4a0O@J1-V5SwonLJ`P&3x zf*e^9dVmsXT@XW@ex*Fh2Y|T1AP(8J5552ku;2@KfXV|A3aId3)c;^7G&Kmo@ZGu9 zWseor>DOhyv0bB^2GzB?0PMOK+z`wN2~jNBsFut$?XJ@d!4Mo1qxcD`xY-Rcg`0{( zhAU2^?Lsi;ZuQoxw`OOWI}sr~f#U239jsP<5DL36(mNm#SHPxXf!hbL$7?ZL{V`j8 zke~$t3$h>(7WU!?5aTm05VBAVC;`$1;mOE-2ND(u*zMe<90{|f*TqoLeNfT-(A#~m zez}F$xdlXhfYGP`3%SM0)zt^UfC#_Yej7k8h*%FkbC^VOx&-rFM|@&iG1ME74^*yI8M#3%Py0{?+g?)L5C{t#=)2I$VTm*6}! z6`LbZ5GtSYL^fn9o?8$|#30A*GJgPyeF@~g5F%;f zsUE}y!3iRYtjfHj(;UIu>e=hLw-W30($nBnA8$wPs*g?KOdV@wMd?BiAcBQgoQ@b| zp9sXQ33C3vT$=WB|M4NuwbzkyvKbE#%@&Fe1>xT%50P`U?^98}b3bB?ef)FU7 z^93QXOUfu_i?$vcia$F2Nl>o3qjDl;)24V@{{Qd>LQVN}BXiyScOfkH9f74;5Bi~x zB)PrYgF*IbeFv)E><6IhuP>V@fAVer_PW3S0MVz<0f7P!5Ik6LAVGr+4c>vc&=8_T z2O(XAbWr0)jvKvPWYeVM!7CTNbYzl}$;bnoIE`B7j~`2#HErI+nN#OZo;`j31PV0C z!6Ze89vvDh-_k`Uh#EEe6zWJ_OY`YE(CS@Fl`DgO1shiESh8i!o<*Bh?OL5eposBv z;0~UHe&XKABNxxyxNJAtt?S1N4!?yBA4UxJAGM2!?i@^nv7;tf#UfEg1q&6&Jg{IH z8VCv&sDqthX$%ER)8o#Y52iMBAQEYWH2+VZuDS3a#K#9?_ngD#;ue})K#JVhm8J5; z&7D7o&Jk(Up&A!ir9M^a(~(y5#o{#YVAqt<&7Vh~Uj2IZH2wXfi5DVTr8vq~4J zo}5mjB{@>cszu(JiM;ZT(6}{W&zkc2IF`rhR<#MYID@0Y)@x#4#iraUwau z5MS;P2NrQ4j1Ce%*zh8ak09xhBO*td6;4}k&FLuaII=1h8KjCz%Ic=v=sK$oz>z#$ zmu0qDXA`61q>i$|a-VE8YLl*w>@$m7H3xe(T$WzoD2xM$)6G0T8e137n(P^*k7BYJ z(V=46`A1QW5KXkvgGvSU0BQ!A^q_1a0S1*~?uf*k12mx~)MF0#48uVLJ}je~hTC$y zj)U|{T#>;{lGviE%%>?Op;U5LVl}F2DSG(Ta%7ut##!8GS%OHTV)(^2E;RAz>#U*0 zfP%1`muBxyNGOu5CQfC`=KqdC#JQuOg6+W&M`SnRhu?N!@g(bP4B4lkgFO}K!K{lp z;Nm`JJYXI;`nWb-nzZ(Mr#qtd!oZOX(ULh@KV~{{Bv+=6s86hdAv?*Zd-(wG>dE(j znic1~bI+mMqGy{LN|8|xIl2}tyTJXtb!q)-7b8e2qG@UlBN@mZg(9XHVu~@;DC~^} z83z_%B8g-lO}GxVQfdMwHfLtc1d7o>%eeOCy>8K3|`u*7b5739dg=Cwmm6ayFn0fr~yRt(Ez zuo$Swn!K`c8h$7&V1rOmL5v5QNTA{}mN6m41fm&&{=J

    3UQR*tkXbbA(O9tZ6@qI2#&U*5!^9kjTgZ~;Z*5FeS++j6kVoK zP$n!WRcB?4TT&9X_zE7Zq;NomYE%v51$pkIZyiB|Jc+q2WFoVTQgtI604O`MVq~L; zD4;{c$r6xW)2(WSD_j)vxzz+$krBc+vX zkq4SH-~V6`s2zzOatlC?;Fh*zp^P9e(-S?hQYET{L_UX0Q1EhY zSVt|&{8WZi?IejP2dG0b{NbHXG}Wn5>~DlC8#=bQcO;^NMKW+iP6>ziAXH7nX=OK( zjUGh3ZwlCMO+ua~>Q`3N?QqTjdXS+KbxOt^Rvmz+4DSTOWA}@3kPS-Vv0RlbF%Ys; z=l|dZKhVx5CC-E1V35i|QRNl7@>ef(A+Rq-T#~~@h<#|`Ae&f+HEv;4LCixH z_E<_ftO1Tp5Wx-ONQOOzqK;*-Ll8+Q#5kY<4M8ZlP>lG5KCI%E!nuM9BouR`V@YKH zc!5lkp6rs>b7io&;#G!JhW~@C zISHF^!^$$Didf{j9v&7%tkkw-ohtq)%CU>>1P#~aqb zj+89>8nURvG8hqXnltUPmEOU*YffF_1TH5OIl#L$8{3h%wk$7^HzW$>k9%KaLQkKN zzrC31ox{l*W_|)L4pNFWXrvC-P=-F}Q4c#DBpF)Rhf$JYjVBz$9GN@7CN?qCW9LI2 z?uf@@XT$`4q(mJ|0QCVNO^8ZV-SFYMu93`rc z0i5w%vPRhtaEmjG{s8GXKvne7jjsEeh(*czFx-#{bTW?+b4W+5=8=zmxc@_!2QW4h z{E-rKFku)6fixpJ@p{Ogit#G z@(Z&H)DJhv26;$_YY~KO$Ob||`l`-ENthm;sTCU6)B6ug6&gCCT^Gei%nQamG&KL0e7u#o8y4djV; z>k|tZi^|hJNFbb7>8q4*i4^oVRa?Ope1jKs!#6pZV}YLp+XtWt5{(E1@7R(jimV4a zpF_k%v{1vcAh(~`0wc&oaJvFl5u7J8kSL3(v0yPsz=M*wCoN&YWe7w;^rAv^K^_c6 z^^hF*F$x_^1`CnJf9sgXITl7!mhyNdWOSh7v8AX7Vj#y#Tt=D*8UF@zu;5}eRhvYG^vE!| zw2!Phel!a_R0-pd9pIwGAFD)>Ob*END2Ij z3Q>zsM9o8V%WO=d{5r_aJk8hii>nNT$Kptx(8;CXP5+9-O_wCeuQ0N*aLwTi#n_~Y zy0lA<^i1Vki>?&RPxypD2!!YyiK}FW;KWDi1kbf7&hT7LR@p!{P|7b8P4Ywx?{LqJ zc%K9Cv6>LfrD(8N`%d=M&#+j${Vd10)UU(zPqXlf7qE)@bWg9eoTWI3t3WLI6cX>y zg~xi%A-T-~#n24($N&gL=`=N?kr56tVB+5L>nDW#bi<%?a(K^39eiUX28j= z;DN_#s-`-K$BEBl`2>9e%&>e%C6!X?bkZ|b)BgeWiu!D@kO51l+R`3{EHL%UDC$Tu zh0!HlQ?-1ZJ_XeM^oqVT&5jhymGBN8&;pGl%Zl_05De6!q{c|4)Yt5a-&9nJJW|5^ zO(WG*dt}DQItVj`)JmnOH1&_iG}Tr8%&s8D?u5>)yvduq$}qJ@afDH0WYy;5hsNC1 zUscnUAjbQI&YZByrPzj8*oakF1xaAmjgSOMAQxbLKu*gERi)N!ElNTy)|?PbVb}(Z zSkwcsgL1WlS8`U4SOsLDJ8k_(Y<1UoRY(H`&R7#poj}$J-H2J3m0385ShE93SP4P! z7kOQ#vozR*HCXqoP6)lwjtI>I&;mPH1^+v6gkBg4f7OUlP}pTc)s6*OYDG{JJ&39} zfa|o0-+WLrD?4YX24|oNTnt%XQqBDs&zZ$pH?+mmkkDcSO;WqS-TCRk4480N4wchK+-t1-G;MLyl^H`e-}s$A?v>yA zwO<{;-zRW`CvX9rz+WBEUoGh0j|^Y?HQ@LCUqS!}9rIuObpvoP!;duI1Eyg1{a;2{ z2L`^0|Gl#a{>SyL;1EvV1YU?9H!##P2hQe21alLKo|yg zD1`on25Tq;H>d+z0EaKWv;S*Q1wfd+au|gH#>4`y;yJe71onqf5Mnpjhgv8CMqr0b zZ~^?)0us`JJIe+w$lqH~hZWAm38v#mmfj2YViwkcBCv;KD1uuU2R8`hN`{7V(BE-5 zzW-H)GQ&g=hU8R^-UK!WK%itD00(Gz0%!mSGyC6LXb1f*2UqB19oPhW_&8M-=3%Zb z9oDh`jpZju25=yQR~`m+(B&Ea-(MyJMwY=TCgyA&-YYJI7TyO;u7z@Nga17MXfTH& za07D~hX2(8RqzJ^mO(kz=6TLtJCZW$; z{aNVsNY1CG>Z(o)leX%t*6M)s+O78LuO5k`2J5jVYcFBy^_bMMR_m{h>h*xvwTA1g z#_G7H>$>%InyvsRC}_Upl};4!GpO@jY*A0l96{3Yq? zwomqU#>XH^_!e;L@@^IV4io5PBAB1@=7=KLZ_@k(T?m91K(c0R>>H@?0oU;EmhJhz zityHmN*)TUeQj)#?fk3F*jaZ66$Z(A?f;YJH0{}%mzXD_EbB=g}W$>3~ zh_Ni+@gPUgrbI1Vmr(K7FX3L-vLHYgaaT3T4!=2xCU{!1t!nA zH)w`(*eZYMgfuXQW}x;r*a6HohD+Fwy;k&YkFgtv29CZ3P}Tui#)U5jgmNeXKv;$% zum%%mcOA$EXwU*TXon)`f_+Pmi?r_MKlA{8fc+e&TUHha%{5{2hlU0EBhCx^*`gIv@fU00%qpy`^x6 zd(Z{^wh8<#0vL!HeSn61$%dSxf{ZsEj6?w*-Sw+z@q^d_BPjU;P=sbUw@Yw^8|XDg zfbtud2V;;)ju3@QFajgEfox!e9bk5%OxK+UW1%KYu4L9%y$!)TJG7 zvfVHuv)MzII(PEy>GLPhphAZdExPj#6{AX*GHvSgDb%P^r&6tI^(xk^TDNlT>h&ww zuwuuOEh|+A+GN+r6oCd#iwkv6inx*sXqgLWbq)YBrX$;@d>8Y@)A#8BIsals(Pr{T zFP}boYuJbb@=4#sgZb+H+gFg~8zX@x=F|1U2*w-i4s5!$gX66O^Azhmsgk9rkua&K zO9PSjo112Ldg(LVDbnN0mosnf{5kaK(x+3eZv8s;vpO>ED^f(2IkbezCF`OJ7ocQ1 z0GTUv*F`ohg5^yNr%x6k+C$wW`}a@V0qM}gOb(pLqfb2u?ZeC(ZGf_qO8oHi7(#(G zl+#8XeMAf~|DfcdhX?p~Q9D$WbAT(C%wf+s;*1m10d5VG)NwRsr;``2-MAxA~I{C0` z4qXyjX$~_8r74%BeF8_TS7n1pvdudCEVR)|J1wbo}w1B=eXY+L>#{2>!iy%xN%J~uB=srTt&=`Bsh7?a19gk@F0T| ziy$OVK7sQ<4z}Xx*V88!OPK?O`7}<{3^T+EtiRcCWuxcOOFupJ)$`c$%h$xAgBJF5 zaX=>C#ogK_*>W;Cec194&OHe(lI=2U$Y3~2;PiBEum7Yuadp(k3*|!&_$Q@)QG;t) zp_BCzsK5m>uz_2_o@}0gq|+&BXGLHHE|PHoNo8vuOh}jvTH%g+l;!|DkjEO5ktlE! zgC#z=h`4g#1kxO!R|#2)xCpg|9K29pVXKN4NaesG60wLz93lkmA;AM&<9h`IVf+q& z3r-lwa1PT&WVTfa4a(^xl@LkBE`ljuVM$2pn|g5!Y8 z0m`vDBrPLv2Z-Mq2yp;H$U~64lffdgs0;dx=pSu(p*Y&m6JE73AD>_Vg)C+iUP&%$ zvY;ap-hzB4%fb3+D3}S4Q-B(l-U)VqT zKmrK?Lg>9plOmz_-W4GT2uLvq2qMx{dJO>rQbMmn=pdj}=}MC>MNz7BqzVC){v(I? zy*TGw{BQpEd(Es_Yi8{|dq29+(+LvkkUijlc6*@tNRm2p`{Zkv)}SncMcgVu@4Ggp|i|{ zOOd;-BESWpR3e&BtmdtI&Wwt%7X7;k-mgh&sJ0ks600FLCJB7vko% z!Uk`PdqSo}jC5CcKQwM&?z+7a7BMw!zmQYiifSyA>%47Ty2=`s7mH;2N5O8WP4iTb zUf4$|95aU>mAOuHR~)`=UM%vXa^Hzt!VaG0yEXbU{V%`;WOgr>&$L?B!W~i~^62}! zhYCu>c#7wUP2Jiia-sO&d_spNa&xuOn5nzAjxA}AC2nBJ!yCf|6^^`YovMG|RF@bc z<`l%Bpj8579^nDst1XRlaB|cUz8x)=#zqrRYr=$6i56Sz?v=x8GtDAuXdd2r6O#8P zdemu$?a+|TQ1@f=r~kyghKeGew_1eGrYw0R$>L^P?m#XJkFA}5H!NW(QrUj+@gw%3~I(s@d~2fNV#i8*f)&A$Bm*}E|> z%?4B8&W>3xSbE>DPa1|auCUzw^+PQfzG7$UNcF{^9|LrqHx@Cj2H3h;70`oJ07H1< zUscICGb4U?(?dS#DZ^zsO?G3ee_qTh11dJ6Zw!8;xQ#Wi%0;|1RF^!K#6bu4vxsH8 zLq|&yMtr$XyC}&gQKh^Gk{J!v&f~Lx*q4|4?4@$WZ6}_x=ARF}PuT;8%@DW_dBDk( zt2Ew zX_9L{^O{EoRv$sZ?S*DTfO%pH@)_R)pHX~`Q3H^pWWSCZ*Y&#B=qQKxDvxRd7$ZrF z(*AG)>CVCx^0LJUtb(HjJxxIADD9SnZoQ7k7KXn1uc=})kxTdc)Xg*1_%UkhT`GjQ zZ};f}lF224^UbE-CdKCiPVhA76e#ByBMS_B)Gb)GL zNq_EUPV}lb_9Siesv$FYm1cG};7iYnK zObdp#)aqjM_5U%RJ$uZk#d6K5;WUcFaE`rap?{tb!78_gsnK-8nX?W7n_3I`HGj=Y z(wJ~?nIU1gEgq>!KBcl-vjl)pMXX?6UsETNVbP4egQ(ri+s#6TJWV!icfF$5H3&(7g{BVekpT6Q^!1YO!PS3Dez~USB&MyTuLNJUs0kD)7;A~6jcI*59y{_zJg#{U6QI~*GTP%R zW~AmGS;9a3^kQN4+<>d2$aJdA<)qBB%qSt&7U8KW4~giB z0oU@H=fm>X55^@sv$BkG6slEfYyfNtk9|oRC3-UWf=f8AtO6&TtKg&^b-SqLEwIN9N@uk|NC5U6 zBJJh`1gYq;c?J82^S$B@X75Qtg2}bEh&^9B`O5J3`j8uPkX{mZpm{$U_3E4adYtK0 zdYo@%rtvsscZ3aBm*4Ft_i#(hiZo^M+Asuv8DxR?W4CQlpXuAjcm1*IC}Dqrin7>y z1l)usXfE>Sgiv*laUZA26{*%lxhY($@IS0#Xl04<&MO|4Z1Sf$4$P5rYwvBf+53uh z`O+~nEQWmPZ!f^oI{mrUP7#Azk~|z79FZhk{i-T@tSOOW)^u$$TO?OKBDFpI@#UIb zy=k_f^t+X{dSxcnT8QWq6{RbpZe>@rrjVny$IiQUEI=2kxc$k}CmG$Fth{q%~O zD)G(Jt;e6Bsp=Tvi6%=}nsAblQ19>RF<-LXLu66{ZFWw^(9!C91uLz5oz@Juf&D&p zJVWTYwSuc#wbZQW;B%EJWHJe|<015(46N}&oAseq4IMO;PFJ3E=+)TD*n9DLElxq# zo;1!MX^d+uSQMi#JI5%~cb^htND<9w??v*20?!DY-mt_5P#pnOWZ|oNMsDVuLp%c} za`uiz83xtlHoPyN`zXHYOWa>5%CO4kcW=%3lf0zxSJ<6#Mslwg!D$0M(h+DRQATOW znWO0|o~sc^&)#l0R1}~MvQqC`N$2O@AhYybk)u1`r(_skK`A19@BGy}K;CpdQaojG zc4tY@?Du`qpW^7ISbieHc!(T~*w9e^m!KwI!a`fr@~p&U+3Gw!t-XWAF@a?AcK+Yr zAFl7lJge`!wxv?dD?_s}Ic$RxW5s`1@Bc@@eBJ*5RIe@I7YnSRrD3#at=;6euAS~WYfhYi;%GXo4uiqyFq+ONf#Cn ziwq`}K->Z}MGVxCa4vb7$&SGeylH84d5Coa?5+aZQK>7a8U;-gI~^H>q;#I3qpD|8 z+Mz&seNWh3@t#mI2aJ1NWO@Ljz`)zOqe)q=<`d9t1`>b$d9cI0cQgHsqRQ9 zvkz&oH|l5;4*$YMmsr%rUU^?*r05OVOk@nS52EweOh$j{((IYkc1sZ<+%b*!KFgT2 zNY5Ed8BNO=fM5CIrA$;B?w`uUK}Teop%Mp;Cd^GeXhAa$69#%iY4#?w$49?ODITcH zTBsw89S1CKHK|z2TE6tqp?qZ-Bg;X=xx$f}!*y*vH zWv=W~PvS?*I8EnMZkHI}pwN?~iAL9g6U$YSXZOnQ6@GlaTgcqlgu`|}B>!UnSAmyh^NK!K_>5rP4dCu<=bc7F9(`KOmBA$4D@mgvQ zBg%(^74kbW!If*oB*(UQdH)!#}H3yg}#F#NgGJgqH z9tiSNh&B1a8SHOb?HhY@;HW6~=CgwPv|(7ULV{VUOK+_2bW0+4THO3fB2hu>-ZoaO76KZvg>TzIiHLq??(Qm!4*lOW=^ZOGpouH86sVM7w^wM1+Ge(g!p!H>Z zY*xYf`>zT)9~47)6>~oa#8oQhjR!cjD!yGh_taF(KM455k%P-pEC9C+;{vP~-gWR(s_0FA6QfkgOq-sm^sc<^ z-KC%iK}Q&W_HN(;Pv2HOeKG9CUp?RUzQE}HLE8tSQmy{M9jC{&%m`&M zm(EZdtN2gwd8e)Lps_G@nrQ*McAZ%I;a&1`QiP;M)4Z=0sTe`s&d zB}V0cZtt-CLj2m^8AevL)c)x}`SYFCfiSEi=;jWRu4@B%+=8hirsE-mIy=#NL z`W+AY+WRa!zIe8&8v&)dhPocBl(M%CFb9uEsSM2n2UAtL3RH$asEjmsjC@uZ9q1T6 z2oxR-?yKtfnyWmv+0pVwlOLnSN9dTKQJrM&oa9#hCe-;&LiM|R=XZ70DgDkV6V)G< zoj)F{{&ea5>8U#H*Et=gIwQJwdkYk;J`jod@2&JmchVP5q{^IVz`*DKK78n0U=CV% zsoOi<`Ch1Fkv(Yfw6pqHb@{S+{&;YSMlJAw^fr%LLjih~JA76Bnj}s2VP3(y2ia{b zu{TsYG+h6Bm0N>P<>Z&dmkrM-g*}x`$L7rg(!ykxUncsLrD`$SqIBX_w+|wI`O&X z2LbAph>LW0>jsy}GK=<%7dFkFEB)!pnI3lSeuuw*jQB8D7Ct#4XHv=Xa_Ehr?RCC* z#aj|`ZBJ^flI`O>k}2u(lOtJBJM79f@s~=@t7qTKP0LT9tpcBsh2{eps=2-|=9^phD5kRLoQDbHwz3z0ySrTnWY$gCZQ0U=mOq;0_`Sab)V=4i<5fc zugzCu)F6_h$X;rSg+E#_O)Aqq+Ja+3IE|r^=@&+88R{=g4)Lb_tk0?^``NvT=3hT> z1nf-?a7R!*803xZc+PAN5-H8m6xK29;wy}QFbp<~*a%1Y#EPl>EZh4wBJoR97jLj` zLzb-uOBv@6Z2^7%D!=0Hkts$-_ne19^P3~Z&RqQWadndP``s9KYqIeK0)%fum-U5t z(@QGoZ-6w+K!DLki>{YfU-8e>_iygm8{bV0#nV69!%*u0$uMhy)U8p3&ez0maHkaD zD#BvgEWPMg)^-Q2_TgO!#mb-1!~3n zbI%p3hT3@Kdf5kaBZRLX{b`B?y>P0ZcR!JgXn8un-yTv8t8YErpFj9aLSswlrjS@5 z^wOHx9)4l@T)upT}J6 z#w;~>?6oHSI^OS&`R{}<}#%q3)kSY8%n)EEQFNP?Sb%Qu}%WtSHt?s@8!tiyKnC{ zz57vR)!@eH`k~4)$c7@6bL*dmb;INKBC?>5FXrl=4}5aI%&3}c@%X;__U2Pw=nUF? z$0(L5zT6b@k59~9&U>~2OY!}mjl9?LK)8TeM*K(bjSkEZj7$7X%JyrKY-E%BBT4N~ z4vr)Lub&akqV#dMpUmmXYxhCZ9w(6bYM8OqjW0Zv$7?ekO@df3kBp-ivO% zM|8jQspIw0$fUB$5>w#ee(#Xb)xL_F&*0Sf^X7v9N#8;6?Tmc?3+GL{XYB$N%V;XO zt>s9#(vMuv$W9kj*gjb~@6*12|0bd)BewFf9C9H0kYAm@-^P&`yDSD*K9jMIM!2;& z#8D=*%myiB$eYHVM)+AKsN`T#nE&-NjO4cY4e8y;rp*9% zZfC1FKoGiJlJ?N;S!v2@_I7FLx9#n6e6+|;11K3$#6?{)&fVuUVslD0AF zc?D@|rE9r8LNEN_9^uB%a6i=e<5Ydvzs2A2bzsc@*0>6Lru)&5aC!C7uvqin(FkHd z?08gW+Wq*e!e;gHn9Awi@wmWavA+{K1-VB`W8r&;a=SPVY314YhB}pAWNN+2G#2>x zC+o{eG@U(1*S{I3%oiuKuH`kpbGprcPUc(6RKCg$sx-j9y|R?{8Qpgxk_@TrIW5TF zUROE#qA2iEy8Di?dd&#gqg*i)MVs;OXo=d!iL<#pzy0$~e9RrCVXsV&i*3&$_i^cN z_cdzeJ^zLT#2DcHp=ub2M+0oL=i{>!1|EYEjvCQ%LkrLc?cNW(FP?o&Ca zuJ8aOY*YxfG-x3$^C-J3Jy z5;BG^GPmXZ0A^ec(EGQnKqH>4Yj9!u(Q;J49<6K0RWUc%&_KJMkc^8j;h(4Nz5D1W zg~xPOMp%;4IOhpt8NN>@&>wbP8NoT{uS4D#5zW8POS^(YGlzFmQsVd`%7t%2b+A$H z8bFSPS`FdG!x%1XBu8cycgrF z5w4|)8=?8Q#${nuv@~a`AZ9e_74=+GE-|~qZZMLS6(4=G=KzS(qQz=4=!@~3D!jHe z%T}Gp|G946u;0x`SD^tCA&-D)Q;{-?v*h0QerKl5@~>R8sr*6au=)Ex$Cb#09g-={ zn}~_@lnfk3fQvU)zvBtVL)jSRi)N~-|8O*J!W*LW5Q+dJ1X;_}hGI_yxzYn5dasKd zq?2QGuMyA6?yS#h=xv01u;#tyU##?GGSUi8~EK-dX_iNlNN9KOs_!+ecHSR9==I4lWCm&PO-+B1i42|al*=$2V0$hg> z*QtYdr&(HjiT6xVc~F%|5>P{fX-+|d4~8St!JGlgy=Hg zy}^G7B#DMUUg?-IffdlQG)S18kp)-${Q;6k8dQ#Hj$PnzGQLrtL=lOzVXLwFjONje zJCD!1QLvYjYND{`9Luz%5#&<6JBio~AhBy74k6Wm#|05q06>5ye_t}}A;&VyoojMU zU(+?aTHt^x6C~+}H%#W?GQbZXtrDL%11vcO^zZePfKZPAeT>W#uaF9Fy0VkVy_l*n zZhA*8_WNOb+moWi*Wos%E1UyLKY#nbtd^Er^ueyRY)rfk|H2D<{6TSgfSQoQOR4OQ z{4uJ+QpITp~I4RjhXa%P{0FZHM|=(2jXogA<*olUn+Oj1S{%u2xyb z{Xdb69VV7n&F=`u6n!l`OgXlh<0qPY7_uBY%4omZKqLiJs~R8YJiqr_VZ3$BZ|pe# z@@jMOW9vjrs2HC8*Jcxsf%yB7zh%n*ZR-iOO_ke=R@nSnpN3=EVO|MULI3TdniYNw z7@yS3Z*x2~X`h=O^9?KR{Nt6>zOZS0+BW~+zW;dp;_2Awr_28i!f85|!6s)t?AHXW zNyjSl_*uX5^&u{)V_nGPeAwptC~LgqxBU3|SkUz`o~Cn4-{j(3?)8nI(Ya$ee(|&Y z`d@8Q=bnqn<=p)BNy~WWzTf!e;^p_?D*~G894^4mJ%3MMN}Ck}c?m zKxg3FLU22H1iuy9R5pUiAO4dW&AJr|+CsO}hB#=19G$|qrXy~#M0}WdA~+NI=VgeP zD_r&rJ?a;MIOE}9A%BSqk@E-WR)l@vfr0BFZgDv)Flp9-~}iMr`*QDCJ0c{LaL$K$Yng0rvYqt0?O(i72YC#4W@X4h1+gn z4Dn=`uFywFhz=1FO;bmK!qIxvz9y@q07b--nSwn~U>`WGAp(8Z0R9pQa`BIAEvMR> zh%Vr9EFe&P;Gy|Y3mL{c6-+>n3Dh6F-f-$gSyV(su*A1$g%Zm{W`*Em^08|?@YET! z352#~8OwVJ0^_JgUEw#?$X~5!ty##+&k}a!gKE57nFL|445HR?RE=k_Pg^uC$fyET z;wS&;9;>8}QrO>qaLh6`n+Migo-l%=Zoz@j;grp_H^XptDBN-v#1ILd#Zg^CXdi{k zK0<+SiVfa*0Wh@`yKvfgB=k7~+6#c8y#Plj@D=LmvKQbHfO-~30Y*YETPQGI)U!ks z4aN(Q?M3|)1xDcEkr0Y=NTMEVP>V3UhKJ^bKj00H3LQl=<^ zO|TbJoSVZV3Ji=5VCU+ry%70GWketrs2(lG*d(oLaNS#n~5l}VHeG~3s`mtzMKt` zvBnKgr|_L-CkFsL0My$Enz*cltSr#%L`D-2jkz;ycPP{lk=DWh_^udjSUheCz8uUR0%sZGvR~t&*qAQU|ag4$rAnZX}iVV>%>C z0q%>S@%j7y5UQs-$ zaj~V@t>o+hfV+>oPfI}@MW{dpcJE-q6E*D3! zRY_I@02(52hInW;jsi_cP;|@5#*-OmQM3TkBH-Yi*itkSymcGS-kQ7+2w=Yrd4~i) zLP8^u;E3AFmWkRo6=d&fDN@>kZQ^Qr{m2jIDyv%qYbK!g1K!ji-k6_3`Pv~|Hc^7} zX;K>a8%6U@75g`~2FcuT9oBpoVhdHG$cF=w$}+<$Jhqg*D&IH@Z}~3x$<4cQ7dtvv z|9G&mcJqxnMU&~h^wGI=iJ&IvgGecV@=1|~X(9NQANfmU%}M~}5E87Tkpxw$Q*Upu zpRLqxFJ7_=9p4PQ#nO0xx6!J-Irx$`#tLp|&~Oa?_$?3+xeWGa%ct(HZ#S)TR0s}u zSJeuQ@SJbXU}q0&hjSRjV|JScTw4@ca`Y;i9e6W9ykW^zITik`)s$XZgtpqtHV#cP zOAWHddt?leZLrA{Fe0Kn99pOld96WxiLbf5feJLJdrxVmmTBTnUOJ%wR@fYwZN_C?M*@CHVCl&@~05^=Og9Mhr6Hl-qcxY zNX(DGl>-2|UeI!$9P>v|q1#n<6R^9kAyXPqoQ9R0T<`%d15BWq8wvl}-qyU*GDq3E zFyC3P-$bvOzdY}|ZqxIDl1!M2%zl|Hxt6jPF6S2x4?)7EIcQJX$y_wrjcR*Ug2^O! z;BS{Znw~Vncs+V~AUG6FSC!*+To&AQ?OW@rGJ@4@h(LCgZ46Sw|d$$dR~SbJU=> zRv&d;Jc@*(97Uyzf*;+6??GXyR{0({3Z1UkUlocA6+*a#8_KQ6%GuleDe11kMcK-2 z=gn2^LO?LQ{Qao6u-M2;F>?E5@KyB)DQ$1-0=zAFAR57*(?!#(0+%#`|GOMe2nL+b z^9yGsQP#!dC@5B!2dA>AzHN0h1ps;ppz1(C6dr1VgN-wDH|_*WDU7XGqnYx?Sa>rk ziSuJgTk-$$zUun;x}9ow{^# zcn@#-O_M?*3Dw`x_a#*ReAi3>YbU@BLI(VB0|~!o$RsDMC#S&OG|BKE?2}-}b~5t> zc6xDI(ZT+(tSa4#Vh{FaU`4QD3ntPgY+<^+NIdPfE8MBNt(0{p^6mT_8tUUd6MG*X zQ!|h(KI>2Q%)oA4*NChP?*GX09oJ1j{fjXSw&NSoV z8tbR^f(J9n0Lste@HUmD1o73=7jQ)AQlB_HIXw8@SGXt_t++kB;5H=@H!&;~e7y(H z?dmc<1C0lyfFdY=<6d1WL6ALKXYwFJ=;w)g@V`KNKkO+au24l-6e{;)sWhy z%Rj65@NH7sHSh|JYa;)|TUuEz+B`4l-&2}vWbQIPmb5+f@1q2C_~xh|^-qU{4HOuR zqBg-%lmc>M0~jG$@Wrk77|J5npzr0(+vi^UTlq9N<8A7)o~s3LDejNo9@hL3+>dE4o996|nwI#kUXOrat}e07!&LK6t10%FDHFjE1(A;vFGl`Rd3wlzLbQ zqWr928uxX-`PcFtx{CH3MFmJv&|=x?@#Zx}8*U#?vTdQTtxc5E0+0o|Q%Y@v>3@$u zMGZtD97M8c%TbUJc<j zC(AUH8$W|nHPmPeOvjJAn!$B^OXMk+rLYrN_X{7&F*a&z=^6556|%U5on7f8W`zSV zDg1|qgsq5Dqa?Na5XSW>&0FmTDs#^3_;R~axho}$|Ig2u3x1(a8yjd&ZcA@88LU+6 zTJ+vZup`=z-HL$f`5!+c&+70=zhjh2G@o7}H-?>(R~aGfz#Y{JTldlPMQM&Du(}jS zKYH!8`RQWyft0T3 zhraq^tFu%ojf9;PhmqjC2Z+LrdL8NeveQlt_o26x@n10U?gq&gi1^!lDk#zCI5i!2 z>4`=->kwRx{fLh^ED9r_OMpC*7;1?bt47}KSAA)CBj<0g^t12W9~=NGux_*guOuZ? z?@Q4-8TS6nl`J}SGpneIEn|?ew4=5u5w~mm>vQXxfF7>0OVX9IcFweeNJ;eJ%x)>Y zn1!%f$lR)E97Y#XCAqSbrdfM4^QGw~s^lf$lYiPx)5!fs0pm<0OEc|_)h&d-2X5ZS z(m$YB9ne9WQ+w9FcKk0{4&_PhYa7G;&>-{UljOpOwzpP4NW5W>ZgEUfC(o{iu3@&2 zP4DW23Q-S-jFQtGk8dT#$V#49qh#6?dG+{3rg2Hb_t#B*W4Pw*{JpE?pPBq%+n7=T z+V~YC^x}MoYa*;|3QjfC>*MNGAMy=Gudi=O@79d#DgSYd3jdyza>#QolvE!O$XjqC z`Rz~iCjqgixLcF_DREGd-NYPKoeG?0#YO;si?Rsw1NB>mAX=S={Bx#-`f*N)hRL6b zU`Fj$#rmAuVG%qckM6oAuu(wY)>X(VX**QaN!h&k#lF`h&f-DbqQCQ*Jjib?N&i|? zVGUNfo^-^J#k-;rs8VRABqREJXJD9I_m`?6Ps4NIkw;O1I>L5l4wKVe$5Z$VVjQTPvsgMgcVP3o21q%rY|KJ;02}Ll zoog8#z8ibg-yd5zn)3Nqc7+G1n@P*3AFf@IbSo53uI?Lw^&o7nMLZQ{DNn205B!fWN2Uai>>G0mxaHnU0m}2ZCRIYMy@Fr+3IG+7lF^I{~oJ z;R_sl>D~h55KI>qwq1dm8}N4q2SkhOY{U2-lnOJa#3b_->EB0mchfe%-B+no~C6 zPgF`N1!s}Q&~u)iJ9<5dC+WB7-fr2`)k9=T^!+_}^B*&|TRjbFO!syaAc`E|jOx

    h5(x$bLZRU_5ick~`v_R)Z4bfGFwFl`IR3d1o|R`BOIx@`@*xH+(Y2 z&0dITgbr$;Wd1bdEoGHRUApqpzDkclJtz53X{bD@=`gMmIb&IM=pZT;cVW zx(y40&~^S}<@+UqZQiSvm+V^QzQ)zk_G_(>Rr*qLWX+<2%uC`T2crGKvim}b zh4s&0QaB`+yw7V)dX>%ll4XbqrU5~V^}e5sTn}0kyBoU^`Q)+VupoQU8##TS`Axl3 zYtkz@5#ZbyFY728sCu9_aGwfE0KJ10ZBms=py3ym3U8^&vhY9R}01a=5_KD zZAi?Qp3^+>w{(73rcEPm`&{w87iBVhbZ5_LpFladoa0@(9Z>kjKz zI_3)YKhRqN8%}ys$KiT?+`f+kg-u!h)^FSLO1T!=&*cSt z%gn!p^kNsKasQ{`@*m8)#9e<~`~VAy;F%G;mn9JvKI2F<+!OuN5;NV%7qw^KiNkWe zJFC0ekSKSi|$`FiS1fUH^}`m^QRLO5Be3Q$X;nRyEwNDKx+w)Yt z?Hqe%kgv&*0ygzSO7+^@&ug^waS@cV#}FAvb^Igf!etjDreTBRHt=~edAnHMg!*uo zI@+q1tT;Z%QLK&Z2-aS8T@gTaju6rS8`Led+ng|U+L29TLL z_BKdX<_FNjVhcMR>}1(%|w7dH)O{oNmgY zgVBy|;GSLJ<2M)|croziHrP6E4Q!er6a~+F!PW#s#scAqHA;YjeA; z>4+gX`XYmh`@YTBl3UXXxb;2_EE}m3M0N?T-UKKhK(Adz&{&M`puWu>kkhB`^gJ~H zDQWu#^caD81d4VCka-J}BWuA#_10TRJUNUOHgmH{d5n!Xu8f=~i+Kal?ur!a)pps_ zYs}U&xu{YtNhzMeyl@}NP2vU~Uv3Ijng*O&QA(U=A@~?vacKsVBcvXT@v}k*gbI!&>j&KciP&1&`-pH4~SsuOp?t2gh zQXQK*!(GsL!z_si0qu225sHsyc2ZS29vXfy;CvVIzG3V$169eC4E_n^n-L`TDs}EE zRRyAJD+BUU0t9n3S>}n1Y21NX7e~1&n>e+HpU1d~OduYO1T%owM_Z@`-oySF4Ml>Q zilfDBnB`nach*M;S6TVFLvHa|@!6DsN<+rd$;R0TPMloAR{j9hKm$P<-KDO++~!$r z8cQH;+{%9KT^6k|Ual3T<{$IKHAaZ@{g1);faOLQ@4brZPXR13f78k(d&)vIdcXo$ zaC-atQPhneTdc-ojAl^ze2k3SRX9m53vpEmj5Rhm6JxjuEDm9*TTyX5#4-imWWl8$ zfTna+GuXw)uObsT@9RbZzV~!@16#Uzou`tv5V#4Mf3Y(0LHAImGm%Dn_f1fx@+_d@p_`R#1oMVog+AUTPXY5VwGJ{%C$>W(#7m z$}#&4zG&WE;duv#fU}984yUnn+{JDM0c>SET-2>ekh3lcyUCL_D=!Ugl#ha5^<^AxeNIx zHCZzI{c(t%>(z`HYXcV z)4E~vU&|y1=Nsp@`JBVuradHHe{34MB1c(shG!oYOd>b<-!$B!qEWo{#sZrKf##~3 zs=l^~;IxVsp6P2!X%p!FqoP?p2r^#*UGV>!wxiT1v#G;^Qtp;<3*4P~3#~sU)qz+O z`z;;}{D>Unw0L?5{ugLtbZ%*&!PfGtYiG)ig4Re)Y&1F{PRYQ0I$`n8+qlxVc5Lg| zC-AK9bftZ2s*DtdYBKxC?{g~xi(8kAL;s8nTC9z-N5XYYC(~_?za+&UwibMc6mfPt z;oIf$a@V@3`ZJrxu7#wjcVtG(z5b1V?H)V6T&M|IO2jXa$6_RaR$5(YdH=qbvi^by zQX#w|F%zVkfXFC7q*4X&8iLXACq?@^i2Flt01QSZkhlR>$zTPDk13$W6iiUS)!wp8 zt_Wmc51k%C4&jalaZgdJz2T((hot`maxh-D+JnGV-BkHAOF0Co)-s0Kd!9%eYX7HZ zwT=g5%R-J8#yHhRI@SUiGr;0Fa-YGNpc#x3E(Yk2ehvXy%&@u&V>D)XH1TUrgca|K zNG+Zi-~^aeFgnXBS{~1=$b%tsTQe!MYH~&4T7VME%_bgH!UjuAUpb<-R;Q2VdS+0y z&S*Uc`wdPCIUdYSzCn)ms`|fsa(Wv#X@Cl9fag3A@s{XPILOujt&58ZHi*-5{Vl5i z4KN^eRe(M+Ksys05IC^17ugXY#;RgH7~&LmBMo>($qtfR;}UIJ&}4k%URFTe`6UOv zIZpp46p|cWKU}Vm8)ENKmZ8omvhmdUkozZ<8S~%OzAzXgqKRQMvBoT9!2T`!pRQ9- z*KWk`5(CoLu5k{?s30u(l^{fU5EB51EM|!Tdi@5X(gXbC{3?LO3gHeDWNM$lepb;p zZT;$Qc0qEa8c#q^vM3xU7>pwp6ZfrM6S|afx67Zx7oCCPW!iT<9%DS>Gji{hY+IC8 zDn2*+RBvbTyLhJw@q0@$rgQ@R%AfSr7}pMgSCZe|ctK^AgF6lsY)52s>D#PDY0od+D$7D+75v!WZ7{q7J`XQ+pBbPMWK ze6f*$FgmPcIk(h4voKa@>@%7ggT07F{N4^A?G&UTTEH>(+2Ch_5KYv&l0saXVRSK) z?8f5a(1R*3V~o0TgC}AFC&1eZUjgZ4mUyqw8Cn))c2^V!b))2YxzT$tPe!!z{M z-K8(TR-?TZR3Nk+sY}rlPMqgE;*jT?FL)^1I(6(k8xT(|BA%@!t|{)Phs$hQgWK>ue)`)MT14<}AG zl>x3Smh_81R^#Z2y@K(`Kv)Nlx6da#NQ$xaT<}KI48RykYkApJO%({ZT`up5rtA)i^)+cfV;Qe{*@a&i9tjLmcyIbJjs84$? z%@r$k^HH^i>Q3ZgqOZMN9{yG9@4~sgCT2yHog_hSMox{rUVK3G^>@K84vq0w05yeK z=p|{N;2`Q8qsFs-p-FmLo~KPLuZYo0IimhDb5C>>I!Nyy|MRdsLuL9WY{_-NF-kKS zC*fV^!F6ChQ+5`WoZ&Kp==%@KxAF_k%v zNVp~e70vL1cr{J@&xL9Zj12~p!c`K{*p>7B)nK>8x;l8-#|2@(@hmm@NSMPgqZ zv$V(FndJIliqK2WJl{XvNv;BSRP(Z>wkC=;J!T~@WOkf|1`u zqFQJS9=WE;5|(>n=p{U^6nqj5{>;4hXLw;P-Vn&0^(9&9Afoa_;9$SAZu?+$AXQ>X z7I&u+{yM~sdvNHJSrIto50{ zk0PA$kw0%Vt6R&;UDA)``N6EojF87ouk~m{nRp{7**V(I_zcXu6mBKRqRW_QB&Zl5 z);!(5teRs2>q+Y1nMhh*IgwWW)cZ>3>ozJCQ4?tJR=ug2mR9RVyuH`CKo-&AscdPQ zk-#ef?E~4UCH4{Q`BN*K1rnjRujeQ@w5ZdEFgezO0YZ3-C}!cpC^l%eS*%p|kopzJ zg>XsoU8UOr#4EFPt*i%aw=HTp5JKgJaY{RSo^Y-BG7p&3s0KsI#k>2na16A%X>Ry7 zucvu{=m+MZRyy_Wi(``yU)b79O9w>SC-I`s=DsnF{EwgU!{@A8s}H7=z#H<{LA+%p zPWeviEYIqnX1<8KciR8_KZM=&S5)EKF7SbwVaQ=f>F%7Nq#e3bL{d^31ZhwNX6PD1 zy1N|^5CN&7OF&8lr9+VrL`pe)-}lrnXPrM`uV=5l?)B{Z`dl5?B5tWGsUlip{h|Ny zGXy`qk!;X0etS(U5AOquQe#b@(AmLpWO6rHjU{Dy#2}633&aq;d)HmPZs-l7`|ooa z;X6OWqYBFZ<2ZHfRuC6|Jc=0C#g6%V%zjoEa4*qje-ong#`JbdUSdY7c49=<%dfnd z@n@n~?FTg-1<6hU=jTa`{Je9`;}H02vVe%+%jPVTJ3k|ezcajr(TiG{kjfO>qRSLAar~Jh_Fr-7?Kd9ij9F96wSIW_-hH=-=56P>`=h+rj$DYRw3Q35j@#S(-B{g_7xIHX^4BnqN1* zc&eO6IDTtB+Z^Xo&n@CxGj9E>Ig5_7!qjVj+>X-MSVxFQEd4#gT;OfaR7*Czh=0=c zzx<5K!0@<9&*#48!v{RlI3hu(__z5xq>m&%)=c?Fs=5Qe^xgl=|M9q$l+1-~oI@Y} z@#QZnZ2=YB>k#VZFv^Tq!c^5sBcrc_Xj@7iUi0R9WK5+`6T3h^RP&SH{V#?&ic=_L zs38Q5RclH0TxJG2W`PtETzyXy==gOV81h5BsD+#0eZ9QIAAu^m#JZ zR)@Kdb!*JruAMh&8st}YVYeYW2%$wpHZ(O7K2^i<4f&A8F#`&ZRbBK>OXi3APl?xJ zJ=_EDPU>KdI5D=*i>O~fm)VsraRfFhQfKwVb+TacQO;k2cCp6Kl5eC2Ym`mS7t_a3 znnNx|Ue+WA>BL)9gzSWJ~Du>QG((%+hqJx9V54}IoIu!RfzSA1Jaez-%ipE zkyT@oEUh@(n$l)~BYt9N+R$+h=<^37);^P}Td^~$@1X@> z_yFu(-Psze&!Eu=2xoRB70%mF%F7ll-f}V4cwRB)7IEL@IEi#J8_sEBl;Fcu+-Gs< zPx~{qnK$2o;#V<5b!9#I!}ALc!&Q*QmeD*=Vv}+~N}a8}j3usk4S*QAbxX9t!iSC5 z+ZsoH3R6>9dHdyR;yUISBi*e&b>T6Y#P)HU9uS)^smy=N*{cISss0BogGG6(@JJcO za^!EWdC_U)e(Y){xP1%>z?>^$3Q|H6O9>|f&hgUL$&^g(rKT+Q-$2&KOo?gL|&3Aep|;)$>)+#g`9c}&a(e9e#Y!(Dyg$QV z<8?t1nX$HwBx6j|l+L_~{2UI+^aW2ynQf$3eF6Z3v3Zc*4x|(h3aZ+wyWsN~j;wxA zQHG(){46vk%*a@JNqVhc8XkUtZu55JnO-F9Mp$V z$~2|Cv}6pG>=x1yM5HDBUIUanNahW8mzT=Wt_=V!n+v$_31Efy>qfWB+P_6{isAEmD+`V&i;)f}9-!p+aOOxf zl?R80)dn5N6hEF*#0_7!>JoxK#L^&=U!lRgyj1 z9K8hcU~$Of615SC0?1T1K$Uw6KzUrq!l9&c$R*-R#<|vyhg1=U;Y-{sQdI*@=-Jt= zP!x?yV#i2X^oGtLZj7jGEgHE>=Zn_U-_~sX(UYk(uUhAg*8R77|4Q{e#SeNzNiw?E~E3+CQUPaY#Z=L}^J& zDlVl#cS+-*uGpI9`Q=Q%I1ofd;}?2Z>2b(k~+5@q`pRHwys?K^u^E)ddkte@F~<*IrK^O z%YeOq0~LaMy*%MK_;jSTn3By{FOO}Ne0w~Fn373twfqQ9(b3F9`wLzMuQZd2lnFjF zLwU%U2Gp@M^f{W`q#to}i?Wz1Ph|nXRMjj)sxt(17Agi5k8uyAH{4&K1s2vZ1Pi?I zaNV$h3MLgsRW=K67t`4Oj5gQ7F2<%}Fvtt7v*W^Sx`(Oc*8u5YmrBTCHMtgp%dVAq zwBNgJwaZK*Ejmgy{P=~EH|TVoiWN(lO{*UVDRGg4N*DyH`gKyxh#%zh=PIj$^lQCL zYo8^5SMILLYOJbJjG|kMVDS@ZFxBBptAx|CC^>R-Ic?BUI|f%eW1-H;-5bHofY9WP zI%2_R0$a@s0xe?`a!{Zg6OXOzw&I1=qfz_^H=BwreGK7MitQ>{Z4uHV@mZ8O`4Q#! zh3&9+0EQy4G)9EJaS@|Vizu7rd{+ID(^7UF%~J;)+y(9^hEqwh_H` zx^8@a;pn1{?SO8)LX9i{c1OWBEK2BX4==odS^c0-7Eg5#B{6~XX;YHw z^<;Ls#nBzB>^P}N5f3P!ffndpjpEuD>R=|ADhsK|fnq$VH-6GaA-pi}f!Pl{CX`?1 zwjz?9)y)gVL3lE$vfBL<;m0qzvUBp)lW|T+bpX|(_N=Y4@xu=8?HGu%OGMpU)HK%a zAo|%8!p#NRLb%h@LrPSeNqaFMTGUv9lyYz**QXt zcnpmWD`YdP7B{Az*EatfpbQe#K*CM@N-j)~9nc(dbZk@yKy?-X@69HjUu4@9ig^l` zlUqklcj%e<6M=PCSW)pP-1V%rPuW3EUiB{T^r8yQ+laSTU0pqXHGC&%GQdWFUfqH~ zn|&YGK^GQSsxO1WBX^Ae#jdoYiW8{H-iU=A03s13ieyjo^3oYomTh5HZNZb7cvdr} zJkVCY^UouhrM_%r_<>om;+{Z3n;YXmyTXyqz zn7FIvi(-wIL)OQ?3eGrLp4AT5a@<$^QGDg?At0veA{L!2a2}85@&!>EHgmrd%XcB> zzh6^u75?d~V2)|=3qB#$mj1U;XDV8Ljq+vzNTa1tgdpo%`(j7sf#=`VH(2Ucmm|a! z2KKq4RoTC->YX91ka%K&zE6TY|1H$O$erItZ(|95AVK3|n_{{Gg0jx&tlV2MI1WwG z6GbOobAR{Litnv*I7+&=kM5w_n*~5gC&G1j_@3v@n>3)LBWmf_x?(I&p3A10FyX-- zu4zVv(f&+f&Q&TL=pfecnc%aJ) zco)jth9atSD50fwgo!eg?v3e2rKqEdsVPmS?3gYKD(NebcMBlbF6Wm>zacke5!h3ZT=6{HV$h)8w0aH2tHb5mm`%#b>je>-{>wp zLQLmLN-`je* zi*!G=o7@Qu5%{zD+VicwnWAm~YZm0AZx@^Y+U%O&NH47~@1X9Ct!FH7g>uxRX9HZ` zRpjL{hLiY$q^L4YLM?2wB|s*DT&7qjiun-8W2@}W8ZI9cnDeng$fV!%62LoR3GrAJK&3HsCk>x zmt{XjH1HvFS>=ebjtYCU!*yB_zt4~pBb;9f#t=Ak`(7Q%7PrDIOL&cS4=@9HHy_D4 zGU4R9P~eX1C=y;S;ta{z8s&+88fkG=6QJ1IiN-~cS!|!&Y3JY(xTqV*$NJ*wcess2 zt#Umc^c4>8xC1VP(40H96jB-sAqxko_gO+A{H0*(zVGp~~Hu+_KxmEX4}@zAmV4KSd4_-HY@mRsBfyPYOQ& zRn%Uig>~tEnD^d=T;d05v;-F|kjEran(LO!^|5kgUW0Vv2iYwow@U)8#UpGi4#9_u z+EyupxP5w#;@sH#w6pWfEgA{xZ+7aZkW)NLP!G&cT}g9Y2i@*|3CePF0-TU8zM#i|DAPZwn@Bj; z-pfiAUazeAyZdj&V?thf_6h?(W-7MFaXowU|yl~jr_O_QR zT1x1Cb#=Xu`F20#5+es@nTO=}eJs()QY;AZ|1UqIyC5|1=-Yb|NxrnL3x_)L7Cen< z+q~c-wDY0R1A!h72Z^0yyN<64VGih8Q2JtZvv8reUz#&p$biyRT;n;Swj?%FTmSub z@pEWb{Xj29uuSSdeukFN%m9_qfB6}X?(z|6ZB4|&bh@q>>+)@Nxp;yE5Fucm{N9H% z7`pc+&%v+1oDy}TG$r+XXoQ^|HFR7pRfEO%Q4SMOO{V81xFQqe`Xx<~d{X=iJ1F_t z<3D~z;=?JK{VjKd&9vNFc3P>fW>4x1Lg5dQjubI(qlNm3(>*{8Rb;HxqtQ7b-$!@3 zSmEYL^uhUa&PjfLV|FY8GXCB&th`+@g;`ys{(@3t5=M!#t_|}GmOhjJ@iPYN;5Gvk z!}tC+o6p8*H;+1*u^t1fviT6q8u{rrC#1En4)BJ}6snkUMA|;3PKnyexrFasMn>&g zfR&C5hP<6_)zYS^*Q%2VnX#<{+!M`hi?8sYW@`~dw<1fnRFGMs_XRJ4#*{+`BFXN35isjj5v|yy|Pq&3)kKoNq5e*AcE7cNkhf=(qEp_HVo9 zU~SfPX#Ekl^;51$vNu^ECfUg3{mFm(8G53`jVG0q%o7RdTm-~CSw)0tf?@gdc>Hgj z)2b2!Qj*{Q?Pny}Oc1$tmGXKm{l0D4Wij24coq`!)Cnpu{gj6J@~Ds8=H`Sb`ERL# z>2`b$P;uRv^_A=svzqL{{#sx087`aKzn4efUQs&?rw`tsc|Eh49{-{sJNsMiPK%FO z4NphirSVK}->!iX*-B*kyb$q=xN&GPNwezY3&y_Lc%F78nnp~Nu;2RF0Ek9Eh+D?s z{kQWc*(%J3m>7kOWWz294Tsj0R@e{gB`83?Ix*i<4Ji zRMDu7dwq23h-h72P%Ajl+@@&}!! z5;P4HhKFwvWUMykSwR*_a{B~ELa(KzpO)r*62mb`*{AK5mR@kSm4`vz(|dlDULmo~ zZRwsFhDw5$(j73P3T9Xn`xcITNrA~i?%sYrUx zq~DHs$t9K43LD!oDQ zRC?j>mR*ID9D|pK=|z9fb{|;ofy1F0#bD0_PO{uP_dlbA%zsbCU_c{QKckeUb?@$$ zR5wVSJB9xDo<^LE9ws@Xd}_r-%P80Qbz??_u>Zb}9mB&;p>>Q{>%N{(?!$sZKNb6G zeuD^xIcEIzDrL#RkPO7}&@7FCwu=Ub>P9k3THbsRyFZwr>ArXdM9MzJ&55gBCn)3m`&okH!%-pzV4 zo_lluh2@i{ET#8xpTrsE+m~HEQhW30BtdUyL-I3lNHW<`+#`Pzj$h_sGJld1!Q{wJ zo-?8*^(!?s-;rB1XH+lXS9%H4Q+|V-u}5uU;$$a0^fo!;vF=`3cQY;Y&0dS0l(>!J z&L%b9p9xPX%bZmv=Zu%;Q~t?1k}EAw<&MlnvUQE3FPU807`GW{9{hY0yoMJABC#UQ)}&3dCc;a z{hQi;H~18|Ti+h#E}oD^*}zua?NZcca8l<@sn%lFJb9m|&GD`Bn1A+R&6elC>NGVJ zczQm|`?7j|{*L~Shj&We%62rg?QN-(@0(7wT-!gLJ!$4aoaQU1ZGooMFOLFo%KG68 z_q%5P9xhLhg6lO=zzQO)&zC;|C^di29&E5k%+};|f6mOkx zfA1bbC05UmIJEkD^Fgxo7`fre;atbIR5Zx+g838{$fVX={XV%yo0t}Svn#1MIB99+ z$C$+=*k{`DE(-Un>T&1rK*?pGs)9eW<@mgDmi|JkzN2KQ!okqjFMh|~C(Sx?Ki!X{ zW>%9uT89;GKYLeQubvbJelVar2>s~)?XQ=+JV5an>lM15`WI>#j(;+oxrjINHONw< zn@H{Tsw0uAeomfc%zfll9xAeKDSCr9!qDGMMKAZB^id>B z1K3)gIqSuIoBC*|Q8W6?iQ$v<-{!c^xG2_oV36f}-P1!NRNT^`qOg z3C8NaUC=Rr0^8)BD2NZoV?M@XhvRd5a4CTuZF~c~Ta8rn25DhI zdfq?-I9T_QH`p8twmt^i!3myv6S!gtJdX){;1GXrNH7-i@)!~UCyX*ouC^oO)h!m9 zCM4J0$$<6#>iv^z*ewPp-v7Z=ecU&(PRuOC2Kc{$B?MrYAQAZg1(qbL%gTmRn8hzo z1MhZ2(s?Pm`QM)a#+V63|6c!5-yF}A6G>Vb^{r~krSqm@kdedDl3o7IeBH%y)mZ zG8HK)Mz7nB?S1-~M3CkEXrs#ehs-*Ky6>B}$Fs%VzfQb=yZf=2Rh?OQ)@Ch1`caz4 zrPxkS5l>YAffl2b+h^XmD{%%{Kh`&<#NTa~om-$0&Z2>LrGSQu*y%jzvRm65|GE!v z-BVncC(n;af5+eM3jTTXKv|f^cSDsAzEK`eB7ROv-}U$U;`GP2k3BuNx9RkMQWIWjC|(_ADY#8OrrnL z^F{OB^+fMcO^0V2`)U~fS0^YFyZjrRfx!>|*{|v+WR;B1^5+9L(+$=6w=+ykUALX^ zLrfS@H0uPPkk9CF>1Z1sLiQ}OHYrThKiljQ4@TmkZB;wK@QgR)VjW*o&c15(xuwD| zhnYwwO<9sJ&$4xC)^_$|N0Z;L6CWHgKQ%KDPm~{x4uD;Azd% zyehrht*1G5=V+%aD9hQ9?z?XDN+iv%EhodbLzhMrY9pg=1-el_RZtX@;flrIlJ}UR@{9iMG>=)D&Ma@%`qTvrl(RP25dy z1xB3SP}aD@&_h<+$H+cY4@5ql`vh!wO#jkngd>c)VU(G{uQVfEYFNzAu9r!CF8BBC zYw_OAZ9Ys#Fa`Q8>Cf6n!<}&m#I%@4>HQY_%j8^%Z`sa`mpl1?G_X*PxYg1b64TupDeBS)rQGa@>d?!bP4;- zn1%-LW=(RR@Ouv-!x_m@@r_`DwsEI`y9$l@u$lV;^)<(QAe|h-u!z77)!LycP`U_Rm;> zaran(#uIcD(?>Q2p;$&QpKuQ*B&-o0s{jQ+VatX=kp0MF>gLQVy&;Q7GhaDwhbodD zllp{8ebJ#zSyJF47J1=digbm=oiF zr8~ohamcSoGm%iWNX{PAt&&|Fof3T6h%7DBWCAx+IxMC0x;YX8`T}mTz^R9J`*MW) z1XpRYxsxKnU7OB|v>z0&D41lY`z8C4@z&IlveflHKFW-8R1E;a6ZWQM=GF@FrH6I--QxZOq>Hc&<%L3fhjH4!J_m;Adqd$Qi? zf$xK$tB34@h;Q2X-(gaXhq_OI!dZl47P36Y#hF@rqwrHi+O5_!=X6lNa8NL@v0ooq z#L@s?FE){Df|F?AC!fJ*qt`}sQ58~W>5?z@`+<%e?U8#A{dNNY11tD1bQ*AQ*($%(NI;u^Q{>}AK}kmSkIx*K3b} zHB2k}q||{u<<}V&7&Iskj9%;idmbd5G>5GB`C31ey9Eb{()h7SfLd#u`QtuH= zx#yO_WQ|3UIGaIh9dTp}%Q4I=cMb{9uz>Y3@!RYdPBcA196Wr4uTp|1ZbL$1@eU_> z2U6EO_#8whZUzLmjMhvKIQy1+)uNbxzv~v7VpVV-aZs3Whw^5!jT0hbzHF-eOb1EsBIsbs4tCR8cH0kPe_O5MhbHyW+I}5w3Kt7$Q*E&jlT;=M(t8s)7K}9H!W*%&aR_`r5QHyN4^HNiSXnPcix|AV zzY4^vuzgzv#q&PdI>c{9uW$PX-)E2Is<&f?+!`L?Nkx#rA~%V&V5)2#ORu{Ww%Lx{ z+tkJMU=qiH)=lJ91z{TMDM)r$A-gNsi$b+-xcG1&oeCNv=?H~Qzb&~GTekxzWE*OD9 z5IgAK(RLV_L3C=Oo@3;ee|veS95gFP+?#WiVc-MKHp($VC2g^oK;UgE>HXL{B$7hOTArX&WYz5(;q6E8hOeBr?A|SNhok!6#WJ~6)>@w5u)OYj zZBtiqCU4@Y-{=q42L}DH_+$6vo%?MdMWMY%(K^@qyKvH_aBV7wOKJ+AKv)*cb5<$> z6k%cVFz{QZ*Lr{fXJ23#Bq-uOgxDyEPdca&%f@F1dWIzY(ML26M_ps7Mlqx*SwxX+ z!Re4NExX`h9}3}59AE^Y6+3M0IWuUT06&7HN<#OW#y#I?>fiH1klvSn1|MB+htnaP zH#NfYqQjK$xoP%=;h&HR^TOT~`yCzYLZ)pJ$o+scAt7X3;eC zb0f%S02zM>HA49PBp&V|Ixi`@~0O#b;sTX-^`b zt;J(qP;W1SS_#F2G7?;G(_z-@hO%o3pP%2KM%+c2_@uNrS;b*yd`X|oQjLQEHiXfC zUneb(D6H(k+S$l`U2H$IJzj?CdGf)$`Cv`zF&B?rT}tdaGPxMJQcwsC>V!m>jVJ(4 zcezCTuigDD2mq)_7WZuO(TRksvffYf3h`={$;ozQ5GFJ~iS$2HB^*GSHJRnEMSMmLbi zbWMQfHYA}ONfylp^D0&{uqC&KlSibLc4A5&o!$vnh&`j2L1rm$SE!pWF7t|gTcmxB|rinp#h3lhP;HIoeBCg-~ z43Yb_v$74kaoJ9wqBF-zcXR_a2aOA+{0iT*Vhrb(~uT zUU#>3RzwfR!wGXyvI&*JxeR#1x=q#iv(>cAE_qzg4LIS)`>@=M=d54?EpIZ{aN%29 z!aQOkK4PMB0bLcXyjCrG4RhE^AVK|d?Hn-!miRUDeqCglDp6DNK@e@wNL}1To$oD? z=*Km(Ni69IoV1KhCcwMmFI|e6HfAC>bMt-0_CAXD%UwrBz=2HQ6&01X4o@Pzp}U1( zT5$Z$rw8FNu>JV7AK$@uHM>rsZROLJscT>lMuKNpuruI4`jIc=n*fqGU>~sPG?5EE zMfg>G=|1_*80w!kuWo7{ks6j(wkGzh+7=A`-iyvtCHz$kzBW{b6hj@cL|*~{@zYHI z;As4Hrnz-5Kc760vOEblSKaHD4|w@@e6NM%SoFDAT;R^A?PRswSWO1|y>Qa&aA*&f z{1c$-6h``?mt|R|;zLM@(=cfY>tfLDV2fave*Eo4s z;);S=WRMs|)yTn8Db(&nwKWvs#@gMRt*qt!l!Y6103ax{74E(7^rcD+NuL2hc8J<{ zXr|V3d=Z*l>R9-~$R7%5mhCigjnRABOJ|4avBiKdaXrT*QETKqKS<9FMZbpMEjB?t z#bBW|;EQ(5q&D5mctys2oJH5*cgF@lUTQF+d-V&vqcj58RQYGCGCd~}0;t;W?9Te! zjgQyk6bd;K?132e+{1%FW*}Uso~!X5XC&B<1Pqt}VK%D@Z=d&G3RIVkzNxCM#UPs} zf@sTn+aUnrIhaBun~eCGRg@uNL$NlOiIp&#$?^Op#;KooqG^DTlT??2-5s{_xH%3t z_|FKJ$J42pTc?H1Pg0>9GDQ9TOch0AuJwG-ObFM$GBMR9(-`?+S-`LzkH@8@&NPqh z>vzf&SJ_<)nE&@8@BBzZWSc#P*C}Bt%y!t%gRpAaGT5U>V|}=GfB0qZaBz4Z1OU0C zn{F^k3T3R#B zV1YZ_lyqKeeYP~Oe~$grj4Z8)2MpR3C8sd|j~yrrkGiib-D=7bK12K0Sxq5AE&U;# z{!9Ixn$L}Ymuof#9ee{952!4xVQX@Rza1NGUPfl+#Cs7BKYh7?-#4`<5A%Bg@bqju zd_kNFCk&~lI8THHBrSs0Np5-1)Yx4X$I8%avYkE3kd-?){ENr-G>;^21m8!+c?Ff!Gxx79wx5)j-=t zTEyzhgW=2k4PYwSQ7^fV9>t55)hF1VHRd;oT`c0UrB!g!yx!^c(xrnB^hc}0W$v|Z zeNvffqro_pE9P}0V;mwhhV&oj`50Aof!eg(&PXOL#s0R}znyENdB&hX?o{=!b?aSX zhF?jGyM>E=i@U2dH=GNm24A*~B=zmzu55S|OnI(u+_`5}7(y|xML%YWGpmoYvycUA zSneIxh9P@U2z$*!@l|1DJt>%fnJB!jwOuV1LmVWL@iCl6o%L$+4yn28^yZ^R@yrt z?Fm+f#dj|_lWg80alhp@Gp6=arx#1TEHm`?FXg}Emk@m>JMyB~T4g5i4jqZmqv#^! zfopw@w9I{EM)RwJHV@EbvQCg#EPqYwTWfeiavQX^saa-7DD;w}sS!5yX{i6z*8rC}^DLVtVBJCw5;ry>orJvDLiL{CnP*r|veSA823PJ?%Qq%mJ zBtc9??Ed_g-1p1laC>S20wD2U*}JUYgLjj}O+yY8j~*70$rrAE_TI-w966*Rcu()a_1@yEAnnG zLm#$qrKjeX>px9%my}ME zz5!99)*Qri$0PS||5+O|nV;lUP428wr;VE5LbCB1671t8SRV`|2>-(&8o^m zcCi~4f@o_LRP9i~u~ z=8>=PA=YvDrmpx$q~&A^klJpGa^}#MOJAM9E=f;KJ3T#B(F~{Zai%$Vw`9x1QiM{4 z^K;Z~Zs0)4P+?U&qr|Mop?9*3ie%h?jG5#6WQL!G`2N!x{+7Q0(nx`$J2w8*ft#HX6rV6mBN0`TC{rS54X+g8%QCG(*oKzfdII`GjE8^lOGYQ*AB^Pn|B%Sb(0v*RfumIT-Y7`1zmhcQ&tX!P2%7 z!=BAr-8V`e^#b&r#R0_33B?r?8jA6^1n2D{wK z)dov3WX2TA0Xn!1{_;IKvxwRvX11IEULu&ezd?KhofhTd$*kD~o5hXR=D7E+^X5G* zWr5QNNKvTL$Zg@F*j{~|oNf?T?BX8)_Hs9sMTics2wD3D^Ra$>@aKiE|2-w#Y8lex zdkslNQHr8h!#K`iaLJORZ9(sO?qS*OxqS`iKR1gdOTr^=>D)^R zxR$1)UK*~mABB$9hG8G3960gP@?_2=I;%P`%xj8# zTi@0)5-T*MH5F}^C*_**C3Wm_M7#>(2$?M_%vDUwt*FqV=nH=+uptqv@V8W=Zx6_6 z+{a@?D(rUP`>ps&Bk2c|TUfdDZ;^k#O#lV_GS;gaLJTGN>` zh*U5;`v^8?m$+_hj7ORs!jr#Fje)80UZuwY&7z3^?vqm$*9|Wch zM$#>M+dLL45n>}iSQ-a2aamBlSJL%T)so+3*w$)PlcwNIFk9sHV^<3c6R}Q^4ky}> zp{$r=Pq0}p4XM`3d>dz^rj_HY$}MXYZ#q}X;mY|0nu+ZpO|g60w5bAkTQPiq(7ogK zhwy7E7gh`;v1~~bY%;ON*+MjZwgY%!KDjA~ep(1NN;onCdKU zPE=TqF%XQrzw2UZ)Ldd4l@2po#N_+CSk!w;)kKiT6hAq2SkCL$$bJ%!Y+T*!kXi|0 z0@d_|<>NGjzS3M@K5%=qZGpZqfFre7yUWG?p~*+!o;{}+TmP+w=ASsTgSSP+Ukvq~ zKr~n`6G0MY9hJZ9ui2DLnyS=1-5zyXus`(^eOXhcq4tX)IlwPDKGiI%+t2txnraB+ z+b6~-9R~T-qtMu5g1c*75{+6{nyjTkBaM>;f`9!o%x_t)4#Q)=g+J%DXO1&D?HzB> zgL7fMi|(*_s)j)_lSiRPcxw>kyS<3|YU(&&J}{+q+k8)0HjuH)R_bFLlrMmJP^@3Z zqWkLi8$|zT8=Vm-phMg$_Niy|CrT3DA!Pzs7$GS>gCUhXsHkb$nVPYaus722ZHX}4 zMK1Ks4Do0S!;nw1f0qMG`atWm3}a?6m4*z*5ofA-A%g1`H|&(L^{#-3?AZ+x-xdVG(n-u^XXbaFx;7vjib3NEpqYZs0?R=q&l?Y^qy$B<}0&ElaH85=eEoEyRt zR%_=7RtwkAZm*$xAJSB_-_=qbJmXm2j8SFdpz!>wS@A91RkU2G5gZm9@rm|yp%uFH z*IfMxy}X+-39V{W5>s@Rf*%G>tD=nPs3%XLp1-sZlsPiM?x}1EL%$3S@q{e2cKbJ0 zjkL;!Q##Y|e8Ei9maAuyYW?1m_qa#F^<}5+w=wGLmg)`rS3>o#o)nVKY(V-c?>X6< zWYT9hK-&A(Y65%IiH~kLjzVYueAH)m4*!JSV54~B#_{tcCLG^zU1=Qm?H>QC-+TlE zx%+ofsB5!-{%KsdNE!PH)P!k`wKcGq{l@lJdd%%~&(ZOmh#@r59#BUASQ991g-EW? z#^vSP;&V2x$9p(NF&6+dAaRI9yOl_VZ_fQyWl|PKe`wVANm1>pX`o`8pm}R&|Jm15 zRN+zq|3vf)9ynV4uJ`Uo{Ay*W-UQX;A$}K=zOt>fmm?-d^$_^=LeRY>7YIJ0<|a;- zT9SC76UwyNhS(a?ch`jNRQRG8xy2>=EzFw~!jz@(sKB6j0D{&KkH%n>dQyjKv0Z5a zN&V`sl~nFS1Y>#R+dd4SKPDFa5}?Q`LGr__U8#>1{GCkiLVBJg`tDmN`~x_o68#8C zpxu|#rGr*A1PPK7Si&l7v5mWgU^kfJt?@<7#wNtptkE6`){X<&hDRv^z_0kCRrv@i zDHS!BV!m0%!Ac2KkAZ5%1Zu~MJlPPQrI>%|z{hMLp7uzOJ^U^ifKT!J+_#k;_;Ci7 za3eWP)>5W;(7p4#{Nm6a!Z|opF5CdiQ5YK)bBrCaA1s6O{S_y%kpa+yUe~yG)J;<; z$1>QD-z&F8K6V^(@*5)XXse2qipeR%WUC9fvh-?-tz02Jsgy)7Vpp++B6Xc9X30ga z8JA)ipI~v{IdX$q%|5kec@sYoN@$Qq+M0~xtBzM`_BvW28#2b< zmya`DciaV(iZG-@@Mw4WLJts?dnek9l!$_al5 z_9#>$+KLan6OO*M(L_tg1JtevrOK#%*4m#WFxC=9-H}kc0Em3KSi8A`jZ2kcF@d^q zu00%7$pL;fGKxflwr^ryvw_cYQSAcSY9sL$C4z=$M4j>I*Gu4E?(lM~wxDrOhm~-d zCFl)TYXxAMl5rf(H{L}`Y-6NjYcgHHH{{SITYvhIxOJLDp^PXot%;;2X02=qe?tCO zZ^DUsJEsyRNF$R&V>JJ*J)B`{uSlj&_X%aic-O=LQ_|@5yEs(w)D1W00*?!3%#}^v z`aV*8DH0I`6eWaP{_5%;rG6Exb+#NM;9v9-8Esn~{c}XlSsLKnJKK*NwI!VTp&ex` zt-p&z-v$Pe?@(tnD1k#`K|UkY>djLr;b24WEU zwrxdp0wTa;j1h<9>;EV%w3UzwLK*emX+>3fOCR41On(xS9mB82(~G?tueW+Z^aRCx z;b!=XPzr640(>!!D4jMOoVS{v4~tVrH#K~?AyoV|Z&N`BeZc~g2jI|=D4daETzegR z27xkJ@hI1}rocgD(x+b3-B^_JSxF_fcuF-T6=uu_o8_n=I&Y7(QJzIeD{r@R7f4Tb z1SNx(>0f0-`W)^DcxSw%6L3aC{;)^c(oOAZMk%}S7RZJ-FN4eBnW$>*{ zJ5U9q^2#tbjR_sxZk8n<9^e)eurVNSEn)&k2k)Vj6v6`tRkrix)o2t$&4}`?h%&!O zXipNU1BX99AIq1E8fAxdhhVJ>c+KR)`L3!gJnns}QM+~@ys>1q3njdDpZ?1jPxu?+ z*fReKvHS-71q)8=B*j1m<2=sz?3hhm$A`E&(eTkW7M;ej6a?K@p zI7rF)INHtjz8T%rnh9vvu>8kWRC6wq8y`dl&8W1GQYt36Q_%D%Vmw@`ZtcCbLcO7e zd)B+fpUwd>n+gD1ml(5nkpD>ZtnSxW;vh3@j3OFjY)1Y1S`^P$M!R7y**s37mxwU} zln<1=;mR+iv0OdLpL$omICSk{fH^ z0yf|SHj5v73S+>=YzOlo|=R%iz5YpnbDjt;rgn`3UQ1I3EOI8_hw( zy-`xw1ytAq6Vefp7*fY2Qt-`TkXVMY6$&3d4=)H}2dWFl!x=_^gglVM$4MlKKV~BxC z^{jF|S6}9$1Dx8cu-wcA;w`R=F&x9~L4{%14geZMMl*yp0SQGwgh)sPRA8D~0_S-( ztFyR+um*{74#RTpUMAgwtPrHM_N>Xl;%w@)9r1^uwyX5TXLG9PAYm-W8VMON0Ru$? zQoXE)aI95(kpzWn^-$=L;Ne78k45I%uD!~91}jS;RMS%hGxjQAs=$j=I8*a=cp_2vY>*@eFNnV z=ep3PJnJv+9E5COl!pM`?$~X(`RwlKH38XeG5-f~5C{KYa1P)V2Sb1Z;uVMJ^iG7s zrAP<`leN6p3-7V!z4A71oMr2oGXxE)+5q`q#@JMGA{++;RS7?fSIh5`_-j8t02Wi# zqc|AV>5q|EatJNtQHWK?-U#8?Cr;F`@NNm;*wngT9*fI;i$*r}k{O zc5TOYYgd+JFd9rBz&FTcCcgrswxzfr8`yn_{<0tE00!~!Jd|_}eh^5isTx7C4WoHc zqY>WaeN8mK@;-QnmOOxB7z8-bI4liMw+Ct9> z_(t?nobOW~iUK7Hq{X%QgOT_`aBwBtQ41XrbqAkplE?X+S1rueYzw5eDe>%A zC%Xs!zlcegkgoOL3M9nDF2tm&7SAql`}K7c+@>F-+P+LLzyZ$igkFP;Wq0FZS%x{d zf*&v&e`bq1`1b7(_fDup_BM;;j@PtcG?8ofwsN$I*TX*z)Re{3o#FS}c+q`FFQpj- zV4wzY?Sp;jgWX+TLqK>#7zgbv2J|`rRNx2aV277{ZRkX_)uZ^E5bK91Z}KkZOAGX~ zIY8(e3%h~_wkJh8b{C!BiKHuvPxy#j6Y&3}IOrScg#L{>k=S(MKk%7f@BnFW1tfLa zXa44&C<=czlAx`_$mEXBz-a@C+`1#9hc8;6gN?DXswZ}LG+Z1dj(3>)^?H+VMA4JZ zdK}pL&FK0A`1-__rjRasDtLh>s0+0Rh)l`+`Qt}$87EGJm@sU}@BqY!5+_ouIPprD zH&EvE>FDvJ#gHN;`hf%q(VYW^OrA`60A#z4#i)rxB@vW3aR>PQ^RBa$dV^hu59@-=FFO7coRWRBLgopi0}u@uyH*DlPc7(hXUgDecn8%N=XzZUck>f92IzZ5$CsaoL_;DNY zP9A>zhX;QJ3V25(K`F=&HIWz|FXedOgHJ9UwzinEPX~f;SE3du!`YW)(3Og*Z#bU-CvThI*UvlkP zWS(;DkvGvB|NK**Mbb(u3M>%$1Pd&Y@JC^W5@I;v0U5$V&4LZ?M-oYYrpsT3^j_%4 zh97?DiG3r=_Qo>*q0?E(M5h{F>SG71eXwYYm_V9koI&&n z5tmMc_CWr~N?Bl?9F$N*uR3I#bF}tm>#w=4y*T5IJN`K2kxLFavfO1NVzbj$lwP## zRdk89*jA)1ds~ooM^~_r4Q03#3Rt1M^+rO?K0di?*MTD4!C!!|_m{7}9){?TzYPJ5 z;v84B7@1z4(qlYMpyJ`@x>u!j7Y{5Rh1?+M2n*(I0qCHO3UIDV-H#OP%{r% z*@$D0oQBu~jyV5CXT#4{sMsUU$fTk(SZFC5@6ggbvhj~>6hj=~2;Tvz0WMg`VuBSk z%GCJ8mXy4T4UnJ^*dpS!5ZZcGO>wHd?K(aw;k`mM?J-H*5^cb9BF;dT2_<@>Bh5# zil7c$tCJvB?3Jzw@uy7hxE=1?BCh~J2t((x5Ql;%JP{eecs}%m@?5mU<`Kj-35njr zsP_hnVGn8%VF^nrg1r}+F;YMI2Sof45lGdpC!J)OX8JUtK|uu^p(2quryLnt*Yh+ku6aSZ31Bbug`&U_{`qbbd4 zK2D0-QIEJ$Q$~&8-jG=3NH|3EeW}>8%b|^5R(`qvDc>!dT%VZGGjq_B9R3xC~A(J zOx3WKBbImpR=^zG+FV(qNu5oWH>9Q#b>S&ciRu8Pq6pp+wHzj}21>7)%`qJs9AzRd zaV)G%cAAq^m@>7gPJJp=du7e+T#k6r3dtL^xJA!V>pfZpV;HHB7SxfItOSJ8PS6;M zaLNCRTo)qOJteZceA0_Q8{%g_h2RVD_z`)_V`{=S;XH-`F-Od)-u3!0(L^A^4|{RL$w9Q~FgpY~CU^vMq$WD81T#n)6uPNgY~rAzG=Rkexc6RM3{YwL#79Hxdj z|KiP|62b&R?5#wG)l80jIILz`Mmv95>SU0++T}90xz2sANTy1~ab^yyUk#47C<3}` zWy_pn97$Qj>mQ%&!#-$)P+Zehkw5tkKz4<~0rJ|RW+aLs$4e0t5W3nr2tr{sVrUSV z!-kSTa(jqCgdQ5XS?9nZBxk)WW;J0Hk!iv|5mB&5STctknbIUsAmIpM)xt(CgKYnk z%0x?D3SC~^5+XCS%pz>~+5?zMhrLyfP!C|OzgZ-alnE|DhI>@X7}qaFmW*;&tmGv# zxyeeLYIl~^x$=+`I9$}O7rPtA?}AsnW!&U~G+B`I;?8vzf{=UrW1tN|M80#_>o|Gp z!wt*8$%OpxAsady<8-*deue~N5rK!TVE8#1qzFb8M6`;mwZe@)QX^UNVcn2)&mk5u z6U9cD6Q@{~PM%JSX{<|#@KPdZLsj8qbDR4BbH_g0@n%I4ewI=k#;mq1w224VkD>nsdc z-?6#Pd7Z(6; z01FN{P+-Fx{D5z`N2K3%x4UJghIivseVzPZiK`I=OYDNlwVJC1)ryG?q)eX0U0kuL z)=SA)+q?~EL?8rS-~oJsXfziEYZATIOT9Q>x49+0%^`H;_U^EGzReh61c+)l+9YkywIbHwT4sh96J)Z$()PiIK zBH*7~sh8E+4!Gb8e05)54UaJxL->tfS`(tToPT-iia+wysrWNe!|LD=+JAsLw!0lfp1_`(73i@EjF@Z3ix zV1^loKA#x}fZt zp&9BL8OR`U+@KAbp>{mMIk2Rzk)%Xq2T9f(8T>;bkY7pqB2V_DPi~43YLjtfS2tyo zFd|>lEn^rp-4livm`!07Hlvq)mo_znCwKxkvf3~pM>xJ5`h8m34PG&|A8@!Gfvw}d z1=>5pV|1Ls3$R2(aKZrUqm3vEAt=g3l%ifjo;3L*EKy$Nt=2*gqz%bbKHOA73S>jd z7-&4AO;I4){F04O2O$z;$(0^vm>yx}Wy^hJW9a`%NY0fN z1328m6X<{z+=4YggEhb=7#PDo3_~Wkz!SJaZC=AIXhF?&!7y0EHCO{69Dpm%;1j5V zX`*Hq{3LZ&r*$fa5E|clkWN?W)Da?I=qTmVQHE1Sgq0`=%SfX|Y+Lh{6Saw%Rbpj_ zgh+3Q-*bc`8m6JUHBUJf*2-Z^P=SMH~b2-ZT4C0V}V91NI%=9}Chf`J}raG(-{_SvNI)_WA- zAa0Io@Rp)rsH`!UY5iq~ex(u-LLsnI64*gDKt?*)jXEU3BDe!R)B_vU9RCf$cIW=0RChJSV-Dh>zC z_1ZOTf_7*@dAWf-C~S6&f;|+$Fu-VbJV9(Staj7^A*kdn41)`RC>a(3BP0PG%tKCE z!#6^N7Rf;cHeqF;PDQ8=KX7WNhL;z7YDAb5 zeH7rz@`|cXBC86-t185?{%2;yg*vWdUD#o+*4<^0(t?@L@J6Fn~e3E=Izh%{U~%KP-k8j6ysR zsXS;wA@Jrk;6f%q1Ak>hq|E;VF{na$@#|3WtB3^*l+KDqHVnlPODaajJfLb3w1XS$ zpsr+sJv@OHfWtoA0wCxL8I%`96hY>e!#wQf0Wg9;Xn_kz#11COKG*~FLhp3SEcI3| zPeR#u3?X(gA^4SCq;?g2h$rbV<)seoJ{axMmert$ue3ZWst!w6t}3$K+4CS0KW4`J z$ziSj*{$ZmS~k*OC}`P|t%IV}!|9Fcg+$}|1i?lG;SJsaJn#emYve5+qEH-SpjflI z&_2Mci$MbzxR@ZM!#CVRK6LP6u)_g-V-l!B9RP0<0BHy(0SNQMV%R}AMD79b0udB~ zDkOm${4g%;L!>MNA+-MkL)b&w0#|5>?g2m#MH)}z6<{*3?(6-9J-n|vxWP^4Bt$U6 zK0JX7P_8Qc=yEb_MASky6ha+%$5z^I2s5t?9)LY$LL2}>9RPwLh_Utdu^<1QqEc{V z{A~A@T+UX;&K_NO`s}qaoqC1@rc%VzS;q5u0f|uRwRP|NE>8SPZTgX8A+_QCRz?#< zME>qC|MJ^``5V|$M8b_NBzOT!6bd1p6kq;DLhxY&M}!ELh-ILZLy?d$FY&Lq(xzoF zV6M>P0PiT+0Sp{KHXu~_8sgFKvTl4!vuKm;z>!8=66HH<13lov8XSNf zECU!o14PubKo!8TvPH9*8X{PX=H zUKAHmZ*2ebKu4ft)WS8mh?Y+FO%6j!CIepILLumiDyTydRJ5*)1FRiDAtdPmFf3=+ zK{d~CH);s#OjY?d)HGX|}LU4~AxFMAv? zp+Zqm>nB*YYJVDa#I@b5ZY|dmD6am9Tgpa(HQd?m<1JeTYiu>ioi1(6w{Pjiq8LhF zJOpV0cq%!u<7_A*%5AS?!Z7SZG6X3&ECV>?Bs2)Z0Sv=8xI?=>fjry-I~WWuSc5f; z!fngLFuW_dCPRb+F*qbcHoSE`#DXhuf;AAaKM(^kssbm>br;lgl2~?zb^?>W3Lh3r z>;C^m7tF&or~)+DLr%KlFaT*bm_rB?!ahI)EkMIO^zH$uLpF#wE$nVG3_~HbLrxNc zJ*22TsKRT{u@L!`Dz6+bpNdA*ta16MIuvMFke*go8YCI!&c^ z&xcRL)OUNHvC%JK*)Kn9#zxE`*M5*4zOs%$!lb1V+FCVbVD(lLqtz}ce zpt7G)h+L$BM6f{<06WBqb#RC}tNAnA660*6x+KiPEZD(A`~u7Wg25cXD!_by8_X|A z!pp;a%|B7AC$lmKi%fM~LpH0nipD+cgArp2S^m_b`1(F86K4;*vrdK!Tzjab#kEJo z)l)>)yF1r+eGpDn_S!pTXbXL4Q@yV=OfNE^hZQCJyF`GCz+WnRCc4-WM8ZGU!h<)H zr5$0B_o|OXDMN(T8p2Z3AqdIFeRMT))b|eg#mKX5DN4dBFo71-{0rPRnjH<_wpoca}Y zh6YDcTY7<&1TDvc}eV!9TVTYVff}!U%FZC28L+tpE11<11Ao=#p#_p5+g^9VC0GtC0?Vls*>bIc$aBZB3C7hV5~F-9+ph=@hI-r&q1 z&ocSsk|K==1c{wseyQf4eS(?Jn_tke4#8FI z2uhM)W*KOeS?m~3OSRDJ=%bKE%A_Rw0DZ5%_hOOh6F~9P@3>`Rd*hRw0^zAV;SK<< zzyc3MFsvyVOcKI7K@C;ZQAsV;)Kfz{vMo12GOVtXDeiKKc%4TM9L{`1B%MMKw9QmqLwjmo@$;s z%AS4DRr4Pv*gQZeJAOG}74i(Km)f!NJdV%R{tQ&$Ky&|!#e|jcYw}t~-yq~6W*F)g zHK=~;^3rfi1Zzs{l>Btxk3kMuSS{<_WA6yyIbq6XgGFHZY z9LffkY$BmdXJj9;d0BskG1;tWr&ZcPYyE{yHg3O_$V!LG^~YsXeLJ8OPW)Le7=Pwb zu9|ABgYAGg?HDNE?iLD4U#GjuQ(UFk^K;<6SITLTgOf<~TG*CpxNC@VVn)&c4`;~Y z0t|8l2+NV_)Pj&)oUsSZf965Pn{}Ey zppah(kpvkz2&z|$UxK3d`S*(#3cXRv#XFh2Ny3kBLUXF){;->8xaaA_KZ`q!#42_% z*t||-l=DY}I+l{mA&-I;wBQ9Xh#{1*${(&W5vD_dMmUkiWvnqd_jBX&_Op+D(1RiQ@a8vl@d@YGV6cJrpa+yzk?vtN)+92sT2^hQt6f2&Tnd)rzN{r|X7Op`h?y`Xh zR<6)k3e8mxXW37P_)w!jT+QGZFGCt8dP26W1Qs_$_xJ(qBysuQ<>$Q2yhO0z}j?*o+z2fJyF(Ct!|a8 zU9HLnTSZW+pe}@D@g!mX@w(XgL}w3$XwW9wN@ID!qQU!-kZ8G8j(XLjO-f4hvi624 z)zXWEIgU~)qQETCjhRU-OCWN>gg}ThA43i5Wx+{Q${J)RgzU;oBT}462`Fn2j9@(@ zf>qVNg|Dr3?Q8RCNtL}SBdX(yVjf~b75PY4H-r)G+zPZD%~h0&2~uaenpN0JD2V$3 ziAV)R$&EY?A`1LRmQD(?n3mKZG&Rek4xl(D@ZbP1AnySt`zXw=*C2q*u2#kaI##~gAbgRB;-%k}Sn0c`)We;P%sW7TBL3Op50f^ufXRSYQ?`l|!LVjrj!ZcBW( zg&x6DGxBtnR+Ssz30Vt5b0&F zLD1=y=V^qQk{c~;fMdD)HZryPb;|+x8!Zt}naWjG5?DK!V5b~7W@Z&ktwPCL7V#>s zHLMInEF84q+R(v)Ia<<^D`hKNNO}H((uviXL5*Zhfyr_4Ah#Q;?ap+uW`PtBmP!%w z@?gj4^|3+3yQyE&loM8J7*danWTTk&v{v1yei?Fze&FK}r9OlUbO7a4_jk^%cJ-@2 zBU?<;Hdb2R@|R-x=ze2@~uUF?GW6lQfO@Eux4bL zSG~$P;TIw?FQd(^3sO5d@7~L`ix@F&N0-~}?5@kl0^agsMdzJ`$hYzg^kiDP~msK`Yl2~`n_+dOC9P{C$*^`S#qs!ed}2EponlCGlqXK?4Jzt#}#w&8bT!4 z!)B|_dX2+a>d^nI%jPO90dOWSjMMoKYR>advydMz`aXaMVdL zZ4(_+j?MH?s7h~7=QmoSmb$5}9{Q>G!y#8M_1#gQ`YOxXww+usXIc-KvOoOnMbj08 z*;=E0sJY|6iu63i=NJa2GKKfCFEEHh{2Ur0aK>vQJLxkV{#wGCqFaY&w z;cU$%SVZh*3+yD$AY_Jtcx@^&&LLodhI(&Deot5Mimymc0E_RVN=#~yZ?JMn#gGFe zD5BcXV$lD(D=l8&n-p)`Afg2gCEU0V^1$yYqUUfZZ~QW)0Jnl_>}%=jt?6zl>JGsK z9O48@qcltd{|?~*@ZljwkJSE;1Fi51D@fM9?sN|DlY}G)UuO0w4($>{?aWMA%FNev zghwjQxP;`xMh?`l5LEIGTcC^PCduzsthz2{83<3v%*gT{>zf9TV#-Y?&h6&_LY1uTLEvfv4HU(oP0xd(s+AuLZOaq6H6-CAPpsf@5j)zz-Iauss-VMcm zFp&Qa5AlGC8N}%m+)LYZF2)*>Uam-P;G|yMgozp=i{NA-M&TdU!5NU@QX0j`CWdNC z>k=g>6IV?%qK?$+uOdhTE>6G&ia_A>?-2UY7!fid_k{q%@J9~d3zK6O6^w)qs?Ay? z4Ka>J93nC>G9!y^!)%X5-V6>wtQZw?RG{W4_Ku8xh)c#VIlOC-j4Iu_O%Tswy}T)$ z#_4(dDElg6UIZc`*hdRy0V>wVAi@JY;${_`fgjcZ8K&VK<55D!2n^76$Ak~DrAh33{>9Zp4<-#pAg@QfVCt7Wu9*84xtJK^EZJLTFx>7 zM@U&9QWhJM%f=8FZ-y!!<1rp$0`t-rf3Yt^4lqqJI8Ox`dkKCJ6B4g0w_vU@A2a-b zBPP*8`_fCjEEA}Pin6?EClU<@1w;$(B_UQ}6@K9vM&ST{L5$=^3xa|WO5qnqbBS7W z$d;jUgm6%-N_0pg3iFNhLf|%6i{RQq|3HR_=)WF~bqU>xDp>a08*88Sz7{SNXJAm!e;;c@*&302Pwj! zYVV?c1oz|$B6g7%opY{0Qd?Oh18Fqtm~~{hvpBp{pBjc3h#_2ZYF_Czq>5t{dWn9X z3%>sFCq8p1a*PQYZ9VfL#{_hY+J*@Tff$+tfWpRApTQgOb$ke7spf_ZW+6h}=M5G# zB<4+2Vp9j)pb$_EE`|Z>ykQ84;Qeruzua%s4uK4$?jX~(W@|QD+yJ0fr^7CxPY<9( z^He!?tuN=&%whxXisoS%Qh_|~1u6eC)*x=x`~-wd*MnM6 z0u1!S4O}1_vH@`k0UA_62MS>y)}bG+fdz`77A65805kui(H%adl_pK9svuaIO zF!40v+^jE-^C+OTB~bK)`f^ZbgoPYxcQ{fPKXOrr@mve;bT>y*K@iWRQIZlf2(#l- z94knR_ae$uUWkJqsv(NJXI-8_ik!hY{J~0t!5R9~KD~4m20{{;2u}Kz65j`G&~IN* zVjN6j7<7OUNEQ$tw-81_2mAs4?4byTLDcLa>h_V;4xrSI#PfP{2=vV$fp>wm(^)~p z%aY}jN{DrP)K3qL!CG%c)i6dhjvo#{o3sgci7iHekvacIa%$0)fjMVgm9bqR$t7R1 z=(@{gm^WebcDjt%&qvr?Fdyz;!f^Bj(Gp}7*287f`oS^Su%qXM0pS7-46Mf zytzq(qNTXBI2dK8RPu(0jFCO~8Pz6MxKx<(Rh(N&R9q7~c9n2Vf)Pxj7M`FKNVXib zzy&hlWL3Ec=HURqVc)!g4wO*-U|KJ15`t1_=YnNd1Mni-=+F3#F-qcezwVUU8tnG*)N8u5Y?h@oDS!-H>!n0^)> zo#I`et!s z!5-GZ8nR#nq$MA9ARrGwAT9LYU^$CPm!|*qy6aRWX9)~~Bcf$~d87}-XUR3~nzoo- zD7bpjXfNZX=Psk78AeV(jW@-(vW*+SQWuS5#VjZ?TMxSo zU$mGjjIl@fGWv1{%++_L`M4#C#0ryAE7fFTN^m>XBDhwPr9z&)*`^o;y{*fzM<#vk zS!7-tE3>kIffdSLmI^J@b9);ufHh|4PjvBNx4HYkr>vtxdLnCWuotiaubW#vQb$(0 zu_v5_pVlCZGx)TdvJt$NY&wv&D-i#g`lvtqaTLgsrKgw5*}WB0yx(VtN2b2f^m9ec zAm$Hr4`KdN&A)%wEuIkmEH~9Y?>0aD$o&gvk0P~UH+7giTFZ{4iB`fL8(1ESr7s+h zP53BCG7dYWxRJc3uQo?ToNKD)@3sOxQ2aQi!lqbUr}~UYQDtMZCK+0redD9X;dInW zBSV38GB?ti*;^1?8!5g431iAnh zyg@=UK^3~7EuKIXHo-yx!4>~VR$4Ye6#^O%G}l7+8y^Br2ee>hwP4gq{o9L2!5@9O z9UROWY<4YOBeUTh9E#IB-7$O%qmr$|MIGF`D#XiNLt={1%0kV@PNSl_)=g$5QZosX z;n>~c9H4F<4nYg7LDVMq8W=$b*Z~Z5V1K({9^w}lia-^b7#zAF3EH6udY!+eC4p7V z6%Jq&?%dv8o`RG-%f>yo7W~%!)VZPd!QNP|>N41F$KBuk4j`LF^w_m->E&DNvQNEv z6SOAVSpeyLJzCz@O#&QD0u0!}Ewo@5;BTRap$kOK9}dAD+5!x2fe|tR)v}=ou0a%^ zKpl!88QOvo=->dnp&$Qxffne%6^23K(V-j)fi$k62u7h0pdlN&0O=L~BA!elx?mkt zJ`*S632p%zh9kK@`YoUQB5=zg(5j@zjLL}_B7VLqU^I_8Jk-5?@$<>MCzW_n9r_$+ zUjdMhEaje^<|Ot(_uYaFdIA3W!5hv2_=o?K+rn|XT?cN#4d%f@)!_+fVXg(C7sk3D zhJgjNU>~6F9}Zy%c;*Q#XB1T70LZ}dS^xamZz8k+9HL+HC4%zJA2iJPfdTt1nLElS zooK^VX$|6M03y&Yu6zOtJt-m5g)*UDW=)kBtMV@5SiaE39&73=X{tP;F$&7BU(K2ZA;geg?Jez#& z#-gz|Q6nOJL%X&_gO~pOyOeRF@GUJBA{5Ayp>l^0g-I0xJUhGcFWVA*~uuE=7GF24Abb)yvo z4lQofk_|M4>_w6mwOo_UE&8Fz+7qf=V@)PcWF=!snaGxvZ3kTfoNiJQ)Z1^tITsOe z$vuSJO3E>`g%Qnh`37_s!MI|R*s%#`oN~@dQ+Ubj)RTFfphq8jQTcfQQ*;h`P@nTz zCLS7y;?+$N} zcVe)gxoL313NM^pczF5*l%Yc%1*m%rvncVQJNbjv#T(iW`;nCuF;qnwzc$4);Db<`}qc0g)6 zxX{Hq;{dXk7Rg+rgV)z+LDCb$SX0?8`%vma5w2uI#+%iND_guyp<7Uz>OzG#L2vjr z+nHQaQ7^y8q0+~`DfR2G;LZ(fQNdC>h4AE-UygZ3c9Q3ho_tCi6QF`-9$Lof+2{Y8 zMMIMQ)mN#pyw(W^9>Ul_EG#*~5LJwDNbiRXbfC`%vM|sSWyK{o>B=w9Jg_rX{hAi* zT*G4#qwMnpAmC&I7)gxSL&j?D)P6u6{}ggmlO#Rqk16K)5APxx|LLHC+{KQpG;SjHxPmtoXb!1TE~^wttBo8dQVU!)=x!AJ!|22zMY+#waK0N^SHl1E#VqK}9~#xEq;kqc%} zUi0Fh2cH;{5MpwZoK%s+cv7C9!0;oY^T$70*vXc_a4K)$#4h)x zwa~63Lj+6^jTn~|*ix5EOr1e5c3!kNea;pFS4c}ZdeER zXrjK@w9jrd3D^NHp(gUkaVC8m$h-bQ&NGzl)qGvY2c3)|RU?0K)j+B&lFgtEDU9Yt`1HEsbt z>-A+d`_KYG2(b^zy(FCE8f!V{MH{iI^KNe(NS3^+Sm#W1ApHMZ$Q~7_5L=|8ueNC5 zBlVh!UqnI?->qvw96HyGT<~8M<&v5jE7ZrzcE9}9TuvU=IZ>{%J)@IsXNU4x^5jPl zoP22#O5%bQ6r>-t8={PaWs()RHVd;WW`92n;xD9Z-FlxhS~ zqWb=9k|MB{hh_0_n-7g>*9@y_rJ=EeH$QD^AOxk&Xce?rj`a4Kl$E44O_8}OBsKqdxVGB{*VGxAuMJf2| z&_R6pkzf|Ht;vjJ;XuwG$}Opy6OHW;Q#McMp$}8klgv8HkcK^ps_`g#G!kvhBJ_XjB5C!7_guQD#UvLhwAkX4h6GeJA)aCEy$b7?vfsl^SP=v2&*3s@pk_0AK1fnNC zc!#X@9T^OB^|2pd1u`Apl>Qr+NpxIdWPhQs&9qlfAzP1~M3N z2Uw8D8Qz$OJ-mT(>f2)<>o_?h`=E$m1f%)*RDMG$PwUHHlBk>4z59i_Ig9v4Po4PO zfuUCC`lxiJQAa%v&7Mnx##*dbL{vi(1(E-CWpN0p^?nWLfZf4dXv9uvf=&lPalPkz z)fH>TXLl2kd^i_COr{*FqALDi53IHiu+U_E@MZGVFNsxO&S6QB)qW3XgBlec(^7PB zR)6`&1ajho^D%CCCR;Cc5D6%N0?2xC;XA6g0)wVR@^*t$NQGr&9bKhy76)Baa)C7= zckh&i>Bl70wG`mE06`glZ2IcJgpaixFm&r$cde3Q%&Mp5Xz{K z^kEc6d>5FQIR&In4R3eHR_>TLy10M)cXlRf3 zxHvhNixM$ynWuUG=#e*>N_HZQ67ASkOt{WM3`t1nGz^*0&O#U7O9OH**j#A z1u%e0@Dh{ArxJ`432aD<*$^iA*e~)3T|GyGdq|aUc}zMP zh&}m}$tXiI^b@X>QYl3qJ>hiZF)jTEk+f73x6?M(Xc%y*nC=&W6-Qkoi5YSSIAO?f za~MgCLk;^-mS>5U%K?vzWf8+blQr3ki)os1DF~S`EdZ8M-By<|6qK#>6MMOTpyYJE z@eeG;QmUB=g5ZpGAeh-US~TH9n|PYX*=8WAl@^DNC0Si3xsURAnf#N6ZfKVLGA1zC zilEs+n`M*837(wfjH-Djf%p?WXgYUE2zg1Hoa2|}mYcfCo15U9zR8Ef8J_tGkX9*y zSUDxj856Juop+d$$-)0W!Pkb=z?mUIW_B2Z8x)$}>6ZFQp*b0hJ4lS3FbcF;oA2ox zy1AP6l+Nk}K*G?g%)asa;*lpmkIbZ|D+|G^6r^U;a3x zaEhpj%0zCesEyi5hdK~wfCjn{3yY8h1rbiF@rtIgAHlbR2^%B%UX2(f?$c5#JM>YsUIr<_`3vZklQ z@e*ce5U{YIUiyNo%BpNBq)wRtx(f$pKt)ZO0K+0sg_C-S6QrnbF83R zU0oTH59)z|>Zb&eFJnrk*}1F}5muu~n%MfS0V}X<(yaq)u)dP3x^NKX%CPlN5BKn? zahH{m`J8#WrF`0_^?Cqsh_BPB94aY>5Zav*Y8}RTuqTVMn^CYS%d#*Mt{HKzy1=mH zstcd+2`})N|LL6YGobPs5o=YW^%@DNnyO^7uXs4JlBHiQ%d|}k6)WqsQ44{8rmMZG z3rV1`kt+WKL{J21@ChAgFW{i<*s0bvr^A;w zGCHFm+oR4p5YXDO9?KAFIWK35rq|)OtIN6{!MCjoyH?0&lS&Y~stb!CVK7hxV4Dv^ zlnFgC8%7WjHp>h%s|$hf0%fZbUzoXG_^uX%HH5 z0Qd>M<7;o%_6deN5cv=bkw`3r%d5e9M(QFQFF?OW5C}F~uDU?EB2iZIgSMIrN1}?7 z7>oaw2f?vH>zRW}9(9{vGGemi3&92}z7b5p8F6q0al!XiwfQg*x_|~IAVoTWQ|1~7 z<@N>vvjZ{k0_R(&zzm_C+bM0< zdaZ$0!Asn<6U@Z1dw{ZcfCNzp=yOSoAPDALuItNgCBeJ*@DJH=!YCXFyi2qDYk3Dy zK~fSCig3csKzy#y3>(vGvGxXO;0Zg7rB~9G@N~2^`njMh5CS2{urRtSDYt*T1N{nH zOZ&u+?5$1;$$gtW1K|exp#yP%5^ewp1=9s&PzUy~Bl=bZfbaxyAP77%P0Tpu4T-tIC~Ija0NF&2*!K{T_7-2KnU-E zPN_p4t}qbIaKp5528_T6bC3oDfy)tVd09$#>^LvdONVz53HyM~Jdq8j3JZvH$Yofj zGipix`mahn$@d(vl8ny-JH`DRAnh=A*#HhAJP$fR3%9@s$uJ5!FbbOh2=lNbs=x?f zP$P^m47H#GjDQaDa1Z(r54+06e^vx_(8~D`5BtCfFVG3izzDaH4LiUH#E=Z!K(jpX z0)fD*Wa}KFa0yf}4zjQb#vltja0`lX3GgX@VVn(&5Chcw2G#)6il7MK033>74T|vp zHvC($0!*M>`p##l9NF*=13`mm%0sP|$@v(c{n~@{kYvP}2AC3Ltz`*5L-Ja}0(XctuD5CFSr2 zt#A*ud%S481H7x#6Cnzm;MzMt1?>PG2VhF_Cx7734B0T$PJIm#aRuTqN&AouC7uo2 z+!6iDxj&q-%5lyh@~3V14{k`bh^!padAdRR)_42eJ)WrE?c;CSZcmUTT>u6Lonqk7 zHS6F4?fu?{{RAen2+Tm=@=(&>AO}(z*(Px(zQG1SP`n4Q56S=vZ0HaB5D)R74+QZE zJYW#^d)lep)8nwn%`gzNec}E94sARPuRYDgx6}lY*~)9&&l}E)OwP|XCSnca2hfsE zSK~H*e%ht!s{v6rRFwi;x4%R>t$zTn`PzTun2!dS%!;lSN zVAxEM4vX;YluZxvAPcpS47slBCocoMJ|4cI3BexhGr$Z7Fc0~#25gWG-=GimVAA)% z449w^$3T$n!wEXSs|_9zu0Ra?uoD(;;j+yX{y+uSa166C4rws|8?a67+2Ujp@7OMrNNnk@XoDg_3-Uc(^^1(g^yvhubPp+Rp1CAf;Y@i9601Rw+4};$cmw+2b zjSz2#!k3$h?c~D*3bfM7+|RxC)XneKy^o9>TLGWL!Q}5Hc439XOCrSH5`l;^kx5kRiQ# z^(y(GSdroZADoH=#o+|hH# z%}Xw8?j-2b=#DK!mD;@1)M-nO`3omVEGcJzc+e~0(E(5Dc7D_ z(PDK9OX}3BZ<#lxq7?ZKV_zw6$7@-wTkhe-k0)RM-u!v=>D8~NoH#Lf_VMM>HAJ{BIm(4&T(9DTgq!A6Ld`KI^iO@Q#XoeXMfGxJ0W>9SmByIyHq})`BDkftt zxg@x`hO^0-;;ciC3NQMQZaP@@iHfSYrt_k@t&q#kpG@vUFF*Kv6mm!+i!|~`B$J%a zJ;Z`k@<}M8l+wqwZqnfXw>u`jNIf7=4 zZd2yGIF2hyW9o5A$ACn2RaRSd^;KA74UEbEB%GA>R$Oz{6{ji*Qj1r%ikOG3C+1m0 z213#yQ-(FtAw~u#=D{YPdhS^yGfw#N$0dH+$N`gM*7$@ToAlf$2a3?`(+3D6v6c|Pw74gy>eX=R2e})S9DCJ&s$|mQao6ANcR6ObpnNHnxul%mO zcw>$`_V{Cv1*0`&l1nzZyo?X{HOm9KxaOKd+R;G^a9}v#SZKk?j0tkqc$SGZ7RiSm zeRT18pKbqm;raGd_~%qQEg><6yO6) zB#2<+Bt}@Sr*4XoM!Kg_?hUKO4>Na+lr!gt?C?3+KKDaYGVi! zv&s(X?6lSXx2Kybjr(AuTFg5qeqf<%x;ys9={m1sa>H?}1n2&H@WU5>e6bWK|9td2 zX3JNN3Ci*baMXH&9h*73d6;VmK~@%K(aekxZRlem_i%|g+JF&X$O04NXoE%21vP>= z#0m7kn$~W@JB#=(A8WASS%e1!;uVi3|Ed(*uD2rR(Jd#Dklw@eCO4yGZy4K4pX9t# zLmcK%hdaEL`FQw4AQCBZl4IZh`{JjA`7Nt+1d+i$c#w`Ytbq{ZaDrwyk&k^KWFHJ9 zNF`)}kulgqU42T;Nf`7Hf^?7|>)M(RT2ZJ6$>oE@i^)qu#5|v9sz!In2`oOfN9O2} zZ(NaK4!svdL?%*^ixiI!8Tm+9?IRjhIKT+ZAdX$FkBDobT$f?#q=T~Y)>a}gdJ z_~9Ghi0CHQvEFi;f)hVZZ#sfJAy;+;791WDlH(+2In5atN1juiM}h|jxNv}1P~Z#v z$W_KHLpgJh4i}j0g0i0fxQR7zf*hM!1DZHdM|s?XA<;O7*2ZAKHps#kT#K3n!ImHh zUT|HqbDh*qfgt4Lft^~QOK$0Sr&GaKLYY8H-e#0c4V>iiF2Jh)$43Z+r5waZ;$A&E^i@sg90BsaiNsfc=#LO^1( zE;bs~#BOTH{0LRDlcg;AfLdA1Zbu%bSSn1Ik$_YD16RMYNq%f*mHucZ8Fl1V8%z>5 zo1n`kAcfjkH;BytHJ+vom1x~cZj!qS4ilt%-AP{wLRgn*LPBL5tV&_gLQvr(5|MC` z3$e0=h~aSue&Z2jZg_E{gWw^_{iE&B#l6$>|xqto5wzBbDm+}#&u&Ay~v(i|j za2KcO)9HCld}0(Isk|v>ab8$K0R#wu0u$H;J$0oj)Y3N@+IorWZsJQ`SkMQ#C8M7T z(vXYhBWr$|Yj1q~+x;>`m||J*3<71+XZ`~i5iah8yr2g>8~_$CspEyIYn7KW?96#% zPD_h|ob37kgN8LMaf|JIXFNBONqOcoU0x!OYmnm+84w3OMJucL<~X&S0BesM7+c`} zQn(mAfCfAAQ6F%$CEQZ$kbm5eAfKhm2SBct$u=P|;6c@^4)d5@A`>%r_$GC;$#i9{ zueCvl#0P9xiAUE+Mw%IFM2lPjduoydK@0?8wW`6aYB7^JCb1?6tqCH%TU#@b zy54~ddrjhBBU|AMXSi9IWbB3?+fLf(#UcjKgLfP{RvB}WW^S?>PRwH&`&dS`T>_47 z`JfX2;y6aj^&1X(=wlxZ9K$<~(GFP*`559ThCfUb#$(Jw7U6cnMaf~0O`H2PIl(Pl z)>Vn5{iD+iK0pwb3!5eQ!6sp*cfIdj6<1d{8#{?9sIWp)?P5neI!t)P-TrpBKOF81 zcSjTyKm}6RL*ua0DQ9+8rkyEk4JE&?OB(1jA7El4TRVU}9>TO^=+_6?I3P7B(urgE zfEumwfjn|>QF_SYBw6-Nr$0v2&ux(zz{|@-;rao*zG|@R+aJ%JE-C^p z@R?>8Q#$$^+rK+^X;pkh#Nh*WsO#DqOkG0=2+ac`CPUGfE%8wYX7fl4?ghLDFb@Vp_b1WX_XPO!fm zKtGC*g*Iq|a5xEtVu*McKdHlrHZrm_0B3Sxpf{5qgD;t&88e$NKq)EB-W4WOJ8>9JC zJXts+eZYo!kS#Bg1vuE6{Chu&*tvHQ2Z!K?g3`3?8_JP%0=z zv=r2_qFp59|J;=peyhVjX$eUT$C-I|^RI!{c*C zkNij-Vn&c0Nx#4`Y5Ta$$OO&UhlBD5V(5fMTs+grft(Y^oHL*y^MwQdcqkumf_P9U zVpu%N8v}Nr2rrtvwBistViXFtJC`}0u)1H`p4D@$gC_fE>jAx{7PHIgRp$aobbheh=hBSK((YuSO^uk zv|6?yL`m#hG)3$LVu%TT$UFuA97wKNBh}y_BjXz0 z@(reZ2zp$%Nejo=0z;yZE7Ci#-C36$c)+sYOA-Hc+ zr|*!??3_>vO`JWe(8`hrUYLRb0D;gFqQ4}HX`?}Z=!BMJ6x)Iyj68 z+xmyqoR|K3O;!vW*I+lR%+IKt&x)W$v;fdN7|R3j#j`v}oG?&UE6(TAw}O!-4SANd?bjb6V!@mGH$s?APrI_JqrN;9ZMuFJDp(CRddn`6bdPA z8&Uzm%ED4F{ZvqGj|&aeb<&4FxPW(vr6`!EZ9&rzRnyd31Ekr9P8b8QdNNnUQT+n2 zWXiN-5KiBC%CRDs{ajIkph`pa)%;Y{8|@RWe2Yi5u}B3=2<*Bh^#Tr|FyE+&H<*}; zF)>diRdF5HzUWeN&7pc&RhKZ;3wXBqNK>6y(`1M~ViJfJZs25*rCW?fWIgM)04g#`gM zAv}hm8^T}ht#WG#eYgjGpa*(jkb2MuJTa@5Yao67LL^(VK0#E5E!NZUPe*-Jfb|U{ zwTa#QN`|!7db2u2(U*;drsCtXkVRR%&0D$4TSaOombDX0$bffv2buMbla0pBm{&Kw zS6t18O87i*aM3#L#)vwNN;rlwXajWApv%pHHt+{@nTOcHxkh}ZMu`V{*vv7w2X~;B zbkMJN7=wozgKo@;aO+h~>#-CC+K-5fXobVG42z2WO$mI~oX8j4K(1tXPGGxRzJ1x$lYdZ#pNHmvW*qD#h*fph zA2D1-Bd8s7NgjApq~V8R$iy*lTpz$mr};c;@Cfy52XDFD#FO76ZXjJUN=%3}Buu}S zQ>#jNKYq|Z%^f<1c!zv=2j9^L&25dHqy`B_y@#-fCc|Jk-Qb5UTi#5%;FSvi6@!AL zI($hK#&tf z2!zuJgkKN@idX|m_yuA31#FOqbwGw-@M~oFg-K9rR#*kY4g?AI#zut;wiUDIqJ~hY z3jpolW<8Bkvu2#mY|XAAZr<$kiZ+`VQAOl|O0FZ<=~sCeG9#vHjrP?c!-S!;2X8^V z`J;%XhT?rj7kSVIYPknyn9RqG=dsHHV#vAA%_VdZ2MW@MaPUdTqX#zrg=#PjxnAXh zJb++;Yaf_}N${Nm=!Tj9V98*pg9BKF!M>SasDpK(Y?fx2P(bNscIK~SZ(~M4mpB#} z$nU;%izM)D|30tI{%`OCYH91n*KiJk2$rdw=rcd^iiucTiXu!5MA2N{gC2?^GW*`l8k?Sj< zh(K5cA6NzJ&VhsfrUz#Dg?!M)*;#{GxQIzu1%gAdI@1pJVdSdE6IDAzET zhRADSD2=T71&VlUU!8|v_=Rm?2y`INBFDB#nD$>7^dK#1-(5&Ci-h-%Y%1qXa2MM{ z%`#%3S^DDg>4f!KpZAcwX?p)`?{IbQUFUf{05rGNUjI?N0QO%su&Ag6+uF8d?Gt9O zQ$5*+Z4d^A2nM4$^fl<>@$?37*ak;uhKlHRPpkAO3WQnkc7vRY#)gGZhy-d_=}w<- z+0?Cn?02#MSW^m>_j}KIy>t(qH?La{ZSPEmT|d$B;1Uv1B zPmqR#Xb5W02S?9`h8G5SSczjm8hW_;Rh|S^z_wsmgCBTyBNzBiPslZl^5=4SJ61^g zPFAR6_p+d`!`<%#=Y>S7xQsBXA?fjvhJY$#Wp2NLZl`gn||6Bg>W> zNy1#>QX)->$Nc@vxyj{689sl);3;${(V|9=B2B7vDbuD-i55AKe;q#-@=V6cP`zkI_~1V8?@!mzMS^?^EZYE;bnpO@jJG$ zro@gu4#<)yDo#`H5j3U z6H-_qSb1TXR}uONgr5v+B*TwC#1O{A7>3QqPbC~RMj4Afv?m!RxcN{?C67haMllk# zae#=33A7qw^s(j-WCv7&i4RWXvrj(cjNyYUk&T1NG3-?0%V?h%ABVr}E$m35v^%TUAL1P56W=&VDL5Lzt!9oozu;h_aBq0ro(xB=8J+)pQ zVlc-Ne3i^s-+lOTXrZQ?h6SL2oPrvvsH2ivs;Oi>`01&uvf8SvPh}XZhA?>e*8#)~ zMi?jl0G3#f@6ogvO~+)TPa8F2G8tz19FUJbZB!!5 zaNyj?Sq^JFmk&L_wXshQ`P6d{GiK&S=|0C$8rVMfN>q?Sp9}||Ohh?a=sQCqJmjE) zTIDDlGu2yZP7oF4p$wV6nz5@YR4p_oU+OY$|~!IAntQOCncVU z6Jm-1+oG^M9xzTD?)gy6F_>jpi8w}@HtmqBvBsJv5``>w5goA4 zZtm3M?JJ*!#>{VI23*rkDprE9KPyrlTs~uzncKrf6&!7lO$&*bpe8lts2C74wl-@N z6J;^RD>L4przbZax#W{mUO84KTb{Y*n={oiUTzFyq%m)lxU0=7@)WGFG`0Z_jZ*X2 zEWVZGB<<2fR%=g`K44;FM9ev-Rz;^9VF%ogYO@Ao+V`}5zw|Da;-e*zp} zPah)q4?=T41){u?^kc~NKYY0u+b^zHWtVh}V7jtqm294lNd_XD?~7s_BN@xclmMDBjcT+|hCufZe;9*-J9tB2 z-pCJ4%wPr)#8G1y(={!L<60HOOg4}en;K<97J+O79ORJ=oRm*RV|a%w68V^89K#pv zAOs7$g^3+?#vn7yhc+q!uE#Vl2b=&-KGratHmS&2L5y2)09Hie_~3ovThI8I_>o9L zk$vrRlr9|;G2A8NQuuMf8k>ogFgi1u(wwH`&`8Z|V)HEj1`N#T1AYY+SiC$TIl6DZkSX;K~sIhMjS zrZPp4HD_wmn;NB!f$@g|k7T%O*PUG>qCPOh}ru4BF9B^urWR z`^pk%`ZchE9jsGoO4!4~w2i}f;{o0v$2a^mHR3G)DrJd!)S*<7GBvU1^i1ARiN}p#IiwYNm54d08*0_MOPKW1C6NrN6xRc(q`rtTw4>HPcCy#L zEDo_ab*XZj>s-R7>bcU5W`;7cSU5V?o8Y`-M=I-GAY3+exd9i>_GUiRaW$$EscLD_ zO55Dz2&=6)hFf1t%YQKdhuzaCT}hJLmXwdTy@iQwgIg0y5!XJ)Rq1pI%iIP-IKpd; zu7oQrKn%H&o7vTF?S$%*?^ZUv=gc4`JM!7`h8Dg6)gJe7sM)1fVjsW}NIm9JUlo4q5y z+0$vlC?KZnWycFk6Mxo<>ZQpi#vr$U*%ChVeH$}2g0ME^m>Ky!ZGmq~lD58eBat-E zQi!?7&87%<#$7Ug?1$ySKKRj+o;0gcm@PX4;rhrU zPQ0Fxb5q1O%Z(nNi1R)7ajjMeBp>(qN3&vUkT^3Y2Ynt&!Tt-^rtyQ&gMy4z-CHSY%XgaSAOFL%GDoi!M;vUlGKT?ZZFA3a-4Wlw+Mo<5_)_^hWRf79xH%E9 z!Rrd#6vrn;l`zadl6mzei@mQ~&phY74))H2o-1S@9Y;)l?$ZFnD@1L(X?&EhnY;eA zZ!=0CYadnSH~|y;s7EyZ9{6AX54_VV2E{b+8caCxuG3m zsNGeNpZN*IP_3ROsNd_|k*P&cQ3TsV*&3Vd%T7gu(EVC8=mG;sRj?rf!#PSQtWO>w zOil>d)4@cMshLS7#u%{1qA_58P}~J-9Rx~Y6$VxXTA>Ao+?ILY_jzFWrQXVo;Om*- z>al?)3|0E2$Yh1s`z?n5Qq`P5#Mlq<$iCc*TOGq$;aq+}UK=3MvW-MYL;^JwpTacE zdLUhT@yzw)OOjok3|v|kKA@FJVkJrw7Fy!;b)ToP1o+jC%84L3oniT@U>TAV8nVGq zb;KF28+f@P*C?WybPfGM&CS#oyy+L$;1Y2p;!%i)e-TO^^b%qyTca?Wv#khXj6owV zpio#$6lP+BRbMnx;}=n4HCo>mzERnAV!553hlS!ev0m&U%mI+oMx>$%3PmgC(V?}- z+FVPG3<)gZVrIcd|M}lb? zKxF9Mg&SlTc5$HpOPHK7bXYiwqxwZl!TqL{5)J1XKv7|GBy#?9E5v*o}a z_Lx78M0tqE0R&2U%t%#0o!!}lLHp|MUGBJ@`ML+ zWXf5^2zJEljpR8Vz!`p}x~&@$%m5O+qmfvUe7xSTWY&w(L6$5p z9C9t@q#0)aa1y75C}wd!T4O%uQJ5ZUgrQ{u!8mTEW^$%Lgc(?lUuChuO&kC)RHL&}vVioKx`Az@8&L`sl^K$t`% zoWdaz81sq7d>q3MFkx>-A0z^(whiZu+NfLn=Z!*`fNB_IGH1D6Wo0UbRC9yW~VO8f9PT=(p)- znzE_?SLA4$9@ghv7lFQkk0OOtB4|@oC{L)MKtSkMnj~CeMNyp}kg(yXfnb!fpd$K! zp!#BK0!~h@1T37WPa-1oB@I95W{f4Ief|WTR@|C`>ZqR4agypx@hCSog*Q5lf_@kJ zeMFx=D4-&#>W!gLouZEjm7;prchW>JCJ{&A8xTW8g>PtYQm7PArO$_uFgl8rDS=2#P|rx zd6oyE5bIqYKy0GuKJwsJwt5`38Z4<|V!}$3sy+pto`$0y#h9I88jdUf zgr?$G0)vuf<*kSFl~Xnxe`H6&tJ}*cO!+sI1DGZRe6LFNNe* z%3W%-Ey66^qY_!9+$MN7>u%yi-Ucn^1@6c7?d(n@;My)>eWA@@?U4Ry#XhM2SNiE@ zo?=Q5RiS?EM^M&>ZiMGrZ!sd=-i&VTge1b;EKfL0)J;!f`0Nd`}IhQR&gO`9u^~VG%fAvNURG>=p*;< zf{JlD+ORm{aMd!=8u#$X78L`#gy$Bc9cQl{3)<^_uX$do-Q5%U1~Md>Y5E@JB4?rd zzAr6nnOC(Gl`=1i8 zF3*bTE8~O{p6Pw=awQ&eI9uDBk~1Tpo!bSKB(EdJ{%;FwC9*kaRj^$qFYZQAZi+NB zQI+g7cdmK(k|`UpXB{yyuB_bZY~AW6Hv=uf%I-N=p)Eu7qnY#nM5j?BAI5X~ZV5^* z7|-zbj;qs>Bo8CAR~o8yzT7^Oli2#R*#b1e#hoc{ugt9v%66`w!9g({Q?vN2>%NgU z3+60a^g>GXP)k@v8}%3Uaz-=7p8~KX6X|&+3>gna_)L( zBc@%W_D$vWYFiFpAMnJUUkV~j(<<;_BbihaGh#33^9C>fgsPu7StlFc_BerZD0?n7 z%$zCDGvCZHOKkS%`fD!!u`>4b7(kL~a}jX5HgVeWEqC{X>2i28&QkaFQNZO?e^_rb z(Pvq<@1n6{N3Eg0u*ep7KSy@wDmOJ7AF`z~bZ@r%2}JPW<`VX_AXgsx$~8EXw|7IJ zL^gOdjdz5T%mNt!1AWs@*&#bur~2993=WBHPcm+oGT*3e4JUx-=8LYxANVy~! z17I|RFYLoJ`~o9vgdjwDFiZjzpyL5l!!LM4+^s|ZH3S1P1j93+16E@03}^35pLhaK zY*9J(Z*L|^tK;&%cvmL{G#@}sLogBhNVWX;P&A=92@`?U_>#5p*I9WssF=1 zlsP*1!#eyzH8g{xj$r_o4;|0>o%i;05-P9quYHfWaR>TM|HJx}?HvD@2 zm>j58`8otcDgXmN*n=}T0u=nh6&wH~1Vb;(13MUeulU0=R71Xd7O%`lF*pKv-1d`} zu8D2z$A@@|%lSG-`&Uk_S4Qc5-@&wVwoYQUOGk4^u8)nw0vzXe*&?C0lM@^igNS%S z&f~lyz-hZKFb27Tp&4AEo0gdF_>y}>+G!!sa*Blv=d*aCQ5K`_Jt5L`kq zRD&}dK%1|FkKp>7GyG`;hES!xBX9)&k*2*Tb3`hBaWISH0i=kKE_O+0b!Oe*y8#%Jk zL@{H?kP;<|WV2CZN|h@QbUffsA}}^7Iidsx6IjiRnqrEqxzP(tp&{`U%@_%mo}x?f z!1{N9q(oRElMc0dfN4=NG;8wY=WmV>u|nqf^XKrND;GN0wq*+ghDaH6=f=Hy7jIs@ zd-?YD`xkIv!Gj4GHhdUyV#SO988>#UvPh96lPObvd>M0Q&6_!Q_WZeWlFy?_mo|MG zb?U-9ShqIzve}$D=$t(hwMx*&EwipbN%PAVKZgf?v3phxsy~P_55!qDN#jrHKtA3a z8MP!zzcpvV8%+pdqF6^j9pbvC2Bj zA%8N_VlB56)B!HKWUx!M2qm15!U`?C5W@@!i!8LzH2e_65JenuC=W?I5ycc$w6L|- z-gs%APQ<#YnqaOV?w1^MoP>&C>d@q$eTYLRm?DcL4w;Muas-N&rhC#OkGzTsr0qDO z$h#`T+lUR4G%0V&^lDoFZ?EQp~9?% zR`HFBG_C;T7dO&iW0hQh(Zrt`?Lh|}Z+HzRl_t}e#gUbs?C2!z%+tg=D}i8Ryzgc* zR;MYG)y`V}Y6=2BqYi)t5VSy&d6TJ(U^zwHZkgg%+m0mi#}gs;6w6PCvT-O- zL4{)L(|`pYnBamJm2^_k3|^SwhF8+m;fN)k_^uY;FvhId;`k*Obk-^57e{`&;+I=A zVWW^=;_xk)YJw#HRg+cX$Y_#Pdb^q0u6|NU%e?T6Y1*7oI`7({NecQWFVZa2+iyk6 zZ@xFjb?-j*vRXpSjr=QBtb6nQXJ3b0$%JeKDLxzRwAEgFC4?ts8}7I*>`?By?OxPH zvks^i2O%2aBgXihWFWS35+#8~3;{=RDFfU)+>H=9k+8is7L2fZ8l9{TA2GEw^Kt=~*kQUfH5R8XEZPbMJle9}CBPU1`akWR*2q>p@d$vg0b`l(Ba zNUzq*(>YTA+G_XUd)iE}pauX%5(>a%#ZL6Q3BCAauVx4*co=g?@rq}*>s=6o8PwoV zoJYM4e$Z|n1mOrtIFyTJY=p!-TwfH2dcHMY2QjB)0UDz?#!!R4J<}RlCcR1{-a+MbVCWrSVl9d zt%D*w;~G7sMmE0DdZfzYSp1Y7WxX&uGK3)wGl#=Gwy$$4`JDVhM?~iAtbP-b;S$<4 z6j=CUDj8`SEauciC(f>sQLGvji?SaXZY_mmdEfzzu?gYv>i`rq9voTON>@HAjg@)j zEK}tFMq1u-ZF%y9Cwu`6;be)2EU95IZ5YU5?!+pC^dk*nIG!CMGJoR(f+qJ%@IEHE|=EDIMmafxA|B_ygmP@-^IPkY`IHL;`=KKXeX zTlN#60yEcB_~DB=`~xO|RE)9?a6@D9tdP%&79o?#oza;yBhggPO41dHYtAd1N7-aI zFA1(pUQ%7Ovl>%8slYt-j!$KIN-0eVsCcUKcmdVvPI)>QeeScTK{d=jg<8}V@gt)K z?UQ#f!%&4X6q$ky;&&9vOfE%pd^;hDG=Y#hk{ZQaQGv-n-o(vt8t`c%VO?MHgSAip zeg!NrrQ=x+kc>;T6JvC}sVa@ySHJ%CrwaS)V1+_d!XDN_1>K&X5_%bBd1QVN4G*;9 zx6G^j#B^EBh%ArYT7HH@*WY%ivrJ6AE zvsoD+RG@;LsQjZo9o?k2-t$drTyvoO7^!KiXwGM0F(VE1#Bg-G+pr}=CGyPaatT~u zGaA>x{Y-9x8O)fBd14NAM5<#L>d?q??z$7T>}7Rw(X6SDBsHNXeTx!_r(|^h!eJHb zSCYbBcBSb(qm`g~(*Ub7xD8hFlB*Y3!7>?+ z3x@KP0Yj>@6tOXn-LSSecRz_f?l1JiDn>Vp6V!2(DNY%RdB+OdZ&d{k*EGvM_ED0Q zfK(!t4DV9Bz%7^hgLgj`!UKam3RAX|KmcBefT`SQMppd;lt`1iv-pvj>>#phlllG7Qce_ zg}x4bSKbbXCGyOKrJ3DqiaFWY)q_~Hscn^;IK;fS^0Z!tY2nb((IDi5a=8eg8`{Go*4D(s*8#lRaf)lH1BwFBI_fkxJ6*oz3YU;{Q zQA#yok?4D?t6mD${_Kg6s1q%(F}Nwem=Q)K8>bXk`qE)3nS@z}=@X-L)Ej(XiGU&q zStIINn8{^ zllr9r7Z9KdUT}wiV-$rDgdhMR2tpj0f=QM;jBbFx_3H|!Dj&agw z+qyK#+)cJELuh4s%kP_N{<%t>dGQ_(+D-3ZZqL*uDcWV`TJFy1gZS!8%)Y|sl8=sZ zYZDH@*oHJF21W)7gPB2qsNd*~ftJn_)+b`oZu7&O- z>>3M*P(mWYiqnqoJ2*@_hOh5h?cL^X$56_o-VP6xBJV=~LdBY}@A?eb%)+)LP%Lgi zIMTub4{hi+0T;fo10A6d90B_nFQ*i)1=COsF+=>;5JSw*4SVY9LLvt1@Zx6ByeI;@ zelQ2ULd9&Z<17jXD+<_HYzXmf?oR7lOlJ#Ee>B177wEhW6_^jkQNck&QhWd?GO~+k0j8- zTyk&^RZQ$&&+1Z-5cdZbu&M9Hi=bqUo0c&P&*huaWGWgkD-;mbgz)XW-~s6+6UPDy zz(HR?Q6z*c6ER|iIX5nuC5g+qWFH%q+F9Qzyv7Yz=6s%$w zW032B5!N!%moU2EeI~r7s7EY6yd+j@vbrg9Ze}GcajtfVGQF@73cAIl&vWr z6Ec$$GW&ulCzFi^vM=foGtJBWN>9_YMtvy%qU-n%EH}cLBoYYVc54(e0T4>z3#qSI#1Iv+Py0qN z^6t?xud^Q|6FXU=GPjeAFcUDQGUrh3^RjOAN)IYdOeS!pA;g>4cBr_Hk&X3|IqCa=n`4-H^l-9f)kZOA}|FL15HUeOW_uJ!5d29020#!>md7v zvirP~L-A2Ny|X(zl%LuU-cq6%43a8=vCK@;J>}E?;xie$%A3qZn+~9?`0e)e;4XCx z)?#hg#Zemfk2x7Pb7wnK?{!%nDYxMR1h*^G3#JvL;?*(luPqb z{KgM5L$ph8iA47^7vaDTN$&vEv|JD}+fXyJTvTb0kTsDaDRA`nT21bB?Gb@A&bYDP z^76|9??}&J83@D^S)!c;bLbeM5Sp_W00BD75D>c06~`1)J=E!*4(cAWGBzbsjY{j_ zfK9I>Dh{9yeev@K5+Q+c%p%G(O%651AU-5%pzic4K+E0Cv`+!B#3BOU1Qa3xtqKeE zP{l?;LxLuabGIC_j~3dumim)l^9WJl79A z%M&~^qE$03{)9$+JS+!OlU$tt2v~W|SMebD%v8Q|m0V2hT%wRm7AUS%f=?778T3WB zhVufKEhU`Ql&(Qqdm$tM;Q$yD>9{XkH`Yrxl~cj=6~&ZeM`&D2asi`aT~XCM->(?Z zbn5_7_*~V8zD}AF=_{paPRV6H{DBf-Q$F@}8}ZeWG9pc2B9gAgG~p`H4AwvyA#7x_ zI2BYKGl38Yfe{#?0-tXa%wqaNLJ+WZL$_~?MwVVdGA~YsBh>A9|3?}jsc_NqWP4SKq6jL86jzXMCHO>pmvpzD zG?l=2e5=;+)VI{3 zR9y~c%M)E^Fw-{wZp$buCxAfZN=)8b$6R>WXC>HFDL8slf_1cl4M>j)h2mhNFF}VB z6gL5UtM(PvfDqD{5Hwc~($SQ{#vg{^E?n4#?>L5KIO^&bj~(Vz0eI`k^>C{)C2|;$ zgP?6+t#*x={gAlpJ|bxL@H_T{)$Z;nXf$zqO&fP@Fixu}TFeVFE@Os592tQag05N5 zaTAV?5CQ>>)wq?zH+lt#-v|SxmQb7!VFw8`at(A8 zP8nGlwv1{2@&ML&4eB|TtCkQp)L-*H29eIP|#A&SaJ(cs3MB!GJ8%33t$6C72}KOfcFb5)+{q;L1qb zIeXuk0-enB##g+R~mXdIX}cf9CoKzY5EM_ zIVKa8LCg4q2jvsA@9|u@o`<@Y?<#DxaM6$&suTO5&z8!bTCpvK2Bx}A!rFJ6875rK zp_6%Tx0+kZ|5K~84%H5s{m8Xl9fBGXq1T*fXKgQE?Xs=inkf+B6cFkk=9;Dz!E?(o zm7R}Sjg6kQkBwiUo?UsC0fBQj0VWX&ueB7hAKSTASC1R4hM#+FA{!1=teVa9cUv?( zRU(lqy8Uo?vpd>7cd%Wl;S_cu5kkQz*yR7z+Sd3%oM9UeAYm88;U8uijFFTPIDvBM znYS4fjyEAW2ZfCfK#hr8miw6ybXtPuIKU*2x+fgE8JobSo5If~vT5MDqk>yV^*Zd9 zFhDyczFQ&p8`xMff6cS-@@fEa~w|0sG5lCSdzW6HKnG?Z?IM2~I z%NPR@|NO5HAdT@^sO10<3=W{Rbe=Mt%8OEd=hvvfwaU?E!)YKCy6(hDd@#g3BureH zS^S5?oNi6F#YM{>c3~GtLB^>8+jgOm_N@2NE0f&?59GYZ{p2phqONcGHHw^!Ke*UT zDe)DIj58sDUN*TO_Jb&}|x(vUWk6^d`BGY7;!4 zOE~)q?ykNlEr`<7uiYrGT&Ox7+Zl$#i(#OU&8rh*+}Bhn$Qysv{C4poD%27_^dLUq z{~Z!~OB~|d-cMn@WA0m+=rERI$I}}Xs&JQ7LNZsI=uOTqJ?q+FzKCxOh4>lZk8N<{^UDb6LCemDp1z9L& zp5}?x=4<|=)t%gRTq~T*H%K_-W}eB;_uyCIG!KYNnu@fff{)J6d(aV4`?YMA-%JI3xuF0 z4`6A{%NR00VLMSU1Dp_KAOhY$0t_JjNxuLB0PDlP3vIF{F9D8?4Ipmu^GDFlfrAJW zDqP60p~Hs|BTAe|v7*I`7&B_z$g!ixk03*e97(dI$&)Bks$9vkrOT8>iX@pyv!>0N zFLUawXmh8}pFo2O9ZEDLjiWT+gi894pVML`g9KR!YN1rApq%onits9&|6=|e77Gt0_NNYSrQ~y9?NGc6w1LwG3J@sNdDG_Cu03z=tQq!ZDm#o3^f#=i@87_K z3m;Crxbfr2lPh0-Fy_tYHJM9C*mJt|>)5mZMtUF*Qm|U1PE81k>%ps7wZcg#^=sIL z#o)jRvczn~xCh(v`{y^VT3C=6qJ|%R>6KSrr;q{(A`=M)NnxZQBE~_DE%XmUk~x)) zWtbf>ie{f_=EP{El~~$osu2K4Yp%t1&}^H8_}M0mP+`OlZ|ugK|8_j~=;Mz-1}Wr_ zL>38>bI?I&Bv92Y>Ex485_i;6M=1q|KkAV*9(nAc2VQ(#VWm(p@y&PDgcsp=fLj+H z;GbErlogj6h(JP0VSAkt%7P6!2#a2c3?jy22R!yrhWq{VPck9Oc1esTMk?BA1Q2k- zi<~_wBW*I$xWlKP=D1rXQI=}zsi>x^>Z+^)hh&mBwJK7Rves(rtq3WF6ew7RQjAtm zjkF~~=Aq{vKfxa06<7zAiQbtRsg<8wup|^0ENZ-IpB@Aza;Jg2oWfTq2>BUqf{6Ix zg)zSD*3gBB{&Sfzw8aSHCRZ46Py`1=YFcUm1kl=xA0`wd|3a@Z0_wt-=x7kG5JxQW z#1vO-u}`nU8r{VY(aQ11AS-7M9N%GyC_n3kB$Yzto#&NSTrEpxd1g-aEShObdw_ob zRD002k(}bDws9fCEhLcqdEj1sB^|C|>8jh9p%F=@s6VcN$SG`2AjGc(CYn}&Y5}mu zsY0F^{Kf$bFRa^c4~H!G+;rD%_uV~atT9b|Mb*XZ#_hM@6EB_*LUxILo|?k zP`qxX{88drJ=-{#&q{87mr~&zt+e{_L(R{B!QwMRp^L6ZB8fN%xb75*L@1(lt$STV zG9){He2NMNdsK@Ev5>G$s!{>a!a^REHiRHgAS;m@NL(n5XjHs!8)%wfMAd!~-oh4}yA_Xk+@+Wcl zV;`RI1Oi=W!^k+LDGhYsr)-xt4!Y(5yz5uLPL!Gg1nf1k!PLPt13?gm@D0u*p$zxP z$3FV;k3VUl#%xuSA^`G`a$}(E{$U;+4$CPA{{RK#4(F9fI^<>@(cBm9a}c4WX=rg_ z;sH)E#Q^$24X7}kIrcHaW@J$@3LIbT!YIZaK=59n7W&5atwl!s=+qD|D1 zAtB6-j!KBgW;*kk(2V8*1PLou6;hhmTooiwwn${<@FG`12v{xzmBT5^eGkE8CZ!b# zw@^cg``d_F9u%$vkRlO&@PlCRa0ei;K@*z5(g9lO3CEc1i?poe4umPe7MUQ8{Nfji zR09Awg6I;N*bJ#Ip)iOfvtgskrbtIh(vkv>nn^0vHBHLWA@Re8FIA+X%!v{7C=QY^ z?cq6vn9i##0VFzuL^i^6fS|3Di3Y-_|33FA1|T@~ss9AVdq#NBMe4{H3wwjTX4KG! zo+cq}Bme+{8KM|@hBJ(afkZy4qu#Xit#FO2Tu+74lorWjbIq%A3^z;JNv4q$v8j0y z<;@__EFwe%s?OS}mD0u2h*$q|~Hk*d#ZWBz< zR~l1v0@e@{Mjq148`L@xw(iEQdd;nFcgx%3)b%+*!fS7bJCqFB5RBdYt3@PN$%Aw= zlHVL6w17$tY5)jx2cX6m{UN^jNj5?FEZ080u-Wo%7NC6vZS&g3h=V=qc&-s1YE^Rp z0vuokaySU?9Oc0@EVLrFg&T1P|4iTl8`vbj1#WhPd*BAA#JD+4ZiWEM5ceFQ7~vdW zH>1lCb%LZ?0~yHu4thWD3T?9Y%x6NFsu1(K7#M3>q>PR6hJ``!L$S#yY~;I%LdYS$ z7wr`8W{Z(ziYlZIPO_4h%;agxWN)#O4uhLa<&8)tGBQ3Hg>wa-FmWYOGkvK$yUk(pJFw4^7^(ga7@I8&yyrX2!d=StWuG*#AxO_mVJAvDZ7g^1-m;-99xC#QdQ zivF4?$^$7?A^XI`PbE^`|2z{!iwQ(1Rk21dVjddNb39w3jp>m9BYD%%j<&S>Xz5G` z#oE)BG*Y%*r98-oTri8A2qeke0Z5k#5*Tf^A5Afz4;g~&uHeqoCP_#qXk zC>s}8G*dMalu{Q%DW`|`n44%bofL30^pcn2GvQ>bje)9YM{C@xV;@8jq_ABS`ILQgh-QVEGuN)4LLD_f!u?l2}z8b8AA($t6 z>o5=Y;0?j>3z>&=nCA@0unwUY43lsWK^F|OV1a<3KX_0G!Jto!@C$>0IfJkYwHFa_ z(I)b?O~)lW|I~1Apc7dLffo!iAblbjUQiL5C3ytl3kuOX6w*4rPhJ+C4mxby_e_YswUWhSI24yDa5%c$j!&MFnVSh9L z9>^jUA22cHTMgS5Ci}x2T%|O zNWccyFc9m242)nFxR(%2XM+EMg0d8RG1e3%#yMCwO6Xz+++r=shgmoXRZg*I4M8Xg zF$dFUc8ahWqu>fgm~()38E+S4PpA?Z_Xc=JLQ{wkRTy{;k%j2Dg=W}{&iIT+5{6Q4H1a40>n}^56{4;1>Jf4F?c<=x_k`KywG+4gUav)!+>KP>9Y@ zh`%rif&g@h7zBAh4Z9JKaG?jmPzwBZ5VKd1__m1*ab-@ST|_lB#kX(Bw-DpCicZA_ ztr$xSp%@Dhgl0#Cf@X^cfQ#1GcDwO*$>S1tH;lztg;y96%6NXvc#Sk!lQzi^@JEdu zu~IjQjg5zYgyj!$xEu3Ok9x=teCQ3;Z~*BTbnUosn70o85PHr~l)n%R2apOuHwlKY z51)q)zu=BN^9zN*AO}$hAm|Wr5eo0HKp7Gz@6d|qb_OOeB_7YLZaS3sZ z7!i}{hm1XWnyC4VIhh0-!IP<}TlR;4GB!~DFc0YP3KMmK?sK`8o&13^dyK)0V%a0ZuP3l^Aw18Ix4aDg>f4ZEl# zoyiiPiDWL>5v2KdFZr4jTA}Q>nmj=h6KbJzb$`X6D4z&P>yUu$Xq@f%fc`KI|Hv>< zeCUAZSaawglrZ`a^(Ym9U~@JXdT=<1Z1M}$unX8#pa}Vb@HS8n(Sk}ep5h=bGMJv6 zGiUv#eE$}3oaLSep`WWjn3M1e52F}#@C&ox2nQgGlCTPmsh^V|1hbb4qkvI0w;8i% z3xbvl!9WO}Fm_aB443eW-{))ukqPBznjaCNG5`Y`%AtswsMCg_9b=7(N>bbQ6%lqJ zRksi8fDVP&c?gJecNmC!Xmba#bH8u^hZvppSRSYV4eSsM02q1*NP1snl>SgHymxi* z#))2pq@A-fiv$b!WCj$$V(d9^LMQ}OFbQ$v2ERZDIG`9*Fbi(53U;6v|HHtg&1$TT zSqQmM3LI3R!h;N}a6F9A1qh^eel~1^#-}CGpnrO(Awj5y`l#|cuavf$teFsFNUzS6 z6rmtyF!hNuMG*f`4Azhf2fzmXcbQG;4CugzgqWKL;G+o0bJb7^H3tazw})Zbjy{SE zpSK?>`gyQ$iMDDMxGGC62ulA$d9o7;LyBt@`E?c{cDqrmK8O&G@C)R+7^{$`2jB>b zkqRqna9gkmoZt!@0r&nHz$s)Y7f^ydyG)G{|9h-5!;S(n0f0^ zj=vy|b~uU8fDRBC43C9B-no!(!8zW-q~;ly`|+K48MA?LgY4;i^$Cj{*#(YJrqikz zjxY=4x(Z^70|$T%Vj7>5(3m*T3EAKc(@=<|FbWo%3c0Wf&*=tHn?O@LY|$ zq_r!-wKG|^&>OvZ#i-KTOiHmPF$FBeFge~P84?HuS22NkmMFg&j}iL|xd07tkOsdX z2vXq)!GHuyK!UFubc?HpR0)7<<`3TBfHvojkM(FbM`#lnLkz|Cw+J78?wLKm}a@yl!x< z!`m2ZXS{oQwadc^ouDK8V6-mbyww}TLi|?MHpG8)wvswCXWMuO)e8~`2yrk8tctla z1E8%J1aBaLj8F)t7Y6N9kMbgjniqNp;CTlHW&%4?Jp;LL!if#(f&qjOq?BU(##jU4 z7ZFjBRCTkft0Av_b&9qc8`Iv8C;h#{Ym04j3c%SVvTVh!i}- zQhTmcm98SuHZQ;fJkSZmz{8x7Y%Br9M!d?b3{5E2$}%)E-bONN*m75t1``+ztB{9V zfgaB3#Zs{axtt2%iynDEqtg&$w^?&HXU5!=Ay`75|NU_mDEP(-5iZq&Pk5kDDY(Yv z5~X^{o)|e08u^1aJHaE|1s6OCg}lzkItx@VeV$;Bg&WO^vJTiedt!^jAZ zuE?7a3lqwsEXq4f5MG(JKB3C6{Lm1+M;Q~*DKt2>e1D*3CZOOJlJqPdEfpB1KDyY7 z1QBDqfhcLK6>AodY$0_i>p23H7YCrtxrR9o=?~ut&UjE~%vYtq=Fi4DyFPf2UBJ#p zeZi6-1att;ezp(O@C$NS4b>?x_*@G5DG3R2j}h_DY8TKWbi5i-&<8!%qr4lel(ne* z5)Mt#Y~9w^f>rs3`0ZddVOJ zTN=YZ%cT{;)is=_H%t))eGp_l)}*Y^SH#djvDR@t+{9hnL7a^yLnc__*L?jfEMq41 z;Y8XJ389b(p+Mc%josI6Pq07@qNGCR~2|6dUVVj$frt|ltmPM~-v2VtIwfL&?MFkm4&|=i0I+yO3SgMGbj= zS(}@e`;=Yi2I!t^*?7vxK)pqOOenB)P+r+UDt$#~trdt~612_9U%jAT?hs)<$`fwZ z1aaX)k>StF=B9q?sIF;^$1Ab}=W$NrLGVs?KI>{h3gVFGqog2+pg&Ud7k_TvlC2f{ z6Bv;|4c*0;Pvv}-p6KTcANBLgdY)|{`8=pwHhxRi~sn}|NPL8E8A8TJwyW; zUGn_65HB4Pc(Olt3Fv3fKXb+w_I~pSQPR+^^9a$Gbw3gau67Fv_j?}{2!sQ@fB(K; z34ed>ti<#HaX{cef(LjUM2N7HKZXqVG2~QG;zWuSEnX}rL*vGcFkoN=8B*j(k|j-^ zM43|MN|r5MzJwW5|K?1ZHErI+nN#OZo;`j31R7N6P@+YR9-T=;DUD+O4itl<^dCQ} zpezQ#x&#j%iJ=myOhoF`fnB6X34|5Nj~$L$7^av*9V2`Q|xjywPnxVVbs6hGK&ZzT4pjLSZOvWzY| z%L1E~FMgU4Qz$YaJHSk;avjq#k=z6g&Il!BNVPlhJg5_58hYrV+K%#bQERWoHd}4C z<+fXI|Gx$Irs)pIF{((LnzYiaQ2jB}140?gq9RW@r7VFES(Pii+;u76`UrwmBE9~q z^*(jc7zQKQgKf--(BHikIl6R3|@Mmue_*JitIx8H`_rsvQMMWC2z03}Bn1L`^lX z{{_leH9h_5&?k=KroDFCZ^u1%-FH7xM(YN;dq#o}=-VQ9?ZaF>BhNx4ak|)p1rjJ} zihS1L_v%YlftKd0A+b>l-L}RiDp2&saImTL)3ZW0fdwiwu|W=U5KIHv;Fm<` zkNY&k7bZj@nEYYF@Fk3VEv$)S(3g|aJ?L0mb6>`I;4El81a|bR2}eHiKOz>K=L!V6ry1p8QmZ3OWcU;HRbm;an^1*V$E>jFi8eH;))E!DNJci&k&lFAN~TDu zg4`_+$EspTu;?jjWC?Tpa9l-NML3(l#|vphB@jL+5I62^4g-2&`E)ZriGVJK=OaoV zZ7r zsQh48wvr?iqF2RgR<*iSuHJ+nP^?JIF3FEw#ET-k(~m|F>|;~Q3Y~T z;9Lz(e{8B#E5t0QW2J6|G#HLQ^;kG%>vue6#cf}`3>b@*!Cso*6Pq#$lg=o*BJ zuz?LLRW3(8`Ij$k(81^*i2)KmgG7<8xr+msMO2ET z5-gn3B@*8UbN|@aNd2bQ2SZqIlq*gy$2F3<4j2P+0xx*n8v3?F4n`T7V z#h39#u6`P#8Z&iHU31M|4B6w^8QIZ~hIFJQy`sPr0~Gd!|Jk^zd~B=YQy4?S9ikPDa$Iix@~a=%G;+uPp;cesf%V$6jC6LwRI6+K-ZM3{j} z6Wq$EI!dEuqe*X5@yDiA(!5BRMJ$qoZZQOY=>+!3Q36@1-UdUGUhmq&m$3-38*c0n z)|^t08VrwA)T=H*!HB6A&T4OFNb-|WeyTJgrXSE1x&5Q zK(DlxhZJV`Vtfd~s-5Awa;JvXW&AS+-t5>J6ApCAfKrc=|P??lZOG*2-`|z1CHq zb*>)(*m|XvO-{*>AAs01INz&22-N?0no z1HQ``K8N^=;~S0S!@J*zwp|)Ik{hjG(wt0i1MPFc7lgqW{GW1ojyyPqnW2hZC_d8& zJbPF*FnS&gLcjF0E|(#NNC-Wt8@jxRKqn?Lkq+}4AelXI2Jh^zG(Ttx*HAU(~T0$5vMpoPPl|O zxCFzhJ{dH`Lqx3qzD2Nhq78i(>oGUh%zF< zqPKv;Q`7@7z>1OZKMF%Tv2(q^ctF`(|EDh;3FwM5ysAZ%P`U$P!(Rl(HFQH8(?GeK z!(fU#4>UeJ6v3j1n7vc4y%>l~IDkRaoM9+LMbyS^796n-GMDniBXfQ4NECey&T zRr97%tCEzmh%D(u((^Y_Y#u*Q1Ns=peC&=f3yJIyAb!BTyi%zG?804C8rz$AG)1_uNmPuIeJlxoRLI;D$Stf1 zhIB}i@U8uzy*DefgabqU7{Q9D|H!Wt#x~HnO327#tV28G2f8B$yX#7taFfO;5Qd-# zLd-^(w9C81%e>5qa!|dRv`NxC54-@lrAZ8Rgo~oP2&(A3qqNBdO2wtbihtz7S2PUR z1B_XG2{*d4V+*m)93j70KmnY%V{=F@!9bJ%OR%&+vBb#VGsd@zme*WHOugbD$^_5Cn1PFoLkXOT)cneeghOQPNZ6FS_)JS?tWA>e3>?@MA&94+ z1U%GWLEse70VPnpT$iLg|HVWIr?SAZ9}$Qq0l4j{h!JZ{mB1qF3{I?=8O&VB?SxA2 zEKl&1h+iX!hMR$jbkC_c&7ELRigeFo*dC3PPvY~)5WG)<$j=xnlYZ)+>1)9P1=1iD z(ihAMoJmm93z~QH4n)|6i<;2C*c4cx2DSj4mY@#|?MDsG5f1Ip?X=342+{JSh^(B< z5>2BMtw@5XyA>sh77a%CBumSX(Z4uL`UF7{`~jcZm7r?7Il;yu1=K(lRB@w8iWoC3HmSzD@2z71c_84K!OyGER=|>L!Evq`GXSvVpdW}1Sk}+{D44h z+M?)LiE1T@R?Jq06G$yQvoZ~iZzTvglQSR~Rg7rEggi}+Gg%+7F`Z=BHg(quB-1Z} zKzhZl6Vk3%ipzoE*B|><&BD*0Swcy zW2;$#Y6zY+A#$ml%<+ex9ooV*+{3+{#dAz3l*h87GKR&MaV$D0m0Irbjsv3xjyjW1 z3MY}s+6>*=?kov&+EiC;jw}pM8*^KhA35>Z-4mG^n@}xKj+uN@D zPo&G707cy4CEntNn*>FKQ&>>bI}d|}!pWrysYObH$P0V>GKT0}$HY>QU`oMQ3DW)A z%M_7RDp`UM%QYp{)-^-ZBnYxR&DjM_oa2YH4GuNL2;I#}nvE{ty$@`xOXCIL02W|x z=?=7V|6H;FH7LXsD2xsoiOzzskHM^%@3~q8-Cm67UVsGAEJU`jMGnKTUy8s;vprRc z;F7vCUybvDxFtjVpxfRE;gkT+-8HiYVy<2l-T~I(9p+&{F&v*!-m-v&dz8e2B}ctz zKg)gK^w^o?BuvPIg}R|s$lSUd@nDniTJH4T5HXCBWy6V}Kp1UK7bXY_j8hY?-L$0N z-H2hDm|;3oG?mQZ9;V|uw&Ub5oPtP%Co4xtsEFs)9wR-=>9kjYAgthzG!g%&xWABjt=Ro#_BpY{|73Q zWv4~OdprPSH489$UXh~bOp#~l9Y+k^XXTU=aI}iZv|^rsWP<+K0St+to>1EhT+1

    `8*fB=xpcrhUC~Sss>X1O}9RTN(RAtB} z?&1d6ahTo%DCzDHYf?}H>V$+`Mv2ZA2=Y_nD_y;UXzS{D*!#%EQ9kC&Q0<{GXp7Km zk|;xWBr%~rNc}j5HP#8GCTylojNUGZ-$hDzHa6&|HrXT%21H* z>E;*vnCE@mzpNt&IPgBF@G=V1giwu2f!sZ??Tyza*A`vP5Etc(besrhV7WO^7Dn0uw+emjn~ax+ZLxl+kkNyXNlid?BUk&G*@$OloC`-g#Lo( zc3J6{=|6+kKauV__e#U97 z`#;NgJrIiI{djU24sW}r%KbQWF{E;&087=Kz^@z#N5=>Y1PS=QWR_j(OV9M2pmBk) z@x~VQZRd8FqteR8BEW2y^f2p5En+P3@=wb1ifF}L+gR62IOy7-)jp|#2KELlUGeU9 zw8LgLUc-sN^7s8kiKqlrt%ypXib*ecy3OrucEGIxifdo&8}Igtw|GhO4x}VK^yrRK zxruSC+Q8Un?8s>^X)`w3^>n)Mn5b*<4vEU_y?JlIe)o-mCwOL$c4;pNESFuDMR>qK zS7|SJ<7>-?Ckn&Znu;C@#1=%SmSd~F_^6lq_Y!b}MfF|y|BCKFaGU^n!n}-;$7!p` z)?OP3KmRRHvan&-RzcT~D~83r<&y8#PMQ}EOWygh?D;U42rOUWYPMhATT!EbaaC#v zr9TR$=k&$a_Niz5#>c8^Vq8wcdQnl(oH#{1SOSM`@`>V`t(_GvBzq77hRyR5J9DtE zZTWk@%ENf(I$L?#qkH49`}TET4E*;pUg2YCUGLPhpdWuJ zI-ur2u%t?nMS^wemaU}73JnrC=-01cS%0Ofno-X>4y>EeOD$ItBLA-bc>fJk6;Nim_1q-fJ>1L(C{3^AH>ErX~ zgKa7uvkclt8-EAi3j9}4FfhbI?dqi{QRv5q4&OwaXptgDjkt#sFK+xe^5n{wGjHzv zIrQk#r&F(ffT-19wit2e9%&aUWVw26Diy3N{~krZN-<*3D3c$RVabv;`I#JD4mJ^J_~kU>`0bxdh1 zf#%@>d!04uX82lqS|w{vsHmbRmJ4cIapFWOTc#43YHv4IgprQDT6{6a8Ed>T#~pk8 zF>yo@n@KS5y{8ByuOyFvq&)<)_|%`mxWohXvk^p-Z7W%QC}nPqKsCemq}=9}+Z`!ZUI(JkF8u+ZGT znJCkt%C>O3FS2?h#HYF%9LRwS|2{b3g&Tf2;)x4Y&XYA~wF)v>l|l_Qq?D2hGBS7N z2Od#Dt`sBjm81tAO9fM2kl0{rU0T>;Cv@-7L8I*!zm59)=w|^heV?|UcKYp2NH@H2a>*QXX9BwPl$+SLvzLa7aeK?E}4(bUBsBesxtFuasNVkk;bdZaU8>&w7QbT;B$ z=tYdG7fQO$fSy~TKwdA2(Vq%wu`D2$E>!rkilaXW6w5B$_DNb{mQ)T+&AM>CFEU1wP zQv9MCq&N@c%-{z^{Nezq=z|??21hrREIyH_Ml~qHkA3W88qRPAGS;yVc02ez=p z_@OMZY6_M9e3PR3bgqOH^r56$h(PO#&~-7UF$IzxLhj;1N7fCK0izPcq$iFJt(j6C+lDE)t5vNl(Y^Tt}hijK3` zqZ$Y31u0~f|1&cLiz`V%PXoOf3~+XC6$3d%Pu;Q(WOzea==euFzWNWXIyXfs?3VEm zNf1glk~Rm)YeMO|S0E@fLYIuwc>TH}#Pm)lkV;Etci2%+>4z;_8yiO!iyE;-YEj(c zhk4z?x+8XWC3XQus~k4C(fZONuxc%YBP`(wQ@FxBdF@)z5e#KEcf;$jM=j37o^c|> zxL-=eIFkaomvz$?eo%xWXu(#tu)`V8SjSqq>fCwkV;wf0hlEtv7Y`Q7A9LYuCi!~1 z*wpnS<0WsQ)Vmk(?sZTBM&jLWqS1{A*hF4Ko(~StysmvMdI!-jz$CjUiXu%x3q1e_ zubfhp|F|f$hnrEvV(O0vTe#1D{xhHhJz;YM1GX ze$XUOE-yoihF(gtLCS2|$7b+5ld_HE%Q#$YLbyg|=y68b0|A(0A6Zg@uoO-R^!jyyIt%`nqZ#`|<}hB4LIGYNab+anb_yFix5oVim!l zN+j0dVb?I%ANx2!Sna)zXZ*s(bcA&z3&!LT_9@GBK`2aq9pyX$_OQRRWM!=Fk}WI5 z|JlhyGt3t7)*-2A zO@3W$Ij`t3dleC7IHTC^W!vR253@%OFLSOP!!qc!XKTSdey6=0!;qkrKIZxj`)t`0^u7LAN_ z`@}pq1ef!%VZ%kioqxsG2W>pQY$hu9h|NZm7|Nci9efCgL&4v4S;YKN(Ybk^MNrKDEg=&&p%Vfcqez`N z?852=SFzy1mJ9-KkqI7%2{PP)9z;Sf{DLTu-9EIPJxo`toMBk`gO5FfJs@8Y0KzY% zK?u&-fzVw+K%aFy8F^LTlwF^Gy??|Lk3a7)W;s zp`I0C6>*-?B_ZfNAt;8TD30P5L0!2p6hpN`l~hA7bXYEA1LedbHP`|&Km#@S12iB5 z0C@vaRD(J&)EX+wgw$3rI6@kvK^&~YBy0f<6ho`*heGHfL6qQ*q#)n9#btz__6f!z zb_C*02g`Ltmkk65byAy!8|9hf2U(IOnj9P0iDS8nf&~-jq0i^N4=LuOKJFtwehfU~ zNh|$>I(QXQAj1aQ8&`3a+J)7q`2(WqqCv{th3rFFB}4K-0U)e`!L5QLoIzQLVAM!s zB>`b{{2Cw<$^i`GHpbu&2}w8_l<`aw3e{b)6$S@I8Du=jLb2I9|9Z+nxQa1oA{NzO z=iT3)O;JB4rBW^>Qxb_=`~_cJ2vq)tr#PI$A*8EJ9rhGMANY&}!GSZfg~vtX3GN{@ z0!a$?7oDhNA#!6&`p8QfL^(zV-ucdW9f+I3nem)Oq40%5xQb9}5m6Sz=QX8a9wuTY z=5g>tzCi*t)EDY~l$`_{6R8Ge3WgkB%K?zZKm@@ciDj-Ogkc5Ac!k+Y;zuPw8)+Eg zTUy6Uy4(!Z<>mQd?;OTIZUkW3)L|FElIR^W z-$wunpUjS*7=~p0Ad&z5i_0;tx644v6G&PKbWl1Sv{Y3-&_k|~?OvM*IvzwNPaET%28_e+9@|l%vljNOvaIwb9^csAY$M27F$DWsL$d zI0HjPYM~*+D}2TkOahb&M5(TV53uJXTpN;phDL5FP<#fqvZ`LVYDeH4tfH2zN{kZX zs=*#C!v0yxObIC%LKvn@D3F4LY};zA1vMaoW)g%xj6o;WskK&ysOD<|4oJU)t19QoPGW~;T|I{FqPJ$2oz`bIsarwX%3@vWx>u@j( zyre|Hrq)9gU4!;!!cHyKRxM8L0@j{`I3#Cr7R#GX20v)%0lY)Vg6w7D$H_)(*%pJx zZtTW-Y{!-@LzPR(`d6I!ptZ`x3wh(=ZL5V;!YBknASfefv_UR7!#dz>HLL|!RRSjn z?x+rFlhy&1(r2cc>ZJt&e(nU)a%p4u>q&emggtFh-kf+BhT%}O0o-tE*v~1b2ew)7B7IMte}o%cJ6E9(ICveNU3E7A%Mor zu0b1k0#CJtxn_kR3`D8^k(ADBsA^;&|I`6|{z8Acmk%&6P$(_venj~VArZRN=sHB6 znJ!YUuKw;X|8|T&Od;&9UL-u``O&R^1qR!O0w#n49OMBUghE*IL-PGD1y?WyFW;iD zE%I?J+{&%-ez2b???bUKBKB>0La#hbT%iFj`hvzPyh36F2cfG;M@E#QjPPt@f`KUojRR$%T?a0E5K< zTbJTo}e-4KYbLZ@?&|kNtu?|CCiPi~=FZ>l*xkh*;$#|H3>NUnwA-4@|-@xZsff z!sgmU=dvndl*k*T3M;p=E88y=1!bR+uI4#t7T+>1=W>i73n@SXu>2|k4+P~%;C*~3 z93L|>r||=WEGXmwvK_#k;xT6ygfxdBNpx%-SF<4faR-}i$r1+lb>CuLK_H+8Y4`)h zP2BK}YvcsODy+d3RPrUG8t=iDX@GJ{E{`LSa!#x-aR5P2+QusnG(kIrK-9<-PZ;T< z&yARtEahcq%5Ly7Ri@4`gy+DDx@2uEPE zHcK-c#O)xvWjM!@C>?1X|A597M9w<&^g5UwIw%u5EW;}VLm=e9XLLe4twTKnnZvcy z0SvAVBOX5EgbyIWKLY_vfhkJp20;{ELZ^f*Uy&4-E*0mmM5nb{uQf}M!jw>hIQYXm z0OLllo?|}TMT4|R?==m8f@;7;Afsqa054_{GTXkiHhXNzLXXNNvbX+GC4X`cU+*=% zh~j3LF1CUv_yCbk0^sT*I>>`Mc*D5<11I=VC6hCdTJ@?1#b+fLSF?my55%fm0{xc6 z4jjNGR77mYPgxs;gP}EB4>xfa_d%$`E@*8Mk-j* z(E;RwDttyDpeydn8h_5NPcKZSWf|Z+2%=Q6*b#EI4MEu5t%g=8|ZNVBh zhj;i||Hc&hs?~Kd&ve8wAHW)CH$ucT+iG`95Vkljii?MYc?Urb+&GS-w|bLod-Lr# z673oU`BaP28W6&2x*AY~u!mOL%VV z0R39{Fztp}H}ofZxSFqd|FXptUMPmL9*F~s>4bzDFW-zGMBIYHKCMLW<~f^an_G}~ zO#Cj6A3CDvfR3-Xh5z)ps*2KkUle`kP{8z*R-Hvc?kwP8xFswivg>x4RNu=@eZDvQrbXx$ju^&4& zyREV>J3oO0pci_YB)YUG`l6RC*c1dtVLQzE?L@yR1z|r4g{Z%1flCh z5Ddh$M|`3mKzcK}c!o_rDkPpI#N()t6sCx^NR<*BrLLRk2P z<4=Z1Z57+Q&HvwgQu=zzR5U3J1g}TXNW}5BNH8@|XF?c!gCIOgZnv5=d%-`v!$ZA6 zVD*iUfy7IEwevW}=hxxQXqRnGxPw${e#9xecHU4#bwIfNy+NuY#Jkg!nWMYZ;ym5g zJt=^mgjy+E7^z;8>#9|XY{1kxwH(kncD^!Y{%eoja|LX1H{+&B_k{j^j3 zj%z)+BgD%BV~D(<#q&cql6}eR#L2f5kIXi2z^{VhRNMpi+}pkE&;I_gUf!>1uKV)e z=fSUIcfL4dM^LbMKcex1!nLTh(<{8kM!iBv{z6#2bKu`w|CRB*<-$I89`SAl)P~gLb#o#0aRSZ-{iyuKQgfkM<#$v_%Vfy#47$%o( zJboNwaZC=IH*x0FnFCWLO#UJU70SzmoaD7yqR-n&vwh{5v?a-B2v3fpN6#LE{#wKC90)J@!;NwaApUo z4gWDAZijF-?p8YzxJjT`BVHxC&nWZcE-|%fGxH&mhc$O*&)LSMa^ypiDt!o*ywget z-Y%?q;CoQ5OnrPlAeO8@!1DL9eUo>t{rmUV-hT)ZfVkV+~EB;rg$ zsl6YC@@F4@_8F3_BK`S?pLh53pe73z=8Ht}?5KsX&bFcUZO3{=oT2`$vnLlI3>(M1>CkpIJk zAc18U5rK;7D-&Hz5w8^o67H+GZc}JBOA*3tpshfWsJN4S)DkOTVAX^T>CQ}QD(`|4 za;PGiTWKXHp_48oB&@WOJ4|r>F}yCnBrhpB)%&r`1J3j;O<)YX6Hm6Z^@>jP=IWMF z3Aw$5&%pc{4A61eZP(p*;f+_`dFidUFb+q9lv3u3ISbRbG}Vh!-Pl7bsE!h%F}-4L zO!!nDSv}5Gpfxs3$aWUjpEodLI)7}XEBG96u5?os9sj05o>Z`HNTK{W=9L4tl zJ;VUTo}&0+>CzS(3V5%92?mQFj1B;fqk~300B#<81lUz2BdQoZi1^0pV$QD3_E7y2i)$`ph~8Sj9o}#{ zX#@##-S*pY&t3Q3dGGzBa=yk_G%*a4`0cG|fFo@g6Jy)c^&C3hp^`WX0%Ct!oj54J zF$O{tiw6&X@Qw{HA55u|5;-Vdiwu&;BL5MxD3Mn_AP1N)$7yEmcRrvEk9GFBvVCWC zmr0W*s^X7x6{=juaNq+W_`t6q4P12b-DdXmGz6{df*thW2SFG@5&w=bGr}X@K#DOG zPc0;Q%OllcoEH-5m12r)9}S6YCxhHE zFd>Wcz#)J7%bcrrrj%xRE?O%=P5~uzzyvOkP<}Dv8PS+VG`@k2ZFJ)S%w-=ER;GbT zd&{5Zm`6SCk&k`!qw6@d1d3$OAFp|cYhcqa$Hb6lZ?j>0Vzj+j?J$Uy6e2%>NJNVO z;b&<%;wO`sKAJI(C?+eL{Em_hghZzeRotKExCACKv1dJ?^Wspz=os(SXI^Ub6 zfY`CFb$`rDxt^A;+8L9X&2;87p&3ojh(?gJ$==&Yb)rN{X8&Ltc^t|nrb9Md%wjyW zWF;LkPK!MxO^ErV5kq;a9{~j@jzd|$R#vQIRl<0XTozO+p^4~~?Uq8xWny+&%Kd!s zj0hnRffkyW*clUZzv?IkC1u=xhJtQJFomvLY9>#bwbOQ1&zo- z`I6A0L{x+gh2ujD!>zJ76L#j(;6*!{R<*8`t!>Sk7!cA;tQVf&{h*W+Okjy-5lKjTe&{`c z#t57S9qnGUDn~vxG4h-R`zRdccFIIF%}_C{k^UQRy|I zcK}$$)Q5kyWIDfx)sGZ*Aqbq<4F{MN#d1klig_%~BD*W2mhu2joF5b?*Gi}6D!H(+ zSjFT-(9&M@w05CS0*eVkueSCQT>XmC3}iuQ!d6>%o zFmgjK#k%KQ=YHjf^$iJi5n^4TAeO!Tbf1zC+gQhbw^^Y)08!l+l+QZxS5Wi`vM`ZC z<3&rx5NWAPWu+Fe6il{c4dz#6w-o@_Nx;#pX#dgiAKI-qB~yX<-D6qFsE}bq`O1~H^rbP)$8ms!ZN-=`g}-v#Fz-}WWZoER&-@Ub zVzR@n9^DRM&4!&-h1QYOo}3j_=kmB1#(#zlNQUBP&;Gcjf@Z^-g;r#avi70=U9ug^ z;$LY(T7w7RV5YI1ZEbHGcfn-{VnO{I3y+!~%k}GXPpz0Te?-Kfd#Xi7C*Iw8n8 z#+)0ZYgvlY*PohigyZe2s~+1Sr5oC95&sQV)NLhPYTW@G<${oFbDQE7xA?^sl^YaU zteG$f8#RZ z%w_sRSmC_Q@a8!t=Yv4>M0&Spbaa5n+SdIbUCK`P``-Z{c*S&TdxE>U*F#=TGB+rQ z$0m2^#9_tZ)H1Pv`J zN%$Jc^ZxAkWJoEdLiy^2|L(&7{_lGvuRp@&?wqXj3Zvl?j0Pic2YIjunF$VRNmeef zD4M|&d_iJXqA0j-a5(UL$PMm+??8pG6n?;i-n7-WzD z7jW5j!22RDPEc>R&d>+pF#itakc6zKmV$%`=U@(wu)UH{Vnom~G9~~g1}{Re-o^wg zWC%9qY_YnqlPsf$Sjrg8h(OA41|6;~76S(vObxAV4n6S`L2+u@=9Y}28RkF;^l-3Rm$M zo`Rnw3?gpEDSXi%#3LAok#t6DCH4cDC@~rRW7^6p(aa@+5K@BHkjWa2;s`?rt}!Ad zav~X|MZPJ1Oi>6lQvVO9u*X)>6Pke)O>2kvB4gn1)(#O0)sbW3G4fyo9sx>Dl!ObT z;v>QY9}z_uweGaUa3O$cq6BgvnF*MPvMA4}wHor$IPm}=k|Le*DWTFa(55PUB_lPm z8{==FhK)TuArHlI9Q%gzDu$=VlBZnF32zMx8%bykV`IKV9(e{P&j%s0Ce>`(j(QwixOfouktI6 z;se1V5YKTadi9Glq;I@(Um@At(pa z%8t@75##7|(Eo$n;v*2#F_m*U7ZVXnNi!?6-{vH3XbB;Ffig9cGh0z5LxP+_Q!US8 z;L@z82vIg$Q$5O#b9OD1M20FtCLcfMBWm+P_Hi?CO2U@%A$T*kWN;ZT&F;*l0QrI~ z+OU~M?;)8pK@~I&hS6i- z66O>_I&`MjvMVCAke{X{KJ#*OCge78Q)o)_E_l;7ixc4{(Y16G6Dz1kKWL#2lqnZ9 zNtF}=rB0{bVloe455aTnkmEurQ#<{T2^Zq|oRBXxbSq3!L@(y|5Mr>r z+Jo(2)Bo~hls1zO-vGo5`|{hIaV>rc8I#dJEv=!16D?qiA&C@(_QU%S1WA{4Q5jY6 zXiW(t6g&m!8~K47trSDSviY2As)8*%rBf|J^oLZ8JzWz$((*g#6l7qu9&NM|_$L3_ zbFmn!yEMa2t;H`DV@Cz@H-Ym<{Zz?>lu!#bgpSi9Hb^lWHCdHa+p;nVrPOU~EhsGY zQZcnNugd?X%3wT8OIxrFG~p^(luFZ*O_MK9AL32b(^f&orCxP_Pz)>DbGvLtMct`B zaT8Y^V^8C#PX+W({er*5C0P3;+B&LOA3|M_by*d5VHfNoTW%g-u91XdTB)^Kw^N{8 zu>a=1;;Iw^oz5aD-YmPKwNni-T2#Y)7KVmR+AYmD{X`Obh-XiRHLsE&)7l5HF=Kvup7CW(2 zLo-&oR*}#kaZ4S-Wg&^)O1Aza6=hrYu>Q==!tUQnj40?fEArxIJL5k8AwL&GU&(M+ zf7a-HwEz#WXqAnlkTGeQl4+l|aUJ)W;>TfIZtN1mYJDLOg#aYB_DVC9V>=dG56W|+ zP;kg+A)4Ym_~tNNbSv1l4RB?7=uPb6mgVg2Zte9(zpXQPmOt$za0Pcycr_#nl>ei~ zknN83agjH9`6zOe#3)dP`bINKvDQkrVskeWEV(lwTu`(=v;_^vRSjcxZFV-LqMzo` z3gdPj#ZGM%2&eTd7}$Zamln&k_X@*I%O^}yS1rWX ze-=xGO*FpHu`u{SghS$XGsAmK7(!CmXM43k(t~mbHh9@8acS6wb9jx}IR9RhaT(vh zm-sXp9at@f_<_GPf<5*z$_IR-1^H?geU_z&oQ0~s?ksffitiRba#O-iI5Kz^PWW|x z8L(SqQh1Gaw~E(Tm6mba_>)07PvY1pe>5oT7%lF&h~+PQ3`2|06lXvd*gDdJK|)r4 zYKqB~WWD7Iu^1%OHE$y^L%z5Y&DgC5)hkAiP!%j7IXN*sIh3I}njM6c)hIA45r~D@ zdWqOt!x9AVlQR04jAP_~Y}6vcB#Ov>@LSCe~_?GW~vrMaLDS~IBGZ%x?~z#^54*oYUyl?mBI{g`Kzum3#2;+)HboC}#k zbr~*lk8c9mmnHfU<(GkcNp`@P0b4lx`uVdmIl=fejn(*|ZThC^7mW@eq3!N(>6oFt z!lAi&;2v}S*+L7BOrR!p=F-l+!V~k;X`>HH3AL3Zc8m%>ZvtMhi2P7!{p)21Su0fI&jR$P; zV~Ndnq+RAdUN>_(Xx& z$kLekVE?41IXk+gJ4n}hjw|t$Eds7lQLY6IqR}F^HTZj38!VE#WntSeaL7g5u@aIG z7{NO-Y-(@qg|U6RKUVlZ2@JRy%!g?@v#0yN0lY6f`!5#yBeXlNJ2#JW4QIS-i$a!a z;SC}xp(_;Yr*1MI-y1UM8DgjA7>CZW@muxu` zvr~MH3Y{K^IW)j_$%13DRD{L8g_n}>RxF3&_e zE0?9SN!~nNO*dyW!5?x-L@%S$c_+#3S17S9Xb(WtO%5vejZu*@HWcl5B^WyvbYGX<+_o zw*Hx}{lsgStkHh*Z}{Q&72MmNf#(2^g(Aq|1(qq-$A>*m>r*TOi>KOY#6EcSpLfoU zY>l#h<+lxWvOWPDADSMY>?42SDZlrfR{!lW{{RwQTIdDz*WIq4V&?St*lx}{p_lb% zS0TdQcB=V4LjCaZyEi!;hNmBdtl7_-wnlk6)XJ zJ`4i+3mC}2znTuTtWbPQEz9d01<|PUB?zp9PUWlcaV+P zA(e}rH+_2Wis z?UUStb|Sc7o_ekcs7Qhm*49ajmU{-t zroo4rYV+|+aKQ#2jIeFkPV@o~V{r1%w*06n5V#78YotHrPMhw!A!(;5WeG3k>y=yu zJF>m^DufZe0vQ8y%>RonI@!J{&y;FGId$sk%|8DObkIUq)nmgv9DQ^r#7N9)iWVP- zv2y;*N^Qr5M%1oAHrYIMOjm`-Xh&Rk?ezhQ9w02)Ct%a!46)NV#2O*jvoaKdz}m3#|s)D1pJqlG`+$_A9?9i-LRcAJ-NXIr7XIZSB} zwQ|DD#wYN=p|8$*>#jG1cisZdelpC8`VF|(6b)W@?}yL1kE(UPiYK`c_F2@enq245 zB~~HiZ)LBC^!2avPA}39TANMNi9q|S=|Io+jD7j$pKrRNw6D+p?0sVtdq}+ZPQSyP z5EF4ns|G*3o&Uv4y{G+1jws4wop8F?+B=)>8kn%05hN$6 zBi{r+2*MDi32%Fw-7tpXh7_hIH76WK{@Mq_&rt?`4ym6FlZLph?2jK0V%(4%cNl*_ zE?NalNO}zNJcE=*b0934=fs9V5LzaR-q9Z2G&qo*!A*o*?4lR@^9Gm+=!81q8Qjj; z6BVv76DNFO4A)1)h1}4FzuQ*uSh6@f6)8^}W6!ygqCCVDL^~8zph31aIxkiafmr&Y z5)XhtloV?vWMfvdIJHGbYI2jDYz+y2bHWs&ag?MiWg6AULKnV~E1c-W7!)$c`aR5z zs+t%cEC1m?AhKm@0VK~Km!iCaP;nqhEJ)^ti9QI1jc?NHB=xL_kY)+Zk^wuTGp~uw zYz`%iCF}?a&1lMSic_2^bi*1|3B$v^5+SjqpVAU1L|p!mK~kfWvYb?yfglr!h7{)Q z64}K?K9M6#>|#cs$xjSQb7-kL76+}V&4@~LqV5SJC{Z}hjB0eFXEY}pX*oM$9PS|P z^j!{hxDSE!P)K_;-msqZlVTEtft^&QygCB9Y$Egkr8{3kH~6+pQgo<9-K18!xsh*j zbg4{TsyR223|q2Kq?|BFNeNd+l)k8c#`&Le`Y0+Ouz?_vd{aLM@-O(sZmj@4pFkrB z#s7#}#(Pr4qO*dkx}xfJujbp^-a@(2h%|MutAT+G4!Z_UKvk;iqbfnJinNE}Plw#% zpFCkjPjZn;FatSaOwX#VjewMWGAr%-{8rF{+4QE&Y-<;{lUjuAbZ*q#R0loC*WBuM zZd*~RIEO-5QyTWL#4WC3qY6V}P<0HDMOs!lf*4jEV5P7c*W-?dnE}QH2*Bv9YiDv5 zvvFm#tDN0F36>QLF4HCFHQx>v6){cz)V2`at$pw7v!sF(jhETzaEl9I04tUgcT6rZ z1TqHZw)45rz2gD6dNJ#^g_qc6Q$Du`DOCN2yyYcm-Buf!t;Du`bam!@1)@cv;{SKW zEUp$tO<9{W{x`rh4sc=@TVARz?uN76)&ZIZ;p1esLA~4@subeck(8Bg>Ftn++Z(!` zc1DwIYg-oa3au7vdCQ?<1o`$vBW@b45fPj9V@tS@3gXXUDZ_yA7+Sl^VLE- zOOiVqxgz_LpaV;6L_L4dlE)ffmbr}RL~Dt^`4O|DYkXr)n3;A2VHGEi!HG3H_oO#L za~{v))x&@lM`J~6RK7+tK_^)~P#zkHKi5nW&z2$abtL$#d{;&*de^*WQC`2ykVgyK z#si-8hF2m|O&gBW0Nd(ip(f|$!A> zPGh}inAFO3%NbvBzX|6=3-_&g>kt^Jv3v-V# z2d5O0r>x2Jmi5U-7B@mB?nOe|7MvU}y3r9P1E7Rl-ij@GLGFn1WlQGATkS-I`3Uo% zVLO^P=k_KWo~4HuJY`ar$v=Q@Q1#*Z0EWix(ccbtQ6>E-OMi6J?fvwPpuERz^R(5E z6K%K1t>#}+_&>4fZS^j5#OO7fX-(VVtxTNptxGq3*&X-HYd%dyfd5L}YkYUShv$yV z$aK<{=H`_4(B;aZ^GJ{&no_^)HCtB?LXL@eK8HQ7gJ!GmTNYw}%o>E2zxaMPkNo7{ zs3%46_*6b`+)V`UARQrw>03GV;7$L*YQcJYs9mLobMBD9&;3Nc4Q|RiFmII^KC#?i zFG8yu<8D{J{qJ8MG{V67ae=-JnofPy*9ixJeJa;)DfM8>AS*@oGqtA>E+JD|lPM5a zQxst{Ja>0(NQF_6QTvw} zEGT`H!VxFe3H|^v2H0;rbc1@5bqPaw4-tW8b9mbLS+4x3?u@-reC(GkW^^t}= z(u+YDQN5vfVWWNyb<jM=v5$y2l;lN}(8U%4 z85O_?8_d{&h7?*HCLoVjTBxO$YLkhYXq7%Sfu<1>Hn}5(aw zmLPR@FJzLkXB0BmgS^sk-DH=MCt@FVepGo=>i_t4VRQiI1`_R8c@>Fw^GJ`237hxV zn2s5g()SyuIhm4|n^V&kO8FCPa71z$Dh25oo@rjJbB(s8;_}SxVf96HJQrcmO(La0;w zJzn{YqvW3-YIHw&8}eoXJ&_tW)maCsqT(4sHFsy$c1_6%homWMSc94@bDxFDn)X(m zAnK#;CZZ!MW-u^HCpum#x}t26lqMl_5dZoqxrlIs^bqwKjG?)36zX2BhM~|SoOLsu zEYXLj_@iUmVzb#C0Y;?Zlp2zOqzBrY3c3)O*`?Exo-dlAIVYjYd5NxLp;*(Phcu`7 zxual8fBZ?NhpJm4>G`LF1f$MmrONr2Xc(wSwx#+M zs`!aiJX)wyh^VVtR2$WN-QfZQu~d%A5s+G-Yq6vaQJ!c+Hc-lS2az6B%0)6-grACD zPCB3RLaJQ!rMX5*tO~8U1)#SPs|PWwna~lo8lLvL_h8cS(UP-9?rK%unv|Qw0twE$DVY2zEt(pJ~ z>0u0|8jgwg5J|X_bVyNodaw}{J$1;l6QKo?Fblsh3#&i|O>nW2@C%aA1QTHgzaY1B z`wMnJ5lvtRt1t_*APM}`1Z-;uYFjFX**32Enn#PcU6iz!v9znWQI4vumfAYsN{K58 zvoWhV@R?0P2)1Iow~_$5tN&29yhsLR+qXMl1Y`@kb^yAzPzuiTw|on_d#eS>Xasg} z0Bt)hU&<1Oo4CJ=v>ElPRMEIUaj)2lq$^>ppxUy(su}%+kXvi8aJanX!$3Pgwt;&C zF;KdzU<3)I1$xW3Z;QRNP`fw#4v}#Qr7*q%K?bXUy9xBZdrJn^va!A8yTGfz=;Nx| znG|VS6vsQ6+Q>|k+r0j|5aA_(G^$h68-Ue|Js8mowvYxC5x%RSwiA)Mzwo|p8!6`7 z8{shz2M`RUP!U=nxEj0)Xj`{}>n=jehpAe$`%A-gBeMT{xJGfW$pA+Li;DnT62)}6 z@Mjgi`kPzS}VPoyQdY{1X@rE!GH{}>$z?lz8)OAk|4UX zkPGNA5B`7-&L9xa5Db2-1>ZXnr7Hc-}E z#LAM3awxWZ=O&Fbdvq0LZWp=m5>$U=RPW58eZ8rK+vU-#1*~CY9qA%u+i`8(N%3N z8a2Ep0R!Od8smho;_=R)lB08JNO7pJQCU+nS9oE)lq)$AYmV=Bz}I^n$$Oi-W?R1$Njrv{!&dFsSAB*4>kyLt8shZTjg*j;xHp|i zI}UqVxc^gUmXVo|#H+!Wx`BJM*vr8HUCf63xpvzGg%C3SU=M=b*VTXw=#W4A;0#Ia z4bM;wz?}-BOU#L_qu9*YkFDJ9GRl;V5NnJZ@&G)&2`lsEjw_w zWMI#~%(k`b!oN(+ZyUwEoDvO<49H*)4Sme&;1BK%-~C2)4js5uJ2Lm{P07970Uj;Q z{SeU29bQe&z;e=#)Ns`DV&1^wn~>67nbBM^)l@CuIld+!{oIY6e`-42U>&1C?BEZMc-yu* z|NpGFbM3YV0n7sNw|eWx&Y;lYfezKM;>bYdiyT1?UFBG7y@R?DWL(BNZsw1|;{##f z_F>sUj@ir!#F?s|dDfy8Zp3tB1beInD4Y;Rz~=^U&8b zHRG(qyZ*q~K7QtvzG%X$f@_{1(!D?q%np?p9RmS<>X{S6SouOSCvn>(L$| z8l@v`4o9TUyz)86qP`H={xhlmI@@zIw>#iT+6eiaG#@?=47XLWf z&ElNwz9r&L63K3#V=bLxF6r*d(fCgA_)+GyZc3N!XDu4%6fULP-eTa6hS@!oc*hdu zPJ94A=>^a6?LP4DZc4ju(h~o#`aX$xHrl&Im{3je>qAQ#%0*G#vAWjrHP0TnjwY6! z;BVe-ed@e3)a#o|+ER4ZvBR*a<=Hm@wBR)|VvO$YZu3!3Q9yp}zTWUx8!1CfR2gw@ zE00Z_o7( zKS8>l2_Shg3yz#u53U!R_3OM>Tz~4N?X`!uhIHKTWM3*#9q>>O_?!PlYX7?PjY9G$ z4fhEw_rI81j?Xe&DObNZS4&?-jxP4`ckUc<<9^Tix8FKcAMf6Jem$7-IlK5lFZ81w zES4YUdph|EoJc;+P#Q18wvYSKUpGKb_!!8ih>u}+SczJ{_0O65#vkT06!!iu?#$mc zeE(b0um0r|@`K;mhToppKN318{9ms=2c(*-Z#%6Iv_20Imv#)?alqg~gb5WcWZ2N* zLx>S2PNZ1zz?(~#{B7je(O;%aIz)~nInv@ulqprNWZBZ?OPDcb&ZJq>=1rVAb?)TZ z)8|j1FG~(}lWEvLk4Z1R3EI?YOM*Kt$&6YsqrZ$#wQl8_aH_wD8UF`%C0q99)vO1q zDjW+@AVITngJLw6wBs<4L-oq#+t=@3z<~u1CS2I?VW4_Tf;?ciV_L+KPez?Ovnocc zl_hVEOBZZIV^a%qCLJ_m=*nx=j*j@YZE4sCPdna-*Nx(mv32j}-P`wX;K7CG#66NR z?TwI!BaUiw?dhe5JJslpj@InkT)Nn)j*emKN z$$hy{=`>`p{ zXu~Tc3XgR1NhqU~a>|q_G%7{fl%tZlfi&s}%Mim9Gr%o#+OZ+*$}DULrchLfNQWF$ z)67fiQZkeE*qd`tKKu0Z&)DwEq%q{Q1e7m=zC!4qo3J|6rZXAp(Z@%f>hAzX-*n5! zN@0r7F7+s^uv1b?HT6_fDH7D6{K!nz(k>6O&dpc-igckgYu!nzhB6%zPOmuC^`uXe zny|@XlT~(EW-s(`P(riBvDupvO^88*d}Ya>X{oI!Nzj(M)LWH!eTdc}(G-?khmuT> zNo3iTcV2qy1?)Z$3w70AmaNq@TW$H>=~jiXqf}tFcK;A^qJUY&bzOuFa@Q`~L>)C^ zj5F4FV^xb|ELyt^KPo}%}`s+iBD~eUxyaOAdq?P`R z>a#5Z_i4BgHrFMa!Md7djJ$l;;`!zLIEsU`>P$R>EZys0JeZF!2yk$f$x~i~;3ind;4sq+xiBEt7Bw$PgcND@s#$+5j9?8OU zfVxCSe6v}ZK_;cYvvo&;;DH`W^7pEVfy#3MEMN&uctVJH41uN#S_2(87WOUhcke4$ z{6d$YgQ#YI*V7dR9mBicp-_lJG$HxO7BU%PEPdsA;EFZ~K6g3KhM(hEaeTRkD}Fjg10~;_LWF#TcSZbN>xVqd~N&tPmP&gna~LCp~#K6%x`h?c>)H zT|yA1II&y7i;(jm*TJvl4K9lTY`j^Hw#xx$yJgn$0ViiCg#Xm{!Nz3$=^C<15IjW(j&a=r9Lfs z(OU5nfn`KyDFr%EUUl@GdaK|C9qKh_KJ%mxo#(P7s(9y^K{ReMpdd?y6LZqcE;sBFgf;%5&dlBH(jO^ zjtULZn~=)9Y0j&fc(T~VrutU6{-~tZ zIigd*nX)mMg4EAGl}@FubYvf;Eki0OTHQ8ltud|WYK?nb(kZ5!Wi;nq_f@-?oK<6+ z73xrB{W)ZmSTJ9!|HQ6|8j?TTiw& zmc0ArFJdG+IM;5~ckBI?VgJJyLe6$piNQsg((Y(qdX<)Y#4T=rEqr0VaC4(M1*q3} zdo6#ocX{tkh)Ef|)AT~bzz#b=cQdBTq%5he?ZI%3ZOj$(g7}*qJ{o}+av~EVxVj3S zmmTS*HWzE`yEDFVlb!sN99y+;DV8sf^J+p8BP3=JPS%3<8Y0`hcCc7$swTlp!Y8L$ z%`o||j{nKH4?85pxEiTP5=`V=ewlK5O$rBN$vMXAcg=$)v`Un_;RM1KXmOTvZwmV7K*!F<-EwM%bf1qzT4S#YA&XY zS((r{{8hvCG{s$RW4$cbwIyfSzb6uKjWaHjL!LI++AZy+%JzDh?$fpT_Hv~2H|FO} zbk5~vb9|z^#K0x`$QC-Sg}ZZKLvPk%C6r%mCtd8T)itBcmcg$@D>lf z>Kvm>MzB6fAOE*l<;jA0y-_=Mz^gXqh$bAyqvk57vqj)2)EUo3Zrh?J1dn;Q52M%FM;QLT$gUvj?g@uiI>QC;`!*0Pd(&w-`Ld?mcP?qC*JHb`q4Xo`@BnS6YiYZ%?4WCu^JWM%ii)Xtvyt6|9pKCh3SOrx3{1k)y8XC-H-R#&*3>+iO9WP zefKntp?`jD4nAN?A^q}DfC3W4p9ClXp77B+`_Q?5T+*%l@~MS+m@2}$2{0`eFA^|E;1Wm{TPsoExfP);|!5ypw9pphqV1!;khjmy7>u3>T z7zSJzhGB3b8QFwV7=?r|0xifwEocJCYXU9Y!aO24ju^h4^RTH9F}P!?tRt7^3ojUa zLm`sBAA2+Ki9Ze4fDJ$bLlD9sZoREs8%gjG0zSuhAL;g`d zg#QDO1Z_MBF5Ce-n1xl41TwIL1NeoA62pR{Iub0URT8mBG`KZN$b*B7gic6>U?>GeK*&o-##FckLRtrBKn7%pMue~j zZ*Yc-97MGsg9BIvQapf8w1XYE#9ttTCMbxL>_p*OK{8y&B1=A4OoIuFvx-|NFhAPgVcmnScOv9Lq)g-Z}^33FiUj!41chP zYCr~Wct%Mmh#gpkS%6D}Fak|%f=fIA*xUh7WJ!C;nwiAQE>ploQJlELKe}r}SsYB{ z{F{=PEN`nmfk6SqRLaKOfFN*88h}j6e9FnJghB|0ROkeRgo9EDhG(z`i`2-*c*be~ zi(p90g2+U)(L^oC4kKs+JNO0ojF=F#pb`AQSE0O!xJgvp9NGCg0UW^OOwhIoO2Q)= zevBCCTuh{F%<9C$3T;dph)hg?1gCt3SqO%P+`+13$aN@7u>=c$Sci<12mgQYhFOq= z8#n;jTm_g^i&glAk|YDyG)Hr^x_RtP|16a*>9dpAOTBYNjNu}BJ5U5wP$xZ_pq#-e z8#_=Qy11cJ{h7ivOp&q| z_><5q#lubARO2Sc1ufgi7#EPhdz8T?G*RgS|*F*>| zoP{P3$+S(~*LVOHyrJmR~#tep}7G%c{JM~)3!gsIf#1Wr=X zfPb7$lU3PoP1%wy*A0*aN8nO(tpqZ~gi8R4O#q3jbcWPihyTMM*%|+)-FdV%S*nDjJEA*J6lxtRqJC6D0-AuoGL;B^RR%(`Ns-H z*|&vV+pXQ%?E=@F1Uqm9P)r3+Ajsg2N_It0*|5!^Z82l0hF}OsOsrE~4Mj;0>irWXOf%Wr#lIMq6lC5YxxM zsY?-x#c4HRFE*9br7WUkU9<&Pwyj;-ePOsI*DM8s+kIoYHCKe>P)_g!vdp3SWDDAS zgHceWfv8W~q)h?3V0et;>@`6ds^b2@Txu%cN9E$<{9;MADUuLMe_GuqX<<*5;WTFB z7*=C6=F}XZ0jHcyI0zU+YTBzfQpQ76C^qE2*hT&W&}h=s8)820fw&{ShND<9z;Tdj{!o9c7orgnu^M zu+Rur4!&Hr8e1l3dXZ&!>p4bdm-LBfoW>H;jbw}N=^O!Owc))ei2;ue>5#5xkp^WN zh=gY3Ka>dQS8C;gE@UhYnr{Z@m8$808jYOJXWs4g$6| zYLLc5o>*mUW@!E&;pAoujywaomQ8`>|HLkco&$sM1i~(C ziM5W2rf9{!ZD*=)kbk`-6YwqM%CY^65p4QSe)fa-w;o6>sasxCf~ zd!9y=&Nz;vVkd9#;_`SO58@?EA*U8z|VP@DhM|$BLlZS%VRj_LlA8&qBrP zpJ@wsWJL_#+A@h76cOx(@PuaI2g?a>gxG0bzHlgy4;0n_T|lD0@WVV1a5eGG{_qo5 zary@F%r@~5$8s8=&<$|$tx)OUOvC63njGI|(oV(lFw&|Cavq-(z?Snl_-^D_2q!nc zDF1UQZ|8l}vEG)B$j0*e_VO`5an0WBMK^IV=W;N|Lo+|~x=;v0s)_cay#a@yaei*= z!=4|f=9E+LKDl%5mIw$Bk%q7*+Xi%4hY$4DM-GRLLr3uwuWv{nZno~y_TF_c|MD%D z3mC_ATXkxR*!26VYnS%#uYsje2S5M6UT`Brk?x)dJr6ysQ1c0U^;rLQ_n39itM$z| z^b}|G5SR2|SM(7VaY@H-z9{yE$npBm0l!*3& zrgoG829-c^CI2U>s1vhRc$*J&9dKt5EA-fq?2FfU6=!SWhV(9__(tz?%`S7m`0R6` z=J7bUd;fHpew20m@s$S@RA-4iAEj3k8DzhCu=fpd*Rh8e3=*e!b?;=Z(#UW*JL}$vcriD6 zqaS(|r}!)vb`Wpz!kGK)a{7M(A1-opz_*vaPYOlly()GR21gMGhly#`(U+IfkJwQPkknVB;aL5EpNYbM zjOeF*?GF?|-)%zS`NH5--miS$@BQExb`7X>!@!KMZ!l_B_O=Oqe9w1pY5r!V!v__y>Rhc3>dEf(8#FJm{$zKYtD%Ub?hnN5YC0FJjE7aU;i$9zTK%DRLyqk|s~0 zOsR4u%a$%*!i*_%Ce8nvA$8!)H0)nRh;MAh+(2U}(V|9=A`LQB>Cp`+fU>;g5ad6e z2mDQ>2z4vht|}uw3>)@fXPD z4=;W^`SRwyYv%0PAL!vPUXV^LfBsOXt;fd>`R0<_18;(#7hp}h)iuy>(@`g&f*tM0 zpK};RClZ1QemDQob5(g#6L(WB*rA6Xf*7KRBa-+MPHuE&kwaxYhuaG`lt!P7^`U^m z3+Lr05?HlmRicj`?Pm;cvavWJg+F!}WP29%1(JmmhG!u`|1<;CcD*5)rIuTA*`=3X zW~Kv*JE_QCi?6{KMLK>;0lTw;cdMWnAUZ9x4_reA#3O~U;dSH{)DLU9ch1FWDvBx5ttg?^gglR&bZED#Ko^Ien4n&EXEm1kl zu)zkWhM50qNpudnEO~kA>FadnVy5JSy8>tsuLm9aYi{#0IxM^U^4qV!|N48Pv(J{r zX$&u*z}f~p2z4zDIe5FUsjj^_qPQikI;*Y#dj~6Tvi{d6$BzM;>&A8NaAraEmV23$ z`Bpiy%rnzmv&{+$OlGFYb45+Q zoDj<`Q#R3*0!hsUZ7f4vp1SI* zvwr_<<0=;1`bLu{EtR^md!>1I>LQB!NmU0vkkE;xdfy^Nvn%QN4+^9zcplU2`} z`MhpIF8WgCb6fvaoOf$Hc=sFiEw9wY6U2MzjAc#b`0v9Xzx-_Fq;pS?kFR!2axXpq z@8743bp7)my=W(3(Oz_U#R~P zEJg7z$@@o!ylBTe;xTOXbK^lan8%C6X-d-*qe{$}KL93%gX@bQz6`=gjBK!kTuIrK zV)n;NVltELs^Ja$h(ArH?;! zrI-U;9wj@XOa-pdCip^~G~4OUcM8Z22e99>K6%Nb0dq>f91=$za+e{+ktPUzU_(o4(v$y2hLijR zWke;qPiS6rDgaF<>pE&vkAl>Ei(JVp&xz8X0yU^YO`0e(;>LX16OS>~lm}~i)2I65 zqv8A;2wURJp<*?wT3v}e>3Pfj6xFB`Er>V02u`u6k*0|g5>(qNRbpOkoFi%Eu!OMH zyW%yk9;u-;zh_Q^Ohsz_?5H^9DmJ#ZHL+0@3kD0a#JM808A6z>UMp+a%YLLbUTmpG zXo<3_g7U0kQDsKWcB?YFMX?=ytJSCqS|>FS7?Yi?T`_Ch+v0X0*SsQUJNu7wEaXF}U%SZJG9b*bAg|ww@ZmVnElOok1Wu0Jew`jo6?lk|8q9vvx!y7^1 zZ3MapLEr)AFx}~1H@@<9r&kf8S&MczBd~f=SySScPanINLe%-KNrXCyWsV- zh4FbeDVG+<%CRzmC!J?5?>W=5p0(#TjgeWMx6nx)30M#<;~94p)lst|dgHngS5vyu zwWT$)n@zSc-35>mfgqZB*yIBmR=lSEScXY0%vG;9Fvmu=o-6I_bEEra(z`XE&KxH> z&q>sYR_dZh>z_vN@X>Sba7B=fXIRHN-2xx@zie%hPMeu|v|CB#=4@U(URb91-r;~j zJZ^FWyvqdNILDR6nXqat$?)U1OZZpBlb^hK|GoE=sSFZ-Puded)_BKjZu3f^NX2{d zwk>S|wmmp;zvcK1~*k32F(%SgcCj+&VeY~{=SZIFz!J@A6p(#KWI zs%T2svjfpNNa(Keudm4Asb-|b`|kIG=y~v(-#m$OzS7^oRM$@QPy} zMwIUFI&wbtvR@Fi+0A+^=1H4%298J+ADim>=!1&&`r*ckz8 z;09U-w5iyER2|5<5)M_9KfoId-Cy469p;D|1zO+>9$yA>;0)5BWk`>p9g2U6UPWBr zRgj)0wHfybpW^HQmcZZXm(`qs+Kn*(xGVJ#xZMAmiyLqp_YCGx`_`W@^E;wEw;Ox$208X|WgVjGf$ zV`ZD7Ar^0B;SkzPPZh*rc)}$5gC+VKCi4GbC*oo*vIH7Fq2=J-C~5@u@XRAppB&m) z9rjBbQISEwqAb!Pp4lRv>Ebj}<4HhYA@Y_KV#H7E*QWfMSzTdb(4o-nOB-ooMKmKN zS|TP^V>`NINO&F&p5p0&n&aq(s0Cjr#^D3H*$VPYWO+n7&Z60o**hBKK@x-qW|yy6 z6fojYMKoN2&Ep;2U$@;}rQG32z@ph9WJh|WMOpBStom zzL>;DO5;b;WK9x8NRAHoDValN7D|p9G*u+ZC5tk$#4_6CQFK+_Bpiat1Tu;xA>~$bWl1O`Y}Ee?1%Z_a)*nZJjzo?m76oO>VPuOqP*=ibT#f`z zwgo^*(6*74No0&pS!FTWlp_-3kGP^-5@um?gi_|@L@Hc&(4R(}WlE|fKaS&#U1bY0 zicuP7W@@HE@ZuLKrtdhV_h<@V>SG+HA{JIYSjV z;mu?&XV7(zZn7nb3}$tj=Vo4~ea$93y+K(V<9F`n_*A5K_6~@!=6T|0X2v5~?p$^% zmDS0~a=As;4cOKRVPLjSn?e8QYFZ{8<>!N<=T7jaZmnnBS)GcsMDcace8y*h03?Kh zXlAA-y$GR&j)gKYUPoxC*Zn1QMrUYbWQfYBVJf95-A?Gm-#Im=*2ECey(c-|3w6Nc zj1s9_?&nfgXwMPeHLkz!lgo16LA)2Ljt3YW)`q<)QWsTNliDJ{{SYMgE5y|1$X(keVBIsgFCz|SMTq35{B&iPabmmlqe|$60@!AGtEwKSq*{@WmMgx_M1!7VzdCG3)+qY$ z&M#7GTbxj9N##_wXg)HhOZ28zK5WQBY_{^`#1h-U0uotqm}{LX?zt+*`lCw3sL0Z+ zN4Be<)@O^MERU+^asH&Z(&=-;Y|NGfy6$VuA}zbxDli2sj_s^&NL%%U+p`jzy$)?l zLRy0!ZPIcrHLCxqeI2OIKCOXt)5^M*G$HJBOzTH9D9Cp0+q&b|ZY#GQQM^87M-&@r zwk))6EU*TvW4R?s!R_G2Ey?bz`k?9#V(OlZ=Gg-6p*A_xcd~4~_O0LEp3z?J=^EtHVyD5%4zt!yl}+uIx@_NeU35*!)}n6ia$>|558`&K zu3B5;#;)uh?6{8ByVUM_m8sk6Zu911#6~LXs!r}9C+wOce0Hq-ES2y|X|+1<_fBKG zYHmN$W{R4`W0EfRb}H+nZRD;Ch*d85$}bZxEijR<_O7T(=$rehuj(C<@iqrqPTXbA zZvlI);cEY*5Pu3Z<-YWfS>{ktTC; zColh)DAV#NBd`<}Q_tD0K4rvG+ES3XAo=anTx{}oG;A#+v*7WuLHP0BX3$vjWDo8h z)Y?*32*wMR(j+JIHgnzzi_tLxp+8v!qxOcJ-ceR4hDUwjRWK$ObMrgb94Tw?2H&MN z%b#P?GX<($w}|<6;4Sbgik}`Ee>^651vLBwB!<6Qa}Hp z@IIGFlhaf4bVW$D(pmLc5A-eXph0CLSA(>F92&-k^dIY=So;I+p7cQC88BEhTKjdg zsj*BCF69dX~JJiHro}o809j>1#KFB(Hsg2)q0LK^YdMA zL|)J2WSh3yVRib1)K1#8Id>zxcsAmIwnI1e-&O2s<2Jzsc2;Zkr+KtFBeu^9Fkz34 zt~^9-E5wB6_HuLFZWF|N0`e~B??K#V=pGXY9d}3|26J;a)K#{e%rs5o4l1wMiwSqQ z;*N1U1afzGdvhKsuQAr3SVJOq zyR&~Y_*JX50{-Z-qE$NR@LV{2-pPJ< zc#8uud|z>IgJx~YM1`ksipREx4%CLbc#p@PM#GUJomq)%koDd;j<5KRFSw60`F}q+ z$ThQw^OlgP4UQ`;Zz?%|H~E&^+=uH%h>Le2Zxn6hm#|)O zaWC_CqMyf}`$L~QdZ(xHlj~Y|hdGy0`V)Nwrkh72t+}VOI`e%uZ_EEUyw*kha&a7E zd7$ultLu6i|Et{=7UF%3G*@y@c(IP-`a|z}vNIo$_ePXU`R@)at(%gqZ;7fSyRu`u zEyoIlg88U#^)3thpb}4>hlsTwbGD;<;C(oF3pq9|+C8gkIe&?{r+dARa<2!nBeK-H z!#hX3p|>Xrz1#c1zc;8Ojk5#%fE#wWTT^~}$859nxfA@vqqf0giI|3}4j{LgD1 zkkh=Rle$~KDc!L=&u5R%1AWsgv&Bz^m?r%5p!^#RsGR*R;V}QU({ugPN131xdUR_% z@%)61D|Uq_xM+9%+EX@sBaO+o_1N1wSn1G#?>toOH+!@F-e)wv2hjRX5H!0rwWkl2 zV||XFYuf8Q-!neCF*~={Ja<+7TW|Jx&-K(Vtl~HR<~#YVwS?hy+*pJ-U zgT(&oyp`4ebRp+kul zg_$W+MWsub8oTr+B0{56siM5JbRx}5SGR7A`W0;0tQDJ8HG39qTD5E0wsrd!Zd|!@ z>DIM-7jNE>NSXGvc;M+*y@Ol6x#};gO~b~VCN3Bja%6>L{rMt%8FOaMn>ly({26p; z(W6P1Hp$m7(}7#Tn(n;SG0v_2x?Yrg`|BlwWL@|6{Tq02;lqg+H+~#>W;dCJ{Y%Z1 zwczB_GcK|`j7w2oj~yQ{{7>KX z_pd!F?hfEhz5)$A5Wxf$T#&&A6GY8De^!G^ItM{JtfKao^60PoJlqdN|3pkkz=|xh z5XBT#T#>~VU3?M7lOT+cwoBrRQ7;TLREuI^v4q^z5Ei)FvT2`%p%#N@c{U4EORO=kjW{fbf3j6HI%_{#PX-KxI_cUVZ%)*kFYvY`Nx~RCCi|JDSZs zf^LREL;D7}l7|D43f-*{WFR2exjLgkQ*Y5c3m*R>Ez8K?-HQt!IVl{LR z*@V@l70!Yl9#ukgC+_!vie0vtAjX@QSmkCuR|-EW1yD}df8~3 zm0p_Zrk#Gt;Jy%!sNM)Wx;5x6i7qJVj9`8m?6Aci8|pzME!`ot&C#Y}e)}>!Ca98t?zY4L=-lYjKWH=d^?U8)6^-ncTT%Jh?n>ufI;5 z^Ugj0{86));`GWZND9NBSlw=^wO1ue78A)yu5XS z=D6IGX85rj^V$8)9s1~{pI$*%_eR@sS%C+#ZG$f7QuYImcYXQdsXrh6^wmdB@09(}?RlvA+m@5QHHV;Z7#lJBRq{f+!M#xMmN3@f;I$M7PTlTgcw7O|M(&t`PfH4qHl44LSg~+gb?mf zj*Wj*{!TV1aZG4(lkUJFXIzxzyz@)wRi3k?EG7K5RVq(d+PCr;HCjuR>Qt%flBPn0JW$Md1|f+#t6J$=SE*h#qr>qeMG|ROzy4LJcqM9Z_Bx;e; zKtKcPtI`4j03rDV1quKM04x^(F#x^>i~|4&{{RmN97wRB!Gj1BDqP60p~Hs|BTAe| zv7*I`7&B^=sH3CDk03*e97(dI$&)Bks$9vkB}s*u{26<*qo&Q9ICJXE`No*PpZ+fG z97=TOrGGPvDqXtc4Nay{bzbr}%#F*dShH%?y0NR*uNjkw9ZR;X*|TWVs$I*rt=qR_ zD=wN#x31m0c=PJr%eU`dG;{&`rJHfnPbP>HD_+dFvEyZL97~?;_-7rsm@|_F%ek}X z&!9t#9!C>oFt6tr8tLxXWW6Q>xFlN%IQF{UfDin8aWB+>lF8b!u)0$3)`}R3( zw)5xEJ+hu|TC?@**t2IwBX_X(@8H9G{};RnF!{h4e{!PCzWw_4@EgDRslEPL>iF~P z-_O6l|Nj66DBwlW6=>jr2UiY&Hek$5o1DC3NRp&d!3?g-$hc-nhAy5}`snZ);iYe8XyKQLZO;c56<(mbX7$uTM)@i4T z+;unOo_zM1mmP&27G#g_4I1B&$=r$EoQyW==%bKEDk*?)R%&T<1$AWGmTNY}p-*3O zDrQd(cFHE2Ki$@;ZXsUks%w)1|ETD!w7&JCpSb3_r$*`-Dx|ORE#uE7wPqIUvB)N? z?6S-<`s%aLUPVwxS&C|EQ%@CliJGQbXziM4s@m;ORz+*BO3mh1?7HlVl_y2I#w+i5 zf%*d^u#^>w?_@s_+pdf01}yNv1Q%>DN9QK2@JG{TDcrR;B?ocDz&#A{RA7E(GG?DNk+2fd`nL_<4m zgW^uyl+tXL$u!0@X*?>3MH4Nj(4g(CHH$0jnex~2^6HPiIFIrVKR^AmjLf6li!);L z`E%LU_hD`K-FWA%H-T06|6M6Tn=*}@)N7KN^u#g|E@qqM`knCAdwWIql6Xl$RCx?6lWzJIIdbJ|#g83qH8-q*|=B z#7wiQd&0MG6#MdTcECDD!b8um1Y% zw?Fjp@EbT#mWTVUw72#X|1`PrN9(>t=nEiP0E0cg5X26c(_HoJpuGmlNNi*?UECxT zL7WLIQ33p)1~*}$bKBcqSH#KxT*Q0 zRa1o13!#XRBot(Zu{%!=38TY>HM97JlksxSnmkrs-$s4+HFbK>X^*BezltECBiFv~^ z$cM_f%?*8(jHN7RIj~9EQYG~3B88j+D&d(bcqugD#Ef@KO49NomlQ}Q>*Tz;;BX*0 zR0xfvH_9KDvQI-qWzAYwzSjwGjK>V8ILGXx9W~{s#%uD0dlWHDA9-X4Nk{@QtB^!Q5o3o{lmanYaA;yG zN(P*HGl1a4r$|RiQq|b=q||DVFGuC2-RM#|z`WR(HWW{#u@I#P3Ta6Js83AtQ!UN3 z;WLLS&98-0ftSNxK@D0S6JVrQz^W({Dr$sZC`O~Ju!9z?YKK`c!J#jhg%)0RK9KJ8 ztY}RuSa533TwaTp0zuPC7w1S*i4RQbq#9cdq*JwO#Ei)t$WPTM)WSwHAwlFEQmuK- zYyxYnOwhtAnBdjKRCW}Tg{)O8`!-?u3w?d{t7u0{+P#`{QwO*fsKhr{4;k*I%E4H; zV2c~Z|CzQxq)km=0qGT{24=%<|!Y^jAT;-aN5S*3ja#z7weEku$ zxy`P2{d!wly5Ru!63Fnjwc4Mwc9$sJ-%M$X8)9}>gxgikB?Ehaom~$jzU52xkjlWN zZZAFmSZI*C%7ix%;svYNs`)637>zo2s&?3yE58}v3R^gw?>(f$22#A^XzRQWawpR? z#9rUfGsDga?S-q;Q^C#(EcpeGVynqOY~rzW`_d|6tV)P|_`?~=2nHvXQHaSp_`!CF zFup#@+Z8+c$xTG@6zNBh4(Bhu?MzkuR&`S;!$!qWUd?>>S)cpjH^$SnQS}&0ucsOp z|6di&=wyG933LR*AKrMzI*_prJ8z;Dh4`u@whCEbF&UO&PPC%g=j9fr)5==h^0*|u zD!n$Eii=*-ZZTu#Gov|I)tjE?`l}a&N+d^bhI5iPT8(|U+8f?L$3M{FjcKGp$w@A> zq5pxwCTIHBz!uu2L72#S22*t<4so)FW7}cFD%edLvrp>=<4>oIbD~Bdc^pebLZEGR zMB2wpkmy+%Li^n4E||07=T_h?yS-R;cQAbd#&u%_%;`pvv@Pe%u2|cFV6f3CQTe*v z2zX!DMRdLw&hSXt`*=uucWxve6%orDlK!aY!&!pwhA+u4Ui)|U=$lX-X_E=4|MMO< z{WvUhd;H}vXVS(U7ZZD>5X5GRY5ph<72P!FwohP$Dn{W37j&cxqfmt#+|a5gWMb$V zA4$v~<=?@4QslxV`9w%}@&ZG(l{#DE)W=Tt{>;2@#eQU@dERrjFC}jEW@{0kk&LH< zqYgR%12}HMh-A7xfG0#1jRp;_zw z2H+PGHRvQxH4xgCg4UKk-GgIYcW^BCS-w_BG2R;+#a)nrl znRkW>Q*&(C6g&7Op$AjQ<~!mOH8vGV&UOp!Knu_?4q8wIMKBK8pbFQp2~9Y6;GhcD z01i(;dmS-?mKYk1ND+5*g_eUriU>L@$bt^xf^XA0VCYfGw|~DljW36Z=OTcGvn_Y^ ziM~N91*l$WLTRE$Z}wIMZU6{z00thR1%LnuPcRBUXO8HojvnEQ)aV&$fe}t+0(S&G zU~r7`vKd{dN2s$lLpBQccX`ZXkN4P+6=sdml7mn4DgFRn+*n%&C{t;&iEYR~00;(| zKzmOB4RHq&4mlmhqK_~@jEfL(04XDk7>p93P*rMucZr1lbUaxwwl`2bA(v9~p6o#Rz;aNf*hej10kyrjv4CLL@L4 zhBM@oRGF3|C6v!%ML`iv94QqUIWdbAmpOqkB?)~`Pza1r2=w?dYFQm|u_DL>c_xqq zFfbM^xs`VzJ0<6ZdL%xNNJKKYkb!xb+QpWxB9X&mmk|?+MOjlTWQv+e5@?B;6d{oH zl}y%w5o*DYhbb22fr47-m=jT4&$wi(V{l;iMQ4ecz^PWHSt*=ZlqZA~#0T`~ z2w?yTkl>tQU&gSVp(~5^g6F( zR@NDx_%xiAqKR-BnsYf!$?1SCWCeZzod6o3(HREQnIQ5x8rT^_tVwMWp&f_GkBa$^ zF=iHzd4Cg>o4N@*lz5;VDogbFCfL}S^X7xWWSl-1M$ajrDk`ATS)k6*p;^O)$Rwkd zWF)W|p`}Ej69JY;G$fH2mh>TwFgm1U^r2N!oXL4H`KeC(Ifo&Xq5;|wRzRSGu%awV zpwzh)r%9v>ah?D~qYYXsH|j3N2sT|QlMaDu80tD@iAq1wYhuTxa_T`wS|vm|OrH6f zq?ep|iWAHcb@1b#0P393ITBME232aM(0KsT|CyyLv88ibMquilUYa5!W0;AVm`O03 z@xq`F!FBhyV4+%>%oC}m`ag9#B{g@EyRY^`ks$Y?yl!~U78as(8o|`J6GvcYsm})2YqY?xnXe6xGdON8)BJ{I!pmK9d$|XYB zB~6-fC>o$ynyW2wsDt3EiaMacsvy^@Jj5ENm3pi*G^XSE9cOB+3!$c=Dym;dB=0$f z@mjD!ldU3xq+I4w)kmTl$s6H{eLp8ff(o63fQ0C(73$iqkie(}dInu!ursQo#X7P- zl?0fIn6jCOf#IwS0jdevrtKMxLMpO0|BE{aiy-z{Je|m@!vP%P2(EBQigK8Jw0Zyl zdaECiv9YnS0m`m}8U`SHv-Zjs4pFZVak6WXtYm>XfT66Dx)40tqyMUqGf1^)n=Uzf zAR$^fooHSq1e(P&w08NYC`u5H>Jd!)9J{)%9P6A@o3>=ung%hiRjajb0k&A15Tqlm zzA`iS;<%mV4{#c%f_u5hvbF}Iu&(vC6LOresx+hMnQ&)FiOQ&XtG5DyAVn}1T_ClI z`nOUWvS_O)6@j=c5)m*ySS?&5izzeGeJPX4`|~(Ya_Wq0(Y52 zy!QJj#tR**T0#^#Q^(1?u|;A_Ik8g2t4cc(dz)gI(Y>+Tu7FFsbBeX;gBd1!zS#j0 zjjK%shbn7IC`2NLmV3V%pD4eA5|Aw6V8OAW>q-NoYj$^^jHNl@9!4{I-F}#Yy*juQx z!NdQO$+9cQ4SAlx_sNAz$9O!-q}&kp2fQkGe{Z_VuDs3p0n4wU#YI8Ornj6(d42Q7 zlpc{8zYHxE8=XkF#)ayR?1z5$Mi!d@2HHUgW>E+DEEbty7KM-mgz&m&0K`EYzQ1^$ z;-Oe!E6UQmD9_r#x+&4XLaLU@%@~~;-uxQK8>`0o!bxh&_XEk=I=`2>NU%S|A8$|A7lnU>3;Cu~HibckFuwrAToYy7%PnHkBvPxrilri<4uNM6ct{9j01nhZ4Y((G!|(*B^SH{SEDm4oj+`$b`#LdEsq<~vex*tI+Tx}q-TcBjk2)CdEW~~a(DGpDd z3Qnhv<^b2b|2Paz*b(5+1w}-3}c=3pzm7I*`ydvZPzS@1 z8SpI@gir_dT?jNC*{gR8>j2iIoj?%Y=SKa+ zF*6E7|3=|9gW-ch(ZHh0RNUc`ju9Vz6^LAYUaWJ!)Du3@3^zUpo-hYOFzTdU>ZX3` zsGjPlJ_iX1D#OrynLyJc^W$3qoqoW6PAj0hAP$fq4)1UP_VAzBt=*Xrg69C&9Z?H9 zFb+E40`c9_YSHCi9_LR`xouJA0!`m;um&`(-|`?9;6Uv*4F=yX76jhUYSF-^-A@Z= z7S_hlgN_yrQCxovGn|0v!eWq}!03|^GqIh`kv{1Hk1&${NFq<{*H z|8NPl@B~qw>^iUswU7y}&;=l|7G16ixWEYHkOX6n8Q6~A_01q!01Ziy4ViEYw;%|b zEd%6`35=l6s<89=ofch?sEK+8xeINZ0qCU!?+_l*J<{>{Ug7Q$+e~25r8@9*?+^vg z5+Od0c$Gg@opai_;-Wt4;?oQ<9{3l3_^Phss$v8QK?pMA@pumMvR*7Cj}jJ}61lFZ zjarW#F$!6p&V$|sgDU!vkl?l(W&*h@bcFU6OwCUWENrjn`_35rUOq}Kymg=Z2yyqg z)X_u8P7OQ8#KGzQK=_7F>KPA*o{sp;U+S#>mKz@t1|~D86ZxAU2<}}cl`j$||IZRr zYS2L}3e6x2?7)l0+}flM2|RrU&}sVXa$#l9n0LYY%jEj?jx&e;zWRRuQY<$BkwoA? zf&~p8M3_+F!2=B)K7<%i;zWuSEndW!QR7CA9X);o8B*j(k|j-^M43|MN|r4#>VO$j z=1iJ3ZQjJ0Q|C^eJ$?SvnaQ8OOFN7nMVeIUQl@W=4TTDo=~Sv!Fa0z2rfStUPK`D5 zHD`_xvSrJ9ikjA6v$1B~zJ(k2En0tCjT#BbL@$#!gg9|pwr^;%Oq&GNS(sRHks>-F zK^g=!W|+r1tb_?O=<#OGn+IX;qFD53(xnM@*?dMIWk{h-zgFl{_H5cA{|O#glw0?1 z-o1VQ1|D4aaNuar*nyq=HO8Tw_CALmUHWvr%ZC2@mv-6TPK2m`2mhQ?cErlfldhd! z{d)H8-M@z)U;cdhASK_&pI`re{yE(Y!)hx5kvbqLr__qdt^pS`(3pRUV(_RpE_n(p zvE(Xi4g}Zoq%90T1d*&cn&Bs_qf&ydufLXAh97?j+awb~&Qpl7njSjdODz{M4ml^!yJ(Z4-UzQu@HX@Z zyP=4&ZaYr8GqX(V{Q0uZ+oZ%ZPd)eKvrj+&1eBuw1|_smL-+d+|0@L}6woU)$7GaI z2TfeCD`P6`FhsKuWGgNxpzz{TQ9sobF0>ASa0eswk}W#F0GkuW8SPBMMjalDOeaFz zZ~-PaM$v(_QNYPWha%1~#~ea*cp{r&FdIZ1YBnQ-sr}A)VaOh;A9lQ{BaXbd-WPD-g3`HIAMhsX1HO8 zYdbVzi6@>|sJbGpl)^`e!njiGQsv6gW-=|+EV_p3^sP_D5W^3b{lEienO~-vWiMD3 z!wa2v_97H&sF{Nbp{by*)xA0a_|-XMG|WyMfpSBYU?JJ1{}2~kA%u)gVtS$+9ki%L zhjNmLL!2;RImMo9JG*wsA`O1+jLpDha$LBde7IqP+~vD(zlVbt?u(imxNs)sRBIVB z!Qvb82g+<1Z=Rc?`boXT|Aq!2(DiOGJL>`6iufz%m@HM#(;%{b&o zZlj!HyhXQxXa*7qq!s7*l&-&3(1I7#P2lQe5i!-p|8N6)1A>|yYt=e zfETmi^-gz@*aayJaXjTQ&x>DNUKfuC2Qbbd3|r7%MYQ(@VgT$76nT!)22+?>nZ|qv zNuLgOH4H5jfe}(;%@f*jiy{yL8ihDyCZ5okY=9vX0)Yk?AX$(B`Ups!K_CkSA~z)+ zmlor&WayUq@4-O1*gllDVO8B^c`D2BkER862xl3O5(w7j!VK9YR zC><_pDG(82SA@u*)&&tM6RMDhl4vRqf$E7g|BGVpsF(*oR8fl9L1&2*~--ffmMsi9Z-Yh9V?k z98b9AHJ&g@g;dgkmz>)f7#ObwBIJ{}G}tdYB9JK!vB?1}G>Z8UIimN%SJe7tt{x{7eiX1d$9k5Frx; zrN$Fn@PuJxjal|^!z~1IjU+HO3GxUa|7j{IE{tMJTeRZjx9$pwKJb)o=Dgq#_;E*Gnu2t^Tfx;T-1{%ZgU=k~a@|@S-o?!H-Co@eNx* z5nahAkU=y=F`2N#6XtOXT==gXkRXLUtYMEu+9MhEV9YhHF%RU7Vjbg{5j3E|4roji zNd&AcuCnzu<#aS5xbm!Lg_;EWlDM=b6-Y`~yJ8lz%QyvjEh}w1+Zme)Dk1JEaCN+6 z9`_iS#07GYiEjp*Zhwyn{}Oih_gwU&=7tZ;xYf2 zuV^?K>Va4^!y3NqLcC?@|3gDUHT*`nC>c#sN0T@SrNm98t)z@$NZdDQkinfK0$Wdm zC$=4z4oz=~aD$8*)h9=J%5}VImKPPNuZDF~lsjv#I4FomoGO#8=?6sw;}V+)h9de9 zj6Ntr5rgnUFc`rIq7VJ(LXUDVej(*>Q-j)9zdALd9c`BxLY!JGYqT{XZY{sVAN<(I zwE0nPa~}`Q=Y&O?*k0y$$D1Vfh6J5Q;UXA4QXx$uc|idEZ^&%elba!U!8aOse!Fnt z_BAb}Exy`MXd@Yv&dnz@kNHJxUh|p%d@1cf1dT_egCPG-ZBc)(?2Mf8=u>&@Wj}jf zw%qnO95T!^66@vC{~RevekSUeDBY{lj1iZJgc+FKbDAk)6)t1`FS_ZnK9u4Pzkmic z)Q)xT!y?;1D@HcT4wY%|W4+v`_T0_u2X3Mh6xrZMyW9T7x}QH)e{dFWIcb_sQ@%N+OxqM#6gF-y&Vjl+|xabFrwb`J)?L7 z=L$Yt(>dJ1F0S(frW*uB5Vl`ngg#&dTQCEck-lHBg;_|2Xk)WqSckJiKlJlHL-?6p z$cA@FJFGi9|1liHwF9?4__l95r}JXJ!Cl*VbKMm*ucYowT$8;~Mn9b<5&A#9x;y0zh(ot1eaSfB=2fCVmd8754HUr2=} zOoc%}gkY!!Mo0zj`h{Qr%64BZ?8DmDh__(#iEvSsfYLv^lq)Xbs#=A5WHy8?I zh!Ad!s&DkYtM~^6!8x7F9o<>OtJ?>4WJi~=g+dsFNPxd}Kn8EHg_rpS$yCV9jJ978 z1+97+EII}8LaT@rw>0zz<_R}hfWPhgNQ%5Vf7l24Gs)WQgLlgoD0qmK#E4C}g-rm5 z{{v8kO?Uw|h{;Q+C3A=o$Px(tfg~{K$s_=Sqr3%E45)N?0y`K6&#I&ZRG`Ob%BU1i zhk*f7ibbo$pl`s1+#rYb)D3oMg-_tX%zKAiga#EnMu{vTMw9OwqCo@U}{j&&JU<4k32rr1q zhj@d1P=#eslTFx%6(WQ}NP_6(qa;`cNlF5CNP=NV1_;A3RwNBh3QzGwQ?vw>|J#58 z7B5a@ymzJ$=ENV3A5CMC2Yn(;%}9EM*gg;MwhbU=q-@CI*a z)qQY=YVd|&K!rgF24+JB$Xq&AWrS?PHf@W9Zu?O*dpp(4QSQSI+KfY3&;%O=()k-w zNHC)?xIfcthGuvOo}V7J6Dv{kQG@1t<;kJ32kJM2HgQmQ43G~R3iMCajeh~@q$vlE?9s~ zt>d{;=!JE#2Y*-cDbR(~e z6byn)Cpx6VX$?d~cnmTNgEydphhT(;xP^xhmv425PC(Lqa0t3>2tw$DeSn6c7>C06 zt0b_4TX2I`5D0$2G1fTKf!McwWn9>ZlG3Y)HiZE{JC1=R*xt|vVf+Mpc!k_Z26FJg zJrxJtAj=ElQh#-bnu0-^LXhk@ySCIcd~v-69NF5n-5WI7+}()NYb{gluRAVmN?K*n|TRhxH21!a4v>7`HAsfNTJVeEO-HU1Rt&u^nh__lqEVB?TK{wd-!e->t*cG4 z<4A>s1zCuMJUm~qW#2M0qcccbC4~ew@Pcgh2s(?EnWSJ)!eGU~D-CAk%2AI?GZGL^ zmpHv#^pw~Rc8H2)##f4pW#HJ3drPPk;!!5$l`G;?jtP`a*(64tCEk!GP9_IInJAWG z>%t}~!zNgGO|8qOJJ3*m(6V)G%&eL|F@71U-6Ax`TJ}pfb30Y_Gs!zRRkZ6`*&IWI zB)9S{uRJcZvSQyK0c1Ati03HR6>(msIb^t@tkU?XMt0{fNr?oK^yH~=&O%>QL_kbf8%TK;_d!C9>fX)6QGjYeLuGUGe&0xGzIv!$Nr@q%q07HaFDK zJ2tawH3X|Yr*FaeTtVw-Y3X-=c@iJiwLoKre{jFXO?m;iKyX! z202a^YflSM0WIjXR_ho#=uFMtC!n1ew4XlPd7KJ-JMMn96AKlW{A@~T!yaL7I|ghW7u z&;}Bu_5!7b2&Tq}zo?~r`x2>EWX`hc+s5r9nddI)>i<8@XNc$^9%e??wJCmXRDoXW zcf*(MF_>ONLAevQqjw`_LY?+=pkZg5hGtRzjbP~5WR7W`k>TQ0Ep(Zc9dxu>x zgmwVLZZm|_PJ~nF3~I>V1b1v>xQ1*1U{?SKa9D!_U<7f<20}Q1H5j+==>l+YmIELJ zaTo`7;Jf~#5!y}+@67ET=W)|0Ppz)!-gdF_MBRo+2DNlcfLT-~klpcI?k9)xb7^iO zR%M1(*$H{sr4YfXT-og+xR)cGv)Nt`_p)_-ct5)YapcC1-N-aPlaJ_Gq`pDL2`-hU=KC?kwNb0AY$Q z9}3$k3+_(yF7xh>)=_E;Y429^Fc$+hXoi3A1+B2}@3?dMzVj>Kft#WyqR@+MnQ1>a zD~#;(FM`%VFG=>@B1S+4E=;y}l)7Lrg#T<%1#hSZQ4ohgaD`q726iw6O`rxwSO-zi zgm&lyf7l|DhXq8K@OP+IY9NKj;0JMn1V3m8HW-Fe?*ev+^)*nN1CWDpb%#;f4rqW?#l7#}_n}_O0i7_@MS`2aqDd7?quFZU4Pm z;|lE7YjHp6@7q4*Wx_BX_bKZpF@ORgpo^lI_vxs2d&hIx>K-?m4(@>hfS*>dz2j<) zvR_CxTOhVo5W3?L2T?$Vm<)z-=mTdMhC5gXRTzX)NCk8dg-Ec6l4l-Zkn}zvdD5na zL>SU{AcdEYNve4aYG8wX&>l_*q5pFrA{@&h<>e_(bd&;C#r<*xVs@0X3QFWD-$a^JOUn#1e!SBfqNX7Af*E9)ve zh$8Qfgq}t}EvsI-S9cf<9+m+JC_;qHX~xgk8zW2>GF z$myRyP8~U3c>`rmpOh+BvTW({CCr#ABf;9Y3lbz?*@nSFr3x7=WS1gEO0>_GC`95? zi7RA_R3AmoidpM}Zjd2QclfP@rRh!|t|@^TO8GAosYH` z3QpAU;}1I3ID-y9$T)*cFr(~JjWzp-)5|)!WCDwdzx3fxAL}U6hd5iM1j-$TWYb3^ z!1Mu1AEvGf%OLHvnvEatAd-k&a6tl>TWzrc$|VQ5LI`{hak9)l{v@^uWTIIHNf+Nq zJ1w=9XaPrQ#LxTSmcp2Mv~1t{_xY|k4DmXM;=Q1 z5%khDiUEZ{I4~)MLH=A4WkYW^GshJ_gw4bgb3AE>M&P9%LGBMvxa zp&|~bql!~ZO7^5Qx~iy}Lu;$zkZy=l;sDy#JEsu-&Mtni;l*9@5mFf8!?4X*XU|5v zF!Rkj|2*{3U(4;c;+lK?xM=(qUfloSJ(3+{%<|lHdXGQvLh}|fOBWj1vC8-YFVz0` zBM~yF!vE5n*6_yt`~N=x11P`&60m?28yNxF7vWYbR_ z+Lnw#EkjN98_5~AfRey5F(!k9gdb7@i)^&x7xuUbPJ)3BE&2l%ws3?k3NeV3Xo`$Y z3|x$Er52p9v5k;0gcsNly!YV53#vF)vXrG5JLxhtNN2w9M`H4?wWQiegVhBZ~A|;CW#V&H8mR(q} z8r67FDoQbmV1T6%sTgA)e(|Yyo{@G>bfX)8H%Ihb0Viw_jIofV$HgS!3^+k0NJA>p zk&4tc)T^Fs7P%XA0Y_aSQKv>Q$q-Ru@_mAsq!#Y=uk3*GIFeWeOc_$jI*?Q|s+=WK zld9CEGPS8o#U)guDpdnHaG1cH5PDd4RSUjhW)&lM|7!(#c zTGZY0wzs~`R=8%P(sMa7U56>GCH*BZI}n2t!6?K+q@#+4ybGuTQ!Wz%7E~(vU-!VH5}bs364C|0r7#H>4d$1iC_~LHal@2F=0aSnGtFUr2GI-Cc<~6gq&2A>(dgCl-1e$D@ z^p#L~He`&$xcANu9%I}GFgUl8cf`6Z^AN{8fRQTMVJ;NypoXdp z!D?!>Y92((9Oh(Fj6u8uCNiG!t!~`LIL@IjJf3KI=71Bx3=fYR<^N-n!!7P{XC@Zf zYu=K>l^fU;cQ7s`Y*4i@$@EDAIa;97FV?X|b)e%H=uk&6Y|)9k^;9|aGPAOb{N{x- zyx|Uiczot8@rg4?m-F>Ac|;^PfArbU7qV~1KSXFl8#)rnO0-#hbO)aKY`{>9VT{B; zR~p*T9|&Q>LqM`aCdh!PY>S(4IN{~OhC0JdRmViN z4z=-(IqZe>#M2Mq$!H#z1#WUPzVSt+O+F%@4_(B9xaf9FaQ~Mq9+zI2UhrFm7Cb+T zRTN?$@_5EG)?p7q8Oj?V8BV>^Cokk8%#;d;IPP<=``xpd;=cbq$xL?N_ttjL8|S#k zK_twOpU4X&e?HO5>R**3Q-nu*ku|A#q#4efN!;ApgC$JfpARY|LccH*LaoHVaTpN~ zMMO+s!K$wNf>kOJharw}_Rf_KQ?O9Spe))l4GID3h&{+oHi!c(fP<>=1Lo{Qs~kgE zbPfap&a=@N;I$SU$q{)hmLbGfVQ7@%IUWg?pdc-RRpAr6EdnMoD8UNq$Az$)^$cPA<%YfDM?H4t) z$n+7#^Yuho{S1(BU-uD&K_G@p?BD^8fsmdU5j@7Az zsc1q^fP$)t!ysTvA7q0ev_nlS(=wIS0P@2C8Vy>d1V4-s>A*@Ks7~p;)3f!#tvr;p zz1CnXmf@`j;voi+nV>12Vzo$~E~p?Ys$%82VDoHVl+t4r9=hxK{4>3KSV;ZL161ZAnAY# zS(()$BH}-!)z*mx>5N0_q{KkNSO=xV8r7Jz;TUY;!5hiPD1I9%ek4eWMl49)CvXcI zd_v{5Vk@%XB4EpSaGox91QTu?yv5`~aMzIyqfYK5Pxd4&86!}tmmA#B69$HSHKW`x zU-AK3GMWe#R%2MzL|J7cR90VqQG+MUK^P81*2v8;xPgEiK$^W7Iu2GY2Gtq3BZuKc zA|QgPwS?Z~2`HeBA((?cW{#>v0ytD+AD|uAwTi6ZUmrkVF%(13NZ%qR;1s0fSw`c#x>;=f*j0HV^v1w2t`73lAIS% z!6jUR+(ZOj)!box<$@H!Shg93siAGc6py)4TOtA;s6;WSP&V8FC}czHJSHlTP)ZB} zeWnC_=80jdL<(75i!37QfP&S5!q5=tso3AC+~s6aCQhh?jLiWP{LWgkks(|GL)-^< zb=xuw%Cdx}hniptc7_Zf5=yRSE5^cWq6T@q+iY@#ki|)ha!11DW^dN0jozqu0jG}I zk^|YV8JHUlvD!#^YgST4|(I^566%^F717D(ttj;Wir z#8>0x+$Elgq&^!8?ccVu#0-=ke-UiLkL;h_$i=vYe=Oaik`+vnP`fR#(6+$ zq%uSirK?bZ1f}{`rpBwh&i^aMaH_qAjBq|9wq7f7Rwt^ymvX`k&b%tC5-gNb0n8X5 zu1eLeHXQi{-C2GQ6bP%Bx?g%0D?`cOiok*_yoj=%ky_Qj`G z2vgP!6&S2B5rvZyY^=HrGv;cXHSEHb<*y!5-*~}nDTQqbmVNHiX)g^V24hS1d#>=x8a?G3{bdaav*tvZg95`igZ zp65L3i90Q5H=^7-=*WNimmspGN_2#_?d=TK-ZI$7D30LZJ}Ki{fPDRxbF4uh3#H`4))9k?vL<-sghu<^me}R!EW(tks_G9jtE67$4UHCG3Ld z!*9GHAqRhG4REDD-YHYTT?V zS{`XgFQF!`;__^y&Mv#+CXI?O3%78MmM;tkh|=mS(}qXr+LzQ0?CD-z>ON`KYVCIB z?~d*-n}w&B2LDwY>1_ZHFag5^O`IIcoz)u>uLEnu@n+@@a>Af+?}gR}XOiN(as+=dlj-=)V#laCoi_Z|>;UO#I4k z4?n5>ChTEk0t^%Jnsup#1y!(`?6A6D9yGB_Jh9vQ460}Xs^A17RB=Nnu@^)za+MMn zcLekD>5y^j7;~@(m+=a|;v&4@WLPg7vq$#EaVp2;q#oIK-mx$bGw$he40~$maxO*% z^3z7`a_VqZMnV_8$dVqilKybYXk3;Wvm>inuXdW_0_z;u?h<2iS4br%vjk2=0u!_e zLtOE+&i^1P!<2mhZY#gC7{_wueL@S$vKc#u^y-4SvPT`5@Coy>y8<&YFEm3toH4`j z4AZbtuCLQRZNR=vAy;Er?ZXI75&hOL1PN&-aLhvsNH?3;H=AF?)=%w*>5ZKy6JxU6 zx&%%<>q9UBkXcm9qTf8vV0{3t^Wt;NnrJ?hWD<;MW27cgmoZVt0#bj5d$8ymvk5}` zLoXItFgLVTZ#7euH0DOML<7c#h)4T+)iYc3^Ic)0{cg)arw=1+eeKy-lC)PB$VrnI zI;wPGwKQhBUrd|xj9HX7U2!C=NiQ2rPunDYG;b*iwTG(UW;`{bs-{2Z!y=R`OS#8k zc>hm}euV!r!C~v7_o5kBm$qp?Rb3x#o%OLYPV{(K^dQ4bMpxrCw(ayGLgz$hBEO7C z_eE-VXIA5N|AwtNlXC#)uI{eH?!tseVKGCH^7eK@-Ixg{poyog$x64Y45sU1V{qU) z_9;s5Pz4PRF>B3$x0rcDGSv{ zgvn-uL|GkQnGBX*wRapd!F(`w7=!n?rLh`gc4sVE3Vs3+ct(6kb!Vfv+?aUzMgOvU zCj*k*w|+1AjrxarIC%j{_@;vOrv`>~2Frjar&$Z^fkSbkQDt;`K}at$U`V;hP`G#* z@n`=p+1{?jqLzj7n4Lzbv}(t(7-tiTiHpCu1#=`TYcP$A8&O|&^-A6vXU2SNcDf1~ zQo`tL{xTgixujz%l%q$b2auWTC?EeffHNbOGqcBCG=5PnI%lE5Hn`TxHH1farXvuV zhnJcc#)Sd!OItD%Ik4VZ=oK3RVhg!(qIhWYIgI-`C%kMXxN@NH7G$f2cz4Epuy?Q* zR_!&qqXKQDPdc{S=%t&-w);=3|0XhXI&seArvt|`I`g18pTU~kCWHAkkN>$p3`1ai z`z^hCQw0&w9Wl}Uj+-L_+P*{;Q?e4Vkss7g&LJg=hqJI#>)+ma!W?_D^OkrEv}$-T z#cKwA0J)MrCV`YWfUtUiYz(~{<51e%``#Hd9%q(^dVxRe}43+ zpy-c2E`$AixKss?{l>L_3Li$2!9M-#B<<7n$=7~=u=?#&96&I-rGsEWg9mjyait1j zLx&F`MwAFKlRtmP-t5r0kz+@XA3^STW6WYnlNK)>P`PqtNS7~1{=@jvBNZ=w?&Q?D zlV?w#kzhsgIg}_*FH~rDd}DE#8Y|abw4i|BBuEW-T;} z$uez9vYB&d&!0hu7CoADY15}sr%oL!U+a9jREO5(`jcnLVmFmsW^pZK-+y=eTl|~2 z+@=1K#a6z&^lj(Qp+}cKoqBca*Rf~UzMXsb?FLsOWGOy8LGN0xrhmBU+SDh>hN+i7 zpP-vzGBYOC4|3#5|0ucIZ@)|a`R5V=HM*&&1&4|RCk7$hX$u5*AjzLhvZ7DJ4LOwW zybnQCi7c}STdS?&=GtNoHvHfV5=0>J14Y1&Tc)_gi2vc_AGJCeB{9Qh3^K^+DC4B0 zO)?RLxh0uw(#a=3`^2?;Vlkn~DXUDPyG{172uMyw`6n$-fE4nurG_)}Hy!=a49Yi6 z3sKHF>8#VvJMqj@&+p7D4?I5$8ZXcgJ5+BIYutmc&_x}xPs{@;MDUIN{yQn9ts-?P zrkMn!BEnB|g5^O_7d%Q*rkr|;(N$UPu!ucjeQrd5N=#EtCcIz+uUwnB)h#w{400_o zE#e2Qla@(VElzqQlaMlfy;V9wI9cXcB$b3y+ikg3ZpwTXv2sb)Tsto}i%yJdSmD@; zR$X@?W7ExU>5bLid-2Uz-+lSTZcvrT1Nb07<^ODzszZyYMV)L4DT1IP7|CWHYZxKu zy{49FCmAgqHkiJOF3MD7kuI^&ze}|m`6B}V$!|ZKNQE#G2V-7vLIf|d2*V6L?%C&w zUhP+CmS(kRSv7lwmkD5fUANMbh%FFZrQwxst>7@*BwKp9?poV#os_cNExYswTEwbF ztG8&|rJ6A|>+qV}q3N#M?z{2MJFJ1B3fLh(LHs$YO|nU56Gl`~r{RRJ$)u1?)={O1 z_n^5Y6GoD0#|;+*ugVRJI8`~)Ne_7AlAHm=RP>GBD9{)Rx2TyxSne2A_MVUuu)n6z z>)iLw^{%_DWOO6b?c$h**XgHCvh{d(qyJmF+RHNATJGzyCym_JYGd+%DL?71j*`-C zj9H`C7Sj3W*|{5>Kr3$b_@aCA_Jc@V;3MaTp=wD6vNxM2l4 zaDzG+qCbf^Ds-#U-6h_jl?Airli&*(Wk0$N zuOud7-(lFaK6fpzQaZe0)xrXo(p{}fS+m~zkm$8VU`br6c?uJ^Gd?e&=zL>3n{R^k zL%EbBiBFQ@7r_`tG0yKH0-H+yVAzmNn8P5W@W&HWQ4TUV%mq)_2O!>)4T5k^9q~yc zLLB7}NOe$m8x#v6SvJW1#14f$G5=vBd$I*1=#C`3+sYp?NuQvNv0o!P3vb${#T<%~ zP5xQTViKc8_I2eg8YCieGSfv_ZtGi%aAH=rmk;hpQ8;FzjAhtG93TGhGPCp^Cy|*< zWiGQ|e*;vYoO!=Y9)vvx;nEXsQ4TF|E+OV%#KjD9jbwBzlOU@gA!#zH9o(jan{t_c zL?}C<{DfwZ)QPDC#KNvjlb=>$Cfz()tMVyrl&btyaExXg#az*#(PD`Zy;7u-WX+fr zUCy^)aGI_xu{FBjP7Qb1iQuFUhn;BXTaGg?i{A2|Ep_QjVY)XRpeIA&L1RA&Qq6+o z2AkjjLqVRPI4}&u7zWA4F#pJzMhdf0tm_MA}+nzPhlPc{t6151nR+`t)JWdjxUgd{!(#1yZTmADRhEM@sME42!Xt#b_$Wti|R zz}R6H)g=QHwD1e<&O#DykwkUv;1)Zq;uo_BFLqZki&bbri?_Mjk&@KdymFL#p^*%I z!DWK%3|6teqD+{A+5bN0E=^1-mG5Ydi(CaSn86KJRdIEYn^8DS3)YB_7WOe=9TZ_0 z(0Iao?9smf+9MO(e4#m8s~>ejHL9X>X9%l$J8JC1ST#15n9!1qta?>a782`NAsl1} z*G;)&>hD~Z(cA%>X)Vke1zfVrUOW7P3FD26BvyglUuYq_c6h;*-SUg@N}{{Y70Y{J zskH-lv6e*W%yaN7Sl*oU4M_%NVh0?YxUHEq2_EvF0Uc;$206l&O9m~nkqt5sgb?O9 z^fkcIzxUiC8MnB_I6MqPb22r>A2FTFV5_pJB8ZVFgawUloN8lH!w_AK5ODQ_x?y~U z&_Wip@XS)YBma+d$+rR%u_oFJXe?tCzvx6Mkny9o%!0j4Aaj-9LS-wzpx1NxN|BaP z#Om?6N%jE4X26gQXnaN+`-n$t;vo-LXz2;oxCR(hG75GOLM31TM>1A&3w1b!8};B` zSIl9DW=Mv=&K-G)4z6TwT>O+Y6yK*#TIHIS882cKTn)rGz6twnZWC6 zH?5QwVFx;#QH^~};~CBfMm6NIk6*~cAH?XzEZ$-VEIXUbzmP<;mmV3eU|ZV;b~tIk zkPLe~VgEDiNCFu4(HVP4=^pf;hc*r%2vrdLnLvywrhSKO@`lyD@sI24))~(D$1m(* z5kY{x%H$0%dA*xu>N{pKm7$*7QSTXkeA^9f0*BsN;|_Y)9S*=BRKg9SAs)_6AGClFaA6qCfe?nF9N;Yz?7$9)0UE9$0J-8^j_i02?mrSv zZU0Kpmx?L=K7;w1F9v0B24zb5Y>*%}?e;?A({iuHMkeN7X69%P)l!WbhL6V(#OJ`` z262i8^XB;yYW)Z*Oy*(h!mlL2?-%C5A4b8-;DXAYEzG2lI9$m{sON~{Z|;)7;x=O# zw16|7Kpy159rA%6op}K8UN5> z83h(HkNtq@w_00>avRAL^sq7H~hEtZaXbmL1p z0eujQx!R-@O_3NyawH{A7=zCCUeVKx;dM5`IYg~MSSu-fuaP1F`1nEiYKIp;h3E7` z34_rj(+CDhvR~55ioTIJ$Uw}hjLLE$7`i0t?4cT*LCXlC5PqQ)2qC+|jJ?M0D1Bum z&}1PX!P z6!HL0&JO6!4e;#%B$8+bD=o69*AVJI3IlC`iKNs=O!f>U)o~~}vojYAC<*O81Susw zVp2$gB{jk&VeW&@i6-L7p6;N=gzpF&$roV)7=IEpCCD@9$LNm6D;s0Heqp`D>ldz$ z9mFIRz{@SPU>1xsFgZaB$V(f6ldjOrh_J^iCU74n(HaP06lM(<=#3l%QXlf+6Ud9EtH!(CrT}n5LD+fuFbxZ~|Q_}|{h4&T-Hve^E#&8lv?|>(b zPiMq}LtjWk>8EIru{wq6$e?Q!k`YIvrAQ8-?Z&b>tOE?}KnprhC62V-?r<$z;{cw( z4(_ntv|uH`KnuV?^OlrKw9kH|NJh)b6+e_xNgXCGJhgst4 zQmvIZiUgQG6;|-8N~Qz9#*`}rAwi90L2Qd$LeD4}(lJoFV!$7D_-SPv;vSVlzQiA8e)C?xg{7Ig=GOfm}gX9iY`$f7Y_ zwOgrZBY_WDlw~cNMcG6aUe^M?*z- z>?wD^Dr51sc~|9llQ(#Z@;4JVUK|u75x0MH6lxR>vA zjtT8xZ|`&fcr-^eYkSgqNv$Z_xOU_gC;t>-6$W7y7-5>#why$p50DL;(-xcifNjly zgygs9VDvVCnT~zArED~0`}i;PxKeE7k=t2a6z*!W?J}|^NuDEe|IIn-KoBw`8Kl8A z>Or@XMY!^Y(~eD&}V4b<{X0N2|`Q@z(I0eC1^&$99H?mR^o&Y zfDz_la}J;gIHrdW02(A`m3O#x)48T8?wpHDPxrKBDrJzOSjAk2LI{;8-ggzs_6~xf zY|*z5QbC&U;A;&*6uuU1ALN@?fo^-^jq@pvb}?J1NNFX!PLvf&yMZFs?YwS~s3Sp^M} z$||1sLp9=bY8!QonZ+7*ez#UYs<xm!>uC|khMmTLp2r_VG%qjum3h# zOeC${VoG=*aZ4!_t7ZL4iIOWhEZCu6@lbMVAu&~=95P`AptSxH4V5pOqiF$4pI{iy zaue)fcUR(H@e+crG{mQLyZ=f2Ud|}HCjt$0Ar@xi6Ku&UgqgNYhd)|USY5(IBQ`?3 z8Jo$rZQIs3(E$};0TD#u5`Mu9viA;Oig98>}j>_MfUAR9cJ5Ef`9NK1I}veH!qdT#GvZ12DfP{AUo(I32_8vMZ?a={iNA&kxT z7jz)Bn>0&oP~o#G1Uz`!S#kp~;%9m4=_u9L;s%6Fwmj0^`j;fxm%G z&e@92FVi9f9M2iS9608)HHVY;p_CDC9JGLicb5!EYy~v@RqCJ}0AZy^AsarJ-zORn zG-tF4Q{c<=v!XrXE2|+^(b*d!RJ*-379kcMVzz19wpqQ^L4p>U*jQtRe1{Wk`v4XG z0WEgD3at(q!Vew5_G`hnsoU0l6ZK;GL&~Sz;(7{ z2Lb`yGk!{#0o=tME}lMc&;4l%Bw3ux&hK1wX*gfAVP`DO(vkrjCJdX_VHk!X83?nk8viz-5ZZy>0O7PZn1`3P2wVXi+&&xhT<8%W=w_-sXswI{1?U?>#WSAU zYl-7SYl&%FDN4R0ei|lRC)Gb?*JBX%OAGTBKBb(Qa>AtArb}wn{R!``{1aH zLfKt{*_$2m&nWR7%;*5O=xLZW;d%vkI>Op<#zx`Wy0PU=G za3vGJPb$FMJ!#z_4oWU)+<>&)01(_Dqt74xr?d#_pybw3{L_DhQ$-5^0sTLE{8#$? z;~?Gv;()+`1PdBGh%lkTg$x@ydW)iEr7D$Z zmFXK}|Bz;Ny5)}8v1H4d728KFDt|`#`SZum?c06X5cRoxCvD!deD8Rn@>Q!bf5Y5V zl!-X8;>C<%7TE|nvgFB>D_g$Iu+FAUaQ$)OM2Ly#(WFb8K8-rH>eZ}UizdYBt?b#e z|GoWZ8!j=|ynCO{&B?d#PeD)fV8Y|Y3nrh43w>^r*>U02tGCWg`|UDLZ>)Pq&B^wr zB;?DRKaW1W`t|JFtA8xf#X%SHC)b}Z5I*Mp{QLX=4`6`&btDjhA%z4|Oa-)SBGzpc{3MQa&QxZj(paUA8>;#=OpS%!Qi6vfgNnlt7b_s4Nnz#cMUg*_Vjby>{ zR$Myjm`x;+>}8{kTfjKgTf)7_nB=H_0Yf(}aPc}`M^XrhWP z%4nmF8c1NIB_Ze%r79`JWTu+JG+|IVnXrNj9o~dS5hM{oL=ivD${P@Hf)v>AwVHnnLkx7hI+TD;YPIbNaq?#pkr{{9Pazyd>Q5~T|k zY^kM}F7#}}nRdD+5i5{X1PnX%WKt1DWWrB9(##3#tFx+D>sKxQ^P-7V6w7NQY{8}D zuq+2TB#f6Bd6C09?>y~>KjBP3J5D17t8POCtPocPjBKWuS zlv|vE5Wd)ftaA00l0l9u|3F}1!os;4QDYx*=}}%b7s0XA%tSXM%(9r3y%0iZdL%4i zwXT&ds2$H-OS?^KxC0xcy+Jmw;}$b)a^N!dr6Do0u zOiUX|5Okm?7K||{5#i3t0h2{M=TqiWiN@rCLn6RWeoe8TPy+D+#s7Up9a0fstQ=^S z$4TX6#vqc6FqpxyP{SVlkXatj;<*xmPIT0>q9GI0#6&6*N<)*4(S{f=*j%DDwj)Fh z?Q|x41!Xxp#33Y4118)6aWuI5WNYw+#8f76k*sW`D+!jMSRQhgB+-IDI+6`W=->&e zctSab0gg@RKox};g*{XOJ{=5W6vN0yEp$)_cDO?yV8qEHKqab{WMUug$VWHI;g5eb z;|=97MjgkO4`u}7Cb}S;QuL>YTQuVu`a{tr_Th>h0FVmm7=}155d#5ULLF}yhAf7` zj~(0q9K^VWES{pksN8CDCW7D}%>s*kL;{Z&y~74iWTX#*kpGq>UCHTQiPDr}gmrFt zq$!73yxU#UJ9)BKyFAsLKvc(SPIxI3-Y~V=*yd?Iz0O-Qp~|EZN~KI~s#7a-l7p4h zVMVZq4!}T*WawZNZeRo<#Y z%STxh(%Fi)w&3ltk5O2(>ROju!R-uf_LQYgi~@!+z3wQHCa2`$B&Vst8xMOJn{VA_ zs6#eQ5w{EG_4s(qWM=A)d6o=XfI$^nuqreP(UGu@q7d(muQKUdgm&nnn)$%*Pxc0r zWc(u@`Orr@cfgN5dnypgVG6n&jDn@WvlA4a%Ks%6i{Wf2Vrt|PU>&Jo4k{=v8*p5) zU|eL!8jmFsuu!#F0$HNi5)vb4p6W@A299g!zzw5Ng$}^ch3>Vt5Kjne5x{ZhFBaOZ^;jP}W6{2BrX&-%*+)J4 zoDXGm;~x3oGn--n@}(&5V(!%6CMYdhOW$B0O0mZq_CYS&7~>3#5HYEjQgfwT1GJ`I z3LWiOIam9LqZhsLSAJL+joh20x30I-TmQ*Ye`Lwm<^uM*Yh&El9cMbrmU63h_?>Yx zK?}3Mwj{9qTqa0j6%B4mbZ`gFV*pR(HS8jtO{0l7la5?Qpy zLw7Z-10(B=AbysH@4iZbJawx7I!{;U@+Y^h>?kL7HeV?0=6 z*Jm;~0~vgnJxzy)uNXa1=l?owSSC)$Zov^#P3Butn0{B-CDyhIva<@v;0@Cd4Bjvb zV>otWNC?)J3Qcx)w8$Fo28VGN5p#$S+1L;GFo$ypi{Dspk|IT{SX&b4hZ7h9C8!JM z=!c8&A*{j-CAcOzfCM8rf{_Revw!tgWn>GPT_nEWLjULgVeWCuI7Uaq%4s^ zj-&&Q5y?d0*IUv^Q{-oUJ`@_d=u=n5C2x=l$e<&*feyc54`C=8zW^J35_kG%k*e{A z)d*(SxQ*FpliFyL-B^bb$&MIP~xC1sB6IDtVyloQAacU2D;=XLqui1rATB8ZP~ z!ErVrV6n1^>lTnr(f@OFw3SZ*V-W-kV`&ycM|63FidoS?N8*q{$um6(mnH;cO4w^J zi6_fIdP-wSM#E&5WC zm!(0CGPzx@Xb?qk2sL?=qj{4xsgrSunu`=SZuu-l@B}5{nkMlCTJQuzDFaO4hfL5@ zTI5!N-~>)EfliQ=w{Z+U-~)$pZOUVerFv6*muHF zJj6hZ^WYEO5dRF1=?(v|57U4Q{_qUd;504y3-2d(mnol8^A<+LnM$>u1aSyAc?cmu z2G~fNC2E><*q$l+Jgb?Wn^Ff~MG}SJ3KHiE$*>96unB&c3G#rOxUe19pa}V}l;NNX z@*o4runxX=3~gYXIpCyD>MmoD15R)gIWPl@=$uhmg7kn1{}30$29UIpoi~UwKzC8U z0y8_}55+*1HTGH@lw)n#qR!HxDr%=bBa0Pzp_*wMyW< zWWWMNkpBe-umZC>q90nKq`8gVcnEi@QvaY2lu!W!a090hPVO)X6@UOD;0Nz;Taz-U z&e8>dpaWXK2!&7xxZnbe@S3*(12V7%*D!%ha17*to3b#0Yd{VcgA1IH3^4Z(#lQ~6 zDX%%uq&W~2Q+g9?Ag@=Nr6M>3@)!g_0Ev>w52TkJ*LfA$*K5Je!G+_;kj!2*sqt1D2ew~7z_ zp#QZs*|DwUtCnB^pnwaHFaf&&V?dn0Z~*R52%>-si|_!DZ~*_{R2u6rgwRXtAP8k12v_q^u>4R7l^_f9>bUYsr8eQD7MKt8>bO^mrBFEo zW00@)D6pC^up=pR2)kkg33O-4G83eq!9oq1^G9zAQXVuJa=R&AYrD|1Yjl~JK?SmS z;x&5*8iop(fcY7nu(B*Gs6a%#130{b2^(wp8A}GeO2!FG1`SA7mwS3UvXKl*yR=N} z5Ukp&uSyW7Gqo;IwO4zqD0;h0R1Z<`1#epqHJ}Dt_7Cm=zqS##wCgN%>jt;b5vqVp zL%IJ3>5vUPAOn>r1K)s~-fF-IY!mn34sTHm```=Wz@(2muc&7ePLKoY=%gBKocwB! zGk`Zizy`+1e?lsGa1nVnwAu&uR6tD8A^kwF%VEEt=y{Hr9X+P*;?FnLO{MO9ON z@);(3u&VJThnl>><}}%>z44MK-765^3%(5Dw4-?lQTq_*ORL=|nq+VSLaapds|L7n z4`t8;1&bSomH?*!xBKhEno{N)8iv3<;K-@<0r3B@gtlr2EjM zjI6P%Ndr_xL=afKT@N9?ty;zw zF|}Dx1R(0gx(q#QoB_MA58*HcZS1R$fB*`h1~5m*x6CATTL%DK1g?M!=XeW#xDQUS zhN_Sbl^_H0yat@65A?us`s&C&un(3i!Z`pUPI?n#aLJgQ$sC*yaFDs5{G6dY8>D;* zr_2{_kk^&# z*YZl&m9WY58qtIem7yzLh+Pm&VY)dObgkveJK{&JMbak1!Y@#7-A<8krmcwNboKEmxCUd${m&8G86yH9hH_=5nF6|(uVFB zc5dqhj)a}z(!U0UU+(LE66Os-=BY#w*?5+vr%98gc?ekm1GoM&{16KR zfC64X4Fcg0(NF~xFaRQO2k*cSg-+`bg6N4(l-6Br*!{?sPUClt&^95Zl}zKA9v8(q zui~xH@&4(do~1)hdMHznqbPJn0ogrho>NZc=iVgL4)Lgyr#D?(?e^;zZ`wKy;SMqE z%mW75kPOz)1%+oE01gLG3N`BuL7la=&Atgi)FA435kD~4 zK@e~u5Tevd4*wwOuI}f!1})AOUb>_Q@W}Rl-jB=IoU8xWKCt5-z3GoDk9~dDBnT?vQvu^Zm9S5Uy>j+$imEPWK&t5CdQIalaTTp7cq14NQL< z#Ww~AkOT8z53NtHZ6FT)oDXX-2I6oGV_=+PKn>Y|`#zxiynmck>H{|s4aXq#5xez{ zTi*W8&|pv4Yyb?n0Sux}_M~U_OTp2t)dvZ$@H=eMmjU{6v-#uCHd-#ltKr#tul{0_ z8>tNues4BlFb>PG@q~W>ZjcNcRtSe+57`J1#}5D5!-wy{K{AI96=c}ZVLyBdB|^mK zqM?Zu2Q_Zw*wN!hkRe5mBw5nrNt7v7u4LKLd*qYK#ZVZbwhEN0vo2peGkB(rhMSd%8nk}qA_v4hGT z(4j?-CS7`TBv__ZuO{tD#4^c!{Q33o z=ilG|e*gp2Pm58KDZ-wE%n|MuM*7(&qIK{g=n&yf$U?XkGE8V8hZySTLl7A%;t+@q zx$rp@Q&e$97F%?&Bj93`aYh=0L+U6dlF4S7HDp*OlQoXnXCGqtiRzeRI5|j`HrkK{ zFj@R!#vOXx@yiD$queUXE1CT2E?Mpw%pZ=fL~N_U=s9!E!)8#-G0Y?brZPI&h*L69 zVCjQ3K23`xl0EwrRJ1K-GgP)WjDaeX6yz)5t zZkhK=HT6_fQ&n|U?c(b+nL1h$a900XYqfPhRkSDqjCKy#N4Rkgc;cE~@Y$!IC&0nS zpMDN8=LwHkc)|q@73%O>5Ane$Q*OKU_FHf@f^=MRA06t(qmm&+1|C|GffFHz^hYv& zj%nk7vvN3~5;!V3CL3`u@u8d?d~l+kc=Q=#D}K`{*oTH6uB43|(tPKg!S30p4K~%X zD<54R?s#N3XJBLA$r=lSPRH0lrBi>hNo`Qp{tT36L0vm^=N)SE=e9=66?$l$!ZrG6 zq?1;9>5`;NrqfRe;Z9Vjuw(UVth3g7Ywlcy3f7ly6?<&5^Gk-EVW7<<*i6dF(4o-wFGSRXYZt^}NgT{nHpao!;(;{)iCE1sqf;CN&w1}kjj zk=r;XvpHE-K8QQ?zyr0+{*f7H(rl()&_a1OG|@#-Z2bEg`%Zj(^2;~>{F0)3+DPlL zTLwI?3C4T(g%9iRwyi%1qqBEAD;1VaFfh(j)fK=egWf)jKJ z_$TDW`LrZ^{&S! zooR12J_DMIE_lYCP*9C)WMdmCwW&_cM{4z>V;${?syD!_J~HWFAN{Bwkc_BAg0ve1 zRWiVWP-q1VG^86HNxpx$;{X+Sz#YV~Ml@#fQ836Lx;XJP@M!LY2k=J;eV3Kecm)N%KtXe6G)A24 zBvRG@N^^(<989cNCD@S-d&uGdolxlkvH^~OsbwAj^TjKvArDN*MIYn{SixRO4S|&o zrerz@5an_ZU@`-lz#Gg`lWDxn*o#d$cp_uOFwJUa)tXuCR5ouW8ZUNJHDLrNY{-b4 zZ)tRB4Si@^-TGEFZfbqtndd$2dRMHyfe^%a-`DatoPGwDYzGBkKL}}9m=snxiiK-q zGxd)HJOC2@kVh;qs#eSjrK28&r&Bsnq`dH>5+5mHGQX4$rJl)nq|}H%#3Yw{{KKfs zFl`RjAUyx4c5I26aVGI*5Cp9TSGZS%#eDn$i;xWqmDfB`d#pvN3WcCpOO43h~o%Wy|&VVHHJ|H1Onn5=oqLs*3qmd6yX-vK_RfwNWdx3M_mv*ZnKf= zEHOSCm3ob&w!xdrQlSdjjsTN)uO&=w&s4FynAQi!VCFxh+A(Az0SzREb6fM8=XNHKP(dr=LL8I|XIaZz2G^#PEKhodSIl>O19`jqwM?K_IqPL}fSw?a z18DzY9vjiZH9lmIB0%Fq>*&Q0*5L*hWJ3#2P)8A-&?`4c*A37(z%4T20#y*A2;g9B zVNE0)a7>!Zo0bV>O#uOFNG2X1NW}TBd}^9JZp1S9sF8>M^D^d`#C#tczSimc(W51$4yz3mb_1>}TU44@a(MlA~wbeZT@0Uv=^wocmlw z{Y-+W#tEm*eQtECNUqeePF=_R?yQx08GU_Kn*Yk2Hs`xPqaegVpfRn3Bm+eLID|Mr zgdj%8nHG#F#oli51ZZ^OAoD0fIrjDhii6|Mhqy)|B$H^2jw7nkfX&c$v*Uk)7B!k>;-vP=|p7J=|$n%!RUG8&_$-3DW zHF)Q}J$mIU%>0oISgBb>`X;>D$Z!x>0Qw;O0MUIJ50PxZK)S+8hAI@l2|(B*z}9%e zJ`Umnir38^hJ{8c`r!?490CxkC;}iD;R0|J!Ucu61>J4Gk61K7i2uOGLBe4Y7zCeN zI|p&kN6d+)1buya8LiQez7?w@vl7YHOZ9s^7^Ozv*0@IEVX{v2-i|B>OZfkK`MoY} zt&W}S*T!aYspo|#!zSEiOs86He}DYvpCon%v)=u`9lk5CR|z~yDZIi1FyXK~jbMky z>xX}!hm4fMX~It>~C10gN^fhiu3O z+cF|@0GNr%0dU9$evk#d$P6P%7=6$OiphsC6bFvUfpGvBVnU3MX&uB!wy0V|;^{i` zt3zl*zbjflJ*0+62!-M@yXm2swRl&p zBs^6p1b+*#1F!}VITnJjn`4QPJv%*xfCey#xP!p6a{wrN7zhW{zz^|;elP(osJ&h> zxr1oIMKm|4lPHR^D1Pv~K)OMs5WW}L!OSwo;~SD?2*S%55+d{na5xAOBA#q847TtA zI5-AeyN4!uLLcyjD>R24ixMWP1Y!UtxVVRSKrMN|64GghHOYZbXsUy7!s-*Dqk{uI zutR|KI`z}Tf8fKcf}YF>#MOYm`0E+ls50zY9P8>uimXU;laA>yuXcmPI+C|D1H3c? zmrK+)FbI}Ii!)91xDPppxcLxO@CJN1hf?eZX1SXWxdw%p2N(Ys20*yLOgIE)=>=L~ z0XsXrFsOnqpoJ%>JzaExE=V|w+_FeQ0}AK>ED(pB^g+*i#to7e zy`Z(ukp*9n!b%Vae%S}V*aumVg{km?E&LZBzyx;i3vpN&arg_kU@>{Hm#%1oZS(;W zVh1GH3bv33V48}sK&`WwhuFDB#E6R)(}*SNv8_uYBnU{*d^T9qd+WC%&58A*MM18{%_EjWNWs67(-hjk!9 z9T|ncIfQI5hh6{?<^&P@y03z`g?8u#7U+l3I|Ohb1MUCp1wdedE~te}SUFuh0A8$3 z3M)Ia`-rXVs2qHbuhgjegq$BFOXOp^@Qadzu%!c_2Cb+|wMAZ`$oM;}mYWgy98w}ZH~!1b-Q2sqn#8}ex55$5eDerFq6mi42;pD> z1A>7Ku^SMf(t;?c0Ac|K`kNwk!TlVuu1t>nG^aDYk^UTm%E^lAvzH~zN5teDCc(n3 zs7qNG2QPubD5Qoq7z45ZjKB1OHt?W#(4Bo?hKc{7h7aA)9Po#~kivbqEi%l3fA|NKiIrK-k8WT?NwiG zt0R5HB<-3d{m4p094KuwDPiZ_i@ z5Ar;zvQv#H9X!1kaM)9kX#+?-A(0t_Yy^yXKoS(w9es$0f^m!4u}dF-9ktkpe{BP~ zxKwg@1-W30etn0_Jct~yIw8r67v;JkTU8n*&CK9K^OMzCMTO|u3~&O{MdS%yy;hSw zS#)Z|dHa-37zLJfSx#u#mz~*|g;|-cS(^X7S)H|6p3Pa8l@Ig!yJIb%WM#8u^->56 ziN4tz48e#kWr#yK082X&l#RP=UA6nnjc(1P;LFx<4U%zXzO6V{AF$Il$c6*R0dZK& zL!AdCsHLs&h0!@wDJ0abIEHR?QN73pPRNIPa0e%V7l?V1vmIPSWlLGehlFv|#KneS zn1x`-g~Q#7K=_3PcgppBIiv`G5jUJ5+ zNRFi@F<6Yt_*l-^o^Uh7sI-Zy{axUND|d1lz$;$kJznHZUgce0=51cUs{_H4prT!` zqiu+i?Fbi;mJ?V3h9HCQOe9VWUUdJv+HBp{mDpO1>e>tn*9}53ryEj5tdGG~^F~YxSOLvfq2G)jP z$Tc4bhH8LdAGm^5n1wYsfHe@|gFuEh{0?*oh6A{QU$}y;NZmD|!`8LK*DXj`sNq-@ zE-_dcIJuL509mu@6o{P;l7O$h{o+Nr(XC3Y+FCEu)73G`jY zuw>u+VLCcBS33>WB|N&#v_9*@A&U8!)Ji5ytuZ(Dfk|M6zX*mB9^oq(;Zm)JZP=Z` zT!qUGgjM*9IzAKD)nW5{-Pr$Ct+TqzwY9CqRPZ)z)IEYnn0^`{Sbod1h{)fR> z16CMj9}t9J2w~OzW`F-I=kj}1Y9MEvhPEZx3M7E0bcPJc;9dCSAAe42rC#cfsAqfb zh(+S(R0fGJr3l1g>c#?St(E~--UxyYu|)e0V|W82FoO7C=*}ElU9QtJCY~md=!xFP ziav}sT(QBpYtOZdkN$)ln1xozi-<)BXQ+mxnuWjU<`}MNA4ue$CNks-gi#yL*KY9GmhDWUZQGVIMIoiUpbQ|Gfi>v}!ywdt zu?i?*k^>&#E-Z1<>0moHaMPt*zBs!Z~b0yF7NXE`)_{=@Dmt< z!D)yRk%*BvZ3Xvo#NmVVtsr#!0kc5bHO9jYP5VywC(XaTCD!2q*lVepQP@ zeOu%47bgGOy=!~WHt+>k@&QF)l4IB%cd*+XYhWjNl5XroW`Zyj4E$smR`k4i14 zUN&!bXWud~=bwKn0wM?jr?r-A=~5~_gag+IGf(zsSDJCioMhmHO@MQ)7U(&rb4YOm z3D0xdAd{#71`JmoKrdU4uxPc|Unh)`{;h;4X_DyC2!6odF(`)VQwvo}c%710Eb$9j z@W$5}gRzi{$n=MJSOaoMh16YxQr!m}ItFKWN4eMrlb4I?76x7Ti-MViRY(O!fb#Wz za$)}`GRuA{EB}W#=W01e*=1+;a1VN+U#Do_AM46qz2b2*afyuk|s;SfN@|Y%a$%*!i*_% zCe4~QZ{p0UlV*`3NqzziDs(8(qCs~eO{#P$)22?JLX9eQD%Gl1uVT%rbt~7dH;sY~ zD|Redutjv9ZMovW*%cRaN!+w3KabteKfZ+emt$R1` z-7{uvl+|XSaE)WcRXUbUamarz`SJ7B=GeeWnA&8ke*IVuC-v&lOP2%O@MO{Q<(r3I zUk+Jga*WZ3p4>cs$EHJveypXB9R7WLf*yKfIFUme7a^DjEQ#?03v>{L(vX6%gp#0z z6^Vg_Kpk=D1AZY96Paa`!I0KpC!)AhPi3(PR*Eme7^93c(paO7H{zJ%OfB-*qmM$F z*pv%BWdXwqN0Jd&U2zquqmxfUc~xWo1V)&Zfz`H{Kb&kbqL*KiSelq)l38YHsHtWQ zYq7EUhB36+#zt>*(#hLz9Irm&U105p^posq}Dh{KS$deB} z4pb;{2H(bZzjbkrVU?h@KN|6m+3O4(3NFKkqb1jfArD zn#U3wcGyuRgNg)ZWhzCPY*j1%=%cdFLL05L(^6ZlwM;det+p;o732XdJmCV8ahY(f zx#!ZDA8nnCVda&?Xvr9t#?tF03})h+ufCn3>CYvXxW;B|ZqnutFml$Ju)??@(MB6c z_)tkU$ACm=b1gwv39t@t+(yT&<`az%Yp@D3Gah?r;6QEEgB~{1{gdB*EO8WItDhLy zt3tFwXEC7+La6ga83G%uMr|YpqKNgH+$LeRuibZp)~}iY3mn^QaB8x!;0w>7$&@}{%+jew z2dfKu%(RLg&fRT%%s%%Bs9Jug(yY-Mk#h>G&N+jBhj@vHy%T zcS&YnEw$HV;oiINzXKn9*1Hq$Y*%9opM2Jpd}JzPjS6OlhY1_NXCr_nKq-6!BZG0&`XBcoq|4%E7b z^vrY?Gu7%2Xb_^suR4eO$I|A8Jmpc#C&l9(20Q4%4}$+NgizTa2{|aj6Qb}XD;t)n zptG*EP0uj!dfU9RSFgHtFNdKy%`j4iv9O$c}F|G~QNFXt6D1!^8 zP+1x*p;+?h$3FrxkmuqfA&Vl&LneqjG`2s@Cqst$Uysh-vK`I5BZ?SC7uIa z0o|AfYV4zlYHUt}j0wRA?y@CJCmMVsRM2{_AXH4go$ zm8NqEU~1RN?^m;m73!w1&=oE^@^*CNh<|Onx-bjjxN~u#)zV5ZMrq=G2ky z#wnDU;xwl^<)%%wxznFQ%V>*aLgT@$A{w`u|vS~cw{P!j9d$3j+Xj3xhMWGhP}*rl_DmMa*$+8IfBF=ihJ;L;l8 zsXeFW3pM%dBtNGbM1sZas#xVsDj6wTAP}^x2vz7evH{Nkn zBAQwE9-|WbxNr34TNpxcq7sK81~LDJ>}32B<1za!tqTBrCVWPINqu%W=!GErRJ!Oqd86pSg4W1P(# zH@47X3yj!0CqJ(-J{Di!Z`*?_AF4QoG>Gxa%wLuRgP9Xc5<7Z=Lgr)r3 z2Z&s3%}6^*#)!r?x4ZpKNAJ$t;!f3te_Uzi4Vj&q*7OTn^RIuYsbKQ<$EZo2>U+Dv zG^fF54+V7q+O*o$t`_A#WPSg{+LF123dVJsbxqa|$qv{N)2zpY+tyZrtUv}*ww~Xi zD_4f(+0ImP9Oq~sV)d6^+Z}g|w7qSX!#w861Gm>?-t7x3a@ZK{1iC|=>24^m>*p)r9Xhc+C8wad-EH05A=vCXr6Xqtn!?}8uvAOXKE!ZRA@9Z4ssnb(QU z78U4&5jxZd=59~?3-j-O_ZymC;L1PU%LU&$n5%B}g`-mITwfR)?hZc|$_$LD`j2pP zU`D_~#2_U_>0jH9kZ1og?z+P&mUa;VqnSt`oX?g{4n12LsMV^D}l8a%c&@&jUja!ZT{@ zUqY-@$z=>;`DN>(TaVY0cO`>U7Hm` z$=@}hB08cYP9cv};Ujtz7WNv&JP$@?pRcLSC6J*Rf+8r2-ap9UY)KgWF_@gRVG7O( z9hTAzZdF(Ph5+fH??r+S8iXDc11yk2AnqUV1&i$X!!eA({?HDgQR1^OVk0JFGcI2w zw#Xzp;~`n%U}@p?b;2fwn!j8^D0*WFB3K$8+!~rsLOEC|a-AJcm>s%eZ>*U{?4Sch z2rlM9C=^2^>>?rv;vm9K5pE#LAz&g-W3srM^9|%dvK%zBh%_RkA5|mcY=}TqAE8v}gekqD5w)PHprfv-qgQR!3@Qw-A;JFLVnRp+ zEEEGGL_!<+9xy`O*Nwp(y%aJwWV93{0~Tdc?wCTBg;L_wLz>mFJkLKggC_{VMb29{ zdgNAy4{XKE)~y89kskc1&(*P_ZnUIsxMC~{P7vGy$H@vk+N3W=2t$y(VRnCDY$Xh3IWoHu1 zKLNu?>PAVvsm~g<&{-l8TY41{5maJ`BW`$s9^gT4;z1tlCW24{uFxec z@MQlU=m9VCB3>eA+mT$bv=lM^fH5AT+%TkL(#T;VCUs(`IWcA*W#=_HK zL@4augERyzyhG6FL0!TEDj?@w?&O~lAU|MV8&KOZW>0sTi*-t%hl(g5ZD&}Fs2~jl zctWKQ%m8l01VOn_V^rl;qG!SU%X*gJXVRvbnPzDoKntbr@y{4!AGJj%(-eU~o+$q| zEhA&LX`EtEiE@jarqGHSO^doHO_&~STqccbrj4p6j((CBkO3KJ0c;S=I(P#+)F%)? zK^(-v6^v(CLTVjAL2fVtA#B2`F_I?0r)mmX;UfG9H-YqAaxof?v|iV&W1$ZzCEPPAab zSS5{Sq>XYUq1wSO%)%`Ef+T$AJ|M#{;DVe$!MCo$FF1mw0s*)(!YWn6FCarO{DL>U zl90M9`fL^Ayo9Nm&kSyzI-;t=h{1rqs;e$Y!u3^1G=@C@LnKJ(aPmsD8IAuO>BkS8 z>7eM{mn5LGUdypgA;^+!wJ>Y5mTU(>>qbcHp6*1SHpZV~t44Yfp~8k1{DK`c!47om zI?#qU)N2~x#ws`h6dXVuOu~;6R5jEqI{bq-1cTG=!!tO;D1mB^_C{@)&cCjnz|vNJ zsG@8xOb{e&*}_7;E>Xie?CR($UK;3y_@uCu=?}EQG7L%`6<^9ijmVCy-ui8hoNV&_ zZ6d8~%et&ml&7Cwr4VFhR@&?iGyxgx>>Kn#)HcIEphGYy!Yl|a6#N1dpi(iY&q|;J zGGwmPGOC~e?LJ&B)~4#HF3?N#7MOYM>&77qveN9*iCdO!!p0rLHmv`y>?A6*EtpoU ziUwO^VBeVzE7N@J;GPTL_AT^M?_UIN16J?va6}tm=mi??;W7n`TIRJfZlD6(pn9e; ztb;Q+Lo+M}G6(_?tU??BK_Nu#Gay4Xh}HqDLoj&5I{d;qY^V!4LoUDsZ8?}4F_cTB zUpp>ooUkB-DNL01?v$1o$fa#x3GbH@Z-qJpTt3j4`sLi#ta5$-O zqP1|@Y=p2WFW5y?h4BVe6qL0t?nRn!W85fLUIIJVD>B?d%oM^Z;0EU&fFJ~eGkAkH zuy06ILpAur>E>%G{K6G5uuBH1bg`y5=gR(;(PRFv6}efu1eM*@^}WCtl9+#O`D$ z95Nzr^V9f%urab?WDMg#awJ2=w326x`ooO&Fh$4!Z zK`=l8Ffc~cI>Qq?L%AY@H-N$cOu{N$K@ecAEuWq_hL!&WV^vy~@$E)11lNgx2D6k7 zbF+<-G2>+-DD#(^wDDF%9uwi*(k)~7vG%a(H|LHZ4>C<#b2ldePD2frx)6riutuCS zIy;3r#{?ylFD5rb(gE?d4jnxc!YcfYC;S2+#6cZkbsexPBh0}si~<|*ZvaPe6i-7i z*n-hE^cHmSZkXQbo#vAgDM$AP9ipX0)5*bpw3PlXvxzj~*y=Gu!b!_99Ve$kh{1mZ z@^r$%suX;N$aGphC)h5g07zQ+vdSxU+mp2wuXj8G6dvh z|Bhr&HhiaSH%}*h&q!u}YMtDKgw2F!|93($waoVLX`iowfn>~LGCDkiy`};oBor#G z1n1%g6v%Qgq=M7N$pKu!FR1lwd+RTFYo=z^8K-2K>6&vtDH_8eil=dPTlXjlZ%FqQ zcP9cfBf=mIf+Fa6cS~pok2f>J&UBSW zHk5ZWr+erjH#w;P#g&s;mRIVQli7b}IZotxn8$2slR0X89=!cibN~Z6$CgpMZm6cZ zOe9RM(K*0ot%Ds5bE7dr5m860v7h4sEUb<&$4sB)Dl?C_A}~T2Wc#*jyQ35K@an1< zO!^R-oO5bylE<`~lDY@UcZsfhVT$^@Ckw?KLy$4gz2CdT;M%?;Om3wfSkJ_Xo61Y% z2QWl9uqQXDc5-H3rYHCUF!(}aTMYkg@^1L85a3S1Ur>hBsb{f*0tih7^rIuD9K0`VDQm zya!LaySvg)W4t@PlhAvx=;^|=goOD!O9;G7*xJE!yx@Rp#j8sO`;5iU!Fe{ukN&!^ zv;BXUI9%I#s=8v_{(n+@i|6JRHM<`WQNSM*^a2d(PwhqIdgvOQ=bU z!X+p|ZUn&+00G1h*7BbFlniFQjC$19v`#mr=SLybi~fz+Uq^f|S}GV#7x+SGb{T$V3fnZjhKoJ zcXsmArcp<7ZlvVv0|Y;T{0cu*iPO>Eczarh8oM2Kt#{p(6#C=m4`ee> zAPkaTsx8#f$%C6lwVwa%9PqDOa|98FOaMn>ly({26p;(W6P5ERqCuYSpV* zw|4y+c5KHV;YCd+&kOW-(dc7{EcZ*cPSYoc&I^#Ql6VTx zx}5l_P9g>8#sSEH23?rJRz=Dy{78$t<;8 z?aD5_{1Qyc5L*9_L5Hr(=s}-|`mQMP#%l?|m&#kOy!bAPt|LLX(jE(s2%u{_!W115AJ+$RHgH6WL^yUG~T&w|o{_D4Cs>+G?#u zHri~ByO!H-z1<8UU>-V869oq<=%6wkJqRcD9wM~SIM;j+Baa~E±P0VQ2^@f{R0 z>mof=&YTQnG+vt=T(>AT9+PlWs3M8@DOeJr5D`y1?CMmncIgV0u_Ebs8M|O zn(C^%%t%~G%{|vUbtiH&zlPh2;p?)Nh$4X?vlP>-4uHi%45jMyD}R6yYt=|#0cI?bQ9TurQxh@dRg}{zq!2)0 zt}B~gn}NgTUO@tBn8;ut7RY0*z8&}6l|)+V-nY~p_~3;H&iCSz7#{iLZ|iz%HVyJR zPVVs5b8LVgoA+Lz`gB;khz4@|?YH?w*H4GZhLdo>Yua0IgsUGasG0_%)Fg;AJ-{Qa zqMHBsaj!@zbwrgz#s5e)2u1W^5OT?wSGqEYIjAL8ZUICg((p1`8RI_L=!8RbG?Lf( zBX*Q20__l^JQJP}g-0{q3ZH~R7rxMhER-4yX;{OPWTa2d!&<_mcbRxi1}JK~j@%L= zz5OT%eBlcp9Qc(k>!EKV>RTU!*0i_xea$1#gP-A8g18Drf*Nx(2rN2<2a4fgfsg=3 zF*r6C1{MQzkub!`6oHmG+;I@0@LY)o(U!HmVS;HO1g%^F4#E)Q5{%&B9B}3j41&ZB zm>D4qY*16N)TFd7*-1|-Ym-U)E4`6z=R%nT6@a64C^kf{Ge zTZ*rVCQ*pkV1kqPEkr?(y5djb=ac!J#C{cm1^Mtq#teDoa%Bmbhfo2Q1}dVC*<{2V z>Np4!iKtcEWCS46K*2%A$QTyMhAS>Hic8?dgT}bT>mo@?d){+snGEGVV}nnB{xdoJ zj21u%`mKXx=1ftC!4l9-RM>4^rd` zj~Lm+pdd)3d#u#YWTrQn!nN&|L|l+b)}&Fx;<8`8%wqNUVi8qVFPM)7!Z9P1I5093 zA!76gDjXqx4yIt5@?vWZP>3bl?bTi`TB1f$bE)gp+TYF(1?D`UK22anw9T6x=B z<$x8fX!Y%I2^!oM5*N8dN|amu#hvuXb!$cp0(V?;SG?w}uY08oEHx_F2Yv6b;oYcU z{bVjJ9*R#1J?|C&Dp|7`PC|*pibCzf4>B@vjSK{t$Y4PYQo!QBs2Bw&2+Rp?GNO*# z%;r%O;aZr%)*|d|YF%8BI(}d^w;KxP%#|K}xkA2u6BUB)G|q-BuH}(j_s^ z*2u&?%v`!9cbzeL6jTgQZ&V`*?eV>BIqHlw5j@ZnT=PtQ(n(di1AL8;!^*}uXqVE(L=a=$##yc0J+VP112 z&3rbtvpLL@+!Aupo7V0wSGvV!856rweIm5bKvM@ZJ!%5ZY4N)eE!j*SLW#To@oEm;dUp^zwPN6DaPgzi>`!< zbY2HB`22Wi5`|MJjA1tj#G|snQxR~#9E(KS*Pazv1QqypWW*Z^0kcO&HSf`e?N$4} z103W8(2ke>a0|cqO->*Cpt1gI8lU|^hfOkPViRP@q}|BV55{ZSchfbZFV2Tv^f^9& zMc_(nKe0Emt&h-rzaEwO=8*QD$tyNyWI(G#!sr$Vfe8p<7ziUP!U7TO=wymbsFuoQ z(8*V13*}Ib7(n8-nr{bkCHlON1kH-uwvUBMPz56c1zV&0R&d0?uO)6`@)k-m$c200 z&DH!QDQ-;jK2Lnwk040zu;9--?9J)q<^V>oiGu%3^?r%#k_=+zhO?XkrsgI9D@H4- z5D!uX7Q~^ADz1&LzyQk703x6O3V;wcLR2EbfbJ-$hOZFhz=AHJ!qiE^qRkGe4a1u6 z5I7SGg$9uX4RJMI5D}5fCmuum6e>S}h{edSd4vh*_+j*bFbMU9Zjdm? z;>P|EV*T`D)Ru6f{0*U4Z)^@u{}2ZjWC|+6XbWqK;Z851Hl`d*WiF1YWFp}O&M*QZ zzzoyy32xyZ%Hl%gDCF*F4&~sSAS@edq1jN*ojTBwa0>)muAUmv8~>>g6|s1}aqz@3 zH5ic`d8;OTa1?cD5^L<|G7(KmLZUb^e7^sO1}aJ*O3@UR5VO2v{i;d{L1FVcD&gkO z0XJfBwr)|z2Gj0qP`A<%C;cfL&9QfK65M$5czlw$*73%$4$20?-7b$F<*FV1 zgwyO1-#&r{XaEjQj~|GTi3IB({|)qt!5=rVD+AHt=p`Yv&P-CuA-(7-B(e)(0TwXC zrJy1s@#I%Pq8L6#_d@0hL^34Luoz(=RZ2t|BVhyUqR##Skz`WuJWv}!a0lLio`g~| zNogm6a)u@|#efnsdkgZ=?I?+k#@PQ+hcE&xp;DIiaVlvb6b1qmO;HqG&v^*aDAQY4F!0OmmVI7Sra ztS%so7-nk&H{lNX&N2HAG9hU*%d?Xz(=wyRJdsN?*K@6Ujy#MqJ`Ca=@x|v*2|oDo z^9CXmQgbQ=%QnZWDXmfy3DW6ULWkT&6zQgJ%7jwfD<#wtBhjU%jI(0?kwEiprrMB1 z5d$I~CWkw^FRglzOiagm(x4J1!zO1wu+e&C}XON&jCTc41?a3ols6rU7;>((oSQPJPFlUmB&y2 zRFsa@k_MGo?@84jsy--BP~?$K9F!w)6CNyTG+d z4i7hQwwkKKXfk3Qv*kM0YlElyFg69hHg`CdY-{LaiPAut%QDnYUE^k4SC;b}4isK? zNjD^iqSQ1qie2vw4oqU-r0#hL4i%^ZjA+U#?$sl>5KQOtAo?{bAO|IvQ3hz$3`O){ zwcrvU3^DbvVd?)Y%pi7a{qS|p)^u?vY{m8vPnT)TmUU4mZRLeQE+grjPF?qr-#UsP zy4647APdp1vEvoG(l}$ z`4?T_U`civuov7g^T85+c#rZI85RfhD*sE72-Tfbtar^PRPZr?!+ti#a#J! zU&0GreprlbHV;z&lSv`ffLqqb{7qYpFyG*V6mIb&pf?gSlzPF`_BzsYy5b7bFikxe z8F@ANd{xfwjC_Ulg!?XqXBdvXrG;HMTjH2XWY~_YCW@e|DT@LJOIGs2!(iOCRf{x8 zO#+CA*EJD12s9OLeYiH0xKe$$7!6pje|i`C9*B7ft~z zF6Jr{Dql1I<@B}~dYht^KO|K^B&Q6?jFXQ$Wl|C76g+o1JRixIky)XaWsZlrju)DE z%n_ogW|#o^kLN^vc(Xvja#I8Hnh_$AXO^yJQ&ag9oZ%o8063iY!TriPd|1}sHd%a> z@F?vAlu4nTccGF$f^okn7gPD3C1#%k_RZjk6xIPGU{ZutbOT?9jSaf*5PG7gT3H&} zp$CepZ^InXF{`iTeyeBbh7(=2a(LJEJG>HIUs|xhIi>H`AL7Q6UD}+HH?BDuH=&Fg zIs_7K4H8I!6iy+G{9za1*|M|(sDm0RI>o2DI1$bv?eI=c^{}Z1+JvDRMjt5|x>~cr z#Hz3V8d^5{GqxJEh32bUkub>hhFaQhWwV;;T3_mRk|jAGrS~f38g9~=h{(B-iRe)? zBCol^UiCn@hnp#GZ5Mit8ru0o&PWd`7_q;IfjWj10=t%P8I7y)k)GPJqZ->r+q}Q`8ukHBt(%0KiV!n|9YS<;(8NQ(Xt@{loYzXw7|L&0Y6mbOV#t}&H}0+PH~vo_)X zUI6h!$dPQi>Qyh0YpuXkY=${`yV_Lc*>8ht@)M|@bd3dYks z#f5pr-S@=Bk*n3*N@P5J(o19!f+cjDc=54!Q<}#&7VZs8sNL3GU=M$uf(TfInB zyv@@JwBg*oGlb^DY<3?N?Iir@q z(WhMx=8Mq{{6mu4o&Ea3GaV`r;jg)T7*H-7+(~@#tQr-;7d}F}RlWIGz1HLZeMs0m z*4=!n#ZlhD1PGJV$9K1?@bi=uxzlibw>?6p2|ZGioZ6=y(ha=I z^q{XP9V}$k+rfR?1#H4VUDQY6)9G}!7{P;d+1(=+-t*n%n}go#otTjs-(UVp_I*!W z4&dUWCA5_#_-#@NlE+WaE1kzGmABW^8C{~XwwK6lZnmW+-qEd{$zcH!457F&9u~G; zxhH&8JsvFjU<)j$sm7h;je$-tA~CV)80vK8xAt{1+vevU=4C#(e!1r9o=VK}q`u1_ zcbi+rc)%h(At>HEzf7PQA8KD;De53XJ63mjd@sK6ut;S`pdnZ}6Jg7xe6SIL zVmyA^4M7Z`Kt~h-?R%v6{Gk(|pcyKA_9GTgP5k%w-#2t0Ad(0iNU)&6g9sBUT*$DY zLx%?&lPCw0T*(wW(A8qcp<8$%82rs8Gd< zJze{>>p!+ftI7=mr`S}bIJ-in8x_vnze^72(Ic4f;KPU$D?a=cR^mvf7E3-12@Ibu}QqR z@#DyoD__pMx%21HqiZZuB&GH1*t2U#DZRV*?=ZKE=MKKS`Sa-0YXqW+=vSPYg3AA? z=_x3Uc-Owgd0!+|igmdq5m;drXyAckm33Az{v5y+Tm1c1SA$svk)K<|^!3+LsbJeDnRphJ797 zm)BGN{TI=Mc|B;~fqeFPU{N^10S73A;*=p(cn)Y`TY5#cAz&#+y4Ze>4F;K{AFhZ< zBAJ~cBPpbqL1St{s0JvbJLXjzk*v158*sD@N9L@w)@tjmxY|19m%R4s>p{5&``xcs z3Ty1K$Q}TcCiStUQ=3B-breVp&dHA_j;!*_Du7fJ$1iC_G|4aIlIuuBisTYZFx9N1 z7eD(v^Gg_h*2`zL{P?96p`hT2Q$+UVspnpgRuvfkrU>g1$y@(KG8in7B>Z6_pk`*V zW~4-dN~s*r;mfHz?#I=Su9obok-;Ua^2#i??DDa@5-an}RlaQVN;Hpm^UgefH(#@B z0mG(G(He!6NOI1T$|`caA;>S?O7sS~;T|x_Dq*CtMH*}rvko%Ppo5Mx&g@fEMBb1~ zuf1&3fUmxY;`@|8``BYPs{8EIBf$krCB|S8NvzmqmFfWt!>5Eoir|Y;>}h6*_+dsQ zmYqV4+5ULq3CBWwjH;ep`D60vtzHsbCOxOF`s%E=zEaFN$1Xd0uJb&5cD3iOJ4tN< zf#$yeGs_du{gH&%Kj<(m(bW@8;z%%6r!tBER0kCEk3Z8OvyMIfpc9NYXQT7WxJxY2 zw!NSL3JMg0Op;13cRyuMHPtwS3^KtuQ_VBgaKBGAzwib>yn&2g%pw@%TE*3V5sU+B zD-{tb#VXd7ia{{$a82RIWkTT^YB-E>hoRVLU=%qNd1gh1&_q#!lesyR$`hYs7+3sZ z8`9ZONGz1q?smw-9{P}0u)CcQhiH%=9*c-6F`^QA*t?!E3qnLOnoE?@6evtYfi#Fn zwhpk0G)QF?5Y$gKkf9FRsDoWzNrfY(c82rWi-R~JMlg_Ji)Z97e*W;ry0o{Cw6V*6 z^6=jGyk|hEY|DLO_yr^M;D=zOLU4y;R8jUr4G<2-aWX35XGV#K zJ1hYT!)q1`JuwFu@&k0Cqu~u_*&CGk14&EFr7m~L%jEgNxz{d1sG69iQvL5*bmVh}3|#v~6Dj6tAC zQWS;ID|ti>j7}yIh=|cfJ4#AZHnBY`q)lvCxYEwv<_#^?p-)Fk+S0PFIy+4*PE89P z)h2|suyqnphX*H6$c;ZN2?8|5MXp&KG9p0;#wZYoj_d71pybjY{us!>2|6MyfFPG3 z%s1A$SZ}d2gxA=dF%Pr(a~{)h#ySZ23;yYkfW^h%c-OTGZOy`cj(~1cz?*jo6)7`_#1UCZHK zWwn)Q(7HT5*8hw;Ykc_Ll1xs(6P#>ZixCd1Jln2!z9lb*k80-^f#i$)`q1dvaEKROEJTxp z(E=H~ zB7^V-M*LzO?64nQX#xPd*1XG z!xHdKTYohF!-X7!;Ylx%(tzKvrKp>@;0I55nkt&%h;O*yAzt{#XXIxRDXO3}GAIaf z8Y9#@KrfJSK;MpU@^@G{K1a2J)7wP+z*v2#fXTm`@ijm1vQ?Mh!94?&TywU z9u`dZXl0Ibd4FX|Stv`t+Ys=MkH7p2uJFX${~-rw{QT!1l%Yr@Lp}#6n1&xK1{DJ+ z5ms?0&0s}gAPCu#3SCn_Yc)^u)MfJE59>fSuJ8tq-~}|W1koi2p&%%505xOPC+>7y z&Hx1eQjt#Hz!k-S3ZRe*>yidj^9#-Z3I*i|Ula#n#z0baW&Y4sWhQ;zQw^w)3Bh0s z>!v1(A}8Y?xv7 zcYkoW5RRsQZCH40fF|t$48YJ81Hu*u$PopYaTAe%5z!P#VOv2~4dcW;dBk;CHA76d z1SE)aa3EynV?Mv|Tpw58#%2(#b_o%ai=kPGdF1YdMe zs?cQxgh2drKVwu}z%w@Z!w3=;B2LH_P!&+FGPm_ zwPA*57$mmj4{BJ4-uR89^@edcj=(}<3kQyaR}Ln{6&3LmDJBw?w`up0d4l2(w@_Tc z!7l!EKg(5hkH{6%5DaioJ_eGB1vyi40>X5m_*N={J`_4VSYPf!S`r zBN0vESSm@3ALN*z5^tb#H`Gv>2{w0hS053vIi*4cRG^swsv0g7paaS|RL}{Xz(V^l z52GLlMlhPYQJSY2n-+SZr*(L(xuHcgQ?QAlhE|odnQ^;`o4Sdc7}1;mxAmJ2l7R@+ zE}Hcqu(l7^a|`$6460BdVK6SifRHqh3O7bB>%^UH<4zBvmwh7@brA$h&>?|?7?BVP zi2w^CVxH6n2MqlQ0Wxx(alFepJAw14;~Q zx(e^bF>BhUj-WYt#E;If34JG_J8%gt#f>0(sEFD#tjVEF`BER6s2S!J7ZD+u*Ajxl zFSf-Xn>9mp6Qj~clKzlBuK@~lSufk^C*7HIzKNtsN*Bc-1`;7LQA!F_s(sXer49la zrvinKNuP)?lN~jtWNMk^H&Xs71a$BVZcr+A+66ekF?Ko&16mFL(kcX9psdJ>twJCP zv(N?B+GYIER@JZ%#vq#6SenBiT9CS~>*1`H%oA<9^y%g5ebKL0Mq~|9wb7KQyRdk2MIP*WSWI^ho)V~ zF^*sd9ODMR;H{;SEo*9^vrq^F+64hRvL%bHSMx%{K%BHuu7bJ)pp}LrQ3Nso1290Z zL|e3p2Cqn45JohwMr&HNNf8NquPnip?U*Y3F(~}vbJZh&rdq1@(w#!*hpjplusUE4 z3nJTh0I;A@r6F&h5vHW1v3Rh3IDwyL%3$VqtUSqz0~)9QUBI_OV6wLWpqj~wFuMwl zAOwW_nL%l;0au!a`VlZ71C(32L))~No4L-Rp-KC$JOpW)TUsqvn^8LzEumW!@-O<~ zZe7u0z_k_vOR!$+C)afpZ!@+_fCqwMwvy4Xm~;T*KnmuGj0TpmcqX@>LAU(iFyiO2 zILU>biJ+4p39GQI%$m4>%ZkrnW0Sx+gkTG>xU6xSEq1yJD9gAkB$T5`p&l{0mHWPw zd%2-Izw}!Zi`u#4=sKWVzd5C(wnZTa5T1Vl5|yf?YN96p^)681Oi}^6U)weXdmsD} z7Wgu@c`$aod$x&@2&W(po6)w201FU{yl*Rhbn6fQ%!_AtJ6q4FnWf?e(Q3U{Lj^cs z2f+}a)JaN(JqOetg=vLkYPRIuSq%zfNqq{2Rqm%o6vDzj2s4 z`#Z%iB^SIowo+>mSOHuwb}Eax78pk;O6rcKnyRzAiDF?r)dL3wawo-#vlrpMPn^o}tHrF`${SI|Rt$$Wlf|ygOJ4jam?sxvoW{VTo}}xq z`9Z2$-yS|%I-}gBGF?nDs(otbrt0|0U3xgAdjD?p8vMwBr zIFO0s5~ROC2X=6>z%YhmG!NZ{R{PM&tH?2&49Z@3#OZs6N?Z}D+|TbTw6z@20(}6m z9LuttEVMk(N_5KwLlI*;A$_d~!5K0T^S~%o0=5o)Su%5($(keuIGrBJ3EH zHOS1n&G3P@Aj`ZWfv9l7h3@v{9w@+O_$s0P7#63 zeT}el5z>j#up>=iUP?kUnFyhPU?fbYi(RY8n@NN`w-7?pZDP}`ExmTSE!N99tT+rk zA`fG9Khy9U|8q|$hj-b+rjvlO@9mkQ92~DLVJwskYe3r$?$y5?;hC%3yUp8S!e|jE z;lRz%!riL=qL&czU({1DZLw+p0b8&F8z6D~M)qMafeko{!KK_?*xp^jb2hBY_%Kwe zv6Ah}JJBYUUEmy})0*iqbizWRvm-u<14J(5nu*T{?zp4Vv%$d$4}RqUt>IcuuM}S4 zi5DdpzU3Rv;cT6x{=zqlvbvNip6+N{IYJwDJ-g{PA8*nlH|^v+*-E}_Ef8YakRFXtUK^xLIxoNj3yN0$VC7f- z;8`x_rjDpx?&XNbBw>E)t)tcn_|O<9z$TUFj}nSF5wJJ6y2W7UZhTZLUVB3)6-%HP zzUv_i!xfGh&4Iqsqy#bliCyT&tFgB_Fzv?PTbQPoF66GHo{G*7mcH$ne&7%`Ixo=a zJdp06PB)t{>Z4xjt{(5Pnd+*(>gUnw@}4@dF6*Z<>|Cr^nO88ud?06Gd3H|c0nAPn z%*=@K%!z^C;y@aZ1EwodlaN6p(k|_n;~)Uz%fRsCc`NRat~uTgArNY@?(U>++xdR;NXfbNj<4HnZ>IiE)PVD3&+21K%fjzBfHWst{ca zCwMB@4das$8otRD)BssEIo>y(@r5qg{W|GSq?0JW?cE;Ym0tEE@7hw18!rFyaNh~U z(5azL^Y3o+K%e*jb*S?@53jA|^Ll?XLN6giU-XY6C#5?VZ(}dJJ~!;h*Gcvk;?S@T zuLqkVS=;v@uMrBBdGTIf=!q5fzAS~6toCMq_9ea+;coiTh`v$Y8|M!9vJdl|5FBPR z^LFpx@E-WQzlMC@_kN!ojMn=vGx%}S??>M^)dEdkJU4Ds@O(Ih)Gh4D7%_&y7?ux8 zq#?ZA10h!kv7G<;!^&4o&$^S|6(`U7B9Hp7v=-^F{@hOPp_vscIG@?^@AVg2iR_1|X9SFLhZE6|e=(xpwGMx9#qYSW%PeYQG>^=#U; zg}C;YTlb|mJbeEK9z1v_PP+H`<0M1*a^}sQKZpJt1`MRttzXBUUHf+K-MxPYPtoL0 z^5xB+N1s0CNA>MfhKCGy7gFLP1uww{y6mdL_<;qo#Ug5jKK5{z&xwD>6o4zoZh zM!yk3fsm{v@PH)44foQpLqr1mkRUxqtV%~%7HjN9Q%_Ay3?NozwN)Ics?o+9L31)U z(U!!uwmDww%$Hn$WzCag_8}}cVmg^J+21;`GPy0Eg_cX|?4-6@Yp=yNTWv>5Gfr>+ zzXi8Vio*42TXWAnH_#vskV>FE-9@xd`vigt&_D;JDpI$K=}gfGK`HD}IPwT(FTXOa z@IyZi(nFvSLj?^qSSD5xRf{PTV~JKbUiDRefN7PDVm+B-SJymgrdWTH1h(bYs$$vY zmVcnR5@L@#?pS4$Wj43tIN2mxp|$K1U89diI%%bsHmX~4pN2YWn;w$-CZ?~(8azJ_ z9q3*C4q%GjrwR%Jj{f}AlOKQEf}=Bi3x$+N&Zwd0l)YftB@w|EZU~Pf<&Ky$s$hwP z#fvXim1B-Yu8NJ0b8BXfgiQWXX3LxLC1%T)#DQkde`uo~#6Wfxff;=AvM0S|n$wA3Qp@WWfoSaJJ328NBP{PD!0lLgvb z%OV#*Ty^eq2dsq6j-#8>nGQHT+eZX});bD0=XJruU&x(w*3ja!WGL-oOb0?GBKuFfV0}v2b12iL$4!Fku&n0kl4CI6Z zmt~xvRnU&hxnK(QxJN$r5nUfFVIT!LNc8y8kg~%QqecX;s=!Nm3t?XK{$xYqwd(+k z>YG>O2fOHDVn?*q0VdY4gfQkvP7EABzQzw~Op%I{sUHy7uuERX z>PElBQQ&Hoo6ii>A7AtY|HxRzG};D@&0LKE**MLb*-T~rfRY?}P@HDn(VKZZWH`k+ zPI7Vwkc32MI@Q^da<=nao{V1fLirSY$?|xztO^_kl7?0MVik@sNDu_^i!?CB5wi$} zBaon!f&RjwzX--Kz*iV={K6aV6JHOD5l`;T6D(pVWho&+jRPG2v805FpFtM$N?68{ zmXSD>g*Js3NJIh>1^Y`*sX>+F>}gLr0_KfkMWY*m%9xM?qvoL5n#wKJG}5GIRDVzj zV*HSS+C*LIuH?--PRpHN1#4KvYLRoU)2wF&;aJsrCZ7s1o{YMrgQ%iUfeh3UfN(@G zR)GY9q`{#DRmv(>0SIphb_;MwMKF5d4aRz77*@eWFf59h=vBpD>JsGvLRw0LnePDa z`v)~(K@d`PrlsxM#inX{)12lsLwxDWYc&*GxrpPlP!ys@-`Y`pjqhVtRNO9WR8-Fl z6LSY}P051QGS@h@G*Fdlbf-!zmFdiZRr1+ZxoStRuGPE$-vw_wPl8tRmUnmIMQ?oC z>Qnustx*J7#Uut2hhU^(AW(>JeU$=;Uz`CBz!=6e*1?ZzAj2Q_ForKQvCCEAcNNIE zD59p4D9kPeq?;|JUr3RdQyPXuC0Z%_P74=H#l=#w)liD}(%QeQHens5q<`w^F@87> zxHn#vaES`4YwG3z$RybuQua(-HP@-om9BI{M_o8xmz!Fh;C8v2UMg4F${8H5d9}P{ zHC@@u*jewMC=9*#666g)m@h#G;)qo6lM!ZnMlP647+^eO6>zYhBUS;0U|h5_(o@$G zFdR}y;O!KU@B>}&pvul{62u`oEoVrasn)I*FnGcLv>()92t6R8E{e7bU6xScvgs** zK)@f4RUKR#`D4c-^2b0T2F4;c)r?8TH5=Wyz$eAgbf`N{GMpvl3U>F)$3}Ltv6W>m zH{01cQFgRR5@ydFKwb^u=PCxmh=>lO&;QtmGp2zKXE-AjHlD;J^t=i|K!H{KOaq_M zahx$%n3N40bX_Wiw?r!jM5E;qVW^QKSXM=}r37`p6^>y%kQ#ae(FCioSmRY!d}B2V z*>Hj3M1eS|8A+v$kykSZBq<5WxkmX^tw}mxE30ROsUxwcENz$7$K>>}LU z=NO^3RRFz^hNeOj;9Ey9rtuGSAfp$>&_po*Cb0@z*g~-GUWHyAF$sUV8w#^<1Q0s$ zZA6j!!kR55+DoZoGe}0WctFH1#8L1j)^g!@zx$|3-L6x+sxTn4c;H#J;E0E8M}jkq zF+WbS)QJ2vb0`v3l**cur`+;xyk<6C?xdK@yx2bnedt9$l$`I}^l0t*=vBXv!~52< zS~&>!K#`1Fc%$6w*he*-kv~SvA`PoTC=@`!hB*8}5J0%X?^jg^;{!p@YyieOAdEfC zETIMj$9CNWNKUHz0^FR9lr_2s@7Xg-L*dU%-WRKnHZ_Gu*o@Jh?Co z)2!>$gF@4gNH~B^!H|RLkVsGiQ&Njqvb#v2hV!Gsx)1}0vn2TAm{g0uE(8Ml3%d4` zxK}$s-S{~EDGid_kpO%y0(8RyWHMtx7M^)B)nUMBae)lf!#(6ff}lVP1Vr4yz&;GU z4Wx<}vZs5xie~5qPhc=0m_b1htV#TZS(pSCJU4%skzcR{U}y&7(u5hzgmQBRWSE6t zK!#`VhaS8S>)R|LtP8X|0403?ExWliy0DAOAPB^p3RoDa@~gsy!vnp;EVQt{8+$)5 z6g)5tx{uMq#UaBUJ0_pUuZuzCgTYk+g&XlUbg&11sD@y`J%2z4i?WA4n+I1bzFr8( zW^f!n^9HT*!L++OyucJvz?+=Hi$T*xf~chsNsE0rfGG?{g}XvhtEXqYpTAQ^i=(k- z2m+3d+;rJnbsVr-aJUB+V~d%BDokaw$z|gFaAEO#8t&E2@KjvP5_LLd-D8>B|jv z7|39#2DCgdZ$JiAtOk2f%qv)h2;+zQ5D0~{kR(*Gj3foV?90#qOpi1zBl5+>x%Xfc%;Bg*~ijQ8lRyGcfcAE>#?>h%r|z zrRVG{y-b7<4Ji$y&Rh(w6g@wGc$l1%FgSmEalWrRVx9#(gF2UDg)G2iOrS_x>rHZjqw;t z`a!&eElO+u(|p^vT`&U^z0P3t#XMM1RN7ATJIp{yOc_=W10Uv0C1UiNhVN`c{)cBOtYt%+3;l^blhHjduCQsS&S%)~k@#Y4zA@t%Pf}3X&vAs@T>@?bejrwfpo91++uf8Ao@O*_qWNb!Ask zrP;BX*d3MERzaTgJl4m#SMEu|zW9q-y}N&{6b<6D)!X2) z*_%zry#=eT<=OVDHnNq>iVLQ$n6wu2w0~VV$JK)rON4xjgj0ap&3Xq6E21dM4L}Q! z0r{8QNpV@n}ke6qzbb|+ty86YsJ37I9g9@T7~;p$Q?qzsNPbl+)%jO%_2+;o0xaF zij7L7#u41nMPBke)m593kcFXpVqMpz-;agek(J%It=;-eQqoyc-ObNolMdr0-~y)q z9Z)4+bu!>^T3?Bi8-Bn+Z$Jm&#Eb)o$T+ag21|o0U<6Nim3_!T2_~`0wTnSe1nkuV z6y7Y!#jsN-*zet}f5^9#tS6!KT>LP#^_@5}ZQz#_)K!}Sw6)f;^@sVb-y^o)kOh^t zon3C-Uj&N7pIMdw-cLMQ;48-Bt3lud4x}vRqjKos9NV~musyR31_-kUwEzYh8BRjT zF+xCwGe(ALAQoV#hO7&QV6cS^Az?k>wp18|kW%5zT3WyeDHQQu7}i|N-K=13AfvdGwFKJsg*N~@K~n|a{EJwOV?eeG6-HqW zA%(tVWJMO=e|TZYu#d|6p{|IYQk#nA?b;o_Wk5Aujsazlwbpiq=hhWv{3T`mP1)P+ zwU(`0PDldZt>u3PXljw=S%#W`=Ac`4P;{to6TyTaB@#A0^1d$G8^Xp>`%f(aJUYCB;9Er6X{^ka0 z&+)nGu9eD4)@fz5$&Ll(Hc(U{l~%?c>d8)Gk>#oUrClS%XXK~^PT&Mo%8g9Ogsdj* z(#E;rz3THa?b$)-_5@*XC@^nW$lMb!>AR?Ks|MXOOWF1ZYG~<82nJdpg@J@9MIhUhmx#dn1wzV!ePh-$w~!8#)F4?s8Ya1m!{ey5@&T86yJil!iHC7JjTSX z(P{l@BX-?3;IYU~AfX0o%6{*nzU+F=>`6^h(B_Rx7^cx)?ExqMaP6?_)IN_^E^u@K zV@n?6f3SyYa42U$2mPohfNVN%_^deoO@;2WZdL?6CWTU51(E)RR9FR*u8R==1x2Wf z#43eCD1{l9?px5~QecGY9t1oX1Wsgx883tr=4(CpZrlRwr-)Gpy$bf@+S0|R^j2># z>}hunYS*oV8+BB({pogoY{|Co`&MFlcH8~N#+7rDOE882U+^_&^P)I#1n&t2Z*y%4 zW9S2o;}FYIT!(cKYk|mcfhffz5=*mOv=tAAR3L?3&|_p61V2cuRNyo{7=%M#?iWu5 zS=2XMcx&^S^i+`aU+9BG)3iwE>kzz(BUcL0Jpfi=KQJW!h&2YTg;>U%j`H|J;w_(6 z$8M{R#r073Wg-1?c%J9{E)1j|z+D-pGzV}ef$BMT_GkBqH;40@kaK9S79E}y&=@mN zkOzyZsN61VxAX>fa0XR;DHO-WQdosjFauIR1zLz>TPTF*24q7JX%nn#k#5=&J%s|x z8$_6EPY>}OAM#LJf_D@;ut*y=7>J9*k%H)1j-d!EI_z4vxGCS{pT=^}VC?y}a!?Tn zFAw&{#&00SY$r}K954-JKPqMyaBGM8n4bvLp7!#ncA1}(b0#j%(34S^1f~FmUzi5i zeg@rp2Dhw+11PZ2DiLHTX+Qo2cE1aatU8j0s6$u(1V%sxKgfg@*8_V`1xBbkM#x?p zF9k#JgXTVAZWH@dD1|=gZWvBU&EO9KsS5Qxh>SZ33$+N2adjxSc;LeLPrmYI?0Cu6 z^&JuUk&owLC-zc~DjZOG)M%2H4{e;s{LEhnny>ksxOvSNlLoKR8Hve13j(Sb1sGh4 zyaGsjIO{(@0AntNx}XI;mh@mKgrG;;f-rCO9_q)INy(n?!uP3TaBs$^ zY{zF}$oHI(OD4lqy96Y3cGM%$P3OumR?eA5MP7irv%+CkPxkpn^;awkp-C zUz0=~@aJ!zKXk~vO@w7DSgKS;VZq9UHEUK|yGZr21$Nb-tZMXl`*ll?pHhqltu6Jd z7pY;$QZZtbE0rQVib^RmqbF@JJ&G4IZtR$`m>`mafXbQkpXJP;c=7|rCZkN4nkfD& zeL#~Ym?1;E98EDb>)5hq)1KkuHtyWIZ@1~0`8RNW$8-k|-ex!Q27(occXr-B18ZfB2G>OF6Xi^pMvF*4<0jL1c$V}tdvm>-N3B1jqs z^a@;;mYoSEXk)s0rfCzU`I$xn+w_{8K(GNOYz@mq=xxXRc`;5FW1Lx_6np$}a%`YB zAx?=ds-2@k%;AZ7rBV7S%rVP6GtD*Id^67Rk(w&cJ^PGM&Or-3G@G;0L^4jb+6okB zweq?vulxE#jg?hfp{`^7QJ1KHNc31)d7$| zhoEpCg@YaHlyKj%fxHp;#LX6`f-oLxme7 zSif919N7_3P_&c(jqQ+TGDdMHJHMNhQz|vRDN?bDR=gq>smQ$Naj}c4$|4xU*q)e3 z$Tt-VAJhDC0H;N*7-*c#5(3AVk*J{*_zMOyaxsWVOsZr+atb=0feimS!y6^?Mm1Kk z3S|5u73Z=`wZ3JBJ_Lgiiy6c^sxzLp^x_w_;7V2|vxQYCPBO(ImM9PDD#|bQIc}md4wm%X;QPA z*1RS*{}UiDa+8bM{3bX_C^FnB?TtaW5cs}lPB|{dB#F4uji^D5>G)$FnVg^f)-exz zkcS$H7=$1HY_W>K=m8H|NlPl$!ic}&!4G(Vg>TS7HgDwbDPyw-W^i$>P=LZ${CXTt zfT7Bd(4?fOah)*r#6pgcDVMB~VQ|zW8yl(whdSIL5Qm8q*d4QoM=ae;Mn=y>IfYs1Xus zPFe>4#Pd+Kx4!)?aD!`~r$)874-qbMgO)TlVl|CEF=tnU5XUN^GFeA3DJHkXCO$EW ze@k5Bve+Ogele@yps(g`4=2%`j8MWShQ|;oeI_9VcAdg6fBl0Rq!`v=w4w+J+9FB~ zRE&}p6W?E~L!#cGU;dy{4P?MKzSqLcemx^He>~PC57VhK%y_E%^8!m$7N z^5y(tU$W-(b7@k^gBg6VGQWn-Atj-hVpEgpn6S>4>DZ^DQ;8cQ$58(0;Q{z8=;jo< z+(ErvqMfqnOS8M(?tb^Dwn^zq!@J)0$@HykOyiF7YR93T<49mJseuQvz^MF(*o=`i zShzYY4LnLJ2BC;xjDi%Up=gP!@z-bIuaNT~8&ocL-+6e@u^2%ON}LV3WsgMvEoK&3;C+{TyU9(QsGZSD_G+bPCK6p8Jv^rbVs=_`@9(IvqZK*|vKs zd=Wc62k6QX`p|)TW~aPi2RpdLC6LZ&s?)yqwqH8bqyDqo^WGy?H|M5%qV@3cdouq1 zx<$e+c8id`?5)$5V#3+O+0SNY?AO2xBabO2JghT*h@1fE9F;}J)UmnQONGRU{oB}TYm4-O%!YPD8435Pq zKms3e3E@~{Ke!=o$f3E}L>=NGH15C~#2(V|p&?!)HfE!w<=!ARL?LP; z)e&D#bQRX=#7=ZnM_GvYG)74%2H06m!Qn*R&0tum0V15j3?_mhCKn2 zMjHU&o&?=2F(ZVmoCB}ToDUgIaUIafj1@{~PTXjn$gaRy3 zgE)wTJ&40o*n>Pp!m9P-R$@#fq+$tbT4#MmXrLt&`iIO>q0!V5Y~WcDZ3JD0TRaBG zO<)Evjs$ZE<49%}#|Y+c@R?y=1Y%y^cs!tEmL~-N&SVA7-e#^Rd$uQhU}lSHrh7hG zjXl>J5g1#UL}?ztRVKnbJ_B_Vs(1Npg>14YL}ky$#+Ulc;3=8nkS5&Cu9bXdd{bf-YAZG z1bjl3eC8;MITwat6=-72kbJ~dM#3q)raT=0RJ2Y}P2W})CZ(>pfP>KiEd1Y{zDpu1jV#gbQ)Zr zYR*QqsI)nwKiFZ69_o2gAf?o(k2b2K+USn|deft(SUGsqjcLg+<>yDt6QcFRK#G{2 zOoX=3<5)NbB)le9ZYh*57D`QD7G~jTC|Il_7_+&ef|L%0PDER_M0C_#N*)tO)afuy z$B2#|p$Kbq=2R@Lq@dPL$-E?@Mr#DlXz*C$q+TnwZf2zVOtzX>IcU|sc}Z{-DM;w% zpR6iyXbUEi0zNj&k)5h;s*yZurDedvPTVWLmZEl2{s40s!YfLDnw0>*^PNN=LYqyrH$!a4vO6ti1 z*SB73uBeWthJ?B13A$zmRK_5w?m{{Lhy#=QkhZ{}9?&Z_-~kO3tm)p3|+3C#+#mwod62M3QC;*X`M}{M^*%(aOWwhs@YNw z$I1j97AnZr?X*(sQLU`r?rk5YEVuHlZ}Ef6*5{v)t4Pdja9pir-0WhU>MpdyIRu_s z{cM%6U??mB(q`__!a*otPtmSlkUnVC1Vu-cT-kM&WyJ?e%AW{n!g6rsR_bDNQpCeT zEJyOtG1Mgi3JTkrn%nYg<(XyN0)fUJfT7wg@=74yN+#eouk%u!-=50zPSrSKRXGM^ zB$x!^<_YY|&gL(uM*i6hoJgpy*zm)bfO~wyxHygrK^d zUS>pe0Lt!q%+2*F?hY_UT38Mpu`gBR zcW}LJD?@m&QfWqX4JmLKE=lBHPN?ShhA%a|!#e=aYT_e3rbv}Ui5`f7`tGpNx-SU9 zZ~Q*!^)}XPF<9!d1jokWwK;4hNN~=9gl>de4%G);GRK9PXfZI6m$4Z;8VG;U8D~>)fR72=Yyd|2d3R^^R{{ZZpaV+f$Yo7A21XrY<;zmd4*(Q_d8v0ztKCl*N z*sO$3vnnP1;L-h@kq2LkSS$H)^Yhjf;?4+ z4YJh?;v*!m6DfpMSOF~#D~1jevikb4;BwV9D{`hWPQgvYIhL-)MxHFK634FSbKuhc z#;HGQ@-A^QM&t%Zurtps2N*7guzHD>Zn3X+ak&xdC1k`ZuQJ|7Q!N*?K`Yg^9`rQP zQX9XqJd#9KUSc9>-iNN{lI}xAuoVo-;8>7Cf-(lFl7bC4#voI3<{C1%dKx-vv-Pe{ z>{0~w;21iZuCi@Tc&=zg|0t~g+GP`SOcZajJTovnzw=KUE9zh*pVjW4un=Y0MC&Ln zKdYWUcSJykvB*}VLT9yBQxj%xbryB3vx&o>^0JYh0yQWlMntD>zOaA}s75zNABR;U zu+w5Bf>d^NV@$J2XKpA|uaIUlOOxfAX+%s1)Gq7 zEpiw&$mkGC4pUlEo|3426gBjRCWtzyRsPIClw zp!0~1LfMpG8Q#zu|E$3eJn;dnK^?5Y6^LCP=bw`APQL6O=g&I}L zHC;D`yY50F=(TbiZC~qK2@dgcdFhx6@g-Z1bU!yxRJWd_*-ZU!Na!@jP{bOn!Ys%Q zet}{o)WIyw!WG=c8c4#CANeFuL?9>}s&0EkYswR7uT_VK z-G`HSh{Lrr|L+1UocQMQ#2SsIL2k^wqT`FB5#zX0NYHq$ATmwMS%gWLPzQBKK=!p& zf|gIjm6w7I$^-r&`9vhemS1@w9KaR)LLl4*5(K%G&w>x+fax*EJ)hE_fDR0eQ)-ks z(M`2`s5!{8xdqZWwO6~fTbfLGK|$d`Z-Y>kHcLK&uevTDMm!Lq8)eC8H2VCT8nA0V zF1ll|>pb~GC_p+5U^ozquB4O3Fnx3OWXSdICikS~MiitX&#!i>iD7cNMxy#YoJ}d{ z?i$R(Bs>Ro2q7|XLM2?mCkTR%Q@jrZ!Y^!j$p1o;v%)G2`*ni3>vZp^w}yhzUot)G zKhFoW|4ZuxZt%75JkR&MaKXf#AHb75RKExdC%UUy%M&TQ<3|nO9q2km zv_k%jO*-sDC3HeXO#H3iJ;@`E4_pB$sr&)5yy_^f%)>ls9jt|pCu!ry%_HhSPrJ`= zKIeD77`?=f4L#9&@A)*8UCR>)Y#BOi*TzTrDp2es z|IC7V2f{4ux(}=ZD};YAOajTPJbwS{tI8@DO4fDDZG%PiXknfj`N!qMC_ucq_VnvG=F=o`bkz+@XA3=r`Ig(^alP6K8RJoF6OP4QU#*{ge zW=)$nR{{YN1W!+&c>M7b8VMFPqyDHx!UKsEsa;N?LW-0q)X{zWf*OqkscNE#dccBJ z6P9dPNT;4AD!Vr9k|1x32@M*GMqRsi?G_7q0MuK*e*p&;{1=o^!-o+kR^0b3oC88D z7K1aGa%Ibd+h97DcwwbVK0t>SJ=&sYZ@+#yLuZd)rBsv@P71~;=v8mQeyv&)|9Z`= zS*vni@o|OKtVw|at(vuabaUs=q5C-InR*-R*V$auxt+UCHk!bLXVV?XcVIy^ktcut z-@k&Fa4Os}pMHJ&_wnb~fB(`zg9H(ZPrv~QEYQFM5lm3Q1sQD6!3QCXP{Iin4C0QT z@Q9?UpxSd!sHA#2zz;tXiR7tWP;5sW#I%BBA!=axN-Vb4g5<7|)&+UcjEemXG@+xt){3^S~X|C)l56$iy_w}k`} zu&6nuA+o5&maS{cLaQln_27{*B{?kDE;#f$fJ%O=ba$b658E5C$2g-h-+B37_us|+ z&Fq+nJUe)yE7tgdp+1TV)kNQI7pNj9RY! z(nrDb2h#L3!C6zC{o&a_potH4)c-OmI_l+_Z{GRmp^skr>8T%(!*LG-_NPd;=I5PX zjlzl_qtJq77xQ-!XKc93VtXyHcfrG3F)l0Ydb>k`4DrN~bj+c6EdwQfEJSc`IUN74 z5|_NxkjRPY03i#+$bm9}C7)2>g zaVF*9RbsT)6Yk|ID@l14EPO-|dr-qE=_?y7m{OLptgTvSc?u-tMxTIgpVK4A>vv^_T+`3_3rU#Ol_t21*1YAq=U6 zEk5Xvb)ab)s%XU}15pWd1fv?>KnI&r@dF>Q;unI*Bqe51hZ^qkhAY$IFE5p;-~I4C z4JzU>MWr((QjwX>bmlXm8BJ+UGeS}NP!=;p4PTAV|BGZHg@<-!kYk+)Y@}G9wZgK- zwXD%b+aiS@bVNTZ*)K7JR3wt16p_6p5-@t%W0Le0E;tO7paq44AQ76cVn}97ZCKnG z{sqxSV##rkL!D@@5T{@KrVbC8#4I>*jDM`78qNrY!dkJARyc!n$fyPgE0Iy<7-wX= zj9o7)0!*FS%rL_w=B6NoOk@f~naZQ)QIVQdr7o4JO^srdk^&1@#7&FZv>IDru}#Gg z1S@1D=PpihPPnP_EZl-8TjsbgC3T1&hrB1hlr+G58I+(4O(;L`b-0D@m9Kl<72p7? zn0*`rEA1&pLnn%*1~PI>k9!wlCP=}BH2h{r=-C!HEw+0K@>wYBYSYhuOmDMhMO<=!@vLZegsH8I-^3PFql6|n9? zZ0rk*+em>38p)Gi#psZ)?D^Kg5LBVcx^8mdUS?0FH>rEwMZAICs!Vki2@ zB^Ase2lLEd{c)8_80@|hG?-^&rxDTaw0GY9DQbaAA=VbpwFWUNZXq0D2~U{96+UV? zfCYzIs&KaTexhYOW9Ct)VcKNYahsiGg3aZeB5?8#} zjZ%042Pq*BdC1{0vOmJZ1|=_<$x9~B{|)CPFdxa~v{OQ?M6-nDiDm|Z<0^<}+Axvl zRAMt;_D7iBv=D+s7QkWxZDr*%%Sf)@<51`~v67WVU>0Uc;T5BgO;k!m&x z2V#bhMZ}6B@nN#El|-D#DegR{`}EMxrocEX)ZJGhBSqXBTZX%!@GE+SoI8HRY{>^` zGLyR#9yqh?WjmEfly{|O6Z^`&m~bfL7RyM-G08IV4_wRfhfJpXLZ2YE1|!5waKkDJ`(_DD}OToq>T7Az3a12wLAm`AfH5@EpuA||b^ zuZk5c?F{Q#?JZ+=2~ZOXA+2Gu|6A%)pEuPqQ!+$kCK21ctl$s%WzBLJ?T7dP*Hab> zdwc!s#RZ#jTT(BT2?C~!6x$*DC36Hd`|Re-00f(8kV!Qo9aBC z_f@^+2YlyyTVM^F+u|4F|HQ?$;tEl+Fxd*PhPV1AE&I*^3LfW3F-qec*}Ip!*d$C$(c9}q0$M=G8I_{=F3zGe8fDN;7@ zKYFTaRxMRnW(0Mr{{$Zk7^J zcVW~j!;jdI1O1^He8CfJvB&-@?oOpq;P98^@Nax&o4_Q@RwBwaBft1g`vOncG=ta> zu{k{Byx7dmEbb9Ui^_xuCI(^>V;V%2lH}^K6oLy?QAa2Z zD%zn-{2`$F$keW@AZ&3C{LvSfL{kid7kg1XU=-?x%+@RW ztPBR@tIK|@|6-z1G+r*SI#M)J@EWnvAUW_7W1}vawcgqii8Dj z&_$9W=|!L}9^ppcNWlyu0TGUiSFmfl@CHiuu^IeP2!vn`d_fBnqZ#6@_$WjKA;RsF zOd-o-Bex0=i4n|5VQZYiZBT8~TlJF+#ZzW-+ zC0!B;y{#q%b1(_BFqg+$BEj(@sU6|bCu!s?G%OPQKnx77D6a<;CS#!3ZVmr|DV@?O zp>i%0LkOtyudFgcY^Qf5LNShkBG1bqYYZX}?*L|pHqVkG(oz{|(Yp={BN@m0=yJct z>@DF%|2RWqBqQQ3c}fxsWG|VfB{va3VA3$DvpTKwIum3q(grNDDk2)wF|*Em%;^q- zpdl!wC};67=8Pab;WI7xyOPgKmc${C;lDt` zEPcQ>6IAae5;4}Yz20ka8Vef7%rz+#IUzzhCq)|*_mkQ<1IT;_K)(wl4|Gh-QXvkMByy7l`>rkjCR$3K6y-2yEscbxr4*O(BM` zJwr3RbP^&y(LGCm7n)KCGF4S`F+K?gRTbh=G1VXp4o6=GQVniXmF!WXwC$F} zDy2^}BVtwIC0#EHK}iETWVJ#0E?NA+R)O;nA&*WRl*GUzr!*8(7UB|ifI^IQ{~`c0 zS%+x!@HARMHe^Ni6Rk+m6vA2us3)@(Zrtd6U`DIL^+(wiNjuQTic~QeB7z`eX4~~q zp-%*%wEX@CUztQ-r!DQ4^o*KcCI z#A4~gR6G<;9Re`3?dO2*B}cYx-S%x$59%1A(O_gnSJqpcLL83eKl)K-dDcCta#aJA zNg~1*{+3(~qEdkNB8bFF6~kz64rxcM9kUd0>XJ*jv>`GVCerdM%#1Aq#-X_EXK3v2Hw8Y z4;TR%PAU~j0pP-d5q=>R$YKy|VHJWQ6&N8$AVC&-!K4(%8wkP|M!^w)<2T&Ec>z~P zbp}fbw|aqLc|DUs;TMMCVp?e*ZsQp=gc{HR8IVB;+~5}`;WORfH*nxm{Sg;+r9+0b z^NgYXG;g5)QfKDVlM%XSm2}m(vUa|MltbBNm{hbL0#}b1|1{dbNFk#@D>Nj}mzHD4 zmhshxRn;&=`Dm$3jENZ}R(d3m`9BbhRK(a+SPM^|P?~W%r*-;N*jNuVOgk6N4-{b# z7UG+cfh-sy82Z>2u7MiXfu(!}DZFS97-0|+!5%~jbA*5j+<*!`lL}ntALnzQeL+)# z=x55J`> zn)o3cHZhEGH1;|W|5{9n4X~Y9=2C`-M)mfFv7|$Jx!Nk*NurVXcXqXWjbl;$^@nj)!%EU_FVr3KVkwVcC*cV5Jdt zm^eCIg1b}3A-sFUW|44Y__!x-2qn8B()%GkcB>!oxTz=-779A&e3IrbBawGhjd3By{|_BcjLulMRP) zX$hUyQo1FMTs}gDBbI#UVmh(mJGlL?%3b}{VO{EgdeOG%9n_hnsDT!cff4*5t5BQ3 z*BKUi;+ua#6r4_6=ir_tfoJD=*`Kl*gw?}6mRS!v&;@;=KfTaR`Vo;>AsCN3CbBhK zv&O_-+^O;LcF;MJIBE^$By=1@8$#0`OK`JP#Z3~iWum2tMG4l`7>s~#+UiaJ^xHNpeoINI;SxHS!|G?Ce0D`gltW7>>gxlJmodZoe@C9Ed z2w&ZA&t4M$5GSGz8-Lw>ULz#`BjEZVuXI&&jtC26>0RRUJI_&}etL+Hk?7 zo>xG`4{Tu;B)AX&B2}Q5L$=VHGi2UGQIYgZlA}qhX1Nh^@z*3r zsgMQp=I_#ul`LDjd(v8XyLug3X{y(;2Pz$_MAoYhu3@LTeH%5c+yijy+J!ndZ(65L*%Srl zkKez+gbDLYsW-9W#a?GR|Axspa^#wbC0o9XIkV!&E-x9oX>eF3&7@14K8-rH>eZ}U zyM7Hjw(QxoYumn!JGbuLynFlpoj4LTtB0vY!h;;SA4bT2{c`5bUf}717pk+lu3E5Q z&d`a%0n*W`U$a(qp#q+Y_+P=EdGqy#v;6roFHr{V$JXI0Wh8wb9X*oGeZFvDpC3h0+6z!XN9L6^J%9DVcg_J)0z z07qk5E_w!sU=?hQb@rT14|GwCyl8b7txx;<<@dxKl{&mR@S4NG9CsQ9HNZf*cVnx@UYjM@a zG5nwfVV_q0!_|ctekhlqcZDcoo&%x?nlUr>#^z(b$+#(#w9)6LO__`)YO1QP%4(~w zz6xusvd&6tZqx(@<#AL}DcoVc{<&3({^%E{5OdgMOnjX#J0FfY=2z@~bNb`eotBPh zprle&2&{r zs>v5)j{ck~aKZ{N%y7dFKMZli64#h(BnRwD<*mPVJ5*u(_yUYhaW->UO8%ZKpM3@o z8*P6=0SLrc|Me=BZM=AK%dv$}MHr#Bl~C)aVS@D;SXb1t+b+-G+B_+0GdIP?z5f{F zmA)#nSR2a!0?hBki*crMjtF~AcG+g1jdt2#XD&w~Cumfa{`e(qRD*V*ocOEaEY;!CknSl3(? zoTH|*{k?T>F$UZ=Szue8i5s!sj(hI9@6LPgzN;2Duhbj>blvL`A7;yQ8pC??GldOW zGlLU8?YP#?Ja44oI=-M?ZAk868`REqdHLp7PW^yI$`B=c2U}fjzK>2$q+?k@y9V(C@B(Z=6y-gMClk4xc}AYMLd!b z)_{ntBR0%2&H@dp76`>CN^y!*tfCdU(!fYOsc2mB6EN5SM!*;(Z*f{42hSLj`r+h* z#mbN2u1BEOyyb*nIRFk1#IyCm}h8_Xv=`oi63xOTyGGn7eN6tm^*7I zRvrpbuMCoXF>_i)2}3p2Fw!5YQT>i`rkk&Lo zbQMP#)4D~n)?nj>*iSWgumRq7zVxlHeeau=Ug3(SaTCJyD2=2X5+{h@cytiTkUGA&YKtcWOKb5ja_H5YP9F#|98bKZn2Bc zX^utlHm?}_?M=Pp4>Iz{xCriXKMVU$m#MfcbzxP6B|KrmV79tU-O#lZbI51@qrIyU zEt;tONDw!MK9eD_S+N{3<)U~jI(V^}&y40Y6A%`#hy;!M`(Jw!@2_w&(?2rk<2=7s z!NtPC4=S+_2tC+U5l-@xmP{3YIM^+Tn@f~8%$xGU3dCz#OyImc(%sP{EyFl~4$7?N zP>Xuhq*jLD$v>`$%s%CYj7T%s-QY5#5qbHR4Dy$$h* zOMK$2N%c~KOFD7O{|N;RM)orb{UCv^gxXuq zc6-PCRY&%dqgrTTycFf`8P5CYAbq4D{@pju+h)iKFYVnkJ(FWm{Nh0k`Q$5q`ElJ< zoNp}LR$q{U$L%TDfp3#xB;!=IbA$Jfzj*F*-piqP9w$CetRZ+NwnycA zv46|=iqe(f(%z7s#eI@SpJ_+3L6!k__Mv&}C46YpL|q{o;1_kw2Z0eNfuH1COo4H% zq;WmrTzzAGnj%ueAR6E2fFnqPZXkZ0w_fGvFE79YJkSZ8z+n4;5bMW&2atML;dZPS zck<^JONB!rVj}yee>?O(QkH?o8HARdRiD-C<*NBbT7%N<;btR*5Tv0fD6HB8waAl~9 z=ZKDJ$cnA_W!1+LvN((JI0l@6f~0pScbJE5|Hq3GwI`I~7sg18V__ox02oAdjChwg z$>veBl7vI#Q=z3zQM6T1SB2VWkr#=PLSlhl!gU%5j>ggq)F*m`Hw>qkjwgwdBe;f{ zz>bx4T=58#vq*X|ODSnfw2-h7c2s0`@r8<4 zNtu;tnf!+opQ1x>BFqA|&AmKGNT|q>z(vXbVn5*G&PzgnmDT%3gnb9eo)A@XxSV3I@ z6kdrkm6)XAU?s*Oj%23~RiBJ+`*8IqsrH=~#%B{`bm z>7gIGctx-VoPZE3Lkyj;mgXsw)B>B8Fb3>-gYKy$nspg}*)e~VT@xlj`zbpj<|-ZL zh)SYmnE@FG@R*m8NkRH5%}9|`|LLGl3Z)VV1i@txf8~kU$u~*KCghl6-U*^#`k^o& z17kX-oRAD9BZdA@o+>(r#2^#~fs1L^o^(^2L_(vPF`qYjKK5y7JUSQs$tscAY{;pU zmw{Sbaio?ubZs+{)03aOD=b$4eFU+5DT3QPVHnx1z6UJ9n4`kh5UrlU%xoUjQc zYA|c6qUcFH>M5J-MweZrZ`1V~cS;(0x~E*xr+&H_J{qY1IWYpN7h6-Hd0{m`$EdX9 zsE;bC&FZYBRxI-;nWBPW`os~SQz`KoIdNJc|! z+QJ&PS{iu@m^r$u7d4>8|CuU4>NUdJqlqbaV|8#}hC7XVlFw?e2kT;$*AuVAJes;% z*}AO}JC@%{v7~CIs(BM9$_c9qgK#;6a%zK`)2=pC8t%FpxEfWuTCeunQU0nbf~us| zG^E6duZZelr$b^fyOh9ZeCUX3IOwx=g0iX->Rh4#hM~Z!wv^&n3l0j>? zce_#4>+h%etQQ6BiVQYvQ+mE4a0bj)sf7--@_s zx-u_Vu5vh!jPkf;@uILQxw9Idmix7|5iGlEx`}bNp9_40DlrB}KZW5Ga?o4f7nt-H%wz8jC7fPNHYlei|ihmyRRak;XANP4=t zyyv+_lD63^fF~n(IZ}_TWx$GQFionu;48rsj5|C5yND{gN2|UYjE02kz90O)P|I2; zDw7>+5H?6HvYEB+Cn(ChC$s@vfMIAVvm(DSz(oSO?vo@YcRxM(JmN5fl&#a(0<4i7mKrNNd?mJj3>fL(nwUp&xq1Ma-69$ zj=u-f$eKVv{GB%~)?@t|Ila?ojfy?((;rNty=&3v85pUzev-=;WFZxK;mcSl(!4qu ziF(p5i^kog%)F65r^D4b8YQ5I&8?L=u2`zYjGy=GRtz)kQSDw=F9Cnir^3 z)lwwNAKKgLE!Mvs-0j`L#J$!NU7{$;3Ah|+8a)PlWJ*g--7S0@drcUsoLT@~bZ1N> z`kXuBeQ?ZaBMkRD=Z)U#E#aoj-tKMTXZXkP?b8#znncZDaJs@gINb@gA-G{F07n}p zEhGm18?W6vGi$5>+u*XjJ88Svx;^1J4!*N{;}`DZ4w&H@9?@pXyICUCozMxW|7wGY zoWF;{)E@H7s&V32CE%#RP1MWXfE`KS{o*iwa5u}JPWd}C{iQl?=6B1T2GQd`&gMWa z9-8hZln&#zXaiscFK)D^^ zXD;cIT2|cK=9ezqZywQ^ovQvokLG;mIQYm$1=Yb>7=Jz+Zt~BA{&9-P;>)&}U0$f; zEhCO`K#(5kldkL3X)2iR>*qM!nqIiZ9p?to+yeC{?aCFL<-a46-OHxHX+ z;9S0Ni_V{Kc&H@}-hKDRpt|ehZkakF*}snNl`ZT;UdtrbEe^&*-{tIl|9u;T_s=9I zaz;e$n$g;b4y**kugYZ~j=oKHtTxWM<}^+23xAR4p6(C-X~DkkPRrpd11#%9DYn;4 z&)(uIbMFba?_l-nx8dRjL}_W|jx?TPF}*erF76Bu^OgwlGtbi#KjdfX?#a$?%dYW- zNbkCFX&+BwA%7bE9%+JoKm=3kMY_tFLi7t`;}RS5Q$K+;Z}pjO^W%KntVN#+QdB)( zFDUNXtR?g-^Yqnj?YmLHXHPaMv-DbaY2U6SWFE0pZ}*UQ^?8rs5})-H%jsM%7&w+o zV1F%QA0%;W5M`grS)TSlAM3oMCU5UiNGDQq|GB8Ew0E!hQm6Nw|L@0q-}kz^^*2$E zH;U}QN%$k;=Y2=n2jyl8^W-e>=GT@|(~5+vfSd@8+Q&$i!|iJ&b|? z^7W~&pP-d{UUu)VkI7o@`2T)8CsUwG*E_nu`@PToXa@Y>|Iore%N))nq~CeSul$<$ z^FAVWqz@XC?QJC!W2V^=xk4Qs>5{tQPI1y1^+A zXAakx!rnNIC0AbE;2Yk61%n=G-TQa&;l+<9U*7zA^ywQG;ojc;d-(A!iauT6{!EK* zGGT4a^C@h8hN^AA*=~bMJ%h4~ZaRU~QVYR@niFd>zp^q0I0)a8P(lptimt;99m6iG zVKR}=qYzV6aYYtebn!(PV{}Xg7+^T@MjUh0alZR{|MU?C7c$b1zo&`>@BrBeR1yea zili(roM~ll@pL(#W8YTynrBpL$ZozbsV9!7|nJGBPx=Laxp(y`*c* zoCE^3Qcfevv?oIOtf*90TXpqSSYwryA(sSI^;TSO^%GEDTe9^dLa#dXzeJN<6e%_u z{f9vqqm<5}-(I{FvI?=fa8`yQ1$A38vE9vCe^R~GTXM@a_gr+-ozW%sa&`CJ9e3>& z&|gJLZ8e{U-Kp4Pk7A=pW3Y@d$|)bB6vk;C{{uHIQeRz|+Yi-ksM@QO0rzcu3(9xMfl3cPVK2-RD0 z4jQMxa_x9&rki&9>G4=u89X6>dUTN6ac|rJ?rwZ@>c=d@7ZIwEA$wJ;OTdm$v4t>wNVUYCy5eEIU@4 z)!wi%y*1^z+_)VCn%mC}BJS1BD~5M))?0V|b&h42+B1m~w;jjD881A(U~$s-p92Cc zu*lCZclBT{*G5d|oJyBC^q=W={(#{y{|8si)nV6ud+xi3vopnR7k{(dO?KS9-hU6? zSfeVR$oN(>PabE*7Jj?+&~ZB8jiMiFPFCiH%S74pUI7hwKm>+|Fv=NU136MYK!Hq0 z=_}Gegl80G{o_#*fgh)kXC~$GC3QQS9>>xa7KYHzdV3on0TcK_7{*YBdMQbI95_CC z(MwhL+6h7SrHN#{Y=cwjV4dU#LKPY&fK`Is2~ilK5FU?i7IWbYt$0N&W>F+7x?$pS zc%Sp-X+Hz`-Led`xj22WO;L2q!XDJb2bIlJPn=cTaze!_W>JrOYVkt0hbuwI5BV{p-c}!Rp#!RSepek1) zL96vnQ?UHyB$X2-d`YR6n_7`Ix#C7%X3RnStL6d1$)x~duWHC-XFJ^qqgAzunKv9{ zA*og<&+Vm}Nfgf;=q5CvjdO_O@#a)^c}|J>_E|mjfGe9q%Sk}rXr6+8>o~3xi-Q)K7bcb~fOs5PMQwUhoC5Bm%q*Ek5hqQ& zbaWseor`)NM$(lcD5a*-|I*;#BDWC6RHjpeXhd^*Rjg*!TRXjIN(^^Vd|u^#Wg%)2 z$#c|^3Qee$S*pR@I8cs#$(GGos}ZScJFVtbuX}Y9SN-}|pzh2qW$j;vj*3)&(5##M z{N_LF$|??BXf9`QnlSm6IKF09vztB7Up?zr$OV-xL|xHgeZnopx~Q!aYwFTGrBJwt z=^zVz-oh@6SGpE5GF~aD&@CxGHj=D)Q&H(i*BcB{v~X(Lui6DhlS30YTTkYmozx$;~ zcm2E5?@9-uj2!AF{~=`B-h_9JjFpHmPwKjV-lah%1Q$*5%U=vVmn+Yvxv@t z%yXqJeMLTJI%J_GVW7nv=16xSp3$0mBNIkD$=NoE>6m?*>W#*-AeQN`1 zTGzSivQ%UJ|7fp#+A`(!&BPu&D~m)rD`2-{`~Ru1>f)=Vhr3yj-h2sK%f-HxpY+ z!R;>a!y%3qiBH_(GpBj1GJf;-aGPP@0rX^AZ0v)p7SRcEV`UTG=3?_(j*E1YW$#Pr znnzvgbi#SnLDTD?|Cq4vu3x!FK6L3CTyQ6Ev-3#XblcXM+EZtH+fQkAxNAn|+zigv z!LCcM{}Vi=C4b$?+snc6zG;b1N2S{he|QzeUGXO2w2zfz_nu2e- z2y^GJUHa>1KVLYE5bJwpc?EtZD!t8lN9E@$M63)vp+g{4TDZ10UQgAL_iT7!G`d>h+sg%z&^_;t64%S z{|eMUH({gj^F9E|Bu!F_3zU<=Q#%tRK_C3V{@N+3KtYq3I~okK*%ObWX|)9rsQqIs zW#gWxz(GwKh#2F#IT<|v0zxh%!RJdrA`FSf6R;KBycS$IgIm1?Im!*m zl92eRJ?`p4JT$;Aa=$PH2^EwKSrR_Uy9*|CvsO`_hdDybnL|4Cjk{};=6k<9oJ8oe zv%}~^k1)dJn4|Iw52SN4MI@+%iNft6KPpKoDDpt&L%$BAL{|*G3tJ3Kj#fz9f|L_9D z9K^-#(?vAw33Zv4MD!la6O&N^H3L(|mg^rtQ^#d|jAw*KX`Dxz10~F`MvKtI$iTvd zXhy^!w&>tRoPfbY#F=1hA|_%q@l!q&0x5xbG!i>TIP=H8NV^@QM~t*MckvE<)PY)L zjK~ALTvV8a3q_&Z5OgcW@av7~Svp`k9XdM3horAY!W3GgzKqPtYr7cnutt4!44I?~ zifki@Nh_25zAG6=DMT!@b4cRYB!?`&ezQpuNxwVPNvyQBJn1Y<97B*>jMURQpEItb zT*IDgt=AEjy74xMd`beF$)fo-Orf%i%u2h=GaXTnS^UVvkjoz%L=!7Z|4E9h;~+?k zSr~!*JK2l238}&Wd^1sF#XY-A%Dl1@2@y>ENw8Fmp`;3h3=>oI8xG;9!THAGam%($ zMy7j5>xjoKt4!F`u=i+@KIF?3>CBqp7V2myz@e)Q^qbH8kQQS{n2fY4^vla|&DV@g z=G3nCfF~lv#%{wUI%Ese>X6X<8|Hv7-!RNNA}N7v%4s>fS+dAXYfkjMF7R0<6x2BY z%#aQ&DwbRb-VB`W6cw=&%;G{UUhI%`q(jJqxSQ0p^ej-$TA=S~PtvrK_=Jn113LYb zlgWaqPV1#_L`BUbPAs9xhV0NJ6ws>7HUk~ey{e%)VL;8i%?6#2|Dc(k`gE$efUkkr z8Sku<3!TplO}!@yP{X1db<#Bw4N|NM30H|fuUtr_TG7Iq8E2fl)`<)3FvrA-(DWd? zPb5TCbVs<<(B*>?$rMo`4bzJ12w90gtgF$-i_at*NV9m)CmoA&o6e=NQf@KIb(~7L zluGi15alFLG5u3_(g<>~z7$PT?K=oGB?v?79tZW13N$*=xzexnH1kW5KJ`;T&D3JD z2y`LT1r3qlV~p7I9WUquil`%!!YS9|@z(JR#R_)rSDkVI{oqUqHu zltOpa(-nOY+pRTsHbSZ!F5UB8Fr zC@LkQw`5Io)rl#!rGLewi#^pVyw<>pJtH6kNyu4A&;o?ef}CxFfzVl@l?0#_h?~_} zEii(EXo8&80*&=)%CQO;xq9g;|(|RhWfe zSOqdr+JcaTUzi1+J%A?og}6OiwB1>wm4vfhg}AkY|DqiTBY@jqNZKup*S0|1y%;=& z1yZVg+|RSxafQ}x>_n36+A(>-m&KOs$k>_`95VO?WXOcA2;Ehf+kvnHyFFcj(1Kr( z1cRs&)g@ZGMO!i`2r@X^U$|Xlq*-wDUA#NixPx5cH9V`URW;O@E2ZHp#TOOn#u zMN<%hV8o{-7fE1Sb25fefLq=b2r^iO?3LTrecd%p3$zVfGOz>GJpe5b-?aT+Zd6=t zrQgLJP`E2z{gt|^b5^YVwWtK(=Jg7ZLPHAd7(24UnZ4dv(So)eh$ct{WGDp)&R(V^ z-vbC;*d>UZ@P=T>g&0T(re#~cmEU(AU}9z9|C;g9#?`j{ePNBnxij5YEd@U0Gz%;> z;HGgFD-7VLX#zW#1xY9b2MJ;_Xo6KZ-4LGL^_2uWCu!n!BhF_=#XK)5&I9tFK2qfNFK;B)HW#b(EToFlF(mP{M#x)t9 z-0)E09Mz?OBul_iGCB^)jJaUD)mwqcUM=toWKiM*;9E&JVk@wPU_b_Ru!m<5U2j;2 zbwGz;(B4~~1>WuAV8i6fWsIoBxlf*E|4Yj_tovVLMGR6lryHGAs1c^LSl*0@0fe1X zb0z_lK$D3xv27a@+qP}n&cwED+nm_8ZQJ}dwY#-dyD$6Jf8bQzzTNkng(Hn6pIt3D zaBYlWkT!n=yfC-h5RvCl{Tgtu(_OvMU=aB&@$RF37cKDzozzNkCS7hzUUQlOc7O=0 zv?-+DW%N%xT?_FqJAiI zYaS!3#l^7acip-~6Qg!z9JFn*Hpmu6n|uK~-MPBy4Am3Satgj2K(oBNIi$7aW0HqU zUdiyINQLmI3CS@(v*d>`g9I;a*;skn?+X}D8nQ@>L zc%yh|;m}O^o3E`;CR>8PMf&f_L(?uMKuY~h5!;G&UY<^|5yG$;eig$Ws-x|bvHy1F z2RFV2&v6f-ls$8?|Cv_9%Wic?Un#cKF+8_;W^Avw=36jBlB=ySPNVaMNlL|{5Q%TK znpCtNc*6dr827-2h{A>J=$^Uohv=CbKh=aJvnFZFANvT~PKKEdIoW=0*XeX>&XH9} zN(^B9I%yWS0qr|zLN#P^zY2^yasxLswm-DI4S5+3chNr-#j~y24Yf?$J&0L8JTyj` zv_o8>o<%c}#k2t^cc~+IDL8)0$i*jOxSNH)^V?>WiW+7t;>mLv4SxlFB*m6Y zXqtQRJnx>W$B`9&@n?aPM@BV2EEkhm9l&GL#Jx%OlE382#YmX?|nu;OI;PAh8GK=&;pgR(CU6qCRD5burD& zr~Uo(h(!q~lOmiS$;ZLq>+ z;A@Sl0*0z~BjqdepmFl(xbvdDQBPQkJkn%!F}aMMAuxgHN|*j3rDue~deJ4YY;xij zzJiAv_>5vi3{EG8*>TO_YwGBacjo7;Ana;yRn>ScE}QM1{89)P_z?Nx?tc>j+vKXM zQ4q28{LbVOQd*)8xR()obJz69U!jDnT=FzSOl#d7_FM#IazBoCbHXGqA~)f3g*4E# z^~Uk6e#tBVSe&CA#Mrq9rM+Py-Lk4amGQlYfxX0-cyXycJM4J2n`HprUz}Hrv0c5+ z?pFYq4Q~sRwxJS^k7e(5P-<3cRq%y^e1;=BhlzP?*M4j4(T#|uQHVXCh|rv&;!M=; ztcIcnq(a-7R>E}*xd7fa)yOXX0#x5K#=GZKk~*ufCNaL^>iB#_A!NS8a3PNdN3^+!=UnT`Wu zSnc*F%bmz)a(Ms#f~9h%m@5#CC6cLdrd%kI%@vHMdZL`FP_1p4{Bx-{8V6k(5MAML z2^Xg`Qy^2hoLett*WWMVIcB}m&OH_rUHNjX-O4%Bvh{&LzxPk%q-07MiTYqT2485I z(4FaMJcZt9y2^w3WIBg0&=teO*_bVT(HC~Bok7$H9>Ad;sp(?Y;i7b5EEE5{*v+<6 zG?cBuc2O8MM@3fc&EZt_FIOm*&WH2qe7V->WYfEIa-lESELZX$&0NzS7{1tVypvbl zlW<*VoHfA=i|;yn>W zleca7nnUwt@Yhf?t)VPj^$a8|Fcisb8CDA-qdYJQqnPK_3!~Y(Ukd(im%pIJ@J6#4 z$eKaD8Ogunq8Q5IVo}QL^%F`Q+LPsk6)=X^mldXHwJa8;>IGnyq#3b}kvehzQYA@8 zJ1aTnM`a3H&JZd-Rgss*T1$;p&^5LtnJ6DtkQ2d$H>5zrOM}HQ%O6k zVi!3}EiL(WFD?^)FHA*r&Xan5@sFX1?uu{r~ zZ1+HJWXAi@*Phs3S#1C2uB`5wOwO$B{ryW1>^*i-h&^A(=fW^3bRnHtFlSb_B(vSQQW3jo35gdlzOog;eM^U zOj6Q?F+Z!j5zyGwQwa$d24usDzg9tKEJKNJtYr)xQGaje&@)rb>j>l zh|Q%2HB)wrie%$f%Z4398LK3DA@*}Ln3(YiKf$_>O`VU>;*$&V-)c5xqtuLiO~Hw+ zHYs}{y!OLHv*R{6XZ#?R0{2LY8ZVe32=`{@7x$#yg>;?QunZ$J0ETjrTXDrvW212U zRqH{{he8b3)x~kJ4yTJaChefxhGrz*>(nA}si!!nlq7+u;uJO4)k^YX0tO4FuwO;{pn0eGp;0#AI8OWEVi>{%aSAFILpWNr5d>ZZ(7jk2_;+yVy`>%S z%`Mr{jW*?3@1^EnUE4@jI4C0@$LHZ+#0HrQ7^C$hwQkOt0p$Ja%3`!A3 z9ePTxN^x>ARf#&``HD5+*_z*@k-z%Vg!+GuzH^xKe&JHcbF%j0#6%Ija_g}@40R72 z#q-PED}n<+5&wQCx`J*|h;h9m#H7y}*icVsZ}X#t06LWPMv>)&!Tu;j#Mtl}3Tugu zoXutK|H;GQBI4l_MMRO`gLM)IftJq$E<{TP#UcQPMu3>oV_hsZytLra!pfWNYZT=@ z2+M=fP>MeOQ)OsE+M6*Z9RHP6j>RuXzH9Ht$PWy~KHCd^`W{eBw^VLjQAPrL$e-jt zl=CCeWvvZt3;RSR9Q>>}8a`hgDXFhIKU@)(&r^oQ0cx~*3L?6nRsE5Qz-8%!AW2e# z;*hvhQY?+~%AMyYgD+R?rI)B?zqd!iCD!u?(b#!m3wm`m)Xi}FnXuTepj!ihL9|iB zt2}#g)tS_sA0({<+R+WQ)Gp=nTM~E@e)7ebOZjzbS zci3dvU0Cg0Sxi((j8{}r2?k8gtAHTQUh=cnfyx~20eSQa;}uzLo$#u4M6`*t!sSgR zWH=|~Z%!%gP!|r8g?HhEulUtLqr`=^Ra`&a3Ndi%8Evx-GlgjTl2ccPGq5y5VAO## zP{+Z3suRSE-v&fZ?#faSAs5R>5s}gK_*4yGpURH}TeX1@oBP9PGW6SK#F;R~EjS!l&=OQ3N^%7e)eNt03cWTo`330pG4?R>0xLjjFC$C{74YH_i!2d zp(<5|X!R+em>G|=ZuzMmzj0T%m3}7t(k9}2<#_LlsupfyuC=cU74h&xE8OF>-atBM z|G`k=w^`_X!!2bia2Sb}i&XZoK7SPyMMUL<$FC06}m zDs+R>+7=;8}kdvrTVY>ZVXO+ZY%Rr?;Ji*?!=R zSx~Qy{L_jSp&mECM>0Rksc}trfU`7rZZk=i5TY5aES&CT1U}b+A--3kda<556?7xP zNYyB;%sl~iTHnvF-ITj^r`-Sc(TmONh`1Tyv%Cf{XVgb{5%w+myofQDFouMsvmbpd z_s|;>cv>%_M&st3V$=M_LYy>2QEu)pFY>H z2*KY*GSotO)TyE~mrlTfSz6X>@!12zK~`+*Mw_^Lqe^M%CS2Y{6a_#UacnRa3!nz>COFn zhBVXKGa$$!7O#dfx?(;1W;Ap}KceS9=F&flbH4WU;jqN>vv5f;$8w`_;--M&P+;Nkrt8AD{caaZCY3+e2o_HD@y-o45uoLw@y$nduMzY4L4n5z4e|;12+@d$ zYWPs&`9T%Km~E`;&8ef>`U|u{{e>99eh^EDgP=iCnH6p>n-l#uCL+!GGY)E!?zt8*a}nF!plc37=_v;fHw5! zFeJv)C$a7)kt8H`&LqU~BLdZBsmkP$4t!V}5J(cFRt!3<*Az+Gn@cCA z*&u-EGl2F`fNrv%ngV>wA)l=Vgb8Km;ipmVkNGqefT=o26PAb8L?oq%*E_^tRYh3d zWMJ}7|NAR1>q}JasSpC}P#(#|#2#v73KF4vi-3%96LlAyn-pmp2yWL80k7BpOOVQ0 zkglqq1bl#s8-UfyBeY8>q>)f0m4ii{&?l0#PlMqSC65Dy4Wx}UzSFCW;S1XPGnKj7xf zpTA9edM%I#1y3zX5GKxlKRSTF_mFC~1TAP+Qx$IkDhP2kv*Il}dWgU-WJvbgH1{ac z{ux;Z0Wdg>LC#Nk5-3O^heIYuG@36`Xew$XC`e{Pw-4-0Vf;$~eQ=$Gy`Ll~j|9>m zL%84Fus_ZwV7D5(^9_U#5)`v(Khap1IwRwFsZ6S-fMgKMhf|s5sL)SvNcR4S^NmDJ zM?#3fJTO2dNb)SnaWL|cfcJUw_vb2tWN9d?aEK&XnkS{QqJOyLHr3CXMZV})gE^jk z|D8=nly7kKyO}_f5M>a7WcR*rie^sBembKxx1hG}Fc_Tw6gKUd2-u7uH)T>kMzWw~ z5p+M#FPIwIIQ3LGGiEc-bjjK0K0(zmzbW}Gbe zYXDiksL1=CynhW<0ol1A#iGz`QXzCn5mKdNhd4ZRSPGeOn(JAbWT`XfVVW$Nfb%J0 zNC2MlFPck`(l?O5OU5vM+a5!f&6`Jg>r_evB}dE7GX)nLNw+G4>FT`vSVs+sjtCW2kK_MCepSW#5H6uzq|N2$9iX z)zCq>;}@SxR-;H{fds_{n3t)7Cxomep#he};6Kk+e~$h9uLABBreuRE+juXlCaF@O z6XM@N$*+!vh_nkA;SKDq9ek?-Bdiyo4+69;T!AhZUC$Rqt(sf1$4$=#QTAb+0sUO3 zWYerw1JeXmNf&1F*7BDL51R!uSgKyLR9)_u^ZWS=>$D7lHiI42^4j>zo>asYRYqj{ zR~BWvq6duu3sX55!~GR7DZ2i`;e+6(?cFi3L$Ur;(3^Brr7Toitjk*gws7BKW1=HO zrlJH3BfNLZFjrj{@*js!5_M}v*x$(Cu^>|R$D;(f~-d8;58eR1;h8LyNKXX4T@@vKx<6uhN$fD2geX%K@upTLoEC~W8X4p zr&DIu!qoX|T}UROTZh*vhAd#FrzR1@Wz|7cddDC}BEE5=f%~Xzz*vXo@DmiMuq{(F znl&lBFbVk~uGi_g?fsV`ctjs^9i^o0wWaeP`{94L{w=voZZ*_mQZ!o3#MBU2O2am! z#Ds=Su5^a%Hx0=2MsZO3zm-DPK0zkiM5e0L3n}W}Q|^_rc7Cl?96(D_D>X)HJMoRE zvvN6_OzP4**$ATT3w&JAQ8xi2J($c6q3NvtGFcrmk9Zy0<~D;tRl9V?srxf_y5_#b zTN}Zb_{b*&O?wfHh@xUl=G+{?AQ;Jv2S{^pcra0yR6{xCS6&lVqAQ?yU{0hLMP?Ye z7M>Fn6VnTVHV7AQl$79l@)3~azZm*`+3Q3XBprz(h<-WF1OSDWcabpy_c?qNs%uPc z->JNipW8)eL(SrqP!`lm@i$;?HanlP|I|0$fa}gMAd`Daw;i6uC6gPiNHF7?&Y4xeN zUV?yW3C&hlIruWskuh2U8O0YO+m8`juU69yXh|s%n7CGlIaECS7YAfvW?O!kf4z^< zuCz5nXnVqHy>*r|;UZ?CXcxv>_;K!yR=iFxuHJ6`4**vqP;{!5g~zU52b`+(rovwrg)z4%5{rqqzN+-PCkvqk zfVgw{tBLlq{W5DSNR@r4Mx#Ff*gbA-c=@k5^QucV`G> zBo9<LL>Ss}4aXIs+#@w<~qCKNr3aqH)rr^Dl)DnE+9fp{>9k=RAyT^)DR)rzrEU_l?*s zKHu}o>8AtxOah-t5MeT05Gb@i?g#(_!QkJRtj@2qyTIYdl&Vech(@B(*c`5puZYIt z@x&4-e>{*(B$KH%TAbgIOr_JAEtZ=+kj-SXDUnUbjpy`crBYqdSUksaC-Q|1uI=AZ zES1ZZim{p_9L(jbwbFH;sNyYGap`twSWK-ed;VI4`?^#rT5sZ}Mj1RpA=>G7dA-4T zf1umz_XR?svwCAV7!E~ZlJlM(lgsBvQw|8PFBfZ1sZdV{XQWu2q-N$$({MdrYF4L- z^pMh~xD0jrSgf>M)w$Sib$Yx!e_^}Z?+pmyMbW&?WAFE;4u^bbUf(BZ2tcqLYkP{G z8d()Qi>Y}$r*90TOtF8sdOiVshFaYKc)s3m4`(ZU7PI7{e^;*5y16sBE8Zu`FtXd5(Ha^=ShdWK~#c><0zI+m`YQMl#=aB3t_K0-VK48 zP(|{Q(Hh-};tomAOfXGxBTxNVg0ao}giLajnK|uuEJC4=i1-o0ea6VX=_ft(vX=@~ zb{K$SAuDu&>LksH;`*Q{Caf<~w9gaqoWV9FXoYh}mklCF&%S5f%+P~$ITQ0#3enH0 zq6(retD9setHQak@3I3TLjo#PW7YrJmXS-$I|_3%HziamNcc=KV|q20Rq<%JB(H1b zcA;%pH*cZU=hZQ#XoYXDO0rb@$;hh5i2sJt23KK`*We4cp4}?Mx|bs-0`7CNjprC;q}nU zgQH;JG_ zl;4Ooh{0@X4Dd0c`WcaLbQC02-vgy{CBcD&?iI^{xq;tyMG+(4442g~E+4ENv^_Wvlc`D^wB;)Qo)7ZgpRt?5 zTd=b1gPh>9<*-osB#dGqQB|f!n=`T;yZ`KDzij)+!JJnY9cP?tYN$mzSK%*Oa%UZJ z`7R7HhTxvYn6k-F4cJ+8y@dJ#@IG&cdcvLdNIU504(joE-m1?V#ynn|O0!2+AfkDR zdpf0^zN-bVzX=YIcY&bP`Q!LYIFZLPrwm=V=bG*0Vx_Xrb4EIpbgVr|%GJKb$@`G1 zul@oxr2tE)3nD`^xZg&|f=G<;_MnnVQa{Q~-kx;8M3A^bAZXrmzX~kxi3fpk>>-4! z4^Af6I{yY3>lfjap`sH_Q!pkGf%VMy%zmDR5OU1HZLA34OJ0~0{n^JDQx`2RmRG(A zP%c@28Kl-UiBQCuT&JVxYDhPhl?mD}u!dk_%s`CuM=5H#TqYtdxl!NZ6*R=6Y^PuqjPubIjwilCPiww{kJQ*4y`+=q z5!GN6+$>b3@K}@5D}aht>nO}ak*GNrM+&K;IWjmc8>fLyBwh*38^Q~gYB@tv=vh2w zZI>ui=(vePj8tM=aBS_PP|Au5KaA7Vi04_lk52z2WOZAV@!CeteGmSd5DmsK^uzfzT$r*x#n}Z~m|&R{0-ICcmiCLg~dpv*&BlvNe2IHsxEcwH0+(|O7is4QKjOwWL4 zGA-}sO4i;KT&XjpscHkM+5tW!Z?HL`0i~rr&;nXg8BUn^xJpj0pprgVZz^-enf#&< zR4G?wlvUP`!T|SNmydd7&ey+~O{*#nr;KL#I!-BOdXikdM5RpU75`5ZL9y;_5?B?W zq8t>5*4Bqw^Yf)DiSpN(yXGex6E@1)QIK=vWfd)ios^8I#jxlG)@OTu{C_pHWWKOrj(&CQ#CEyAUna+1>6uk%V*iE{wK_b}1F+*e-QYERqgzA;(|S73LSB z%e@ai?=dDcmQ6Jq(e%?D&9&(%@6_@%XtIBmrb{g+L>5CaQzY6%q?X9ly&74^ zp)0Z%5w+9Ncuq`j3&-PCpDIGj%-WwhI@kmbr{cVqAPqf-t&>M(;5kJ^)jZ%JZi7zM zb*zoh?dN4(Y>7&-M7pXI7Pv^83NKSf;)flkbJD`dGZUsL}4>U;Beeiwgn%Q(7kVSNKZmOF=~L$N;eh-X#KhVKL1zs zb;mxlcF3{9G5)Nx6glG@znrcy!4+s2_q{aJUhFZ?f+EII>UpA&%Go=7<>Xf?VSoUQ zGv#jdWVR60B`mg(drtZse6_ycyVVNK56ho9#m<} zQXPI!TR!>RijQ~KSmC+t4~G>zZfzAg)(JBd^{9^Ssl!rRE^ZJ`4*JHBV&hXDiM*Z#P#_PhCR}(b^#>+CJuU`7 zAy1_qh=}b_dwVNeG`dZpfU2gzxJ_TOi14<5@cUyJMd$Y*iV#>c7*(AS3U2)5FZnNZ z1&mOKavDUmHH5NB3$_?)w5?x=&0w@lhA0w>(SVRGw2Ml${9gi48hB-u`lNEB7Y(D%<0@qTKNvh%HEyt-!9jHozd*$ z?jgQ^(~9KO++NQS;x~{*-C_6C@^sJQXIO8i+?6vFVAk$qnt+|9l@h@vVA0c)6^TOu z{GkXFNVOD6XX7@75v<$f{Ev&+qAo|58E}>CaL;~ZR#Krv;`1r$^dX9lKi*NwL`4!L zd!n9eo>3?+Q#sc>BV=X+ zMFyRlc6+HvDmu2Tc{C6tNFF8m)hGz~JUVzvW+W@z9a!{1a7!oVrPr{J|G#pXvw!3xbJ?Glusx zb5+yglRRF7oECyyUcp>KjH-dVLq@4;vY=6e|_xXK<1<{j2g6cA4 z4|t;~DgXRgP=CbNMiGrgA<|K(|0$HH9tvGi@VEpE0E@D#7>V+LAw3~Uv?h@rIl=tRb?8`=a zDezxUdeO-YZ>AsM&tx2Pf8bj500sRL;sYiIs^(*Hs%9-ZOUx`1H`=a^^OnYvUnW#- zBxHI|3ZcuET=J&TtlUt4OeO1lO779@_T70IwVWg83sSgiRc-9*G*hLl`W{&mSxp^V zHd|ClH)RwuuWOK0sT3V;04-2UD%RUA%Atkf|5Ew|AMi(1cNeIqwNYoDymNRr6e=;HR|T|HcCA@K8>+-46;1&Ag1!O=vDE=!TSy) zUIs352?HIhMOwxY65unv;C$*SmCBvK9M8-Vi|(%T@@nqSK)cisxioo!^E-mpgG<=V zfF(V-6fS6QCJ}g5_$MH~&8|pBzf8a}4zn7gwU+8;8_)BGkbFY?eXXcj8>4FE8VaHb z|CXBjw*APS@}@3uj222$r{GJ^8ltGXWSg9indL;67R(V2Ea?oKp7c;d%}}0MT9!KS zBV~jmTX4@P$Nb!{=W)>pbigzMv~G8Eb{{$ zy!&_@Ff63+0LGKlT36z8WJ>}$cPQ5L0*&%lgs&-r<4{*JgV)Oo-wbRz64+K0m9VnG zG2{XRlYOtsJ2^MQI?DbYlr4b5@h#+kA!>GMR`FX;ko~{{^hG z9a50@xv!+Gf9tL{NO8@ZdrB~4d$7dFN5Gd)$n<%xmK?vr9)vZ>V7KDi$BL{$J6c?(jH;p>Sfu$ z43@L~n9G$=XAEuaLw0Tu(H>@lX|8S_Ea&2)-yFzPZ>dcrN@oKHqY5?48V$bavg7XF zbNqI{Z6kN8s71h;(^{Uj7>(QXMmd`SXl*kMXYid_}@}{YleZ&-|wOBFrv`k>#|O`YriXJytY=%4AJn>Ew89m zUOh__x7L%l=DxJY66>)*j#=np*K6O`M|9R!veq_mNNE&n6HxVyV`Zao!Nzp9CoI=y zy4GG~!y$A`OzhS{9JT>E<=oAuTd z%+5nv>rAy{>$l1CiS7|e#)~oEi~Oz>F^~CTm|9h`=H~6o3*XG2bC{OtDQ9Io{9^o7V*DdFFuD~;#BxnVRt&kov_ zqSBM9_$b*iB9e;0{yT52QO}{duNuhm_c+NQgA1}RZ>>AGBAh{5+mCWMeSn>uWaWwX zcKojak=J6t%+NBK*Yc#$5ZprUx6s+`TF<{N?@vU$nIn9HPh1S~y1c$XNMtJQ(YpMB zPy}MhEb;n+p-2p7%gxdH!jV`4p$Hs_hN7`V3Z)9|v4-M_R0gB*ED0z566tTp^Ubp# z!D%jkAT+LIQ`uahcp{a~coU_3S}Gl8r*h-Dbg2ye9gSIY4Gc9r|X`PM`$9O=Z~9;R!^v!+)J#<-^XCvtbx zikGth1>I0pxc!6ZzML|}dI12^vb_)-*VDaF zf)I05mkbSvy>JR7mjq?5_R@4lv}<(z5Ta%CgJ|~SvV#~Px>sFqN^neL3FPxbqQGx; z^Hh&N_os)6@}iVSNy;Up=m})d<)lF*s1k$;ΞL&N8YN$LZ!J<;NM;Si**B{I--Q z-b5Z2Bx&Nq?4}MTEoUdWe&AH6c?WOmTUlZA=n2_+`{AW&O@Jqf)1o9*%d_IN{wGr% z2eR|>A{0i?(!!!+&_Z7?O>oPSs+RNf%DUkSL@%+F*R$$g7ZS_D;%BNji=Rf=W!)f} zm33Z7iaUDEWJt>#cIW*$by_8u*JbmnY2{T5j%|ll=~PH(s_2{~*Hz@w^YB&2Wy{5N zXRv2ydfTIGh(h~uj+JFcS>MG?4-f>+t+5(Ynn@R=m^xzj`?)Dh&oms(-5`pZwS&t2 zbmr|awA`S5cQG$aRR?;i_5Bz{skB0av;V~1gs9A82xIXw7Smu}dDX)-_lvf}@IW6; zlOm!I_xV)nTS~=@G~3nVLc_e}?W{7yOWd4TAZ0^ES0N(A(~5p5t!pNYljhT!5J!;9 z@{Ns7x}9z;?aQX~iVpFtQhxP|5=`}!s}6DDam!W^y6x-UX>!-bcGOKCLgd2wKaJh| zuZY*9G_#sF8!*7B;{gNtpmIh7&xhGk(8s<(C7Ic~61W#uOHC7O1R%mUP%vm92p}4C zAV#1~@F)-p;Wng3aPaJK=i3ktIx6+DgwmSa{$J(79 zKak(gnGSV(oS96~`-9;K$nDZZV!i`|^@kH_%vRgn=?gtF(6EtsG9Aua?PW@p{|m>f zjW*1Vt*OpdyXHSOtR$5vr?Us&5lDJDPG{K19BM~d$w~<%v|RmI@!bb96=X6+0f5l$ zMfZ}O(}ha8^iCgPfr*sGudK%BLDzoI;_r=hv~fI4|xxk>IK7kx*Lcf zO0gG&qH4Yu3|d|KgJTWKrVKmd%P?swXt1{9Vf>MH1Se0k(9ha~bP2A<`6U@~MPz7S zA@!A6I+PzAY9RoFH*GgwoXlfgMDjU#$1vIeWfwb$p=FZk+a75*C4sT!Cn3i|N#-q# z_CGkboRI|y4pW}k;&V0~gb}BN?Z=2!kCvj*DWV_1HHtS#Mz66LBr6*$51Ba)XR(|V zId*$&q@|fsrTJuBKOOoa0gs0BeSSW~%9og0V5S0lLTQ%PApuO!s+yK9FRI&)D=Mv$ zp3g6&S^O~!Biwm8(c}RXBc+9v*1^&YeQ~ciE`N^yoWi+sTW;5GR;V4DKL0n4y)7(A1jqS`{ zGu~%9xa`i>$O2Zg&c?;bs~_j3*>tSN<=xWi`e#uu7!(oosuR&PG3E|1Y#|t#fMXsKub~tU~=bT@HLxdQul-cyy8v&K_vuTXWP$`%U_R=lxq^NrA8zNj17z|FSTp8w;Xr?yqBDiLoj; z-v}E@1zqsNhAPl7Aq?O;Idx*zWC5CU6>CSKO*zM;3#`sxO7t>2r+X5#n0P}pMN0{_*8Tns1e4;pW%bDIRjs+ z!f4_4z*mELn?z{@TtcWcu6>8tx*!w$hn3ELLIw}%I*^sLUMS-zB8(_XT{>L{s4(&Q_hFE4 z*A6FFpU=X%Ze{viN=2jv<|LAUJ^;KO`vK;5oft!fLbNgkJyn7`@UQwmA}+_I83@s3 z!sHp)j?)at-w4yf8G=N}+2)yUOv8Nq=TnvW(*+Qfhi%8|VrsmH*$mNV0Mp}!ZdgVB ziq#R`LlY{)%}1s&=hH6=$;AS!r!p*oGf2h?g>dtlLN86DhUwJOkgvha66K0M<&HLI ztf}Ik(46`R=R_eCs9Dk*rTjs$OtUCinV?JnYP{r1$9i&^CK$d_@X=xd9l6!5Pz1E`a)0{NGa$an(ptOPkoHVIB_laI5w^zuO?~YRL%1>b=tw;A_lil$ zbNg&`4TOtU`?Bg`^B`imHAm`H-*yT&85fX?*U@C#`A{pQCyjCFgzoe3L&GtrZAyX` zrj~6>dt6eD@5{u_a5S6cau=N|$9wxtgSm4H?Sa7-!8Ty}Ed3Z)+6ba>JEZBQAEV@Q z^3Y>Dh#<8)mlTvQVQ=$0<8_c?J2_AZO+NxAt#<=fC-&cOSypJ{A%_6dATeaI$K_HY zOt^+PGtbmu@3t_DBN`t@^$`@Vw=sE9P9-Zs$0*{NmH0qD?s*->l#JwsgWAW7DWP~9`o#Nwd#?Lo8tz9JXm(iht(IZoR z$C!x-vQ(A<-ebsn)esXt6s*UhK_=Ul?w?VhX;^_tZ@csK{5qG#B41;0O59V`&i5tE zc;{N^E#;NxLvp+&(`chl!=Iece1j^yFs)Bf(CsZyBm-+{Dvw4+z&asDGyN~A=qwX& zG^z1J=Bn1ID_bR!)x-i8JsX>0ZTO+Nzo-_2C{ecepe7iYzuY|4bu0|=&Hs*|K{md~ zsCEh$!3jE0HwP14%^Pea>L^16QK=7-Bstx$uev^#X`ZDC66iZE1RkHy;DEW8a^Kr@QBP50foD^q@awSjO$%vpBMUkcXP$8QO0{&iIRjgD$Uf7 zp-?Hq1>SA~!`FA=blJQ({vF#d?2Dl!AWNB3%wd@49d+2>w`Ij2A=cZ7O{qy&CRJDR zbvUbylR9_S5*_n5bh$B?Uk~424~zIj^nGTygF5dJ;V&f~gPq?`T7#dS7(1_8=xCK% zbi@G?ZXX!m>!%H=5(*r4Vn6n`*T_?@v#-5nw$*k<7$F|yx~{h6f$#U#6aCvcp^wG~ zW2XXRLI9;(?p#Z($aU(DuXI(9$9`hTnXK6NHjmGJC{WhhFFBR+pawcwXG0Y}Qk1o4 z$2B!SaCeb&Hx3gwCp-hMV=tnj^BBXnZcy^CIJ;E0gURws;7GVqi8JVfm@8~Jfl|1!GXqiw#0XV8f{2lPu4i@ zLA6Oia^#-h;E13nf93E0vVjGIis>ze+N-UG`m!^awV`RbyS9m(ds z_yfw21jW_NM1xX>Lu^h%NLquG(e2aj=w6A~fkvsCnqjCh{3=A*;$K56+9J^I!z>uX zu;+r?hn>*aRD4DJp;NR-fW2$lB5Peu^Om*n{lo1jTpZfG)mOr!1VXdqBQoYN%G4}t z5+kbAqnB6lx-gKJf)Lxt5CT+;avwC+T*CB25Z2U@7R?Pu!h}-T9S2A4a76>M+L%=w z&8FHgr_Jq^)O}V~W53-APt*ku4iK}Qfyf0tE|9e%R;{>+WI6R?fZyV3N<&;0Vy<6f ztW!X}n;`WOVqxP$1C?WE%rM8wRJ~4J0BH$SV+4p}NE>O0Z29CnX>oC-4r6zMzX5Ly zypZuHX)$%I;e8Zz;09b+{_&Y1Tns>Z8KVg7fqyMgWgnPOzQrKlAh~~u2UDjfYf_ri zmLt()Ius_6|NMyEZk7l^NgERE%k2?U(H6t8h=5jZCz>A5_Z;t68askW|H%-V?Pun> z9H8Ew9KexAFqf>$5$7<6!x4^xXs({1<{POYiQSsgb($FFh9%&E@8AI>+>YQhX8JfH zEy@}zr><2*f%!BVrP7X>Q}5|5o>qsMiEfal7nByx5z__{qPd{cF(xD2ihwAQ*2|7i zT%Qg#m+ttME`TNh2b?hGLR5N&uRMk!FPIGENCl$KmO`1iS)S13fuskOvJWT=bP(fg zlSn)&LjZ2i_B~B;!9>C?&q4ByJ^?HLxYf!33Xa1mYr$C!l?VLf(?coUS5iRCiMk@3=QJkRFyy_-Q{Q7BoFOvQ-= z0i8%E83~11*eV)=BvEMHUWBk$$Q5LbNvNUyUf6_;;i{1!a;^$^%h2p7Sz0aPye&en zM}dgTgB_0>?hm`%3tJn_Y2Z*zrO-C8Ou9QVC|Yxz7t_)a^Rxb0J_1fl@EbrJ7>V#m zi@Q}*qFHlMDpXdBM9__}6v9wi16k6; z(xB};HS@fwGW{bAILGa}G#vvY5M(?`Oe@$H}vx zyi|BCV+k!pM4pCM!o^3UTOojD8t|T18?sd3SR$N6q>eJu&jHF+%dyfZI~$qR^1OzS zEAn0cXq3h>Is7a2T7%B7X{+2iYxoZUX+W00E6ZNtN;{Ed7z?YP&zVg(>sBYJraarV zP?oXfw-c*Dt1ntcMhls_2(TyHi(V@bPW!Y%7PavyOH^B`AliIUNMC8ndTracDF(Lc zBNsnW5a5Wf4nuzAS+WsPnSKkm$0xVF>TE%J5KXzRMTCczJ7@lIJxuGjo=ZtSTYhs2 zsgXKvh5K3vRyrm1pb){fuI7=m;<&^Jxh9~n2r;vtb+;?Gxx3T3pZmL5^qmklx}|Fn zxfrrYOSGUgqXA1PaN!1SPy{5Q1#Zviv|tXKkWxP>M;5}RF(U)DL%zrdvy)p8=__y&+pt2B3D@(!D1213IlROR z5`$~JG>O0LhFz@Ny1kMK(C`E4e^}X2hAbWH> zp0>dpOma$jz6DXa#%ip9*}f^<#n80E@+&O#`w_Ti3`mb&DkSBqqy^;;8 z;0ATz2DbnWE}#x=qXqVG0B*1k-8&NY5Xj`kZEtBCZ|gs||6>QWlgLvHrd9mG1Mzp6 zt7m75CCQqkUcAYb1jdFo5MzuGYvYX>70ROvKWS{IYXoL*++bJAiuWUV9*XntOI~x4oX}p-j+W+|GI2o;6pL<&#*)q=o`%lXKRQ@K@fc6a}`Jwg=NvS>LVsm&K%v*uG}q8unyOt3fW){ z(whnM;0nW_z;U1hgkTS~;0o%{#zLZStYi`XjA1to#f+@e@MMg(OAr_}r1^IuQR#$Q zdx~6()QUYhN*%`eE0ZTei=aHw5`AE`#jmUDka?=rW$4kr@&t8I2!Qa*Z(0c4s}6Ob zy@gN+UGQLZZC-fuff_8ni#)fEYr&Zn!h?i|)wY_3L(Q7J*uwodjs4BDl_x{Nb5OlD z+I7*7sk)AtscGTaQ3D8sAiZ@k&oM32uMKhs|1p;`lfg2xvH@+y0uk7UnoYiqOsA5l z!9CpY%`^_}*nVZzYBbr4X52j|dD^^aSY3v?RS5eq47ack6I{p(SA-h*t>PWt${ESS zip8kPR+Y@&yxY6+o#9I}-}((oUWVVe)#1i+ko|4hmdDjyO-@<>2&V1Mlj6ImrQj|_ z-i$ok2z%E@iQ5B#-k02j>y1F{i{TnRO}p(9LBf4B%Nkxw3v_<2Y`xrcn?)UPMo%Kz1MrPZSwX zLADmdT9D~DThvCq=B92bZN7kSUgzk;VSWJjSK*vt9a_LV!V~Hiq)1wT44c3NzwkuU6Yb1nk|j#h zrylO89+7UY%H!wiJqPRB66J3U6Suw=RzMJeJ_x*C@4h}li2huPJ{Maq-h16%@R8es z4LFv5NDmYln;=1q)Ie98ouw}B5D$>#uIl1g(TG^ltnL$5I_q1l=MtG7em)R`;0Ix5 z1z~Ui^j`0~e(!GtcKhxc1?xv0|0%^U8}I|6+xB88Ot2M7gzaxNJ)k~4h0+zHj@XGE z@kl=*6JNHwrtbOe^iiGhJMnJ9-0tj=9=WdTVW0zj;Ms(p@+v>?gpM-#4qa<_8w_4q zjqFY~KhOgYJkPF6)(Jt=GYUQ*L5wu*$HamcF62r7_Y$)7Q2$q*H2CSp^tKw#LQ(a; z;^(?P2!@{WE(g!iN356(~uz@#M-R7iyc z^n-LNnOx0)U;8W>kmbH>vwDc=j^r<_GZ8N zD%&2noqXb((-3aE40}`E|855(GYiYW4#BVw(-2VA;0?(TEtYZV%7aUT1l;d!`|?j4 zxKHtFe71&vEVWvJ6bOC*u|wcMf&~p8L@3ahzhQ24JcJlg;zWuSElvyrNh72%6Z>eq z81kW&Fc~+V+&HMD6_G6|9)KBB=1iJ3ZQjJ0Q|C^eJ$?QJ8q{YJqD74!MVeIUQl?Fv zE=5Cg(ITN$cTUBcRqIx+UA=w<8&<1{r%q$~^T&zFTDEQ7zJ<#~(yvu(?aV?Z4{fzz z-u9vU75JAHxw9n2MVy$^KYw+~K86h0>SW55Enmi*S@UMjojrdB9a{8g(xpvPc9~lB zYSyh?KXfzf-=&1L|7{O^V{9Q>-o4-423|Y&KV!dxA2;}>x4%oqXd{P?@Df^wudP$G z;wL4`iGv^wx-OBVNt7oKtPHQC$Z7WN-D8d%U;g~acA{pDi65rc{Zl)O1u#GX2iyt` z8R#<#rcKaFtU(9cf@ZmW&|2n=2QP$cF@F%`FtYbP1TjPrM8^s3Pt9ND`v)4nQd;jZ_MQ zyVX|YvdhXk1T)OY$SP_PFb>!XO|Up4uuV7L#0rKmVM0qS4DWOc$li*>vri@%+eA!3 zlk&1qLk~qX|4~I3Wwg%%9)Ui{UbKqKSKr+HK~m?66z0gK zD-CuU|6!=jI{?crZsyvuBw}(oY>CPInploMM*GcX=Y&?}J~<)8?K@B2P;3Od#yfAl z_vX9ro2mvJ#!UPfnrMQ4Hat0FW=q^t-U@GghgAIyTn8&o8sycGG=j47h{jVGrt-o# zV{5-pr->+;>}EYo7+$yd0E{b3yY@EiaJE{xF|=^^3(*R+b@@;yzIfx0N1jB_mw#<= z$P-6Aa)E{;QhI@=d%kggDGxm0D>WDCO6IXU@9NP@PyY0;zXn@)_v3?sEV5+>%69t& zB)h}5eSeS;JNZ`(px)=9^cB#62Si{3|294bw#0c!>sj=qM?LEm1YQ-K-jT-FswS<5 z|8otb$k)0+I`g4~bYW1S-V$_x0k*I#uQST*a&kW!f@N)C(j5R5qr(Pi$c2wdVGxBl zL?X@%gh#B%11l)O$ngk*M0?j0BRDyU6ajFT6Buj6heY+LZYCp4*uqjmx*~FoeeL^U z8k0gcj73EzHH0Hq1hqdNBIbW}d<$cep~j}btc-sIWFQ4OA}$v4AxgB~yD;cP4B|$L zJ=I>2NYG8v&g20;xm z;_3{8tl1e^$VWcP&nRY!V=xzCATi|-k8Xk6G2sF{UM|ItxP)djr8!NZ7?O*K|D2$6 zmbkd=HSv*3)1XB9C`w7yG9`n!gbo-{h$1ke2wE5hEpz}0YM^2tssKb63IR`77)%wn z=mH_gc@Ztx!x}o!LNZ*To>A07HLDC%GE{MZQpjK()_B4)4giK*yz&6*IKVKvkd17J z;}nn}g*bLm9+jYvnh!f;GkIx(H)2efwVNY@j)^i(B$ElfQ)XK<6g-(u@});bYEq?X zO(bHoaqU`2^`OViZz`>-@miXyA`%%&MoJ?c8PCGR0SS9hBMi_ef;teY3P^|}4D-+d zA>6VRC)(ydAOdc+VG5p|7PdgE} zp!yKCM=5P^g*)5=GWCc~HC%4&byZ7IwTVN5ZgizP-AlB~y4S^Sb|Dzat#W9f;rS{? z!l;q4ii4K#fW#@vVGm=pH4OI9K_T2AR~^)W5$ga$d>PT#BDet%R-8u>JlT?6Z9)r- zO@drU0a=(_)(+WVhdnT>*#jh_mC1OAJ?!Dvl9Uj0q$RGmV)|Q&>4c{F8zyW8lv9!^ zlWx5E2V?w!+hyEQhk7LO3PZeO9`{&g#%*A1<^{c_Er+>2655fE|I@DKETkE8fbtwX z@nk7`!pc|1a+bBcWh*zs7hWdLkc_jmra|OaUA+z@&J&U_7y}WcSm{b>Nzb+#q8(N^ zfE!BD1sw?DzE6m2nOox5`95SHf^CURHlf%jB%u^`;Di=hvD(XC111s%sb&jt3z*!( z4L9lVtw8MKUafC+Ii8bFjsm+f*;K^^3Yo}StV}%xsY1sD5>azZYF_u+*NFo1_=Mce zbtyMU#D>lRf)-;X+Xkw}@Ukc7&`lHo~HG z!*-6EvN0ZCY~gfofV3D3} zZE4Q|++o+cwVnTU>UVwG{HUH0*y2Ao zM09^@U2die<}54I(p#|8lgI9^95<6KIpprRltXU|yBuM`JK?_W^M~(? zL0}Q38f1;jS+k1BLD9;j)qp_yt3S*jy(`(8CE>zcGD4V8qa<`07`hk%3=jfD5Cfb& zW%|TpVwo(A#8NcH;qpSj0mBJOIvru8+sKVeh_*JI!#8}gImAVAqqgjmn>>6$@Eepa z07Qx?C5YIBh=_w-ShHJTMtLd%RVXD&g2oPmGedkoaVo-_&@s%oKPHI@NIb=^8L`%} zME7Yz*V_s~vArvtLbi}G)my}Hl*f7eqg1S#RrIDsaxQ19IyTJ3ZVNjT{Ks5W!8xFU zgFMJOazV7OXBM#}=BoB(NAK9Hv++z;y)0c3g{GgU6XP%A-snd(;_x ze5zLTz?yiw$jEreh%|~BJg7~uhGaM>S8%(B1P2`$u!mTNhiHc)xCSfAhQHDQ zX!snH6r+;R%d$8^%}^MboQW$zN}6;zLAl9h!bB*XEq^!wp&Uxp#KH&s%-4iX)KSWu zVai5|9H=~qr4dM~)Hbc018QJ{|1E%muOv>g9LuougXC0B<-`L&XwK&JgFCAZvJ zTuwiDvr~wKwsgy#h|4XQOCBNwVqnO-Y>K>O3Q9UCxH8Pod53q11067jOi%^M90r3) zhIf02TL84kvN^qKcFfjd+KM2(V#zh{imq$m~zaYzY8W zGb%xe0VPnMc*&YLP!3fQ|6(Z+H`0vyD^r|^P#hvR)noz+#UqBqP&MV#KJ69{MHdha zQKI=2#>q`5qs0?NP8DU*<&;k6gwz>T&g!&INsZ3teAMK;gGAT`9qj`i{nSwHgP{1) z0~pos3{MB4f*)XlPGF2sL{jr)Ql@ayc_0eEN`i-Q1&t8Ng3|#gEzDol$cIp?hw#$W zAc_%cL_;i{_}GcfyorarB|kk80AWzi2+h^Yi8%$62?fO(^Qk*!O#vcBYBkq$Ef+xD z8QDO#2(ryW-9X(;R9r++8C}s9tbYRiWqu zIQY~9KvlQ6f)^N4{~*EBwphrry9JH7%%yPBQMiU{ScW9Pg+fSzW_Ztj8is2Chk^qH zZ~%uo&;d69hioVW7qA9vXa{&}iKIX`Ffyl>nvX9!2^5OfG(}esVbfya4>g&JYsJ>o z`#)|)5VZIQ1T42|tFckA!k+U7UE8&!72C1>5OrNwG|VQajE>|x97HuydRsgG;!Kta?|&q+D=4^)C{WHi!sJvj2i1&9lFq>?A_|MUe7SwSrODJ zLJPJ15!{s5x6R5Fol!-w1z3oLR49c$2!r0$YE^VVfpY@2CTi_SU^!ESJ#B)VJ7C9P~s(KSMP;I;v*bo zUgmj`;y4^gD2UtSgatbWaX3zLt0jXs;x#i2qWnE6* zb_8N0y+WVc)0O6FBtB+HVd74a;^J!}s)}YRKEZl*RBQfcegNbJ_JdOB=KQq>Z>R=a z=mj#i1v8+AuC9h^&|he9WBu*wVkqmgrUqCz%Tv(K#8q6}s^bG_YJSKDe}x52Kv)JQ z=tj0&NalxzhKU0X?7(hVn4oC3u;@)z3_UEnnl%TFAc~bGDYRpReJ~0^uEG`xe#uR^a)D10LCN$ha_-=K(N)Ku!amL3TQ}zbxHz3_+&x|@mpXW zpdFp~Ky9SxZK1dy*LIVbo?6*1i@`xn3k6ErbHH+K@gDcn--eOko;qgMK;y;JrltmH_ytA~g}wj`bhvVR2nKZUhG2jNM)-wrw%a}kXK?1*|13uH?9@?8 zKH&9sYm$10gjL*ZC8NKFzzT-v}g|9}330a4) zUI(<8hidSKb+F(;kl%y01xK)jLQn)tMN740^FROdI|v0pp6j`u5LiI>%Jm6BhXg-> z*pi3~Yv6=6c!5002902gH;{+!D}#Iclnvzbr4nV} z$OAlRPQL8}xAtfLmFMP#1zF&FM9vBAfCNLJ3DVJEwz!36XbVOlhB*Luws3`j-v>QJ z%>(f8B(R1K*8-wQhGb|wCmkS@2m_6WVfyHCkN|8dck+H+b~|p=|DoT9qW|k+c>41eel))W zH8_)EtC16)XgT5y9*$QD5uh87xO$OnipNd^)uXz<{{0}2;1Z0PVI z#E23nQmkn4BF2mwH*$=)=p)FGB1e)eY4Rk>lqb=kLFn=&%$PD~%G~77-$EujcQSdy ziPJKF%YG8#Y4j-4oj#K?ZR*r0r+@x7(X49qD#0Qhw{q?3^()x0V#ks#YxXSKv})I~ zZ7Ws>+_-Y*(yeRvF5bL)_wt?VX4t<=2X+uHZ1^zZ|HO(9zq#~gF=UO5jRn4RiJ!k_ zo`i7j?D;bkF=G6XF74-zY1E}v-@yZmAM8k`{Y1*fj~c8GIZxo zpXADyGjFaukDokv@)+uq$2s=ok@oqson2F;KC-ftC!YrrBtsMpWh-{z%`qmNu3gJU z4U#dPuGZ*eME_b*I$5JrC&O@pQ!U_RLPQdTSVI+75yBJ(dR<`E1$t*l7?WEadiddo zCmleNLMoYfB8n-pv>}Tv!gLcSIX&eQP(l&)6jGevxFe4`MKzU+L0SbOkwqGLB$7!g zxg?WKI$2gp&zd9Icx9(|q`C~1fg7s+wul?NT8(G8-gbDG$eO?Z$d2TLE|SxTNE z==ssdMRzQ828HNB!iE=D^tjVc%W$_zD|HCT;u#fQh@L>Ry7VNky`F_eiX@I0EV0F^ z*pjZv#$*#tGOkKvP(yJNpi?@odTmlt`J*hi2Ko9exZ#RBF1h8J>#LRNs=IELe+8xx znDJ`qrM!koR@fVqmAM$2{;27hn}WUx=xnvU;}2{J!$QrU4a3Q2YJ{4G2q~wKV%(<8 zF*+S-*KG>Na+(zL4>gr$9C9SEs0^Ma{~4=yKy}Pngovp%dx|Qy^3|A3CYuP-ZA^op z7a@j_SO_#i=PDg8uqF+g;)qWhJ2llKt%$U)FglyFQmxv^Nhj3$C^pyF-jod1+%CN~ z+iko3Hr#Qu#V*}-+Z|UXHwiXay?q--uira}iLbt9YT2)vqY3;QCj?X5B7h;66%PxIvu|*hRY;gt@XPka|>Z_A_#uBK??!_6ZpR61xBbR)8cCuu1 zaGm~8la0zNo1EN2pOW{GA&Hop2qMngY^on@sCq3SUi0j8+5-so39p1 zQZEuU)aqBA(kJhmbT#=_F&m>o|7ADj6T)AItv}a(1flu`>3jw}AOaJpzy*TnZVr4P zmGb6~z40w@^#YvV?zMw_k;!oJ5(O*}rm{gnOi-wSoa9nCyxlC0gnV+G7@zAEzE&ANqoodn7FB3PO*O}^hYQ>wW;QT4ifJ`L_?0V z5Z#RN9i(U{B&s)#IV?j}>sZ4uRHcqJ+=4&$Sc5ByGLKCxV;FLT#xRDFEK`MVXrP=4 zDgil2L%L5yiv-Chp z;YK&S(cB9q#+zn(|HczHc|#7Jas?kkfv!kU6%_z@g)?YEgyLi(ES@+_e)OSJ=}{DW z#IcJ5yh9wMu!lJMK#g$#qYs0i1~_1G0LUI-9EOO*E}ZucQ|*Ej=urnMJfRbIY=RLw zc?Tml@d75yV-5Ig#~Ln?y|K=*XD&j|AogfcpjHK`Z`>l!^-GXF8dWsY|-n6|pUB(-jkUdUZB3d^B;2X|H zTnP!)xc>bwfCGHWr4m?`c`K7sp9-eNOmLPMDGXHub4xF5wZdEN>Ihkrr$~quHf1#? zFbSqi7mk>%|DKtH-gXdIqxfVQp3p=kG{J^8+!dRhJdi(hM1?m%p__j_895^t9@(g~ zJmPTPeRdI^cJu)iptwVIit#8^L;@A+83fEgp%8J1Q5>cMr>Xeii!sRkONW1%CD24*Z6OD0oZx zGR9jicrOlKV!{^wb%kN^JFntNI4Ua{h%Xo75|TzVGi1{;1ZW%&@!C}GOcOn0MQFi2 z^@du_B;=}Oxq># z+(*BOtWaKDl~cXyR=@gLV6Am_$(q)+UQE8+YgI4}j)VKE7gm9-c3q}W*d?1ya2`hD zWzwC5t>N6W*(3yL`eWLhw)PyZ@B_g!;R#P@NF4-GM>{8D7&ig;P6+|(zyAZiJfec? z|9re|>>RJKMNW>UBB2RCh!zrwfQ2D^Q5}0ILOHOw1T_@V`X&!z_JcS^9~9A!g}_1- zFv|uiV3CMK*n>Fev1h~$A&xf-B_A4vJ{6XLvqH(Q8%-EC!PNEB$<9+qujLnQ~y2y2A}{Aph9e&0ai)Z zCD_+7M%cNRG3c6@nBCYxM%t~N+6C5N5gX&2)v`fM4CS5Pxzz-%nEeICwFw>-2+|!4+Z07C{2&ph9H9Ld&c}DpZ3vph7kT|3fLP zLob{|AM}DZ*aA9qLLX#>NS;B0_W54{5#U&apZK}lB7H(O6xuix+DFJkD}>bg z_1s4&!!p3%N!Wo^NRUI+-%onfQWaSiHd-j8h&76D|&14%(*YpP@={#;9rg#El#C)y;d_$E{I-)Fi+Pll#(9w%}- z2~jR5T^Qv<%;HiqWmEP|M$DQmp`BDt&>TyRS8alXGT>%zf&?1KKvl$~Oxh&a0B2GN|0jxii;6a>la3NxU_@N7 z4Rcm0TsWsg%;I76i!Dx|mShA~ot?b&qIUjTRVIvg`l7JCg9dh`7vMm7enzx0qk1;O zGcth;yeE8~g<8&MHtG)%y}`SI45a8MU7CtrmIo*V781?_clg6zGN^-Q17a$Nh4#TL z%pUJ(6+jN3h8ltwSPw)P1skBp7BB>z^_ET!MA3}TlBVdBHUvSy0Ie>>M*b+S{^)Mz zSZ@MnTOz5C)Y+>tX{;8ju?nRQNNJQRjg?j@mS(AzDh8MKT?S!9g!LMBmZ=3+8cGz^&#g%m&&^$^?4#s&D=(u$Cgq9xKoG?9wc&MNFx=G%IsH zD^f-)*kLPmUc|LVrMFV$SlNeNKCOj;D=5stxSFTlgk3Ylm!5hbh^#AH*5?go#}@sd z>0M|aEMFgh!yQy?DR@JLa$zvcgFghrO(26h^uaugf+(0nHHd>Pq(Wp-12QN=Hb|Cn zByKjStv96}V=hOcWb7D`5kkrt7@@~Sw8}q3{~RPl9m-x*a;|Jcw5-e8LCmIZ)$A(% z6zNRTF1Xl50nWwl)U%Y3_>yFf<62~FjRvf*h6wyS>l31Wr+hY z6az3U%%hA$AHYH}zydp9ta9L|7=3D}8rDW=CL{#K9@4Jp0wu9pgz3Jl>dr7qXyTAs z(x?KbKg2GJ=@;!5C+-HZ5EqHv^a}6>|1V&~;&T!&@m>T6y+^h}@2?rA6#ts^ZfW&; z!u5Iv-`xcFP6YU(+LQDtX6#?t?3EXwZ6YX2C{)%N7K7U=2P$9|rbJdB=$iv?up#`z zr5J)gga@VgLvnxuC{V*?C5JsAM`RJ)+Ujv1fP(yDDEm%NWn#pK66Bm6Kpw6z3#V)< zCd5{ZW)f_qi_$R6&MZvKpX=h+P2wz)>g=!r@et24EvtplPN`fRz+LDv&^E~tyQ1(8 zZ?r0(iYeX2sM7W6U*Gy8W)(rF{Dsx5!M|K|H3}>@jQTszS&1HB!?YWY?Y-W-FJc=C?);z0oS9f6^N0uFf!xav~{Dx3Av_l8m0}+xn z!TADmpxz@7G!uo9hF(#qiflvhpdWm+eEoz%lxRc~(D#AzR=hCF+A8X5^hcudOQ`ZH z15hPN1!h#986&BZhAvBQ|2Aj0bh0i4Ow$EJ2(6OPv;o@mLNGBgM{7m!w7hIVP%kr3 z2elU%fxI+eCYZ(dx=s1!*!l7ZH+?f1?SnlumLV7dIEVwL$O0_f0Vs$AHT;_)jDt8h ztT>26rCfKVBsVA|2Q`R8cjHF8P0>FjOm`GRHuwSuJK5$P2YU2p^xQSa7G!!%#8ITG zU=KF=P@Q3S1Y$cx3@B|C6u{lMR`7_kI=9M4>ze#5GOQM5+% zH$}8;Mi014ar8_;wx+2U(n+T)ZyGEQ>x9R-oJT}1!*qt{a)u{~4sf`KgSd!W35mmt ziRZLVOGKCwI%43`^9D5)$F__w7_MEjS>Q#EuMIa#OU`f;9%yJdJ8m~>N4rVR6h#iE z{Fq^hb8{F68}OjzHo;ertjKM7_xu-_S9GmkM1YgIv25Z^*r8wd6oPx&GQ_S)ck-Mc zJF?e#lq$Pu-}#Zi1&0^G6M(@J$c401d$sGphu6ZjXZxS)MWC-ZbRzF8Rz%Zg>!Lrc zSe4a_V~UGE|2mh1oup4XUsU?qlrN@Z3l4&;hB6!;e7bW4Sqc%)=CL}eGY1tg#J-yf zm5&8O-bBgD`m7g~m#^qjiv>Z9xvrOl4budXK7=Q(IsV0NW}`H+pM0F_?w#YZ$`grP zxWX`uLNZuGHe^B(=ztdBf;AWeG%Q0QX!|hS0xcv%eGtOUf4g0TySOJMu95rKQN*<_ zy_P7iwn9!6MJ+YNOi&N?ZC7t@-*}bSyVCUbW%J07b2=h;48XhIKDeR6Xh+MGI`0^k z7d6KmB)mfiHygM*T4c`ws4!g*Y1BK{^3`|OR$81 zZ#^OsC3lyLV+9SfhuRS@*J#)+(U7Ia>9DEXXwyf17MZl{%Gb)sG{wX4Sft z|7%yTU%`eIJCpFxKfJ$m$;H^zwi<4l@$>(L8OZ|>}RG!-v* zaOc*&n|JO=`~2|}KK$Qse%T@!>eHupbKPF3&@PR7m>aqWE@z)yq{wx;bvA9nxr`I1 zrAXO$F$9Ty`}TJO*sl)mN7jP?JdVD-aUp z=A+^uHrg{}%bq0kXP*Nq#L&rOkxjNlPq7k_qk)!v@<|j`Y*ECkIvO!XWs^WD$8W!_ z$ts-w(TP+fjXGD|pNPbX+jl=?R^EB(t=Har@y%CXge>z?O&!2dr3icK|G;aUGn2Um zOhz_s*kK*$D~5QvF4hVti)@`kDqDtNi> z+A4jW1?fd;Pn=d-kV+c+*=$cV$fQMfbkYQeyam_pmg26e#~*=QH^@=_Ubm^Iye@p^ z!x2wh@x>W$e9G)p0q3rP&jg2%$@d`yu`lf^Vjn=Mp5q%3zvZq6 zx>Z>A0d5!e{@MK!PDXK_5P_s;ZwpU(I$-c+Zte+doHog%@cZ$HQQojgyvoEC*G9G# z*(8Ac>t9J05sQ2*FcvD|7LD%qEe(;2A%R;8C*o&8bq#K7`BPSR92Y_nj*x^UG-188 z;|hB`Mh9^)Oc8DYjm7AI5bdDD6Ov&LE!c$+>e!+2fQXmUVa0WoGKT6bmYO#dku?e7 znCWIG9oz87ch1S(aFBB{Dprv15c0012`l>VGe9a-}K-kAMMSN zK0+e}dzi;OfBeHK{GdjAPJs#xvX2Ra`%zLP#KBA$%Y%)C|Cg4qwGoXFFe8#b=?5%=A(!wuR!4paRViv#90ux@jieK1)36coL zDrT{YTkb@cJE0{oC85EeD9Mo@JmE8;8BJ+UlbZZ`lb423zie3J2}J8U$!g>o8iibfk5G)FYo^FWD+q+Q|65-p(LhIO0-xBSm|IomkSO%hV^x!_ZFTEg;i@G$Sx5`G7>1Y#ql#hF zq7a=^MJC)pi)`|xp)iBz>GC1 z{`?n~v@t|Ooy>c`0W?zk#hTGm&VyDbeZ;*&N}iF2#F!0R6MU3G&A8oDc$O|VYJ2O$+ze_~6s?qn8P zKt?cUfmJ4SdCSNAg(SrK-m2As$Mn_jo8cU1Ih#aJLAeMbaBFU*R4R7I9z)rsjj3ZM|=N2Y#IyR7D& z^SPS1-}ZQNuLE*h-?~Xi{zQg+oj~di^?t?f7O!pc-H8vR+0UMZ9f-t_Uyx@MzmT{r zB@t#?{({@uR_5T6@$s*fo9Rt=`qRhaZ>e7<6Zfq0LfV~meH!G?fCi`+?v3aOhkelb zzSC!;Gb;i2+p>@gN3ag<@D52R2Yc@XcOV7x$uv}O>jbX_UGVER zD|e_tXne!oVDJvSzz7y?-=stjt8bbFZlcyj`!LN9(t`=o09E_|4%^3lnu3prLO7PN z37>G|-e>&?Da8`cA3AOh=dU4d&25T{s7~%!K4}reaJ~T0TxRdKET#fQF(_z{7H<&` znXwt2kuB_^E+|pz|M;*Ew<56sF%Tb%AR=qQ3W7E)%b>W2AG$|4s399Ps}Y}%HqdSo zr_s*fN_l|Gc>+hoFs(hoE8Y>^s?iUbC>yoW8o5!y5W)~2Y#d33 z9QOeowP>@}(KVv)aZ2*PcF?VQ5F?L76D`X8G7=~T#~+D8Ne0qhQi>o}>M2@^BdIdh zz7W_P(kedb6NatLg0XMlFe#VtD3gMjsxl?paxH1IHbF2>+(I!mEG|*f zb@Ie6wQ&%Q?;BggFaL5M0@EDFZnF%tPgn-D+)+2(X*S>N5>xA3knlAxh;=TrD9(op z8)vu}&ojxha4OI8lHk`ylYtV5l+csMz7j(AQPs2)88?zDsna&~b3et+Vc1eS3yV%( zOc3YNH&theR#G_gj5tYy3h3>MW-^N&<+5_JHQF&T0ThUEPaff}K98~~4!{&qEynWl zndV0-|8=Z9RkTS$Q_0LQ2{2DIlS~&xa~HjGq|y)$spdL8bSH4^Ecr7?g*4nUR51k< zID0dpSmvJYk|n$DAX+0FAB-B1lTirM`8vzOhUW%Bq(~hq1cS0ibu=g9E^45%Gr*H^ zHghUhv`shU3u8elVst$j=ogDCJ_B$ctxZgQLJp~NNC7oaNf0-^w9bx{KnwIR8EZfj zR3M%dN*mO{5RDq_!8l9?2D8*T5tB*^)p(dOJOmOG`Se^`5h)6SM4K{%u7<{BaXj7h zRigql7sy7bVos||)_^ZnIWHrH(nFE1GX*tRg;km^13Mr?E;_ZLA_h3|QqNi=b^MW8 z|A{Xz3GpQ(wGp%79sKA@2dz2v4JV)zLz8t=K+?1%ibqG4GT$&r3Sy9S)p34A@n#WL zVU@`8VdZ4R*N95iR8u~AHCfGbC5h!E9TNuw?o zbx#m95C@`KtyMInbiyJb8+L(P%Pv#T4qUHfTpcDqnUO=W4`A748P@guIDwy<#|cd> zO%I0&ZY=)TlwQlzUa8CfC~v4x6FzaYB9D<1Iss;xV9jLHV5N3y^QBl9HX5(?Ezy9w z>@|S^49{j`VzKU9mD1`OwHwFQVtWA_cKgk_P2_nO#P-G{}&|{ zn~+2m#|j04Gl8}$WwZ>t@*#(65hT*3`ZZ7Yu~$9RPdSohsrGU)_bZ|iFWizctVv-r zbZbY`YvDv<#WrnegPzKkNrUqM&=z$;!#D?RIn~i*rGwF|WNtUba@7)4ZAMI4bs3H^ zMD0mQ^k_WDLuZ*qeqwQ63pWdcYJq&QNn|wE@YKpa)BtWkk-uqwHEJ`rd%c$|=0YJ5 z_H#Q`bm>%jW8pI3>2wtWb?PaJq;&-!6;egRI2j=reu)w8EfsZ&V81tpV;E~UH!_U%SaH~DbF)az_k@S`D$!Rm)|Y(~!Z$BriBy*; z;+Ng1bvQdVc6&n+et|jeH#ZbPmzX0M3SkhWxDW1^ih}_W`XCq>fq@aNLRsU&xI}{E zgm;Hjc|J^X*9GJBmRH5np5AqFZj5|D2!_@Kh~N|Km8eMfu!#7HSLTRIgOvkue(4u9 zYNt26m_MXAH-e!LruYta`3_Q{5UThNM1g^qBbeVdc(!zn+4xOl*lsPTRR4PvM3YGI z^0;xVX)bNHmhvIWx9NK?9a!c?XiOIhaEc3LzD2!3=zP zi+A}K6ahCZ+6+=56&N8E9AOZ0!;C4^c4-55Q+AoPgPjM$I@JY(M^(iJ!XMhzeWXb| zu{oO?iKq%$L#*pYePo5ts%pq3IN}&xC-a427^b0mSZ$bw;dzpExO3mqoA22K^0{;P z8Ok~*bOgG(KH;Ad8c!CQp^eCii&&P|_E1JTfV~(Q?f?;XIiwk(jQ?%H5JEbnZ6P;w znK{1*f+N_aFT;(!w}R>MJfu+BoEGu^fzk%zN2)nI4f1Dw+H3kx$(%&1k9NMurLxD= zANwe8eN|v9H>y=zSSLB2t=hFUg?!)9oYyI#!MXzB1!ACC z*9~>jnxP#!mOu7T%wQ07S(h0>70}@qdI1&sAf!vd77C#hQURl*+ka8IiX0gFhDWXp z`>I#FAmDh?)YY^fJMaX8vZZNFQ#7-c#j}IjDzut$ckGaN^{6+PsWZ|nxp%!0oIh!p znH#1c(5)OAV}~-~awvngJ$VI)U@}zU8iqCr{0m}+K{Z~Xlm7!D1_ojr4B`f|;Q-FS z2o7MyM*|#oz!lEmS(BTgUw2}f+c_BFuleH_7{L*$VaR`>8vLOgr~w#Yfs6qG88Dic zJNn1D2#rZ2Zk0K`wfG;;j7KSOpAMGEd0Tyln$ot^c&A^MlILaf1$}0xLS{lnoGSRU@;QwUSvB5lW=KCM6X8pX%01Nm4 zuF4MVU=r4R+k@@^u3Zwc{QwH^0PWyPKG=TlTt`0)#Ua`r zZb2Lr!3boW#u-5rTp=4e;SFw~8HT>p=gB3r0*Vdle}f?v1_2dt0yvOi9`>jjkf9pv zq3oeyfm5NFf9V&3VHQG0rCsAWw?x?~1F`@8)&JaXkGeeCr5zfS+8>Ca7oK5!HsKfE zfUF9_mIMOZB;m||;Q+{B7S24~wd8z;;?*#_-KV0zorI8q5jaA1HAj0-&N(B0RGsfW z^@Fq|yC4%>z#gta2LKBY9^(nV1j09=OfsPm+#ut1Aoi0%5QNI(Jvjul;~ct49~S5p zo_;f2ek%ik2LeIKcpwIhfC+3~9CYOknnA^lz#ewM2(qD4mgokqVF$*a#v$v6F!e2H-efr!nWAKhbgbEuvbhu@Q#EBFuQoQ8P z-!L}^I(qyFGNj0nBt_~ti87_il`LDjeE$hECd`sFYudbtGpEj-JbU{5xoK0fjGQh7M958c9oBT%W5!rsWyXsZjeu#c$dhl3>-}p6&hh$BJYK|z z5lCeo-2l!3<8<^!GgM@=gFO;4nEysI#td`K4&dzI${9Pn(GC?mP;pK(B3@!qi6)+S z;v2^NV~l4wNkoMg56ws;jRqCt&p!U}!()&9WD|)(2^HiJku^5tg@-7Xh>=Dd9cR;W zQcg+blu%xYWtLig6jVmb6y;i&Vvfl~QB_Uzi!z^)-SVY zalk5)P$J1Ja&2kTQKI>y*Cw+q%4nm7RpuBBjjq?2ql|7+r(GXS1x;$4xJYJcZ*XQ* zsHT=#RWg>Y8e0*Bz6xusvTBK1aI@ZuYpw^J^bxPURtapd*<|vB8-=vv0ytXe@I-do zZQ|V~g@|`jdElUzk9w4{m;Z!I>J(7~I*i3b4n6v;$BYw9ys$$@F}zS&ATe}w;DHB3 zctbWuIJg6Y;9T)xGZtc~NGHuG62phaEXi=g6{*Ogi#Ne2 zcHM%t{B+)W?+xV+O=bif-+~XW6G|Q#-qFg6CpXGC%vv*w3(x@agf-XbU=DYL6d^6O zrQF2RKC#NrDx9P~riQ=m=J>sKhH?ZB$jr7rWvg*Mw_6nlv0ul zav~#%vY|f-QyJ5ZjZuco$3Fp62X5YEDQaVz&0q-5(!l1RTFa(I3HJ|uydnw#_~8>f z;ty;n!2b&e_(KCavX5|}fdUC|ViHGk6?w!015JE~7H@h}E>`4=nRwDgf0`v~3Uy_w zQ%MnIKnOzUf*$v%Bq5(_x^3yA9{acl>?p<5qOgl30b)$iJc6QxZK!=2A(2=qVuW6@ zZ+jAZ(f62XF<9sbNatH7TxaA3wL;UUw;HNnlLOSi>M$tD$e=?bYO_`7=@*hGagWA4b;2@OL{v{lDP~{-6B#V)B|B&bu!jXh!_|_gt2*fy&a0}hG zLkmfeM-u8Vj3ij25J{NFCmdOsfeJ<)V7P|XHbay`iAse;!ETuRk!0;wMNwE@75|Yh zeWj~pL?4gnfjG8!0DrXi3mr-C1wiT#ZnX5JBk>13L_i97u%L=q$zp%ExFnwT7}LC_ z34(zP>>yK^kRQy)u%EgHPTZp&7|sW_n2`e@NLv${=&&&^(N@RE3q>k225LCdA{C4K z5-i4KPF{Rti$$WwF;2J0qPJr(N;B9$?zO$2CbJesdf!X&%vmUil-lT%pBt=nVff;Y zz6_&=efG-}$ibL%>Ejbg07EtkA?A4`fgN4O#VGik1UB0_35AdbpkqsjRwN@Eb}&XZ zz>ow%5Teky$i{Llg{h3RbtH1@gpLjym8tOiDKlia!5ek&r0XV% zmbid8keKQRoPyONiSK)54T)RZy4EB{QGhctV5O@)afYLJu!{hLV-wO2m085F*FcP* z{o@#I_{4=jk%KW*CI~Z-w&B^J31H07i$=f}Crf1FZ~J3m;!ZKSS!8aU#HiiwzC$F= z*ZF4Z745s0mD?A*_SD~MoBDI%(D(i1C*MlSwwcO45k=gi4~EMje?nj0>=$_GLm$z| zhdmb2mvUr+;m`mBKm3x6WWYQL*LXrY`r-yhI zd6MT3BvN_3^h+qF6EOl~q4yA<$9eANOxd$nF4KX3rGFd9hF8LRN9Jhs7g1BeLSOQ4 zTS9xgL1h|rWxB_E`!Idr;1`Ra9=dQY&({~`kO{VxW?H~|Nf3Q>Mtxu)h)KW;^$-vD za4w%9eo3GOtpEdcpbAMKh+seteUS~0l5;3j65rHN^T!0sApeI9HEFSN0Qlz@YuJXn zct!fq2tNdB{!kC@RTZXYMgBk!4LB0%g#gV+0SF)fY7l@Is6}PxFlVO`1h$KTm4?$4 z2P1eAMKBI-Gz^45NNdmxEI1Z2zys+(NQ+Sq(I5l!zzO4nL_cVRMwkOWP#I28gxK;4 zG*Ea<$b^Uoh5674UgT|7D0x_zg(S0unP(GT2!>$@dKHNzO5#fkS$d||jY74JA-N@l zWmvE{iw{*59p)upB3*YV9C;`l7qko+WMu}&dmGUg=a&SZ07$xERi{{S7ngAx_glCC z9yyr=>d+U`AW8MmNJ&5l!lea@5(uO41h|j{ABc*La{od!kzLZ&dQE1M{6;mDhKsTx zl4+SmoaSkub^xYkUc>la9-(Sm=YSru59rVg&;Sk6@BoPL5n}gWmRBnssh0Kgk&5$y zI-m;Ka0{w1g5$_6EohE1kPgX4Vc9@z`EV}FP$&P84Q-H*qX~rALJvmh1dMT-K0uJI z83dJa5C0H=42c@y_K*$}krJVKZ-tR!h>;nog$t>T^Ol(Mql<@$oV;OVKzEXDGZinz z88f7ksqr>N(Frc;6EJBU1BZKN`A@v(Wk~=WNzi=Epe^Z;56Uo#$v|fs=LU8bXGyRQ zbY^FQkZ0B)2r$47`2cA000wK&3Q1rGisA;U5dR2#_HbLdC<;Xq{5Cf;1SXx(oJlcJ zXNi`{$%ehybRV$~*uVi^fD33a0lR<|S!b6}gcV@dUlv$vm4}UKhoOjBoGP=J_HYuk z0FH4d16#HUgp>_Da6yE`1M=XGgyaO6C^}cM557Q}O}a_@D0qyqk488H1KFBD0FXgI zZ9Gz<-$r@2$uPMoku<@Z6}fH~`I}{!fu#2`Gm1tr3a7@AZ~HT$abqT-7HYI9ouc*= z+LJLj;6?3k(Mas$iCxfD4ic2Dl(*nt=f_F02mVT z@Cs9a03dJ*S;T-RDiT_xqB&(nIAx70rh&csG;X>wHF^>vcx0-TF&gxjtEkbX*ENfC z8wohoTD6KZwU^5qZ`e&4TQfDwr{5;C*%@$8Ba<1V7kyYl#nv@svnU1CvRRW*J(wCh z=Ml4Le|owjYa^jUSC%}R854`SsdtxH61WnS4v}H|0jK zH?eu{rnnrF4K-%47#X<`DgT^#qr57Eya}uuBza_bsHwyb3JCHDSNT`!`ZM!@P08*E$S@ zv<$bf2C7iKgv114TbbwhwKmHSl^_e8K!nF|3~->n`sf(+AOY+urBghbGk}EjD!*IG z8D8{|mj|$8Iuc$uhTzk`9OEO5i;)d`jSma4J6t6(oWpl)6U#Z44*V2qLljDJ7G;7H z7yL9L+o@Q?82ZsDE4#Xm@`lt&yC6}gw@aIFgA}hAQQP&xn1RQgJTW!gMYZC|wL!-z zlY(-G%6Ml$vRMfqQU4ihpvCK&no_!t@v6mbPzjX)kOC>c1c`XS0B+c(S65-1hFcR9 z*?DWsF+0K|`>?p32geO#f6+v_rEDdmjLkhUr>@7xtYMu};Y}4B5`@e*hK#z4VzP-G zLhHdOFFOnwu@7$}dtRBbC|t?h++@?m!ggAVn=BdG4A36|$~$$#!x_*eVa?Tq$_tHy zuA?JYvBV*PE&1TK>YD>Y$QbVmuZ&TI3x(OQ+q;KTjseAAwI6Rl40N2u6n)s{0s`u_%;s zvacF_{;C@7*Z+zRe7m%|HgPBwjMl(5Q*{3P&pwUK1I;9&Y}O&6(=5Z#a;M6lxp!?a z60@AXK&ZtVoeyL1uKH2YxO@!!fR8?a(G>xb zp=Z-7jdo+y*2=NgpKTMGi?c#K)Zq*@qkB#EmtyTx9N*wXgPi|3Gz{n#XdxS^LZK*Yw`aM@rO%?xvf zIsM!)!T;084cZLMoTP0kQ*&KL@l&}3D~b3X^`m)y@OUKlH`=zOE3((nOWAPT-!WquYcWodG@6ZuBzz!cV2Gr2y{$OVH@Z`sE z0HJvRvd{@RAP!F+nuYzYZ2+4#g%#u5qRY#U&V-tvMP+=ZGQ(x}vz_w40%X%FS^YA+LaYg4%zGp7ypv|#k^z!A4C-0xWk@WukI|k9^ONcqvjI0RL zrp*~Mfb8VilMS$yz}WQEq-o{9OP2;NrQ+qzQ>am;PNfPJ*1l|!B0cR>)$7-%TXu{k zTh?sZOaA-~bF z_Ivp8<_ik(RI#rjUrSsCfn_T^`;=-6BPu-W4Yk-RQL+^iRdi9j+&lD9NF$YWQc5e8 zYm-fM^e40EI`#C^%v57-)B`s4%+jT3gEF$>X!^v719*7hh5tZ!^DQ@Bb{p=1-k8}{ zu}^~qRW(kt6ZY87P=f}u=9W=wJM*HIc3Nt^i)2v zai4vT@e(3?fE4?r0XlXT?ApDjl^il$b~gozp5av;;@ zFLPS+AEDe78VI9~0;MZIlhz99r2F)OihRdWM-Pejbc^dFIVZiZy>9TbN<$36|YNt+P*fdg?)3BN={( zsYK!&vGTH*Hgae~oC9PTL&$;-q9){Q(mxrYPwEMWnU9)GpP2N?0~5zM%0FmwkClid zA7kQK$XZ2@oi)%VRa%KAhIT<9paK@E`3Edu(KN6u4TMgETGXaisJ2}10NP`rq8z0{ z7{*YBGo;MeYE!nvn_N%!3%2s@%31M{jMA3+9HCFP6 zF|Y&0VDaz(kmF(($MeF%bU_~LP{l3gkqq~!Vj0PR1}@4Wj?@)m9?) zaIbsSvmWePc*+%tvU}fq88L2@BY*q@eX^*8%5dZhi`4G`?bruDdg+5UWJ4TnfCxg4 zkpm~>qaON@g^+x~j!LwFf(2AyJysHrlt>VnG>M=DAu`R2p=l>Uz#tIBfCqGXkb@o^ zVN~=K38uBvDH{r}m|%3S7#SHxmLIiso|CTlYZ{fvBgSj5Tf zEgy*CfvgUow_EuNE(Yc3L8Yj+>M*pU&JmRtO?uKKfUzz`z(qE|;2uKkqYwue#Xd6O zf&;ig9iuqF9}j?2LTKm-|Ja0ko-ht>9pI?{WNLi)fsFxhAwLg*!~w#=h+E*|6CA+8 zJLJ)dOWdLrf3UzQB%?{Rn$Q?PE86h-RTx!{Qm&=+nm+C77Z=I(L#*^iCpd8ois^_) zOR>pYzN9jN=qyYlVUj?41lU*>@S0gV#!T{|i*9~NXJX2%&8EpCoap3&UeE(NO`A>! z#qxt7d}lo6Nfogyk5Fp?<@N4*+yAXKRkyq4ts6bT7;JlBpI*kZGROb4{4MD0U}6*TDnmM3JhQbW;j59SWyB1DBuRAI)F6nl~xQ( zXliWQ2^-of#kayGu6orgUB87}6pxr;oB$s&#xRCu1h!&rFl=E3Ql_~0ts)-b$IB#( zu9)S6BR=4!Hfb^j1~#w~4H5`w%aj9g@+1g%DD7#jtf!-}vri&?tyi8VTdMgZdMZTm zZB^=DG^bh3?-|?6aJb#-HvdPYLQD+d;FB9x^#;x(oh^1jY8`^^xox5n2zU)mE%Dj| z5K93^Eof?ur9i_rT1dt@w&jM=J;A;lD#R_U@#%J~S=4fQ8S&f_OJBO?Wdq5`@DAW0 z#$;I57Fz2+EGRTh^lo^C`lRYe{A-56z{Hd)vzdX-%6+()5I8E|VCCY?xwMKIIjF>v zdwlI58<4Rf#^mxr>qLbOl~e9{PEp!F~9kpH=8XXS_U#Ui3g3o!)E- z1R7{8!V}!Ui2ZU44FCK{Y9Y$8i7t>q3%2QZ%~AD+S!Z~|K`Upj3pgrHYy#Lrhmo)? zg>Sp6xMASy>ll_zF^Y{lF3^@s4#vRE0|4`}*X}Vj8EYiE<%1WU1yeFdLUxxd`6&Fj zm^XcZ1UTd&59y}6Y1d5+wR8}k?%cb)t3pqG**k_v&*zzKet5)>x-yx%VZbYXwo!0m z8P1x{DBeJE(Zr?C%3ZE*bPLX@UYLn_lzh_%panSOt2#j@Uil^R2hMYz$xE!2=jD8pu2}=iWN=~)MCZPT zhP@%e=QFP)X8&>c#=rwkOstpA?ucP!(UMAl!%T9K1vqHTtC4Vm9MmA@M!=DcV{n<3 zI0l??2Yv98WV#1(ASNFegJL+QFR`qe2pO2@5gj>-w&NKxfjd2rI}gNzxvM+6iv)D> zhiv$u*77^pVxAMar@;%q7Fs?ToIy4Ft$|uS9h#2S=&`l2j_LRz%<~Mgc_JO7iCl3w z=)eu;!a>35v)Wh&)nh{DAT-y5JuBo6!<&mDaD{6)zL=V+QSb*m$|-dys#};TfnWr7 z5WZ1JBjX#LQ2+-ToWseeqUQrM4x>I?>pD?!C1UU;%n-Wn8@lg<4;W-2rHc{pNj9g$ zk%`$62LH^u_H&6Fn+J&ShX#_rr5L7$NFSO=hxZW&OlX6BXux;y0a?ffwmSwVxCbo3 zgi3G%c@PP4c%ON&I!gqT#af_l`UpN`2?o?A4)j1`{J;)*X0IXy1g^I}mUm(i#almZw1s|vcdng7Uu)hOHnKqDz zV+ezBVbzH2IQh(-gAVNltheSPHtBB(Xv?#KlCI@&9`f zzS2paq!^#fOGzAvF<=N(gaaR72aEwGqog(;I2m9nl2QaFB*=kz011~-hOcx7Vj6>E zaIqsHMKVc;Cm9JR@P{$bhLJ!}1x3ZYbcq~zpl`a%qZl`DT7teDQNBz!NeavoR10^L zC&0rOd#Wvb8qb7bP8zLIu=zLBBu(W&jgOKzQR%3PdI2WDC??8>cKnRo&{5HNgJl>V zks>Z7{R~y9gVuD-*JF(Nf(s(ZQXB13#bAv~fKIcxkUXSLo;XRHxy}Y5oAcuVzoHSc z5ybDTo=B0=gDKCP?1b|hgUe7)NW`(Mo04xbO8WGHQp|yNsGm!;hkanw1OF&RX$nA> zX%J~D&^2hl_tO~+^#>$?2x@rHd|-yQq|mR-R3o91o7kpM{Rn%|HMVm*h!9Z{oz)VJ z1iVAh0-^?X^9L8SVcissh!#qu|Yr!*W`d!Z_UgogtN^QQX(zV zSJ8rSO+Rr|4ei2ODW$?HE!RV%TDaX1vbd1vyu+P?*La=Rm#Bn#Rf~JYS2s<+m&pTJk2H(NAAUpF)LHMF^RUX@@Zgro7|22HBBp@RCX> zj##+WNtnNZ7)GE4T38s`AESn%#RGIhr*#vR4*&X!r4)Pt7sLr_7CDb8Fkc3qrTP9cq0w!QP;0!xh1xXNKCP-jO zIN;9s-(|DRA(UT>8@{%6TkvvU4!$t7U{_hY+j!*(y|qr4!A`gY+=_bB?(A2?6_NK) z-$Y^Df3PC5*cZti2v`j!aJZO=HB^cfhti#<3=!G^YV;_*-n^+3# zz22V%%xvpkWIQb_TZt2tit-hd7xgC@K9LSiWJOMl$p6ey3-&0qC5`({&4T*cA>|GI zeIf<614;OW1D=HkCIbitU{0O|vXz8c;ABtc3`q!vU??>Tu3xns*9_L+lQPyt&gFrK zkT3<|=5g2Q%i9t*6Ta=SUMiozRbhRdnCyGu7eU;@IOG(e;VN>z9oQGO;0H}`i}{<^ zkGRW86A}I#`7?UV}?*17i3EbohsuVTM#t;~#*CNtj-k zs9reeKs^3gTa7HqDq6ohMiE>$z+|UijmD0)mINj+<L3tKj{i_YjorjVpy z!CDJu>KtZoD&}j0CBIT(?M&EBkyB@uftgHz5E{f-Y!U z4TalD=t!7V5bR^`O((pIr8$x4s!6ko7HZD!?4?-N#T0Gv7YW8F=DeWAP|L# z+(0{+FuQ#40ao~hZGg~UxPly5g*Etyd8h_gMu!}!gnZbBZD1hZU4>Zy=%5q`Syk*j z9$JOQW63rxG4QaX=;{hN-+hBxEM0+wP2C_=QPmhT1TOUI>Oxh`ix` zri1Fhh103#ZmXUP@cs)o$b|8(A{%y|Q2_>$yr7)8@+rQ{U;I!rQPl~wnayIXna~Ac zNbp?A0an0;it!PCK!;zr1!7``KK}>a{`O~9Sc(a!a9YjYl_=U!kaW3=Y`PPJB_N8n za_+MzDyWe@mLGy%Z-6=)>Fa&?1p&V8AJU9M_yv_l z;8{TO!7=XRZgP_{b&OsfP?wroldLu`CpaH#3lv=%u@NqJ)AGR#7k**78uPx`YWG5O z^G1s`$6M-K?=KkxOt@T|zyw)P1hRA&$$C|4L)EwQ7{vn1dKeR<TcJ|Dc z!SGXdmiO#N=IHH8$G~ZIKmRkEkY)fwpns%*cY94gzY#)R4b4gC%ZeauWy%6tGDQ^k+YNU== zb=OdPcprA4F_#brPH2O704(k0*ldu`acBc1hi|N9!uiS5dCXLs@Y&I2TZWfe2V{^3wU`EH*oS9O2eqgM zXYdDP@CKy#-<1|%JO9Y>1|D{%Cn-~t3#j*^pq_m%&7?QL)wPRu64rY8r&rN+YEH=Z zH-*z?cIL7lbAWK;X4nCL#xA|tp>QF?9hdw;gb0ickct*BV$6tf#ta`GJtApy;DD?) zIS#auMeP_re*XT!jQNkB$$dV+c^o6FQYDYF#vF^5FQ3h9KHKm-25tXW6rF(vX0K4KZ6b}di3Vfrca|zt$H=<)~;W} zjxBpO?b@~>*ZM3N;q(vU8|2QP3-`S|BE;Xw-*6%p(Irgk z-oI0CUi=Lq^2C<8jQDRKGH2eZA@gR>nS1!??0Jh{EtnQ2l4ea}$1iqhVTT=(3@FJ9 z&@tGcgAYbG-6oeMQK5wwVwj@{Ti!aW^k0us% z^pTA>;+Uh3JMze5C0Vt^PbK?A)CmtqB8g-toMctqCNe-7rIb@rS)~j`jFzRATXNZ@ z4gwKmkTD6d$k0R7O>~%=YhG02W0hc1QX6fs^b(BSwc*h`J{;pi4mliyNuE9kI?otG z>4QWzIsd@vLmNi5Aw9{IG8KyB~l6kU1 zDgUEM5u00YJ;O+249T*KEPd1tpdRIrO-UYA(uO}iAUXy)mB``|9Cd#p&rs}KT2DUk z=)=!3oZh_NF?oJMDyg5)Gn5ktj3EZEliL~!DVR*2c^*r|9IQo}#FRbo&T>S z*=U2Qz8?t7|pniQ*O#VcYli^$SVlY9d`;n?nrVtmlLmT^Gpz+{YST%#Im z2ayR?4|{T)iP4#R*4m>NP9xIpn4BWn?yrACHDtd`8A ze3%#qpYqfRO!&ZTy&MBI{IsZ)m`WeaAV&`9^a&ffuvGFm#yk9G!{yB6aQ`{_)hB#N zDtag}FR-YUUh)8oBPwx;zd~OnD)ykX{Y0rD&(~4Y--SgbF3^oFkLF;N) zME)7jgCbO*zk_2O>F7{8q6Q!R$Rj=~Dp5W1F`pXU=mE;~hD*TYff-?gA+u6G^Eoo5 zD)j**%{L^M>_c~#oay{@$BDt=j~}VbL?#4cO4CJcIjl_JD^J!yiD-?Mw6vv3gOo^j zx-*ggU`IB_;HP6`;}~gq6gYs%(rk?IPqH9~J{q?RAAG_c@t}u0T-b_Z%wr$oXhjX{ zfxkt5WDISvs-OOJD6e2ciLd|?Kd7+}YUrh$p(tlM1LLc-u+yEy@c*AEVZc#qiRQAJ z-7IH2TbtbM#vk&snDi2ATG|Qkw5kp08-AAz>S^YovX!H=N`ps>;x@N=+~XlU>s!~M zOlAKNDc9J56i-#~04)dWlQK(mTW8X-|JD znxKjaAw_-VnPx&LE;B6fIw1U5O%&!ZONd}2U)av1uBZ8M;pi?4tpGqPF}f3 zpKde;MfirVK3LU&hX{-LQYT2TfQ4Tg8yL=|??*A=M3rD*+21Bh2Pj@Ki(AZM*ol@~ zxtq?tR%_!M<9Lm&jmT?FGut13thSmd0!1-;h}>FqqPXR)3;$f~$4YJCV}5IMnR}EUh?u(AZ|FNoZUd)R2ne7u3WDm z&qd#)!go!!Jb-@xoDpE)x6r`ouS!kzLjr3<9`8snOZd^ae0<`+KG5sFE};k?tl`mZ z7$P+)h)Wm&39%ja@LZUfK03u@vi~#jlW&uuTH`v`x|X7DwB--q5CS^VOKpyeZR}$U zlu0~>t&f51><|@bKC&^Ow ze^H|KxLZ?%I`%y1LLWMcxablu8pn;lMmE!%?)2d7SbtGW&9ke{A=4CL+WpwxNQzK| zCmdh}+}k#{bqj8yqn$G28*akU&CZ@&`6F=85xh;RWqCUilJ5HfCCPkA(=g-)H&BS+ z2QPT>sTm>PO(5e7?syd)+|UYNc*7mul8Rr1q*KO7Av3}eNB&81HtfmGgLJr1qa_Cr z_RYyJ(TYn0w&j`|Y*bI$lD@FI<}{;|o&J$?o&Qsb=V>pE*MUC#<0C)$nAzvAg;&t0 zLqGa9j`}B=ts1LiA46C#GCr&w?gMze2x30~*~^|}jB;-r${%+~+rFko&VAiBia)$t z(xeJ98t;ybF3xhscl5*$4@idKJq7_D00Hhm;hoG2JYEA9+(WcqWCR++AsS&3n&rKh z=DA0$+obmNw5DKBtf!4O@PDDsw5-K4ZQD2X_M)pBr5}3xcRg@2Uo!G4a8SD}F7SR~%>Q(WSwtYj0p37nIN%-PAw#U)L|8@y4NHFU z!(&+9=2Zkqh2bn+oXj*6HPr*`0Z~0P*he@T3bNh`l1d9UR;kq<`S8OG(%h@vV66R~ z4o=DUePLx39}u46DzYMq!5D8WVJynx#Yj)}#YPlnAMtUaYOuf)ut11tAr)5CAryf* zv|@`z&}5L|B3&8CSzeH2#oe``jcD3`RU_NL6sJ_e4|oD~e3u>OVK_eC9MuC6Y=steVRK2_hBNKck%S1sY~Z5RnIdHfBR-^tvxJBXus{|#%aT=r zI2hwZb{5xQM&6Mg8W!49%~wp!V;+``;2x{x zfkDP2LXOx%mKaQ8-9u`KUi#%MI2QE=PbdR zKMWE!bTC`*4AOBkOI<1zy{51m56@kQ@uz_>|}v< z&J3&xIx46Tz@{8tLjQ!i>4dTdMjQZ19RQm|oJC9}Fc4ygvdOR@oJW+N>DdVV?90A{ zrQ)P$BtU|Sswl5S!aE>VPR0a{)+k-_2=C?SD0(NBq6S|=B&ULEsIJC&#!j#y>8UOnFAG46mRuWYS^lMii7%z>J?c8Yn;Sm4C?`$CRW~{<$5UxdnI(MM4P%PQm&nh;3l3PK*ZIlAC{Di@M&@3m!9HjqM2TQjlq(j zT%qnuD{MtHv;rn1LMSjQzOE=+(#kolsBumzL0YG!?g;Oh6inpcjzURe{wigpVuv(r z#7b;t2xgI@>i@-hOM9M(s{$GLdEEg#fi;-q#}>gnOw`t$thb#XuIgfy9)bz@>cn~v z5R^u-9)QhW2Hn}D!?6sr#^1973lb<5YbvNv5~Vk0D;`E3Q^u)%S?EZJA=IX;Kd9@T zmMdahUQ+!beE|bXv4i6tfe04YreKUWY#szl1 zn|8jXj_xQA$}I7DYG3~C;QlSCHlL|tY~m7!#-a$v&Q=kCgDQ*yI6OfnWCI`^z%{6X zDu6=~FoHcy6zF=xI*cwCnjOnp#z?B7H&zLB?acY?I+{i}}D98Y@;dV>-@m zp+#c5IcuPLE&8bD)uO3uR;#rJukbE}5kQ_X>_dzc?`lw>KO6wlM(tzR(sBh!^Iom= z0vbA2prM6-DTP9 zdMO*qjP7>mx7r^J`>qVnaD)oTEaRM*;IVS@6t|dG3D_+c8 z9_&S4jB%@#agTf%8oxxsDy%3^X8qc)KMV9R!p>kKT^>VU?=X*dFqE|Xu|qk_6WoFu z9P%no$xe6X>`#>|wmGlCEb zks#e&87e!Rv-*IUYI8+I#>7$UYYt^IwB{`*r55}G8SFq4ObphngEJsQHNe3EOu{5U z!2vizGLHll2y-DQf+qw+HFV`OI74@&>BtQ!;W^*5=N7^(1hO?uR0H<|=&nN{JVF0s zaInYLR!TaHCZDv*=4xkKi_O0DZS3EVwjH4r!ZagRj#nV$g^V~bDA2jgsQc$qYsA)xN;GwPS!!SesrUIurk zX)XIOL>vT!zCkYp!+rQeejLCmP|p?of+{$}SjUJroOODq;XhQvSu^cp)Y8@lxPWW( zAAW1XZEeIQnkFnbgO9U=b8i+?I3svEBX9wQD*`Q)Los}BB#=Tei1DpN!iPV$7!XFf zNw!`!!#3Bs`#ztdatM5XWwyp%6P`o%R<{Yj_dg7@VFdZh6{|qlASCIbn3{4 zohNgfeHH=h`g+I|>zA8`{;?a5@I?KYd7<4Ox&AcGUW8->E1OfR?=mRTisKs$Loob; zGuVSa48t#EwVofqF*^e~2zoW_!#vcvKRkms%mZP0LohG`%_48G_VE97;$)Bv_$(=L z+f6zUD6t|aLMMnbra!TRuPrI4C@LhvAbfhLfBGoULN5%%OBBN{pn9oC0v_OnzJfRz zYub+FGp$1e{Nm-d%f_zrI?*G&xV^Z=4*PMCHofT&vRl!zUyuAA8IlpB{0`Z)kzXEd z9T=Q|wkJIn6==BINST*=+N1j{+0vb6M7XZ|T3-a4H^YL$yDi@#*3|tnU^V)hk%X_*as6sE)0xi%2I4nn-oeN^=MI@ZU5UDR<;BEiG;^-LgUC>uHDPH#2 zr})PhfAT*WuvZ7za*OehNB`=}LPPzHr*<7AyA)Bq^;rF_b{n?8#?|Z56HpW-kHkwV ze{EC(WUN6TIKmo8MjZsgV_bpz&;Ll|K>Itw4?u<>07RfbS9}ySco1Pig$gTGT3D$K z#7f87RJ3@p4I7ObHFfL=OcNU*BT1Gl$%bD_l^`{ZJaB*{Odv8%*3`t$UrtX#c=Gh* zDQC`0JBSuFderC}WB!cInUk~GuPeW(R$T?<7nEcE_WeQ^jA}5k&JJiwwQA-|wIta9 z1Lp6gN`C+7)}<>qB`}dS`Sv~emY?35ZT$rnd6S|diCqsw|D;@eth}!>7(DY zDOoaq|8mMjopYH01LTC0PDUY+kT()ckckEzd=SD2C7h7L1{LHa!2W{DFPTgPsiVFS zpCgaN5=}f2#S}@Lu84l{!RHVcVSGY87h=Sxp95}$F$)oW{1M0?(MzeJNoJX3m01E= zZmLOMTH}{hkeuZuBasYdjRSm0a!P`9`w~oq8dCp=H=Ou6MxhyI@XMr-*a)dF#PE`f zB{uEs2q%Aj>ZvE7f@%z@KzF!gsb=PIBba&o0Va;Dpm-FDRSHpLj$a6Y0vL3D@n@Y* z*KwwrIe>8FD(2V%Y|c6BniCj1T|ITtmiR(UFqHVo<`&3wjm)ykGQ-R=%r={Y5iT+b ztrl-+!3CFP_p@tNmG+U#wNP%mwl*=4$RSMLa{6tIW9Z@}xpK=D65VvwUAKtuR1|OB zc;%g!-g@o57vJ;h_;BAkHp%2ZfH}-BC;ssI4?qEzA<#gE7gVr92^D+;!(|FXEk6%I z%oo0QJ^mQv64e^T8b*jXO5+wdR~<@9i^Z^s8s70R#tgwl_d|DY7MfhWW@)q4U*Ca zZVPfd%(%sL$cHlLq`M$B`D#nnzTV_$FF8|XwWC)}Dk~+O`0TTp(}WU~s7s)lgQroD zai$a_Q-R}eHd1lqr8s7Bq>x~|nP;Dz4)`1htR`_p5ZGyQNfWgOSE=?l0c+K8zX&@( zuvzm8JSAgx)m5@yD~kkJUneu9vrKO3McL3uqorVIRZEqcNU;4rHZgL5Temi@!3kV( z{~=~LbKO^t>iFfC*Ikh3zaRhn_22)WeTmE1T~j< z!ypMMIh{CV4nVO-HBylZLNvz_8#_Q6kW>nLENU;292=52iI$km4tR9L3maw!guV1` zFuOZtn}#a0^2CH3m;PlDn91fJEEQ{du zQc6^sL?gQkUMew3lBoY0FP6O0Wgy(GZb8vQT(lqM=tVzVb_g<9;{Z>9#yCt{ zUHUXcE$l$XFOY$bf9xX|gh-o{)RLrM1R@7b;?^u|y0%I1^h;(uNJZAj#-yesa3K-g zoSZtCr49~wZ*j{;4)@fr&gH7l(Vl7!;0s_lr5X6u4p_fxV48>(s{E+kS^ee~xag(7 zMLlI({sGIlUSj{2%*za=7{P`)P-+f&wM-}?QH*ko=9j$~EHR<6;8nq9vDnhqPZ8p+ zGmT-g7F%EYFq<6fJ{e!!tRR%BTxBa?8OtF`?Up~bTD6p8IRItaKK;owd*H(!K|BOI zo{$W+%)<@6J=!%g@yG*^VHj?J#y**r4ID9d2rK|;Cfs1#EFT&>4yi;?_Ti0S?Bf~L z_{TAzcts}tVy9PN#Vl3f#7E@$ZUwSPZo@L@Ld_;S8PNg% zk!L?EaDyKl;R)v~ml>X-+dllZO_S}5@Bv%o;=>>KSjG^GU=A%9ExO4l#3qjB23NSD z(JMOypI0V>17yPm$#{aH6<+gBtf3)X@rpB$(Q~l`!v|T?k`F?C5KtFn4N9`NsL9lj z`lh7RLIuWsl^Wu-8sO$B-eInPF?hZr=a+$tivYub0`dxzd?tn945^0 zpdD=u|Aj8OimNBoqGDSn;u7J$E2RkUlt{b&pQvy z%tQZU%ZKk{AX%DpVe-F?quH9Do;^~YGU{31de^^RNDY_0iPSQVC%6C*w}|f3NI2%? z262QHZ`wN0>>_V?~Y;}vc@uNb|=iuZ0Q5KNbUL7WbCHs0mGDyh4jUUF+T(S+I3;w9#eq@?Nq=mL0z z?M+hRF1AWK_#!&m&XnK;?&8RB<|r__%2noWt-?SS=EB@mR}x|H2(R$KZ4Qj# zlKjCn&dndJVObn+7{DR&=)yI61raRI@-Pn$o+&3jPqNye8TR9{NU!v^PYJn$;0ph4 z37-%OqfiQGj|#^_EuJ77tl=7Hq-J7dqxkH&vLPFuAc*$i9L@|!{y}B<=^xI)8iFVj z#E=#az!pTPAJUA^dLa{DA{(@Tt&U2SNFod>Asglbu8xQAMv!@4g0J{$5QwD>zO4-y;oAt07HA;{ z4-a8dqb{hS7?j5{Dvt+y@O$8Z^T@>WKyTlsY4niLW^z?L*)@Lue$ z!fg~>0o)8>GQ?pUwI>@Rp)$U*GW=j1=h8OnZRxxv-z4h?wqnWL(Ksj)FqfkVoiH#9 z(=ZS7e)f?HC(=0}Qbuq@X&6&2WTsu7CW!uw;$B1{GZXldCJQ7JF*pC~AP#UJT5#yR zuNbBUC+uO-Qs-M-5;lDRCY@t2X0jzXLKB$sc4Q4mpc2`DL8^LEEdT=)g1|U~02J!T z0@co|a8WpyLn-|xHw$CHIE>X=sU&0}8}{QEk*8O@lCRW4+ae+GP;eUWiW3lN4$x99 zZxCAA@+}eJS0-Zz=aMdEBR9r}$jk>Pgix}AV_f{QI6yNr>v10Gu|N}4K^L?>6m#|n zR4p8n;+zITy@MbRzywTS1^n?4GSfqy=0*aFK}EA5)MC+80&l$UL<^%5_~9d+s10Hh zzGky1_a^RSawefp6oY^ycoZo^#FU^DFp9w!on!9c;5d^sD3kxn0c*55H*6J6B|1-n z071+;T?so+VjoJ(D!nsUaH;PiffOtQ5y0)P7=b|2Gu#*<3{b&w-i;c>fgj+Lc@V*Q z62TDcQ%~_gTi%AqPSigqs|eReK#2neWM)Juaxe)qQ5)4!9~C+rRQ4+LXgqX?uEPZ= z^JzAe3@$S>LqJ9%6H>!zG+!bj=qN?KPcB-tMNu?WWi(BY;5ltEPAt$y@6IHGKrM8Y zK9F+miUCQJlc|`)R)950kJUJZm8qJv!k*Nrifu|wi7Bh|N~6swM*=Xq6EY-2+Z2HW zhyx0!V6U3TGEk5}))bKx!3HBQ8@-X1>U3OjDNpxwF2(;~2}ojF&S((>bshV%P)8Lo z4-`QGmS79kFeSC&q+Z(J>dufmaD z>-Anuf(C#93Ft2fLGM4=u~6U9Vih&D?pAO2_6ZS|;iSU_IP){rBVu7hMjDoHj|fa! z^)hH5GZ*RpM>{e`lX!EE3V>IIRXA!1plY8NYgJGY4!|i?!4-yK zOwHDoiXn%|b!j7^J}pli_f!mgv?h!bF%17j2ykEs2i4#F()8*VAIrC!q}YnDc(c}b z%c8>{=l2kVOFcXkN8lHW?L}@XVL3|jAokZ)Th&CFjz(R!cMu1_c*m{!#yu98I4L+; zSE4W`n2#%1SqG3QHTXwiH`@N;T8Y+!*#vilu@h3v?;=44R(OSnmjD#uYB2*8xJ^Ch zKovxxSKRXNc=&`V<12&sdiiv1`vMM%0VgP@C+6T7w)7v`5edtfd>7Sxb=jAHS$?z_ zwI~%L-Pcls2#mQyj71fgIfkdu*hD2)Ohl>vT=gXbm_2|IRccZt5V<7uYlA1uB^Wr6 zjdN!I;Q)%EoXa^m?ZPlXi8fKKCI|nRm3Wd(5F?J3V3fBl68hk2Et!R-wg5(;ct;r# z24N6T;VUOuOo72y{_gJ(K`vLBmDz+a^ki}T!E zf#G>c!A_Ufl$+6@(l=p{V*-)K6dd3mG_Td^1WJWzU`s)IvY z`a@ruj8}jRER~EITSS=dreFW!fAJSZz3=II+92XMsI@LgbyTU6s_rmX7Xf3b$9a#Z z`Z!mGwvn}}Q$=SrtaFKVI(0K8x*94C=aGTH3-a16vrVsdVf_9%ty?$%NN{PR_ms~T z7K&j$X$cind6n(8uk~akW;w!wLa+ssuro`u5BqP^o4wn6IviV`tfL5Azyv~|Q)ODR zStf{}V@Jl=z13y@I{N@V8*;~ljaA|pLc(*~!~yNAxbI|2YZfmY5LS%!w#|7ze)7Vr zn(9=-!jsc>9FPNv`gW_8FcvvZa`(80*iOZhNQ1(;Em?S{HoA)!6-WUXa+rF71;@=6 zm4jHXiMW;73ZsR9M}_}j4#qnu_AokN;Jp9xzjrxdqnygq8@??FQ(xi)Hr28_^FufD zr4Ip7CDb!ByUN?cC7~Ioa~i?vW`9L#+2rG%NikKZ&Wa6E?# zdU;@>hnsP`Cz_)1V93!5@tUD0a3Bc&C?||zDb~q4&il*{Q>3xH*Ml9HuRO7%Vmk5`5iCJ9qLp= z-TnN5Q-TI)Kxa=k-gnz}=49%RGq;N&D5K@+ue6cR>fZw%4oA=lWTkz zng0@*frEL5An$ zo6GN8vi<*i^5Fwk=?`QVVyw8mC%66R1$cm4jnS7fvB}OxHNK zzV+u_w{KSWfi-5&ne6Ro-}~C0&ngJEClV-~?X7yj;bwc6U?>_uX}siDEGMX*85zcmSkopPP{oS9JWvb{PniF*{yXrG z-+}*?U|YTfrV^}KFR;48(u1dM+ep-g^3zI994S({Vj%brcUw(Z-v zbL-Asq)3wAz=I1PPCWST*&*~Umshc`}gqU%de!=AQ03LGipkGG5=Cv8*yaTfCOSxmPrq3;?hzLY1LIlP3%LFpMd^pT@ekr;6k5>Cc374j5a#o zjS*>b-)a6y#9Ds}E*R56017B$fxvuc83`=n_#@6PM8ZOtUZ@<_ zS6ru~7&kh@3@^g;)ubP78L3CGb(El{F$G9$u`dQIDydZ+1(jS8 z9iZx}xkd!Xs~BpiQ;9*8SdfFauBt1|9`~B+QTn+Yl2|daZ0sFwam7z$*M?GMw3J2C zBqEVO`B*XBew$agXCIc=E{r({6D;dW)^15H#jDx8o-uas4m;eyMq~b3EcoDr+Zm_C z*cGn$;*2-$_-%+s9_ZtgSKeO6m@BmLNWjA6@=O>-x*tO!sTS5lC}*TH%PqPn7F8xz zR3g(}-HdY(5>7P_f?h)U37^0~M}19bnVUDav#zP95^I5fEbW<8=SAK~U{hBwhWJ zwH{W+ZJ1P#IR;EI;~JKBBrZ+)cK7RMNfKthY=*ZGb2Nr8-#Z9VZs3;p@Bja(DVXGn z1Hb|r@PG(R&j1&=9YQ7Wfr`sq#x`dXhj@;2A@djpKf<#9q)sCo=?JD0bTSf}P!l2~ zmCbO1n&TbicFe2L?t-!_5uGY3RUzJlj3=QI=}LIOs}P4ew4>>Ls(O@3%hlKyx3=hE zFXb{9zaDb{f9wMog$Wm44im2QEu~6Lbl*teCqKN^%O97(AO7|S!8W?FVuxd(ciu?H zI@%F|a?Im!9C*h*{!4-y;}}>fQmKu63}h6k6pJ=^NU4nxbyNRYP(waMNs2h=BcPZ` z@m_d4r0DKKaL5BDqB0k)L0*DPFRQ zZDR~IU;!?*?J6Vc3ZuJNQm(tr?~Hp>;|@sU5B~Y_n%I1k0QLBrY)##O>Bm|ULA!ZLyXYuiZP`f;SiO12nrk?6j6!V6_u+z8tiz| zycR{TAR(cVmA2Ow8~p>9C4EcwRw|{Iy3|Q7H3S}HS`fry>3ukzA7{>(MrrcROr?3M zXh+MMZIY9;s7RcJ=gp#9FD z6)9y^^02er!66h!BZ^&vz(W{5WtExS>nkIYm6-HF3~V8+TS&pLWG41{{3_)o=|W7s zKw^uLbqh5jLJcrp$qTnFSC=$PzcBICvuXq_a$o;T;L#SfsRd53g8#?bJTCab9|7dX z+*z#D6mn(4s+mT4%iET4rG-0z(9BTt*54xK05b&2bDO)X=}NSs9QvmYbA=+e6~rI) z4QV2-v?H3Hce1sT5?6-VUavtmzLJ@5x@x*iAV9<)zSu8+{o7Lj@8GA5fv}c^YTDCo z`O9ENSc4hJ$1oST5@@bO8yGcV)VOFh{#m4qvMLb{JMtpHa2rLK!ot+J@RUB>30wK` zNuI43D4`hTP*z!8io&ob+U=o0)vFa{>9Q?KwrmqAOKBpT4{b(Hgk&kBG&oW{!0>4~$@0+xpgO8uJ3njBEeW&gIt;ImR*2+=kZ-2+lHznv3Wxy{+2$ zrs-2(QZhna*4*_}peVG8p^NB!0J|VAel(0vT?QE;nNKI?@`rr@jvX>Fg@P_+I*OGJiXm9)FzMx=0;InbAt1nFXbQNIK?hb z0f}h!_|jcNSADN%Ew9;oFNnZ*6MrPPCG>mhs@9v;ua5Q5mi_dOQ~1JB&-z}Eo$ReI zCrrqqoYJ-Cul&GpfiC#$=$)11+=WSYX=4*i%22Ls&Gto8q?H+m+l8$ZybcR*c$oAE z7O)@%BuKFf?(=eq=auQ?Cj&Mk8{H6)PokCDg&BYI*GoI~$LL9qKLMjD_V^!M*S((q z{ww(Ph~t0Wq!AWZdx*3enqm=-3LRxR99f+na3kgyBXuo(aU(0GZJ7UQ=rK{6zffC#x%QrO29eE>f0_kQ#eaP((o z0w#b&NHMCndPSIoN(F!s!)r=NM`VFQC`1y+VSB3)Pmxkjp(7CuXciARRyIQ`88Ljb zQG689Dl0c=|Bz_)k#kx>6&q+2ANUegF^4cwVkMFXd2j$H*oS@C7QI9br*I0PuypGJ z3-y(LZE+Y{Q-kj27XN?;hHwo05@r9!UsV@`R)%E*_Jp1&Fh_`lpE!zs#DoyzgrtZ- zs{=g=vQD&Ndvm5AT(yODCL>>1P+?d}CMP=?@e;{$5a{BDD*}gcs4J?{D!B4PIFv&> zu>^bQhtPO}N(2ij$bJ8(KngpSBO-NPV3P=$_lSk{4&pEupyz|DHh-F^Mpy=Gso0K* z5{jbej`CPQrf4vzIFJ65GQhwh7SV-pCoGAyTMRfLw^%%>@*!j>8)nE5a8ODSL5FP^ zfxkqI;nt7?bv(90JYf}R60!sgVS;=ZjeV#@|4@S4XN^2pSZkq(x%7=z!jf%)2&XU> zm*|7_!x#dWjsRA0_}G(r0+0OXlR~LD^*A|02|(3X5c{Zm{}^&vD3D6SaU-!M!XtAH zVUa_lJj8dEY}H+3C|9DyP{pt*4Kj>Z>0%vHA}De*R)JTm;*lXKk|G%j@8A_H$rdOW z34^!`-IoY336B5d$9>sSjy6eUI(clucrFN-C54@* zKn=h!2U6yPKWH!Lc$m_3CY0Hp?9rI5<(~4%Cz3gt^T{~XhjtbbAh*Ff8u4tnrId6C zogqdM7Wtd200@o{43j_+NDvIakOmC#3zGl{f^eY>kqW_34ZYwD&tMPTZqxvcdKn685DJh03)|UqfBBuHu$Qo~8JVOR1uo&wQ4BoIK=zt8lFbO3}oO7j|K{GR@c_O<~ z6GWsHjvAvn;gQryoj~V@kRVccsRui{mqXf}fC-+bfC^p!f983fXtboHw~koaszkMa ztmUe*`W#j&C-*q315RdiUW0O`hz$k6}U{~)7uhTh=CnzM-i3fUc7~6S`*|;v) zsjo`cukhyyb1(Z2e1nXIeDY0%_8&N8yZ#%bQ_psVQw*oUViG*7ghOz%6 zx3MlFtak=hLsT=xWsqq4pug}7uz3JOE1S814Ct_->!7B;Pz~$g49;M)5c&(qPztlK z1WT|AYYMJK3rbzF4yo`9!C(txnGxvl3*Jx-&rl8C;0!mr4p}h`)nE^OiVTwwr;9th zt2qg&FbP`_1WUjOsbC9?0JU;Sk|vm=(A%ks$9-EHllt11h;Ro`@ULY{bQ!T<@u#+H zD^2!?x9S@k3cIlD>$Y~g9q+3sTM9aSiyFKdfq-j^|0y-Ev#76>kT7-{#Q+Gu;0UWb z3y$Ed3<06RAPS7(4VN1X8;TCjz`C3JxsAJ^zYqqe`zqtwr?#u6)j+QNFuDJW3!J!X zyVW4MlZy=VFrpN?z`@`Masa2t3#Y$u1_!_h!H^1t(7MnYjn;{RAvMG$s0KokwL`MK zN@oauAO_zHu)YwCAJSi9a=t;>r1RUwrPaPn<;A!fzjrIf3Zo$UNl3k_u}mo={rfTl zYFuzIb4CFnJ5&+CunLYap`<&!er%hX5DeFf47K|Y)rt=GfDDe127bJ_q5HuqCKa@6 zMf{+qLm{HoK(ma249MUN|6mW^pr$qJ4V@ee$}0$~uoK360DbTa&#MPB+XqODeRt`L zYoRqr{D*pAuPBKKX5a@=JjIucG*-+H%}~WWWxiUBzU*nn&U_kR9LE38?4)Fz9n*{_ z&Vxd#0TF3zLAvM_WMMKQ#4;K2KKDdI0Fq~BIfk926v0)X4B-g5pa=|s1dKZgX^_v8 zK%vk&2|-*8#&Eg+5Xyoq3cnDWZ}0|k@CK{!3vzI}p+t#8V-NEXFZ)mp&M*|DybpT1 z57i2s`w-IAFw!=AyQUlj3rqt!F$cjg2zubdF0BW2`pQr{U)i%3*~1Thnad}b2-|lG zK1vGQ$9-M{w)Eq-qPNWHNKNc`%}&h_aqE~*-ILW^91%O!>X8!Le7_ZedrDJ_bW^b+ z6hbWnAiiXoHs&E2iCuekxOSHYKa2!`K)MWk04n>#tDp+O(8>SPfDFIj44HeutNRP7 zumu+~3Bh34Kw-KxumqvBP=kgQj8VB5{ii3ar~lB=5`43q+`|4K!NG~U96SrNS;K5l z49-vrR$B_cV71&645i=)@M=qtlG8UrueqEELJibHoe00|2R*8IR#cvIfNqkVs!E-X zoOpj&?bOlizRfLu^+jF1bg zySR=}BAyTox1gKIunz0s*Eegy&M*%be86Y0&u0)6`>Y7ewPFRH2geZEhnE$@0HMf` z3{l|>y$~;YD#P^+%9ra8&+rTD;13rp2+hi%LEyvB5WD}-z&$}M+uV~1sh|dxN|(WS z5Dk%oNUYm~c#YT?EnE{VcVGz3;22`NSs9oW#*p0V*%(c2-Ol~o(yZj4INf{Xmz&Wy%G$22 z2hE%5A_)ucfLvth&bTd-Hh#T`V1rj;Q%Pb!hz}!-P%}n0p zx$b{ZJ~6$%9)ncn8^=sq-eDS%uHo%5s05?V{_OuHqN2}^A`O8`qy!V6ZLN*GxU-wl z4G|2CVBjTE!x!=kV*tr=^$+YY4-w+Zxa+_eT&*J-yR7Tijcm$r01Sfs4~TBr`%ntO zpyGHC4258+4>C!7SKBuljo#?QryfR5*%)FQ>r<4Iv>t>4mgK>%>$@J08~=5`K1Uyq z9fjCNfb%2j4ff692T`p{@CHQN*mYX& z2e9X-JFc~>2{sW19KH^>zzB-K2!yQ&aIn|Epa_5v3<*lQi#(fWKn>3z!5zNYmmItF ztOtXT^)4=wN(OUEdk~2TjScUq-`GS@XBPh$(HLPeG%L~=7hmg*G4jpb@g7h32N&{m zg81rD@?0uQCodBH>zNLjb6}oVnFNAX0aXK=t{umy;X z1fq)sUU1L{;K7g#2cO-#Z?FlS48RbI1SsvfbKnRE9Rza?1*2=N_K?YvE5Vw3$^769 zxggsbs^U1RWN|-oOXP>T?eOQN>dSUxDrG9j9r)=eUT6m3|X~*{v00g=PlSehzAqe3bKU8nMtdH zP4Yrx$*Nx^OHQJZQsqjPDnSuM=PdtNuxg5e+{C#m)vREvCe2(0Q>jfQ8>*|GM5Io=B}EDm9=dhy+7+_| z$X>pE{rUywk6^)nWc^**ky!C!#*H06hTPbgLw{r~U&fqS^JdPSJ%0urTJ&hrrA?nk zom%y3)~#K?h8LN*O-^QI=_io<3dCvwOT=;O}#f=|Fp1ibg=FOcyzgzAJG?vBoRUygK>P zWH9$MlrKXK4@EQx8TBMEPl3XkNZezg*ONQLnVvA_U!8~2(du9 zRKk@U6bV8a;K=kJcN48IqdY8&1Qu9Mp=KXQ&!vi=QuT0AkF&t5@y4zaL1dSD;X=d@ zKW0TaFI@jx*PmwQ@HOT+5H#!(#E!+;$tWEfMqHnN20Cb=Kl9RCqi-8JX{DF0@@S`j zV>)W7k*kvpiq8cmU6$3G_uhEFP85!-5!@GFu|m1@L4X7PHzk6lV((x?L0JNi&l-L> z;)%hN>f)^;$(}|n*>1zK^XT9~-RfpX+*Jr0)vz4tL8@#O1TbCbD4iI~)guy0WzhYDsEAaLv z-gLgHEM1%JwBK&87_s7Af|?aMGxcwWA(l9Ki?>4cI~&zv3lhU)m1`HY8gE<-$Rj_p za{K4#RS3)}JB)MB{|B8zrc^ru7SMoFD_ZQRbwCC-a83$@odYGPwD|$yPPr=&@6_Wi zu?(+xAH+$27G*9&Ij?Nyp#W=<@B@lvZ zB4ZlWNSyyOI_*tsgyXWHSfmk}OA|x7pxiq6t^Fq+1wVn z_@teEF^;#yWiDZ3#x{ycm%juiW_oF~HwM#~*qI|=0)xEpuz@`1$s>Hoa+B})k$C(8 z&;c?O$Qe1(D9#%U+WN&pmb|1ra9~Lz5d}%EzydRrgr`@i@eXn9q8OZv3nCVm#8B?z z0MsBQ9v%lpBTdc?lbD1X>_>%!#;h3!bwn3pMg=$I!WQ0ur9U=d2T9nW3A5B$=#Dv3 zk{^Llgy4xUQil>q zK_b;QM7pFQ{1E3#J~Wm0=w}IeSW6^ML6&%Sl`SFLMJGwI3nTuhR!v+YK%4l)Q(7p0 zB#{JMD>sQ>Od@7GiR&-ifCC|{VitML#XS5mkEJAJ79RyElR!6_0m9U=k8R*dTk0Ih zR+e;=U7%$(3mQ#iMy4!Fk!5zL9rAGPJ$*D@SbmDApnm6I^h(r>suI-+k<)DhfhwhB zh+6zy)ovL(fZx2D!$d^FEr;uoT=3urJ@~<4XGJTDsKHMlv9*Gz^pzuKL51vYH)j7` zSj8$F;j1qEq7>P+gAlaKUG;9)6S;7PJ*<+7QWznzisfHpH@jc{GEK6W^-X^Tye$B; zX}|~m#~nY5$El1Kn!-Dtq7K!ys;(Aa1lt=wDvT3uw#PCWDk>;sxG&mT>V@c}R5m?` z6W?CuRFD|%S_)^lUG(Tjv^rU>Ui4h}Es-B7Gv#%6HMxmO)K_l!1$(KW*Hxrf2ps`N z<)~m}A-G`{U0AXkI#H0#-8V7;6ySlyJmzivx4=*%bDGa|W?!mVvxPZ;f)`9$t@)*Q z?$M@v5Jh1NhY-Vh8migA1BVYQs?hNnOG>7?C=rwM#Fwg!Hto}57oQ4!U7i0iK4TTK zNSF*r&9%#m8V22dPQ{5quAq_pk;*E9cNH<4ge3Yp-dXn|yb7(Ht8q}?gX&}yT9l=i zckl);`a{2NMs~8zWM($!M%mB4PP4xSZOHON&U60Lx(*O%oai~VRJCwxL*>nz%u6bS z?#xZJDZFxyc&RLT+qO|`sSlCGU39UG4j)FzO!Mef`ox37_(|#@Z6)BP3X+d+RF_EP z0Sa?$87rx{3_qcg5?gRY<}ag^?%-C6qT!xZy0Y0t~jqDmKv}jUs>n z+M~eN%emMalM2+p1HeFQ*}&RMoCDYgd+;ZJfIq)@xZ6Rxc=m>GURhhJcaY4C>d*$0tRypiL$1jM4yYrt75J<%uv z8Q?=1fPo48z(Az7)nh$DM7<8&IYT6)fAEIFat3rT!9wr|$a93ffP(uAuSrP3A>qBu zfR{os3d@+m`-nk`;WiDijN`Gvp2{t;8#hGykb2S~7s>xLaTpPO@&nGWizRGA^Yg{? zJ2<#e98FEB|QL~!LXyFlfS|{Mj?=dV3>uUbUeygg=+8xu&9P$C@gen z2$@KVV914-@hiDH#s%y$VS7L@(u_S!$F2Osdi4Lw0VBjh{7N#LM`s($25N|DKn8no zh;>j(bf|`P7!N3zg-R4JzHo$9P?v@DMB^eC2_pNoGC}l*vjQZM?gHw=d3JuoJZ)~ zud<8|>NFsNc!p}gymb&jevlXt*@Rz+10a|MLEwuk_=T;h3Ow744;sP)p^u^y!XG=lujD)ctz^y_^+V^x&Ko7Eu#7z% zg(>T_joIT-)1eAyfQrJJ#;TZyXQ)PRFb|*Li#Yg&P3%Pe1e=$TPa3Hs;R(#DdK5td z8&OQm`_Rah08n~kp5qCt9!V}z_#{Mlr_3lHRgq73A`A87#h9$n#`(J{G?6Qv5#%8} zA+U^?(To+vqN|x0oix-|vO{74DKHxbH;_>prBrnc(n}2{>6}hX4JIFjM@~H*sz?Y( zBrInLk$+$ZB@G5gc(`P&11P8ilDPkZ-Q&yT<0I7i9VJ;5&NRh#=`alof;9LE$a{nP z@T)Dr38I(|8H`ms0ACqYf#r-v)gMpr*BMb% zgT*4MG=}3WmYL&(N~Ksn>`G9@SUA$r9nDxc^3;wk9Z}s!!B~d?%^*zS5vuoqf>qrDj+ljF#R*67$z+{{G}wYt_=Pt(06~}qMVNz57zShb zj&_gDO~Xp?1lG3vK@hYB&X0P=j2oQy_7%iHT1F@dqKoSD929XDY1#F->~m zvdkgafUVokSX9ip8ZBg4Dxyl5<03HIhfS#1!nIM5MO+Ee)J;uX3HsQ^jT%!WQnqY{ zPDrv*cv{M+#sX=uQV50vK}?v1mzuI!W+Key*%UyS1SGhLE%*gNz=<@#zhHoZB?toY z5upse71Ytl+Zo9dU+CMN498gNoELZj9_R%AS%bo@*o%eS z{w<)5LJ8f=kS4(^y|odEepuTZnCp`sINzzF*3i zSpD7K0!HK6SzN|VH;24FBn z46dp}YhM0HUitVBK>-l%)zy9#;bavAo#+o>sD^!%h;@jFU#NyuP>4c!xc&2pNtjh2 zfPz&R$c2#4O3wce9?qe+poU!tPpS}N&@7R`I9mddSxi!^CZ-GP8WQoS3O~Uv%fXxl z%$(LRRD{)&h27#R>S8aZ-!R5z`=yM*HDkj)+&Bj3r2*go4(FkH<8l_4iOPjvs7or~ zD=P4-Uswf+nuBEkTtK70@P>pyhE(PYHgH=_FlLTXm9D8NUgaAa6;q<^y;c*jQ0${tjuLW@_$Y$N=MP&gM=a1~Tqu zZ${^;PMS4lW2+|rFdv0ut!|c>kvI{B%~#q7U#PRH>F2;G7vK%vwkD6a?vrxSnq}(D z+Z&I6HW!Eh72u7=LSTbcC{G{=$X5M@Sp|kw4(Yy7PbdI{S=a(y*-jbB&qHA+9a2|A zz?kfhZGAecoyHZ>8nRtTr)}eGAD>KOKncnQ@ zg4-mvjKQe?Cm!LXltl0YSMUW7D{26d3^SKT3B3t#2F#fQ%dl|SU`_wy2lw6Wymi=1 zxaQy{aWR${;x_L6MegWk@nym4tZs2Mf$kWelV1TxP`PgGMvn_(na*ma9X~<+OF<~8 zD<}|zQb6)&pow7^hF`!1VEBh-K!#jkL~I0JMo8d5_J&?~1!Qmvf50ASuWqa{=y!0}e@l8jQgY{b+*YP>Jplfrc4Q;TqCav77 zgVzQBNLOcrg6L$2KnMZ!25H;}nOKKr$XRDtkI}keo=TLI?kbkR|2;jC$qZ>Z&jQ zlS2n zQh2KEt&y$Jo|ca%F({s|+a25iUYXkVumJRLUkxf!;GSpAp9lKN|A9(C5z0V!qsL}; ze{iO6dgkO`tS5b`uXlSdec-tI)X$QJ`1UNawyu{cVg!2~7yI)d%<*_C_)A5rl6zA* zN#in{u_AuTocq54Jihr3hmkwMpCml^AQQSaxi&ht{f@?W{6QCV(P$;zmi(BZe9IUA zO2GV#T6E5LbfpLV&|l7{XZ`n&jj5-4_-~DTr++JPhy%%Z*-y1S0SHY%1`;g)Xz(CH zgqjv2Z z(msC=slf`R2NtY~75P!KY4oU3JTyKsZQ2yhLxBd_JiLhUD%OQsf$8Mu?T- zX!a~xvqIK-^0f9X+_-Y*(vAD$F5bL)e^lD%^=qdwJO&dkT(}e1eVaJRXzchgl8Egh-DXda#rdO-TLpl|$4-ViQn9=>&^`5ssvkQx!f{j85+z zMAbv)m8S_C+l8nJSJ|294_R%^!5Lhh%uyGNG0ugvrH$3`A8UI{^Ya? zWkniU5Nxh0of8kZ%QSb8}onPp0e;$K~D=OLTj zsfQhTZOVzBdhD^M;Z*CDUg_S6eO^)WJZKR5w&2WLLKlAERaZe zlo%Fj+7TQWS`=qOTsZ`)oL6a8P@NB%nC4h2o;6o9FUmM8T{PPNcXI~KN{8v zCt&%**pbB=YnhqJD!VMR%{uFBm0?Odt(MPPd##exYU>-e-Fo}&0kV1`tV3&-dM+Cj zVQ22S<}Jk40d@|BCsukoR16%T^rWAnFBNLi0TM#eQl$}6!w;mFiWHPa4??K09(ZiJ zDJW5K$Du{-x(TA45_R=gGhV3(Ym9BtDwnOes+?CP#H0zVuZIOIbx`0 zJ^Q?6wA%`8<tRiAp6Q+?PD}pw z_oq<-+Z3RH{;GWxP!QKd4K)o<%Fn|F;<3cU7IvB;saHY&6u8y}S=}*2QjG}AL&B0J z>srmw<;g>k)0*pusbH0-~%KKrtu$?wZ=ifBoe@8`ficfNr6iHD)#Vb_aHSOJZg@1qgVO5T2kW?WqaT{7lt>XG4r=q8h=d#x#8Bjhyh~0P}GFMlfu#5H{H2htqI|Gt}V^Z~WpJ z)v(1cs&NWZjKmh%GZ5RT`6hh$#rD~EX{yD`{{2*L+h^NDL z5wL&~F%^k)A}oKXh;k9ph%aU}!3r{xFFC>>=y{Z(JmKLGj_ldv4iPenU`zu$_IL&|x^jT!IinibSw}F?VUK^HqZ-3t z12QB5l2RaJB_dHoDpHY)nurl82at&&&Ims>x-X3jdn2V_u|GO81r*wm6UJ6qxK{d+ zJ$Rf-AXSweJGrGUi)B56D6fFwPQbQx! zrCHHXBe3)iJBQ+siDU>N8i^%B>>*6BRKpqmzz#Zs*-Pwr0~wzC$^puqoopgrI}vBq4VB15 z^Mr`y-g3`;lC@=NB1W%#_0J9lv~)R>C|u(zSLt~2p|G2)DD8SByz;d=VV$9{;&ssj zAcUQ+eBc2Pm^C0|2BZfOmO7~D4eYRErB?jMKCIY1WK?4w{y2b66r_h-%iehM#A5G;SR4qbSjS+CG<{42uv$~#(4y2E8 z^y*jZDOR#l*G6sVMCWLh)*r3)0B!Z)K>I4*@sc+*3Ds-t%1c7@I!C?kmCavaM8m0d z$FO$_QCA3O7RMTnBL1+4Gk)AUR+a4tpNtI(qKv6M>{8m#d2Hsf+5@UA-aEHjnsvlu#--tk0ERU-$ zkZ;wOmvO?Mi5ZqgzH7R-zPHIv=4)NqE3_x8PRh)|9hI|8n)s$tYU(U3ju9u2ROxWI zjI|*fw&&GiG(!>0^kqxYv5$ZMT=pN#bFe?q@rz!hQNpUI1~P*2i&PBa0IAi;Aj)T! zU@*GTiqOa?kcf;_JUSB95U`-jS0EDC#2@(^=SN=b5EVP+#hTEJjAxuj2wH`|K)CV8 zmJ8-sXBBH7JBCJrtn1D7#dF*JRbrCC39~5qX5rN`vXjlp^ICam%I;aSgM;N~Q#&nO zmeG8_{OT|lFiue!?tU|Z=HzCl7@qn_D}HfA=Xs;0&daPxy+Vy7iUbd-ScM{*D2iMN zIu$!zMJD`^3Pm5l5Wi5wAo?(fLFC~8mk35LP$7yYq9PKdm_@=7J_t@L6>kyan}tN} z+ZOw8Jf4wpdD6+;Si;)>Vuo|BavyRGhjgxU{J_x|b{*s)W3b5FMbJJtu?g=M+h$Cz zHqw)xyC_Hdg-U-`(`EPcq+gq&stjb;+G&-BWehXN+a9;&1BW0KBN?gq$Qyo9OlLd; zipW65GuBbkickX&zbJ%AqPg%~^nw)C82F$Wor+Sd!WOB(!vS(yXtdZO7lp!uD1N~R zfu~~A99JrK-ZA!xiQKoIGI?k`bO4pR+B)h9}U)E&oJHcL6i+bNe({84nCQ5oy_EXh4d8=o}`L# z6@;0E4M#ylF>K%Fz1RZ=K~s_6DonyE`~n~Z0YuQ5FL|0R%z`upLusLc;6;-y*upT} zLK7(hhUG$PC7?!RLiwb^peaHk0EIK;f+8@2-Wl2$YT5#dL?rZ95lx|sJ(qTbUa1fe zs$t+kphs5!Bv;3D;0Io!58w#w?Sn@61Vg2l$<8S+Cp#!)esLboE#)Jmn2Ri?6F5BU?N4f-s|ba zS?~kx*&ZmW4CnY73!WldDVYr3qDh`4nc!e8wiikk$4Vx_Dz>Ct<)SVQp;xWP=oy5| zafhn^r5Pp42fo0;0XT*K2xK`SB2z#G98p6k#Fj{~%~{;vDI5SwyaXyt8Xg>=A_z!H zd74?M!2$R|^Xx)R4MI6Gg5;e~fN16A@eL?+g+`eLQU(F{>4`-xS7T|79&JWLMq-F? z#|(U+>qX>4uwF%0r0aoJ5piO?m|#bGK+5%yxM5yV1f3{RfL_I%c!1m#%}rKcDrGfvDBz``{;7Pfp-4QjN<0 z1uT5fi{Pna>jz*X+b^T$wX-H5Md2js76?oo;2Y@bZAqc#f5}uGL~ASGQ|@A;o}OrX*G7e;SLPhO4-$hJn^8aEz-)IUu69%QGn8l)s z9Rym4q+&*;f<`);Dx>uRH4srwbfu64So1I%G7Lka378%3V-^Np`K-di{a<#DL{9bS ze`uu_902)AV~Tmrl9~n9z}RRID|s>^Mkr*JDl2z{V6@I$CD3fNdZ{M=3Q2w5+FQ90*S7CMVm^-(XFe}F0E$JsktJko~kR;!ce=e#k*QvyhathrWr?d%`rZzQ*j^I zmRf~~fo243XbeIxtSu@40}(kyo_PZi+C#gwoAU@sB;cbW&|fJ;lR7d&qHUudD1ss= zN+{&5;mxWZc#%hJ!7m7cN3ch4U55mo#+%F&h^$6Nbj3oVr_2sSvw9$obm?J=pv>WH z&N}O0>V)i(=?Qiunr2Y9vZ;~0>D1mX)0XSgatoZUr0wD^?X>IF3gLue2fPF%zB*Nf zEMwmwrP*c%+KL7uY!NBg!`oIwPB=(Z{g*w=LpCIWPefCJXl4HY;XyiX+*1Yxs5-+r zAVVp@LLv~JN2I|o#KANckco87la7WwVQ$Ns#(8#zvX-vvQDhqs=0i**w5D#(hTsU+ zoVDJbenQe*i2GH@ndWPREvN9r1yl41oH z?SKC62=B4DdhiFUkYIyG!4CBF20qhK$ z1}vyj7yjcvhyxeZ8@~-2`sUx_?&EPHTsnTCGt`oud4p%|gAYLwEg7N?r)&`c1Bfsd zX~3K!;<6X_vPEEIMld8u&45|x?Cbea8j~(!!k$00u^WTnMaEuEG-jF7aqbOE1$!$e zn7|;1^9K9zAL~X-uB15YPM;bwt;_)f`GQzfg&qNcVnNU&vv5&PG9~wkB?l*^W^!q$ zuUG(ccw`6Jz(T@A%pj~nE|_mHY^5HEZ-gOW`}xp3JkixSajBvMO9jIa@nVmC%~Y){ z{&sOy%&TV*kcJ?nV{t}B5@yz|2kENumeQIuPxG_?RsyxwoX^g2Sw$wySnyY5LOK`q z?UHjj+u|&uvr)IstT2#iy6Zc~^G1yac?4s6OyEP@GjQeR3ai-I{#J>uRt?uMY0!@+ z6ErpK!fF!XQt|{WMBX4Ar{9*3n_-+E1ceU)6WsNZsaAtLaF$T`LohtU)r7Q2YlUJj zq%JGAV{b)?v=emQN#=G2v6`9J-4Iu-+;@Aii%Mgq}b&O24Jf|62U`+5t>8Q=+zKUo$ zt;Z9Bg1H4jNYvIprv@a%n)LB-BAh}y^j4n##oYzz89MYrjM{>(rh*|v9xVjLKU|vJ z$>@ys5@A1lVN!bH6T!S;DLQt#&+^wcqv@&)8nuGC!o>fCOe5!+^#eXNO5_U$+@z`Wb zgpO;*W#c)jf*=)+uUn2(l%d$rl|d13`pmh6kd>geN*q;s{kMI^sC9q$~3=u&!(WZ06vA5U8fGY`U|9FSNH?T^uD|CVA9-}hWK6xe2WYcigS9z zzrALHdZ<5}jKe*+vr&b0-YyFPaFUww9zg^ zzT`)~{Z+~)Cy+fD*zYL1nEsBAX#PfYs6LaOnxu4EAU#^B^hBI{(F1y*hejVY_D`~h zc&_JWRAgs_pob%lNgq;7$HxJTJx)8Y*;_imt9|d#&>;CkCLp}sKmRQu~V!G;w(7OB*R`}P?;)@hCqw{PJJnd7NoUAz7=WpcWgZ(qNE0S6X5 zm~dgkhY=@MyqIxg$B!XLmOMFfks?VjXV$!#b7#+=L5CJCnsRB=jYp?et@?Cp*RNs6 zmhG3WFHdggH1mc371&C^C~poNN|bnU<30UZ9S91PM&}o^M&}1hPj&0pvFm{q5$nKx z{Jw`zUX|w0gLTF2B84Zr_5 z(Z(Bb%uz?cE?dpVAAt;V#~}#|(#X|_Oj5}unS8IAIda==p#T0VF1V47%hEWK{L=(J z=JX4KBMlFtu087%!fw0r7;1AoG9993ms3vJC6V?bfn=Y57P?Bl1*usg%t86{uO-0( zG>N#=6coq4S3%D%EJsW&aDJ&8+a*+{Ta zFr6EdOll%I;LLFk$S^u{X`%*}Q1l?BPEugmg}pqfq2|4U%Eb^vR3~DNxrzn_Wucl3 zOBAF58TARF0~IB1rhT>g>z@uo61B0YFeb6nN)#H^;}B=CQWJ&mI&sw%T`fqjWLa+6 z<(FZOdDdNrt=VSIWQOf#VT;Y#=bvHx=~)D`Oca=Esl9euhqrAmBRIkR=uC05QwTnw z&_xLUTz0E-my}(0p++2P3Q9|%dSQVCmQM%Dm%I%Pif*D}`~^kmY*QM{;Exbyv{6kC zJ;1mEA#Pi+Poqle(@_W7 zvYlDKId#-pKeFf7X|Elyp&zX_@ZpdyPHDW4vk54ty&Z@_aK|NA4{_J*G~IBoOXL)4 z?Aga2d+Iu%-aNCT=Aeb>qd|N)@_-{0OhPF>y7At278sjs@(sX}4(_|kyaW52ccNHY zNq_hO7(h*6EMo^aM&c?58H|PGad49yPAV6w-l4=)o=TM`R>h)%h)!j;^WX7xPp%!i3$ET}3V$x2Av2SE9$gnoQ8 z&Tkeam`34{S_M)F4T&=rs8}e0A!!_97U&WSMTA2TjNpfA7(C52(L@;Z1hd%J!52=F zl9jZi&sMiWP5$VTAK9djIvGl!B{D$@;RoHhgyki$f)B_|=@ikK1DR~dM;uf(ezG!9<6#obXHGkr?{lKCBZgXph zOFH6@_W|xBdvjwPiFO=00%es%QJ8R!6DkWur46G3$uT1G#|r6FBm{)XAw3i_Qff&i z@3hOZnrIbCijtuXb?8H7RKibA^fQ*EXlfvuQCto5BnmqkM+>yHfuh1)7+S~yVkyh& zs|30m`q-juQ+pIUqh2u!Q$wx)-q)~lhzSbl2QzKz{40ZB#u+4l%;9^;~JW-qap8o zY9anW8ze4^Ojw)(5!g{%PIsyX>!?8tL!BlKUb{v9UYr+*TIgLyyb1E zL;=g!5vJEOvor5|O~YLv1c#1^{9R$aZ~(``VnJj~&%16p%TvshYcEC9OV{*Dt${1R z*@48I>{MFp^pq4o%}#8G>e??BLv;M8+igLdk=!;!Qo_}XcP!XU-ih&Dr<=>A*X?JVQ(3;nRd25#^2<(9d;SOPTtoH^I z3CH>Y5|IE~*ud7{1551yv}7Vb1QMsTRVPideDK#2k>~bM*usC#@K6iIkEA|_TZsm- zx3H461HkVjl7=*jbNEhpA`I0C!E~mVQZc4f;?sYUP9drPJKeQr3_d|VwZlnORaPf* zWC~STl6#$Tjc+`nw$}9uPxo=maGc~*9jKP=>(NI~kl4oFZ<}UHQ?!wSq!hMOn-2h5 zni|hMo>ihs&-Cq^Cod6a#>2T`t3^R?I3nu~lfT?;TR2b!C_IdhLdH4qRO+wZe!SYh z0d6TjnhVrfAu-qmvp}!3;c5jr#@eT1>afhfC~(wz(R@-6V;JKu7%%zX0Uvn9cwFQr z1X|$*U-BZqbLGdmA!4f)gh&W+ruC}VPfkkaY$)3gcz{IFl{qI;M1qOB1QeYK40JuH zwmPgoCV&kgOLy(!9K}HT?K!-h5Yr9OQGX6i%=It-<|ITuSU2w7Ctcis_xm7d=Sx!* zLhvGPs9DYjj1PS5gJWEcCSjF6K_FiD!64sC1Tn@NcCdp>T%zxOPyGAgAAgZNx$v8m z8RF&NYl?Sd|NGXR|3+r3fPsT(0xd`^Av{ajT+R>tAQDJ{8rne|Ht3r^%Q`|~+knpX zOsl67A@*d+5X2!Z`~eO$EYOtBTb%B;#)S7kp|*VQBCL)~w27O%MI^G0{DKE4Fb(^@ z?l1x_Yo_lftnc|wEtql)pMdY}ppP(ckb?5gA1)#Nq%i&1&n||+{qiphwXoy}ul`!c zWkjyZwy?>9jqz$Iq_dY-VlQK04CAYM+SS324P~H8jsaxpb~TtBnFQ9 zhR`X#Z~6|7D+V6bIuJn=vTPLls4l2$ABs zxDRU>Ejo@t7JZEtpD+q>@gk+L3SR~P3yrZOJ#xH)Q5a9?R`Bm5;Y)W^t_%(3xC#;| zyayJb(O&v%d$@-57NlILfllJ(0e1lqe~6jxj1&s-hmKAoc<3J%5$Oo6A@0%lF7X}x z1romujhv_5o`VKs5US#byLzk@5y&fciy_piFFLK$s*8ZoQX!6EEe&Wbk72B&Yc1QL zVZ!$gxN-Io`vE+6+GGqF#2P9p)sNR1Z6LN_y}td5UtW2!bE337WX*CsME--O)0U z>R)(>DxF6vuX4n)Vjm|+B3+{Y-$)HCcB>)Ak}#G~;KYKtzCtNPWc%PmFCP*pa3`H` zup$MsJExE^@q!~Cb3DoOg%oo!zi>$$vpnw#?^cq_eBuB^s>NCo4)Fka=8zirgv_8P zJDR6F{9zx)=3VL}z`QYfS}%HX3KGOEJMchI^dkmI@UFF7c8(tn)g7B5<@5`Tmk2&d)oA zG$Z-WMcDI5ku-(Q6FpgnNY*n+Au0#`FKOa)J|lDbz$IMvi(WXBKZ6e0CgoE+OHO95 z!d44G&qR9Or9rV{9F>ayto{KVnNIgEG(sD4`kZF!BF2m+5k#X7E3f9o?59S-a^T*w zAHf0?{f#l8k8=D8Mt$IMpo@%hR4=82M}w;gJt842a!5UO2i^cYVFgM_wNy`MNtx7j zaHJSbHA;ztG952I=dFfr=v&|r%%TwzvVj_n=}baFAh?e~KE-ogv^ttK#GVx?$B0|I)mraVL!|Or zzvlqx=4A=xDS;tfO_UWmOD!v*4p?CpW?>afjfcR%+J(yUGG%Y>XArC0=zDA?Wp-$d6=<;Q;nEZmCdIc@bgl_HJ=y zUN-nZj7e?IOb?SsS=%FJ z-EB;)!a{M@HSsh*o;53YFLb5uDHYC;$Rb4*0v&=O7p~w60^t_|!5 z^9uiVe94zdx^Qo6CN@N_d;!;n7PiF*w-aqBTOMtWvQ!Q!mZsPyW5;DPHN=#*f`3=f z+1zD8(X?bqLBg)XO?_`3t->BrS00^bBJ`tl`xGOrGJ^A?4KRUCR@XT-?Nh4Z8P;JR zx*}@F)*Fza8iFAmDq#&)ArNvvA(;07R)G~hVhwEf00LnZdKP*UmD8xRh>bl4lJ0U1ho9ykFc9N~9u*oPHDhwI<~t`>+xgdnHyKx|?F zvxZ@C@Lv6)d-tM=^;J~;Rf~DKmr2NqhjB8p*q1|SN@Mj?tdxQdS4&zB54OWTp;3Q5 zc8$qJA^tPEzK4uOB6*l?wDxRd5xCDdS1{78H}vfQ5}9(IIgrVG?}c6_5cPIEX`NcZYd+790V2v6gsQA(VrG6|O-4 zmBWISn=yMehtlv(>vX~&-WD)$*;6l}NJod5ReGfzql$rgHdt`sx0-TI)Hj?YR{PVxK+c3WDJmg25Zup&+~=7>G9*IN>MkL3e*) z5}cNJf5CS}8I@;Y5(1%ze;1?87B?3LB;aQxW}=9Fv?2?mq=ht8+i#{hyR!-7d|z5v z7USc@(6dPg@?cdaY$)=I&EY%wt~+dIJ% z)=YcB8QdjYI<$}EFi5+>O^2YkihpEcz)>Q8s%c8-x1bcJaQ2k=USbWmN`QQ$f9|Lz`bU7^$H!x~Q^?LkwY3=T z858Ik2^e_{w0o@|`MVFm5q_Z);M*I#oP`4+unA6dVAmT|VHN^G?Ec#SB_f)?J43gQwRfV+X>gF~VYww8u}0ctJT8Q}XDoS_srAEf+R@7 zVNv4CI-GGC?W91WjOeU?8+XhuGbE~Jn^n(pm+1}+K?ILmBr*d3Br1Z#-iC9Q#S?&! zH)wH!{$eJwcesE9v1Xmt2ME=yrY?@5*VCHHs~i*9TDo-1cLRIA{b-X*_^w}Jh7X_> z%6lDF*n|(@3jW#$rWTVAo4-Bek6fI{z2xa_pzIt9O(WeglFwD9ZtMN)RXWh) zJ;I%W-of5ybOP(P>OFgBrypH^OAOaNHX*RWA7;w5xDR=b`pq_-(>c%!fB*{S>i{Ey zk1d{?xSCQ$M>jACO6I^9&P8ZGo}-*1)-#nTsvhJ)VlEH$V|l#|ascLm-JbDT2Omhk zCpr*{HxNW(5?Xj4)fRBEy&6&wl#v7T(96lU%~=slR1pf>PVY#%sv!eY#m1%_)57BlycaJTtfX zez)yx&jw*|%(1_cJMj(2DxTzI9v>LU-|PUwA3uJYfEYZ8FrmVQ3>!LJcp#!gO%x?s zjOdVJ!G}P6c=T~GVw+0G`0e9&z~8@r{4il^lOraQm^o(ByqN=2C4mEbR;uLV%A{Yv zR;>w{BT%p_JMDQ377Up!iIu!L`xUHOr%Dmmtok);(#Nr6%bGol_T!9@Y}0Z4W=b{P>ATo!S-2%R)B% z`7K}G6EMJN;!jG=%ppXAbNIs3cMkI7Ni+QLbXRm1UWj2r6KV1mM-(|UgIN-l_0usD zndIL;F5$!?i!PlsP-FZ2G}%x7?1Q5}G#*gNKR529BUdA)MP!jge#TH-8X=^Ka~Y-R zV_(QwlvtHk8ukWbj`@=bWK(_#W|(4*NoJYY31^&g&Y4?qYTk)w zo_b35Uvt1fhv9VBS$9Ar)Uec@dFVM9o<%*C7ZN1dq-UOdf6a&Ke2JU_%Pz3M6_7#OjR(Kr%!0ttD5k=kzS!wkP}W}%W4L06ZrsFv!Olww}VZk3l9vn7{%&P#8- z_TGzczWVNaQJZxB3vj>!$7v_O1|N(tWy}Q#D28GTik)`cL3+TV12r0vgA`u`3wh=p zFkfJqj;seHol*k~C<3w+V`I(0ItPOPLc}U7qRn`+;6>sA=8w!Y_vGuXLJw`wk`^}U zpIvN(bY!+?5gQ|r0_h}^vNyd5V~o%OR*6Yla%E%IKygbpTHYd**{$PhL=aud`53P; zZj%Rbv)#`;F5F3i<#(JO^-o>tN zd=Vtnz@mpl@Zph3Dyi6_2wRGzq6mD0*m8R7?I{9#Dw%|`i#XzxQ%yC_RD;exzT6yh zg2o>|vr7Ll*qmj@(_COgay3kJ^%wRU^g>AY#L_W8wP8`P!j1(#vja)(&oRf^WVKGC zHnz22UFQftkLC|FcG>#RfW)rF*U8RyCIl(?cqe0;a}X^25{egI1U{+wh3SIv3r6_C zB7VRjBM`wJMFe9NsaQoYS{I2@L?su_2!=D};g5AR5gASVMHi5VMdQsuLjM6!Puj9G zwjd9B;n|3|#$~-U;zc4X8PMYxqL=2dWRCpso{*YGq>+@QSyEFUOlo4aoL~Y*U&EIC zOoF~j=&@xw(jVE@(xLwaMvVs{U;zzyKm;bRZg^v013d`JP>OPtq~sgnG>FPn4y=@{ zY^6n(R;%eq&N`GsA;{$aLygS2%42N_oyk6C5%@477^T328v2k5Wb7~^en@687{Q)q zrXmuOvPCuifetF#!yopj#xK0lj8x3R4GE&cDprAmEFzDKrRw6s!WbA|WU(130h&V2 z_(ogtXP@{KkUs~Mp{21=mmt&#pxEFb?lj9MiY(Ij&ay~nHD)D#3}j5)*DUxMvMoRH znnt_E$ox6dY)Fu#L=*xTN&*2@{=uY6)uqWzvTK2k`J^jviqo9xbf=!Npela~RNe4& zs1c0i9YPne6DA5%1bqkr$*aD#~ zDg^@4F6q*^%}q@*ohePZFM6nvdxFYhp zu!>0>FJ=*9P+xQV*TCwPux(?=VH@Pw2=6j`y!s+r9@M9#J!n)6Z9`^RD$*^bT}RrCV|&f5IAOYz?m;}Y>dSydNFTkbfbUkj{^~U(lXQQ zfF&f5h)^#fb&;^AzeC}0fhV$1a%W{5OGlBC<)Nz{pNpd=wPPuZwBL!}MOd8LTDSJK zl5vO#DY-oz@0iDX`mwv<#Xu-4d)drxHfoT|| zP!nYTZi!DsOqLB~;LsWC=#DqrDvDruqcK;pg&*`Vh&taP2*ub(HIM-oauWCwP_f}) z9b*gy8c?v7Zg}!cm8*wr@6!}rfFL9e(h}NY6tPr?`VGjv<6LHY6H9^)8PAz9F^N<0CQu zpNtw)(H7CV#VfbpcP887ZSh*>z-}3`Zw`C8)obU6f%MOnj{Dr}o~K1Wy6a}J81)zKX9Ai$tflDA7NVG(~7VVK7j4h3>) zArTRE5)<_gp*LFh!%!S0VKDb`pg~Ef(ip~I5m~YruLpYulyiAPdy4T}dLw)-=z=fE zLB02TGq@WtXoJ0`5Ytg*Q0E?8$9yd0e3l{+kl);K!5P$1834cZh=_CX=UNmym*l0crWCe^|s| zkXJO9@f-$~MvaGI+_M}y<0_fAfZ^kSALbW})GW&ZS}rn34ze{L(Q>Y$f!(rt;G#xI z(-^zu7a~Z4uy=xb@`i9|K(}{;rD%$$ST8b2gTCivsECRQp@ZJR63*94KNucCm?>Ts z7@ngNF;X7ZQACVT9j_A%?Y1Rub|dUn4fAj_&wvd6z=dO&An)f0LU2z0Wlq5$HT4&Y zqL>n?a(Hw2aM5FjMZ+PIQ6X|MG#+7rj>R02#S*3G7n@~>@EHD>| zj;LytXo=S2f&Ku3mLY=gf^+)Pjh$3er09wfDUlO7C91fJOV)}M34;d_i^@TZwb*t4 zaEr-DGSsAeTUUJ&#Y=k{Hr;&Tfmwh=n7in~Ud4oU@1cpMESN42W zB_EJbAp8J2-4=ZzQz)Szi|O%;O$af5PzuiQ4AtNbh|(sg(XOr+d=;ww?=`P<0j^b!MnAQ^l6&bS?M-Ot2Y{6+p;}B-ijt+u(_xK2O=5JhMrgK*p4~IgZXz8B6ncwAB!C5f=+_mByKs1L0vGfqFh+oT^3{j#L?)S1dWA zK9z8mjaX|U^^X(cp`8Jj;(?)qaT=G9B?ZDJqWbm0mPnvtPBy(;>2wq+%QP_u|lY<_zvSAMTHX`{d4hKC+nV~baq2gGFmN8pEBcjofhk(+6 zkl0i(Miy-VVaJdbohO}ZyDAo>CexpPF<*7#X=p4X40VQYAwc0j5cVeIzs}3Q8!oWO)&`9FkU{^kk5N_okZ^ zhfQf|{D-E&IT^FXn--xqKcQkI(wKF$q9oEi%t|CAF^Q6KsFs0Mw4)7rvn1Xc->JN|EgM|VK zS9d5ZlPJ|OOJhn)+LofO5=R9htXMREZTPFk7OZk=rrX(@DD`W#vKDRNJ?ZlknxIH+ zfU@8N5)m`#tkMmeInIU4RCxPAit7$fFC=6Rd+U98jvQOM`Ac%)) z26?ec8!vK*c!jpHL2Er0(Id*iJxOz`191$03%GW~tlz_&eu@^~!+?KLv(TxQxQ0GD z;u6PM5#oAk!ZT`wBA}J99 zF-NeFby78;K6;sCOQwDM9Vo*e2*HMhhj?x3t8WXpTOzk?x+Oo_u|vaAmZwmjmN6np zy(qyCo!7GLn7tvVxQiPY)k>Wt*An}H3H&HPKWnEnW<5iDmw|Dq!?CWPi?K_~y7g%~eM*w1=2Rx<;+$iJ$3sGksVz2}bJhb5$ z5y-Pe--xai+>miPypAC~n`UFTauzEF!T?xDFPgoCN;WjREpFjR+X}~CWW&l@JrUc! zm%+oG>%)_gXeelGN}6m+%*c&w#7B(8j=XFE`noAB@ro8MM| z!%Q@Q{LG$_%&4)S}S zi=bkl5STd12Oz;>EYCMh&ls$Di?@y|d~0vqSb_)`9$`Nag~Bn$G%=uT6 z3Y#5}fCn!90BAs$zsXy?&Jvp-H2u!J$`>~+*n^SN6-q|3iMlm=KNh+ynAWS!+Gdi!(bn3e#IIon zAFvQZF>=xviK9N zJ^-jE(vR0I(6(IJOdT1RU3mcVArDd2#{t@Ikr<;rf}VIU^P4xZE#LE9k$_3xpp=-m z)E<>`3K9y}T9(qgU0twX*9WZ5>zoo1OtBMOyvFU|$Zctdjo1yr%UlE0D#omm0jQ_f zS%Bpq8G~6P<=rCg8A_tr8fO;`;n`o3-c(X0qg{e+m@lXu#P@CEH*OlQ{ZlwjL0)zW zwCx_$;5lanAbq>Qv^v*Q|K;0b3ezzy+zl7T7VF?sem9s@&wJ&{OIa6ZYuX z5BRVP^Nw*D9wDyFyG9yI^PA(H;tp)g7p>JUekGCN)jM{OGd_4?&EtLU=b7=*sr2U% zgf1_{uMVp`jb*?p4LVpX#Rm=-5jfoH)VAPB<(Dps3&*B_&C>}{;gm7UEfy_=dx&Fx z(iRatXkOW0Ng59PV5QbYP`Tn}!ovv!7^NNKR*lHOdY&3R=)eB!I(|544eSW>ZM18B zviru1&gfcq*XYc!kX}itlHA3O>DNx!R<68Reh`ZrmX{IgLOtq^z2O)(-d=?25n)H% z{oUX_kTLyWmG@vD|G4X$)E3Pg<1b|}y`{)CRqX!`@F5ZCg+uHCuP>CPV-a@bV~XUH z)7wkVC?HLc@>LlTsP~qQR89fr+;BIRoVaexy$p@(JM_te+1*AvQ zBq%PIp!j1Uap(E|)%z|}wl~cN@AHE$>~vD_KW{H@UF5rzySgaFk>JUWKF&=})xlfO z6&u(Ye;AI2^;y3I82_sqPq8#Z6-2$KAWzw1UmVOT?gvormWA@UEfLMRYiDC)?~Wl9 z;Z8XZ%{wO%H;?m~$gT>M(L^u!e;)L2GWdLhfUpj3Wji66Oty6m?V2nGL7+V`GU=_{ zs}gbPkM=Ie|Ay;v(}qTByk2k5j$%k{tis4)trxNO2;cU6+&oGx_Y6Vz8KMaXmM*%E z-ft)ob=mirr2F);^L&2z#XsML-y6n{FdK*Bj&B_&G)GR)+XYT2)J3+^ZV&}o&&1mn zZ!36@W(?u~`@@!KTwlhTo<%tD13yp+`;a*u*MNp<_GfQLV(u!h-?s`l_C#XPxB?Id z1P&xvkRT9*2^B76$OhOyh{oPry5!HIMPru?Zsgd}<41x!M2;j`(&Wh<8z)jUcG2Za zm=-mHq*>GE&5tN`Qhb>y6HcH(g$^ZJ)aX&9NtG^T+SKV&s8OX(rCQbMRe?o{B;nfC z>sPR0|G8o%Th{DZv}r$<2jdUVZ(g7VcpubYo9SMX1oO2Hp+@H zJzd7}!}sq>``q$7R!N`_CB1HsO&?x8?)B@{`L!Xq-1~R%$Y(evukdDh z^anEpTATTXvM=AbFnRd4xmg%%RHHl&Y}2qz7z(tis!n7_6-|MfJ* zy7oE%OjaR6bz(eJB@Y-FVa06LqfojvreRp~b!3ux1y$CzEI0>-JHk+t0^;-BtYD9&&N@^%h(PDEkw&+z@X}nV@kw!D-S$|R!xn#l%FY@Fh zDRTFPPFj9BX5ZTAq@YS_p7v&tbe@Xm;d~ww=*opg6C|V;5~%c~=LG6Kmzd^n<)y0T zcTjuJw*7Y8bJzV~NhjR>_uDz7D-RX(diZUK{8RnRsr5R_AyvzA=sM@%;XV2Z{$2cEU0$QRI z4^U8dz;i{UDC@e=d}1fNeGLjGnQ#N}EOAA?5!+Wb_`!cgA`c@ZpMuRNDeNTrw+!f-6RU4h8Pklq=0sAcCzQ;jMe#g7g{phz5 z%|(TC3F}{VisPNiS?*g$IUt;r1`*fcWL;sTP<@y}5i(+GKCH`C)1pp-Uqp631>J>q*fG_GrFftF>RcpqW_N3h5!x_IiW+-44TqKhCC!9jXcU27iGpX zrcsTzsU04Tc}!#`(_avBfij)xAU=)|7JNzJa0oJ&QWdf><#~}sVk9H#3G*W#yNIqR zc}{c^$&xO~$PUoANq7#i6P#$@C*wz@QE~}?(juTz+Ca@sjS6V|4B-E;s6|sc1%bN! z$KRa7#=R*Dm`XvT!H8)mpFC5e8|7$6J^E4G@exGTGLKbzWqi@#JX{>3KwZGAlS$B4tMic+~F{MU^QG{~CC*xSXf@z?M@v;1~ZP z&ISIdQ6p(eMGLmZ34&CtVQPYgjw&kMhKnHg4(mp9ST zOu2Vczy?-)G3i84<2lcICXre0t4>j&h*Zeh>?TWvSR111R9ePT6I4AQL#;OzUowiT z!Q5*EndGO8qE)r4Wo>I+``QCY6QF=xD4bp{94rG)Bx5r! zQSNemTF?K*Pn2$%?#-C#BT?MPWe%3xREoaCUeC3)J;lW#$!5TP$ z+~it#eLv-kaNsAU4Y#Gkrv$NeX(B-F0PtIvo$88NZ0Dt*E`bd--;J*_5v@9^#)29& zu|8rahi(lKT4#r#0H0ZV7q8iMA$f10s_mQ636Y~(1y})$ktgPzh(nLAR}JBG`uFI+jGr}opG|r7*d1&y0Pn2 zK8}yCdc)jFSWo_TxW`@YA7pvmmCWQO|Fa5)GW;}1Zmw>g2fllz272Kgoa&*wgcybG z>Cs`0=EmBO%}tj)Q6lS+@Q#-akP(%5HBt4gBkjdGG5b}-K6drKt7&R)U8dlR+WF31 z_Oqvb?ek@K+~+|IIcV|=6^R)FC)*%@*SX-0PcokyUil7=@Pvs@@57RrnrHq&bR$ps zEfyu}G&%SIFt*Chrx^4GK^;T?A$)^K94qTW|DlY<5nQR=;|=r}qiuhG{O4c)(9HeH zcb^0C2$zL`42Ov!a~r2nE574fKwlxe<$FK~J1*HMI(d>lHA^~KJ2C9LuAqRdo7lXz z2rqy5nYQpe(BnGK5{lBZ3iJ}R|2!dxn`6C;m_H0@yF%GN9Lzx-+`*~nzi&eV0Q?RC z1cGkzhr6O4uPX@RV?ZV>85nRt2wXnnN<0c^RdhiTH{=9?U~M+(SM*fO7CbK3W2yVG{yul^BY$ z_FKXxTtp{~LPzYf=8K8N<0LGkzAaRT!cG793e3PLeXghyP6RKBO^s*L}MfwD11aIl&}fB zLYKHe;Lx|W=&lXKoXjDh|1b=SG3+0RAP6xrK_ZNcL|cj#RK-9GlvdOTSd_niITriN zMR<%yd4#k-^uhllp#4cCVXP4ZEDgXrMu0>{WqiabBrGd*wdsSrQOZQ>GODA>Mxoe7 z&+$fX1f!@(MbM%+`dgXySjX`>MN7erYMV!rEJ>5BFCX+p(SbAK7=s_c0UQtlL{t}- z$hm;L$-+s-fmA-BgNaETvuDi0OEjo|I}XiZx}#bOHrSMGp-65_!luB;sE9T<#EMqz z8==lOv`DKg$EjqX1-VL(aSuY-N@?>Klb8st43M(SOwHWP zH?q543__t{$zyQI$RUP{;Dn9&s58yuY+Ht02IC08q~<&Ztz(r$CmB@X8nTJLhcBu6a;_ zpw0?iQYLLu3%N85?amD)&Fb3+FoQmL8iQq6O)Mh{6P2X7MA5>t%hRMyPUs{xQpJTR$@g865`I4Y*7xaK1sER56#kM#kn<* z0T{R`|FhWCM)Xt&R8g0ZPg327N_f#rbkj|Itb#j$gt&^N0Y7a)Blb#=K8+m%#np?m z2}3g*lBk+CDpr2&SAX@05sFfwQA_)@Qh#{XN{!ZJnAR<;R!Kq-Y~__s)z)_-Q;XQC zZ#C5|6bLQCiGCsv&RSQ`X{3ta(W;2osey?g&6ixIiH-Z3d<7f|`d6B**fof zjGSnt)FHA|i&)s7bJ*^&kcbVEC!|;i+=TFaiTErce*m*m?SyeH4v!U`(-D_EGZ%Ih z$2uvnS#37t+*5i@388pdnEj7&l&?ayS+{-Lu~Y}7`ll)7S@Db~pp{nTBifN+6l|SX z|E1-!f?Uyzt(*+BiGoYlE)t41v8tsxG_XBTT74+8E!&~E*R%PL_>eES?Oe|#OLJ({ z?>q+a#L}NtScY9bz9o`*F;Tz`+%2=%eK=F;o7(%l#_U5^TmspT5Et_UR2++3$rall zomYHm*+YBRv;~y5{aojLUK~u;x(y{~HQn{8$<&R))$JGcd|lXOK4w%rge=v4Al=5| z&00E|-5r;K5SR5pm(>y8;XR3|G~VN_*W}fR1kGFsY8B}HUjWv@Zy{J%i`32VS*VR# zy`@VSIGFS-0`L9a!KJX;1y@=7pMKj<@K}?LSYHoLoyR>}V=>mY@Mwc;;4m0PE`;TQy!8i8&{iMj z-iQri2@chz) zVCD39;`*)SlO<%LpvrbcvKbZ6=R2%t&vh3frLEbCkvXeHRE~P?-9c+#m>_0A_jKXpTN6 zAE4W|aLG)@XDrp{1@=^e`Qd-wm4Jp_Q-+CzsSbb8I)^)GgfKrSMv9VEHgNte_8aFs zF*J(4)qdfLfI~W+;;2&pwL+8TVNZ=?m0oFyCFLlzSZfXwR@n=MD+-(L zx?|&voGuVqK3n@eUU;pyT0qQaSMB1hJhf4|I@uxen!!h_7|+q zR;`voB1V~nu}y~KB0o;(iJOgG-ALl4s7s2@JbCMwIO|7w4~!NPybf*AJ{aOK;8uB7 zOGPfKMrj8wY$t4Kmv+yKKpBe=7Pp}3^Y~!T;_Nd@9JC8t`VFRszLco>8_8T~3jvV1 z2JO*qZs*37F_0hBmQ>XaZ1x=N)^_cYfo*|y3EGB;77an8*xmP4paDT=mBm~INoz6s zY2tR5we?8kPVVdx2)a({=gx2azL0Yu-Bw{ddID^vwd$_XZh<^(2((!6u5H_9xbb7$ zssdyJLGSUQ4c?v#_U2+*Mm=Nc<;(QQ3x5<__1}zU?)^S-{}fk{52YtzS#8!n8w1~N z1YbTA(1Dy<@DX$y+&1W}l)pj@Ziiz7RX{<@?6(6rXY` z$BOaPVeAcD?1u3emssvb=^+`c*(Q+)lp&%y{Gbf71mGCv^5A@!1 z8Eo=e>FJwT#VO8{TLFo!4Dm~O@)9@kL0@%N7mA@Xbc!W#3sUqV`SO8W-NO;{9M2B% z&Sq}fZPFv>u#-%#TyIZ5@(oY&dg+smU~;p8r~`;{|0!>EYOi*Ku!v27U0Kf{S_f!G ze{{mpbupQAoQM-k4|X;mc4B`CQ~&14on^RwZ`(Z=k!Ctnj*1we&=`V7E?su zpl+9Dt;Y3|5qC*%Y#uK~xZrH$jfz)XcMoTfIoIWQx0=ro4UN!jK0li~+?9S0`9X)> zfPbTbALZ{Y0v@uYac8(4Z(kPy_Mv$Ar-*oGcfVr?2~a;6lW0zsh(+7c_k9<6qCfFN zcczmE5?gO{aGxYGZ~2#Zo^w~jA9o6yhedqH@SL~!8O(Z$zqoio8L!WGT#@!5DSEVT zZaC(sq}PF^e=wD=si&88nua;mA;+q33XY$R|3|6#C`NJz{c)aXiLnoqJ5<24PkY5@ z>KE^*wzqXh7p%d8di7n1G@tmSC<&|J_`lidzTf)4A8xIwdbIU;nD}LoUwqY%XTdJ3 zljrWZSFp(^lh4!LO`CeAXlSQ+>-O+`K7IF~*!isy{FT+6kLQ)uPyR`M&65A9*LTFo zAGO)f4o#>VQ)K8NEeeV*tiFV%?p-+9~Pk#X3$!#~Q=T}{xi;co$ zIEA?UL0-;JS6TGye(&#jfH)v@XYC(oWfe*z6EbSTlHMvo#*YETB# zrcR$iRVsCAM3+{tV$G^`E7z`BVL*lI!YkRbE;IT2r*#=3Uz;?1k^ zVZw!TCwBZxm8RakG5ezQCwMSY!zMjGtjicF;*=`2PR^`(Gw05pKZ6b}dNk?Mrk93I z-L%N*)+NotjxC!k46tE~%+9?PEy1|J;u?F?xG?eJjtTZ%OcAo{$c1H|Osu^5%;N;# zbQE6jE_Irhj3xGW8FTmY=Fg)~uYNuI_U@IcPR;r~dfoQ#o3-r}H~#)CGi7o>Tmw!= zlyL{<#gTR+F_#{3hgGIfgY zC!?J5P*3Hm@=y!I9P?ETe{A5eR7uQUvLabrC4%)j^f^y{ zw|naKT-sCY3b`T{W zJdFrBqP^|qMRx;KVTTOZz!^d@ic(xu>8AL=UghM5vB@E5FnAL>?I?&I^BQS(mc3Aw zNO}vY2oR5`|3VFlhlN(0BOUA5qLtY3ijwMy7R|!N&-5@zVjQHyN>jwgs0oDb!A{6J zc#yRz(nR2MqE+%}$xC7~lO&2%Q2I!gKLT=xI{_mhFLk}yEr*0AVk8_rCXgj!iFdKl zBrR)c%UhOaOi}YBS3v2RK;ndyrSwN6%Xr9w^bAR?3}PG6wWUeU5|`4PCN-<6H~%Pw zm%DLe2u1nDVS22XM8sZ1l6j?N4pMi1dYf#l>CSh;GoH!2kGQmn6<_|+izHEFDbqGF za`FX^>eLWA*EUcMflpA;lqW+Q>QHIwCNuWDCpSamyqWM*jQ)I&8Oy0kLZP#bDI`<@ zXYcxheAaI6i}a7)USdytaBSwE|aQ*r81_e?-Hgn+eM;| z@};UeEfq}kX&zacRIGa4D_>8BG}D;%ta8P-16pF6-LY!nROVEKgDaWZJ=a_Bm17 zC|{T*)nl4dQTjqHL`b`;$VN1_%3UsV$yZy>_9(X&q-sx7i6Y?MR!bTqZjz>o9=x`; z|GDBFFL~+q-0VhIy4+0;gM9m2R3Z{~kJ>Kl+yt_pDm1+1-7kOpOE8z(7LA=z??JFL zC->U4h+AbyWA`;&=xJ?43sy+0?Bm}HV>rXQ0x)zR=Gh<}>AJ?Ht|=Ae5r~OXJ>b=^ zhFk377jJ2z0WNV&)#?+so(QhUL2s7og&+Y&6-vmpFpP_A}Ac`bH+nsD#U^!+If-oav?61T^RWW;yj6M`x^3=zij6_ z;xN|t7#Ut2fY*1{HmOWA2adnDhRtFYKP6sx`w)MiYNX$zGpZ%-@|W|M;_*tW z;JoRb#B@AWA6NISFEn#5MJXiww%o8=4)dcUJ+__%+{im?bLfDR;0cEB|AgcHJwlq8 z{C?RvMkOQcm?H$T5HcRjO-(OOTkxzT>m*e?Q(`T*X zZV&CF{^sJ#J2CWz5%8;TeJKhb^|E{H>N{xr<#%Ui7Q;M2(bjs5Gg@T2ygvKepTO+r z9q=+WqWA6R`Ytvp*JKM*^B2-_hxl8IoLY>yUjZ7R@!Zhx$)AlK|A5(r$M=z+|C~zf z-Jf~%-?Rka{6HURgkHTJ;0J=B-6Wv)EudOCUMZn5Ci4P52GAmMPI1$N-pnia?ul?A<_k7Y8mO6PDo~ z@?oq*p%o&F8WIE>B2&7F7`?=ysjXSYk=@|z&fD-F0rue}QX-=KArHESbp3^qaD*Wq zViG0diEN>)ao45oPD!0fC92{oX2~VWR~mX&(BunX$X>HN{|6u@${ZFKkhBTm6`hT+ zVlWD$i6{>mwnlELk;xfR1wKxOtX-nu7!o#Fdkmlr4&yaqV|x@ME@oa~HK4R82emIi}H>dE8TqcLU57kQ#B;zbr}Va;U9^BrM%#9kP-lR;|aM(Ua0%wspnR7HwSLpr2gs98Rq z;#?%$0R%@9`eGAJ3P;N1OlFfuCZt8p9~ahy8(!h4JtLwR*v24;KMAEsHe4RQ2u&*G zQUV3(d?Zflm{H=RV?890wOgY6T2azVK^Q~Nt)s|9|00<%p2tJ#%l#lqIaXQW zXeC=dB0I+9Us~p6LWE5sA4p22PC^}GCZl$dOp+fRaa;34r}^KjUs6<-e`S}la7+8zzvd#793qp4uv9=kX|K`rbpGq(YPe( zmsX<8;AoD@AQ-hMr09X^oj#$MGO0p(p#z?22Q@?r z^4bopVFMB&mWJqBLRf~9qM~viVQMLK45u~XX{Fwvo-U}Z9mpFz)t{p2m7r*rT%eFD z5?r;8oWK{O`cQ#-sinGV2*%8q24XK#|Bk1+lBlRCh>U8j3XQ7ROCVX0g@A-)0BfXf z+@wDpPCgEdQ$E}UZfF=c<*3hz=E3?9k ztY)GKSp*Oo3Za_Bn{mmm8k96Ts-qglx2h`c?Q5}YXse!U!1~_8@R`*i5wyZvrY=gJ z7|I3ypG1V@LgK5F3Pp@2jKE^-=n<^C+NZS%U7{k2GHwh|2F6n<2e`^lnYE`>1Z16h zV8+61*C|ZFTIm!T$KZvL!9t?|u_whUllisLVxTOss4Oq~EKyt}1jX#qCf&?(ET0Z# z_xNAU0^NGz<w!$iEbds~Qe$5vuGos=B6@9xl&*A{hTcwY<+5(EU9Q@a+2BrSsXd10QsWvS zgt)#dp;no*b?t|VF3U>p>b7q2N?N%9F3|F9M`!L02-6Oe%dYXkyIZ~`x|MmX>TYk`Gm!2`DjxyH=> zf-sVii~e%dkM)Ist{(Ji$%5tX0B1=P*a0#iLom$3EJ%VDB#9*a!YpKP1OLJf)9?cJg*B|2^q}7 z5|=_Lq{1&qLK9#b87pxQH-Qo(upLM+6J&%I)G!^B@hmWLT{M9XLopl2-SASe6&o^! z16F|HV&h!G$$88m?r7y%&6aDZTh6R!di_plbIaS@N&KU{(ilYtc& z@eACvJK=d>kbt!U6m_kOTY({*1(bW!V_ zO&noh{IZI*Qe*~idCW01OM*bGwNwW~DLBLiTk;JYz$T1!HHdXEAVXODgFV>7D1S6O zOS2=GbYOGF6w6FqleSphHSCh!!JC8Jw!H2%)>7P z!!q~r4s7#Hn=_1h^IVs9a^D@VNVNNUQBp6gD*-lWy9P?r@egD7EMWI4By&G&j6cl7 zSKEU({6aOL#6QUJCOkEEvo~==Zr&m*hbs4cKNNH0HJf1&r@n2N&`I_dw|e|>PY(o2 z-*8tO|F}wb^#Krc6NJodKf^qD12Q7X&CL^Ap#zLa;+*|HD2wLrg2gc;j|Yk#Q8u zIHpmzXNdM_llYUrlZh+riIN>+08yF(@YT3DX&3=Yf3h*_uq0SPk`n|;8+Hxbf;Y(Y zSFeLYM7T4k`83QhI@kk42nR|>HTGU9tFjN2`#CjHN^|e0H*wtk=x3~ODTeZLb2u!hMotAI;WY+oG>_fQw1BL&PDT~C1gGOAt>>f#byW0`9pSaCR=P7r_d0vYil(Dk2zcRFlb9~G%kjKY6$w6mC1W>!) zYL6B5$#)06dR}7@DN`#&#%sLHBfa|2{FIa9U2rPSCoD>6`)VGM&zA?#57UzY|5|Go zeJibdWhQ;tJJ*>Y{2S&bMC3fMQG6_!lhvaK)?X-LNT%B(1(ymWw2OV-3s0n!J*b9! z+!jRIKhoL+FBt_u+#+wvSx=n&M}u`wgxB@7GQ1GrghZ zMG6X$t>C+of4;6JKFG!d1Eza?doS=)ztUKZ>qBi_C?nw0`_#u0Alg3jSBBU@f4Yab zsaJpcyUg_uzlh#Ewr&0+S9|z}$Vrg=Nc5w0IHY#Z3M|Vn~rANh;iN66Hyd3H=H5Xw2Wrk~3-6w3+adM~^ZG zru2#OW>BFuFBKK~6KT?)LzxzQlT)X^OqnuPwR#n6)}~vzcJ=xdY*?{l$(A*H7HwL! zYuUDS`xb6oxel||)fn~T+_Xt~9^5G~XJ5U8aYEH8SZPYaY6IU){5a`igNAidwR;(} zUCEm{clP`lbZF6|NtZT#8g=ReneA@GD_FJ2q;C{C>rKw|*UacJ13wKey^SDsk=tlN$5O(Y#{7|1rmdrQFdNY{=~! z4kvjWzxvPbJ6iVsUo-jy9FV{Q4LlIR1QlFxH308=?LfW?@`$#cP8vuz24~_gFN2I@ zFhhv)8}Y*AILyQi2UWaE!xmk95ylv0oRP)^SF8xU!y^2NC)*BE&%PQRQZ77%=36jG zhe%vj^{MlS5M{O$^CJ;iMG5|I%DtE>k;2{T0|?g&mgI z>qv!=Q2jZ9{TJYX1qSyiT3KQB?bgWVEvmwYD3ec4T`%P~ z%7HcBnB$H;rm^5s(WDY3dbNyoWN8be7AJHW0`4?@G0ynonr*%r=bTjw8CfoYQaDeP z5mk9WS4VDD@o@V4$_U5Mn;xwJl|sr|tTnSPz!1#MGSJ z_vz=XejDz%<(}IhtdrJr2as%CIJ~2Y7LaAL4=oN~|6O5s2gwK!Jn!+>3s< zzynmUd=k*z29V$hI9vh_ih#o$pa2E)eGh}m|AUdxJSevDcy5HT6Oj_pmKOaKMK6AlD=}mkjBrDO4IDs+=iA-+1hRo3Xu=SfsKfy0plboSxHMKL7|{WcW1*#OPHpas*w6xr9nT>$icN7OA&2>uE21cplDySVyQZkk4On?3pppJuP|2q#L^;{hI;hlobB6L6@+AP%62QSjpcQ4xqaBcm9xF|wqSBj!3|V^W;}Q=~z` zsx8yGmSbiSrdFxxTG`rGfZa5j0{R_K5!%y`03n=4t>`OO5sYA@q7-nTXeZ`y4UX8u z8^3r4ItButP2}Pil4t@gPojlY%wiU+Aj4!)(gZuq;uo2O!{~>$uhdLYvuH96%B%vFtBaAqh!*cNNyT;tYj1ywV(wwO_4YN|U!z%I1nK zXPxchaNA%1{&!2djq7&0cS8#@q^AkyX+b=3TwCas6MoIaDJ!9fYs}*r!9a#|sT);) z>;oOncy4z8VT>kVmJA1offfXkVk6igvMS!eWPdT*>kP75sSS;y;2U4C&a*4}saR}Z zx?kD?7|BUia*G5^(CVm9lx>uUYa=4!~pA8&xMBnU!=|IEgq3FqDHNn$_-^6u1^VQueNLBr$t9*@2y#MWE%Yvj`{ z8PbuKGrBO!jqI&xi&Q5XR? zzhH4sRw3{m*jW<4wydw)v))9Ll-Wh;ajBl|ZKX+j+7sWO)2eN4ZGRl(A%|geU}y2o zn7h*{7d1iLIPP>0|0KbMuth3pz6pn((iXuuz%bTv01k5m!^k+mKhV);EdVmKq$Q6e zenEy|o434@ScPVl-f%$=x}N!yxJgak$a}@*iu>&N^F&^Dv!DHHtSR|!P=4-E3xozR zhx>vrP>^y5;fyno1ayO8i&IA;6Tx_eA{1fo#df3`!SIGXYHi%f8X@TxVtTO;4%(?> z*2V-%wzA7=oo0IktX=2)qQPF|v0n!5saO5#gF^Cdr)I7&$NQ&U&QrX{ecYg)f!oh0 z>J9w<06@6G8Ti^NQ_|cMri6yir|XZRJHs9vv9)Ar8F_Vbce7*&M#7t*1u|UL=?2>T z=-r#0W&>07|69FR?A_An(+7z4@t6Pn6{7anpGKPpzgfdhgQ=V&!a)+=Nj72=MoQ5ATjp2>$94 zi0c=g5DK5r8N2}*qRmznatX>cXr|n{9 zkOps14(CwYa`1pgBmX!}02fTuaL*5W&*kvW5vZW$X73kL;Sx$A%Vy3NazVqM!5h$_ z8YYnv|Eq8Vi*52!LJKhK05)+IwlF0^Yv7RN>R5`akS%-GkPX{#+Ds1)wSo>~Q5GXD zGuDnYhOhvMaOKAB4~sC=#tjNGO9*_>4Srz~mLL)$f!%K5%+P`H4uJ9OVH9GZ6p$eo zNXyT_@Fa}jyy&b6z)yn?AREIGL`o6svMxH#L={(&6*F#IUNH`5Q6A^ft!nZ9JcEr2 z5CDx3=K3(@TJ8sTum3i{5oTc$s6Ys)zzs613ua&mFhLI@>Hwg@85XOgR$LAwN^ z8$%Gr!0-S(i@ZY6`wGqu0L?`luD+J-##+$p*zpwOBA+}0t>AGY=n*G#lBVoY2L~f} z|KP3=3-RsTF7EnK+|msP9O1GqE3@37Ie?5;ohjLBL?F8B5YGCPcBU0|}1Hf^eP*?!5ezc!(>7W>|nD1V-!ZA6cWx3Sd3N3fD9x- zGk;A;#_u8I1=(0;E#b2K<|6EB(kAoLHgD65_VOO};s$_H_5hIOf^Z;;((Vev%62a( z2~!L(ff}Hyx{gL22|_)pu1ZvMHP0|OOlBovax=NSCmEPra`sJ zEzlG1ZZ8P>5Y*gLA&ihX5u&FAQ=L*pkszX7&~b?z)D+vXCDTvQ0Mx7uG)1eTMWa+o zrKUBER4nGINBL1lw{%Cjl=dhz-FmbqFhul*lt@$3O3!gWZ%i#mLJgPHL*HU1`{PNm zVoL86PdlbcVN@+}gVa_o2)EQIg_BElln)7TJpqX+=;cgX1Z6~zHQSOz|A)jS>nk~! zhc@dnPdAlQ{bf%{NG)zaFl!VL;j=>h@fV9yLIZO+dvEq|hbtJhQ9%R+T~I{Tt5RDg zNNv@=PIPVR6hS*xScg?u>cTwPVy9@}MrZH#hO-C>b5L>AJ}r3_kskjng# z+;}lxfA9siHC6|fVA1q7#+7hb5)F?A(Y(T8t;iK4R$?nwXLnXe|1LIOhvEfp0Qln5 zUtM)a`41>fRWK!#_BOy;-J`W`Rgh}6VPQ5M#T6kuM@etRGu#hnbCzerR%{u>XBqY@ z0112wV*kvIIPJGfGZdcr}s5sIA%Z( zg3V%OrPh6$27@!0gMS!^)#5uocqIWT2KM&|e_#WCKmwN7f=>3Hx)Xa^rK1iQaEO?K z&sQ`K?InU2dDTyRx58_C_$GtcjL$gjGU9&mm$G6Y2427jPWEJP;08{jj-$9U%%+@N zm>o55H>5)!1Q-RfySDBS-qAD^W&5jp`cY}p(xFr%IlTB3ousDl7nKO*{ zhWj*Im?SK^RVozOB3fCQml+~nIhF^_=+Q0c*FRYSu2!JOPDcEEc7Ln z>y(+x*_`V}jjKzRu_RWexn2&SnpJo^9@Vv&v@N)}o1wXoNiUq4w};Oepv^g*pE*}k z^N=FqmdW%symym%xtE7G2Dvz%B6vG1g)GDwnUgu7H=30P8dR~QmZRbyLL#9X3u|4( zm?@g9AlfY?TE1rXn>BeXW;3HTnxk(TjWGh2|JB)Bt>ltR!XrM^p&z=E)q(|G8k>cQ z4bNgOYZ^Lm8mfUZWCjr@)-4K|)N~I-usm)@HYdWgWT7##Wrwdv} zu9~Esi=kz1vU)~B8ZQtUt|!=0IT=p7 zdN77VqV<}nR}n2R+Nl>=us6GK37e{Wx<=f3=oVs7%3X1$@{*E0sxdiYrkEY`>EI4z&o|QrMte_Igtutq_0w}4LYeinWZDn zut6BW^Xq~Myo?Xr!|yb~ubZtkq`Kc5(*hjXf_uE{nz)U@7~Wu%9RsWQeB%n^9z+Zyt#4Q$-{FZ+n_QEyCPp-;v2X+|2u2 zC(#^Fj5ljX+(Q_fbMKIpi~KVb<;%T$&i@5=%*ou(CmknsK+1mv&S84cEl#_wZmWr0 z(Yuz=;o{K|nRNEN$thjcZBPdeAk8r(xeY|V;d?zy4#g!EwcRPyf0=ARqtjD1(j|S> zhg}X|9WY}3wC9^rZT;4-Bc<1O*Ll6sskhmMW57|J&xu{z<8LF%#?Yt5zn2|Og}P;r zd${vu)JeVCZ^E?n3B3n*+vA-M7dl1^<32gG*Mq#Rhy1^z-B;g7G=9A){2JR+UEU8q z+l>9#zkNWAr|Y7#liPaBW!&HYoiqe~QJ1^m5uW2g4wg$A))`(v?3^JOUCu?GJ`{Ly zS^PxPeKKDB&exqL&b#0ZzTYwh38GZGTyy; zao*{bOy?&9XjAQd5dQj-G3|eC9R2=FOh(Z42!SVxg11I$i#S)obD%z0@TG;uYfX!Cua1e(agM z?fE_grO%&0g9;r=w5ZXeNRujE%CxD|r%Q36j7>O%Qhidsu?|E#M;*F+o6|?wcN`Q?cISX0oP@S zG;YUCFL^3n%($^*nSUcoo=my2<;$2eYu?Pcv**vC4|@G7Fzm_Dne%>3JGix2)Ibe) z^jmc>?13Bq@#RZ9a{o%#gpaapnfS5s!EFvck3j5HF& z;6|mXRijUD=p~^?;`ue=S}b~aQHWA;sM&n-edv!dVi)spU;OcIoAp zV1_B?m}F9PqeeOESmr_T?H1%4QY8kWMywS+2n^vk`*VFRqi!Raa$I;<(h~l zs_3GOHtOhIXaAz<;Dd=8`Qe)*#%N_$KEXYwfkzE=Q}a zY%S`eN63<9(0HD@Xe5Oj5_?yk#vbcrpI0q=8dJf#6z#qJWvlPL{PyebzeLe`QMZ-y z6|Qy=1sNQ!MS=)#lIn5=YP-8V?4G>y(wiTu_;$P^z#xY#^2j8!D)6n$h6(DyXi`*X zlmY!b5{?8hJmxH|P&w86;HNnIS@41w%wTo!_p>hTkAIodolgQt zp#O6<&?)6xR|3IRGZD#aD(<7840WKv8rtxNIIIi@J4hpT8EaPp`Cm{-C?MdyC54eW zACOKsIQwi(f-|IG4yQ=PDq4{#J1iWqD7L2qc&{i#43PNlfaBXHotmkCC3 zXjhD*9Op>Khh#BhH2UBIIi-{^rbm1*%Npf2qZ%KjkunEt9~9r1xH>xWk&w(GtuXSd zJc{m%ecT*`OsK|05;B2@%nV`B!^ZqD@@$bzr7Bk`ze%EuhcHs$yF$qt2sZ3^M;xSP z&SD)unkql6JLSDtNz7sz({Zj`qm1;3Ba9SqDZac8&1U1m+kKLjnu#V+nCC`ervIoM z#|)=9$62yuR&r+T@(W9_IT3AA2ata$<7BwTPRzJ7C^7V=p~%V4e)=<8=4?%jeE6Yp z@zQ~s)Efcoi4=KC=AhNNCqB)l&n*4(q8QESqXH_>7j>;q5Jh1^e3sZ3`ICXPB3KogTlNTI34@Rc;4y1WcMQ##V74A5CFeJM|9%G9Phl|?oU zYJrS6k)38zs@55!vam`St4>FyDmk1|k@M8Dn)R&Si7HnEq`;AQ^(dLbY3G2t)=!Ox zs73vWEe%T1v8D~JfDNo*QKME*PL-NrJyKJaRUN9D6qcA7DqcxR6yJ%}um6e}tY$aM zS<4jGutn^jPtL;73K8x(j(u!TFY{LENOZN^IaM$*`?}8B_O`ga%4e-PAa-HXnWZhr z1Hrl#t!}lhcX4JQgJKqY=CwSKEeJPhTie`P_qy0UiW_!&(h~kMxPlojZ1Kd&Q6cv& zlAS1cOXo-4j!TwFt!Q@VOW*pA1ThY?(4yAKQ}GfPD|A{fT+d6E)>idy&fP0?-CK~O z9wxr0w6BCGOyPmxccJ>-??tZaU&?|ewW=NOL+`2*#Afrk2k59y+elp+R`|s*#_omX z^2(c9a=jh)Fnq8kB?6nznIj=!XRM}7oi1{$F;23QZ9C)H)Y!+%-2ZSx{o5Sz33$Mu zMWB>d+!C;DhFRwc$z@-<j z%R6J4(VyC~|K5d~Ke<)5m)5kbXH8B{A8AO6qB9u9<{c~7r_cZfvOoyRr&h;lBo5|C z^JYlvW;?r>wx%Sm5vA+OVoZ#4?eVAok{6IL^GVD7GN}@4N+~}3+~|H}v^~A;9r4%N zj14U=;|y%8d^^&dd0|-jT)}kv``=ew_pzz1>LI%Nu=Cb7s{ikjJ0T`G-sC<}>i|yi zisLZa2OpC~3<>XPhp)W9Za4AvNHJ4$Sl|2ZE72^@@|Ir^;{z8HLBm60y~f<93q7&O z?ajiH>zvmsW%0^gPV}Nv?~dltILV(>^Y3Nqzwr5K$QRD@hW91hi$3j2`3)_jd;ROO zLwb>MxAcv?$>~WCuZ{<#XoYtdXG}`x)J-Q8OREa(c+Y#|#6I>N5!)XuJNtsqSv3?l z_FPyuZ@rCTJY$($)Z(o>d}muIy<7hBYU4ZM-Q9CHHNEh17Ovr`lk7o@d*@2Icc>l@ zlpG7C^cq=q5xSOa&-~{93-`I# z)b`qScI5uvGr>osjfDc~5A6)Wxy-SGQ%)QR|JC{EPk*(bzkP(aIk@jL^Z0y(l1%=q~fYdc7x%?<9f6_=mn}BsIvhipsTOA!~aDlmM+?ee+j9Orsy|@QIJzt7`u@P7}=68 z`4#{fkR_NiO(IBpIA`2Qk|haXM{)@dDIidnIxjhtM2QtKiATOjlk(>$^tfYtk%2>I zjLRczEs`>^Asa=Rm0B4UM~RdH(vc+>BsN)yRW_13DUseePU5TO>Agjtv>F_&~XjK(5eREd{u=#)8UY)mK|jaiiu znPQ1)n3}nnqM?ym_m!(x5d{}7$j66W_LnC&jo+b`5aLT-$(gVjn>ON^8(EjTVT1+- zF;vD{X33YYSzM!OnIWlm!zr7_N&lFLnVBsZj&&BC7bAX`**?ALn>Sf^l_{JDX$yuHAG@a7roKpdv#R*`ghMK9_mr{|N2$DCy*`4xPnBNJWspb)hrJmX7dY0j9 zw-J3>;hyiAQ1LmR1`3z;xt)acks=|Wi^ZRFCZ3kao)L7NE7qi~ zk}#T`RYsX2if5ztVL2HZQki-+DiXf+RmwS}R*I2D3TmWDcc?LuJ{pw^X*gfH65#h7 zReGgp>W@Wgq#iYOp{N6jF#H1jT)-5T7aXZI;`mzsgk-$zWSz*shEUn zrkaX_A!310n5i*Jtk$ZC#_Dd#8mJ!kPU#6909qBw1s49tsMUI{=qiWCdaM}IZMvyv z!dhIZYN+R`6q5CAI%;r-ny&l`g6nFl@49*M3Y@yStGt?eM}j_*Hn9ELuz6=|0|TL3 z#CmzDoijPDgvg^SRsW4oS*ZWVt_~ZrSqQQ0c7wp87ZgjDYIm_T2BcwH6p24{6~W_`*1aTw4->l04RMLp&PuXtU#yr7w9E>493ht6N~ae4P7-RcQ9BgU+O$5Gk6jzLiKw(o>mt=iwjH;s zptrR$+J{wpunp>c)R(mjCbxz=hjd%Fn>4tzw6+f6v*HT0U~07wp?bykf`^;AahSLg z%Z@}#V;-xWV7s@ZC%KcmlM&Z=#^*ws+qziDxg^RW3Iu$nlY zv9idVo#eX2+y8^G8@rzSxt_PPy`#Hm=e#AFqY?G2{YSfm8(zhmy^#8~`+6IeLc6EQ zyzhv+m61A&3ac;sgw`8=+S|TfOPifrAdm*W@%MS;)4e0cyS+=H2hg^^IE!>azV17~ zEqA=gdy3XLgLrGB(7Q|eyT4{TZ2#-F!W+O1Ou!gibeS*=2UD_Kiogksiml4Pi6*_% zdtR}qhHhfJSCzpoT&xvio{*bd6Z|189GLjaZL)N}=*xvE{EI3oz%M++{w6RHE5jG; zy)_(v7L0$UYlgt~!-9yh<(b4pe8m7~#2);?T`0I#7sNSC!v*`dsQVC7Jbjf2F<89D zwWq~M9RJ3tp}IN4lvZ56CfrNUdd5Yo#%$cjm*>WBT*tdB$Dy*6o-@PJ>9fhV*5SWS`UOcKs4uDo%>pIpo|niqW}&=g&91Z|#Z z+y8J0J$N|FlZt%8{ak71+&dLr(pikksVvFd7C7=psfQfDk?YAlT*ju7qyS{nI9&fmzxB%RYreQp$$Sy1m?(rrN9hp<`Qj!X2;~SE7&|*;yTf?#kTU4QS3y*ImkS$w%45-5L5U zj@cd6-M!vt_TAtuqxeDI;})mZ43x-Sxs1);`YmI;-P?Yj$p;d0&I{;k>Yq1 zp=T?r#I!wGwteC>ZeI=V;2$^L588JxUf`#hAVyu|LjGqr&eM96&=P*O6F%Z3&c8$c zx`8>f(l+p*2ocwXp$#pZ3!=bNljSI&Vl|svMdthq2B6GHR=mpL_UJl_q*w2 z9u;4qrsOMms4*Yr-Gt5E-h9v;-oK2Zga z^<@9m-`=fb?S)ty;VL`lR9yCOZ**F}^=Ys6c{t$n{j*~q_k8c&XOH&Fu|M>y*yZln zxQ_09pZNba_s>13c0b4CEY|kE_ljTnFvj?ee;cj6fC{VEPTeeTZ~3B6YfTOG67SJV z{LjGL(S?!hqyPFgzSE{(;`hnQP9pGAU(ognJlPKWzAsLtKmYrI?~zUt@vN^gPucsw zzx?ek`?H_vT}6`~Z?04wD3s6q*gsgoFZ@v_{V%`zXg%@QpZ(;2R@-m-sc!ptdb;6{ z?1*3f@Xz1y`}}$<#@;VN)ZhMPzC`ig{{V47;6Q=}4IV_8P~k#`4IMs&7*XOxiWMy~ z%;ZnwMvj+ud;}R%t6cX zIP=b|pv{7I8+h_+)~#K?h8Y}&PL-^QJ^vP`t2egEFvS>~GqpzA{ZU9v0Zn5e_5 z&K+I)bn4ZuU&o$Z`*!X(cQ;QS9&=&l!u=669eT0&kYCHgRKFE^cl!11-^ZU{|9<}c zr+5u@v13@+>7Kqy#dufB*m?`2+x zYTe2;CDyNC!-A}{DbpxUoCq;l%eJlCw{YXiolCbalZ$US$q}?^lb|Gk0}CEZxUk{F zfr}JL(zUVU$B-jy6-&9Y<;$2eYu?Pcv**vCLyI0wI-=y$TVoc5*rW;19Zhz&7C4)> z!JW8!>U@3E=T3q{S4W(Bv+2^OZ-^^TYRqbBh^V8dEb_d%^@U{3qE&0RyZ7&FIf4Jj ztCz1|#OTwj7p$X*^!M=N>$pz8zWw|7^XuQwzrX+g4$1ePYDPh{3K?4bVpD<&{`wspXbjZYiZ?1Wpv& z4hkNy$|^CCLB;`ZyfMs*!T7U@78w@Ap>H1MhG$P~5+!0z%MF!WiiGY^qI3Rz*%)WHFAgJq;GMuBU6|9v)zpj5yFo@gcL*wTBBrA){>~AhfsTpw(6Lpu*Ux?>#Vfa zYU{1_x$0P$6WJumFBzh_${Uk7<4rL0Eago#og9FmoxFY6A)Y>k*ei-{7D{MUS0$?J zWVqUz1VuD%N-2(n=cVdzU<^6=?ZDv{Z1BMd zC#>+oR}RcoCjJO_RBs3T5+NYLlv0g1|IEYjvd{=br=1)UH;_%%UaRfOQ*jHR!!0rF z=wTC;YvZ{%vz3>=lG=5Uy%fp83A?5u`R|gZxd*d=GB@q?(@;k(_0$P1?NUttNIYUs zzce_IBt{&NN*bk%VoNo?#30bKBrE6BKq*hm^4vfT#p26WPe-+ts7C)}bI&1 z5wy%doNOe=0YvwEw0ac@oHt~9S8n;`m}jo}bCa)xHBA-mc0d!e%u=VBm%Ks7FOtMC z%P+83413qNMP*RjThpz(O^3$V`IMXY_c*{zGW2)gIS+2vGMawG*5ZvDJv?C>vHE+= z!Dp}i_S|>xy+GHa#A{6yAJnE%VXMsN?S6)iREbYrBLD7F9ont8oiqAGjnHe{lGLCYDl)32G7JIp6aA;xNyOt8mh!`=Dg%e00g+_>B zY@%#Y4~7 zocoC~Z!#STMz^Zcfov2moAfBXzR0{!(K2xhfeS=9v5Zrt2R{_ds$Azv*ScnerUD%( zLF9K(<0Q0pQUPjS7qX^`*<==y&_aX`y8|QaK&o~aQ#R2^rQcE1t{LH~X8Q)1jd}{2 zI5QtxnTM%=?5LIrk*7o~<+zOE2Vj@QtZZjX+lv3<^{)*Hiuu~aSDrd#IRaTIM1B>U z$V#F$tALGyc7UKAtYQ|cSZ)iq$<0yL_9C0j?$HilvrhP98HB?TL)3LR)1DTssSV^r z@**cy+32vZ47tdoKWEZwCk^cqCH6+uffQd*ezA}zKUj^^bbfau#tqbQZclpw8{HjSS64HV65ycld^I+@~!AhI@ z)Tpjb_yS62gxDE4c+T@rgUjceLUbvn^@pOd>B$uh!%F!}H9;^qwnV_^D>_C6=Og|0kq13%HR;^v^c5hXqs=QgV zCz38s5MwEy5(rw5?d*T_>pC>Nw!jBY@QUC!zq8IMQAi?OEds@$4xK7hD=g6q3!KYn z5C|I3U-b|Ty-+lkY2zyg1?fw<~5-Qv&8sT=s9WL>f zffCpg9XQ4nvhj|4{EZITL^8yx5q0&@v>{1cGFr|=nOptpsiwI_M0a!J7(>?PtF^6r z?(@3=eccz|aKf2OqX{_H_s;hj+Ze~&#)(dM`t_|5B;jIL zAKB~Y4~knDW?4>kmp9UOw^NTI%LvI3(GiSi(4=&xJAfosQ71pw$qtezX?Qr%mo`qj z@34=(Y;7DdZ)@n)IUW3Qc#iwTD;}cf?m306s_vz|oXaC=I~rh6>~Mftm?=YDlTiQmRUe+VhEg+nm%aMe|I%z{&GxtFc0uI#`?~pFZV^9Y z@Fi|H;#b`G$ES9bQF$8Xe1HLcCZ-V$gnD-H3M1ov2Ve)M1A%7Z5OBd-=$C%%w}Bj3 zOzvk>H79>L=X2tgJ1Mk6WyF6!7iVZka6`8l%Ex>kXMlkbckLt*anXIh@B*ke3bSAb zw4(*w7lD%S0s=99X?1~eQc4=wfll~@Qj~2^u@SHK5w_DOC1`>>wG>c+ZjI-EkLNHk z_kyEAfG$T7hY@!P_z-jP3+m-(p(251GK2!L3Kkd_oUnwK;YLu{hkl4bQV4(X2W}!n zg?eUCSvYPd*c5&;Rq6j$B|$fa8+IRN2uu@^9tb!QZlMK|zyx-%3KB93z2FU`_z%vo z57WRgnRkTlL>J7n3E$L&e>jV@csYS+hzTc%uJ%)x@O~UoH;h;m`)5X028oknb;$Q0 zm562)u^yRdOKky!t6+q`G6_Rd4Z*Mu`w$GXLkP1&I|^YJc?gS?!H2bYj_4RQa#nk| zNKiuof?&5-zW9qku_D4qc9O<|OA~q5Mut^ViP)7S&&Y=SRuH3*N9GkV5YZjuSdOxo zju071h2)J{ICYO{j+42Y zyh$3B$(e1#CkoeBzQub-*^wTJGM_nFD~KhL2$h<3k|#-rR>GRrd7V|cjA^)Z2$W9F zLn#<25|IDdo8(!ZnDLt(QH8J;YsT3d$eD9A5kI`OoSyWEXgQjs8J!P7o&ABG{^_4e zvI+cvRzPw)WVRi|u!f$7GmiNY<7u7{8lfX`Jr=o^;AWu@mo*@9Mq?zOJ!hYI34r;j zS+eqMUn-`Eny3Zg zqc#5poWZ$Y8@d}ril&CbNpGq&e-a0xA&Q@|=cx@5sxmUFQktUwl1E07av8xx zgUU)asS$@7tJVskj4GFN`5Sg~tGAb{YPzOW(S;y+mvZ_o>-VG-VXXRrtWhe1sZs~3 z8g(YdN^H@p5>c(!y04R&t=@Vv5Y?7T@vjJ>tGh}SmpWn1Ig%|ntR%`2>}nnEYNE=@ zr>p3!s9K};imwo%ul)M4JNY{mx|T!fS49f0+B$AIm9SNosa(>q4$D=a3K9|f8593& zqK^Zc9FZ0UB2uf$N?sX|ISR5wTZ?2mvQ(H;c+{Z;ODzU#rsK-8x&y4iIxu>9b;L>; zHG3I1>z_uqtj&Y5Db^Irkf8EruRB7H&FHa3+qQj3ra#%VJ|RC_Sa@c708b0G%DI#r z+LZVCMC_NfTssh3TM}IhppV0>VrvnBifjJB4|oJ(fwL59i-v6LwwTL)a61!n%XRWI zcy>E>CzDg*nh^#iKZD|{!nd#t%c&f=S)pO9h1(H_dz}?arMl#&7O_cpbT1pbBZhjp znLE6Ex4CZ_f)@%m$Q!Vwt5B*+l=Fj+zSbx(tA4O6v4l&zwQHSVkh2FMFYN!~BSUl% zpQWYt8Xo=@yhBU8>>G1%o3h&~q|EVtB8V6Mu(T@Fh*RaVFKclfc)j@{yB4v%D7vSw zsc&wfFGF({f|#n3t3zq4zPj1I6#R1UE4O)467$YmV zpV?ci1iYHJn<})VyMlxk3milb;V#X3zDy9bLc6{d{KKf$IY=9%8muBdB)@%y9E%sH ztt+ff_^>H_tSej)Ev%Yf%cuTOkO`qL?y?>AlDj(0!>;;}KwQRemX>iFsr3uBM$x>6 z2tT~Gx@PxJuKR>Cdl3A2C9+$^c?ts@_rfq7wu{>kT!kxqoTmnC0>cA+_bZ#v`VVI1 zF5vaEI)sf0q+{*Jh$U(A&2Ba=EJV2AurRPk>>U_~Lb-^N` zv?_$b1R>9oyfq=Lf^$3(FCoe(F>~{A8UGB>N&-hqV$d2Pou&Vg&4660(Z|q%zd_LAjYVgBX3(8I8svy%1eDMjqWK^NesKZI}FOaQwW_(EQ9S4S9c9YUm-; zAwh>=9TusqrxE1Jx)c(P`@nLcz=kXrVm!tcjns5)OhOE#9$_~}`qUu()Q6YMy!wTA zwbBHU()|3)gl$FA+=uT57_(~`V;vGUeb%N5%N-F`whSJHyh@gWn~aRkbsgHI#Li2t zV{9t0yB89DEfOj8x%Ip|BPJSGy@C3AQ4cR~oPhi4>J*Trs-VDLpk4+hQED_mEL&?zI#Qm(%dcJWj z*ROitGJaqAJriqels6uD#T>`Udl4xl5KfVTR4v#c@dWk|2Sq>z*+2+7pbFRU1Wzyw z_D}~!pbn!@1W!;4o-Go&{o!|f5$1i~1L51KS=N-T;#!OmTbjs3UDQTB<8b~xN?jm5 zzPv?DRrGtN8}Z{2!{d%fgs1p?}!w!oN_$S=OO z;8X-`mg?Y+Ig>NQ2b<#?@#^M2LVhmCxm?&DaSfwj5RXnBPcRR400{eF><7>e$?g%0 zZRvGd8L3&7one&(?CER15#_6;LqpEUL(%jd>S#64-QR{1x+77{VxfP4&B|Osb52yYR{|@k9UhsdZwSZ{{20yAdjm3ru z#zenbSt_IPa=vXI@n=Z!PVY1|Zr%NLa~dBKuO1eFtxbTwsQEMzPmm3x;0A?|4L3Oo z*8m80AmxHk1jBF(bsz}PpbGx(Fg5?WIX@bzNfIX>K{5PJesAp%@y!A5(?Dy^rS8K| zpZF7L@%nA`dd-C;arIcA^(myOr~wfco(+gn1f!4*wV(y+FyDo44J*$PH(!gFejQ=H z5qF9P{%O|JgVwhMNR~}@aHS_-zW$8xPWy@!AF6?kEk- zloJt5MIBmT4_(0Jbgz>j-mW`e5w-v8`hJPw_(nl)|SOoE0W7&J1_*!lTV=+H$)jTSX| zROwQtO^>31fm7tytzECSJj@M7jvN04j%! zOQr`FIdqy`yV9u3r&c|{DQ#A-T+I(@U|)m@ zZoTEVUw{7vIABDz1&~$>ecfv{19wo&k48FamP!te z%QewV80xu{MSSDC zWGrPlOIqHAk_y3N{D^fK>?qofAx%0!cB5&N{SG!vW8qIE%xZ`-6S*gboXrnPjEgj+Q54r#A!POR)qR#%6|^Tb5r9XLFx2E+z79K zk<=fwj3|_lBr|u@gv1kTdYhTjF{2+fiYEKBJiJ{5t4=BB7)u(Lk&;xUtTd-kUYUe! zR@JRSm1+QgGo6EhJTm9ey#3fz09;ua%A#ez6KpjN$;R z_=O}$I*VCo;jCz}$~)VL!ps)exW`S@R5LM*H1*Lgl(|}Fj8Rv;{uD3Kz0BsG2H4jO z5{N|=NJ0urklEE{A!lQ3VjT|$mh#9A?HtY=J;>`$Q|vutCO3fag~wZ@HYszx3e-)a@A2vX_r@IwE4Uvz1; zK1{h=C!d$W(vtE>CSk3D2_gw|DOd{wu>+SSQDL;Shg8EAT9VbgW;O$6uEXfkK!FOs zovvgxe2npGTAbai<#|_v_1$~RX06~Xmd8A{W=N1($RQ)J$RVmro8`7-CSR~d#<`JC zf&!gL*(_M9TuVt_JCN1l_5hOjGACB?Wl|rYz^hmVg)5v+ysTByx5jm@6MapCflikC>#|Z39W8(I#KvUBo83HX5ZXEn34o zk0+Y81CH_~J+sE^BnTc7A+#_HE{BJ;t^IO=%_89nTcxEZv>9f>J#hbm*Z0kF_VxQh zY-bA%JJ~ykZe)=CaPK1Y$2vGFMGdkM^(tg+)V6q0JHBY!w>p$QgwitpddGoIm|EZMJ7|3UF_yLO6<^E)gE9Lr9cNV zyupuOtiv0~@CPzVF^WR?*1@u!wHPt{IL6oB_7^?4inl%#WUK$ghhG1>jIlm;KPPKM zt>fK|Jr;>S0b(F-a6uOY@q{9D0TR@>gbw1cB`pA=2s(HIAfDg`l@p{0*C<30iU5d< zxdDiase=y0FaGrx!5-d+z831x1^JIc5rZIwQz*P>3BYLygEKgu#k)PDfxO5YHzyM( zCbI(~@U#sQtFa;pEtmwEv4d(rhY*?vZ}0|t@P}#ehG*D7vj{UX^S4@isRe|=7>pz3 zf{b1vh^#XuKr#vYak${?Gvdp$ACeV8u!kaWg=^@xf`A4su)iYEf?+s6G8{R)(}DkaV1y@N2OZ#tGSmWEC<1FJ z0$k7nH^_uSaDyUv0!287L3oE~@rP|Y!10j@8BCf*5H|-Tx09$e%d4`qI;Wu^gzWK$ zeVB)RxE^SbgLWe`CV;xA%NIsO#Z*L}51TIMdKeuXi9qT>A0(X{j4>fh2=zMv7bp}X zbco5?1;g6~w}XUTH~?@sfLpjexYGe}5C~-4go6M>X-ft&+ysm0LUkxPkjT4v;6*Up zyS=MJ9jJp$xCKVwLq9x-auA4f7=>Hlhb9`EfiS=`FdkJr85n?pf_OPdWU|SVk;)UA zof{)`$_$heMKS}Q*^@eabjXKPnwp{&8w9G+0Ji^z7^YbazKztg)lrBeYY6ot5ns%R zazF(}payEVzOhlsmi!ZEoJMdcf=oDwxXX=X0D~vMlP;Xb+{in7kVYNYJD{w?OrXg^ zAOt|@L-Ml*R=b9VNW3$ECd1;GX@f|lalC=(M}NF8C#y6&FoCeT2n=+IQ?fvwt1x%U zi&ql3t8~k^Os;#HNLPHWU9yUU5eb6Q$Yh&1j>MmZ2$z8n$>2CFLkh290K-~12P-g# zklBZo97aeeL~(e@D?9*307JVY!j3Qo>N5xMtB9U#jBX6daMXc190fqo0cgmCbaVqk zC(@RO&S$B#)oxRe`5N@N0=2U$MS!yz--OQS zj7wgFGrZ!Aed05^6so<{OXwnv?*vcq6qE5JPx6#Si%|$hIe@_giNZuIa_l=dP?9I0 z1@S`#QHU0m9LC5T#z-&*H+V|T)Spav0`OA>nk<574321Y1zsEl9dLy$QH3X91R@v( znp6cX@IyOr1zey7To{N^PzAY&poZAZsFF^>SVaEN$9)8|M-h9AyHvbioYc(?^BW=@3%Anhd)%(v0A)&Nv-eWKv_uQYoE- zX3)fDpwc-If>TA+R8`egWz|*{f;qrae%Ks0A-^(BGxkios2UXUiWV#QJ{@oYi3-NU zo6}>0Av=Yff;gZ9P^LME)U{lW{%BExaKv;I)X3`z3S^f6>z+%L7uy<3MQu*!JjG`< z*K-w-d*Trj zD1=Ptf_ESVM$iI=a0CBUD1vhszY#qLKs*O~_#eSjyWn}-6~)+TNkC<4+`P3lkmcL0 z^xIIP(aSSbO*x4-IGlzkT*F z(8TQ_1b9uUQ5;v7qP-Ya;*Mosgd01B^A*0l+&bAM(DmO{^<1j}-OyE9D1ZVl5Cbvr z13wT0FEC>-4p{#QQH|5}o&ip$O`zK4NZ`2`Lsf8rC#YS7c!GTxMptNtQLu+SK8PY< zguMg5^g96L4I*tLR*=h$BZH5E$Wz`)jwH~XCDw=;j#g>aM{3RC;5^w%!92A5;ZE@& z5%LEiE@Bpxy+%!9OonA3ZQ@M@434arO_edr$Wku8Vj(EnT^3z024gWE<6^#pF+Ko4 zxC1;WW->10GcMgVCNnqo2i84co0#LNum(FQ1h&d!gs_6b`_(5Xgf2W}Lk5FFI0)qZ z5RX7YCo*B-iDW#LTZf2=OOEAA*5no8!a@I23aX8i-`5ZmUB2I5#$qY;S15(q!J3xd0Bn3n8f-TsB zFt`FLP}H-aW^2YxyPb=sRD~n}gJp<`BDjSouz~>e4S@iJQP2VxU<5LlP`>M39RSJz ziP#c;*g;l28fMnA!HDtsn1@c`eg0S$?PRUARtMbSMH%HH<~^f5%bGr7ByMQ1rt4Hx zR|5Ij-Ft~YvgJ!~;?~G$&E)`kK!v|$jy~0mMpcj=W|J=IlU8PCZfufv>}4L~l`cF( zxPv?B1I+G&&ED)e@Paegf-|7$9KC6C)M;%_f^@irYk-C%um_)RhioWBGH3^AaK<7S z2WYqk^*aauXsF#num*py2I$L@s&3@Ayx12@-bvhEflgGi42v@w zshXy>#C6oV2JaZOSrB`T$&d_=^lMzcWx*zFrj=5}7HP(2Y{`CX$X0B}_Jc?ez(~k! z&F1X?2JnKIgD?nfD!2ld{RfqV1XM6!9Z{wu!_|-AMS^)}V!hj}R+$@{%8ZB!l8j~O z7Hj_~>w)-ZP@2F(wZu=s3$sk+8LH_P^zK&Ws4-(!CYOEA;;BF|FUhCTuUB z15}6vF=&XBUTpfd@A_tP$yRbhIE7t^gh9A${|4|YzX&*J2+sy>(XJONaEpIf21SUL zD^Lah0_F$S^^UrQgaww}YoZ-_^q2#@a1xCP<>r_=x98@D1O#+w5C?SUtzj1>@lVE) z>Nb@+Fw}xv*|$K*#4%zMVradk@k%E+8!r%Gqsx>CY=GLx^q#oD-s1K??2w*=RS1Su zfQ3kStzei1M(_hgK=ncx1V3o?Sx^LJPK8yF??{LQSdec5IsijpY0JKBg1GYkE(qJ% z?1pHhj2Q3&M+++W0ke?W7H5Jhh?XrtivdoOOt|KoP$sE}a7ubF5+>F&NIaR)@RCS^ z*L~1x7f4U>NCCP=sJ$X375bV)%#b;Rj%M@{`8{Vz2CD z&xioWh-QEGk)J=@oMfcYlMsrJH(tingolnrK@Lq`J2gVD4oo00=P$2HqKX zAQH8G)L_9Ph{q43V5tuD`4wzcus(`X`RN$!fJKaVBEh1DY#%><@BF1~*^*kvNHRm6 z+Jy>{Oi?5m%A%Id=SqGk4H7MC)L@^aeex{r`Ygaj& z2z4d&CL5=J|3nRZVl4^WB&ssmiMwnVn7D-8*twPD2{bLVbUeAH<1pg?#EKOkZEQ45 zm_b?xLh9nUG2Am+Enn{J`7`LyqDPZ1ZTd9o)Q;n_ZteOt>?CN4qCrzPHtyWIck5Q| z8#G)PGI$f;VLOZ~i>`^y=5M zZ|`39;`s9C)6eA3*qebn_J4n4%-C@O3h2)z`|SXlfe9+Opn;eCgWnte`P0lCa|m%E zh8b$Op%73AG*CxGMS_w`DKSLV0jZ?&kROpG^UEzOcC<>12=(%eKl|*13`-^Y$PX+n zhEmKs;@HDajwI@cq)I+!Q&4Gn9FT_}OeuBc0Xh;?lv0Lhbp{px)O95b6N(UWg)3eW zGSxuGl>?3-aAl$eT!jcS%oA~?Lxdc+*^>l2TBzd23iQQS#BX5?r08gHg)!NCkxDu# zr3Y}wooBUOx+$lEE3Ucf`l+G4 z`ihtv!#tSZ0S0;(A%FuaTi}7DG5G8b4jOaGe-m2BA+{WPD9}?xbu?0sKl+1?KQjFi zNj6CC^UFHUz!FIx$eb97D9FeZNig^7yYIb-ka7wshK$4zEa{dQu1nM$1dAq6UM6K8 zR8Be2l}SbA4=fdH?37mBS`~(Lsg8L) zHdxkeB3{<5A^J4iZM*$8+;Pi2_j|wEO<%CX8pPjtmt3Okac?v`8ng^L$m($vX1jQX z+k)svK~LQw;CIf+j;>3A8M0sO<7?knG8hZ(eAxDJ)rdMk;!$|dA4RZkWU$wLH zFs|(5&phnRGY(wxz*R>faM>eBoJq{1b`kQe-5h8CjEV-AWRTGPKL96eVn8gCN<=hBgG=FMuBWAP7S!!V!|tGn~*QA#kj>m!3!VSQc*$_2_}`uCz0q#>Vol%b@;;@$OuL?jJK05|Ch*E#^C~tF;4vf{4IxUws8Nh;WMd^hp~fA5 zGQI&ZWPHp^qwG!F{Hc^DNED?#fqr?YC9 zpuX=A*$yZiI@^f9x-;X;0NLwsFr{5<0o#EiR@rEM#z1Ob~Pcz zAkYZNjdkV@457x4GTM?Hy^&(gJ7iLx7ro>q1r)FVMIX*^2}o{&6J21#DI&pyHCzIF zOyC43R53Cp*pw5)AcjAZF^Xhl0xotKOV&!GsLCiU36dGaH=`;kUi#8Jzzilfy%Wsi z81tCQYz%eYpsZ#-bAk_~rm8f!!2?SFwXJS_D_rABH*toOoW)WQd0xmuz7bBH4SLYu z{NV{tyi;59tf%DgP?X7uXngzZXYA1RjsqmD81F);?Cuad%`Ws?u&W(J?;z2Ml6D|e zqS8Hgf)dNQgrH9%sZx-V6z)L+56UyjN1}qGJ%C#kPY5CqI1Bb|xTEtbaJHSTqa=YA(PHMy|paTeK8Tj>Td8uQ~ zYYwo3Og=N3)2!xf#`lEwnIW|9OBB5JmA}#woZ$fMP7TSkTlb`}LyThKgfx>OkVEK# zBkbACDw>RD9Ib~pcG?hkgvKNuA3-}x6cryp7LJLnRs_akiq1BqiNJ9p5OL}p>zEC{ z%^)YhOVmxoFRPYw4)c#gNgfXJ zy4u#hHnwrq=DU%zaN&vn(3k1FU;ajGSbp`}aXg_z4|Qv?kF&71EbND<{0JtD&McKU zEANF`xZf-)<1R?SVWrH$3t*zc8MaXHG@jOYB98QkHBm>5g{C3H8+9L^*KQAoVi%AI zcp^kS5JMp1#;pE0EZ8syu5`r}o9IdxI`MKQ#C+z2XvR;2x(vT00Su!cMA~p&nj~~V zE49pad%L6btW|YV!9Kv#p$=>)qoLTHI`#nTVC89MN6P{7@>!uRrt^X)y+}Vh+S9J~ z=4{(;c{>1}I%A$Pg`i}z>&s2QM$9f%H~*~bZ9vGIP0WLevi12AOYlWX*a z7hR>jh(^f~X6>7VeG6(`puXWj zhV4Qm%mEdI3E5D=4bK+KUi z{EI*A!Y+*eLnHtLHGl&u^nnpZ0xH-8D)<2~a9PO#A&z<6@WBBpK$1O_Ojqo~8ral6 z$N?I@!7Xq?GyKD>)f%TzMl4;1qihBMt{HEXpVOhA`UM;MNu5Ce8+BP%`?Us=9njX; z-v#vt*C-qQfrXYO!?f929$q3QX5xAYps(1KIvvZj6ouU(2)W%E1MYwWQq1nqo1qn0 zyFK2amBf);&Os&G7{Q_lDwKtZffyJ7XSeiTu3LRgfObg72tp| zA^{X!!K*>gGAbMn>fjB2Mwe&>L1mPVD4|yP-eesBFxlXBxc5@Y|f^(#U$Pc3w?P8Uu9Xf1kPTy5GnGc z-jUl+&emm&SRVmNkStm;5R^|`)-AHg2wosVjnPxa(}mywhRi`T@B@AfV|2U$%bdX+ zY$XzSB^B^MNfLrD?1M2Vf>_=l4<1FAP|QDtOIijWBmiL|>_Z>y!$8C(y!_`N6hl&= zLY7=fIo?)MI9DG~!yx1yA^@Q{;2tDYC?aIT8E6s}EW;Hf0~37c*cD_P#>PM_Yd}h{cWM>4|0f3ij{zg|Fg=&I@{<&t=tf-M5DU!PXhi%r! zedMNjyaBZg$O_dLaDE2fnW9fVV2g>y#h6Ht%nQFMROBg|2TqO{OeKeKr+2;qcz(qj zEWfI7H!8zyUCDYV?GvINZ)Ih{NseC#vF}IE;g<4FesK4MED< zL9#~va7zEMMv|&mi@KnWsCdw*)FdMOZ5^r@1d#D4PD#^f{HRd`=~s|l*;(SQ zUMsd{YiTU0e9UBCNeJNNrnm*C0uCpCr6OufoJ$-BC57o`iK)IVnNXedYVhInb5k(9F$*tPSL657U6=eEDaWTR`oB^(Cg^6mb zH}$Ho25lfl$~WkUJPgDuXoEPUgED-=0ek{KyaF!B137%cCoF?JXoJ&=26YjKu@2CX zk_wQ{Ut=t*Gd1gHKx^0qX|uKFTJfLH#;x4SEw{#px8@fpCQEqH*SK0~DfT3}ZGmc_ zp5pmKrj6;lE}91-u4dKi;&{SwTtb_6g~Tp{Z~ZF{Fu@bZ0BF?zfgl`g!jhFon#I0O zEZG>u89;$E7V5^%m{Y)P$T6r#9R%y;j>)cU%I5AzQ6ujq#qY&z%J7(vQ4>yi+CfO> zc03ht%xwt?t@HY7dq8c|KCL*k!Y91KF=)fnzQZ@X!Yd>LIV6Mkk^?TJ2916#Xd-Je zVHw$eMsRgPM{>d?m{kRVhO~M`*rL|~!6x(eum8Ga-KLPROeqU_hu(%);PkC-{;j$4 zm*A>KG-^~q?Gr5c8<{Q?FQRF-K<<4|tXD{EJNau@3~Y0FZgC;3!g3W^P!sAx!5oZU z>t4ymeyqTZ7=x~(@&FIxsiN%mK`Q*hMELM83~@&E0V4qau_EM7M67}$1d@uZqpAUK z@P4JLJm3L<0%;l~LheR$)#(5J&+~?{^Pa~iyo0bNgZ2(Y8C&f;D1#bD?LgqdH+Y8u zp>NhS(Aa(zXarZBo~>DZ*)&NjwN`7HeX$`Q@+AhaV%+Urg$KHY7o6$j-3e#h1+H%l z(FPX784V0dNMPbxaCOqF2HR_Q;>QPrS2Iw^zcPUgkg$2w!6qysCwMRmAHXu&AZeLg zND+nZ0g~&Mn#hVQ!(i$!FhU<>QHmHd#bnVSD8esjL@?ZeA{22jL)&(26lT3vGCOLiG;+ggm&hK}2mJ?1Qkb@jxg8Ifw@# z@}YJhoBD#8s)Pn1AcbvqVpHXdFgGTQp26GO!FVAn#`11XkpZ zqTiNlB|EThjD%yA$W%naHS?ZmQ6WpTqM|u2ZXy&83OFq@Rj`HK13ln6oVBy%sv1EfF8g+^p4^B10C4|xgdim*h3E9K`Pio9R&j{ zVy<1pku|nqZIEL6?er0LPA~N6p0?B9DYgKP;{-Vb2|_A82`p6ume4_ zgRl;SVt;}>yn-6PlNH($v}%r7CBiLWr?zSr z1x9}cVuX-JZ}dMnX#uYXl*U~;ku(E3;FglcOQ&=}QIbm!w@W95MMcFv5M_no!F3i^ zcM=Fr7bJxQY@Wo?*R}AyCgCAr=Qi#KCozxXGM8i;FHUL9P z>;pPfgEzbbeLDj(paVE~!!W=CFxUb#1cM@E%q{dn#-Ktk3_>5Ef+36}ETDqz3Z7^U zgsN?Gj&<|!GQk{#v#QLhLEgeSo84-+hhP)7iH9+2;PXI`FH!8nE0i&0Z|~MBgEd&T z7>G)G9mx5&p1+pNkySjOa(Y(iE|YLKSUIAKSMSA13IY1I{d;u%){sWgEs{DgCBrBl!Eao zLN&mPe*%MnDx_z;>|BF0_vrCg5JD#?f>!JTtzDOrqsNKYdaZ}XVGAoiZ*422!}jL0 zWYai!*gCNi2ObBqbezU#0}db$#QPRx!>(|78M#*N@2p>YI?KnCGx>bPjg&JomC6}S zN;0|D5SC`?NsCrgOof@Zd%MH`f+(!3*$=*UmY@a+OdIwd(G9$@O{0 zu|ra{gCS@FTsOEO6ay&mgF)1hK@N#rl%B~7nnAp*h36V1@E8^6afoUKDioy6ma~XsyLT)C7}z?|oA_nOLptDs z(_RBPC_^&LGxf%}K2LUye@D@)U$JYAj(1J6qlS+Qh}uR6K>~A zzV^23z}vq)-eiLtxBzHu!uCwcw{x^8D)4WB8tUIBK{wNw_=Xlerh9 z;C@7@VC~s3*Lop1)It+w5D8d1h!vWX=Dxd@l4VPmFJZ=%Ig@5hn>TUh)VY&qPoF=51{FG#rVgVAjV9HBP^r=bN$Z$% z;{xU=XhdN))w-4cYgeOghW#^U@Zb)!XU_(GbBU}+v^!?Lm5cV0*f(?Wo~7dDPG7$@ z{oaWLD^j1phY=@6?1c*6O9MR#kt}3RGkzO~4RhnNND-BvNn)kBX;U(R7BQx7$i@pK z*RNkEdgrH4?R|X)iMwO34=PxFfT8L`t&ccEeX`w=7c7^zRPRb5LlRB&z2Z8lD0BaDOkhKq}Z)qse0oeB;vA%KuAEZs%tDX@!G4egZ`Q+u)zvb%+5RSXpGGr))J^0Pdxbtv(0Mq z>_;GztfMr3{K0WXhgdV@zEgHN1r|gi2?dneP`RUzNI)s94?|Ef1ddTltu50*)FTxZ zO%8|zl>-DjD3U=4TW^p-NVWAKSYc8RzK`UqFA+o%!S6LgykLU~gxGKmridom(ZEBo zO=8Jyx$V{jgzP|r#Bs?j_rfC09oK{(1^OqZg?^fdlNBGWmqu!D+{m9gddwEVZUGKh z;DHJMF4*9Mp@gzYq@t9PN=9zE2AokkI{*-4tg$AULJk@w8A71B#+pKkXt2wZz4~&j z1NH=Jt+o;}Gp;>%Q1dRD(Q;F#!y>5@&z}R^0%x?|For-vcj_!#B^6DEQAh1%Vv9NO zP}Vg>5TUKMt!q1#>#xC<36=vii3FiHX##uL`r@n25UgQC=(R|tok>6&3*6*De@{f% z@4t7VFx?Li7<@zs4gV00A5(1fU7+TLDeB1=s@9(d`34Q}%{lMf^Upyia$&6$9^I%q z?6IZ`FzOhGM=jK01dJy#IR}sfMrnr@GPF+n2w^;c+OOLBX9)W!%MUrZn?UlGIR%A|ft>r+gesJ{!eQtjiSrOvEZCt#wd-Ba`bp&I zmA-oEh)1GPph`;CKozc#g)MX;!ji%;(rrbCb?^rvN>+qgjH3v&xJt>M01j8+ZXQoK zh!*TYh~N#6i8{!HK%zG^pRC1rACZ|%aQ3_?N^dW;s>xu^=9ius27B4llk~g?J_i|U zd`MDM<0^tado_U}tU-j;j)e&M?NMzofdwq8Lyc_w@sDK-)~F7mNBM<;A?y49&ug~e z6MR`~ZzufB3o#im!DTQ*6XYa_dh$sPp#cUyYFy+T!XFm(=OFM>B}1mwi4KbJQTpPS z2`zb&6lRi_z4YZTfhm(FZlw+C≪%G!c6p1i?( zRdh>QX0|6Sa&HG+yh$YX5lF)H<$7hj6JyAkMx+Hve1}R@`EDdf$~8+;R>PVhJjF+W zz62K8cn3ey$q$7tRFH%$Tm24#heQSxY*$F-0j>}?q1=R40hH1GK%6H2P5J&}aZif}@Nj%**+@E}mdLi8hp*$1N*8d-!&mKq2V-~kdr z(XGva3Kxx*Yc9*619Bu2n+PgOj+)w_l=PD)U1{NFvQi77K?bH&kw<8X5ShACxBO}4 zOdzsTo~DL`Ks~K$k(*rQE_X>w@d)Z}c>q=qO3t^!^|6wbYdY6?*PxNJW�kxBmM7qa+D7B86oi9s5K=%$AVRZ!U}P$<&`(HEPe{}{$R@6J+66I}#4@3fxH{z8!+BD+i(pBM z7tzvx;8eFVt?@;3`^uWK1cV_RZfdGkLR=oV#6>ppk&&#EI{X8?PZ)+Z4v>j!81VpI zSOenwqBj;njH_w5w zv5iI|jcEo;OS<_J5s6js9vcfte>gZB)VKpe`hW=g0Cck!P331H;fF2II7AHLC~5U3 zVxcDa$S4Wd1zCJS7^hUlqFkJ98%1MQzVgO1#Vw74`;i|1$LPnZ8Hj^KOifY`o7lxJ zava!^3{@}!7vx}mgY2sHLxEJTj)dcF(H4f&O%}FXtD`L6OzvK)-KGV z0|4AL9R4kDMRQSvj5dLy)|Ro6i`s*H3k|FV<*HFmE*bN-UN)WeZ#T}U8*xHFvXoq} ziMtUY4;iGw2Kmo{9`s(iAsJoBL^6gE-6w1!+L@?WCRCvXTtGt=+`fsox0H#nkclYV zOfR|1oK5q-mrdg&XS;Pmjd#F1&U2o(U+Rs5k%~Ma5_%v6Q=ICQkKRPE_IHhA z+VbAsl+%{m$YmPE37fM7=Rg+7&WR#w&F`M~z5hAZz4AnVn7iwj_&V6vi;yd(d97Pbv?SPkS`;zHcGtUE+aEZuAI{rP#%#YR}emjMIFo%mhWfU<4!*&>?=!xPr?6 zFfao((5QfqE5r;!F2VT7t%{Z}-I{ORa0c!FbON0eiu$V0`tAVxaAvQz?}h9xq`IYP zo`&WG%?mUPKd=UV&X14k0}{fZ@!(}%6hXr*jwV!(*LKV%IIgt%Zv#0;C2HdH2Cx8I z?A1=>lv*NcX2Noi&v7Jg0vAF@I>G`$$_m}^4dF0!I&dpK@SBE0c@8231;QXou)I!? z&3xhxV1ce)5C;3g&g9O&h$`OmZrw~u;b&@e}I4%kl1=TtEmg>e{* zWDbc3+|H`K?vU#~f)CNn56dpTp06kW*h$U|5it-^dhpDdRI6eD=Z(xqpD4$$5RAes zaceMCxrTP+uM-*!poIDY7Di!Wf&P4wX?T@Gz{N(IwQ4%>rX**r^Z=Q3jnyAm}c& zn!+3X1|0K=r^pWov*!HH;2`_}r!wp{n(zQlaUk?X<_IDlB~XNdLPvIO3iq)MEiy#< zOc!Fo#Xsf! zAmlF%LINVbvJ73y42x0>lc!q3@&IZCfkG@5)p977Mi=s7HCGcVrSbq+ktGBY#jbLc z80WSUlGAL$a&}D@ck%stkqvX{G>Nk~Cz36bLhHc9Bk6LAU?O>jE@rICBwgpA7l8N(HMM4{0xQ?xp_8F{LJ~ao1rB0kIrbnV!5KW(4muWPwO|z_fn~K|0TXZ_ za1Se@^jVK&ATohmZFXmW!cIRBd0M1eqw_=o)%jEuUT5OX80wE;^e^vBC2NoaJrs1( zwZM2P65Gc$RIownbzbiE=0-Ik-k@4~bE71JQS`A2IaFXh;u8vVVH3hiQDRF~(_wE_ zLUQ8s4uE3+J>*OkBv><6Bs}&P5Q1elb`=hQ3}(R&?0|5!AQ(!4abK2Xf8k|MRtr!T zW^v9<-!wycwn+L5XFr!!n}R2N)-BPhWwwb=`&6y+qG*h^I^AvUBx|nz=v&95{CZHsvgT5UM zXhcd6O*s>6MFM3Bmt+xwa91I7*Y|NhLJMYLeGfnqGPl+e5Lt!Ol1A4^&O#6UD{A)_ zExQ6IPIo!EXD7UF_*i0S{}eA^7X@i%zHB1;4hqiVOpo49ciDtS%hg;n$q}I@eb`{r zj3kx+WN#Vb@l$t-Y-_PWlu}ivmr6Z?U<))%vzIDi;DNN1HDf_a39Ad z&Nm_8_W&xFWa$?fTDE@G*A8C5V^?7nCigdktaEeeTmx7%-l9)bQfIr^B2Q)}>{L0! zO?t-a>%t8>{j`DQ;(_@~f+x7X;EWpb3sK8RgVBV8k;`|1350nN=Q=G44}ue*K_G;3 z<~m^%>J=o$_HxA0GrKM#NYk{`wjyOXA>6iM@wQcQP$Y<;lk)*XNx~IN>Ndw$a$e$y zk7$XHcw{zno40rcfMmIRU09b0-(x?ved}@zDzV;w6 z(*XxUp@uRd8krzyDMa>@3Sqb(H@SMP*N3Z=DreY0O*tSBrExCDSX&v1f1wa6BBGhN z$0~Og4nlrARuXI$c-MYb%D1zcHN44MpCEkc${Gr zsP{yuhZ;GHtewmA$M7$nMWRTZT0+lIM#6TgQ8g1(bycm1Tu zX%Ds^`XG*&5ct6xkYOLt;TPn=8-hU|pn*BsLVjEJ0N@vxcM&2#T6zVWD29floAtYS zk4vP)DUPB`3|qGqn~55GBhO0&<@1`|_>Hgivb&j0+ypxn&L#{>kbIiX_}DIam${~P z*mCrpYeKbMB0kA&Bl6QXU(Uvkq+f3@digN}sTU1+Shr!-HDjzL8Wy&|cp6 z7gYQgFnYyj;TPt?AC%h}Vw|~=0U5lZI&u-0=Qn<}K(9H%DV3GHy;vJbI%kRe_qL>T zmdd%d!mxAO!&$Svzil}!dql-sGo!h(TiSuSd5-xarw27@^Q&nG9GUZMwAr$#i!8wj zIU!Ba^)@1M=B2D_O&4RENct6RF+9UH534)*6Bc1L1zoZ0mNmN+#0U0nb1%4uS;8r~ z!3E_3)vG#I`5-`+6z_Mh^H+h`Jjro_ze1N$LH)?O#3Pc*NzNO}8MZYIl)V>W1n7{Z zvDqj57x~VL%V#={zZ|FEBu>UWCdQ~~W6+$pInC7^BYQ7Wt@h3TJ9AiZVr(It9_w5u zDBMV1_@99ex9c_*>UI$x2zzN2ZV|#^T{Ej27Tm?U#MAV(pYSD+y9`Yg(i6~@y4%l7 z9VkTIEaaQ7(mCH%XerX$xz=*YRXWuf1`Rs7Z5N>f>Q)y_K;dCs)}2ToR>r=MXH3w` znsZ%5E&FwQ{b&z^5mq4>3Skgv<vDe;}uaGNz{0MS7LVQDqWrMy5t z`G+0-r|455VS*SKvh071EbrZO0p2I}y?>9~q~AW^3BKU}y@DkW-YC|)lo3J~zo-+iAFPpX5%P|{g_B${X;TKpX7*fFx`ag$p*BkY4j3UAenF2jc;~&G)O}vr<1pxjSHUB65ADVv>^w#m(0+Gom5g8F zmYS(St+uVcx6wTx5IY~Z^oEmw>lfkBb-RbxJ*Z6l=7`%C$u0OPbklc4$g95Ybt3N5 zB$?6QZ%UVj1b%=|T_m`q?-K&>O+fIIg2Puc2>?Qejv_jU=vWjhpTdRtbbWfUW5ZnKWlIV$|mVqg68p{jybP zP^wgB`t0nJ3a6n|w(bP|rKqOVsZ?uHd5Lw0N`L+`nfwYitk|(+%L+V;Hm%yVYKxS8 z3pcLZxpXtu*_4c*KTezoG5HHPu;9Ug>t^Ki&)>4SoR;+s374>BCL8}^EPTMS<;;}J z@=cs9)21Y(OPfB8I(2HptXsRrxVqyag|TMmi)Est>W!ab>0+qx6Oq>$RU1EUdJ|WF zWGB;IwtR8($<(PQ_P2>RSmfMMyVVXpy!i3t|`AEcJL=%zppAB7+z%29p5*rSU^O0~s`D6Qwu zFmBKXrCb3{N#$8lUWw&bcjdKLU)6oN8C-8bw^v=9bh4acj-5#ei6(*hrAC@zCKq31 zZjwoNdhV8GpB(YIk%5aCD1%6-iDZIp428F6qe*1K6(?m8R@WPfxhWQ$np(;geU5VX zou8tPO6pijo*L0dX}VWxtFFGPU6laxhu?lx7Lm;XTDWjPIUA`};6ey4VgiF|X#tKF z21b~c8^icx%o~9K=gu4xM;7y!B4;OG)5rPDb=TuPj4G2{vFdf%W|JBqt+ZNcYsJ@y zgw~*o9-s@c#;)Zg5eDi)1VK7D`%koi7zi9QFBlPni5_AUu1MpSbgo$HlErS|Z#*1t zO(hNKV=#TJ(g!NlR6`0PjQq0y$|%2>u?i!D+%c3H3J=LJRbE{6E~gTo4WGrn3lu8v z!oRg~%ACAWHKitzDJgg&r7}#QdJaz)&>JCLTX01m z%8?0#(^lwf;v=_Q^HFzZSYK2pKiQr0&2K*P32=ZX0o$q6!yd8`aDfc04}jRxHv8NM z8c!&KH8!CGEdW9b|wdVX^3zT=~lMd;R<4ig9-;Q1|!~aivxh;0B-*Doa@~R$!+6I5 zutkh)Frq{tq8wII6fMmE$wVq9VT2+M&$Z+p3z0%|{C8Vpdwqe;6SM9Y6ybEz|-n1j2|+;7SMk5J)+6;0i)y&>A`b z$85+^j{_)V5lN_$3zE@=B& z&_WAE07Eu(aE(PApdRqhr!H|bA+`Wi2liNqKRRKKg*L>YF?c}?3>49n=4u`oVFX5v zaRcgt>i}o}utqb)p$L&;L=m||8ZRf)HPU1(eXzy7Qeg;t_@k%Z zn1?^Sfs9~y!yfxM$1{Sl3R@KA7Yt@_Q(g2_RBfdzpnZ!~Wfi;%Lvj-w+iKOubO6lG z=MB$;9*GZNKeNt>Iw}sO)XGERw)!J9qXDeZ%to5xwGIFsVi|!yXne{`+5CGpyk(zvUnMU`7L?AL2)$U(lJnstSHOB06oZ9kC83O3 zvBXIlGx^3CTPBf{aBdzSD#z$1jcs~E8xyd*-E^(%KI6@raqG2Ak$Fvur!!^1Aak+4 z#PYHa&JlQsfE4gx!8F@DW~^}5*a)vU#nLhidt~qyj3B}}267Em_^=53sL(rI(S;0N zgXB-hhdke=2?qpB-vDw zJG1c;sb@<@#>=QqwXJ6^ZP&%ygpCr;u#+c!54lzC_AzX9yl!(R!9c#*XKosQ?(Q5w zQ48T^`4pc7j_Li|Um-nXuzkOPCl*S8wY%%@!G|yKqu~!XW5gvMRWrMO_wor4AeJGJ zWC+Arnb5&7o^Xr59e)@u$b=SjfP5J+AsM`_$08yi0~su0=DnN~gw7Xv0l(HIzcgCf!(3L_|j7zY>z6^)??OyFICLx0Tx4b6c6T{=Mw zu8?&XaUxu2Ij|OMvSv_YH+IyJc5K%$U;}r&*B^AZ76#{m4a8x|kavJFCW$e6U{We= zB6xK1VumMHcmjIp#(0iLWa@TflGk~i=VLb5WAnCoN<$ldRTnjw1WqO?%JU|1p+6j< zNnsIih?N*vlQpe3f(OS85I_z801uU=bZ~Kd5+^ppKyg`!hI6MMYN!#(<^sWm7QqFF z1Cf0)a0@b^3;IA0x=@F8xP5`PbFDyWz(Ei9&>c7}Owk)I$xswssn5JGdiZQKd+(2ZB?QhE!F8DU&kD!#}0sGA>j95_Uj~7@-BU zC<%6;1sFk#b`Ti7s1dZdi}7)I;RAZ20)#*ad3u$37-1U;5**1WjghxZ3#D5}Sc9Sm zGt|}*g%=iWr5AkhGAFh_Q+OS9Kybd4ifE<}e}Di8KmZgV00N)}O7~=~Hij-SaqGyB z9U&kec#3RM1brw2Yj6zu5DyrEeFT|((jW~Ql1mJs4Vpkb2cRADWkwuqY@I0;TYJa z1+%aUk}wOBZ~#Ur2}`+)c5swM$pk}Llt=j&t5B4`FpTqoN~#3^SNet}$@q9bs8@Pr z8|iZ!wuE_+mu{t@AvQP{NSK5N^>1<_Go<8=9O-0!jOG98yK;fYd{R_a9PnXa~Z)5V=#!H z5Ck)z37Vi0Ah9?`U?2|xITHpw(LzQJXnQE}YL_^HD9MQ#=#noPiinhZXNYi_*&vkp zSNT5@AHG-*3 zBFLQB1X;A_8j#7G`#7O;XPN)8hRTT+1G$+5nGYBd2z>~e`=A$<-~&0}qDXcCpWvcv zpb*TE13-YIK)?o?01P4K59)CMFEDh6b4kYFk)0HYCLxj|NfEvIb@FwRD0y}VK%5LS zY)VpWSqP$Rv!S5noP2RueL`Y-`3`zv57Y1r{xCYj&;hyG9p1-T64 zPzy3Z2;v|Q!}Y@iCqX$5v?{}j)YOSq_GQ^+^HAmU!mupHHZlu7vulAxzVd6m9csr12CpdlJa2%*e)KD6;}u!OPpb{m!l7m-RD1KOZ_ zN)`xuP@cr8b~%NY8YNgbuh|4yAtoNES`lT|704O0*wmq!Sqg;UH+29F*~bobs4`9< z1MI*AGT;iFkbR$U0Q#T{*^Y4_lfM5XqG745(4bEUt z%i#^dP_WCf3X`A_MtJ~Kd7kD8GJO(m6&s&FV`NAMZ)d3+a+R@3b0Cl^vZPT5nJOJ6 z3nyc7sh%{K-S(FcnvSg`xLKB@7izN+p{lz}RhXGBuzfwy{VByML-P2#t9x269mylM9TrCwr8S3(G?!w$5z59kmK`|t|}^#*df5!*?@ zy7CKtXQ0(KgNb*H<6&gJC1^fax*e+#jH+bYvARvhie2(1hr2wU1bAcdmrSr6pc)^5 z6}SWZNI7ljs9&1{V|%{VIs=2K44Ci_)FVC6^S&Dqx8cg0<@%&mfxnTE6Z%^f z{410GtEB-<#1*$C;kbgY_#Tq53byzQqaa|AwYU&G4{h=bo50A9d;m_#i`&VBGc!uk z*}+{oZcIaN8v$fW!?B3E5xRu`Z>zk*q1U+0Lt@Y{N!=K`EX!>k(Mh%Y!Yw;+xjR2Q zT*wWSN#Oy+IBSN*%s|R%ywEU^c*2lOKn^mH3_M`XNSl3YkPdldQ0{;cvLGorFj67` zwk0|SWBk4OKo45$12cfe8G)lSfMhm`qdZz`%kj1&QO9t5$8=l2P^!mp5ecxs$9`O# zP$gAp7{J8L%oRqsl+=^sF$)#Fu$%k~$Pi!#g$}55lm|cvvyjmjeYr%ropfoSnlUQH z2%n#eji-FVv;;pT%*vBJs%>ktVMTaH>~@FUwdDolRUp ze>I!T*TmGkv!$?F1lN%NeVnifb+`uFJPd0v49SoT<1ndQo8z#%}4>RnSQ&?rfEIyarO!{0N$?TDn3Evsh&|T0B zGB6K+ArF}#1M*P+kn^AgPOuJr*bL1OJ>bBi_CTWt5Du7d0BulS2jI>=5CCOBn!mo^ zdjK{Xz6&wN7v8LTJp)Lv5HoHL+NA8#Uy%f~kOZ`y1h=q@-klMGa1RR6b3F&r znNSG0z&J@@52P^)Za@g7Z~#7Z0PBDex4;b4&CdD23o;-Gb&v#iP8xQg3U<&8c2EdU zu)3`qDV_lh{7|?tm??sBCUQ~3Hry#nEviBONNF<1$o#uFOJS5=Dh-`|Jm9oUP`ys@ z#CKSboS+IzTad)i|G1DP4lK&7vY_D;E(?`_*IJtqIq=}&%dCT#&bJQYGtdUUjszHS z;`dCEol@BNIKOxt<1R85)S#kyq!+M|4T$hykbMU{jvl!Oue;aKoSuadZMceDDvyEW zQntbJF|n@wr>l$8RK8L~oe_4>bJCCw`LGYM;8(+N3wGdF;E)9BKpJQ+55vgTiUrd2 zfW7%Z4*Adu%Mb|u=LWcd=cE$*ZO zSf z3~kvukA|6D1VB)&K?q zp9FT03HtyBq>&9%P8!ibe$qe<3XutfkOYO02}FSUNznOrVEOD2shiNaEBnh-Br+p! zCUv>!4w}>|4?rw$_s$eqlT}$>lo9ITk+lCB$t;;e{3`-n7Y;Jjp8oSbzXn0S9Mq$% zN3jfo{ni@M2FIZO%gU_ve8wVi>_C96PQC1go!DOY?9eV2u%Pz+ z4-owP|NY|^DN>(12^B76*f8Oi9T6o?q&V@CKYzpA9N^f|<42GoMUEs{(&R~$BXz7~ z+0x}pm@HGyq*>GEO`JJ(?&R5%XPr&S1ajiU#OP6^NtGh?$&(W_e*%{+Bif138=6bC zDs6g_=s%2`G9@8f*6dldY1OVxGK{Rcvi_2Aj8-q-B76DvmAy604%u-@*paP6D4iCv zgOibsMz5Z{efd5SB9uf>WkIc;EY@P}EnCo`&nCmTj8IOaAfNK1iq$5k(;SzY+*-Rf zSbuf8&J^97>~7$}g%2l=^WQ#Z4Wd1O^iSla1ICJntXSRpb%}2-V)U2kB+Q*fWQ>;q z|6}@j^gCm&XWvphdHC_=uOYVY0C$4N+W7EsfdBvhKFQ|*dU61;zmRg!WxxY+IADx? zB6RS8HrhCbAAa-$Fb4=F^kIe>JOW}w5=$&m6HNrd=o07-sO}A8{xRka?5v~03x_yL zXeL-N^zp|ZvoQ!Ehl+G)3nOZL(U^=jO7F?w+LJP-BA~SLN-VR~a->Z*DUB%G!c1*T zjyM79AKX+djVey8a!n*Lw|bJOWx~ot5a04-%dI4EL97s5%8JLXBqB?PtWgLNz*1WC%8-jlDq zW5e}nN^)5$0)}tXg^#{{h`|WW4EN)YqXYTlkU<0I9VrJV24u#-10u}F!hNE`u#J!Y z6F6V~Kr~TA6G>!46JWSwaUvLHq_J9wZajb?9c}6nNFaqY@??j+pn~J$iaoom2&f*feBNi3EF z^wB0AcO*;48feH$=9+QrfWZ!Mu3fnwOl$aRF@sr;8^;VN8e|%Tjl(y~HO@c){t(0WKd34fCx`&T1_-VGelUTfx zW!PEdZW!-4npp>wyj2(6(o4UcT-|q%Z;fU4F&;mDD&eS-Y{bFDhcUzv2b^Pk$RQhY zju|i>a;WJ@mTagQBZnN08RwWB*1*??HuBEro_GH_W?yC^bb{gkKpZLJ6H~;4F>NU zYmPP&BqlK_2N>aPFrphQ5wR>)Ldi-z_{Esm zA_<=G#$z5Z8cUAtsiPfbK)iMp&mRi}hcD)pgK-!r8#!ph^Zt{K@l_%m2av}ad~l30 zv_Tf+lg9xtnFCI2GC~JX#yj|7mweCzP5)3HNdz{AdI3m(BH^FJfU(MdTmp6mJm4L4 z5{U(t3>FWJU@<2My9zcbk5JmhE|8mXE;YLgGEJ8~0z#bfF!#s|Wx2_fJ9ubPi zKJ-(P90X!vu{_W$LBciTjj-+w1ti+WG5r@k&uX4%m^Mcb{NqJN{OS=nAlaX zdo>m{TLaLelu(-}j8$y9iMiB3E=x?2949bR&Pv4-EdpCagx*O*fe8$rk`>mgVwI9G z?PM9NwABh>gBrjlg>#-e=SvQt!G!Wvwl3OG7J3=Az$KX9-Qf&g@YV)%f0m^eoD`0<~4I7SzY ztb{x!lno^Kqr3t+<$zR)CV{mQtNqHyzx2h`{Dr6^CSt=a4=~pLm33nkL933`suQ*f z$-!`ipj=tDow_==DbRI^hCTe@;(+jo)=X_S2Meo?yx}T_m0~`V<~YTs2b&yu;jbXe z*&f~{$2>fG)krP58MkmH0ko?Gt zKb4RLy#|fG1MMRR{`k*695d8Ph+_;K5yw6Vf*~|b^#D~Ji2K%X66kFeBmi#M3`$gB zG$9xWL5SFz(FDMWG`N?(Tx$a(kyZ*v5F!+$tG4QFlRKO1*TW|EP5dgt5?kq4p9P7E zReTZ`!|9vTnQ^m;^4Ls7c8Hag%nyh7LxEiu$e^i%AcpZOTMb!rHZgM0a8ufvFc~Rt z;Lbp!Y&$7qxyo}C-D?$EY!4gv%R6yhGEr#Ho1ED?8T*GO*kB@8Be~7d6-l0jM`wV` zEZ91b?(V3|k9J)*m5A z$+3Bs>^ZTRR{d1Ftfmc|YL^6PV)=McNi}=*gKxC zHSC!m#2CXEinqXjV4@A{s#OQ0O32M9x7CV|cgl~OytQW}( zZcJwFEKd@!`#%BvKM^Y}d5amwdA6QNtfrWvn`jz;pu0TbHeJZEPv9ZT5*QfhyRs<2 zE*rd?P?{p+Ja-d3usAI^VZ5W@jwgdMEsDI!!!p+zz%AQ>nRtWEBf(s$3DBbm?MSty zb3fA4If-LIehLZID=B~jJ9Lq=j|(}+Iv)LK1D#qPSn>flpt89Co;a~>QnF6$go07L%uzums5g7lqAZ)TIodZF z%(s8LMCXc#$RRTl6q+4Gi5|q57*RDLgg7F^2zMDIe@F&S_%xD8!f$D=E!())`uQR&?G#1z(1~X}swj;cr zVWAk)i4%eiqA($B|JwvpOoAV3MH#?5$xy|3lEtZ@#hn1f-O$CL;YDkM3aSW36|}Kp zG)BqmH}C)tl$0%K{4EwS25FqeGBb&5#75EEM*bPJs6evo;)G);m|tu`Bs53nV!gd` zy*ztD+9QPefXk~wzlFRoK!wXp@ z4FRwmh)5EdNIVEl(HzY~#E5KA#F;pVM)b&!bR!Jwx=Reet(;AOD?nsJyPxTVK~j^c zsEVslw@u7Nuwb@%BZ^V@#&T)}%E~Mp;xRpG#k(6KS3$RBAco)EjksINcWX+|3yC%v zF=0F*xwI0=|H{f4Y>#H7O@@+)n$V7~oW}0th_Z|bhSNs0ERlL?$fDr{9_WN9JfiXR z2)dLHyR<6~8!0DrM;@>}(e{NHx?6op8?p5*p8&&mBm!AiPf!IXeB6xK7}K z{`}8y{~X7P8&L8nPy^kgCS<9P^M}3cODTNN@1jsrqtJy6OzRmXdf*Q#tPuV5k*m7U z`{9=eDUbshiN^#w%fw6~+{}9fkR`|iU!7544NZ$gvVTBLlgQDA0LhSKl94<~+0;{L zB{r1|&MlD~BSk#!zz`Hm!F3Z(jPSg`QVJXL2xbVFEFGl-Xil~OH=-1TIw-ey6^kxO z270a6pdkjqQ_~Q1z$UH9=~y-<1x_ZA9H=~+Yl70M93n0XyJ#&oir5Y9=sb@QRPD&d zLN(MG*j2Ucvc;(cMjZoAaF>Fyl>m)1Nxh>FlOvO|qfDi}1&x&jS|BZ))&8g#MA|8F z|B!|M09F40r3v8=>>CG~!v%ji25}G{=%I#eIELlJzHF$31-S=(NQc_X2Ynz1mHWM? z6$!oj1o9!w6-5(Wy~lh(0$)AbUkz5ZjlUzi(F5Sfj?7W5TUJR#$!Bd?y!|!XBr)7H zv1{eL_&alFSHqP!iuiUPW!aDp>z5cG+Re87YUS>HthiG!5YL0d!lX;HHE0VIF}JwRIm&I1|k z2pNrp_+v90Rn53%&AH{6{-aGFeO(J4HX-F(C)E<2oJLQiNqq8GnxMBMinlC1fW~El z#(jYo2!zMwh;xnAGfW0l!qNzFw(EqF7Rn}`2$S#BL@~jQIF(b^yHaMm3@1u_}3qP_D`bSpc6LP#!AG z1~}L~=CQeBSYvAN0rIMldFVMG5eG(!5Pg899Oxu*m=~rM!%HFreUK2J|C)ygSp#yY zLhT(Nkf2OPddpn(-(3yh0WM%q&V!G@1CA&}H0inR8>G`jR)(;!Y7t4;jLnTRVp*0} zBl@eAyb^2O#RJIU!y=)?5@C`c1Qq$J97D+-E{vwY$x-qqbzkxr;$EA~ZjZvLIK!Wn+4@}^MN&tr+2{ir4f%@48 zuk``<0*84~V}wEIHi(P^Sc7yJn(GfO{D>3H2W7}P7JX*`{}$j+&grxLh#Cd6 zezei~%TZRQ7FVX=U@K>&9=5$@Ji*#dX6r<#7Fb};9BVd-VZI4tmW(BWv7|ue7dQYH zX4e@0glKNDUlv8K*cBpO$`3|CSs9^PaZ@H>T_UC-IKv4o(1N6fCL26woTw3XCTfd) z;t?T8o4&_Y)z;p%VjgId<4HFGJ=uNEqkbL+uo$2h7z5IxLArPe3e<}z9Der<0v|J@2RIe=vl6OquWW7cb&K<2F0 z>UcZraDA~vCv=_Aro?+8L+@q4@@6&>CzAJi4OO0 zAi)U#Wb7*rUVJ8AeeNBwbAwE*eO}iJ%2C|Z)YC%sfS+(hfeVFZit6UVg+P)1vvPIU-+~i2!>K< z(5c!6Y^a1;s002$bLJM{>6Y%4@Ksod^X;4SI+sz4EX`s)2qWokB}t}NcE(t4b&%h( zr9N+Qc{U{CSD8GDMt}4j{s?0p*PS@mvLd^jmkN~zh=z+deY6U?fsw)H~zFz}+ID7;7 z1#ED`KwyOfNQE{)f={y$XP5?p_=kJghHc0PADD#@4TM!7HBROThNp?@j(8za+ZioQ ze@Nwqh~QRs8UO3i@NRnB-!k(i`EW6LMbGp`@28gkh{wza#ziejcg0MH^Z@7A(nXKM z(|H14GGT1I1y6M?q6s(12DeEDa2SOu|51fxxP@dehuim{uIz~UEUuqsztO`9te0Zf zR+Fyx`VkLyju87|A$w#8%LS7NfVkvu;6Pw(fFMkmaK?cHJ|04hD6t_#iashGW z$A2FGRca{G;lmt08s=kWQX<5aC-cD!G-=f*n86NA3WVf9n`7&yA+zW2pTA?mVEUN( zW6iHCEFU6)qo-k>s#Zs0&5AV=wV@w9Qp*;}YE?XD&!SBW3)aWAckXQ2A$Km_x^&+d z8<nE zZGzUXfAq(R)8ppeo8R6veQ=WU=Fg)~ub%LeWY@qPD6;8XoCB)%Z7MQ;KmY#zJMVCS zT>}zGAYNY~h#)@(DFg&&PeB+VOO^P;kwyb`!U+!>a>xTGo$RyEK%A`6kPIiHn4*d+ zt_TAR{~6Ypj58kQ#xTSDV~jCxyfL6a)-l+ikO<8nVMHWV6j2+M{L|4_{Dg#+L^&u2 zlS@yLbO19j&GO3{Yvd!0E;von(?0726HGNt9@9o3!N9bJ6Tz%f=TlKlbpTmaNd}8o zAB7c(o_kuAmZ4_pVHR5h|NR4s5d|8Ump{X}0i&hU(U|FCmvY*vr=Nlvs;H3Fu}Lx` za+2G3--&A4c0}<*kZjv^LdY9|Ri|A;tLnysZ@>B$Tp+wM0W4s|Hg|w@(kaUXr@3Ai zt!T3qhAgtxB@?Q8+j4uJeuH(f4kIEx;m=;G*z?4w>$2OfUy#Du{v^ZQ0W3lsF^Vq!r>Vt=*@&Y*JN8K6j{_}u(2ye& zS)_yxS@aM^OESq%g8a0>Zw_Eu$!|lwG2_E8pD?pcKA*hu%0I_o^v^ubR1>ogG$AL9 zQ$7T;N*ubOKe+IE|IdT??g!S}`$rl@*;&8CL-cQj`w%^_ zKL#JX;TW78uiYjRQ{N)%ow;qX8<}X#F{F4|7qUnslb%{KiD;}^lmMKZiGkYl_;5)kncOqlVDA3TI9P?1X2$TFEo_~{>k z8cEkWSg5bz|3M5(NQfqY@sUe(%tr%J8}8PXy-c+*hBBNX4dsS6e~hLyq+^YLoHLTx zc#a@~3*3nQvKqf^=m0zj#Bn0`o8a(3HBH=2bav=N)a=TK{#iz}W)-^2SdlrM^M`m) zr@AvHp)hrLoeM+)j@hXK8a13_4RyD>c^O0#dNiT$UIwM<5RZ8O;zx-7wU5DdVhqjO zP=@?5u!e1dMAc&vre2sSH`s_M#z0}bz()}AX{CH4n}Nwh@(^NxLma+PSw?yXrAmM! z8wW7SF;W?`F@z->ImkgYK9cDqZ ze5_&({|^boEXE)PuI-63p@>8%s39ny_1(O4KafTIv1DFS}%1CD;ev|V=WKnAj3|2jY+E3u4N z?c+m>bl!)Ep|FK9j1!yqQp8|zJ z5O1;C4oDlC87xu==JewyA5>~&oSCpjmK~FTo(#5Pckg9{M0hHVCg zA4J8ogUW+sLL1uBo;J%%cnB%S`cC4$*1Viquwuk)<};(&T{p}jb$@#r!T>H>#Px@C zjjKe6O4NzI;ei&MmCrYbRB>2&L#n1j-PMe-jH1GB>WWb2zZ8KG_NWCTMgfjms7n>s z7>1(L?CHXwH@(Ie=`|`_pMGeV74v@(IE;YcMI7WyDHjGRF z8+L;svtqXD;DJP#N1>KWh5ccWzGOJVY{)4v{?x}~JY*hYz=RKiDGL=pzJR0JUE$M?E2k>z`=8+AL#A@9+2u|dfaaqj5U9WtMcAWNhGLCWQUz$q*Yc7vDI?JMNi(qDr6xr3`Q%14JU?<^W$5v~iD{=U@dQ zihiCWpoK^jK@-}eojJ5_M4GMZGMZbCZj4{tP>X9MgAqh%$S72y1zLDK>LXcpq#j)A zu>$5_TGuar1vAvhz&h5B+(#ukAuyyW71v9Bff0=GhO$Y@I=`-Xj54l+26t7$RIf|3 zpPdzw9U$5YnYIbT=V4cp`yuZbafxM-jVJp+mvdEo4t%jC8CPN)^Dqe#z)_QZ=nt9n za7RPFvhI@Xa^Lh&a+B%d!73ws7qHMu!%Zs&B-l?P5l_g(J(3KI|4UskcGm%IgKzxf zBVQ!C)!U)FQ*y`DVcbz@zi2VFgGOFsLj zzIVRkQDhnJi^@h4lAnIP>-0tSF`Cq*{TD{qNeG4X+I}gIf2rLIyukOo-6h0btsMZc zRU9U{4JKJ2S80-jiNyQWg`{YN-;GcC{9XA_Tl*}C32sDBxz9(y(nH`<4iv*fv>GOy z9=Yj~58zVdZAm@ELr=6pHmm_XkONHc!;dKgHNZqX$OFO5gCb1HF8P2H@PeL6gK1?2 z2Jr((|J1D+Z?)O6JfCFb%Jpdl zcYM)*G?%4l!7BX1ENDSP{6ZlXq8&7ZBuo|=h=d}}0wOlzEF6GvVMm4FVMdkTYUE0% znNj+sM^?RI$8q3X@XpnV68#+sR(xIl;g_p5L{BtH`&0-32A}{!NF^W@+5LdP^cSw} zT?0Dc1Ipcv5F;_(#&sl{R*d3Y2n4?Q-TYxiLNvtSO>6w1F(FK{(VyJ^6L{ z!cPX}0n9>D0wp49!7S9tP$X2ez~ty;VsV5=yLjTZ9L52B7@NJE?rR@}fy6ef?94czI-CM711 zIHpcwMOp4ZGd77SieNM%#7Gbx3UY)gvOzJ(LabN_8??a~{1pzi!5Eh2X>u6k<-i!E zrpmOz>gB_1##l2cmMq*tkr4%LMni_U0w)+r{|>-`ZTf~o9zZ0Z;FC}TEKoxieqlxu z%0>p2M-l^q$-s+@W!+^@@ondKf+ro_5c92M7Wo$RC63A2#%;{mMs$&EjK+tI0^QgF zBr>H>{sLAEWg<$#0VHK2uEGJ>K_N_oGgPIV{lj)xMpiOMuDDBAu8v4123T6s0hB{{ z*3&YoS6XV=NthDKAW4L{Wt4>@8>2t+l+4Fu)^6eeMQ zN?G#Gy$D`rj)X!SKnbE~XLeTL@g7=c;|D5)z64T;K7AG!!IIii90VqDVxg9T37Y?1MKT!=cIwd@cjY zF=%mY;)6n{xA+Ap`Y8>W4b_z*hl-$wR)i@H4_^#b8^~n}=IT(m3@t(i@o;3AUWCAi zNZIY8bzH*S@Mui|1Ck0JW)3MZSYwe|$c16Ww2cg`=8MS~iIlWNlfgugwZgxo!{Gcw zHWXwl_y#9j0=pssOAsd~kSR<^LmQl_NI>L=$>mzaDWN=EAW_Iia02yE44=-(sv>N{ z;too(S$Rr^NQLTU#F?jFCA$D+|D$pOE(F6fOv5t-!#b2gel`T9HUv-pLMjkLtQbQt zAVV_5r%mRh;cUjJg2zB`BKn62>3G4!8>(97ZB zo2vPRhoaBa&XTMKE36q(A$fujcmlE}t4wJqvmU9lVqK5|fwXcawSHh$MVp#s>nf8-fn-;tamu5|EZp;c@TzUfTf-q?_!ig&vvfdcx`%Jf=5^;;ISn!*&tQ$X?Zm72$S%r0BZROM(}zDp?#m6Q9P(yy3A4>)KCfNyj*_+) zV6>=76fI9EZISYn|B60H`0gGMXd^*v?Hr^p(C%p1N^kwfFZr0QG>U{asx1f(>HX?) z{$^N_9IcY{-?`pGCqzR&MvgRWN4vJGG;k^3j=>TzFt9vu1Y<=xIV}ZS@CDClzw`u_ zcCZJx$f_0r@pADi!*YKxtV*JA9^M9Ic1GzYYF`jq_~fvsdWB&0@KF&&$1;jDc!M`M z!`RU75zE6qya7@&rBO=i6GyQW*DM*ajTM)N<`%E=#xmG?F|v|k{2lVCMeT6bDo?W!YH&bFb_p^*$QpMu&u}jF<{3!AOq4k z!^cWB(mVq)tb;$mZZ&vpL##qm0wN;Xfg}K;B=qOZVl(jGM%-|763BF55M54-iaa4> z9z)|`Sg&2SbFM0`f}rSpNk;hkzziUPmko|T$1Bd^AHsa5(t|ESPk?G^gWU zFb0pI|0(CKz``^ojWA8SGF>Bgau3E%qwr6A%7+x{b{I7<{{t@jMd%R1D7=C#ltMB< z!!pc6GJC^1^cp(Uu071BfYv7?3Mg8awNGNkT9?jNZZkJesAM$8@+xD%d3G_^y1f3VqkN z{}toYu;n+D^E3Q8o3&|#9u3K_684dt#QH3Fy-;iLwAzECalW0NeHr#>BLrt(xDe>G z`fm7TMD{Z}h-DK7PT|Xl_r?8MqowyTkdkeCouM(@Lc6~BN1Qg_wyTWaxD&Mk9N0Es zgu*-Y_?~Ofn@-sUM=nbnx%;GYk|!8l8~1U$d9dd+bCV7s3=U885Y0*VQCoKmnK`eh z@Y=j}5?IV%$O!Wa`*|^=F@(&auiyu=S3~?2Vchxoqz|gWmzv^Rk?!BW$g@avSPH%p z@l3d(HwdCD_F`MdV_Qa9Iv~D<6=hGld%>~D6vo8GxkhMur%O5?hxksRYqFv?|2P~u zBb)jpZvr96K_SS&8Zg2u&^WL}LrPN_?PbL&bRk5BvN>U-ttNjI1}-CI`e=iIxO?T1{1Ha)8EJ|OJm7_R zwK4Jml+A8>#JySksZ%m1FhU_H{^GB}8?ZqnM1#7HX(vQNLNYyspapaK|-HGr7$#{pxeBlz#`rW)58oJ+A;7Q6xi{rTOq4uNLp={{b8V?;{4b zv;Jn}#q@gnw*wELKSqldxY16CswvGYQb?OX`21c7@Ic7e8*`pb6fz@?P8vQf+i&fh;{muOz%Wb-DY zLV|V{^2z87BQ}u^L^2x6Xi<$z8HNhgklICRL^bNka}{e=ty{B-$&tfHSg~Wrwz+2U z*s++LWVChr7H-_OFqqc0dlzqBy?gog_51f>ks?V5CjopIabm@b{~0%S{1|d%$&)Ep zp1f(3Kh2ytG4cHQGpB!=L6%@h5_xAmpa6=u# zbuc7;{P>|m{rVli$MDdBLoSGy(|sL#_R0uHc0W+5AjOJkD@i7M9=(sH>Bm;8G`698 zhd$aIyLcb}{ethq&X|F>y8s3JNE1!?vCR`96!gS4e`wNZhX@adkirTryl@9Cej#Ir zCVr9R4P*RS2bo`nnFEMb903A~RpMwUj#++z;($VeQ3aG(MBD86jHq~vyC&*MAPgI z*)&Zp(oXl<6x2{fW#Wxx8pO?0jeuK~RpEwnwYUS2Tdp~WntQG}a-sMN z;-^Q8ish%g%HVrQET--h%e`g4i`KsUtj%w~zJT49zymc)a6txbQ>h^d8Nv`<3$@@d z!bzMV)}COzStSi1u9!umh=LjBmv#K{1|56+nMd9OF8UEjrkW(ONPdpgC`pI7C5fPH zj6sQ^D6@&l7-L+z<;swC;;9fXzYO!sFv^VN%%k+^{|gqR)YNFsn!EbyS+UGIa8G}d zSp(3Z-zvh_q8k+qQKOY!n(3yUe!8JLHc3XaWjN`C(osQ$x=^jX{@S%tZ9{cwR?YUU zu2+qFwTOP6vx~WYtmB$)NC&J7JYz39Rz8NVxZ(i79}?VezzGlhaKr;wPoriV%9*Ta z&#U&@%B_8PuZg)e5J3eOY>?b?(;eNyH+l(%$A79x1&CRw0K$<}MsdcLVG8o+nQG?g zceH&D7_nb}5C$pVg&989NQjA-c-xZrdD0;%Wx9pflR~~;r;<%ZnGr6$^a7PcB0+`B zNM2rQ=7u5(r!sUFHNSW^V=W#J) zNZ#^;yh==B7PANjz8n&WUtkc2tJtC6bSR@WFvN$e_yxYg;;j0mM{;FpLnV&UhAIBT zJz30RT8=T0feb5od?84I5~8{8aLymi0N3ZnbqUhFF+y*+MKFFbjei_q6su4Oy$&#m zU{u2!)j-|9obiu!1jAn!S%)*KF}&q5L?Q$^o_O+uIfgv4A;b%i^Ptxd>0NANGP&L; zGqF7|dC7ZWnnNFoQoi+}sUb*th|FN={}B1fZwXJ_*)hfd9)A#HfBXYf3yBGsLlvf& z$yDYtnMs*VWa4&K>kI{B)69oZ6PsWY+ifxdwGC>pgL`RP3j0w67py=Bf*DS9ma{@@ zzB4bF%nJ>#=z07jPfbMRqd~%t!3t!?k)Y8NbMTxHJRvTBqy&!Wy2MMH(TqhtBSmot z$t=>)$5l+^AGtf^Iu5Xoei@7(Bx2p&4&XduO|oGYVM8Y6DH0%chm#nKUMN9XrBQ}V z6p`q|$-;n2lX)RbiZBW+#Nm%(|Lh_uO@RfP@^AoJ*5#Hp%Vqs4aTZ=yf+D~aX3*eS z*uWe!IEGd1Vj0Uq%usDJoM>P+xAs5EUe;^dybT7u`AxI=1%xR?&T!Cq0HV3Gv5F1W zLmf9C#<8}dU_{nMMuZN{R3aA$Wk^6*5eS9|w2%9o1!sS;h93Yo5UX&l6D8W7iiV{= z`8ftzU^tR8hQuL45|SkuVjycF)nS@2sY1N_t(CIWr7(@@4nm}vX3Rlcr3gkGeo-Nx!vO7eA{~!$l#xDF2i8nbU6tIwS`fSOS_}x+rNU+nhe96l;G=n03 z8mwGWyVw9Cv&czS@{)NaHL4wmGn2(EWxFAu z_D-&4+0|<2;=*aaiyuk)2%mNUbJcw+qMWp;7q`|9I(n3yJF=H%+!qmI)l`=sHYhPOq zndn6MkTTZpnf2RV{|JL9s9~GY*ycbNnX!yx_P)HviGDfj@fdy_6JiYcPvJZ>JQ17N zeg7Na0k4eIGIJnlUK!!l=V1s$ zM-EYwLzi-um|{T=`3v3o10BHt9G;2zi+%bOiNEk|LnfhICzd=tYMvW*hatx<>BKl!>I5;w)6MXfgD})yPAg~*!$8I}3Xuv}lQAMLVo1;HAV}M~ zmk~1p0uBY?hPq!N!rpy4Ml>N?U_^S^*!_rvC(Kovv_zCwV#Ku>Pl!1TqI`)!#UM_Z z%2SqA5e*`e{{kEK4vWB|eGhrJoZ`)6&G@((nh`9%;UcJy^Sj@#m;LN%zn8~Wtx^rw z{qA}HwJbw?fD#7|$1DCSd~M{w_#R)b;~CEIhcg0J31k>| zCPAk_ViE{P5LCo=3?d<*U=pBU?p8qrd+tRpNz(4G zk|07L>JPh=rz4V$@E(G~qNI8-%u1@Q@wx;|=0Fi7uY3k!#L&unxIht90VXs9su<=z z_JJSX|KS~|LB?$6#^4QSo@HnJ0rgZbm{@NvoX@cO%`m)B49D=}ZZEQ=toPDT4SVn5 zx(R}W?>Cmu;$r1EOe^_9NIFKS*kni{ZP(69s>UoLP+p}1wrCr@XsQ=Xdnb46+cST#KT~~OSU%8 z*!V#J571%$VyXlWB!Zv?>q5Iw5F;2Y*&HnJs450!(C{>dV@4?lH=zv_fd}Vc4h+F4 zBv0}XVXVpuOcY@lj*#<`kXWu|D&%Jhw?fBqW@q$d41Pc@{$cgF&@J?>51Z-8{B0iZ z{}CS*i{PS(6EbBD{}CXw>G!tGfZ*^qC@xkIat?JM%L(DR z@6ht5zskc0O5qpygd(=j8~kA!kf9-b=l}#^=jvb*4?v$}NFz5-fxg1huW*&Gcov@5&33+bA!D2Z{{ zFhUkwfhnZNdMd02M`;tTtrecJ4Hy9$cW_L?$CV6W5c)t7ZowPB@pztY97k^}_R0$H zhnIc;u!0O8-@+ol5DXKOF&mSZqz0OBZ<+#mk!62+ET@YB1k~$Tl(v(m+|KW=|N9*`O7&9k2FR2%uGo_VKcA5io>3YZ0eq~HeAY@F_{7`_6ilUpDEzV)KuAU8Ag&snaMcRHQAi}gFG~*VR0;t4vDv=~j)l^})HQC&hDoJ9hh6Nbh|Fk>iz?0z92Icb~ zY;csqD#Up38TYe4r7;W;flS0F5_Umg8r4z36bd8NFSUYFhwk*&vEF`3Q&~?QdzBtN z)nh|eWOZX74KDXi6=g504F%zyT9q&agC#~m2QpzFz=7jj;TmMN5ca_y`r#bnW<>4~ zG(*U34#6}>wos;Z%?=G(s?Qs0P9rd3J>L?a4hjG8Ja+4EZ5^)ECBNesjx zzKB?aCtb;uABq7K?jvot^e)hoDAThez*b?*b|C6BK*FFCTmkX;w8Ex@5M;mr3cvtN zKnpsdCO*t4pwTUPa8Mn$P!%>&+sZb|?O_=P7Vv;`J9lF9{{RlEkUg&OQnheGWdH_T z0BOJQAXnFQU)M1b$R7?aWouV!-hdE9^i&A4nOv5Gpur7Xpb%7{2<%}vvOy4Z;F)xw zXZv9tn8P3NfeygIIfiy<#{qU3MdXNc5MfIYoAx4}^*io^ipW=d?ZRrUbzAJBK=P$) z!6+jZgInr?yf6YGK=G-(vo0zP6oMcK;Gk_UqCBlKZpRZM=(cY2A|iD10LpV>*x+yd zRX$IGa3jC~F8G2ApbNH*Opsy_2(~TX(mx?jE=fT%r~w>E;Q-nybN^u~^q_NNm~#^} zbdex1i*+5@(R3%&^|BZC(8h;@ScoNMYAD4+Z5N3@{{wevV;L-H>oj8%Sk|z7*D!8j z6tqBAikCRLzzs5i77k$_p5u9Y_7I+cv{rx&l*4+lcZdn4ds!3u>>|3z;~{1gPfOiXviW#C1 zhCv{x2?<9yTi1v@#?3^*v)biW32c?kctqMm!ldF;slt3nf>yo5{UT++F&1!c|tpupRK7L?J=y&+I1n*HfUFx z6ONjznOw0s6Qa1Ai|m`-fFYh>9Ljkgh9eVhp&!E7d7alAL_m2tPMsQpo)2IJ4q%_n zS~mb1j@jcb1iFs%gP{F^YM~T{JVKqxi@r7;bn(UhrJx=SnVq7`N# z5MTiqNP#GndSMwg31Q(Oq}sb@ctLecbT104wYm+6!QM6&-yFNK#+t0z8@@x8Lz|d0 zI$;$0kq~fqtwm*t-THP$G8qC~o9Fu9e3xi$;TAH%8W`aK*nxQ4VH9X#6UNvZ0{gF3 zVHj?KGZ_M`<6AW#TQvjPX$RV%XVW&KNTRCMF4h%p^CGknOn|#Cc8^87YRH+%!ulY6ve47be_6+>41%qgc;0a9Y35bS8<7VRk zZa|U0I$aL^JZTSYk8=iZM!d4k_lYg)SvEVO5t!K=+G~$Z(i)hMYdq=r!Pe>m4i2UT z9r?$99Hc|q1R*7dUdTy0`$uF7NM?w)q`AP`kxKCLElKX-YV3oy(rxQUs^6R=#Q!^Tm~}9TxeZL^&L@=Algz#OeBb|FL+fDDp9wPp zUC;@ASOyf)6aBuI7!9e((XAQMeI}bHy)k`PFB+0L4j~JcPi+9cpZ)oJQGF>^E_|25 z&BAv!(_%kdow|@9Y(s*ndV7J1&069&DxX6$0rdqf)sF`Ay7em81{1K$|w*45y0Ic-2L5` zU?gZD2yD2bD5BnpIe-2^$lwv=m8{?WeeeH1R0W=!3I3S`oodbvkJB2_>$~Ce`{79? zzy14(1zfH<731;ZGd0ePk^ckmwF9yvTe4A}=$;i?2pU;ZK94O5)?5$qoV zkQJIFHisa5J}-2+Q-1 zjXHcZqU#eO#UeIg5!QUxob999?MEUAXn?#5qV5S(f%2XUd${vcYtQ}u{pTNP1s^gC z-tZAV@zD*ND;^-~92iKjpuvL(6DnNDu%W|;5F;{7Lb0O7ix@FFJk$@LN00puWhtVg zq)CY=Q>t9avZc$HFdO=qNz(_ynmBVJtmKcMPkxnh`lwXtCr}@4DjhR=Ow&prP@_tn z3M3)0o<_53<;PHy)Bk}~p|ZIOENoOZnz$Z-gAx?KfB!%g3_`cA-Me_{!YStO-vPM) zfI%FK)#t&f45bbv%nukFvryCWGj^%6WlxbJ$%w$YGiL*!2@ptgAXMf^qz+_0fGQEH zNURg7<_qj}q(qSrsSc%QAfDgAg9{%H+zVv7n*8}|Hb)4KA3xeC|CelyjO*C5Yu^qd zruXmQ!;2qJzWl=?MKUHa&%V9;_weJ(pHIKO{q}VP)v2>7)20KP=y%_M1SX{3fd`UQ zl0rp%QqY3{gb2p^#7s2_>RU2J!S0Q6d&~Vo*M4a@9}3Xu`%r zkkwcfLRD?0BmX~8bp?bbR59jLSwX&73|lFI0$4Ev<>h2vdtqhJPhTa3){90}c>rRG zMRfpUj@byrPl{M}31+xO!Ukxa84v+z1{6R*0RM=S2rR&)b{i_H!FGUbt>KxbYl!F; z32y`ur>LS{1OXWv#qhISb3#-)$1!~oW8HR~a@yU6poS{ys1Bu<5vi!As_Lq&w(9Du zuv&=VtQRR*1TEQE(}h93l(SAhzQDb< z=pjQO-lWrr1kGfkPnEQhVquk3=~Y%S&WNL!kU6xYQIFmD?vH4Rg{4tM>f6(ibS3## zw*0{HVuiYb{UVRUllZHKOQ1)OifDJKDi{G%K& zuDPZfL6E$5XKRtPh6*CR9RQ1LzAfrAaAGX+=!?u%YH2fl`ICtWoi?3a5!Oa6_0$ZS zsu9&#XRYKz4cu54u#Kkz-?AY;qI; zXaAfhrwo`swf(7D%%|Z=O3i5!6bURj|7?EHLn~Jd8%7H;M>7K}O;8aqIK5rr_~(Bg zdg|%#|Nj6Cpa2JWAF=BY%bpaY~C`m1}fWd*>f`e`# zpa>bFEtM>eaXN9_8E{s2JAgkT1Puk2WF7cF?(!zwmPB`vXa45AAPM8e{gfxMHesKXW(eL_XqCFCx0nIa9=y3Ha6Y%K~i$`0oW zPAJ(9V6P+SGIQv~tIQLO@Uo{KfTM>);Sn5*B&f>zGDm8NgA}jHOrR2qCtv^r7MLXk zW~qUi%$Vj-5(SRX40)AF8Etutyo7Rw;ZcUb0Fp+Ht^Z1DQrX(}wz$o0)Li<~fmlNe z13~2hO5)Rg{HnOe&FQZWafnhTLm;}%KYv^w1`!S z@e8Z<`dsq*6(p~i*C={5N?DCK7rdku6l-0pHyKtCIP`8uJ4B~mYXA2y0sl9?!;8ol zaX6Kq3@0`eUA&yO+kkS|hZud5$`&D}4!K z-+>e(zxloEHG^Qqg%#vT{%vb9iUEp*@vfSHam-+j$6%>=0Tz;ig>dvh3UExApwuXa zX7zX)4ZjAV7`_c6VBwE`8l@*#>B&DhJJ|E3&mSyqpZnnF5C3EAK(+GIvakt9+e;4n z*vL+{Zhc(a0~BEt;DE*xicpAKa70)>Jp>`jaSb<^-~gpK2RK?eEOM_y*{Y&0L6Vx( zmVo(j+kKZo=scD1W^QvSA+MX+73WHOg~6+{ViGZjq50kgA$lPQpz{j~tO%Hi{*~)M zzUgN~S8-k#f=djkIyy>M8Y*PO^gmAgn@CWjpNw@ZWc@Ud%p~G@nc*I4E-RZzKmrkl z@WaW2mzADSL!uOwibY#&wD(C07;o5tF_e=DbUPhuHnzyqr%v^%6Oh@)9>}r?;sTC9 zuz~{#WkFz21m=R|>;14gsJd*Bq_mqQ@7C^^8v;Xm*Z;eQFHs$vwGty4%_w<*t>_Tb zdJwh@oUCR=$WP#~@ch1+D{o~OlHBqaxGcKS54SJIcgPQNiq{|u{`eU6P}pqwBRB_; zFg2)gVe#2~!>HIrZNL{<)TBB$eh6ghT|F;NpKr81@|S6KZS-EVF9yaK#y^^__U5;$ z*f(~*^rugKRbkyCP+LgZJHoaKW?vyE7{LL^V0MpWx%&3u&`#bik+{=jyPgAY-G9i{ zf|wbe&n%st-#f9bSoZ$_2!Q|6XlG>?tP?wl$7i+^3XKhC7!f^!5Nn22cvxNn7=TzZR`Nx7 zgSLSch)uKOF!uZ)4~L+I5y1lIaE#@_OaC0gcI!qk9a3H4f`;+-hI434^g?%gC3@y) zBlN@=L_`oAh(rcwU+;K{{J?{qwuyfNF zzy=*fjWGEhO{k19S(7$Nb;(E(4dDV=c#{?KYAaF@m5?n&c{sgPE^#Mjb*K>WmrQ9! zj&gO5QW+MGp^gcYM2yy7hsPC+R*<}7a98;g_*fW?m5aUBIBu5;DMKiEL3jZj_SQOT3{(xB!We|7(k~%n1MPib;SaiJRYb?0~ zXYi6fd70rclQfB$oY|STm6Pki5QpF(A_0w_`5rsc6NobqOOcN~_ZCLUA?Bi8GZ2nU zX`2PX22Tl7KX^y&S6d1S=a`A@(#*YgY+U?F;11Pp#SG5?Y0Bv!yCaW= zVO|(@2Q3#0q!0>yq%#9?dV?fB>Pb+Q2SuEP5Wi7+Ss{|d!Gnk72|x&$l41<~Ihg<& zp=5d<1iG1Jnx<-sH44fQW!H?%bqH%Z9$K-X>(*r!nt|+sZydUm3t<)qF`{%QsKodT>54jsV zgP5VCGZIx;q_9T*1f`)fr3A5%!VwAWw3x#YbYmeY`U!+W2&R)cnMlZdb9$^-NQ}t3 ztjr2F$+(j%Z~z|xEdQj*T+!OBDsed6SRzWHr~JaFhw-7{*hL`v6W}U;c&AxvCP#)2OmGpTC@3Q#+>?W%G4T3?+CiR?&tRV1qEREaLCkANW#kWjYY zgtjBNwh=2xR0_ANhp{E89CmxRk(sw2`=6}HxFkC(&^x`1gs`?Zy5PLOsArw|H|5K(yWO<3wPsh5vzORI_Ew(6s}d}by$67}i3<`=ma;g}2FD;wDxz5Y z=66`tvwo_?JrbOsClOQCxi9jm`3qo7JGzv|5BXI)N1}*2E4KZ3z;4N@1F@+7TaZs= z#W_d~yKoA-KnkP)39P0wwz?>|N}r$^P{nbai+}J7L?H^rx05-Y zLl{|!5LK)d`}?S)>qLvT7MM!4|A3aLgJ)q(#a8W!HUR`VlmnBIcVD=C&1w({yD%N600~IS$H6gz2HOz8 z!H{TsPhy~ZzFNrbql+q;&dj^F@$AU%Y_dna)G%L+!j$#dml=DLP`DW|b5LHYt`+LiE!4?`fu$|}28JMDMk)skVy8l7I z7xKs?XvJtpVsUt}1Sh@Hy@A*%ElNH?4Q>p_6|B?2F+S4l5Dkg8p4gY$lxyX@pOSJ3 z13}bz>%1?>)a^_wrk&bhc*Eq8eJ;R-S+LK;WWL`x5d62Z=SmpprA3_k6mWQqG}z+4w1kAFb|y&22c=*P!I-n@di*p-EV+Vbg>0jumy<*82f+@>+ojunuw@t z*I8kz2D8yQN;~G{FkY({gyx8Ou>@7B*!G>+CwI+q+{S-Y!N5V;5rNsj5n&_v4=V=L z%KN2nKoFw+vA|Z^svW)38{rf_eXMOB5ZbJvoFO&@dU`s!R-v>1m&ClS68}))S6}k8 zbEX#Gv^yvfsq26Yzpx53zC>^E3zI+>f-vK&(Bp3q1W>RF!Qc$RFb(bL4Z%7D(R>x!4_f-yIpZ-*qcuuT(KIo@C;ov^*IVR}j9wI^ke_x>$0{vc-o5Wp#It4K=rfh#|!Cob5 zv{Rf`NJPwU1ts2~2z4T03asY|TuSG_ zsvKad5Z%s_A$#t8p43Wh^h(cC=Dzfe`+l`K)~It#AYN7VZqTCB=&RfiSTdEsvyL06 zwCfGK*yLYy0SL3O1$6NSralRyo(ic@4bM;w=#VYJ;0>_0>Hn?f4bBh*2aoX?Z;8Ca z@qQLO5r@0KuI2H1@+e=~2VvhhIOZyCq|iLgiLeW>(8h@ni*4@aIq$}>&>TJQ^Bk)j zpe^)6zmkmP^hb}{tpEC*)by+m^{10(1(7ZFOFZzd5VxH>^otTs9C%`a7FXUxgr>9s z`R~;k*Pt*7zcAxz;3&Tk{f>YPw$KdEkmRWT3*Imf&)^K-{|vv7IOI%P%Tx>dOy{`Xr3s_>Nx?0HH_Efdc~z>Vd`2A1r|l^+Y-q$)P|$ zi4vXKMQT@~Plu3$|*~uU}~0IWX=>p5yV@+ zBPeJ3)AoXmLHsbvp`rvj3YLHP`DY@CLYXK+L;oPbNTX9A@k1mHNjiy?K~#dNnV9C7 z!;?8itjQl^-e3wS7l9JWpG^Fsu|^wj#4$%5z541dvUUVANFj$LvPdJ3%*sb4>&gpB zC!d6Cw8026Ei=uI0_HI(C({HnoiMX%}qgG@Hcbd0Ib_&ETW%Fcun&B;t#5Vd0N z^am83W(&f##PsCTHri~Ngf&NgStXd?QqgY%^gTtTXyg?^9`3_Sx7-VEs&KYzrb%$4M!4PrPyDP2!fH^ zf(b?uoeazg!J|TX=P-#Hf&{_{x7EWBNdFF~a3c-zAjzZ(2Z7>%m|7yy7hn`R%%zoR zQfNh|Uc{HDp=5-zUw{7vIAEuGTvA|z4@Nj)g%{pxNr%B=IAVn(%Zacm!xS^8ETxQ$ z%cIuJY|O$wE;CLtH30^g1O8#T&X5gbuw^S%D@xEu{}j}=NqRYhH9-zo#Sx*2{RN6Q z;s^$qf2wiDA9lP!W*=)-0VE7Tg#PpwKu$fiyCvYrqnLf3aqpjfkf~H5sGW(_pW~ci z8J$*Vz4V!1SOa90oCR4$3_pTlgdkf|!2>5~32G=QY7T=1r*FB1yrD!&%4nmG$TjyA zQX)abk91#Z_hKvOP0`+a^L_D+eg7q9y>-`Lmx^E|VW+)z+i%C+s)rrUy>}d^JjybR zGuxPB(Z-w%%hM3+(o3k=Kz?PJF(zpG%!*kp=bI6GH0K~v2?mNF()cBqEm(U)w?x^P zH5aIVaYoZwZBb6tB@VzY(IC3p4m+^nxD#T&vyamp08^(~N2HwbjN&}Q8OSi(J`#uy z=Xj$UcMAgFXkZ&CH0uD$BG3W)@QcDBE^!AjNKPQqID#DJAB{T&3nLdfJP3qBl{-m= zI_C#Jcwr80@mm`V;zg6nxgJUgC(ruI;hG64d4(8IBXJQL)phPm^O{m*y9J zVUJnWCm7FY4+Wp0Dy6M4A)1B{x=Q_FQqb9}E zo=Rb(PCzC^#56`_Ya}Db2;wn)>Lj0`2`FSt(?Tm*PbYlr77{S4+o;n7sX&2 zFveC53i1XW{zzaj_Hi8d*liW5uq1Fg7{6e6f*`3N+(E>Hpotu1aRRK?@p+K6oEu%!@tBE;H%Sd6kvN~jP=1Oa~GUNv{XhaVUD_(n|x}mrsu?I%*!T`&=1UJ~h4_3=z?*id>9#mte$r3^>bAU4$bTm!@(_tFZ znaf%>#E&UWdWT5S+DO!UtkL65(k|9gdiAVSNx!0dror-U^Zl! z;q7Wp6x3fizK|hhJ!|Gjfe1wC;Uj*o;T?hi1W_ntU-F7;95?$909!@CJ<;nqDLiRP z2Z@SRtp9YTHN9yG+hx;U+;CFT=;TGa>~Widyn~P~c4|CSkrHY~dH@OH?x4Rz7cNeN!%LM=(m^5vop~p-4oAGz91+a12aCsfl7*R@aGBd!r zCaE24XB!klY5SH{At+lCD;LO^#QB17h48_l7i>dD_MNfiR>6&~(M?n;1`#=G;a%}8 z8~C>JZ16oJ!XttomlqOx_@OM?*ml*5tWv8H~EM7i&QP@<3ywt9{8BiF={QIjyMCiK?;WHp89uzS+B#kPuHN?QcsklS$fdg-{Kt5{0JvsmyzzJuZB>ZVcN=iXe>7VQ{LGqMVm8AXaI3epoJUnC4Uw6zH2 zL8>UmoH@oh;wLNVlh2irTY^ zk%TckQO+=tLE5mWIw1&W%n8Fh%xWY)M&t*@bVkIOy_`gd8HyGl?8#H8KUjc-Y!D(N zl!!!t1SPDH_Txz$V~EhqN1TvC9^9|fYzfpfHh*Bv0DH6;;r~C~RM2!9%gbBP2dy+( zgwPy8O(WvX#(;`{AhF>5nA4*`%H&X zj^jIwoXbgqfQV@_A;^pnhFBgW+%x(l$FxEOop476kqG?+MgA`hS%)aFU3r05uqlv7|-jYnCEJe3NZ>m)$Ez(KWELB+YigqN}6j%WNW zM*Ig*04|w(F-n!QZ%K;waxX-n265PhlQ2R^=$xh)RVE$HCskE~paOzm)s=8nDv*gz zu!ngdAOa-_BWQvwJWeqexX*yHjYz z)8&Z@K}kfN6Ty?@BRr~&V^m3;W61*ug_=`Lmz+jKWmJ|S*WU^S@yr=?MJAa$hr0|G2^M}xkN~sK}el*PknE!>YT?IFY2}$?`uw4nQTZLJegq7%m zvrQCYLq25iS}ll*R4g!zwOfYKRk66+y^WZQ{r0~{z8 zf$f4{umw+eq-yYoQP7PTm|Ke5mt^?c@f8?}6+rSu-zO>4^zDkkg^8B9(9TGVxkACPEF-6o6F+F)Iy z7|I@1KeeJyPc4aJh=dTTU62q6SP;jk4T_o5ZD-2ULlZ#RltEl2!>+&hj~~BSw#xh+!roo-zg>%^F3cG#^Nn1!z|Vc z_oV_V>)J`^gaN&vqf(n$aRzTFHctTKt4o&ysDrb0?xAlg_OuKI#sfuu-wnq?Mu37`0J;kg^Ltib>>_*ljC5!vk@Yh-kqH+eMsy%TJN; zw^D7=eS|q!kr#ixVS-rOv?U1L5dQ+`#epse1~=#h8KwdphzU3NS|XkVDkue30jKX3 zFpJ|CE=Fc4nx|xDW-{F3W~K`F-HqWzUPq|VwcC}`xD+Tm4*9sCG&q1O@RV@=1wnuU zC_r1|u}j;43X_#q%H88W1`Ps64Lhoh8{NRqP1K@zWCl5n37$F!=7%82$r3_}hL|(W zJb?K$mv}9SvpQ0ofQW)H=%{tdk2nxKfZC84)lxMtHNsjl(%MxO0#&BrU+Cd}J%Acs z30bb*13-qewc(erq+S*R-9QveDh1WN1Si%B$3sxqgyx~{3oEWoqDE@1D8sZ&YNd!$ zjhzHKcnKma&5p9|B_}Lg;%zw@UgMO9>DZhVshlXB4KEnw=h*}eN%8M54P7Vpl z)?E_@v?L`}Kl8WxWn9FwN*Fe2;&p=}b_5*YTIHPuY6g~o^^|$(g!GsYa*l`AsWW)p-#KD8ADbI?`%Epab$mhSBtLXBPE4* z*eQO11yZ2bdad0~zW-f{7-5e%aEu;2jV@2j9!L7cUsZhxRSs950Fil~R~+ zgd$Gcm2iYvP=^UxJEmb9pi>(Mss>R20`Sq3}9|;Ll<2N zo6*2OObYpqDH;&yf1Wycy%3$09JS(9gDc1Pn8yK6kUPs=PoC^21hmNvICxPE&K3;` zXH^(>gD!w!Az<+$E|!}9<*_Z1W>_G%8L7iK6d|DM6%S%7y+7SP09xI@Ez|)W;PF$> z3ZvdtR0r-IXaDt3M^G1*2^DV~Fq>(3pj7y7>f?_qu%tL> z)+^6)w4T=9W0|Dr^1Bql;Q?fOhQZleV52~D2Bv|27R)s7pNlxSvqIYSYG{op3C`IC z^yY_6Mhd94=%PSyCS7nmh&bCzj5Mr37Y=QifZ^#~iQtt9=$(mG$OQt5u1a~XQgVh> za9-hEiP{EGSncT+X;^bA^^G_6q$mOzfB~j{byUCcS{!+1c6Cow(tu_F7At1YL%SU?>CBo`g<{iY9m6kRc$85X4%M3L%vISjw+-b?3S?aR1Au}PCl+wdiQR|; zJQ4(3mlZM#f}AdvR3LxWz^-S&o=4^583p7f1EAHCnN1}K4-Rnmb81EN@1g*RNU$Is zDF0~iAi{)r7BXz;kYOZh|M>l@IFTR5j2eLf>Bt6{KYz{U2q|eYp~;j~=uC3dCFLAn zzNW1U>2IC4YTnlU+qVy0HJ!r@3USl&Wy+)`J=qL-=}kg}JEl^tYIVn(rkQkb?aI|) z5gB5~j)f8REZVec*RpNv_AT7Fa_7>mYxgeRyn6TY?d!L1ks?V36E19c@ZZFW7c*|` z_%YfOFalEgT?%v)#zPgG3cQ9We?(L*8iCU zKvu1yVKB|AU~vuvN%Jd>bZ3HsZ21Mpc`*lsgwZg!s1bwy zP;<&DyChXiG)V9^_ndQ4OC4ae#aLvJxFK>%URtOcv_)(EGc$Vmu)Jo3pak5=)RE&sfnv#VUBKb?4Tua7$NSkfHJ zgfyew;fKFD(+;+)pj-?R3ykFAX5?wqaL8XO9EBVZ%rxv98q7TYIO9#Rf?b!~B7N(_QJcxA*BYQbTXngXSSNY5(9u>VOW)S|oHL9dBUd?FO( zLcHQdv5Ho_;+L9t87y*fGDVzTQ?9opF)k@44${O6)2K!ukZ);hcq1I+$cFG~!XRjb z;e;NvkzwVLhZG@BHIU&AV+7yC}vx9ONKah|og^01-yo2cs8ZBoZo23kx0M!ZorXBXexy=V%y4 zxd0I%JEV|Cd~rh{{$^lA{Nhv)mJGHmku1FHA~v(B&5LEMdE5LZIKvqgEgnWQ;yh5wJZvzHj*h(|yoFCY18m~$yzRF3%_Ws(kv`Eq7K)H#(GbfPJopk_56 z);n}^wX0tJ%M?fU)v=Nlc;qyUIm@b6gGhCq1#zc4x#uf>%=4ahy=zD6*e>yH&O3Fb z;~igEhe~$jfRkVkdvulxHmqW?|6l_lexV3Cvf&qjGMY1r77S;6kUk@wju=cjO3^|B z78y!JhZf>en8p-x?V_oOZt51DG9x}zQ!c21Gr3!3ZPDOWWlSEX)suSwo5bD4|W?QWOD zEM~rlw=iQCr+KMTJCT@Vy%;%we&H+UHUH*QX>qo%UHO|dg=P{`n!K+n3H*Ea#pu` z=4n&AWMS149RCqwke~ddCUcoP>qr(^-#)R`lwBj&*K|=zTXs0? zxH#3x{t!)7q`d59S6Mm9cs8_`sO4`{z3OuMvRJLIb@FyQ32EK>6T?lVBij5QGfIrz z5JFE{zjQV1SAK#k4w-_m%X z!RK8E90Ukm$roMO75U_wuK66X)r(s&U|tj*X>`H?;2!QZoj>%R?>UULEuRN|pk7>C z@qr)-R#DfLAo4Wd8<5>dz)nU;A6|ry+~Jc9+EFZ>-MiTxyulsZ*%K(x*L~TVcL*W* zk>2-Z1o}}&Xnowuk-`C-!U4RPN=+dtMBc|01T1NUsWk{iz=CYCMgJX+Z5_m<4WNU} z6WhsI0tU&>@!Ac+1q4PQ5LLoHyi`bZ0w-AD(v1NpD2{SyU|VEa2cjS$79z%oAjue_ zA_mV1F5=0A+X_A(KmWWAzbs8&P#+JP8$KNb8(0JkYT_n>;`a66J?R+_3E`u~S4Mz} z5*ozeSRBSd;fo!B6V6{E91i0d&S)9L%GM^>V;F`zz=L=CD5Tw5JM;EA=BB!K5POY24b{1qB^c4A|~QGz9YqS zo$S)< zNYy>IU`C8lCDz3Yp#_cD;YIjkLL6lE!51pl8o1<_U3m^D6ay@**e(=AhaCVUsNBij z5<+Ae{O#q(fyhXzMdDz@JDAo%gyH|S%7ulV-=Rfu>EN7k4o!mJ^99Rq@nl>0WL*GJ zP!1(%{s0}?A$N=cQZn1%WuRST8CJF?@JVHzxTb7&##PQ{#6Z(l&WtZa2=;vCKh_{Z zyiv~Sky#?-4yGku!P!r&jW^iC+l8WhAUno=TE3#Mh-Nydd2evUt+kV?7-OEzY1sfFjfok30}5U!iJ;N&%` z#cy;b4t-{5hGsWL7w?55QgTAG{o!gx+aTH|hIUyyx?_fRXkRpasFp0lA>K1M5Z7EGHjM}@|!)h%qa9zD*Qr@B7>v(!!sC7%Tz-< z;N>kU!XhC8rV-=ez#mKXr3OU;=JBOlm|8G)q2}R1Ng?Bfnc<_Y1xyCnS_EYG-4XbC zN8YvJ%nX+g5nX~B#Dd=G4~#)2sL~ytCI*`0U07&{4yuN3sPhmiqRIt`ChD1_Ol~ek zjQ_Y!ipD5%hT=fJXl_LxSZ<=b8N?_A1A^=ig0PD{1kx{{Lr6>mGOU9=u*3hnjUffW zp`ijSB*Fps0WuU&lp;iWx}qMa0VJFjl#*nY?qXZWRw$6dQf6=rKfB_2i*Aa)MH-Cc9SC)ZMGs zo|B;->enJ_ZI11iT*V3HDXKB|iB`KBlq?Qq7(j0o8173@8o#q;?CJ3Op6uuFlk zO~mdG+pG;bD2`3slq&oJD(nIxC;~FvK`E?4$^NRyWn`~PTtc|4l|mdb?%ycUEG!(O znC7hC_#KO?g+@^7S>DrFQY*XwAx(mWfY=1DeQQB5Ek^i4xVA;qf@Xu-;Q^fM1!C>s zonu_ItJyBEHpMH4GOuiwE%a_iRp@J*wXNG0n~zlD3%#x%Jtp}1C*IDTx&M7cMX-a* zIK$!c!#+I2GyFuv?!&_#sb5i0R>Q(Bd1x)gT_^QRV4lP@*B~Yc2w&J92VrpD12@cG~ z?+#_T76kF$UX>lMUI^;+=I|AT?H1{9Robf$L&j9(rqjZN2zO<%!HoDF02;X{L-Nqs z!6fU#1p>YuNQek9ltQjJ!#c?Cs_qY}K5RAg&%!#x7Y;(MaAz;%iWwln+BG%$xsqg;(+kmL1eOCN%8clk#O#lMKFh?NyictnmR-*k-$d4p~EjUXGr)-ANxTt zq(UwTsR1Fww@hxy8c-e|fXl1`GBg$;A3!(fLN}+v0Yri=Y%@9|gB&Nsr6p$nDY6DF zW;b63LS*CvYhI~EaOXuu=$(&q474&9bllD;e`;#$o?Ae5awd-+J$bJuyASUs zMGN~yMT=$~VzeIq=^F3_*IwvJSN8CfnPneew<%v{KL+-)v_!k~OP3wH_>s>Z0QvPr zK=BcHfC9|AVYXY!Yx3UA>_(er({Y7rbWO)nEzg|bF{W}5OkVuut2V^CC}t0 z8tr!+gzN?tcibATrCwqy#$sQz45RYWHJfoDZ&P}7XBRj(@$i}$xYcd8g7bv~CWP)f zw5^GDJb}x*sLBU}UtX+sA9)Hy20^s`&4>R7CPkDWKvEjOL6GD&HHd-$F+u^M11to` z9hX8c(CR!70v=56DhvWs4}u;<_Z>4r9z#MQ(E=(&LMa5pAoxM9#4#hR^8>f_$4#E% za7}(*M|pz>Uso$8t_3A~xtv9X(INy85_Vt*%Y+<5C5!=MRCI$HMD^gFgr=r|54i4h zZG-Rm)ggF-^ZA*XG@uh*Zv{5`Od^FVh3j$Le*en1FVV#@cX)Vw_;iq|Crt=Kc=Bntg?gU__$~X-)@WZVjr0X5V2{`n!^<&XM0D{3n^%H< z!+B#1NJcZ8ayXk`q~oBk`MUfU!$f92)htzV_`=2Ju=e{* z`gM?@rBk|e2(+k-hlND&D7j|_k%B*vf*K?OEc8M(a5InxaLJCsFWf?qm%{%-_bNEU zE*JwcKsAh)Ivy|rBNzZ?K$*XS8lW+7Q~7&>H?#jdh=pM=slDKeHhWYc^!SQTrP9&n zsF5XNdvU2sCHO!abR)O>#6Em`Vu-tf+@XIbrJeVMQ_efrkBLZ+bk~=ayodc+)cffe zIzRXVF!;g>_wsLq@=}zYieBH{s>N#OTyxA%!B>aaz&64syuuF-9>9XbC!T15NQ@Ew zFW_-7gd8k*!!OjtsU1Xckiy8Cfg1RMkS9cRmviT;B;kAzyVzRbSNdJsEzdK%&nEpZmbw`CC-iShxV$H~;Wq zw)1-xgGWETAH-+xu7sstoE}8J2hG06lfVChUvWk{c;vkWi4=7lyx`Qe;1Et2B67DV z!Z27!c-F=sASsRtsW9phS*Y|kHO(WXs1rcz0NZ#(gjJC{c%m;Ux~ z+EkXP48MN?2bKYYZ(+lS5hqr>m~msrk0D2vJehK3%a<`{K2W4c63?GOhZe1wbZOJ4 zQKweD`haNHuagvEJ)3rI+m3}m^yUA_(;VLre-{-poOp5L$A!%4jr=(8w=QYggvf>s zFksL>7Apn^j!KjYz26LSfThdrfLPM*QeVAy8-v2_%o$ zL#e!%gu-d2=wckIslsObsK&~UBCDyToC*>MsE(1UBz}&`O3ACX>WUw*!Wt_wwWv(1 zl70Aju9Gq7l8ckKzT#vt!N~kew%gE5Q_VHmY}3s*-Q*0mIX#2Z&O7nUQ%ySQ)YH#D z{mhN1-U?&R(Bzgow7KX0X%zn^O{~L?AMLnHPdt@yTB)T;yBqI-_JU~9yZ7WPRgVKM zq7S1%g2|@S zK8%b-NDn`PS;ZDdvaJY3nrQu~qGB|KPCBA;tm#~zZshB_kANYKr?PfhiYXz1n4zMr zilnKMB>~ooE3d%fM@q-4Ot_L`_5qWVxVp5fVSmIltjscDZ~@SbIqulwk3ojBGd^Jp z+2oT^Mw8?@Q*PPi#suw2xx^GDPPsX1Hnf?L8f`SYVnC@hyq+w*>Ba4c_Aco3mdHcZ zQ%y}(BM$KxB$r@qA?5!qkZk>B9eez-rs@}<#cW>4m4YfrqPRMys(?Xn zl3?f#W-MVUxoY?TxVjwU%ZV!{>tZrruHE+AanF5CIaeM{_uqlXz4zCGFTUlNZwd~v zns3h8INzG_rRV8MIzUuUhbp?Fqv6P2B~Y$!`k|Ymj+(JpMSu7t7mk) z@rRm7MEQlpg#2dYSU<2;2t*t}4Hx+bHDF;7Mx+8EcqjxiQnH0##6cl&sNRuOl%k&f z1PF+UN(L(j5vTv~1t=g1q2)Trt{~ZKCqCedlOO^*84m18U-?Ms5_3A#m1K4P*b-ej z@g=-atS_?*Oc69@JS8rXiA~fU?}i5&Cr*)yX^LWK&QwJ$x(Rs-QQl#Q1Cir2&w0?3 z-qzap5g^!vCg3BB_8`JN@2O-xDtXWNa8f=!UgQ+i09(V_=QEJ>%zlvwMMR8Mp#${c zSc>??hFHZ2MwFruikMZ{o>7f+IHMY*fCVFF5r-fEfm=}c6pApI#zAiI0QX8ElN~j~$T+WvGs+T6P!j~rDM24WFVGUh^!^7y%N<75N!+;n+BI3k|f!X3U zv6)S6vS$BeSFF=E!5L1(c=Iz^6z4fL)5R|qYB)U^4jB)noan(1B=Mq-Cj6lgHq@`^;-pAy6|7$%gAFO!lm-JSNO1upa%9PoEGf6HTiVn}yY%Je4!{+w6r~MC5{ohw zQp|wSuwVwO#29kO%(JAfhZF;1!(dmDYW@YCUG?f$!3srhf|ab=BnH6s#%MWVs)+Mw;AS@yw5nEtOT6l2eAT&BGzQN*FoScU}?7_+R zJ>wbAQO7T)K`U9xxM%RXtxZ8W)a4SsHwiNKnIl5SH*nN%0P@H3}U9YSd?KQ43_O z;sDPQmMs`rib%`~9bR*WGmx<>vcWbO)wqj4S}l?pi#OB3?tv{Lgco&+tCL*z*OyT-94G>69=`%uJQf`EY$g94lKYXR z!H|$tOvM2SRH5$_yLkAn!nKZHxO!{<7{)J9fk0%W0v0YA+jE|C(tkLk#UEkE#%Jv) z>i9UgAqxwyhWa1p0$O@(e}Z# zpR~0omxan!))Kc--rXa*o9tybdtuCc=CiMzGVEr%nB`p&<#+-ob*?LJjjm^->*RwV z0r;Q)T9K6Ge8;qc1z#3h@*Rs~7Zo31B2H29M1;aWAVEhkp5cvYpc);3d`qc2zYmgD z!yBaa#ys+=kknQ~B;IJXYlD%Dhr_5MFj1k=4M+Hx)|e#XswXYc6=eThnvh=kj$xDA zpnI*-WawxpbY6RTf+VbtE5SfuQeu473{aS5WfznjFjkDvVNKDXM-pZ>C}SN-FS zJ8*VJcZks4&ep;EQTBZAz5fWNoXXT+Q$o;`j~@;X@%CuZQc1!NjT9p96i5N`c7YTi z;UXTaR#+<-4xk#=VIQW#^#sHvSnB|g;q)ZMA2ZDm z`DV>ur9i=k0`M1O0=ym zo}*#*qW!qA3&ZUEqR0!ykp0B)tKQFxcE%SDAUWo#=kTqAYD)h|s>3DtZU6X*dH_y5 zz~g%c@FNNk(e%KOCT|c!fe(+ZsHiM!i72~!cxQui2@3%FY8=l3e7^QQU|-d59RzJ6Us0fwUMmS4*j-q?a1&O zx9JS+E}!OVb#@WQdPE)9=t%1D6z4D`ZsK|XECBoP56fa!WUUjY;;{}uB&OoZ_5sD- zLZV;+5-95;CM-q31Q87^pF9z0LJ?HTMHh#nIz(vicJ2QFT5&0CZ5<(^??}RxdO{Yd zqm@>%BvWzFqyzVkPpK*aAZu{Pe4-d*a`t9R2@iuA`$Y<^?IyNQARp!utPvZ<@hFjU zi@!4&g5=qP!1hm0{Cw4m1M9TIr9GC@m*koE4_sx2XNsELk}hl9g8rg ze6155i}7|L5lUqt4-T@ngC&B-uqe_yUg`&N0wa4V->M@Ay;4YY%hyQKM(Sl1?}BFX4!0Ch4ktd3tk!Y7>&+lb-H{J|J5fheCN6O0lnS+h0EYt7iq zHO0*BWRr=c5)Dc7(n{jSFb5=6(j{o>6q6zz!&3h#=J9%hK(+?WEYDI8R52g}DMfQ@B^FFhpNhq@? zJajDw%^v{NF$8pB@B&JXN{4WuI6T1`Q8WKFGc-=+G*2kBLg&=0p7KtQM^HFaeq;$N zL9|JAjP}%X|A_NMe`FrlV?__`FfyV7V{|zu3L_wJ7pUPJ8Y=a~rO*yi@v3L%z-6`$ ztgsC0MQl$i3xn_8(KnGI$M|96hx3ak65iIwct#xHt z_A=^pWm5J-I@PcBVmT|Xie{*?yEwrtH76hdJ;2sUktVfO}&BkkoR zU)3)W!!Q*ir}_;dD%N5LkXA5uF*Nq+{9!*mmNY=tNwCWwc;ir%6=koHW+69n8RKP1 zMskDatlG_T--IgtF=y{>XT3EfL83eZvlN4tM1dd(?f?=DmU>u}LrNtQmR4Uig7PZ! zT@%P^fpn0l0WMDg5;jW@7%=|=NuhkGAr!>GY?XI;Lt$Xe_N9naJ8*Kg?8+l+>2V~( zZeMkBptKb2#X2gs6{nZ*lF2f(bXS!yCUp-OPov3Z04iRwDi=3d9XDk)_kQtrD56zb z^EYKMw13+~TRqoj4I@M$0$klQg-SH_gtoX;*C8IPXBh8ydmZyc6nj=Y|$1I!sR^LgFB*EIav{VTZwcRLwj4b z@4DBQ<}f6Ss|}DiiTUNI=(aKLb61fL>voKN4cEDlpef+jvF6Vcnxk>wr$GTYjPaLp z`9zFCW@gR!HhL{ZxV8UV8Fo4dm`T6YC0Yq}AJ`!x0dX1;M;i|k@JMzeF(LN|glTm- zLwEw?L*j^cS}pI3r#-hAEkBElA+R^GMeN!E{(%+Bh;G_GeX<=NfojCYCI? z6j&8QmF*MhT6u<)F+Wp;iZ8=`XMl)5h+Pk0e&5N9v-TQQHjRauW%rjUhgnb1_?TIP z@R}Gtc@`Hx*O{MLpH7!V@7N*mAYAST5BwkzRG1VR(UVSLUk@-8z?m8zi_q=|kxk_Q z1S0Z)H$D;p7I4&SF=CP{Ifhw+R)8kKGWnlf1bmd!Q9P0|fLKcRYAQ;1gkHj2ngUBv z8GRR{4a)ZkUD^K^mn5iavMY@0W0k5G1@nU-BA?)DID8pSl{uxSm5lpDrQIZ%UHUW* z?vslzbbq3r!j+fCRj2Imnz6Y81u=Kqp%K5?k4?pp&RO-aV`|yid?12^CC?DzRU;S> z79#MT6{2hpAfJ_YpAW!>L&cu~daT!@B|O*Xve#9!l8xdxBcZ|vbt0G&BbAS@DAX4u z{#LGu>A5O_m4%9x$yBM30HQMzm)Yn!6aubJ784&grX5>OS-PbkyEZU)vR8v86T^TH zHK(<5rxREXBf*do=n>Jm!a|~ufVZ2!xsTzaY71=>A(FHOxt*t)h241<=ou9f;%O)q zM^7OUlK1~6v^uLP`K!YPIl~&c$67qUWq@M|NJcD1kd`X=r= z8GWL=rBAMRHM#yaK%I-QKYOocB=z2+O{tQQ8r!nzyEcp2PU{;rDm%YTgLrJ3)1a8>zA8I=TAw|l56;=5^r zbcRB_UlJn9yC`J&0vy5Dld%BN?(!@SqakjqQP*C7L@h21g8GqcNl2L*hgUrEhz;^26Q zdkTGZk8Yc@HbPbr<`O3GNRJmBa)w5!}iwWU%uc9qFyj?x0nD76h znQQ5?8@tfoggV<3%F_ztpIsK-idBD>=Xp7=)tEVih zebL@0OE^__;o|_n2E+MSUr(V?hoamG2zIM8E*<31GlC;f;?Y+`#fe*=T|CkeLpl4| zuk^i>XUm^AdC+j&v@Ou7z#{#}#Lv;U2f85DM z{qAdBsVI6n`_^Dg{i4^t`EbJSXGVm(*s)?O{bR@v ztI?k)|9NdGmL=J;m9$p!=TU7;uWj&p^jB%Fj~O$*8a{lOs$w8)fcgLP_wVuJOo%I6 zzKl7u=FOZtd;SbMwCK^KOPfB8I<@N6tP2(?k|eh5*|clVZjC#)?%li(*#2F+xA5V_ ziyLQ1m1SeRz?K$FE^xU=O^Bar`q>k!UTTpJ;Q02wh9VGT9Wdfs1#z|4SAxxD7E5WF$Dw=ddE}y8VF@&2S;rjXS3y1< z)5bAA0Y+9~!lek+b?jZT!zGeUM%i&%ZpmerUVaH?m|~9E*=zs6ooO4HYOdKOnrE^J zXPk0!HdRYf@?+w2P!%K{p2#i61{+E_)>B?Mdc@sA-%&%2S_g1fU_p^Y#+Hu$*h7td z_TeWGMTsD^(0>IzL?0prB810>8+BArC=7=3Q87G4h@fR1afp~lHhsiYj-aTj(M=-$ zl$3J|K^YZTbFmoXR$0LnWLal@b!d)%@n~4IW8K9oO)>rR;F5t2<|J>(I@Op!#=NmZ zyH#H4&oEieNpHRO-ivR(`hE$UoBr+#aKH@t3!K0PAFLa63rW}9v3o}6SYGD}s+4u+ zp~Vk(=;7hrcjNK%PR8h2#E>4agv%jbSI$@8efm{Ykf{Ho-UrL41#%4Rs(OJE(ycYk z>Qc@Uw&b%4{>wKrY*28(X!wkhWvB0e0AJ)I~PgL!Nzh z%KY?Lkk?7J=Mq2Q&TSN6R_`{kV~$#`u= zJWhG#4kyddoyHyjU7wt%7^qTgP?cw)8l(Ch9^*Zh*T|>pHy+B?BFY^ku(V7cB%rz! z;3+m+gtOBcCCv{g!^(=7@H#CNb+?Df3Zk_a2BrLm!ul04o|>fSgG+)j`%zua#^`nV z+8S2ZkYM|$Ew?kZG>CUCc;uqG#Dq!aE93VJGd8ldON0_+cnBR@{h)^y0h= zHEns``WEsQQcR&0#V6al8W$PzJs5^@jK^S`XI5mHG}a|r?sH=t&nd%?&@naVx?lcW zqDOcA4PF6sq&@G6&wO?%fs4G2J{#E2e+smYkX)ELsiwh7ZVp|=LRJv;kUCgIB6TNR z-AUxrDE_2U58X-UPiP2BSfUakh>+!db^!?<`mj_7p@Ii{z$%bsmoet zG&UtI1g>$ED?5>;H-F&qGI{MEy!^=61S@#Kj^w9d8OdOQ^)rGIu5e^A$ESl{GNITr zmIu$}lpti5V;rk!WafsKNQD0aKskKbMq%*|o%)1^`uR$KMwJNMwXCHOT>?X##=H(Y zk*A`k*Gi#L#g zjA~%w0D%a`8U%8MS%9|=zj(7iR>6t`T%pdFNvikio8@gGGlu-7+fOz(ns)x>oti1| zJOgLpNK1OshjXxDDP6A#V_LzEg&1>|LdgzWwpbs$@M1(A|-FkN=Lx}BKW*>1J zw0K z3~vMm3Gb~0GNwVPcU&dltEfZw5-yN6tb)v9uEQDvQ3tRt+>2(N%h+-%y@HeoFY>E+ zXcWyJMu*1H2loHC%0CbK(5J@IDHnZlN^g2ccG|L#O^$Trh}+S%>V6J&chQsfB2pad81QV5Z?{ zeC2tm$AT^Bf?q*;sP}@aA%inGL92Hs)PXKh2MknaeM)g6ih*jjr#i4e9v+ceOCo%b zLJ_jo6O8|IN-fbs#zzrFhY+N|Ylz?lKmZEyp<6$;6FgxOD0U^y;0vDM2_qs$zyM-x zI5BR>7=rSB;J1G5XD!uc6E^`iWrqayXKt8KP9D)sS~eF~FjfY*4*q}+UnV|e#x3$t z4bKn^xd2x16$sbGRcjDmdgflBQ9c^DAx@MzKu{1;a%>(kf|r4L_|qDB#c_eNf;K3N zv-o)=_h7V$8jD0>xX3^(XF=G5L8s`0N0ExA_7pa!YNO z25X6cg|I*hcQ6&207EG;6d^J!0ueuE=m~Rxj_BwM>_;hh0*CJik0_E9AXa`!aTH0x zeeD0oA#;NXm{4|O;D_gSWqHAF-SZ=JfpC*h3HnAU&R`2=0U!I2Z^#gEv(SJA*Ajv7 z3m2#vZUc%-BZ@Ae2}mI*?NN-0L05}*SGmD?SAt-?2$M0nX)(A+GWi+0Xp;t{K~a}` z$mD}0$rQ9lgcg++5_JmkF*{iCjOxKGG-es4B~liV2spG0iLix=aVK;mV{*eH%`gW- z0G2{92fhFdtW-CC@qzKEmTEbV@7R`rQjg&WBY(jn{%{PK&;|g>hkj^f&BbnwSAeUq zXTk6b!9bV?5DcB*16*Ym{!k6SAP>l}3TMS;zt9q5#*vueHa~Y5IieS(1AZQuewqJK zf_Eewj%Ez>l#{E;nhIu%m)4qCWIM>%6m3JdZ_>(8OVNijLqNHLfw|EA5-XJMt3{AU*)#=NXT0 z*@h#TmgnMd?(rB0@DBYLko0$UX*W(|F?h-nm_BfLYtRb4fDF%o4)X8}xo}pM@R;-9 z49?IA1>p#m83>NhRhG#an~51!M?X_DHL3_D?zED`kynrQKe0%gCyJtgM3aV;qAW3+ zEs8K~0ed<{bwK$QLU;!SaeE*mGP`pM;Hg^335`y5gt_jOYo6>Iq_U zx){-tUmvj#dHNXinFD&61ASP3{g`f9abJ_bXO&rRWPuE}kf+{o0N(JRVwMX2;0?dv z4f}8v?v(=?30@5NT^H&$Wm7h1laCviBO982>%U1$V1(jO4GLIY&#(^rV2V7P@jJoh&3#ss~d%L%DK#o~=w1tv{9|5mosy#rs z8W`rG0@0x~S0~d!6)NikcN&rL0WN&nr}ZhQ@VN|~a0OSOe`Egvx&~PZ>#z>!unzOE zcbZ_js4EZRqi3J18rm`gZ8&=YE1DxXvjW>eCP*eDs)BAXw8Klh24kxV6q`6%yt@iV z-ok3Yy0phQtR6!iN-3mLTb>_vy`Zvd&dL;}U<(D|2dj_@sb&kQkP66b@>=~>97x*1AR%Cm|BoQau-)p32W7ul5rJRl^V2*1Qx8g zrWSsggMN8JR{>@WaWbMEx4c0t#Po8!$ZM0zJH+>*m2dwwH%c45AvV1hB@k81l$lHxKcKQ4*zMc(4oeRt;?6zwdfoI3U1a zDW1*y7;#i6TWJ&v%)n^L5D#1|rcuK*Y>J1>yKJCta${c`ye%+Nmn`xR^a-ecN`D7{ zZh7j3>qeQ+wO#MAZlnAcm>R>;ayOOHX>~#|jq8Eh^P#$Vf<7EieAQP;tjoJBCO<2* zEcna3EGDpbG4TVvPYeV$N4=r7y%Yfn)UXdnD~-vwJ6e1hc%TT3kPGh1C<(Z4UY3Y( zR}Ezx45^?9!08R%(4bK8u5RE409?o3>9^zQ7-avLef^~!3G5SJ$+vSL8PmZO5B$I` z(Xw$Ve)#Bpy!j`mI2{cYC1bQBZLwV%EV*~e5O#@|4||_^${vrg!e=GQ?&Hx{0VD7M z7^b1hGwd0T#d5Ctbss6_ZVI8hXDh8-9Z-waw?@9#| zn78MMhHgEUK8HVlL)UeE3C7T0WT~dUa16en*Jjw)c?_2OO2{n{D7I;b?boljd%@sY zBBL{qJEAhJ)=ekeZdZ{O@nOlA?2lBI$z=Zrh(*FH2B~Ew?H6S87alDdv}rGN^V5Dbct2wjZ~;hevb;0Jy%2)|GWUT_^OA_|5I2w*Cn=!mzI z(6`NSM+N3L9-LExEZF}o1Yv4@Okt0St)Yn=gpFNwN!T9kk)IoE(JT_pd)nE2iEesv z0H7$!+vS)1pr@++O+hjPDjmTE6(#nF6fu2m*+Pz~ywzvwV; zkD>>Da0hu?mj0lobI=L>w-8|&p>;e5Yl=VYqThRTB?95!04~5`>KD98WCm^&p!V89 z$rwhW&%8Q}__{V9y}_fL9eN7F0l8*yQ)U}p2?HrcAAVFFsmgd$un$teEdCfhoG-T= zygE+mrCu2|PB5Z}#HPL_JqRwx{lp@6N+%%@Qw^0Ov?E0NG7JF;-g|uG0a{4O9i_ks z5Cu_aYYX~z0M3Az&fpEyRSo_S38=BzQNMv)SHdTfyz_`anhwdmtf@KF03_u zCgLRC8!3t1Gwtb;5u*3<;#k7!7mx7^;oHA0avY!W#vwPb4(Pr~oJTmERG3Q1`VYE( zYpq?^)dm0i3sd#! za9-}Onp6IO?&&U;|Li9TUf}M|4~XWbmo)GBEcQiICi?M-AJnM+FCgdfiZ2`@pWw$B z3E4pJLznU^&krpo-3$M5wNve40=`3-X&bP zt|o&8KPpUo;NRoNd?oL!w3wj}%$YTB=FGWGrDHq&?K^o4Q=1&ARp-EjY2QMf2P$o5 zSZOlf${#yxo?+SdZ{WTS*A-as-|x7|m0t?p-1&3pzr~hKo+(pw?Af(%=ic4>cktoG zk0)Q={CV{0)vssY-g%KE@#W8_U*CRw_xbfZzu#Yek^KS`a6keJ434nkP--qB219}* z6jEUMNTY=~@(80yLZOByo=92=CJG#QStycoMpC%-TP3^0X`Jkkf-`0@?1e+<%crz|OpZZ|N) ztfUgN;(DyL)l|cTOeGIEX12^~Thhyg!t9MeDG}4@IN+4?(;s6DG;caTuM_l8L=#nX zQAQhe^ifC?EdoCOD!ngKOn9TGEz#s3R<#B-!uV?+PgF( zQ?kV#gUwpWa@#IUbT|9#7{-)CGfhm`RZO8V<6Nl9+fb@3%mSrkBenwqZSGIyj5#*c z=9d3eE)zEpcKBh4BbIn#iYpF|(oHkQ&*DQhrjKKgLmrU0fefPPLf}w!b)ktkl<=Wf zQ9b|?YW(R^p$}ck6~vLU%;{GYA8W>!Ig(oF#b^xdh^h4flx+7F>7MwIrbVZpP@f4nR6CrJrm1cxIDROKP@;R0tTXG160~uAlz{ z;_IvHngPtvOl9bp%(_RrjeGkJ&+WFy9Ie-r)?BR(Ow6inw!J6Qmp3HvJW@}B-pKLr z#5HSi{&e zK}_|aL!7VCC0%CwUK=z+uAQW9F>o6X`p~s55|-vPYPuUnDnY(`jcqcs0i1x2M5>br z?0APm+yGBfz{Z7TM+<8h2L1R)Kn7Bf>A_e9FEvQtRIpQsWF(`2Adr$#V>|y0ik0eq zMnVqxqh&0VWX@i)kWU^UL^E8`uc!eGHq1qX1M$c2qSC_`{g8m(5hBx=qnzb24~a=E z3`Xq29mAXvPGO?r0jzjM*>s5?#ry~t$>T*asqrLd!i1XG^gT1;OEUg&Vt(?Z6Cfh1 zX#gY`9`mTjg+;EB>tts;-MK&r8uF0qROCDDsh>v z-H}q6dm#z#LLr7FjEa^1n1j@0X-@9cQd!hdo)Lu<7he97bajc2VKCE%H~r&HXKX`D zH)EDz(#B0%9Mjr9qBitEb2nhz$v)=hKGu|xF>lJum{7!*Zm#Ez6UF~1aFVqUa>nss zl|$#k?s-+LW>u@7il;p5)5r>LRjlBd0jUa7j1EpRRh68`C4+{gEFAP9BzYEV zd8mVaUcERGh@h`YR+b42=^!fY=yD6QIYS_d#UDP*NJZD~ul z=*%s?Nj*9h8`N|{n)X#9HSuDIPW(nCaB^rbNi~m@N*2!Ugk>>%yu?(g3YI-qr;lSL zZgGu!-0>9Bs~-zwSdsf&;DkmYXzgcoBC;4*oB|lKeJeo~!y%9W2PQpRh+g%;SD5%! zq9^$sMusQV^c*%viH({rL3#jeJ&~jzF^obuQ;Fjc#H}AG;bs39y3AuFc%{DqZB9wc znX|3$B$cS9YZ5~lHtLW|v!$(g_6N>clBX-a*-=v^7Z$Rl6S^yAaf?^n)#ZZDkIr>5 zi_77rHY_0z-htUiAW@MGEflT`B^N)%Dr@3&ClA+{?>t4>LlC&OqycR*P?(pCR1hJCUM{{*EinVR^$Xbu|{gKqR%nxm4C$eBV05a+2 zYhdriik}^J-a0lrl1|HE<*RMhfw(YCF;dXv7qc;wp{d3 z3MVu!7aJEY>$h7E7W1#L$QLczOW3|?uzo^LrEC9Mi_EiqYsnw+(J?+5h<=w^nUEnXtrkJsenv4H&_Z)i$*VCcirM@K4@4lpl z`Pae6o^8wQXms7S>g2uueekmf=rN|8=))nk3phVZ6vD#@!wVhm)4BiidqEhCLF^d65xoKw;vw3q(VH7!x$otl0X+Gcu6fn1MFr z7QoOaa-ku5i#`XWKA4-mMbSfrSV8}=P(k9M7~nF7?sG(N3`g&yL9b%O&k@H7f<&X! z!OOceQi=_@VvN>e2$lGx8M>>w>cmiZAy)xKPy!KvD@C*byVx^8JPZ|9+yPhAGA%p+ z!f+1X!?<6>h{>uuxuX}idK2;46AoFaU~CUCNk%0)j3fyfE|J46v_lZ1Mn|#6YqXJU zyhcA^Nl>PE}!5y?b4T-jRBo~H&j02zs7>WcMdL7FM z37yfmzH&%aW3K@$IO`KcR$NG1GeAAlo-aAJw%d!2i<8P&n~RhUw>rtz5i*@P!#3-T z8OWa~8Ogf<3~2i_g6f)=iwpmoLqI=dh*sQ@uK>hyvY4_2@@&1*|Yu*^bV!J#&S4mZ2Fo%l#vEJH4WFpLyIsM{vjD#k84M&Z!QYAG4dgu3im zuNA3HgqbpD&w2#K z(iDvqc^&?%%8am#QCtG748Vbm!l*Dv@MI6)+!5XMMmzEo3nice`pV#ZFFMH%XtKb! zQ7PqIPGtKGFi|7E@XP;8I3S%ONY0zXGxITtytAP-R=39z{>5 z@iv^CPb5uJM(W8Ld=&XqQjy6__R|n*um_*AnK=nUarsY8!#Fc5P?l(p1YOXsTann5 zvIA_7+pN$F^@m{?2J3iJIek-;Aeh~BoGJ{i9m2xq!6Y^G4Y%RN=b*SV5}UW&P8My^ zoOqKGZ4T?ijv8H}Wn`UC3ygeH#frfZK*WdviqME@OhSZGQ5{u4dQU@Qln5f#D9r;s z$OF!t6`ukc#qdvDsSszhAD-wSf3!-7%1Z|QIs%M}Il$EOSknyk6FIdGH&|93XjW%^ zR%q1$>sXxK{7U~UobFxCH2~|}MSb-fKQ?*P1N!5Y17%HWe(aR7P0?nm74ldmY z-uV^QksqtX12OQ`GBrg96}$8xi(`!oI9*mZh*p$MS(TkuJ3RpZsl6+#sHnh!Y^~WJ z*jCZ_({bI6Z!JT21rxQ2DP}SVb&bw2G)}uDkCBwcNBY1|!!3@%k(eVeAssX;G}464 zTCJ5FCT-FIG1#s3lyS(4rp$&&U^iI!HSZ}egkV34mB=}9%GTUErv25AHOL`_4r4{u zVPIC3{agRQUD-^a*4`q!E2LSQwOO1+%X5*bLG@V^-Hpna&NJG`h%H)-(^(PS40u)A zNOf8v)X=ECkxd1TI$cbw^;h)_Th?t|geh2r-H#`AT~JYpP&m3gNZYl=2$jHHw>=2B z1sZ(Bh*7NDC-m50mA&!UTV!RJz+&{!nHE``o+Xe+{JaR#_dJz5ZBEu ztmW8Ofm({4m za;^XEt=TpphF}vAi>nhcv6i1P-F4+Ieqi6oG~UA~mVuMPH0=(>RE{_8 zU=V&|IEL2g9fmsn2opY@7kB|4=mfO0ol00?ZRJ*Q(p>Xs%P)G%D`8QNBxEw=+|I?P z*8~RnrLx=0TNF$d02-L8wH({~*ONHXDh_2)HjgMi$Mc}#QC5_rdmYJWC@wy_20pVI z(klerIt88JRoWrgixFbYjx{D(hB?_d9%f<=;Y^@o#i_X*$zvX9=4R$&74c(0zFGf4 zo=5_*xG4e`jKJJm)#35Yj7Rn+I|Sk#$UZ-@0FJ2OSn_G>&Wn8`_*`bcUEB z^Hryu=d;}{4(L2k>RW7O7Yao&rdu-3WdTfHyycFECfUA) z{Oo zCJae_jKaE+-4fz=CSAgo?ZZ24pO$Rvwr+cd&*+Hk>voTVa#dKsgv`Dxj4iUZ^<7>? zXk3O(;1N~`P2$A>#AEGSVFp|Qd2Q&W-sI>6+pg_SAcj63liemEl0F}uLMcqFKZS_C zEFvE=S)1nk8$s!7$iOJ(E<7RLX`Y_xJ&Yp_|J1AXX~pht5)Wm^_L%?YIO-Bl4+Rbd z+;QsME${MD;DD}W2_6jO)@2J$8u-SDUp|Si4%|e+@4(%JKj{S8?r)BU=AhUI0f*~q zrcS#ft&_&AsJ7np72XTL`?iFuydCu-r1r8N= z^YUOf7YFEohH84GaTv$l2<}zV9u?Qy@#N@ns2bTIZ*52+a%e3A8F+L~*aXD(2mV%a zXJ&G_sf00rYZqqR{h(_r=g+xp)CVWSn!=2ihUtKlU*q}fF|TREK68dR90sE9{iSnU zZ{icz7|WRRTo(_7U=5$~hxN{}#vL(qZaYj7|8;)% z-(BY%hWH#v>v!^y8HMQLvoQ8!KXzqbcDuN(_L|K&dX67=)B289kSS(t-}q~fbky2! zZue;2`*y{R^0_|n${ud!1V$OA5~8x2X;Z3IS8jaA2zg(KN=~4{#Q7oCd9EOfoE~w4 zANqiW^HUXgq9>1WSPa~S1%IH3^IrIcUjiSPQC#Mqh<9%cc8+Mj_-DPG4~7AbAN!8~ z__)}1OJ{PoCiy^q;c_IPuT__mfIja~SD$z3E__+%`84-Rg(RZH7JA1| z{`LI#MO6OpSYXVa{Dl_-B*=lkVbHAqsLhY>4R+H+|9S^P+0Y+-@+W<>KM7*!gfT$< z+=g;be|z+C4DW6EmiHDCWC+|B4EAt$AU+R(*dcJ>zyk&kUb^IO;lfLA4nmA5aU#Wv z7B6DVD6wF~gc?7B3@K9Nz&Do+GW3^eB+HgAU&4$jb0*FInl^9Z%&BuH&z?Si0u5@h zNRpyPk0MQ~bSYDzPM<=JDpg~is#PPw3T1UG*REc>ipi0~2idY_X8_T}kDtG0a}EfJ z>*)Z)hZo-%OF7Jqj=p|%Obtx&FAN!m4 zSK7RGZ6%>*Pos|bug%1=2T;$Lae$4c+7N4Nnr&Mrklwy~1N$f3m|dL&k4sDl*`r{m z93dt=N%1+v;>}+Ylumcy%In_0gAXr$Jo)nG&!Znolqvi6OpBzCFMoc>t&u`S`l^3F z*RW$zpVr1PZ22=+Ttdvz41wBFgqL1?{nZzJK1HbiLt%?yn4w~gJ(kjAolIsKWt?EP zkY=2H2AXJV9aCCR0GdTnj1s{nktV?8c2I3N`om9-HvQ%s8^Q_4AWz2;G?79nF*hN0 z0wvevLC96-kC9G7G!SzPWzrp%UxFE?m}8PzrkOFV=boDE!FQ&cZ|YReRaxm55r1C! z2cua6j&_VeaV1EgF?Z#)&|VP!1t&}u5~iV}j&cYYT_B3cLnoYMwpnMNRYJ^Yq?raI zMy?qIn{2&JgquNZe98}wny?{LkiKa`R6W$zf`Fkh1mCT(iwL0u&tID3?MM7AG47tn zn47L=Z4k4ayA2k~U4=hKbnm?|9I&s}iACCLC!JU(us{0{Z14}EeOd`?K#|JuX)_>k z5X2BevMjY2l03q-z6a8;#%OKDID^tJ&9MB)KqnG9u=*8O| z3|28_%Y}giYmb7MY_6W7WJn0`nmM0LI5&7@t2HL^(`CWSLf`IEx&T zSu8`JN-Sy3Yhp8-BPk+#wCT;38P_$~axSHLvO}S)6c5I*42C3Q6NzeHD!sT$ zh_q5)WbEDV23AY7xiKmo#0W1%h&N!O5F*aIo_vsr#XuT^nJ`;f`JmaWiV~8Ci~J@> zJL*wLPSPkJ9qB~EDHa+3ou(2OJEs&0w9ZPo^DzfV#u^NB&-c}Hfj4DkJ~PC-g$z(& zC)!k}5C#=pYNVimTZ?KCDop1|v^)+?+2PEmt3FmFn$2Qa`M5(ll7cm?V*MHCjyTqD zR%HpJI$b$AsUo_(R75fL$4qOQn4Quyr?tZ?PkXu{SORr2B%&ozZ~3CLcn~B?4HDig z;yi^q533U@oD7+Crb3EDt6M!EM0|MG&w@6z%_^b`M2pR|W`wPM65e*ISed!{gQgnd z>-zL+HQM&ouZMXhLmtD4O7LK?{w%CfdxF%FELM*b6Ujo|rR%k#jmJ7> z34t(0H2bV+cD9-vo-&oIY-MeR^8gp_F}B#nFD48~WW2k6 zQP9S{C0Hlg08kdKO(t)X4NZQW7Jgg=s?kz#G6N~4%O-ir7CrKyv1{QgLpsuup7iIk zyk(1&r44HTTnm`hD`vTtdBuKBGws&Q=8w4fr~BZ<7}7ZBN_67R#DhtX`|M|6P-Mu5 z-mI>mV`v0_2}w$Z@c5W~GDoB2!jxV%vzzVgH;HqtZD{KTZ7F7m1UE8gmaz~`ed-ve zn#Pw3&8v017JuM!Bxm7sPW=3%r`n1^yOt)QmC4{IC;AeDk}%CUE3;vI_1OX+IKc}p zm^`R8wPaE0m(M1%PC&$+k>P}!4UvsS6-Fjmv zAhBiS8Pbp-!@f87j3i})<2>g&-#JVW?gNE8k=mW{BuXHD5EPFsw(jNjBQf3=jn~({ z9cM`Y$UTlhS#Qv7ZS#q{4Wc(h&U;xer+LgrmNJDn)yw3^b|j4+Y!m9Hl1Dss7Kweh}UnX%=KT#lSL}Y zmHcqbo{_MN{qiu+ysve(_M4YJ`qH2NSWge)X^*B7V?dfg_%0d6|NSr((VbbZNqF4n zUiUPHOsjrB&c{PVsm1(8~W%d8o75<>YW+g#gG-vAO|0a{Wyd_-9w&6kz` z%RU%{>q$nLEd<4hA4cp8`XSNzu|&AxkcqTk_Prlju$y4?QZccd{Z$0={R%SKTSMTV zbD5n(ydZ_8Ohf>j0pef|>fj?~+NSZt7&PFdJfPnx9by<>hG3v0*h@Fex8C^`p-qLO0VwB%VIb9M4 zp6*Fd2SOodh+udG$sYX!%T2@;D#;8sSg#ct=9OLZbsj~8o*6pgBSNC0kQa+|iUS@1 z-*EyFZkr6i1Y*P?SZQEO93GsF4-_85yIlukRpCbnVw7Yau`HO&s9g*qnC3D6i;)aN zB{rP@u)p1Tuow9Co7A(U=-}Ac2g=Gd_hX3Jy$o zW1-c{A3+x(?vO3k;NZYw$`~6tGGs$KWc!c>CWyu{_z7J#%@{yKha7+#zGG=+m^>~c zJwk>(E(A%g#R^4*a!uY${G+}R4TlWd<tiZ#smzUC8XVDNcNNqxIre2BwzNW zkNkul*$N=ugdiGb2SyZEY9VEDVRU(6_gsSF$lMJ<1~{5YE>>o78fO6t2xbD>B@#m{ zC5BCe=AbLUV>+F(Rc$4%}$srH1gQ?GPwb8t6#^39YOm z;W(4#IcScO4`Sw@ghuAEAqg`5^*LeRdx_c_x}9>9b8|O<)KN zxIij(iE8SNU&cg&{-Jqd<&A>Rh3e>d@+g=vC{_LFZ5~HdP3W7PgoYYKCQK=l;%T0q zRXMN)b3&;R)&zgT-GACdVzg*ZZE1l*PxMgbM-bR+3I>^$DR7=?v5Bcv;bzHPs*}`E zNVKVku(SJKjXJQlG0oBNM zj5g{A^#<{UDS05Q#F8Da5lebfm_Q7hOH3@qE`-I}>Bjo(&sL6!z9Ytxp2%9DwPpms zVkgQ{1Yp*v%aZB;1!q8JYR*p7Ll`MENyL!WjB>>PE71aN*ov*2aNB2iwSMg z0<5C$%`*zg0a(wtE@;#)TDzbtr&evuY9ZD}toX=c*Y50wlIqwR?%{&Y**c=p&K}Z^ z1h&Fxm*&W$_G3fY?L=%(7RoG@IIQJZ?XoNh&&n&}l5XkNjN(Qjc8f^O(;=;)em@CvV@6hW4XW7<|{Qi??D>dgVzhPMXWjarAo zreNOcZLj6-&Dcd=Tqxa|iSO1agbeTal5d#AD%g@?+O956D6McnmT-7)bJ%TU`05}s z=FA?Z&)BTJS?`yCZ`;`^`j+ni6EIXns{o__t*IS=^2UUzohH0_r*uhgO1uGKVqyQ% zNA}RH^FfJA{){qNEbtca2$Qf=957nGm{0(0R9Z>=$}fXzW%+oc=5FqrcJ55FC)ND# z#UgMC`|uBk1nQ<`PDMrA@-C)gV<1|v{oXHf+%OJiYGJTYTNan6A7?}{)MyYU+v#G%fo?R>|YB`V*}N0NlZ7y2Bv&sEJ6Os1F_vfv4Zmw4127jQawre* zA}i_akjEnjaz;@y6PK};VDisw@(Zs2@|mo0or1C`<1*=zGM@Hu5zE($2JSZAU+2{j zBsF*&DmKl9`~`SbFw^ARIjHX}qtaquM* z^s$|t5)(@>!-+{SGe8G)MOP+8TXaZNb1JKHMa*WJ@?SA8^ky~murLnbX0ms*Or4H% zM!U36n(|AlvtHdXL|TGO{MMS_5`qk0V>-v9OY5uj=$wn@8aovn6vCkrFkunCn=N zGd~OVWn*^HLUm&&X7(WVkb<;TIWb2YwpT}3LqtmpBK2Qqc5AzK$Zob>HyTAn*=KL1 zVt)r9x3vVHG)iE^Uf*I$uyk3!c5xfG=n=LH&UU9ZnQbowZe!0?nQ2PHkWgncIS3h@3!okwqs=#YG;dTlQnUJcYWKpf6}xyQ+Ik# zm#1D7di#-j?_X&T#NV?2Yi;j0c?8lYv-W*E_=8hfY_E47JJSqO?{X)JR*QCl%S5|$ zZR4zVT0{7Vlel(CcwrYbb0;i(3vz~owzC}dO91z?$aiI1c8TM7j#tu&&-lZZ_i3~E z?e;Wjhsn%&ver^+f}6*J`*nls_>)7qH}QCo*KB{UD|RPzc1$<682MPk?B6!ag3q^; zM|qi>dDGD}XK(nh-Yr6J^_yhN6Ceu5%9JtRw*Rw;rzB7Eodk4P@ zyiX)#MksT<(>1|+JKT}Gt~-3kdpvmjdBh*dKiXumi#)m7aKY1%<>aQWoBPMZe9VJH z$X}OBz`Nxr^nhc|$;U^+bG*z0ebDcOs%JcJS2E7Sxol%js80vzj{46Febh^R10$-* z7JXP=@Z}8u>x=KaK^U|Zl025QJflo~*_-`S*HcvU{K1;M)+hbdzlmLZeaXLdSo{3F zpMBozy+o`#v(NU?SI*YMy_|Zz7zgRv0|j)c1ljL>OdXub}8GC4o|`j8j@^GtakbK_4^laV8Me47dCttabm@b86Uv< zIBVIrjX8z|Te4tT&Hm1&rRn=R(i!4IB3uKIdz*s&i|_x>Gxc=6-Omp6YNeZt}Y zSc|&_pB!~Y=3CG52K!p{#rKv||4UC0FYfmGkH7*AJP^SI6%JQ2kdRa}w97F|^EL8~IHNTdlrTxqKg?Yl3(lQ7IM zEFDwa4yNv2JQB$ym0Xg^CY}5##+hU@?#J3F#F0iJJ>)Sz{Cx0M^io5SyKx}@GA+au zy-xuJ?v2-snXk}-_!JLSRacdj*=C)67TRbVqg68ClG9Pw%y|9J&p&MiR@nKnJ#|#s zjFcALbk$v#-F9)J*0?WE(^6Z`yfhFblzt6QRB^{eZ`5Iwt;yYj4L%s*gkgpE&Mkvn z=vPq@%s1DIs@yHu0JpM}OwQ;Pv8;g=9+~8lO+HyghC$sexnl{ks6&Yl^wmf7G9Grb zi+e*9CXrG88R(#e9{RR9r*uo_#9B58W{3=u8DEfIwwGL-Um`GIpNZa@>#n{2nkl2} zM0!Wdj?Ge_h@QST>i8=D_P<~)I^g3&Lmm$7y!GCj@4gu_x>}Y$-18y-r(0sXK&jtO z8sw4;2e@3V{hpli$}J}u@OYuKZrg&?KAdqpm0LVPQNb#cEP)}rob}dSe_hth8@}zd z0}!w7@qwUj`>oEg#_w~0?_M4D;*CEZ`6Xpv*~-&53SRfyxs|9Z-+vz|ck_5YQ}X1! z{~rAC&0Bt7+p^aPdVzM2nr(|qKgoIFw^E&W@$J7K|NKiM-+J=Ww_SSEbDL-aD7=aM z?|HXL7T)yNKnFe$f?kQz(Oyy`0j@1{q8p&MG6)=rA+RCwYt8m5Vy^l{5QQmJ;RiMh-Bm_Nmatt)(E_vBYW}&iw<@p?u z>XV=y1S>PPQ;&em8aE#Pd9J@4tnvG7wnwu7es;u3X86w`kjomscW zvJj94XMrO<=}vjtQ^ut9j{Xaa%LHPow`H_XG8G_8jk*wH43s(=Q>adTT2-rF)hakfE5e+3h4cSY0~%5O6s87#jz`yl6j7rZ-#u5s$-u<24)Th^Tzu>7@^jBJ-* zv|Vm^>04iGGM1ygjmR6++tR7^H$mkkWVqUUwWjI{s+bJreC^v{2P+c46fMka9pax( zF=#Rp4$RF8ToI0`6S+I#~~ViR*Q!j=W>%P#sa6=`@d9PaSk;1^;)ij>4B*71&2 znBx5qv{*D^CW>H8nT*Z&BC_3VJH5+eCqMatx~)}_|58^A9e__mM$$pYBV%zLz{XJ= zac!YoW-}j8%1O-BibZqWO=|f?BZ(V^u?T&BjFnVw{Imd}+|^{Rh% zY10aBzi-php+9Y)Q2Uk3wjP$39vxNrGMLrD7B<3M&0E^V`cHLp9-=WU*hRmuE4^N_ zfKokdYhN2(#jdsaF0-1940GF9v+F=al528BJ2_Ph9()KAmXF}MD9R->w&`8(SZO=c zUOAnBJ!d#(FK9%fR#3(`>CAS2ZjF&Nc)`sb6+HuSQTCSj#9y@@H%wVxD*<=D6{u)< zA1a6JJ~+ZfE^>x{+$e=CQj93xa+f>*inJJC(8gcv@rIWvDvXgNOG)ovG8tIO@oIGV0;+z9b-W11%sU z7)oK2x^ER$A^LVe3o4Aj11fVH7Ze3}ylRqOa~|VHHlpAJicgW&!pPunBHpAdEov$Y2%D z4>4>{(mqfLmryZ=r)c z0LZ}jj4(0M?~OQ+3FA->3j^t7ZtU1-*MKkh?oWNJklP;T@5tZ)W?}r;C;%to0AsKS zS78t(Artn&AJ73As=*uoa-sBG4=e;x5}Ke1ypS?9aQ)bC4o8s`vkEejP7fIaBq}JD z#OR2!Ejw2_go;>=JSz5ic?PWDgn8!5$7E7|O63a$)smfeiSr`(}aj)(`_f z0|^JD6sM6Ip&|t7BNY{6zdD8$vvD!DL-Js;dBOtwDz69yA^|s%1%IIwMnVg!Z~K}+ z7oEW$ya52c!5;X*9vnddo4^i`kpexjHr#N}nyeZR5+RM^8Zj*jr)ylWk@1j)xYP%} z%EmHO4;?B+(h{flT<}89-0=3eW~i z?-$PTikJ)zYZ5HO(jyk~)l`Yl3WY1s;&=Gac7jqdkgo{{LJMY3^@?!yypQzM@$H1= z0QTYX)`1L5vZnT-D$$`7?(!~4Zxzrmxk4rsmqjciQ!*QZERF52LMJUF^2YeEB5`92 z2cr9aVFCvt24bM{4p88-BqV_F*5YAsD=2ANo=fgP|`kAqJYDG&^zgOmj1- z%^)X}IE!;2Ama%|&@A<6wbZgaz!Cq54=_A$G1c$^UGE@ZUWV0IoOa*(K5je%nD_PDs<8v}k(GJ7tEK{O6HM8S5lZP6^2naCq6jKnh^8j~% z2tzU?oq;w5!XCWA8IS=&C$TmGg!_^b(r^quQtCS`I%gES#KR5=?@OG30EEK|fL zaw%(r?@AMW!gE4fDm?pgN(JlcE>t*&Q%Jj%6p54}!-&5EtGFI-N$;;oxl2$u!k|o4 znjEuIyi`s{5lqw4KKlzvnZ``rvqYs+F;FGD9HLFdv5kH-P39C)Kd?@fRD-S~PtD2J zptBGE-BdBc1j(+ZPzIGy+bGhiEm1%9>lSrS9j1dA6YVEf%RA?i_XTi;2>{SX*FbPmeNMHEJY_Zd?#i9 zTV#8p(@zUEq4wlCI2IZ`mL_agX>XQ2@>OT^>Nt9qMSj*;gLbwO>Me}c$dEQ^m)2{| z3};Q1oSbOeq;^FHuWAEUO>akQKXG2^^=sqS$=KsrA68$g#NS-ROwv|ueKcyVR+_jL zGUb+VON>3dWvk>RpL`W})JJdK3n*LmJW8-_8G}_fuu_7ka5uNU4%cb7WK2^cK2&yP z`E^hME`TbRF_PsmMUit~*SS2`VP|e4NEaGOrQ9TUatkO{0e33g5Od=cc88a_WS3-B zWON@Fa^n@+-mP!b#&>^La0i!otM{{v*G^d^d3|q=MsGFNl|trvaa z3VX#?iE3AGyO((pBxC4B+R`ofhPH&vH+}b4eIW#K*_T_~w?)v_d!x5d!AOyZz@ktIL_4gi&};1U#}6OaH3Z~z51Ae9>#lEu*e zDmjy{r{6Y>+}L%JY4~l07nF-RkpfwX4uAv>U;_*pl_OaLYIz3opcCMrn&F@gt^f&e zAe!IUjKM6IF?g5fjMwVQ#iTgT%EE?k*qGZ{iz4`mT?qx2S(TX?1)})?G(Z9fVguMf zAPhkuJOK_A0h^&0!w6%qgHi?zkoi93tc6fHbM41m+l~b7@ zQkj+sq7n!~6Ra7f^FWciV0`^GEgKqOs`aDnH=SpeoiQ4xQAnfzb=5cKIiK@+1KzkG zL^`AoAP7pjqz$1G@<0>vK%fP>q%*-9oTH^DccNhWGRqBOC={#raF5N`lXF_Eqs)Zk znet{C1yEV2i+TeD0;C1Pkq^KV4gjeM0uJW-sSn^5{uM2%T9)XztA9))7S&k0_ z6u~;I$C|P4XQvbQHhdbW-})flTA$w<37UGTF(D5s0TGt^sqb15_PR$p!{iDPdT9C^ z$2G9mjLl-JwFh#T;kL1B8-E^K$UMZ1DZ8jM0tl2k4=}+HN+A_KFBoh=5h?)=3_%fO zK_K=49fIK(yunmDLlBYC`Bd)!XmRu663mR?y16^_DB3vxRC`x}j46|pZ#OyU)R~X_ z*tX;QdvLpE$f=E)`LbC84m!KIgCP}ip|}q~5eOn1_+cHKLAt4XYSv-9127`!&IXT> z5c^K{G%x%zZ$Qc0EzDcR`a`|ZSwuQ{vE`e@>!_@Gx-on@zdNF>1){~5pcH-~6*@s6 zI$`-zArc5;9;V?zr`xFffgNP?0Dch?li~OXf-Vt|^e}J-7}L80S28#}Jc^Yg?ku*w zI#Cq6#J9Y7WJH4hw}*d%jcU2Ac^e^Gyv1F-AOyh~zC050U=#d%sh4^a?6DfE!N+rj zHGg3mWD^+up%e=6$uTnY&`=WOlJ%ZZwyEUGsW?#o1y#!V)R5lWb-CQqDW|N#yfyCI ztr;TC3t|Iiz^DmA2+jbY4}h~*%F(Q9MI?8K%{+t(`EqA%UqyC&0795+5)%|YEDmVmP>ffIx=6X2l6Uttxz zK^rPkpYVBH>`AsEmB8e(7wu`mrQkBzpl8Tao@H@w*07RfXgOY?oeW}CL3UEnQ^ zCca$L7bC6>0?n(P1_ojSfG~ON8umHok6`}HrK%) z9uyr)a|jC}1`oaNyw4oDvZl-1-`kK_nFDD5v(#?B8mtH2=fNi0Av-VO6XrS*Pi6-cCwlBuq;m`a48s5bz9^%uS;`x~%Z~zAiVfi*b z4@w~zsy+`~K{l!TAJ(B7VBI879vKF-><6Od_09laZ#VDq$)hOlQG2345qR56V;wEh zgX3}wl9=<}_EBc<>w7TRXrBwB@CTylnOX3W{_v4L_!VLf22m3fAsAlav-3a}s^I{r zn>A;19w5;lkbxQ3@%3y`-eu3_2jcVpk(E@G-H+maK3;!cbe=?iNU=x!_T&GQ3jU}B z`6=Ey&71!4+q&TmA0Rdyps|6*0f9jd93&`kLy(54ejRxA>({J`7=s1#_6*~%U=l0N zvSR0eB!voh*!d;thNNF)P%3;`Ql`zDICJXU$+M?VpO-HA8%osQfj2vnDoy&csne%W zp$0Wpw5rvAR)=1asWhtBuVBL-xJ1=zCLL(gs$I)gtlPJ6&4JaCD zooV)vK?ODB*(ATvF~bH9Q8CLbK}3=VCV40XOEtfE^WOpgl=#mZmpl`U7RhO`$^pnF z71JtO#9-WSO1TKresWD$RZ7-{$D>#p~O2^mqTPG-alH?5gagU5P?(t?^DAX=LT#9>@87p@}V znqp`uXf+!Z>W^eQ7)ORs2Q*<|ukcHssUH_;GE9>?6a z&OV09L`J3x2{nqQFUMq46O-oLX~FUmMQ@M@hZ`P+6{Mh8rcR>Af zN#IZWJ@4Lh2dx$9IrVGw(dHG7p5wUZuKVu1_wM_8kZToeVRtwC8A@V%9d_86pP9U} zmT&OJP%S$p)ak89t$M_)FMPdEsM|{WtG2K8`}ydnum1Y%pP!avV*Z`j-3QVz!}4b1 zuRrE&a(%H)Wf|U2t`|P19c?S!Q&><0NVM#IMM*r$8~MtYmiAfjf*8!81~<5>_xa~n z-$D$rwB{!NHQ}!*q6q@@G)4my#EXGVA)o`Hb~LxK4uXAKU{7Qhl>**pdqb%m1*OEn zA{z0CNKB#<0rNi5$*(X7i4#JYm6K;Z3wh4^UqP7l5EsrxhB(w7sBY*zW57^VJ>=n# z#y3PFF7b_UjH4XqsKh45FNBBL*#Dqqyq!c*kN)F~Ks11;x_~i^sXG!G6^KX5_z)*R ztC9rU=teqP@{*X$q$Z_iM-ZM-FJ2TR*Hl;#jwR$+$79ey{P!l#B&3jcIppE;hP}O& z@smKBAtY@nN!kUBlA8>sFo#LZVt%QU5No7gl0z)xjg1D)3xa4o1I>*wD>GJPPz++Q z7gBL`6HAj^Cp*hZ*uon2u!sZdP3*as8*sCPVj)Od6;sz)DiW{% z1w+wL9T}wW)RLE3y6G=-irCVc_Oz(Qm13Q!*0+500F%2(3OF-cg`@x{3_`(cu|qC3 zim|E+Wh5>|g{03$a!X$&ZEBax+~zuWKdTk$U$}|L+jb0~4AQ_0raGBJcGY!N{n>G` z%GdE$2eVfStYDwZ-uAlpy@`o#TBmz}7ifS&2l#;m4v>Q!%wPsNINJfVs}QKR2Sr*z zulJ55Uh6EBfk6_Wam@=@+6fjd@XfG>H_TzU$QNR*g$tq()hPSMK)Wc8!DQv*qp|ok zxCpK4i$QxZawds~M!6S^w}fD`Omv7H4ziGkOk{<8xSkHoB7OWKCKRdDyGd!?G0s7NTCie#t{c6bMBq+1ybFDE=Yg<#f@8Ztmf79nB8orteeJ{4)3l1KkX?s&bcSv zp?8wN~Ba;Rd&=plj7qhDto)1drj#ximN@k-5wnkGafeE~||< z`nTyu3CN-1w!O~o$_re?lI?;;~_PEFT=t56t zt6YBewHyBMh!^I-?QWB~^MtW?w+guO4%oe0-tS}=pVF6}_|AL&^G5WzP8?tNx6jJf zLH~6+FVFhbb=^x82P^1jPy5>c1m@pNxz%AEzeM7l@>6R4cKQzgT;Q{O@b`W>?rqQf z=7WCuIH&u$MaS`FD?Ih}M!xX#Wu#!$OK_W~sPo59e#ArH_l%c&vQ7VU$xmL|+tz;T ziI1uVB7Ie{=Y0A1&;OX8ziEpneT^4Cs;58)^nM7(axJ%g*LP#Ql7ITwe-b!>6lf)) z*ApZ1E%(_;k1@)Q5yHd{r4FvVb8Mqw_v zfZRcUST}<-IB~&Ncq=%BL|9~W*McSJcRTSd$`p8!SARE%gZQU|VAp{B;)H`1gu+&Y zT-b#ic7)nSbxOE?G1G)USYtMrdSO_CRG5abbB4$je&Xl+bl%>{-D6M#CQY%!Hf zc9n)7NGh5Yf{}BDaF~VVp?r3@h>TcTc!)5Amu$~whHJ=3K&OV8B{Y3kPFNUPTDXOc z7>c6UQ;+zB0Jjr;s8!!|fIgUj0yh<#*ie-Sdvb_^qj-zBC{LwGFfUj=fJTY4SYxah zg}Bx?R6!M4wSoBeiL#fA&iIVN^ccGcFTE&$IFX9VXl2(Ii0w8NKF3)P$c)VhjpSI4 zaU_j5VMf8|DFN7nznCi7xM168eC@VnPSJ@zxFja1i00Uj{&+;0aD=CWX94sTsi=zO z=7!vOX(1MmyL5=`0f7F4_NNI?mxs*3)ma<}FPa!0fIhyOimO#mwuo;_65|Cmi za*lJ52q`s=iG9M=m#bNfCmERKBb&roocclkn`4JPw;7gV=`U{hnBX_Q|%PQb{Tf^#H$rIx2@k4-^b*+!k!DURc~o$wi-h|!&1`JErxls(CT zOnGD97c@G_Sy>iw4|ROyah+``p9q?ueL988qnmhSsrH>uH~@ z>6(J6pdcEec)_4x#-X|bXD&sVP1AvkS)rkcp-X`zMj@aB%5v`co+6r~I_edNS)1%> zlivb(H42%}X`ahCJPFuqTm^gbhi@;pqfi>9PSK+;X`*m96j(uN(`luWRHUXkg_}iO zIzgjGS|2Sn3>UOoHID>~3Qn#UBiinbDfB6}X6Xp|S`lwJQQEB?2h1#h)dZ_X8Vu>R!J2z={ zYNyV5i4-b@ys`sZQA=v&s5zJwXey|K>Z!PDoS@pEcPf%#w}*5FZFc&j_(4l8%Bt|D zYgY9XmkNK7YId2KtI{f;yIP`g>VjEOs#g{^`FdS2K1CGAK(+A5GjimbD0h2jd9{-CWn(X5jiT1Qi>g4(VIE1PccuAh~AKO%3E z_^-n1thKhA`^qa-n10X3Zl`(wqd0o79_yApnsW=Qo77QoQ6X#i>Z_3|nl37ar&6-& zcCW-rAL(kVAA7TK`KBVfm;BnW4*Rfg<7jB8uX?(A3|OUqd71;OuEUA5PMeiF`$9Ym zFY}si{%VcA2VN`7pDjBp444&@CbRL1t{jV#==#+Z|%-xDmOuwtB08 zo4JiBxbRB3cxt#NyI5qnqTGR`n0g;o`?Yy0v4Cn8m#ew3`;44xTvP?K(+9V{Xh0M@ zq&BL$mggNXIs zqQkcSyR}@~zrp#w*854q>s7?-xB2_P`fIr4Yl+Saz*mESf5^CMc&_U)h}LTr@;kru z>mFy?y|x3vC|rU2yS4&6D^<%A-XfYA?0yd!uvg;29~`~;c%t^JrYZcx%(ucZV`mH_ ze=zJ1GH8D@tYotO6Uwr@ta+^h%d$9{(@Yl)fsUydN)YJ@H)7*ec1Z+?Ya}Mu};_EJnzM z9MBd`Yy<88#JDnero445@-(+c>|5UtOwOS2U1y+1wGX9mihrqNHy zBu1UhNypF)?Jtpu%$CNxYoy7{jJZ^u*6pRsS8dYzc}5=%(vmmDA}wa7S3rL{B{kdA zYTefy#@2%y*QdADT;03$T+eQOdijjZO{~<>vCL=f*OHxKfKA6oZPz4O*kY!^Wvtmh z6xL#0w{_iJX3f`=ecH|i*aR)u8w=O0ZP@Qz!1C;MpuLmHv8BLPpplK*yv`6qwR^vjjEN0(!1^4-d$MGo!AnJ z&D5>es=UFF8F0h;+S1X$rv2UU-BVVrq~cwdjXm2`cizUG-&1_aOYsJi%ibv!)lwbb z2Ch++4cx)qgGpPvhmF`0o!@H3OXe!zDOK9DH3+WRd)?bM-PRE-6<*%mMBoJu<3v78GG5}k%bdx5 zy6(m9@{kz4(4m5-+w+%tGxqB3}}_!x~@{o6|L#A zu0d=~-*yf!$QO2vI_g^v+mVsyjXo<(ajNq+<+Q!r%suPMjzP8F>1kfL*Nd@ZajK)v z$V}|tx1MwW@)T$;h?kD(%O36))a-#q-2E!;DW2-yN}5eR$xQCWpSj`--Qq4T?)Kh0 z@Mb_P3l^Lz+1gOpL-PsN$uHw=a0VM%jmm)e(F?C?`&@JI`!t?tLjp6pS7_DxgkRNw1E3o2O8d&$=CKzi-i{`J)x_Cu4`gRR>OkJf1a_q?L^ zo)`}WSZSUN26zYd^mpWApJFtyt?!nEy4SJmmx_rBCRi0=X4*_`qr9BZG4I|4 zCI7B$St9Y`LAiGQ{JHsb>ea1Z$DUpLcJAF3!X_%4uXl-WC?mvKxbaHz9+9VHIGp|V z$;l}PcX+k^dwPGwqsYV)pIcE#DW{~eN-M9#Qo$QfGRDEjTHLWmfqb+ONh^tL|A@l@C40)gBGYtI zJN{G@D@!}?#4}Gl_v90;EsM$#L-VN0ZAjfV401{o8zgbP;SBsx!;0d}Zc&=(B&$zN zH|4ZbPd~+yq}bHNFw8>P=5tBSYd}H z*0oHAsTDX<72J`>rcOPI(ikO+?N)(eO;E{Xtwq$#Nu|AO&Pw;))>@|LS2?y}g;=erqzhXPZNTIB%&OFF`-cdMGl ziJ`ulX2x=r7F*P){km?u@5VcCi4Yb_YymOG$Yn>d^tY&-J$5@|xYIteX}uqZJaWk= zk4x0>iq>z?8F6Mo&xpCkIi@^y)mLY|^@fg3)>gUiZTzhSm{cvhdbJ!)ouFR?G-oku=j zdq=S5j;?RJd-vamKYmcZm)_3WZ6_T1=x0uxBlh{1|6c$FI6wl;XVb(*AM`F`igQSN7vj07Pm|8cpJB2BW4t^{T|-|K`E3suyaW6lxIQ}x==j9?s9d^-$}NW%6_uX zL!mTfIxpHcq=d7YQ)FmJMLJR$b<>*?qe<-iQK5oXbd67n%>*gAvUMInJq)p?KuNk& zp7u05CXFacRBDrbx>To?x+NK}DWFs#Mqs!ydlRjQr_s8?cGK6!>Jin?@VF_r03 z19Y*ARi-Hjt!i4;x>nI#6^T;WYC(#s|4iS3HK0)?PqX4WBDAvAuYUz>Tioh2xT0hs z1nujAh_uI<4oIR)QdVLEJ6XzB_9cTA5 zir4DsbxA++XK}T=UDgtc8U2u5N2;kkTMQ$Wd;M0lNhtV0_N|DH>n!yiZ?kXOl^yeyk#zH@VJqMs2%NdfF(BsK3cx5 zbl*!|(o|W+EEDpOyF6z)tMJPv=~8z4yCgC@dVtI?2-w%g4H~l?5VB6H)Wg=XrfxGGE)Z4=NCU(R{KJtLw zIbnLHcya_%m@hId#CfD1pS0VH=K^QUa78M{O*TGe5cHwa$}o~?GE>Oj&j)|_ zX~XmB6X+@5mt^(xO?oVY7gEd@fBfY?w7l!x?VD47uHnt7I4hs<@Snc`6hN!0zw!$Z z)su+g!y`yd7zDx~G>hMZD#(*16Y9bD+d&*m z!g2yYA%wyx|J(?a0lo{wzz)Pc2+_VoaEbu+|;+(@;=%RdZAf&8ig1HGV_N?+{D z*jvZD%*(?Z!@X3&uZ*kC!kh>rOpP>5#H7q1{75eH$(Zy@fpf6uLLx~6IdrVd(G^PTEFpOiI#}&BPqW%zR2K`%CgV2?W%U*W|&RoXy~T!KOUT$YU@F zn}{Z3z`88V$rR4#3_s!|%U?TA&NQ=?a!xr>N4r!>==4qzWXrZR&g#_7orq0O&FhnKuU2(B?DE;*21Bo6mtLJ#oS`-~3I%1fqZd03rDV1quKM z04x^(F#yK~i~|4&{{RmN97wRB!Gj1BDqP60p~Hs|BTAe|v7*I`7&B_z$g!ixk03*e z97(dI$%i^ps$9vkrOTHvW6GRKv!U!&!b3_`h0WgUrwb^ zk-qUqwJOm|I-_dkdC6aC>oFt6t5z zwd>W7W6Pf1@+Q$YMw3bmI<%_4qML&YB^rFIG2c{g7gyT#tHrQlUt27DHtkxz*t5&! z^pEPYwA#bR|0R?buwa6PX{%q)zP;lEI;3-?oM{v0tjnXy-_O6l|Nj66DByqu7HHss z1i7c+f-KpF+dxN6bjfkZQFTdvS`CLEhDdeg&rm^e*r8WoL5JW&WeFmOTH>`B7k9q> z)15!oxo9JKoQzVRAO)qz;EzBC`PhjH(Pv*~BK}0=l1w(~DUw&>zD(R$@R%+>`m}csbqMX{a+G}8M!V3k)UM>9 zNI{Ky0IS1Y$f~Lvrn=^$>b>hog>!B9ug7NmOg^y)!ZDq_LNU8>+bg z2Q2Ww1Q%?uNcawWlT+H3#BG`1M%+_Z!?=MFy|EfhtDNnw>u1Ms1qyGW28Bg$!YHS# zQj`2fu%Xrb)5I8?98>0Yx0VvAQ5<$H_8P)!Ou1 zE1DPYLC~Fi^VY-ayCl&yhb{KlWS4C=Xj~(j$)~ybWKmFIHY_f~;#QcPw`LB_5lu%Y z|6MS;;7vUjj8w_!4?lbcF8EvJ$&m@kC1+hky=hn8>DicPuKDJicP^miLE2UnL0UBg zH-%McTdGk1;O#SVAO?-0-g`54bisnu7bnw;Gf`JscP=A5RZ{oP*1J0<1naz$gYLYL zUVAS6^wd{x{q+ew&tT4^L&eZ=cKb8x>JW4LVNSA(NPE%h^-b{7#?M8bopJr5g&mS; zp}!VP*uM%}v-n^Cv@nbCh%9;XTAtRl$G`<)?|~4EpaduAtOmAcVL1U6QY1ta)Q!(f zJ&Tx7(wC(5v5!IS6Byt)5kJ0sj0swhgdN->2_7)P4*Xli3z#5@TUBjP3R#}X|C(pP zBGM*$6ilKLm&n8>vc`z&;hqNnB`Pinjcy`D7OPCCkxr%1T)ErC?pipPS^R>BcCf=4 zXUIdg{EvVHWEYO)u!*ZBP>2hJq8{Jl#6J4*kAMthL-sfuDQZw8AT&nnB({T9MU0CX zN!aZG20t>krGSKZ!z$#E3MLT48_D1VGF}ivwy+Uo$g?BXgg8XX5%QIXL82gMNy}Q= z5_7P0%)*egt>m?m;g4#pV;}r*#y|KG z3{G^ig$Gn+Mb91daw5SLrih4{|2L~V>XH6H zrbjIJ#btF;?Su`m>&;SXec~0hCm1U%7QkllE&MiTYlGx z@8HUk$4kq|Jo?dAvh=DeQ>j+B%GItS468B`T~3uk&zMs20K7rn=ytYGMQTxKuzTy6 zgfi5QV0D?!qRxsq236m&u0+yQmAbQ=4NQUklsV!b%5+;;j*N zOWyLD_j=-O5Ze;sJ=1jtOc|VFPdUpixsva>wTmvz^om_F=4Bb(LELxvy0}zwcOc#s zB6!p5yz@Hv!4MW3gH^J&_%39F4gsb^IK(>prYT#Dq-$u2%3HIUw!e!TUW^WxIMw!U zut7}l@)kT{ltuW)IL@)OYP?IF0+%O<#L#lN)m-O}7`n9e9ChPYr?hke8c-WB?_T^D zASzGB3J!0LFQ?-!d-=&Q(18VbFfH|HRniFM%ytmlw>rg$BMO zmb1L&MS=OxfDUwlCXB%{7eo@jkipF_g_kqrPJ8xSB0e{q`$$e~``5ZmfDwv8#!*3do7LbB zH%-h<@rqk~BIy3DLPGT~GR(pVl4wF9O0kS!>;oOz|E#7rj3E$xv$Z(=ULBhg8ER^S z6_5$0&Kl4%<&Ad7a01q7?+pBKRs&1oExEYTm(Fzf*gD-WkB~sLU<5~d+>F1t1Tu`l z&3mJRWVQ*X5486DA0Xo1%;e7u=A!#Zcz_w3A0dwxgFcDygo?Y(0vTK>TazmRbt zfpV?q_k48m`u+8=&+*e+hiTzr_#hfqcGcBQ`JuQjiW?cVEAZ zsSiu++yDMsO>dzmGEa~chwR^CTp#jJ05^QZS8cQ;f8N%9L+2;X=X~Me5b>vg-bH^F zgnt;Afw!c6wRcG0vwaXD9L*MdnjwJD_Iq<>fCqSUwM2oQmwcy&XL<2E-cfgYArTz4 z2`)H)M5H|$_=7;`L=0A89f(ihQ-sL{72U!}0{Cyzb`rEjYR0#N>&JkCLpb)vVtvvg z5T!1uv3Q_GJ?f1Y-+?4zd!~%FbnuY22GG_k{}6h5DXq?1m>rLD~MGssEXoPaAtu} z+U8e#kq}csBNQ=#@<$Q7cqP9$kMuY&!H5%B@rK=}5b%Xuyr+b2g&|td1Us+_F|Y%S z28|&Xjj9q1Z$JiG5Mti=jeZ!8<9Lx(C5Wqa5Ztj0MaTpP02c#M9^18k8WE4~QI9IQ zlJCS@x5f~@L=f465nFMGnxO^H|F{FyNCwb23p?=(Oi>8XxC#OE3kOL)t^$ReXG<8_ zl-|XP+IAO!1(E{s246@Kd?66H=xrc@lCi;(U>TN@a*rB^jO|5SNGM-QVUxuXac);q&Es!ITr}=h;_h~B;l2a zA(oU`nN4z!oA?lC*%8TzMPp)+2-yUs;0@JK4gTiTA(9jEh&uRDq;Z_fS)c~$8ZOy})A?gS7KcNj5mCXGCG=B4!Ho~2p6dx#QfQIy z*`aNhn=yDJh{K<8h$BrUchm>!y>t4EkG!Y9*dCz+%WYylE!0g2^eqga}yZi1s_c@bX1qsK*) z)#;fbHgkOG9FoDFsi>rEDu3}gpDdIeR!MqO3KD)n5>*Jb3eo4-jC%U~9L`l+A_AiPC{8_}Qx z0bj_mpqZwqK*}>_nn*-ir0|4Nl3J^)rx5VdkuSs%evu~w(VN|o79i0U+#yb(daTGw z8eICEplDP1IE7fDXbjv7JlIm zn~<#T`mT=pr#T9p4Z5SxTB>A1rXLnAAeN{?VXY&9SlJ4x+*+{SH5~^~9VEIDbde)X zwW$~}IGm6S?Fz3Jd$C;vS;7ddWOb?@5v_;{aQ=iDiK;5c(Wq(4f+=ONEPJrzk^~2p zq7fSx2SFZa|78(;k*65DvphRU8mpjU8k3xP6cWl|;WL2L3XlOcZL0Dyvda%W49F25683 zXaEE6$tKkZPrJETCJ~ROChbRv#7(%v`T5bTZOzbmJxJo2a|dL8S}F1w+S@Dm_Wh0 zGh#R-+Ae89vEO^ZV41k%%RxsgKD=wPXA68K+epVjyv3VXUM0T?783QlXBkbNds06fTR|Ke zLtMnF*sgI(!UEyH43P@I@C&)nKLON3L}@?MWJdghll-%_P8`L8Y<*MgTVy-5Re8t{ z|Gb1*gn|=H!Im2uZ`)O6Y*=SZ8jFz0i%`G%yT%hCoCncE)5Hk{)D{BtZlYX3c3^ld zLLTfYyMr9dy3?Z2OyRd@m zp9g?HJroQ?sXuIVMy4dn0%RjklMGKR%itVng{-(<8l9^8hD>q8tJA>0(Z0(1%fKAW zLNv^yVa)b?&zs!2%1jWq8NzBYvu$xdZ^RbAFbZr`%B$QK`C}`^8qN+4XoXA^RZO%l z6J);Yubw8nLDkE?jKQ}h&#Xkx^^DIXjnB*Lo=5D=74gT|oE8OrX@mfjj*tp+|6t00 z47=?5&^j%9SVhJ7n!Eisw2X|=R-w@W$kCT;q`3vs^Q;;r{nSrA#DUq&7-2tlP(b!m z3fdG5>);LEAP>PH59_cNT3~oLJtv0g55BU~Y)xKZ<X;eFK8;(Ol@F(JB3!xWL)0Jqw#UES7=t>?wmA~E0> zao{Sx;^R%a<-HI$(#B0w+z3YDHl9TC&EaqJeTi(RI~8Ieo)rD<8SuQ+^32_-!Qx7; z<~-7<|}Ro zM1W;4F6HN_7lg1UdaC7kEAo&uELF??CsU@1Ek8cNGi=mbB;p;7PGjs?evKNG*4?pQ z?NIG`#8VKq;upS|pG{+!zaH*0!%}>n#b6TD9s%aao`=+}>Z_hhHzv1YA*uXf?eD|u6O(X6CUofA38=*cN2jIxe?N(-0vg%tm?w+COgkwyNO9lMn#SzS|9(z6#=K719~qzXi?Djh zu;3`H*#P!_BR}*lDN;9a@)(W~VCvjRU+f)m?D`G!n?dFyUQ{(dj`*vJ7Ju>KZ3jA^ z+xm`o_NFZ$L*;@)^k|sUq9=37w14P zRhcxxw{rQ+KP4ko?#vA#VB-0210uHPs#1@3V50^5|Ila$@C5cy1jC^ENCOUfKMua4 z1@mC|Bu4XI#Qt&#ty(qaPpdy;mo8le8&<5;H^zp!Y3ODjIJRt` zoMS{pVX{m`_GxjU&|H_2J^lU#95^RT!i5bRPLf#hV#bXfKZYDxvf=|tDlS1o(?p&NToiX3=ACA4G0&(L7dF|9Zmr4vq;;p6~9 zcq8$R@wQs#4H8#0utgVNgfT`LXQZ)48wm?AM;)abrYr3VlS(D-o?7TUBb5^GL}Q*B z>PYj_b3+G+w6MpGyq;j>fMHZosEBdu0tXOB6^6S)lEgmb~n8mh1} z8YUmA4J_M1I5mz*b{}9|zR1r}U+k`YyNhhVWQcEv|F-=YXo36Vb zw>yfVPfsd~$ReFQFG;PIY!cNcv&sagg^H+U89?HIW)vdaP^XYOZUHBg15|;gjyjT| zMWjua6%12nVd^tlX)&uPwBYu{HrvnYyikTd{|u3#g9IJ4lTkQvlnG93OEFy*pM^JG zdFQ3KUVE8iHs8NGeQMN{-T+wC>rQIQ)TCTBPdru;HnJ>#V)cs=Xp$jhp+c+~<_Ws; zDg+v67+F&zeMi>mUXweTHsxsN+{iO97BNg)nYG0bjSA6#AzH1Lafml^&oz{{cHMpV zWTTHpI%%bsrj%r-Z_1>{sQe|h|EyM78nU&i86K^g~^%93vN1to4 zHOEN{Rc_hjiJ3s!p5*NB?LGg=Vm`o5m^mt508N92!KG{~50M`8wDJ$z?2HrUO5khm zH$e(k(1I6SN&QB~udkH^|6ofx(W=BEl7b;_Yw1H_!&pbZz_3q)o5Enc^fyDt{LVL? zK?7$lB0wIB1`Kvfp7J8NuJJT*E9G)r0%N#DCN|ND6?|d7I5-s#f-Zzx8C_LIV!G3% z(2M4QLL_z}iZGm{SrUojvYvP;8n$sU$+1HYb@)Gr^w5qtv|AlE1d#|1WHuoL5%UJc zxIrb+QENnGA{DtvdZlq$)9K0ynF2!EWYK%%Ge&nFqPnkjGUAk-RPnR&GC+RyjwE-Q5^*KQ6MH7&(L18xW*L?md8Y9GL@MeSEh-B zlH3kMjA9+Cfuwv8|3Tj+uy_=Jfzm3XG-WtViON)FL~dj|08P@_%+2L)nJ}`wB~hh6 z1!_=LiqZi6gey>aC`ycC!h@AAlLqTzMX$&e@p)0BB2{Ha6(SQWcr>J?^r$KyQquVm z^>#va7E2LSBja_3TQfb)-ToAjei9^lbrmF`IAIR7_SLU{U7}ezMIBQmwQ5XFic>YY zNfc^RNmb40|0p*q)&r1ItTjpJN56VXkD^m1=>#oVPm0;l3idgGU1>ZOqSnUP2wQT5 z>u8RbvLNErmv_bMLH3GT-uBkFbTe&qIu$BtvWYw9i%1GpwJ>ig<*KI?YhJ8i*{#m+ zqzdV37(g0QRH{;LB`xh|Z8F;60_L~yQY}ke`clBb7Pj}asXxNSN4(-Tw*}eldG)(r z{#vTM&Uxm+s!2ZLZjxZEl86_x(v?qw(hHKsszUODUFwe3!VbyqX36Q@@RIev&~ayf z*_glevX_UjeQWXZNn5Q*B)9gxFF|-IVj9=j#svCsU;hLsEY^}DVoA=HkT@1 zs4Q3`|1w=j@MWFX{p>_E`&Dv|H^ETOk)eQOg+Sr}VIVC-x=`VeWO%b-U5K3h z0%xSX$!4wvvup!rx0}*8a*Ddm&Ol^HHQR>Lr$%+EHzH}C?3l;av?6UF+viO3InYH8 z^bVfu2So4W08FNANv6zQkFt6&sy5k{F9R8tCBbHBc(#c%J({<^SGEN-T#H@2QzPy& z)VUc{jERVBa+e#~#@30e4f_#e9KfPR2HmW4jq5<~`m#J>a!aziU2%pL-61x&3@al~ z|HXLu05X7f9520`Y2%4o*5(WlJ8fp7{SlCjy6+zYzHyF=7~MH>^{X*5l~_;J*68!| zc>wLIrRLhX5Qc;wtYBT9l##sp)~<&A{a=80++NPMB}E8Wvp5!~;q9%d%63MPJ_0kC z7{4ztH{o-tSG}(v$4SW7O_8y9<%$jF8mX&{}JX2}8%k52G@v4(1HZR#KxjJld zR@tmpXBx!)N5_Z^-PuLI;n8Q7Gky94u?xv5ZFG8HBB~bekB9s*vCgA^6!^{-X;^u@ zvf#0U?YNyM-JQXc6?Zcj^j>@eDNIS(o7|isVIZYRS(pe?!WcmgdrG)N$Y zu`;g%P@9Ml5G|+)_viwTYQb<)JyN(med)Oetds!ay@^1$A36X46bS*;7P*=@id&us zO2C3>paucLDzw6+i9ne!DyUky1ap$K6F*OxHxIl(^~s8}&;dUpl*|zR$xx$Jz=8o3}HJ5}DvAKQNn_a5Pd7#9gSx zK>&tputPT(1z>@Mb~u1`s0C}Ng##D`Xt;%Pa6y}(l3UP$VHgH$C;~tj1#tL_E>HzQ z*o0vK2P`22Yq*6XC~uiF~9>HqA0{K+fcT9RLF&#kxv9g!eS~4{4wmyKIS^b|5f=w@e9FLoQXLc zFYF2fdw>LS5C=$j2T0fj7Tg6zK!rF!g^@gfGKt9pum<=ThvuLOYb=CJZ~-kyhB#0K zz;FXq7)l)g1V$hPGJqIsR0XuTg(rXpGH`_xumV)L1W15KlMJUGd_jh^6h+K5eT)bh zsElZXh=0@*CN#c^=%-6mKHF$MP4vpSq)X)Z#89+8gs~czOF4=JL%w9io9L*L;gVZG zg)qnlNbrYwB)`TS$&gfteb5qxxXFuPN*dIGY^Vc5(8IEEpE_U!P%H&T&;p*+0c!+@ zTG+-SFb4N2f-blQwBd&(0S2A3KlrOlNo5Tok5Rtghf?)uJLg>s^Bg(k=iKH}5Ya9g~(1NEN2C3A6b(o2LkO`iw zJrcZ4nm9!1Y!Trsjoy5SB&exp!%)-6rCqv+$N?tXSd?Ol!YNEh3uVz39SQ1;8U`D( zfziv7J2@iDK#JUfzw}Nt)QQ2|iG7eCdnkgp(9d(AgTu53QaH(dASHODhGqbUbEr?5 zxQ1JZO+X-ozi36-?et4- z4ZH8G3C1V_J*3mg$&{V%U@Nop|cs`Q%j6U zpbp#_s4F#ph|6B3)`gYM2)x#bbdv82p&Jc5|8GShfH8_CX$D_thS^+_kM)X>^$Lu| zSPT@`I+cubg$|CI(1n=OjVd;IrB{*CDu&(A)CfF&%}0Mtu{#>n;+rqFTvkRgNPj|D z#<1C>&CN+&tQqB+&HFlU>dVx@*m&F6`Sb@*@B|^?+OGB5IRM+R)!MPu+N8K3&RT-4nSHl%NXZt_E30Q$0B4>TEMn&4oW#1}vSW5LmBLi0s z%+YMkSYy~&)13p@P2H)|3e$z%02biZo!ySLjbVV8+*OddeT;I282AZZRnUSbr~@5< z%0TQjLMQ|SRfSQo5;v%W3ATqw(_UPyJHD+S>@B64lbbV`L(83^koaEk{l_BwyFEG9 zI4LuseT`X|g5n$UHmQG(;Z;0^#uRj*!>;j|1=KZIY3(`f!bl%goKq_NC*STpoJu`2Kku>9bg17 zkO@W@1~8z-a-f}zk%?qb2R#f;9k2(T(A%xFUbso-yCou!A6Gf?p6~Eg%S0W`a~G1xY|_9<)-B@`Ipbx9X4jpAj)g2E_@zPe2fC1B$5=E-;N8f$<9SF7Xh?#Z zU<6g@C@la7L)L+1Akqgln?{yD6W&`E&KJLhu5(%lOBP(#n&OS{P*3L9-*h(p``KtY zoQxn5El}lEu!Dydh*c1X|5JW}fl%dHxMf_fFI|q-UiRpX`(^lz-|J8xzg$}{CS5d+ z=GJXytvF+qUg?#d=GpujYeon{z-Dc3j72+uF0kVyV28xG2E|B0S#?rKn7MMugbIEF zTA&3jC;~751euWM!04(G948dk5qutmnG2ay?Pq_^*NrfNg#c86=2tMNnSaHZ!V6l9 z;Ef+P;#H6YEud>H2x3l%<$-YMRIX*ZuIRc_(SQEv!cMi2#^M>x;;u1ii$xC*Y6dZm zX_oefmxhANhJwkC=9#W$M8W9~$>vPh1VL~zp9be7Fw;Uvha^}AH%NkgC0EE~q0&9o^|K@!HK-h;kke}yxuNIc90oH>+t2B zfgI5lQRNRAl!l&YR4!tHaOD?p<+kMLjyCM{ZZpKzTw$(=t|4a7HD%)DNm`Uw~=+X5Gs+1pgLrg&6Pw zzk@Kp13V~m|33)u01tBlFK{tPa0CwnSa8QVFao83a9_FtQbL8<&}Knk5DZ_8x_z4L z`tWzP=bYfTK`@(&*j<}N@$SV47%1z7Xz>?6I^Nk~xQ-2mmStLA1#dtGZ`g-wc!p{~ zhEaEhYOsY#U;<7LZ^1s=$5`@N=da15v&2^Hjqs$8onO7IHLC!h$j)*t7lO;~?=}DL zF<*0KNA_e_b7UWLX7__KzXMV@1yV4CJ2-$l&~}BG126dYIq;}6fPyoi0xEEnEg+>U z7>Jw}Z9kt3Kz9s5f0~y)zeCsFB+F-u=w_Rv)<=)wi_m0-sB}xerKICDZByulCW!o$ z2d&tL|9O}Pd-w-?V25EKwIknV^v1u3p>7QTpnKXHI>BNdnK{-JJz$CJX5ILGDTbOE&!k=$IS+$49vtr(k+ zf54E(^;{phl|K=R#lY>f@@E!cg-GMeHgEwChE)iLREUI9n1#eo1wZJ6#195V@Pl7i z1!PzSM)>bl_ywD{`8$Y&JfL=+4|AT!_Mfi^qi21ghXbJx19Lx!rDylun2j9QW-vhV z|0Gy6Qpg6)OblEggvC&YTOJ260eBu{dcfut&CW4 zN-uk}9}P^W#I;WsX3Y(QZO-%FWe41WSj&X9vHR!4I)1S;u8Sy&z|N`S)Qip0QUQo& zzUIskV({R>0|$gCT!`?YK`36ti1B0bVyaTGBK`7{N|Bk1!7M6D)u-b{kAqNNyb~!B zwPOGH!Aj}p4jzj*Bc0k6>A;eQs?vTp7AHSE~3XVb1-n=}j< zLl>c02U%CW6Q>OIt=hLrm|33cw`uFqiudp$I0SY)Efrz;=%s>-V%QbT`!WI~~xT3{e;3QGVT}hY&#xO~!;)V+aDhgm2Rvn;2 z5~no^iGP(^dMT!>HMc3JoqD<{Zn`Oih8@Y7dMc`^8uzJen?T3OY2JCa%p0=WdMgvx z`Ll_5nfm%Gu%L11oLD!VMR%{qJ9qR~n_?STm{7@CEoHTcFQ5l#qQg&T@H zE{Db>cnO65G~-D@Co*&yL{LCMQA&6C0n%*j9`@&6=B&kl^0eu1CBq*Y|_e|No11*F3TlBh#*gc!4^A8XL8NdMNB)b6;_48 z)@hMZ`YhRHGs`O4X{-HdX(lv8s;Y6zJvSOMtUXs9uS$n2b=vX$ci;c)+N;@x8(x}* z#QJmW;f*`~IOLIMx;5pMFIKIBqh+gYhV5aeAi1H7+o9m<4&<&uo<%gTiZ z2@5QubYw;(+1T^TJS@%f5{u{jG7~?)#4dZpOZou|i`49rFEvB52=S3dQV&bYNS$n@ zWqBNc$jg052}{1&%#qa;v4orIr~Ac#6p z?NH8PO%b$axd3$y5@!ILX~ZVE2~sdMce@}4Gw2%C@Mdlv{9tgLhQa6jBQ=22ir-GC zLMC8`HWhp!*~Fzd#=)?LHoPGYowdLnQVw(1!d8P2x2-q4AwxwJ9TLm+55bA3U8w7f zyy(RwoumX7$dgz#nh^;+1OpoL$d^BO7mR&mgCmg;g+&O4qnEI;jWD8}i+FMhRKNli z)Ud}sisTRKMGQI-!`}A9S0(N##Cv(jgC7py2k=o!e0MD4Q08EasQfI2Kcj*t)WU== z>|-ij*aQ>C;uUCQViR>r!V{Lph(Zve6#{exY!b*r|HKqwQeTUdX{<7c9P+Y)8vG?N zH5e*U!3~7QM3n|zm7Tq z#E=Ft zhiq(NXV+lD8c<;sVi030*T}{(vXPZe9AGT}NJb`Fp@n3~n2B&Tr)EhHT=*(yG|E+Yl(JEZWBf4zHwXSx(YuUo7*8uqt zojVZXw%RFJ3~}pR#PY-wIWw;*;(aGLc-F_u({ zkC>qkwn#-G5?0YEJ}D7Rxe`-4DltF~MPz-jZ6ETGTR)uCC{$7kBmYq`?ODkweK77( z=CFk`7-0@pnFAYcCCYu2GHRWYYP9BZfXsBks-*E6Uc;*&uadXCcN1-b@# z&J&15h+^$oFpD-RCDhml#VmHw594u(|452ni`eM8kX$4uepoFPZ_--W(%4ENqf*FV zkqs8@Shy&T-jITf;%vY|6R?OABqD*78q=7Ol6hIoq|1qA>;tJ#-4u2MRD{+{s=K%( zO&6?k1_G1Wg62Iln$tEKw}q9x?M0Oc@1{&xrL{YR;0IVZL5QiW)xNfh=HOgdX8pF) zzwj9}q7zNv12ft%n7agE|B6m^LioWQnsDc!W8urx({(QHFsNGs6MOK38cfPvOj@)N z5yzOruH*2GnJjA>AHYelpoaB6Ijj#)7Xo%NaUR^SmFl9o7@J^T4q zZp|;Z;rd{@=DXki&S9e)-B-UxdYzSSXNS-gI{$iND2sKhMRB5&oa{t)HMt2aoaAbW z-xJ~-Z*{C^E%M!-)Wsa79fo0Q$2l!-U-tF0U%R7W3tmjX7E-y{m~md)oQJZV&ioBL z-;$7??cH|V8@{DqFIC>)8K43-&f$HN4ph_P8Q8!P9OtA{6=o-Jg4hw?b#F-#tSwzNAgD7}`7i<*kF~v#c0Uo?w4sula(1cMW zh0DQ0uq8#z8G<~p|41T;12voiKLCRvh{KTF0Vse&ix|Q_07D;8Lm$`!A|L{iSp|~4 zgCTgrRO~}1(AzQ$!y2r~F?0bTbV4%Z%O=!9A*79DbV@^T*8+;2LbRVCrrGeU1; zn52mY5gCKGU>XLJiw2HMXMA8#9G6Rkpo?&v#OA4s$)(axx1Vw;? zIQRqT7=f2u0TrCVa(TfVc!8DdU=Q*Z?ET&Y~r|1%^Ov)#!UqgHw8jK1W3?g|IVr`&Z+SMO&d?W_t-)Q)m|6vEMSYmfz zqHSd44ZR|J5X+&_q)z%uV?0V?{KsNcP$`DfIF(bRsUnC_h)sr0EQ$+fPysF4Vo*$F zIg$^*xLU)In#7>ks>NW8ecZ+&5=B6P5O_kqfDYeW0S=7862wf*zyTZl2sbK)CJ+fY z!qx%&8c~oV_80>5LBc7JLNOS^0l;HC?t?Gf!4?7oFdRTWHbitB04(g%9T-9=grPv{ zUa46H8@P{DF#o|V{LEA^!aPg`(HR{l5JS1VOfXIs4C-PD7UM38r5BK;LCk?K zFyk9IqpYaq6(9kECa7BS0Cil!6+p!qAXjc#2^@d|uiYh$C4z5hPeT}juZe?IRLo#H z<^lY~0f<9kMhW&jrb1+cLQum{c;O&qgCS4@_&i~pkb=hSf)|Ja{=6Y4tbr>`#Vt%n zv-KTC#{b4<9KbDk3T(1Qb@tnr{Zeg$#%<~*+GvW}kYw6{!Eb1gBaVj(EyGJDXH4Q( zCPr!Gm}fe5qME+xcpP4KKHw;hB6f0Tck+EO=Psq#gabIr?@6H!KtFHO_i3$m0~HVga%hJVg?asahhpz zF8`<5k!#}+DurRkblNMwB3|NY=L0rGW!UMRqQ(m8e`E(IbqM6n^^>>-c75E<=|<7iyT&h;F!5hNRoDzl~L zYEILVHfg7bYnt|JqIJr-jz_wx>uYE!+PVh3))}shg}k2Wt}thFif!58>*ndJ-R^B? z5bSmW>`?rxX%qo8sDfyyLNdf@!!FRnGRQfJhQxkLd9vxns^?HBYR7V{FEXtN>i@(s zmS9VKE?B0-SfUQgx-4?Wth&s>75u;)xPm8CLNe6hG7tkN;19j6&>K7lt%SiA`O@C+Nl)%Bt*%obJn7hyRI4>wbw;$N<6) zMI8u2DJ8=&+)SRW;h%v=0B(geo+_&r+ffi3@zNNK@R7v$1M{LraXoJsM*lA)z>F7A zhh=2NPe6h=Y{DjVt8IK8xT;P4lG$sBZ+(z&`>E~u&PCh0?Vt78`ewy)y07_Vak9uS zhRo2uvay=lX`Los9S^MFmPY^ng)0=o!X7{o5P~bHLMA+c3mgFAYQZSb0wWl*zYg%$ zG_K=H9x8H({9fMVY6wwaE(LR}qsq>Zyu?(Z98FYe#N~t-_$Lm?69~hd&8%(-Gw8vR z#tN5GCOpT@jKvz#*O+_-ayDof%t7%U1<|^UWc2W?E$xv&683~tYQWZ1{s_-KnLcQSQ0G4rFikTiDVdyFNbub}|Kjti*(JBy_BfMeD`s=j);DD$CP$^Wx&h9EMyOIy?adKiY>5Lf%tIg8kuQjYagmP`f-k zhom~M^IJfNd3eXX@!dNQAY!ZW8v8Y-)N|s{uVi~-Py*#oUjJu5X9F21#3-!80TeaLm#wt zBz(6almjY+!T}fpFjR~ugaRrIrWL}JilU=JpeSP&1AiYyJ_>6(%G@*~G0cprF?WV2 zttJ(B*_mB-H<^lH?_BxL-8S~vtJh5vT$+{ zx6lH&ag%Z`rm{?HYI76aO%ntYNH?}siWKABFMG%QNJbdq0c?pwALI@!aG_EZ127CG z%?UVLA4N8_LqpiA$P5B1@Pk5tLhdNSIb^~he042c10$@%Ae=WNM8_bM!vWL?l_-Kk z@tjd3tr9OdXms<|CP8M59gEu#U?;~pqhtnwaTw>#G9|Wm)ZN`>$L)srRQR82llb3_ z`iY}>itDYe|N2l6t}7h!Y0vmDKtlp4gbN>lDs!cDHy) z5;eKTK6&OwDwcpdqpmbHTv(QaFuE)QKZwYlVgKFx=Es=JdhU8hH6n4ED}^{1LLbm* zAF#Pn)FVt4tDWn)_(AkH z%ngYHA3+{SQY1-9lP6K847rkJOP4Q0*4dN{A}3BvaOTvx^9ma;kbpv>c52rtM8#l* z64!^Crat>X!SZ#-9;$44`m_VJwEvGdRP*{6$`;CApGetI*~{q9-a2IedR6oG%v?5f zu3)_@Wa}KGkBUoKFQBcQ0eO`h2(GVm*9|>_H<}X>MO({W#7CoBu zWYecnr&hh1b!*qJVaJBKh<0t;w{hpzP5Zzi)vfk@Q}*#wD`m=F5pVVCm9kc!4j6B> z5)B&CC{th8zMcDah|6TJ+&Nw+r+*sJFMC6teS7!hHG=G3GJJje_wnb~ubN?h|Nj9D zP{0BGa|ohLGTBeT1sQD6!3QCX@U$X~$%YX!+_=US7oNCA6)ot<1ROV9a0Q%Ax^M%U zVRUHG#TQ|WQN|f*tkFgt-2WKnJY(LFtv}V?c;gZRi7Ya}H;nm*M`tJ3N`r}(fVym@ z%*^v=lS~9r(^c)*j8)cIX=Q1*TYI}zSKB57PMhgI(Iy*ZaFGX>13pP78EuLcE*WLs z(dMP^8O^PZQD@ zZsjfcKP3OTPr<7DuVZ<;>2eB0D#ehOYF~$=4v{W`E0}0g0Y+8mhRWm1C$Xbanq=!FFU(A=Wbh~ z3AwLaoKhv)=+RMU?>tr0?N0C4VaLzp*-aKwBYR`dUH9F2XUT=%UozO?m2_}HT*QO0fz?FrqMpKn5)qWe;%#W0JoZL?nJO3QB&Bl8ngT(<%drL?{MOdP?P| z*w6&lpz1uUY84Qp=tW)X>x3)xrEh*|n-(gAHuD$`NaR7oV;*20iF-veSCgCS*kO23 z#N{3?intz)~MlA=AU8q7b6!11eHs3$7I+Y?$(t z+5etKg^w`73v76$W!eUtxXtaB*xb%OvC5!c2D3IF0i0J?_z7{ef;RFXCNPuPIKv%a zABk(l;-a~$9*V@OxYXuky2%N-*`yPbNu4>-8CWK)&YJ4V>R}tika#X6dj4?eLTP7D z#7>s7CG_WIkH@iu1{5~W`$$0#icp9w7P0_psJ!U7(ScADqpiJYHoUjdj@}F+AeEI! zb4k*np%k#+ir@SYQNKqb=B0faL{SA3i95hz5XJ42r=0euFtp?fuZ-n=Iyg5F))iKj z^)70*%GKPcP*-5R)hF0N)Po8Xm<{6O0HeaLO=?Lu{g&p!3J$M$!HmLvDB}~0K<{%tVU2GDLanuVuWuq}-^qlT zHu>GM=V}t0ye>nW1@?2fR);PGU$x7Hp3Dx^cmUBlcEl3K8G;NQX-UUM!EtA2mj4FV$VP^R zEV$P_O<>7W(rt;If`W%Fv}9CP#*bd9dgswhdY@mW^H;~Kt5&cBaf^6`HpBtLGJj%N zZZ7j8>MOYWUi&t7mNsZ0@(=uU^8n!Kb9;dNXVg8huvirezheqLDM1vi~OI~(QJ%ufy zx^AiihNYL}uK6iXCpbYg0Pm#b`YvZJ`|aCFVqO2xJ$6>r`!x-MxMJjm-e+Ijfo;2Uz^2t*j)3lk>oTC091yKH1 z(H-%X5N|-X23IpWm+XWkv{aRrw|+Ofmrw>zzxwTQe;bhG{#NeBrZ$}|I`X{XJZp(t zZ_N&9h^%C!v$wF295S+ypy#oGpZo2cpM9+2z2RC;%hKPXcfYP|qH!=Hs3 zhLD-z2hw;VebnT}vSuyfZFQ)@F@(i;?>!D|(EkXH0t>B2I8D(Kiu@!D z`&h6Br-=I)j*Korb|lUvge0J35YYs$`iz8*)X(r>0TD!w@oWr^0x8EVYew)7c6?0i zkWWtfkCFZl0D<0LP zuRh%44Hk_AGveM(P$vS7`CLT}4NbBBE(ob-!VIwy^+QG|4F@Yt@Ahs7OydVbA_z0? zp*9ZwLhcAzEg?wm3AqSkrto!E?tMll3wI3w5o1%ZEL?U$0liN3V8iun2@NOE5%H!Z zV4x%x0Sv}V>gKQ*jj=X-Z#Cu*@hL~zkiiU|ne68|_MNdWQB_$}=cj2ACVvEoh< zujtY0j~mI6pKOFRBvHd2jk8 z0Q2w!sb&sTWa$7>B@9dD3QCU<0&EQBBtISy_9UgQt%_#2O}%Y8^O`wXpkm#G9-}aG}1A{D6tapDo9oW9-!)s{M?bC{O%)y(0WV^{giSbW{fG}PyXhQ6#22zrjlRu&no$E zApP%YuHXs~@*_^qGKMaV#!?Sik0qKdEn_hk(GW5hq*_FRuH^C;e=!)d4L67pFQK#d zHnKbTYd^lFbZR27y6Kz3DIif0?G7`yh|{|kvoU9f?#7b^E$t&H)1THcKg93DjG-vW zZxfj$wKgi)?C7RK(=-_hHKS4zS94$V&xo#aX&9+b&fp_x6B0Hk%7P*{QR59lXPc6U z8BOCiDH7TsP#4qFK0w1Ib}=+8Fgi_Cy#MTAI`Isp6r@~)=mZ6muT%#j1Wg;a@k7ZI zo)}XIceF9l6GzwXMh;*`hO|Aqk9o+l9r-Se)(8meGaf-xwIU&pDoUefh93QMKt2iz zrN~HIWI**L6>sf8)dmvsgbkhy#egCW5EK%w>ovT|h&rM4GW6(FgUa%-K4?klh7(9x zgXv6TL`_0POY}qyRaf>h&svmR;3N>o!@mZT39`{fSI|!@OGg=^pwOd7ee`z5(NZr= zNEhx!*mFpW6z|YL7jz*OXk!E}>pkH!GeJuu<`X1j&_0WBgE;QRVC+h;v)SdAJgidQd+#zszFaK^T7kXUQP zSns8z4v8?!C4oGHhLX47B)sl zHfv(bPiq%#2NMzSaJ5J}_5hGDWLt}HnXqIM*NYezj0{Hdc8hYA)lI!142q5-pV94L zkovqObbW9c&ckU#A~;dkLxFT$UBfsr2kKxq15&Wb$S_A7Z$+;h=5^>0AZuIRbixV?KV@PQF?l0 zZwF6&!xH{j3)NKZZ|mrAO>2!%Hf7uQct)rS4HR{d#%J%No8)bOzat_g(iU4HRn)^Y z2sm}eQ-Kq>byeeB8<^b^l|^m$TcWmtzjJFbxcNvpHcHGL{-6imfgg~G7ewF`{8(0? zuY=J8BsevM8)Ag-cvf1ZY+dAe3s!k2xsp%VgqIgpT^Md-m;jG!S)NJ=b`0pv;g-~f=g zj;0jkV%l(l)$!KoQZjnR3b?Y!vo5?lh zc25TwmQ@#ln^VIh!`YYOvO6MJf~B!Lfm)r{d9bLqcYPP3SHmB$fdt@Sk6Y{??tu@s zfEW6CkpJ~XWk9%~MfgB;nyvE#5+9jVDfxsi*?Cu(Z9kf#iNK;^gb2_8Zb$k4l7I+` zU=iN-6J9_+{NtH7(?D3-io%y;{g!;`(MoQrrjz)lPZOAfnWr6kpWI|}%{s8iNn3%$ zsJmFV(UK2M=gK_jsfV@^%{ZIUShJ~jRe8fSwECMFxT|+#oUg-u9ArG?ruc}4&tUef z%i}zFSFJNxuv3Es{Xridp$Ej_pCN)9`Zg zGylbpC|$z(N}E8&*JBwW7`lca`XCq-K_FT@Fa!dpf`O<6A`)^zra}`T^3kJmx}9Wu zwkNAK<@e8C!na*xnUA_o^Awu%EKloWs)VyoYw)wozF%j)i6m_8o6cY3kr$f36FadR z4je9KlPMaqWuy=oVZdR4VPU}GbmSf;JbF(98eRg#N!%TSglAD4O8Yh>1fmdvVN!m9 z5e6a^eqqK{oz?q55n3ImQXvvhAsAM{7JhsSN@h!myvT3leHBcKlibg;mC0p;LjS#q zi{VsUmK`ni!*pMdE!)!hq*^t`Rk;^77EFLPy4=h20jpC(tI2$g+gO0j8C;;T_?E%D zCpA3hoX{u3&e8h<_`%N4!@c|5&+{gh0li;g+uj$%(0Q^{M^%gfAro966Zk;~ieMO? z;2&JU9=bpWzyS>SVH1j=z^{Q8YQY{X#vE=zALN0;7oh`e3~<>S5CxmKhipBrseNZh;uU!4(dm9jKrjI^hP);Q-QrA8z3toa7pIU>tS;VxoSa z?IG$%IuilUGtW<6Bows=!;}Pqr<#jWRzVR4fs@PtrzCw9n(GpRAref<5&ue|DT5tA zb&1$*#Mry6m~(eQV$lkB7Dz;p-9v)e11VHV|Uq!l^(JjQ$3);ph(_8;sxpJX{d~;)W4LmzZSR0dB{E z1KFq?0Qcq%qhkvzR@{LxqsEOKJ9^yl#@Ih&Z$6r&;-!zpJ1klD>Hou$QLsUG6s;Px zN|Bjaj98|!WhPiDL#a}k=`$!5Aet?kI(_QY3l)AVt@Sd>gB|#6QMU; z5$mP=mC1p?6$^U?yqWU>LXZ=0%9JFv>eZ}UyM7Iuwc**cYuAQ-TXscV`Fi)}YNFzz zMX`JvKmIA!qTpd+IA4gy&hY8ft6RU0J$v=oukrfhWLqp@CT|>@&%3Pe`1S1Dm(N?L zEBEBYmC5~m1m4X^> z$YF;HwgqBZ;}nq$Aa2}Jgd5k~G7K#`faAhGWZ9#`HDuLsOD2F2@rgdYF>_o##HCdT zAw}3zL~--bBTta|FcSz0FT`L3Z}|ig!vU^b!H6P8Ffq;n?J%@ZIR`M3%`nYeLWMOu zgn2+GmmKhhJ;V@W%q?3{$R|f3jZ{*fJD_xcN(({dQZT=y!qO^?n1M`BMcvUyFpQS6 zXfQpoWQ!wAAqr|sQV9x@F;`{iVX6y-$ZD&uqNQrA3f6H~UXZni>v|fNcAjE+HHIE! zoh)OkT)2j&S!c-u**OPfd4ok8^Z6%9q!PMPs4W%6NGgc<BSdpxs$)b-AE9j<&CI3h!$=J$Czpf{npk=+Dmsn!U820*K z3;AUc@1iXPtv}KVB5?8aonG+3-L|&SBEDG}3v+P6pu+)ZBxmLG(QliC393bh2E5{D zhlaq8VaDNl@1dt&?(Pfb*x2$JuNw09-~ScDk6gfyMGqVJ5B!PcL8kIwUIMkZ1e&B{ z{`i;x9|%Eza4|I* z$WR8K*xGRxkpvwSVid{H$2aKV4tPi{AG-KNAYOoiyII5tf#{7cytbt-Z6-`(x&|X| zFpeEuV-Adv#W3DBj`Cb04V3Z3Ekc4B1^-H@ZwTZQ;3}fILg?fUg|me%obilcIAb0D z*atOG0XbV34Ud6U!+x0cr$aOFdmvX&*BOqn|g(&N2P@j=k)YyWVMrch2$(uTGOnXhKu0b-~SSyyZM61~wn} z$=)Z3z)Sl0l3jKPpD?jgzH51>VaH@oWX^ile93Qqs^qI@BdCy&g~U{ybWBBVN>iGW z(_^1)ZRo0ZmIHv5bS`L15oX8)dB|W5Q(Htq3;Kz{p367);KU^;%9R+zz&8~!0!+7J z1dUk4D#lm{OrLv^)cQ#ze*Y5`N(>dao$@poLdix@^Fq`dHnIB4m-|WlnBRaz@zrH!l=QD_3pFeeVE^_U2_DwEG7&A`uCsPzq6h z233AJmKUyeSjtjv^8fv4RWD8u;>N$T4IzN_R;_?1)W)i?gquZIx*ox2Jy*Dvc=kuB(zWwEl5HVcKC}On5_lBNFo=@ZuVb} zE$wA9o6~~%*E9EO>2P}}BcK!VC5SvbaN1eB322>W4_1cz7Am1D5pW-f-U+?IMh<`wgfchu;6P}-CV-I`H6OqTTkD$MFcRlZ zK3pr2Z<|fqNTD}|m*sbegn0?w7=D~Q<-~Wi%PDlRn9Ka~>#TX@?^j9I4PMn^dBZXi zQ}nPrc*;T%Z-14#gE(;+a%q#tibcMI`sn_&mDzy!0vcN}O3!7v!VKzB@F2X?o8 zfZo zWEi(68pmD0M6_K}beezv(=!dYt57}^NF5!oWvIWmKAs0h= zJ(i7-bd8QgV0^KNTH$>M6dsWgES)e4J-%^RUKf*>=osO59~IacfER7PC~bCN3u^~=lJEk&2>)%8 zfR%AKcsZtmE7*~iCJ($I0;kYF2XK~CFaRJRFV&(*yDQ0T`hWsdo zpx_&eQIKwUdv=zPZlq`61xFKUeAIvlnKO}4u?3`pk(Sn%qqCQ-glVj^X@hqF`Qntc zu~sFA9+w1RaD^<~*OI0IlS^4GB14n)SCiOMKR4Nv*13tU5m>R11XWjx)>#qEF&ro6 zBsR1?%P5`kCxHsWY!(4`!>|{>5S(;pV}Q4Teldc8p`U~2ZDWavz1d^?5dRKnKmi8A z5B-4+3g88}@COaB3uxy*3(+9cRF`)tc}u1$w>66dS~9yCBIV#RRYnNI@LS1{4dO@$ znIHqlFhjVI4dcL8?$8_I;0v;l4VsyS_?Qo4(3w8q8$pT$qA7-ArVNcyJF~NU3lVwe z1}J&v6}1@&uwV!)SDUtpo1~SI8Y!Z$0;1c5b2?{Zm}MD3rysmRJB;BN%Wz4OK^vN6 z9~kBjc-5ZMNifyPlRcT8+R2mM*@-&o8d_!o;1WH7>J>w2l*ge9gQb*r>S}dxb{s-? z$aVl3s0Eym7r`J8{y+@DFbr}47;dL_YPWWQL6tmLcmirXVcKE$!2btZzzYg`010ye z3{wwL@C8b$6?xgDj?|<@(++V zA;QOJu!(Y5nx#$gXcx()x~Z(K;;LdrD>AloIQD(t(P{ayR;9HV{BW;z5m$A=bQ$J! zkUAf+(w*ZeihjD2fU1dtI%~aAAE)R``knVZmVw+gfe)KL_Fux%vhE@&5<>;}s0_c-!==!kR!f zs2|4KWyo5V2@4_~Dh@I*gfhSh(0XMuvPzmvr?BJ_{SZ53W_-i8?xkpzOgQP zDi$Kv8!`YrU3Y)KyJ3mAA!=7&&qiOf@C(79UV4NMiBS#65De8&awNe7{pppn(6oc6 zj5T|Bt@~MR1u+s+4;+vP@9+=$U4q)N6zZyYdd;e#qB8Or-P8ZUpvthQGCqrm^ zh^xyMW@`>IKnV7b44kl->_E5UkPgeR27y2fXttpJVGr4m0|x*Hvfu+i;tt^83n;u0 zJemVum=BBVqmP?~GthcLzzIJRnwRU3dGR2s8Hai1n*W-mqf5G`i@MV1r4qar^4nn_ zIlF=}k`kLM`(e9HS)6hDI_>9@??=7;Co8emSIqOBCP1^a@qZ@3Tme(YdUZas0vP2{ zg}yQ%ZKX^nh{cYfV{*)lR4i8X3qbw=4;-Kd{UHyQkOA-T4q*|%U@MXZv=Hisz!D;7 z{edBd(ZCM;TM%4%Qk)i_49Y~9bHGw^0JjyQ=l`ww(3xB@k3*W7^+>K*2n?0b3P5b6 zt_OQENH^lNn!(qapi8>POt4gNx{G8gP;7amT*`#(W4~EegCV=_L$MWWFO#vH_`xsu zVM;HVS9APf9AdmSDQm2Ol&_o*rXam@p=IK^W8_>sI9pkO!AZA!#eUpOi2*S18^6+Q zPVcaw{y+}^^bfhJ29a#5kqj4JYfdELc$CGjnQSp40Ssi=Rt_WrOg7NORvgo}0@80(`iUCqx-u&S)us#m>D1l=D6av=M= zwGOSTYZ(_14Hk(V82f+?9PprMFaf(@7z|WhZ}?^eGg<|C z9u{437|q%I=#K-UzzZSTsh!%T?ONFF(V)Bro#&~<(Aq35(>46cwEY!1ur>6MnTeYZ zm2eCU&c<}K;5>8;lG!QSodlfCf?h5Fv_EEoUhsKjgE^;~SRLKvLH z-~Bxp?+egmx#g2owE^T0^6&~%fB+znO$QJS4{l`m>JbDpWEO57m@KxMz2QFH;Z&Pp z;wa*yE(0XqRVH3#quzO|&Hotwc7>uh29;o$2hawxfC-q;1_zJ>vYx^XB@1nk!nfCOz|4+ntjNI>jqGX`TY56nOh_b>*s zfb4#o1NLyPC|n7$;Qyn?AP&y5SI1B7M zVfk(!yxVI1J{M@5VsHK%KS>+11joIBLkYi1^}>=HG9IuC@%}A5k2=VBe~20Ja3DY7 z2ID6qZyuOUQ*rhWo1N`O>I0Ra(*Dp1-_i1$@bWN!$}$f@r+wlMZ1dS54)Z{A|FH9d ztMgd+^9x}%vQYE~(De2w3rkNA1=nxcP`GX23pw2e`)~}z70LWS54|DnUhjpDORm_S z?U*|tnhp><1pf{sSa1gwF9#GZWT^1YLx>S2-hs7`-$jfWv%!iq(c?#nTMUjg_{Nw& zf5Y4~WZBZ?OPDcb&UC56=1rVAb?)TZ(Q$^(m%`+<%pX6L%c`yFL}-?z1GDTj{I%B3tOIWqN?H|nmX-sn*0yAFpzl_Ogu41m zmT6NG#EBIzX585EW5|eOK1S+zQNDb!OkB?Qi3n28u{h_8T-x+$)TTEbK&kL5V3=8@ zW~E)*_U)-C{jHXnx-@Ly!G#YeUL5AgOA9ZN++jQ>^MY?KUGirP`gQCAP5uMM2FQ2t z;l+>lQUAVtrAq$(q3pz|{l0y>Imw`3-~N64`SHVm;avDn00R_Iry}$-P=+;3lfB2yXGkx~? z=bv~mTSFlXd!!Jvd~)!y#~EfA??@on0OrOeZ(J@rfe?}jB#$D==AExH;wKwwI->H+ zi9~{uAd^s1$v-rM8gNZEeM<99IOCMFxJ@>JYBt>R)QUJx*5e1Ab=335nSYSMW=Y3Q}#Xv0%aUVCMt&(>y|_0u_vHTGCJp-WDoCk;w=OoFC^cFgU%^A1UDzZ=rL z^!QoNpH3>_!9Do);bfBo(^Z#0WYui*T{a6;_r5g}Jb;)nI5{Rhe-6l|4Ihy>WrJ#yiO{r^)wy!Z~s|~ zYD^&@4)M`kc{ zqUGDY3})Yv8FyqC9!=cLNd`ekAEtD)hrmK3k?2StiUvU{d4USAW7?TY_n+j2kS9g> zU|UO`{qpDb!vh@rza9WfqM(3;#`6NEE*9 zCKH>IToX;BIK~_x7MRh66sb6w$b?1)KyqRiQ&R^X8gWlb(HslSc$GKkrVhdi9SYs} zMq^D!H_aM|b6%$`IiXUt?GX zd@gbffL+K3;_yKm;NSyr0IU)hl0_%8VK5c_>j0JTMGnTXFnQ#F8}7&lCuD)JV|)vK z3i*dVFcS|<9^iiY(8cx|(j%2&W(@!PV~^ONi6(W2j|$A$8xE2X2gU@0R(c0DID)~W zX^?{_@kb_{2FIi{Qk^73XFJ{5uB`c^ZCpDeZGtn3QUt?B->OD62LH7lPTYkdWcUT$ z6v8N>9FZu3;RH%Hu|zLMbZ{@R3}!SF8py@Uai5rCXC(Sj$2_HSL&3^X%2-d70xKDy zYvVgz`qHh)5hZja&K;rTIw)0369?oYc#71_+jZ+AP$47_9E6fXB63}eR42S1IlM?t zvXZ;w2PVyfFmV8El|nj3J4(69@*pgfU)%Dig2@ z2D0KJMt$2`$}Iyam0gDmP%D~B$n9!QZ_!>oX000ZW&ffLDi-WYf=hNtXqAC&-Dc_3D>12+?8Eb)Pm z{+bVZyyGIfJOEv9G^2d1VSD|{$N&23qZ|ygm_Tg=c*6|B;*drLJcmZ8FA&Fqj z1uk;Y!rV-nC)niHp_w>tnG?gf(F`|M9o0n=xM=2&*8gfLMs`W%I6(-jK)1+U16IFS z8o3|`nzPiI;{lq}9HoT!j^iDONh%Bs^PU&I=oRXEJ5ki${f=M4i?4p>OWz*%1i$lg z9x*sE1_1kGU-1d1f%TW*4;O4mePwWnPsI%M90NucJ_d(9d@5x!^LEJ$QUFWLkA5BiH=q(Tn&R*PwuYa74(1vZ!>jA7smQqFkBxUq6oW;oO4gL{#3mdhNS z7qSdL9iVOQ8AZBT=sD_E7trM<`5Os6Q-yrDDF2FPx$Cw=*8^xG(m~TGb-XCjZ zqjdrQ`q7=dyD3LBO;~<=flS937N#qtXJ>QZ<1R}>1s5lDuIcywJU^d4R^I`{pZXNt zzm(j^G4`cuvl|#<+h;m@56lwl4GhDaDF3iRtoM~RpmhwGVFp?sOb@ZU%-8Whc3mMv zu)r2c?QZ8kw52Wgy8Dty;0SE9yNSTNoYK2J9NMaU?{cmg|c11$(a-;gusU@qli4c*WUKanRQqd?i{8z^!;2+YEEk-cS6x#Pe+ zmU}tgvoL9rwBS3#^B6u$Gd@g1zRFQPpfi>R6c9JyuY2*YqbnEqu&SoZ5Lf#!9yx|= z@B!<)odeLGPAaj%$|@gloHo!0YX1P33K@r1Vwh|o2Tll?Y&ZrH$p?KP2ZE^taVQ41 z@)00erk1I{x>7duLIOC*gFNUzS$w;1aWRk>zyLHrk3hie*si7lyg6JGEgZ%`J2yL{ z!VWABLU@B^1de3fK*qb24@5yEOoBqd1$jUWGPnjiPz6Frj98EddZ34K_yl^m2VQW6 zZ?uL&2n29Q0z0q4MzDiSAi-)>4XA(<=Te9# zY{=51CuF>e>AJ#^BSwpiqbKY_Lt_ar48z?ULy)X1*+D~+^pUD#k4tMqo=ZMBtN>j= zqQ4L3bB#)b$p=iTN`(Oj5PPt$E3vPDA6ERMmT^Tr zfJM2S#r}gkl$g7Sz{LX8MTppf4PqTa+dICC$pE=X!vr!3+!`u$j;(2^s33$mslaDc zisx!5C8EZNBf)n}f?=qGBzS^sM2t`HrBA?xPq+tq_=F^ohbKq|#83q-7zR5)jD1J~ zXn4)ooXsSdhkTHSRyh%QAcWv7gmoY@&P;+#AcSN92QWBD$EX95!nn4P6LoXQhFk`S zjL1Cu7NKyW!~D)T;lhPbxsLx-G%*axF}w&(C`tA-Nj20R_G-i3dBc{ZkCy}v!UT|+ z9EN|m$woVgX0X0};47h=wZ7s6YLEqc$bm{2um-J!F?a`A5C`qahGLk9cF>IpvkD^;!ng zLp=YGOlQok-7?O|+st{O!PQK`dTB-m3LT!a(R zha^a!I=#Vp*c5Z1!EFCP&S6M`K!{Z5T#U|ZLid0Q$V?Ne@Eq&JPVJ-(kn7GSDhDk+ zRpSs(Ln}|4+M{RE1dl;aoVf`6YfoD}$(%dB1?jmpsL%VtPb=*SH`veqv?lG~E|jRM z^m7S66v~EB5r)wiWb*-jn9A@Q8E?tfOR9u_D6oC-0VfdAdMFWpXahx1gjgychN*`W z>AJ7X%6uRMS%{_b2oWD?gZYs#!pc6NLV_Xv*MFtU|5H+w*aukHOTJVZZky8A3)Y^% zQdEstm=e5*{F-mU*3uhO;V7x3&DL94wKluG8~Ur1qSs9NpAs4TP4Z!!-xjWRh5L#P4GG8 zyU(F;Se+PFnp_WKxJhH(fih_ZPtcgMoq?C|5tbl3e}NE);fGP$&{&O;j zm_R(~kl z@F)@n>k*b1P=jHS9@SQipxj+EJ5oGEYG^PKy@yud1We2ZS8$Ke9Yi0H1z~UoW)Oy1 zU{zVM}%?ibcl8>oeXk|jMW#*h&Yi#9s0GVvig{>r1#K_qs5ZY`cg5*pB zq*dC^!$6tf1Zd!gsBlKBP(AD2V5*o%irm^u9_N=Rh_5B#5*A#tH7q^?zx2o@0<)f2 zb77Jcst4Vjl+-!**j1!DmtJL_yrpCvsKa4E31hefAtn<5^@V1*2qQ)k#AOJ@We8co zgfefIhW^j(QRbQ^w3;u?Ktb2Yc{LLYRkE zP6Be65qcnpY{-#(U<7&SYcRNmY_NmjDuu&Fj3=-La=2f|1{qy|SA76Y#P|mTegbkp zj0OJegM?1qkl>-n)afK6tf(Aswv9d;iY_{9*&ffpj_op_nFE5Eu%4@1r8Y=E zdcIYDkl}FQmweW_-pQ9vSPe49Yb7* zF=zuMFu(KAwJ5f*N;nvWDaG;@k*aKkQ{je6_+0mJ1p*7JHV~5jp@&~Ek6@sOZEyk~ zK!P^V7jHlYUAqx<2nJVSh5&cnRfsLHb&w9RS?;=liExu=8BvL|Vd@kd-Eu~`?{1{{pyI#`Jn zR#`YAcZ^NgG~jqz8gDMF=r|{*4XlN2?-X__hZdRYF5HV9K1Y(H*zzqeJ25{txE*t# zN)H+Sff;TOHUIZ~;RIrU&y>gnb2Z^ohSchkD2CM(N0+sLME5LL+?vYd% zibIBl4#$}T=#o&F%Of4$5I;a&&pQ);z+XpqsDGmt*G^*xsFtu5W`t`n3$w0B(Vrg&^QfQUYdW##gP z@NIk7lB&Y@d@q+u;CJLs^M5a@7a$Ye3zlIpcsFo9gG} z^O*4R=y_E?1!jde9e+D-lNT_fj!-Pp5LX0SJ zBE^UeFJjE7aU;i$9zTK%DRLyqk|r_kNU3rq%a$xJ88mpwCC!v?jQs<~1_;ldK7Rr^ zFykb{N|h2CJ;LglB_2i2-puVT%rb!*j1{`T#w^rO^)X+_=%9cQ4<*e*5ChG;G*EV}>uiN!)g^%1a4j^3w@)GUduYXUw45rp>XK z|2~5Tjg+cFA7d18O3mrg>ej58<;&MfHEY&Lss{g>Z~SA>285?G*t2O^lDf(sJ3$tE$SMv#OPQdnVy3?A?XAsQZdVM7EBnA$S_ zB$LS|6`=^xBC&l!#3!-EVnT{DCJ|dci^RerjXUz#BZ|qy^ah3ubux-S%W(1`g`A9H zp_5NS2_+}+`6H5#J`S0smRoW;7}KsKu$!$~LhTr*E6oLmFWs+=ezk2~_X!ihSqabl+rR|NA3Gu!-f z4?XV0wvCOyu=2?&t5g-t4^-u&%Qm0X!OA3XkaV7Rk+??Km}Y0~1`Z!3}K!q(2cx+3=GXCYfY`5_ZJI0Rril8hj<5 z*rP5mnqcE1GF}N08aB!xGRY;g+;S3i#I%gSt{TJ%As1KJiNibdOyP+BAQY0zGag*D z(F6;rU!_Z@1XE07u9O%~nsU0Pf^Gl&Lnl9?I&}bOUF#XP*jMox)>vg#dDaUo-LQj4 zH(-<)T!zXeSCxk0owqTFy}@*)P8$>%nw=636dRfV1I(L>Z$0W~UjLI#8`t@2P+|vBIny62Tu}{y&?aGBz_wq;QTSBGEt3FRl(3^D)Em{jjC~^D%IF(=!4+l zsce4g1e{FhHU^C_h%^D5;0{o@BLd-YiHj5Cv?eOZfunNvIL!g(A&b`0$`$))4L@8# zjMNyz74NXoJ5U)FXz*-1qC!x)JHi4cQW!l|8!a9L4E4nES(j=Xa-ouQNC zW_SP_;xmV2>5~vV;fbdysGI_AT6mnI6C?6OAwOA2;gs0Kr)VmYQJGWM4zQ2d`9l%= zP>4N<(W^@|!xi&NjXk`$8e-gnAM}U~J5;xfFLGiZ$GC?-Vxz2l=z|{m00&jtal;(s zV2?Ip2Jmt~h}h6WB+4UKC_=G|b1^ci+Ytj2axjBUN%AvuGsrM3>COCTGOPglDp|{F zRt~1`NSt8bHKBwc{UK@@NOIN9G%`z)$dV&5DGSGRS-=<-PZtOLpN(R)O#~`)7z%?E zlFSF1g(0b}l8ygK&_HrnZk{!>2m9bSKQd4umI*Y8)5NCmbRcH~>Ogz!gf6Bx_p9L*URC`c_Vk9UHq0FZc7bmTy&{M#OSJ$!zj5c6G7N?O%C$`9% zb_@fJoU1MuJJF2PcvKwNh|L!Lk&R~5LL2jl%|C2f4|>#t8Eue7Ppbmdpb9lM(P)E> zLQ=@4k_#46m8uwkY8A|+DUzS5q-IGX)(7*a!4jS@g|#F~g+)-Z9xBk3z)7VZs+F!n zx@-N~w~?R8>;QyF&6{c(o00V{TLfGgk9etzki~|^m*r7n7yA#no}sSeo6-U15}L?r zc!C|Sk~aS@Tj3{bNt{3Q>~8&5ADv{CqM8T-P{ei;A1uUj$4D)lnlnvO>HeaG`?Q3IuBxyx*k~bWp zC4c?B6)n(Nr;f`B~wYcYwiV;c21a6euKhc?IrA|r}QkF{C1 zdG`Oa%3Ai`*Co5zM3WdjAy z{*W_nP3RaqL%dRH3JKoX^aj@gNotOtW9LqQbDFv zw?ZUTJU!Y-8t#5~ycdxol=0HA_fF$?6^N`;h-Q zydg1{xm=dJbHd9D%_OHv@Q}Tg1R13%9%rrA>?HC#ac24XoBi-vOTU<;nFJ9<=@50VtkWjo=BQV1r#4Dd8T4 z3`ij~LKP{H}g z9_@u2D~$qt++GVV8SnL83Uc8>2ubiA0Qr5%l^vh;cw97%MpiW6^DRj9nHm2@(TP>O zmiAQzXFSFAnHovh~XIGL{98k&Dk7Ls9&JHU!hS({LSCoKw=~&gkt~; zYqSO<1fU=UAR(v%F1%Yj+(YCD3sn>kFL>Y$MIcg4V2m9FM&yCrS=^``7c4vv2cE~V zjg1|K2QjRH3v^*Zl;HOO%r6pSF<#QPtyK$B9#MqaA`ZOMdS1n1$*gyh;M@Zdo3 zzzZ-zAmm_-5zr$1RbU~OAk={}oud-I$-cqfR}I9^T;7prh=jmk{a<3?35k1Rwfg zZe;{OGKTpTBKi?Uq2V0+?cCv{6Hqv!{Y7F-jshg|U;bgDCKf^|v;r>l0wH{YFr7|4 znAa_E!WdXZ4vax;FoW|gK~apJjnG3IxMHtO-^an>I}n>K<^e8>4QI#;FUmkz$^Z-$ zV=(&1F!Ezss^$2spgrE>Kvdpb%;1X650|_TLr~*IFhPEOf)i*#g>2≻h$5*dmOV zAaOz_B*S7R!vQcRW5y$77(`j14HGsPLBu1!5rULJ13z$Ew`HL|?$}zUpks(+Ku%m4 z0)?7&g+fFHMrPy#GT%p##+PY^Kah=AjAB<*WSTieY*xiaa-{$DR9u|(Vau72@SP@2 z6beop0HX1kNs>gN6{12U;`#AhBpqKE%z^wlMofZdc-AB*1fWjh0#9NhC(2!nNkeKF zrBwt{J~Uq{CIlxuWo$@;R9?h(z@k-BRHE_2xd0mna%I>s1!#b!SSlzCkY!n#30%Pl8!4&wiB8DgJ}1a)r2nM7w2F&oDD zgd@`5cfw?N`f2`g0wWMYFYsh3l;=+30xc-RD)x>vnBq~|2vEU+9w>x;<{CEWrz;*( zRa#|2K$TWbRp9A~9U|x&DCns!C_e^ck+N#53Jm03A?}&PGB!lSfan5oM2x)vLp)4E zoM?*vVDG@ji4x2ca*%|?jD;#$b-AT1=^oGw=@z7I<-$f4O&e5r53PMdWf zneL&P9%suT>1mRrLQO_U$mvHA8neC0pmC@C>EHi%V(g!W=S;%I=U788r~&}ymqzes-ub6!jK_cysHoNTv zY6&u4C|tf0({_Z1is*ras7LS-v1SCVqNwR8rHurFgigr9fMzGKppsEZv`Q<|QrKcx zYs@L>`$^|V7^K#q!!LM4C9J_O)GJj4Lbz7WDonxwT!Fg!fFS$=;QB39{6Zc0z~1I9 zM;Is_VojL^+P^|YqWuG&5^UiV=gP4h!p58y$g3pKM=*FpSpWkeOiLR4gdnT}6a+;a zOp7CA1WJm8avc{iUnyDDhMEIq=q!8Y>f4h4+xXQ zSZa*TY({Lyrp97DIS;6E#}bUeDQ<<&enx@@ZTX5NgQjKppzZpyuY$m;;^tG!<7*aYlVEJgOY7E_enF;K2k z92e$hZl`RnoC(1kAZ*`!78(2k8IXY_%z{lALp21$G!z3H2tqK#K^)A2>heSy%tGNF zfFrCz9HfEY9>AwK)Z(~lN7!kzK?VQDRqU*YU;XW_#%_Y35&{4+0;gp|TgEt_Rz5Lc~_STFwi>$!=1`$&oQjMv~huo8m+g!TxX`9%uLslpRPy+i1ZrTmpQc12Q;6 zDF6W!%!2Cz!4)_(5UheD%)HpPn z9Wz2FUPCtA!ra`#GSGtY(t;|K0w4&WAP_SD$tW+Z=ZeZ~8&Ikv=fS2@!#=#>XXNZ8 zcgGS`a#d#XCTp_M{)I7Pbyk~1g)Z$~R-;$DvMQ-nE0qNPhQv4Oku8G+U*<9wP6@$H zh^ut6{6a9GgFQ4h zG8{l|l*TXo!n&5L-lB6=94=QF82IXwn9Y+8OXPtK1y&VTWv~IA7#~M^WIxNq124@R zR0Bu*gE}AsBTRxLJaqps%mE>^G~ximGgJdQ1cOpvBsQbjM{h(($Iw$Kg8V%q{b@w+ z(lH@q!g*>#Vy*!rz{T$dZ!g@m0A}JKGeZCIUn?E}qh9LE?k9Jg0ySVlB)lOtWJ4`F z^;T9@S6Z?RO*K`QFZ=EVTK4sUBX~xXaxi!Gx5Z%0$S96p#4F?KS`#LV)bd9-uV3nm zv6hc2B^ub$HIU9V1Tkx@E?HhD+}S4hC4q_EkQ+D&wo63tWMBrEQRxfclSpi9sT_b; zcmrf3w>|JfDR^_39d6*x>m-=753B+!lpI%ZhV)fmC0GqZg)|TQ#F-q9PXHR7gDfb6&8##bY(h4emob0?KhOdu3ZPC8vK*whdS5~(7(ygOLPF%h z0kneLsjM`#0)57}dBDQ-N%DSkM}gu=8(8u>enx-`IM9x=UKD|WxA?FpI9JcLfq&j+$M&y?+Gl44^#DYb5iSM%5HY+uit=Y0Tv7b-*AU2Wv8KFV1xYCOo8a(|J3}>8!(#_SFg!MU-&2#UspkKdOBBPipJ7X|5$!WSer$^m+VdMA)NsfWTs zq#}H~;!&RhCR}e)C$)f`haPaRtz+MR19-0wcwg&4u%r9hBl!D*JAuGeJbsw^P)RI% zgcB%4wO`}4FN9F-U>6Pqg?m`tD=WCiwYW13UY7(CJ_OryP^G{)V9PxrRtA{SyH%*O z<=3XXhlFDDdsvXLEvy4Nkp46{13LUeFi6bZ9zY6L&IpsREl2qcaRx(Jd?9M*mrKRO zznTBV=UkXCl+AUd4zC=?cRX#YguRe?k@*7NPRsMpf+JWl5LAgbI75&-L-q%QGnB07N8# z10(4M0sW673v%8ApztZUh}RqKxvR2~RFead$iZ{E6r4)D;+LrYb`RmBo(dw8W*PG$cY zH+KB^Oi2m{26rUq&rBLHhp@>8^i|=|8otD4G`J0Wsf}Q17XMm zx^IijjT`BxVAZ_knziOYCD-1N@#FW**{f2&Ciz(NE0Ck(2Lk;P6sS(1Dw_x&$@S-nb;I zX66tA8E+2I1d3mvh$9X{7+J*@LOl6p4p8=~#u<6MLB|_!e(8k`MrKI^CpP4p&pp?C z{L#Jvfe51$g)TYr$b^tw@{&<*$;P#8ZaILEDywWo8CjHRqZCeXvBnrCk=*}85i*hV zgrI>!NkpJLe##>hi!cf$k~lePNRK=9?C7KON>b^cV=7t3pO$Dk6j9L>U396TieePf zNF|+=(n>A8^q@^PSqrVlJpB}`rX)jbt+(Q$YOcBJ%8S)}n8E9lxiF=4EJ8`WwNp@a z-Sw+cH>r%XV1?~$)?$r~G{R&_Glo>wR{94v0)fCyH{N=ymN#pAQ%aR-o~dS?N)D=| z5_GEhrxJg>spc7PDhX+gNhTT32YD%(WR*$Q@RMIZ(^KxI`gjEJJ!uUj7?^|=21b*H z9cEZZ9cMd0+Wp{j%@<&NX~vghd}&KeX0!5SjyZghv6n(}35E>;b)5gi5!oDBC5~Q# zL1!&sa0v#A1M&qC#DwIdk6<7L&M$~j5E4_&D&HXFk|&|e1{_z8%*0A8W#Ob1LU8$d z6GoV3a+FKZBnXm7P+@bRg-*E%&Ql=TlkU1B@(84U(NigLb|FP_Ob{$ z(4SlMd)NVC*G}3 zdNWB@1VyN108Vg$gF)}O*r+ak5sYCJ;}|owDaE`lcCb?lCv25JwZ!FV2jI$Q=JJ9U zfG!_((S_&8cofE<4l%5IS{e!27}|{wDY;Xmu=?1@V*xK&B5O;uG_j%daZe%4v(2`g zk}l^QqYcSZkF&^?kau|xmFAg&!7eyHA7$`-9dzF;X*vHf9mPjLKtKo(4pu+c0H}QY z$XLl7#19V=XqOY)5F3snn^yiuNDVWlv=niG5FY6Y28h5mO?X16Ey)$xNXFON;6g2N z0&8+8#5FG=iZrba6^Kw1+X`}kP*7tY?b*jZV1Ws0P(w};p;Hs>mM16TO^Pb<$1%px z20|Gsi&}K#L@8QPi(V9?QGpy*;If!Ps?jKs!QZJA(z-Z$rjBs`w`&u*TVo8)owDV}uBDML~{>zOi@ zSq0xJXW25=+^1m!BN#JlSypA{1b(>e(J$@eBOd?x!xJQH22tAw6@wkktVBZ64wu9P zZf=vCB_x0rj`Sq84C6{)LuZxNAfgbuvu!{`n?Qhg06b9R9s2;#JKn($YQTaTn5fee zpNPv=PNLQh-7*U#R(We$oLTqVUTibR~Q(4&x8f&U6pp1&7IEiC$tJ2ci^0q9h zS;ioH+uT3C2z;fU8MjOHNs<9ft*91ZP7ncQS2FD18<^Qdz{wG-g>c6hOjOiyD;1u?Z13w!~sWaU>4#LxQ-NO)xeD9wI@F0|7Ib?&0h^K1v24)#kNS;Q>oqJ>-a_Q|_&GU0qOwyi1v$qn5JTxj5 z9Ti67gqQrFO%P^7a{1~P!9eLH#5D1&OfO_;#Q+8Rl8Kax#V48h88xZ*;|Xv;Nrh5! zMJJp2BR9ca-0rk|Vm2g1OcZ_>fv*9Vg!HI4wwG7Lu^T3l1;~ z$2;B*2eHEhBQN<0N+Kazm_`3!5~4k4Jqs>Oc$&WRzHhcTCEx00(1`ogvT5$3r$OdQO7Xl+K5Q0=(BlJ9Q z-$n(e050_wNds#ucn<%r!4!@?00be*2PFiBTySsVLL(&7gJ>!N3rC{&$i+Q2jyz^y z_Xa~pDk(m8glO=iVZN`^;Lsu5W)A@aitIW93G&8YS}wJI zAbM6p0w+)gmavbCpa|qn7H<(3cPGkriwM0!GUO;!n8NQyuv8q!4lqxGV6X=jVg{RF z2M<8;4uTA3;UFYI3x1&$>WB7-QF3~b%6tX&l5mmAAr~_$yO`w(V{a#p;ePh#0RF3g z`sb6##S71nDt`ZugEkKMrfMJiMwQ}A9YI53yzV{mJ?rw65&{P;> zDMX4GIj487G4fil5CkC^;$j&O;uj78EF@tSyn+yjAsE(SA3l#8rOX>^3LL{x9CL>p zrE;Q5!}aJ4A=fdMj^QNy1CjazK~Ul#`X-d1f?vY0JoeEFfe(95spDwFGg?Nh{v(;* z@T?lmtaAUvAt90v;eh*`$s#jSH9_GI)ez+{)B9-SAm0ZO6UHQ|DTGXb{Vq(f2%rwq zZ){NP03yNHGEuS+!LmA$#@gebH0$fAu)rcg0LjkB;2?_p#Q_QqHPBH=4#4<; zLOK3}FtP9?cry5aFd;z69+jedr0U^FLJavay)uqykPqdig8T>)Ko-n{6oTgvGUiA# zBme(!LsC;UpOiJZFX3+DBSA7G6OQ~K4f@Jz4#dQ;{DB8bs3lv{)d(N}uBnHHlTHW% zo`TH~7NXcjamJACNB&7VJFyd;$e^qf34-i;w38JH<;cAAB|_9G#nVs|RZ)+ED#h%h z)RR}%2$1?GCnCe$MxhhfsNLEK(A)#`*5VD4;%PV`8HT|dZe|`9$RF&X8j!&r7_>pP zz$*%&6;c5i(1P%=(LQ&T^fL6!PLD%76n73_FBi3UCUQVb6e-%E#y+VrOX>FBkqX&L zA!L*!Xf%}|^Y`}g;fzle>BBQq&MBnn0NbNtJTvDc&E()a9(=Zp#oQk{z@{EjPk z0zWymLfc|zv8+7_<&f;b9=>HC-r@kz;TQJdE${Oexa@Ucl?kZUS9`IIju0<}m62q2 zcLt>6l7d-N0+eh5TBUVbUrA8DFbjVI(W)vRBa^-rmkdO}x=+76u3TSJKi<%9 z-)BBVk~a9mA0Cok`_ME2Y+e(WUR%>OvvgmL^n)6P4!873OO0Ub4@sEd)jt0>>Bc5a zFEL_OY#?ClCiK7{5CRrJ@qS!G>^@d@J@!uEfC2qQp#asPQkGCYs07(5jA*= zS5X@kc5e1+iOVMyP*MMOP`wj);a7}k z@iLrPipP@!tI|`HSA8ROA<&`|Ds&m{GgQ%1Eao#m31uIc_C;jG8`fbs*5OpWVINKv z9hlY*m;muy5b?Z18C@`o*Eh|g!hMHjioGm7*l}8=@Bpk8d2RxL%|ly_^k9l-Bw@*z z>J|!}qGkNcJ<940=@73%ax@P>gB90D8h4bR6b@z%NG3O3Jq;20fpB?lXf|wYi~&lP zL39to>Q1*!W6Tc{!eR|#brHf7@k{LLgcM)_4>(bXn;B$__&P@dwUT&u|A7;FHx>tZ zqM(>~wb`3xkt%z&EU>tbYbsQq7cmM9b`a1Sr6Q2K_M4du_+F_Z?PEnTDdHO0k%`71)bMW;Vm5h6tQaPj zd_sPkuhKTTmOS}CA}!`X!6r0#am`0bPdNzS01n`_;Q+CfEoL(}n$#{=5$=y^m<}ez z#1nLx*C2t#*n}bg@J-=#m=j_EnKO2m*I-!Xrt*xu~ zUUV_Z_F4Ii&nQ}N%&*FCg*peq^gBXT`B5i~%23$2aWTHfcqrHrjAYN2^C0z8rFh=V8I~j z$+(@G*#04^tD4xT+PSUT3kW0#R%r&N`KzycuC4zWo8|kWx?9Pc{K*=%i?c$#*_+C% z+{&4NeE}K1H=|gc95fagG?+D*jzOB$%X<2|d&1U&Hgdr}SFe;(|r_UFjnfXaEje+Fet5!~esS`*7x@m8e>VAa%Ny4yMFqd%T&wU?KB^27-VMB+?&zp$)8?6%7N)$J)y= zYIvi#*Mq&bIPl)C+}MxZyt7=(w>&etT-d8(zZJy*tq?uXVev;@WaB@v%H<(#Hh@rb;{ID2=NkN1F2aKGx zlKj~->esvZn}Y8PmMnMDC0%`{uUYNm&ldt-2YudYfTl50rOTBcuy5Zr{BUJD z2qZETgKuKW>T+XQHXiIqj@%fA8X@W=O<+MB7^qY0qf;r~#&lKjG+!$G_cIO~kq_bv zQ}it+lWkK8zLKJsp1yD^iTgfy{6ajz9VUL9N$x>eUi&=P7V$n0wCbm!Bzn;)3 z)wDTS(f3fM5xp1=;vpgO!h5n=tzOjTW4mhU#Bafu+NN|{jPKdv0O>=<4+198QcIMOvo5Wu%JPMFp{`9z_6jihY%x5oJg^v#fum-YTU@NqsNaR zH5N%ivSi4UC{wCj$+D%(moQ_>oQZPNCV%|=apFXXiO-)vg9;r=w5ZXeNRujE%CxD| zr%<21Aw!pz(V8HOWJMd(3evK z^LL;aoQ6SS%Z39A6vJY&a|e+K$}K1wz=P8$h7-5$*tJU+TRwU@C^*n(6DR$z`afWu zv$I(Zj7|2=iY{HsRvlKP^QaP?hXkvf)zPKlQln-*6hl0CB8Ad}pFjTp`sv}ve*_k2 zV1Z&R@tr2C`Qr&3KnNkB5T01|k3X3>1cN{abtnT22P|aPh$NP1;)xIyG168jw&>!E zFvck3j4IiLlTJKErQ`pOJof10k3jzT#xghhlS~~nfu-bJXuIg(94Auek+BZqPjn-CoxHvmBt&4GPC}RaQrrCUmaGPj_=}7KSIQUANwO z=fMKbd#u$}nOpPK7m0uj>2W}Qut0(zEdIvAscqFJ@gU!q#1Q0<) zNFl5kN(6(41c3*J8H9+{O`O!n(9 zN#(37@W2NcMq>Y7Rq}HsVQCE}7<_s$#2Q>*0;9@h?dm)ses zi)~k2q{+P%=%C1f0&{Ma{kCXuaPY;?bF~r2>7RhQHZ!3=Crn&rC~v0nsNR{Z*b;XX zvsW?du?mYgtogIg#0OAwfUUUZ`cQtSDEl8QZtbIXPH=hJ7d6Zp=xk>y`xEVi)XvdN zPVWulMn&5mMDXB*t4nUVg(t4~;*87KE{^cpEBWMO?lWZbaZyoG>$>P_L zt`qTUHi58!dE;AOV%tA%6}SJ)O=%3WiYKHsAt7waD#kE|Rfdrf7z8eK7|h^^4#y%5 zdhmlF4B8zh*m8G7=QGT~qcK}pI|nleTtQvJSZjkb}M z_Ik#gxKsy>WPDB@76pe`$&4XrOy}{AL!0fjkxyVsX35gWKQK|F7?B`FBobi=Jg5PX z|M3q)B0&wd`Gb(V3Q*h<<`x1LP?9NYklh&AKunJ64V$#e-*U;(j$UL%i1VmOM@rI- z)WJqp*@-Jx%F+`~r7E&)Q7vm(QjZ2^A8@HeFHaW}!7$7)Z8*jc@xnf8CXpeS*$n?o zHX|y!XbdysgC^bHQmMKe6E5yNW6Q9YJ)U*57&jy5^cr%`L#Z>3RTLEW9{8uxn9pQh z@Xy)61dOUhqMv^}kVE>nNVf4~K9G#WRrT`7hbl;E4e|v=E4nv-bVmr6m|#sOJ5rF2 zlCqf1Y)4Oela#8mrJxP%y@ zW6~#AUh&mykwC<*;?@v?`js>XEpLJN3YS?qlv!TjOx=93Kubyplm5`;v?BlO4+^gK zz@@b8Wf9Ea24|47?@_5}Crn|Ztk6hx*jJ2D3quFb&?>FHX-;KZTVG z_=x7Mi=oMIeaD&PDz{BdrORCCqGMUX3?yCzg`&tA3OLXp518;rDBkj#h+y|P=R6}@ zt0({_ESa0UUJo3c@eR)hPNP3}KlT7Sl8Jo#B>|h5# zXi$bc%;yj)*d%=pw4enBVb50h(4xI?GBTmz8FBc9gZ5x2-m{NNbm9k<*vG8KgyPxu zveQ2#reS6vM&~lrVjGjmj7hejXGT#}LMs|+vP!e)VlOyCj$V(IJwr?)gt#m z;WJw6W>ZFWOCQ9bhg+c;5B@1AKVadIG~2Hs1uZj|{tAoz1ytJ3^<&(`fLN?Q7eXCdf0((n$QC;=VsdfOXDg~k!0_l-hDoAybMhV;D|#{(WrT5Fa50j3XtQ@0#I z)S!+ysIjCL#4v;nUGh`HXxErF#W*IAX-LUz98FOjz@1HQ8(gTY8;`)@){DwDuk`{Z zFq&015J~5AxLX&YWtXk+)Y+K{NkF-N?aYM?XdnmbKZd$5%m-p~o0$bs;hB5RboR%( z*}a1|@NJ_54?Dr;O>eQA{p>Kww}ko4_ISZEUo8Yzz&(d{!WI9V2V>v_h!d`GhWi@g z5)VAw=dc*{2poZ`jp$=IVL)Kgx`rLP+aQQufAWBKBXMO8jf5Usg zUiapUi|izEzVxTxkwPzH?QPG#Q(g*pbj`hU)K}Nt3*HI&wN~Lj@OwkFB>46Vv*~bZ zNaP)^c&6#HA)#@6omBFei$k;WZvr(tI-UKg>Dl9 zV91wz?-71H2qn-LeLWb2LTG*1r+r2!6x>%@ap!&C=PyDiE@Lo$S4o@+X0aMzrybe`0L1*MUxV3cElGjwo1>7!j1n5ZNXlD!78nQY zS`yhJR>6zC*ajnC{{@P6mXHa#gDcsYWASGT=9!|&U?-Ico1i%rxk&FJk~`4}gfJBVi9mM0 z9tjm3NeG-Ek|X&Z7h)uuW15Y2k|@a}Dmj`X@*Xbvl2ka8m==LI>3)YN5s7FS0%%-6 zIT2tejmk)r#WhK9k&PvTdGL`<1voUF5Dd1E27>SlX^w(4Z%Jp$?b~T!# z2bN)_X%m{WHLB?kteKG;89CVplC^n}R^eBfgPOcq2TKS#zsV#zIwHwHl2O=;2Df*} zIgAg7lO{G1&*_CeiBx0AL~>!BjK?OOAu5yiY6N%yZUmlj$vuwn4BImalOP*$unLm^ z2(f{lR|E&W5DcDD4bI>x=zt8*@CbOp^SJ6 z^!SMF)orU9vuGv;e$Wi&CabdwK`&~n3TYJ#d96U35xm-~L0hz|#iN^Gnx~nXBq^j9 z*_uTf6-X+Q??I9m60L$Tts_;fN)nt#s}cjzSyqvyT6%C@GLv4qoUGFkIp$((dR%2{ zre}&oaM6<&_ZeLH8QiHD^Qtlbn8%b6F{kPT3WN}r{hF14s;6+U48MR3$Pf&{;0^QO z4andP=->_2@C)m(57l4`OOOhaAh8o0R(a5H$MYxlT0F!dGvZ?%J_n)dB(etpm?dkn zCkrNo6qt}en5U2ke$Yp=8?&n#31xGFG-!}ENUI3Rv$o2aU;Dfjp^B>rz0|v-S(~&z zsyW5Fn#WqCQ^BmaX(76~n^~J-2gbFZQ@vn25NiM{WLvgX+oj{Gwo{TF7SXnGK}0kb zTo19Xx0Anni$Hb)8lvGTdUC*f5_E$Fd#UHK2g*H+@C(843%{@mK>!FA90U}s3hGb| z-q5%c><#NM!Hyfk!w?Mr2e1kiJi5~*K2}6l+S5%~H64|L8y|~ZvP-+RYrE%Fp|i^# zE9;2DyQ+ym4Ors~=fPQ?OPiXbQ61y^q*2Oe=nIim z3=##=zVGqA@T)Zshkj|xI?Wj;PJ_QpQ;ig%857~Z7sp#g8AS||Y&+IAZuwl-#Ex}= zu~}&gf-(ueAP2z^8-PH;=?MyFsWra!d0JgkMY^%6B##Jo6(`(Gi ze6+neaA6!4%ghn~2BEF*(XHcWw#3NB%9)eP$;9Cgzkm+^;0?}T6@|J4VYv#aK*6Cq z%EA!}293$S02l1Qs6dJi&fvJ-ur;vr!QSvF6#NTYnZbkNsh~Q$v23CAbt@Jc3BCfD zyKBph2vE3;2f9oOr$7xz> zs8Em;^3z!-%tOty&I{G*i_A%F+{(S&DdE&H#M~0mA!1wAR(*E|cYX>-s}9%Idn{G> zcM)+55jjSUYKWBcT6xLl&RxVZwE??7Hm5At&lEfg#MZg{@Ym>Y-xS>0|G5vHt-`Co zo`<~(EG#{0v=`oR**Jx;Zb7-upt=5#xeAUBf*rZe;GfkH1W25%4sG;p4Y{R@oH zfJkQG)FU;dp*B{r4i^q4>VOOyov8mH+0S6P>Ts6N;OClb3xO&J@d*X7VU=?r2BnY+ zpUMa*d_N~np|>a7Wpm;{Y^vU7Acz17I?b|!5C&F0A)cV)mV|Xd?c+mT%uG(bMBeQG z&@SXkzT`;GEmzu-QEuJXqT|KhSWC)V*a^3#qLX6{=KO2U@L0EHUNTL^jdJQnE|afM zMu>7w9J&QN7g8PnnYoZV!I68(9{mr&pa_diJ#e51zW^Q6^9yGXsYn(ILbjImK6(WW zxxKJ8_l=g-0HE^#xq}V4&M*&uy$+h33wce!VfhOYYYVBM1_zJ|senI&@Cz+@&`cK`*$-atNGke=WRz>pKh&f^Cl+{(_p#U1U? zOXNka^#7H2@RdWg%AuU90|J;45hF>B2M!X5vtUXn}pQE zEg%>#^hGb@q>u=R;0Io?1vqenbMW+0kAj~_7gm4uPVBQ^55-*H{ooJ9VUMFn zt^=hZxk73a=%DPKF$>pF1ELy;fDZmK;Xb21qFfvRZ!tV zh7BD)3<9dyKZ?$rp+i^g7dn3(J0e4Oz+bfk=)56wv_#G?Ibl}Hp%LW&%odhspwPgX zQ|C?^a47mKxROmUZ{9LG^R^DzFK_>zA#=9wS2dF;-vpt_rkKBA&zw=yb6`~|KLQ8+ zDmzf^Ks{|E{qx6J#v6aA zIUto()G!Mz)xv_MF395YhoXPL>MPK`5{ZNq!AKz`kzEE$^bW=F>+i7$BlN_wxh^?C zK210MjJ}S*12t4pM3rLcI8#?;wN+PNg*8@LXDuyNTW`INR$X^hO+4|)I}bhe z#$bX6PCN6oBmVSb7E<;20VY5JU%PO%3apN2YWsi&rzS6r{Yx@xV#^YzzY%i}~|e~cO0vt;dS zwpsrC<3|$!UyD{XY%4@?tq8lN8$*7=6>%#Q4I&6#!65>rXUN(Gu^>1QS{$-{mwY^5 zBk!g0nJ&BBf*~HEzzR$rCn;zZh!y$e88w|@6B%Ux{C&)xY=U6~kFyj}El6(>F)##LK%OG_ zY8XEgqy6fmzx_e#G9CHPY7#j>0!fR20zsgH6bJ-1XaYmU07bbB0znCO(t!%0UqKJ91T?HuuD84)qcu_6xtg+;)XkR)0=7hjjg^pPI8vhoYJ9VI)!siH0IHr zer(<)uz5B@7P2z^i_8B^KS(Tt3-JhKfs4hJ!;vMhTgT z@?(`eQDsJ3iLwX1l0=Iu$P(}n30U0!Y+DL_(7NuTmc1MidQ8-l%G&Zomn{kr$y}x~ zn>n{z_iWH4qCzMu2JoDBUP@Ee1AFH56SaL(c^Vhwd#1>WWY?8lu6nZZMS>W#vTnMy|My z2o!k`L!d}%Qpg-or77!6FegO~Cgz1tu%PKNNdbw%C{qtP^}-d?3WT1ri<;6?4N*Bo zMxj>KwXYQwQ`HAs+Sb;#QJX4NZ(FsiVpTnwndczCsy2@ZL=yu#AQI0ikkO8ofd@s% zTjkKa%OLYY^>S&$mFa~bG#87&Xjh+#n_AUsN}CwLL2G=9asOSEuuwr~3KogyqkzDq%j&;amAO3_wj-fyx9q-t{lr$(D zN)ufOb+o$HmB>RkILk@tl|&QK6DYt-10?|#C#@_m9CR|514PtZB0T^x+nbkxEVjOO zfvgdcxWvlN6cLa>)G0_tkXzycm{5N7aW0c8=zrbR7-8!R8Ae%R25R?QkOjA%wT z+R>)za5^7Ns}PHLeuMV^sy*GnLKaS9G5t{yQ694*8&xANn^*;relZCFU11fo;87f$ zYe|1#QZ+=j+jJvXu20exuaU{_LLx-nhHRIV;FX*znY2;!>IA(aA`zGmpa=E_N+5cf zc4Te$k4T)NWK6_wW`W0FNSufocgFKF#lU9^VaOlNm;Z zU&y*(0;AuV3E zyDg}-j2W1x=o4lCN%7`5j~h{(HOv(23yXBCTeN)s*1O})ta%5u-q*Z0Xddj32p8P# zwC%UQ-#&M`cXQx#tUIX=?#`@|_}*u8o_?s{1}fmk;cm#!EJ}eCf3Rb9&6Afsk^&4M zKw%bwfWj}*ARx;-g5}^6GHgJxIDu^U=pk|l=^<&j)ARN8!j=noM+i+0hHxhvo$^jb z2yKUmfu(JM1%CJPd#CFqPvQ_qU<7jt|JoVdc#w-fxZZW+?G)_phWGyFz>l^4EH!Bd z4fgUr{-?%0JLE@y`nh*^ysO_kdw1uE#|HjPH+&MaD7+9Ru?l-IejULuiE2m+8u5sA zu!UgAv02#vJONn+R$Gwg3O(A0F22IK5g`a)%a8|Iy}YWx)YG+d;VXXO6Mo1&oS>I1 z>!48hz=c?XJZKBH$O|#Mw&K$Z-+?nZQ@&!LtYpf%bc?>-p+4*Tv9QZNdzyo>!>6;$ z6!0^fZF0XS94GUuBPgW8DwGxWOCKwY4)}AYgp(fd>#F==7KbB}{Of{M=!Adpzh9^l ze+h}FcF(eDU<@XbR?YDQ;1BGiw>GS zaH)%-v&Y9!2$8}Aw#Y=i5VMuBK}4x3<|{=~5XA#Xi)pjOk}^dBvmJj(Hz71IB6P*! zf<@x`8Ec|N&RDyn62_4nA6;BDl0?arlnr3S8kH;#V$37?qaP+b8x#|~UvLCRm<3z# zhG{^CXGjX7Xr7;(5gOr#W(WpbppZDoNhnwaN7zH$*efM!EKGW(f#562I3NwtkYGdq z7kQk=p0h_NqljX#G8#CMgz(4Gh%A0+q8c0?IIAf}sWU`4fZbup((o*Z{H$dPCIPd^ z=EBG`WFcr|7Dte{{Ad_hLp&ikLmoj2dAS5zc(qv|10(oIL4q)swGNxAFH&1m8)zw79R+5U|hUOJ({?om$0v(kx98jSbXvA7k_fWTd}7 zk&0^2gab{?PVfk4=ml4pgZ=9S8Kna%Xiy<2gkP`)V6aVls1a+F&e<>*4ML)m0yc!e zB(2;KcwEx!q(`$1EYLeI$yh{v@rUGtgnyhtYik+ifeYnBlu#HRyBvt)xy#@S3%xv^ zzU)g&e8`fjQ#{B|4YBI)A4RkR&!{N#bIuWvhgEW|gNpJ)diXk&mh&X80Hvopv*}wgR zn1x_gjw8W)VYcneiF=GaeTjs?2vfdTQ@OOdcX&=}D2&wL(@&&N>N6hu#M9#0(~DbgLRrm42%s|x`xP%;STX&exR`~-jxYvKPy_<0Bw7nraxAQeAgk%3 z&O$VtfypGj0)$m_1Rge2ysZ%7^zRpgNDRJd-be4#f!gmssH#>fIR>eVkdX)u*`-`?1_1064v{iU5V~Rr1vtn9@1?8n-3fK6wPJvUT@Z*!SIxxi6~Eoj=%G2T@W1UXrpSIC8I@J>Ie zp^oTbw*iJ;aE4*9-jdl}V@)DIkvhQe9Y4^6JL_Mym|u=^OM$T8H`QNsgJb{gy3e8p zb}<|RULXVZ1O!fC1(w-H{e>>rzb;_V9#z~fsFc`rgkwmNeRv0Bz{v{EkB94@0|4QL z>xdCn;ZHt}6GmZBCS^Nf;T8tn7Z#7y^#@c9KlQNx$xmw*9Hw1%vtp?|2&j1bEhOl4UNW})Rnrka%Y>{Nc?5nDo-er4CKS$_ziTE1y^ z+hx}l$4HVSKKAL`K9D%LL(vhCrDecX00M+axs?-;G*G#z-LXypz$^pnG0h7|AQ=Mm zCDRboyF?>sdR0@MO>yaMtMm?9m?Z13w?p{#+6+Z9qb8qN$Ic%Hh|(WwX-R zo+d4Ua_!nCp#3xMS)gVinFT0lRwy_w<0fta`GqSeP!`D;qJW`J^2b0Cj9ow^>5Eg- z0AuXVow>jZdah&c&M7g-gJxJWefF6m94`D2WPxx4H=u(qPzz6xi-|^=btnpsppktr ziJ}m^Cui6~`r}+OhW;L-(SVI2Kyc75@Qq#bH-{AkU+|SaT?c<~`FI2TQKAi}aMPZH*!@4;X;+&2DoykM?Q@6*-@C7am#pyK@I)EktUYKDX&zrX&ns z5JyrFbRUo%E_6dzbet5BpIByUtOj{NhiCo=j6sJ>xMo`@OA7fvbU=l{S%Spkolp>r zv;bgtp09y0XS#TGSYIN0p7kp7)4KkTotEpMGWJ~uWF}7yDz6~9==fv*v|CzDk4E#< zaQ3f(0cf{&ktXSqj`^BLCv2zr60UP)?{?3~^FGPGunKo^A1!HN1ITD?ad#UEA#rMU z;y%+5W$vMlKnKfN9gnF01|AtsykUcYzfO^Ix^WA|93RE{iVI)bwuo;RaexINtaytj zAab`5TmK35IDnGR>)8-_=)rrF?>?Rnq>t{6uL+iyxA~Bs`QbSH#a9lT&v^zf)zmd} zR1HILk466oAfj(B454&>?sGy{5WS(wpgNfi(uxNuhFbpVj-XN&EcG#ig!Z&sOgw;H zke6Oodx}WDz)-&SG{{5=1^4AF_;u^!3Cz5Si?zZ?SbS(`@`t`>7TVwszBl>dN2%h5S zqaXQ#0tkNmfN28%V(=gkO#=M|Y3T4_kR^EZP^@V2q8>!2c9BYi=p!UjB2R53MeQHT zl>Y>>WJ!%$BuJqkC4v-5)VY8AgYgVhLmMd9$66^LYT(DfH`n$B_F5bL)_wIN@*I%XsMPv{z zZ20hD7-ttVZtVCmbL!l>ck}LD&k{ar1{^gH)$vRZfKP9by?CPs6}GHzAF6n%0wF$JasVTM6d_U*DJAvflSnotk_biA z_@mNVEJYGZfEcNPh#q)&jAdPS zKwM&NmKKX`<@jS<+tn3abkt3?31UeqNtj~8Ir$`%QA#-_mA8%78*f!=xh0ofdif=o zoMAa8nOGJvPMB$`DOqxDwn>*=M9Mj5Uq)8-l`ks_l;d{Y0g;t@fgY5UegeJ7#&_El|Pci%jAx4D*b~u!QK_%#EfRRvRs7eAwq6akRJr1#h?gbihl{al~r0@1!QMDw&Wv_&1(18C2`V;7bpKr#mSP{Cf4Md z-Fo{ixZ%o1TA8YedoH@^s=Kaj<+}TB670%5rJMB@7uW&PPP=bj(^Z$<9EP?8fBS2k0pB`A2n6e_7el&UAt0ig8vUq&8x-Hwb<|M{(bddW%^VxoXUg*9i?dZf3#YzB zzVHGMotWrPGTMsGB)9XLeKy)@(?%}5@v8kc+;Ph-W!rW4HaFhH+1n<*2k`rMoz;2& zlARDz4@@v!0v-HlqGmM})x#`Gj4|bbI`v|GYZ;BPQv!ivs~CuY>eDHsdITUxyChQ$;iLV=Xll@_c)SKL@@0&?puPjCw`^qcmOD!4;Y(EBS(>)y;n;q%m1L$2AYt zdmZc=V~<^S-ralu{km+o4L8JMF`Ry;ZcXDpP3HY@Bb|qGxEK=?4b|5co zu~`TeIgWXUag{sZcf9e8YE0unDdC4FCgBK##91W;oGtPfQ5Q$PbE5P*S#LN0<)jcNn~8T0rcKc=BbPZ%u~ z!AONAd(jMgJVTM4e8xP)aSEH*;uodBoeC=giH#h<4;3;MHDF=8SIrDPHoW0Qa=62w z_0VI5Dr7>;qoSp4Wi@lSQC5~{wXHx)FVu@7G>KuYeIUt-V&fhfv#HH(Vx^1k;wCu5 zDNe|gk&NT)o*Ip_9Df)CD{yp<90?Z|!`X*fRXZjTBSsbha;!cF6Qra6fVm#51gZ|f zK!-i{;f-H-V=d@#hBK-$6?7c*MBb=IF?taUM%bzpzZk|TFw}=tq@onA1W+pVkV>pT zLMMnIiyp2*5m-QiBLBh43s1F@f86qhy4JB8|!Ds5GBZq3G`12Qx6o-@yLImgP|y42Qm~`4G($)87tbyJNO}rQNUpd zesD!FP;me?4B{7=NJSwKky47R)}}1oNh0uImPni;6p+D)sbshRlAgNCXFvs-P{C7F z;1w1jMj6O31&7Q79J4aZB@0yfC!|hPwYpNQmWeizJ*{qat=|1^y2M&H@RGN@@wFHXlvWY1PBtXf`xAR!P|@A zfd;<~s;_)lsg4!*I|VV?af#;-Pc$P%&wb1soW_{w0tp9|prSvhYhA1Ug%bzhZgUfclyYFL66axp|D zl*Uxzk97p2(C9!BI*_prdsM?2D1m4-yx|Q+t^_6rPy{l15fnzG!Vd>PE$*(ulh~%X zwvlmFt7f{>+0EFuHx^osCzqcU9ks{vNyvPJ388-!Q!>qM43po2gC7w42T!Jpl&2g; zuTjy;Sk6{g%`EL{f5yvSrZ%>-{TVWkSKDgZn|qA`->kf|u5r2RA0;(sI#0#Ulk)F> zQH1CBGzw#jNlKpoIy+4H${!*Nf+K!`j&(%V9*mx>Kb&FNeH{1~*@(nd6k$q^z+$8S zDQT=?ic^(Zq=h6wg&MM=;#0p0cClMEPjmNbh=5}MMR-0e!&p*lTj$z4kh5b-h*_-0 zIQ1;ScFVAfE%akgr4yV`HWaUVqD^4s*-GN7x1%m~$$0adQ@=Xa%ffAVsWK?lGwsM(@qOCE5_F*x-`M*ImeG-Jy%U|t%2#oElA!MO z>0iC-R;NDp&AfH4XaDPM3ir6L(&m3P3$K~~law!j5&UD~GgXQs3xEmBxw-%K?zVCW zC~~ZKhrpo}lX%E4I6^NhQlte#L@}B(WCM(qmZveoFWAB?)B-6e9x@a{DHK8@l^!F6 z943w4=>3Nx1cNJ(0xTdyr}@DzFoGfY0SltoS=^AR1V||C*X!+4?4`)d&7MKfho#&e z!|0ym2oLcv&CX%PuRTrh3Bm9c9}_+q@*N%0jRAJ;Loztu^Fd!?be|SdoAtTN7Jeak zZQu2Q;c&zcoRAyY#T5}Y3%UtJ`uRfd4GxVYAy}}VTol;@wVm7LAk2M7Qsmyl*x%m4 z8j9>+t$;!r`~n~}1R(rE9KZoen8+gk*~33rgDK$wEGXOo3_>s{LMbo;jO_x3sevDS z*hY2YRUm^cltn2Z!$u?mBLqVvl-A`r1};&=KgbY8xEd(5M6TH2O85gGN(K-Vihudw z&7GZ54T^aXPp@4?&$-22soxSUAroGs@dZniDc@D`!#-Hy6=GpwL>n2F<63oLxtOCm zhLae2;W`4x8d;0DxlJI+@`C<+7Uyeb=W)u}a++H#&qd?4DFb$zo%~2iVRX)ar zHDV)GIw7)g<5V;sS%{-ykmEakWjLW@I)Wuxx=%ZnN!OL7YZyn^t=af>g%Uy4jL;z+ z(btdkPsIFVR{SB|A@avhZb3vigs;RB<5dI;vfx#~m>&!RBB+8b*g`H0 zf~Rp}AK<|%C;}q*K_jgKP;u@T)iDqAN|5jB|wSCWldRwp=F+qGGzcEZhB zlF4?$#=T6%Jkn1*`CRk=%q3kCr(N<75y{>G@TI;9;>z(|Atoe$*eB2|K_o!j##KaF zz*r*mLLwmp}MOAt}PgLHee*HsV669av=X~~}=jhPq z1kDnN0Zhr1f8OK)m;?!8*a3uO3++Q>?N(NJ)ClE*86biggdohs3}~i;hg!tU9KfoH zsL+rpqW%|dZpNVh>}8+~Sa=AL?qP*}%;$RN??u?5L;?U5_FivjwS;a%GW1 zDXYRwk}7Gd#;TV%shP-XXNYHW{LOq7;g#kHdeWgCp684-0~~hh=ZNWiHiTdzE6XwK z66C>RT*PbIlw?XMH7MR7Sd!+Io}--zEVNKB{6fWpfEcfZ^$^r0Vpu$YD)gq=WoG54R&r!b=GXh0;lp@6NEI7hLoL_xp3Q#&P!YmF;Y^`Ms3drmx z*!r13Da7Uw6%QgM%^X7|i~(ebuZ~(}l))`D0cmtH#=_dK7=y|CKIs^rv02csZlom| zzmc5e?^kF>jeP8S(oq1f2thn5pXrAZ8`nVc11Ma@Lo{#@V~W)R&FgVW=(^SgS4dg^ zgorq(F522CN-WYp#1e*?0mq@%NosN|4gy6itwl^8Bltl|rh*yJiX*H-PwpOz*vf5E z>cO;x5no235EAuLYH`U2?wzfDR6->jgEtZpFh2$sE2kDWCzWB9W7usQKl7B7u^B_N z{i<{%5nV=&#AS3bZXG5W$##s<03=g*Z6CL&FD@`IA!N|>qOREIAo|DW z-gBs31u6VRKSkohtr#Ye%mxpF@uI6OT!hW^0x}@NMxiS!H^eF<=8L+rP%`lj`qO8~ zD4!)vAKDr(<6ac^lMjqEFsBH^2}Ch7#xW;nGW+PVea-ncv#Medj*SSe^SYT1HErUELgM51{EKP2e2s=_Kb0wApN87M1@ z+>uHEgAUFIMsvn+Su_A`v=4rCrB<$_RKiG4b{hnF2n#;ay$hcoGGn?`J-v0nUij!Xu+J(q4n z*SQhd0r*1G2(WOs9Rl&Orb5b9=NKSUbt^05CC`!tgKmJ7g@ar-=D;XT z7ItIYo?|n`3?w)(PqBjcd1VW;H=c-QN4SI+ABA6KRhcjPD(p=Ehq$AI#)re|qig4g zn?`EW6?GhdQyz~u=T8x~_*2<&kqHYP;~Oq>PH{JJ_woZAMD^}ib)1BPK|%;$ z_gE*wRU`sQ*u(P9jD#ct_^H=%~YI}lo;#cnVdyEFJhFf`OvG}f1|9k63g z9#6*hBDv51d7qE;pQCiTr#piWGm1cXs1`c$je&t9`b%f!CM z4JlzvI>2{Eq)U3hzhkABMrzv+cMwio%CY(F9H=t}a9c}CTnbbiV~^o@aX}6Z?hqUx zrL5l~kvGV#yTmRWh_1KPMj(RCq)37~)Gw?9I!KzNsp2sIj1V%wLW)>B&DVUS{lm2X zinVv?u5J5eG)44!dl7>>S?DIWlY4*{l6;_hyDPYXBY4%jdnK6k@eO)b&^z&wZ@w=b zqc5xr6g=8%#=wtZ+JoW2mpB^#i+N^7aSBASM7&uHYp|$9o;@+mP433yxF$S|%6|OW zg?#IPNGQa_;sXeE*N4fCNJoSMNjUcbJpSy!E;{T3!9}}*IZT35Vqp*@4cs6>K3 zNGGksKClBs?OM^4N5miv?bp8TD@E-|ikcfeWX$=~Lw!dJ6fkFfpASFrxBI(0xV(e? z&{a4WcMVK~qrd-q+gHEZqnGt>;la0dRm?qRc!K%=**){WE0ZnXb=G3_}CmT&8WsVd|@?X)R z{BH8x$%Y>=g_@K`l?j9@PpVh3X4R@SXQfI9e1sJ{)<>IT{Mw`?yO!-(ulzXfTj*8h z54(5q=GD9RZY8-CJ8|MMmhk6MZP~dhKCWXs624m=4+zMzb< zufG5zjE7Dv+(fc1xlGQ>FTo5`%rVI0?r#a@p&L0?K><+~qdt?v)81ER(3Oz;5vvDE!f+*2IeyE8gC;mXq@4rn6 zOq4!_#Gz)FQy{?uR0Csj@c?Q<`Ddh;Kmk$25qW(N4*71JX{!TNRq z@y%CX(9o=txP1W*Sm1#v^Vi_v?j%^@dj-|ZI#PXUSf)aKsSr_ZM?De6si>8dJdHb^ z^igUpg~`B9bqY09SZpQLWlmuUC6QB3*@YBR_=_YIYTjvCsGW)tQP*CH=JnSKq2+ih zoM_7IS!9D!7Di2gaSE85aEglmyrwKW7RQdi%gn26={tbiBf(8OtR)x9@R$R}Kv(V` z)K#z(E3r%vUU?&1*zdmq4_xrf`aO8I!4XefaXAfd9Ja+FH%?;AoSW}Y>JA{(P#FLF zXH=nz&1xsGfp8SkkjWbvZ1%)?=VVV)RvA>5UnG^9nDd+Y6j)ACl@wS6I>1)fOGUIO z;Sa#H=;eJarou;asubkPo^DFTs%M;$jqSJ3$Jf5 z_10S?hg4fEug0Z_NOR|w(yIjhaks&A;v^^8#NPNenaC}Wfemz^af(nl$GPT#6|~^s zCYZqsZZI^HvrOe&2B^&cHKSq|i`r43CoCUXg;A3NS)`z{5Y@3S2&9nEb{2xNoyZP9 zI!i>%5}}a)d~Q>n3dMdRVMB4)Lmd9FhyGe55QFS&B%YI1i}+EDT!Dyr%~MDUcf_Nc z42vh+W8n&;@;w~sWP8~Y-`2p_6F3TGjHD9_SbR_!_`R$RU^ze~l*A-{9K(J>ssxkV zR*AUvk1zkTTe}Ll4=u@ygO#-8B{6w`2xc%gne^l*!^FwPB@C3M^dMzG_%c8d>QLJm zqRYxBI?9MqhNo+xQ;79Kum#}`cz{LmiXx6v@FY}`fCMa%d64_yhjuPAq8^MHiQe%{ zh(_^;I8sH8gMbSEAy~{J96|w#P!t0wN6})gb`^wQeNlyAn;};&15e7R@iIQ4WA|jD zzN6^UJZr&Y9(l6Im(3+7LV6pKMncF!k_CSU(w|otnJ&M)i!hu(j6V*N#)B(h#eVfA|@|eqbw@}9v7mnBJU)f7Y=|2JVXL% zMWIH`NC64h$wWWKOy&{s!&LpSELqyR9Wn*tIstKnQ`kHzR7pXzT_i$fkoZf`XpmO5 zrWKqeBIl-@7cBN&g`e__3K{1qqk4kwjg})-U9*BDnYd3U;u@%dz9N&c9RoTi9PC2Z z!nOlh2oMx zY-iIjPo%b*ICs5$i1F>6LMNE|?Bp_rn|mZ=|GA@3-*n(jZOco4FN z^%OYEPgrf{-Ibwrt>s;-IN2J`PyiE!Zlu|n8TrwpeQ>WVoR>pU!WDS z1z&3*;b}*<@}w<4(0AL;0KvCDtrRY8Of6mtmB)B!87y?>L*VT~RRsxEbek$O;Car9 zLXqPCDMA5>P=S}M`k5IiR;7mgXjwl?Fz=VoTZ~Y!^{qkMBCw8Q_h$!Qj0~yFZ3gk0dB?1x0 zwArd!m9tRTkQ$?^P-C+TRUYbLX5n?!ez1(?D(}b3V79heL1D6>6)i-$f{9YDHlwUS zC2Y5yubZcZ75n~&&Pve)4)6RkaVL1sO7inSO~uDT_tzqAJ4t01*+0J&Fo0LuP$oYA zop6Pl^wJt!_`~zXX*xlifu8V$pMc37cCXMUG0tZ#(+%g$*r?6ArPR2q7ApZ82tnj} z<$pRQR6pRs4}O3IQg>l9tQNa-^C|Z2qAb;ATUo5r-cKT;EnfUo``Xt&+NHWkG&r2u zuQ#GmQpz3Y9*u52IEv#^h?4J@b*0dcP1_$2Ih2dVyWaa&@K=cRQ2xy=vmD{XB@T{o zitnB87i_r0`yTi)NqkO%Pn_o9@*fo;i%7UFHTAeI@_Le|o#w`h$Y4zsTmm}YM4DC1 zdpy(!0q-34c;caIGLYx$0hz=cx|SiaDp(}q*`UICm6_gjFh70Uxr%z!r>-gg8NoP= zsN{p{Gf_u3Ep=YmqdEs{mh0RT>S0Q%z+cvq0#4WEAX z1Mcq=T>txbLwGfL8vgpC*mSRE%NaRkjUJEZ#x`S8!UxX8BXu$ljXLjVA|VobEE2G) z-z;K7QYGhhLCTtnxzu2X_=C&zfCKU4=3rs0Y7bPxig!*S_jJ#^crTsa!}op<_;N)k zjKaRqZI-wKhLrEkECp-EhiaOy>PX_ixR2jsia;Fy$+hdhu!Vz0Y~Zf2IqA5w7l;%eK7W{Y0% z1%vMht*!>;3;EUve70f-!(#?=A}tyUZI-YtC_`Kf>#!0_Dpt{u5NRL4&$99Y2c&R1 zEUpTT;o!_L7=;l`yzsP!@fek242J_5%LE5%!a8Kidbr0E&BzTUuQEvP8cU7xO78L! zP#_r40rxNxf@ctoX#`nMCbo(iu&icwArbMz0~aw=)PQCjap=UrDJTLCXrS8sQLUJ+ z+K$E_ERlIiM0ql?i-5&cRD{%y5BcaYC;*ETwZaso!brxZ?N-tMTE61m1`IQ1@qXaW z78Sz5c5ym*kqWEu{Ft#NUD7s+QKVk-7?tr~X3|T>;5y(!8mXe==4&*JZ}PrK8<}sn zEN^LmK);G;0eQ@a%5he722{wgWuRk0itX1dumkr)1CI{rY99kUl#5({r~GAYwDVp1k6v;JxlILa_HZ{r*k;uwx$d#=JKgR%`jBPglI0IR}T z3^01W!#mVNHeUwxhKn4@QHY*tWo*T-YQi6m%4TXNEA>GCCK4ehj&qr&O?SqMhwxwt zMg$H3oo!;^iNk#ZPZ!R4#@*t8bXau3^Y6ttsGcd9e+EWR; zuOg<;pDe>K%_i+81T8!xBz>R~VrWB}!4sszF_%LnBQpyy6YUDLTt|v=}#>VYrK(7H=#wd2Pn5dyQ5h_`>Y9Ee@cPda+ zq=M*d1`@(DRGt$q72+TA03fXs6lCHbwlg8)GK;+PJH^vyMgU?!oxcJ^Vh~xbM(fUV z+=61`MsY$A(=+?ntVprgLTtb^KP#bS;oPjMr%G&D8n^1e)@HOpvgI21Nbw2rnS2&lnwI)wp4PiG_qE?QJ& zsEYHBVja5+*rJN5GO#8%@a9&9_IwmNi-w4*v%Hqz0D6WW5b`_WgH+DREtf|+Uj|dA zPCj%Z-0JdB%~RcEWGnQOphV+6*Yuwl>u1Q6EHnc@3A3`ARWpWg29TiZ07O9sv_N@r zLypZK@KjLE6&d-oPtWzl05vu`b6rD2NVvsK0T4Aq!$Vzjx5`tFjB<2j(++_^xJIH< z@uLBEhIovqCS+$S?+iKw0=)c#Rqlf;4{=pa0TEV}|9NBrSO{{hmf%+a#7GaoR(pk4 z?TkKhbyx2UA%8ViW@`CSMWvP7h82iViDb@!$Xw;n%PX5|Yz6^`jA$PCtIMi)6xN{{a;G@#zk?GMqF4 zQ+7l;&jsP5Wr;{wWtIRLWk%>|`CjqBlwvG410w~kcIp$LbT*)j1Y5b!Xgfx8|1bT|Gw{{jTEsiZ7JX!mQPei{h|50u zkRM#<=OAR+WC9Yh0ZN?-LX^VS+7WK|!yW^-U`KX&Y63o}vx>5E|qpmos8kDq2K6l)|1sE_}==Ql1xjeaX65)Q8|vKX?Kbfbb~5 z5l45zRn*{^4q#Po^aIHk9q(3ScLF{%g@S2SG!!z24=ZTo_prE#+wixx$n8r1$Z|?o zv4oD(;gH;@3@jWxHYbJ zk9nf|&f*x_U@to~Y%8N|*>GzfC2J}IQhDTsYofqQcaX`3c{nE^AyaJ!cQ#om zJ}?r56WEwjRr6zTTU9F5sd$QkG`a{5TqNEsaf)5$C3Mw_<(E9crm(m;j4MGXN>?zW zB2DoSK!os&H$#CFi%I-pnCWd;AGljrl7h(q|vnSuH^3A#BmXmKG3SuAG2 zkaOgCwI;@94H%ARCvprtcC3eq>qt3qc6mqWlmdrsM`w_1RC6>xVlUb()*u9zRnb=} z)`>u(6qXIr^K>Ez&4~qVnW2RO|CdQtovs)tt|n57`Ir3*{DissijaE~uq3@Dkd;|z z!8BP%0-DPrZP57>-xyBkn1Yj`j>CDUQ)`uBU&9Ri=@rw7)<)48G8Eua-~_CXURC3 z@5hYW0;!XFns>65C|IY5`m-4>gEbhm|E7=sc&NWvc+FWeN|=S;h*-p~inJrDNz;Yz z0H7OiQd?%RVTGZWN+$Su|0s4ic5FDHLj`=1iWJzIXei^YPp4Q8pcr_?GuX1~b|RNs zd9PohuYXTG^QpCkmay+f9sfvecs4EG^N>VyvQLGfr7uZ7SDF0`ij&!xM?$r=6)0N&CM^OSDHD!1v{wPkX0RTc#f}Y^#U8=!0`oM5@1Io@FAp4~0_%LM|9@Wp3ihHHGfyJj-L?(14L})xjf&epqZ>~AK_iEKw%*hh7 z4ZFFUL^Q>GP`EQXm$Jj+kjM_PEd#y3RJ{dhKwx^M5m>Q!dngpU>If~rQR6&a7e+jr zz{%W`1e~?X++Kt_|IJUR%Gm<5FPAdZjuYoRMt*CTdP%5;s}C<69A`zt0}P>@49L8? zIDg4uf16@U{8MBHV$Hw{P~nN9bh;H9&2GY}p~IbLTh0gSB|QDpLH(VDLdV}Dd5mUM z_?lPjcgUBgM3m4=xtO7T^RS)#Gu%hL19O1?33S_lzGX1Wy#)zw<4VUvJDQfwksXxI z9LM#Kl zY|*gK^fC;K|1f2p!Q5P0M?);$bD?^+y0rR>&w1F-6Fn&67lE=ql|RD^xJz^buYc)lGuE$6PGl2bWlsYd*(Nj&KlmWR^X5THOSPVIBN z&17V|C}PUu2*o-ujwn*(N@Gpdw#RBP{m!EMoY2WFSH0m!BnR9+2O$185A0fr`adh8 zBb*@^W?>c9;6H!U8-Ae<#3B$@VHSd668b(Y9HH=6VG^!DCRX7Weqk0Qe-i4Rp~mK0 z%p&0HoZt-;x(&7Df?q!M{jMfe-%I+q*|XK$a;kJf9_PD5d6g!TZ@a?z z+*bTt|0kMB;B}(h%LAMV8^S-@DF|FaSR0$s3b z=tkxGwZ?~!1N^-G`sJ;X4?({IU0Jhg))gO<5MErx>dFC-7q47#g5-e8l`9pxeCe{1 zOo=dkwE4G^pU$29{{8FeGpNv?Jo)+a2aKiCrA(Wu1Ohdx)TvabYSQV?*qa?(yIwj9 zHj~q_WXqa8i#Dy=wQSqEeG50P+_`k?+P#Z6uim|6ixf!$II!TsgbN!6%r~*(#f%#} z|2BI#vgFBwA6veRIrG?>oIAsuA+;=2O)7mB1!_9!0U%4OQVnuPB_2GHs2%u8jasCp zu!!;1-%fW>SGN{67p0Y?xbj!5E&Ih=@MiYQ`IV1|{nv6d~l9L0}7udswnHOP45PbHH~ zvQixgjWmf%foMeJS)Os$#!O7gbPP{JO*y52q}j#bf>#-(Raahm^;KAIXhvq4|7My4VQ3j`EZO%z&osY$dXPiaY$!DLJEeU8%Gt3~`ed_UpUr|CKI@W@)9WYyM z)aaDkZca@)A8?TexjG4FZe$sGIf$De;-^<{xf zwHp@Wp@=G?h{U=%U{cAUIvrDqT31vOr9j?vQtywQ?0D2V^{RB_8V9hl$^i-;DbgxH zk`?HZGqurK8&Oh;aZpy$)vasywb$jBB6D>~m`7zImY*uG%yP>vzYOzT|8M3=Gh#8{ zjB}bb?_AiPIsXi_!VwSc1EEeixE?TUWT=x+syXFoY_#Q;p>AYFVj4p%1;^=dkw6m4 zQpF9D${={CRLU#|3|Go3wyff6B*EB1N^ZuWQzJq9994}o{-BdfDay_<$tuhqjyQjw z_#>1rz!+7owf^`QABOdHjCtk~cKdC(DsDN@wHI6;upi{MKIR!w_xxncmBvtF+3HCQ0&4P z&#;Fmga8F*t-^4LOWfiZN4>~d%M;9s&q^+Ly&z`kDnRsB5j_?m2SpEeM{?kUnsCOcXE9tp`vN^+8GQJ?%KL&;3u?24D72S!qz;v+#xss$k6;+Aj98J! zGlnz?jpX0}5oIGwgtQTbI3<)dsRT~`7rCoY=`>4YOCh(El{c(pkt}T__&y2Kn96jf zD*Fp3DMQnon(3xB^O;V6sw9q9>_u$=jiC@#(o)h#Gzo%@q-<%m2$}^`l-d*oSF%eA zo<&mjct#qZVU66_0vVBrgmysa5N8ac52x}29`1k&|F8bS8Qx@;B(zx9!6~a5z-R^z z|M9(X=CGVPvEflva=B4H$eoM@f;@+K#Hu*Oo>)0bKHG4jcI|VDs&h#|TjB$f{2~|C ztVS@Naie+?lUUQJL@)xul8Q`JDY6adLY5~~A9!>r<$REXP~)4OloTx|#fny#!qP>$ zG-W_-u5+IYUAEYir;&-Sb?rjkJo)sx&&{n%+R!A5efN(@jmiP~H(aPS6@kR8$|F*H$Td{(O=$f<0q_Q}~1ZGbJ#VDqZ zCo&P*Bo?ZW8D4=BKgxwyol%W{*n*Am`b9P7F{G8$mbMGUqGxRz%6ef)DTKY!0k$Nd z^a?PDhB}H$$C6w{E|~zD#t01aIaN4WnW%iEfkaDFh6t?2|V~=(}VcMAfEX;XQXjQX!J%lX48jXFaj&h zNLC?!K?rQ}hYG)_Yk&NDlw{xhh$&qj?r$d)pr?&Fb7l6&CDM{+?yWh`3~#u@a~9`2SLWe#miT10OL0$zlFv-a zlz7_!W&Jz;-oAw3i?6=n1AFrHHagQxU&_hBvDDb5Rq7 zSk>?cD%b$4b$H_$qhMASYVC$@GRqCMzO{UGon~GKw%Fh7`VFP+F$&@5ykalA+0Tx4 zvp?H4iBfig5=9hEJg?j`uEaeV=MN|5K(nXYG447M3^=ah7ZQaD?JB`c=r{uzYD9cm zbrd|6bR>9bgzddKdJ~>Fg|Pha|MHiWeH97~yxE6LDO(agvP&4_dzlzh#$ONn*q_Og z7Ppz~pIiILVEp!wBpP^+aSVz52GBNHqR3l=#6*?w(J0TQN-N!$JkENCRCxL%W-Wp0UbOd9|y1x%9K0C#4F|D4VoYXlQ(#? zKnMJRh?li4NMwfC9M==`;@m=?&N9badbdZqNlQ zAp~9E2C2{s1sO8WC^9a^b(P30b8v~7sEM0sEhM=bF9t}~vVoCPMss&tWnmNeG9R#* zccsI3sMC_XXk{^3Pw`@M{y;AbB_I6Ii38-vK@o!DpF<6-xTiKOpX`R=}U1B+w*qJkCNf^7woj^m5 zr>KRcNS;c`j%1jZ)UlVt!4$hRbENnWuy7p7aRA4mUxt}!h&daOQiqE96E&GFt0_G` zaV&^anU=|anW>q|MTsDZI0Uj(qDh*JqKszY8btw8tVvGQ@=>NJf~Y8)uvvlMb6GmJ zfnXsKV=nr0pep@$=(p;;EA*;~zdp@p`9ulZ3NiZPs6PvV7TJ_%Y2F`QtbZ8zpFe#eW& z`J1XklvT7Ap)>lAvvhwXk*HsiFu~wG?fqn1f|!RHPogI3a1IDdJj6M zUuUOx+GYBKG@+rXFUE;dQW_mc_0Sx zB{uNrtEaGXkW-*JRF8;Rrv3<^){+~#fe7rBZ1TZ>p1GhK8Lj{4k*qPbYE!D?&w&>aIKnw2(@Re3YEX=alwZqf8|g zJ2;BZW+*<96=?E|LF%w+tG0D=u-mz|jj^!v^R{h5u~q0%K4G*qVX@=61aOcCS<0(s zI2NIB9In|k;))e?SgdABwEW0@Y&aWYumo1YYHOM}`^P13I<(h_xwk7WI0sd@6>%wWCvt zAG?T1X>zvFXsUDTyw8gn+G%mn%NKD=y=mfm7xNE!`x1K#XiLxrdXNWsZ~)^QxF}Z^ zkPr!=30xW@Ai4p$iwls)I*0LVhms2gc9|cRtDu>?xzQ@85NfU3f)-%*Wie)>qaiK| z!dvC!nmAaruNx?4(Y;E`imnK?s$;d2>QC^xI)}+Ink+5=}0>x5%zmu!K{_wJucth%;x&I5NoGHLyfnsV=ybNp=)Fu^lrxI zfCPNMNWm~+o3Pl5PpcxF#bdb}IaY+V93xo?9G!5-VIgK_Ya)q7D6l&W$&u_9H7s$G zycRiZ$(B*Es%wB13${=3B%^yfzTj8(-QKgc}O)FjDV}K=MnndhkGt>jgnD z6=kL$Ao;~XD8~OAz?Jx{rKuJ|G)ho01D;VvT61myO z#W<8p0ko$9lYt__ctI7=$vI7|$bprWYI3%vn#u1B&rLzel^oAZ|6#rLycllD$^0?ZG#41fCo0!Ov2zY?ShAcSD+{o^X&r6-j^L%GaeE|0i)q0_~`%I2Y;?Ms)&;dQlqddN6SR1}EAM=@C zc!xurSXLzKeG#n(nQ;pix z+qQ1|&X}Cqc+tI|%$A(pg&I23*yPQUO4%5oJ=TdV+D2U`N&U#LE#T0*+N=%93p?OL z-Ne=1?u`>IvJ&dixWG3t;I-K4y%bGSFOYq-l0Dh8{|kxmlEEr1$luIkedgIhjX7Y( z-~Bz>b^_pGk>FiEw*_v)2mY#FP8SUR$#o0iqD;yGjoYKl+ZJBFuuyY>+QjaA0NhuH zsVw3n{+}gozi+MLTfEC%hq*7_7BQ}wTF2KK4Z0-FAc3-5OTo)H zuWk%}V%p5h>j~egxSs3JyXy+S7Cy}+XPzQzKH*$l>=sUG)KGJ0?V;3zX;OUW0csTg z5KAjT8xl>?(j>(#|Bu*?(O}Wyg>GSgZtvs)Fa()Hc$LJq?0{q7Po z?@biyZQyqu9L+q@Pt%s_hrALp>m^Dd@UNb{22Zo64e?)polgDK&Wqq+AMvwV)ojVA z!M^4Kjqw;?;VJ}&`}oX?qA?-=N_en9Tzc}gjN(}=hRjOWm&@&Yar5oG=pkL><(?q9 zSG$x7RS%1Ag)R#nagFW5{^KECEv4a%DFA2sfJ}#PjFRbD9zMcgZP6)Tvdk zW{pu}K~J7Q&lci|AXZJ6bz7#|o2o+Jy%$P#`QCy1 zFde&USknPbdk13$_C4ip^t;28zSR1n$V-<55BSh*!3M+iDH{!C|s;eBnLdz_&Li~^|x8R~C8@kHMgPMI1!s{-? z;-UtYP*emgp-8AP&ak`w|M@2}AR(J9JvM+LNH*F$6OAxq>VxW{H==wazDuU0GCnEa zz;Da^HbOE<&ukkAxAYQvt|94|8*fLwnoI5&iL!y?f{6l+v5k5F1SdZm?ap6ZJq(f8w0i#at+|9LH8$>eOb%O?9DbPu3ZOLkQY*&l9a^R}=9*Z`v8 zH1FNFp_>mw7~nY{BCZmF5o%++!ad>}I))pbfelTJgxD~O%M0n^-56yOT#?@ExYAKU z-stR_Q&)X;)>~I~<(N@*9n{z(oOyQK0mM0HT|xYC*S1RJC+MWh$}u6sSVX$`JaQzg zU*waA#jgXV|5lXIt2;|_YtUbslH7F3&cqG!$=Bh0^wU>={j&>_cHOv93%Tyu#PsK` zN*?E1&S(97NV&nuiD_^`P9??zsK(JrfBI6`3>H#3ra{a{<2e*WIHw-041{#|p-4(R zMkW ze#95U7-GOS#4#cPdr08cG{He)Wsd=j2sfWI10+;NB7!>1vkFDAc`?M0mWkpp6}d>0 zG_rJ$3>l|Fc~FEVRG~64l_xj3P?tCqDYt_tM9t9^IGD0$8y(9Idzd0u8jopmp-U)0 zT0A4>@n}nY2rn;&Jz&zte*Qek8^E^_WG0iDJLM@C!T8LLyiJ;3LQ*xYX-#a>v5nkx z|A;vKW-pHb&>?{n4?5GS&Ni{LkKBakZahNIs_Mn6ggn4LF_STx#-t*Q+@PpTR}h0% zRIYQS>s%Wu(WKPXBzOf1MfD0wb9m?gOhib}PU+F%oiwC%0o3wl>B^MuXhvs=h)b`R zG5Xb}QQaHK6^}U#E%sEjqvc{4*`_WtvTJ@vWi3+sbby2Tv7LWI6I7$xxHhPiP*&xw zc(NLj1BG7^2r=WkOZgs8e!n^V{Ro9J(c74L#Q074o z%vwlV+QJvbF7|i_fJIqMDm0YZQl(0iWzrmCSzivM8A+NcXF(z^oQ9UP112#0|1uG_ zXg(5bSgAy7kD64(Y;%7Jqb)-!ERn+Hwm7`y@Kwh{KnmwcxEBOTad*pMgwX3^h-_<9 z0NOEFacR2XrE!gIOtS2H_q#VffR11Im;;A4)jz+)!!7QrY+bP07!oH#8%G}B-QU-PxGRoFdiVz z6=1sUaG&w{Jgq>afg|2$NGMm;-l`Zqh%^R(oC{-+KsP`#K3$M4eQ8V^D91i-5REyl z6Ch`LcI8NjScrVycf^v(%$sG6q6}I24lh`%9#-{)w1l!=mLS>-4HcOi{}P)TGmB*= zcCihN;MTl=2g~lnZT10Y2SYe663&yIFMI&se55-7v?HJWJl4Y;L(n27v{~h8=sbe1UnZHXo-nOJVmdc{F(uf!d zTGldyR&KbB95b0*=U0lLxm#Kz;@LL1PR)sX<9ay?4)S-or^ct1pR2$?t4q4^+u!&Tn~ z=X%$@E)jqeyx?^u_}6EbaD~r>vJ6ieEcnshDLIOeeLmw z1pAmGCwbuw-@bxSO64tQyvv;(^EgZU05;D#&TTte*%oXtO#619!=1R=+Gz$3T*%Qa zv$@OAlf!{Dh=pGKDAXtfy7g8Ug$NpEv*%v-x(|EV=^F4*@7`oON_!+q{kx>Cm%S>2 zxU1_MQnt(;@621m7<^D}^uUzYLg=`=>21tpfY$KiC%^g-Ul2|-Uj2?A(>~x7`8iYD zIoMX9I} zaV|(%h?@$VfoL?>YnK`0Kr=i;?%K2r45c+h!&oT?x+p9V{2{v_LA{_66&#lLg0B@E znihnPa??J)V-N332paSU@ykI)T*M;agni&aA8ff!AO?AnIcsVIV$h4i(5n8^IVJP~ z{4=g5{4*$w9P0SLk}#{%Go&Ixr>g@MOp!e>OqW6wkgS_PH_Sy{lq)q1I5zafU6d8G zV7vHQh!}y9cYr%qi?}{a8ZkhE9I%r`$(R`QwFmsZ|G`^CZOp+UkO6O$0Y~J)^ovCH zD~vabwmxC7lDIR=`$SM2jHemJXVEiL1VmIsi9$0gO+Y8pn44?7H+DJ1SuBWJ91!WM zv|vm~g}kI*1V&2Qz=a$YQVT&>f`$8up16RKy--FyWX5J38ZqFCJRy#48AN;gIAOcN z!V8IQB(`q+MwsM;O?X6tAch_!M<8@FOZ)*$Gz?C}JPUKjsmQH`=)A)anC1{MB#?;! z>>PCRCx5h*xM{$FM7b@DK!l7)t=!5IYRFHUB!}cmPbmjlQ@*FsNaIk(SNlk36iGX& z6>hnke@uv!EVh?uNz!^rnA}TnoJmNG#4%tq|CrlJX^T0N=%#l3M51&NbP~n>p~uOi zyqlwmrffwY0lbi@I$OjPn*yq;OqaPlkb~4Zu`Er~OdYS}G#3iX)1(lxT$aKb8jEBI zpgRnN7$QDoOBD&pXnf0?fi@hFONgMsVH-1}z{_RQOTJuAaHL6sxJe(($#Z0_!Zb{h z5Xw3+r+P9BC|r)I2pB+w3Vq~9iO9^*d^govh|feYw`z@o+Pc<^Px%}b3~WQ!fynuM z5EW5~1kLDL4GH83 z_{>ir4N?cGPu5%={1j6CoXy)DL8IBfqp`aJZOh)Y6N4#?V_48jB!)*MhB06QhagTd zBP|0#P7A$IGi}a|u*nW32qCn@!YoCQAkn@FMdJ{+0%Dj-h`FI$QFw|9Rs;rgDoBRN z%t<>VDCyB0)xuDTz%oQqM}1TQA<`m!nMs9I0b$aF@DYV*%;I1#>5I}~InX?*QUztu zWgrYLWw{qv2ndzXPT58nI8#~uMovfu(g;F-=!9|n!Gd70nG4aM^hBZjrU2y!&;y|0 zKvqz!pr+WTeViaM45(KuR716h|M)Pbs*KhhO$|i-QA_<+aJ31s+b)`^)Nr+riv-Zd z^VgHX!GIN5S>1$!eNOe0PB#VC>y%R@ z48?{`R>Yx-(Zg8qVAh$?*a=Fls3QqN#X5Frh#Lh%LAAY-g)5kCTem%l)MQzhQO&n? z3MExnquj`w1xdH`&4IYm{|Cd>pKZCIEr?{O17=#C@jF_imDQyk2wi17U9ChAJ&ve# zM>wjmIbx^ifK19U53TLm3wqYeM2OU2E00y%F8tDK-H5cUkhR6dx}9CxeTcZFTUasI z+I@+P#9N`Gqr2e9;vq&R`@@`_SAPIpq^ik-WxSxJ$z)iAZ-jv^BB8=#+{QIirFG8d zY~FHoGlg|6%bgX>#S?{S0~F2N=$HXPsi5%qj>_R$mbf4orK!_>uCcw!`;`cHImuXw z-A(b<-5ubRyTjh5TAukxZb;~mL)#R{Iyj=^2F=Ou{fUCts%pA;fF z?9E;?l}YY}TuF4c{|}Y3@jXJO+Bqbgj`e*Y_syr!o!<)r)UTDg{T18%ZO^cU2uUd! z0QOM@KH|DH-~$eo1V-YR2s)a5h&Y6Z#d^jmmDe`8#Acw$4Ca9`NCpm;UNeP(N*cKl zCSeRcVKrqrAZ%0CItHjEU;TM1JdelIA;UXk zG-gf{X470{<6aHl!VK0VY?#o)vpV@Ij145*&;&h36wayN*PV#ilh)LQ#n z=+;V(=5UQ<|4KfPYL@1c&_CeK3ni1Kk;uEg9n}w8&^EYNd>!R4#?@2K-c&XrqitoR zeO%}iOmkG&o@`-hvQ<`ZB8DUHHotDWGZEwQY~lF7~BmWh;>HecFrAug=eJQ1a#R| zr(IZlcASN=H3>Y{~7M-J0^)i$y=gsh+)=YA1UUDQ0hp7Ca6|jr+#c@mK&4hYReW&tj=ox*y_uc zh^vw;Z(a%BtjFgt>nu*|b7r}f_6N7F>$pxG3Z?71j>!`qN9k19T9#wP)VaiTL6jKm zOaAAKtD1xUCyaP5$6l2n7UHKqnP;x-&W>({RASAB3Ql`j>2`>Ip|6+7fm`+st6-cT z7y~#~Yt;thwie^r{>Is%(Dae*^+r<-T{e1lv-hh`TejmE#=P)6HjRMnLq2&ZyFr$8w8uA!K6LJw>5f(k4L z@nv|XnGNo3O@9QBhZ z^;HbOc`A3SV)YJl^(R?(`1oOl=JSN$nAr;(JC{mswReAy`ApOIDChTmmwA=|_++P* z3bvI45L$%b(3NiO_-^PH1DD?DlUDjuy4TrW8OthT;Z3fI3&~J16<2 z#@2L)Y-4_A1{_GP|BnY}Tby6}nIBiBU=<%TdbalnE3Uk!@`0WgH)22t|1LcMwpMs- ze{D-b`iPf!4dn!9TL$HbV;7cskEnV$PqCl_c@7JE^gQk&Z+HFO61TzDusM52V`R0T zd(yu#ny>kg==ahm2~pj7{NoNGJOC~o`h^E`!3QP6SNf$d2%B`a#pmn(V^P$De55PD ze>nG$2mO)v`aWN11?T)kwfq_tbhvVZ)xUo50(R|6{hP=Bh-m%#GaxI4;}+pkLeSFm zR(iQFV{0#b!w(xFJcdjJ{=3h%q$7SJ>D_PB22$;J^b04TE?>foDRU;x|C%;$;>@XYC(oWf ze*z5}v`CR8Mvo#*s&pySrcRGqd@6M+QlVC_V$G^`rkET#eE1j%)<>m({`eg`w$C6j zPQ>=@^Oua%8X0!);?1jfZ{8wX|Mt`&crf9@h7Ti7d>97b#*QD~UBf9Z$cAwFVb092 z(!{Zz!O8?8dNk?Mrcaj!_HQ-o*8fBvxFj3!OO!iYG7L!@rtOVyj2)~jydmt}F;V7r zxY9WD=FXo(k1l;W_3A>2Qq8V?>cs8dk@~eRemwb?UB8CCIJWHBv~Ul!RogIGUA_h( zKMr4ByyE`;{};v>egh7;$z;P}rj}-#DfHP`Gth*ZgcF*k|C(#78S{ohv+ZXPO1Obk zoOQizB%(pXRR&y#5g`W>ODn<{ql`1sSfhw(Hm!5iHv6tCe z@Ezb0eT^wZAYMQYX&iu8VriIwQgXQ$C!0`K*@BsIW{`tmL1+_&Yfh-ig(e;(8=T^O z*iv%D&G{UO8mSl&iXin#BXW28^J0~UBATe8i!wT1jy^&vl|hka*QlkJB2*+v>zSpQ zKWsT!-(D0ENF}CMWtl3LTXxy%U0;Uz(U@eOY2;08;#!)UtOYs|LwQzLr%8lzDBYeJ z{YKHBAZd7GiG&(@sFo9QlRP`E|gzG8L zYT6r%OGby8?w!kYd8rBc1QS7*pl@cZTi<|Q=a0KJ9hH-G`Ie*VB;{x&kK z5Dk!Uu>qh*Vpt{Rx#)vJ93l~`#Xtvgt%z8gptwlF9)n!aT;S6nUN~4jC6*+F@lqcN zyJSKXo{(%T>mj*!D5AN%M>98C|2 z+xlb1m`K5qJkfiz!(jMMH1HpCA#FEmjacOtmq z+0bCRaa<`YA{!qfN_o(dBrR)c%iSDNkdT7lEia{x?Oi01QFIzz)b+?K_L3r$R23I5 znIFPv(jluk;WY6!#+(4HH35@IE9*zY8fxT*t7K*2zB!|eEN+j`@gyj9avC$z&m!HlNp8%kr#4FD zjTWWTL?d#_L;+Eq{~RevOKOln|HhL$CcRi2Itj(@eM&B9tD+T=xl)7#6idw{s9hj= zP`kNig*XwVHcisendAmwmw@HrFzQhp#_=|;+-UL$GRvD{HLJ8lX-ci9)kKwJByG4x zX3o_lgHZ7qovZ@6+Et_QlCo7AD`uRA!L-_Ct%lL;LEs7?zg)5iE=UzZFC^5M zJam3kJqTc5BG?oawyB3L+(+&gOR2hXwkvWhZ3>r86flG_f4u)58NDjyX_Fc9|fsZqg$xv;y1rm zgQqU_JES%oLw5Xdm~>~V)_0E9zu5JUe&|Kl?n?8!*Q`ivdBxQ70yidaV4Qm|>>Q_V z=wQFiut(oJxPgd7r2btoi@n9)>SeaY)&cOz?2A?dQ@6S{UGakDbr3E+_-)a2EqF)5 zSK0a`z8BdrNWhrh`7#H@2%)1#a{I#rka$BPQt~-b+!5u-ILuEW9!7A8#QaAjTzPWB>}f2_=MLO6uzi71YZ zUXHGD&ur;S1JZ$*{}xZ0WoO^H7!%Icwe*}5!?qvug}bKJb8Ctmkt17JD7$Shp@m~& zo#@XZ>3j$t8NCqMJUYa8?BApxTj@Q zf(%zychc1dsgTgHvL~d~+Sc%uvV5UBVis`(*nwV1m1|UAV?R6J`ku~mcjWAS2PJm1 zi*B`b?7@9&TT2MJi?a4j%}jq9qT*cg+Z-d?tB29L-Vc+)kJ9^n(?0yZ{BhGlauRR zo{hWF-HJ`4|83+{kU<0L=;OIJ_#zAQuY;W@E>~&TvywuZhdL%V$2q`(?m-xw`mI1; ziO^R=bkU60I7v@s$(!6;ts86BzLNUXdt-I`RtE4}=ZI&IUG~RAo+M*u%D*FD6BHI) z)Nuy8&Mo5hOlE>L`5dp}fwFg$^nEzDrVYDeL--sX%YKM2bkueL8!%fw_qvzfDVc24V6;?;7dvruoS7EDn1Id+KxC>GoC_Q?(z*VnG)93E=KA+wTqFNQ^_; z!Nj#~|DO8gluRVw>qVLT4TOdSPz()>v#?uYby@69#InGjpxEB+-PZw{;N$U^0iIw* z4BsQ+8Md7uCD}v-THgdxpzS4IM){To3f@!I;ChkB&@4;oomg>{;0huk%NYv8lpzAqA2+G&$*&zN!U6pa6tSO8Z(x1A~ml1j$6RKgpWy>1QL}(FT z1190y1cuJJfnCiI5t?4}(VIUg9+Xv;7iJW(gdx%$3mGDW|D9nX9)S0`;Uhxg8m=7_ zt|7bx#oS3?!tC9K;6@?FUk^4KAr6<}abHC!;vyo%FgRi)vSKR&-z2h~8)ivX=o}sn z|C`|~V>+rM8!E;+8bmwpM#9;mHU8DPft)sWq8=)Z zFSZ*nhND%L;t-Z&Y`9}V8YHRp$3Y@S>S)_McA+5Nqb}0pRzRJwfn)6@&TRb2L`H{+ zJmW!vWJtP|GkzpUQX+H6V0_b{!_U!W zVH&2@z~V_BrgYe)PzFm_CfbMv+fwqHrJ&^wc?&u=qFXLzXL{zTBxWprCUkJ6W3C%b zEY4bzYHgE*?^)kfALaU-qM4{^hS- zODP&eZSrPsLT7YF$8JjJc-ZAIfRUBqWlSW;-KbYLD&;SNVPkbvY%WSiAcS*P=X$bd zJi=ppTE}l9XH#)!F>2>t8t1Oz33+Cjc`C}{q^D@Y=YSF@O(aHvT4#^l|0S`(MCw&z zV15`z>E{foCN653x6I~2tb}bMXoq^JNfh6Q@`uA==U`PRu0f_kI4EwND4WlnNp5JUdWvX{>S#j1;Eu+p!@=n9aG8qw-SONf5Yi|X&S!FNAy_8qjo4^&;;4^O zDS`@Ul|F}p1}XCyXGHW}(>)o4{>6&|CzE34J+fw%L}_zgDVDmaXFlhfMn{j`;g(($ zh+*BuWubpQWOyE@YnJ0gIU3a2kC=8Oo3SZ}%ITsqYNOtSmX_&b+G9fGsh$EVM}eYQ z^5?IS$kH_qlp^Y8DypNBYN?uPML_D3u3IjqrKMtAAf~C3Ug~Q~|5d#8#sQ#Li~dA9 zX{chJ>aPMTqo(StF5cc%>L#5ctoo^}erlkilgQZ+?Wt*UB3rP8l`?BErb7NokvAYrM)Udv2?$9vbnO$iuK}FvhB; zE=mxJoDT`dxKanTHllM{>%1!L!a`@g604*p9k57i;qj%vQfzMskQpM%ogA#MGVI5K ztYKo;JQD0xG~b*6%D(>NWlrcV7N_AUi@ELx$BJsghV0GaY*jjJv+iTWo+A#e5u;S( zg!1Xrd7vrE?96&Zwc2dXI_=ZCT0rPP3|WTlK%+1rbwd@O3gMc z)SB(tvf{`BO4in+w<4bO?c!Myjz+PqO&m+Il*GjT=SPrjoTBaD0`45HTGD1k^W`dI z$*tg7tg@zS1rhGdaxB8aYv59Dk`;1%u4qUGXt;B4vbc}A|}`mN=v z?&^l!s+Fj{eqzNL1X3ni-CD)aK5oHsuH(XPjj9CdvTpDSZ`omP?`q<)VA+sn)YMAm z*5+ZY#t z!f*WIm+Ly2?at`;Cd8BKn*H8x`L6GHL@y&HV&uVkK%D6D{}MX)I1jQaYXR1J@QWEnjpXNZG7%c8n75I zawmK8)toUO_pvxlGKwCSC0|P#W%9;uavgv2E5ow8g#U8)ir{$-XDQ=EC9`msohgR4 zG9t%vFblJ_H1gX1mPwQxaSE-lR4{q=@^bz%Fc0%IQ}dz}Ga3(0NjRu7Hzocxb7RTZ zHAb>{#PC8^^Esn)m0YtZkFrIq=(?^kcm~=x4B8Pf zpjWuYF)oYqDep2b`%ahU^C7$PKTGsPH%CBYbFtzx=OXJy#xs6C8a=sMzhDV^iKmdPvqI_(lX=LiA>kp zch)p}nREkJ3!@?L8$@w)lrujE^;Ki_6fP6VzW*$VAoay5wMWa58&ixqX5+azHH}m? zCuenAyLC&rbWx8Y{}GtoB(*%N@=c#*YwAgCZ4e(>zNl!~NVRJTTZ*_=Z_WjZ|F+R*xJ1~2_(fCfwvu;Ggbgl)f zL_&7W9rdf#BEO> z0l61tlOl7fZ)n>IM6f_peMhqpi*7Ic?kajbGzqu76w@M4D`hC7XhZ#d-m$A{B+HHWx#uXuwG zutUI-{iSk?;5ZN(Duov?haYH-BY802_~&9y#_f+&ADtVA;=FVE z9>71G)n!Wy7^Ad-$9bZA@SF#^SAK6{?QoM0@}4)kbv)(M7=)l-c$B|HQx}RfDtf5b zFr!yGMdGhcBMqlZIXa0r5pykyX#aX5^0$xxwpEMzttT+4KLl^9Fo;EZo?kMn^Lcc* zuyEYXi&smnzd5cmyYT8doA>rT4{4cO%Y;LFn>*;SJ2w$)`Ia~Px2vvUBX*b{TH7KP zxhJlFix{;O``J;sT6a65gZsRjtzjE;HrK|qcl4=P`-#&!*MiZkt7*JXF1;H(&f0sa z8!cq|`%9+yx_gVCySwyS%d2lFs2_aBqb>RzcKz}@mj&&l3;VkZN$;HZI8Wh{EBev{Jset`rbZ$hfDp~1FO(;eX&*q9c8`N10>R8Oa^|v zCWrlzlYQNnz3MDDtu|!~9cJ6z+oAuw<2<3fO=FiS$N%KJR*6aS9NKJO!GH{HI8=6>z(zRg=o$m?%K8aL0kzUvo% z_DAROBfswZMp8HYbd#Xf-+ZyqXnWs?r(eIfYk&K1Kir7-+Ec`y9IHW_sQk}Aig{M} zZ>;$P#14T62p$l45dR^ZD}#9Mx{vI*0p;VZ(hB7`S$hu7jR&~g9#Tl zd~$B$j!d-#c`|2}XctD7YV6WL(FNf)m8+QJYT2`C z*S38dcW&LgdH44H6}Do=Swqt{y`#8Q%$P52uI-ti)88RU6Fe@^7{S!4Ww*{4yyJB7 z7oufc84%7Bc1y?z+<|lh=atkHH2V zd=SD2C7h7L3PXA?sZ55kOg`M`ljxs^F3V50{W@F^x$W2rZ9Cg8F(xhrVY86N8g0B0 z#~gLskw?TZ{3yN?pEHfb5bbNqx!xozt3UO^QgOeARCLihe}<89#vZlYlFKf={1VJC z-TQH=#&V<2pNWk845K8c6R0cYNaRhbt~^Wgp(&|E@JBKI{1ebX1s#-73&~t+L*hIn zax9UWA`m?|v-@n$MW;fm(gJtLtxA8eRIJcYMIDvYQcXQ|%tLhuvdJMM^9s+19%T9` z*VRjHWfNhGrlr=gTj@PWSBhfQj@Nx-B$MEdJ^mQvkV7_DE7TIM(_Q`$W-U$z<)xH7 z7@IO_Ta8`&H8GKO-kIl~eI7K~bj>vGRa?{a$KL-QhS;H{Ig=SPk)Y(QtBt+=8SAXI z-kR(6NFKVxqNBTrKm!+g(P>;+?5)%LE^er7vwQXR(5~&i8}GdJ4(w}1!(LHkT{Es| zW&fAgw%P5dt@=;j-KvhO?!6_Sobt*om#J?dA0v|Nh6X>oaQ~|H?TyD1cbm1wsphxe z%UypR_Si2^_TaShicIOwwzT^!@)I zfC1E!s%p0y_)%|n4vWy+7&o5abq`(#)Xn~oCqN5c5Q7;+4*{X4ACO~YRa>{ z%W$Z3YoXt7USu_nX%L1nl;I2?vp)PJjan;YS@hU8LLG|7ep*4{$|N{9*0qj?N&i&h z5}8=ALlrPRAmm{WrSwDKwJ=)vDGm5IMYjqz5sYCJ;}}!IL9m^tdewQ5MXJai6LQEg zMda4;zDPzp-Vu*uG~=VD_%|tqjzMg!h!xLMI*dSSi|%_!#&A~jVU#4;7R8SeonoRPAn3Ux#Y1zCdcCeE_MBDW) za<&$==aVXAr75$gN@1RoA;=7huiTKVT0Rq+(UjaR&xl4(mJ*Z~vy&*x6GC1o^O(gn z+oqJMxpt?2Dp-NGTz>_>zm=n*<3lDV5V}I#RF$6H+mLW#xkKH73oMrwNOqrlvk~>jAkTy z&(!4;c>6S`KLd2m>6yiJ-*F~MdD>H-b_t&9n&&C6f*)+IXQD6V=6H}J(?kl>IyGgb zLW=j5oQm&UKh^41xmqDILD8BCdCGlQid2kHw4!usDhZ(qRg4Dcm~F+&M?u&!c>ev20Lh>AX>149mpUF*U}atO^~f?wg14DCh#^d%*<+K ziCbLb{^dttEf2~#YqXLbRXpA)tavg;hE>c0yT5QoDViV^>;A$H-Q9sCe({U!&f*u6 zI7kyDab4^lfDBWyLwU)t7lNwuxcSxZex3LpfIE3(|ZYiq~^ovO>uYGI}0t`V6_R^#4J`J-X_>V60oiC zDprx=zqE~iS&H$P$y{cUB$uxMj?zh-RhHo&uu?bXP zcNMj5?=PxxfPFY47|y7MH*DeSRg}2Zcs{^7FS#GS@)W;l6B|AVAe?~=bR57L9AC!)_%VtM>o&yQz4xLYBiu*N9PDAI zxqof0*@I;E*?=5nmHzWRP#fk3P2RSzVQY|-cNahutHv+90d;p1gdh6=x5KadXMC@Q z#V{B9;u(KQ|87!qYCU^M1{`_Nvc2a%f6Onc+-38kx4h;h!>sM}lxk3X9;f$)k^X^> zVB`YPR#uH1FBp{@#=Q_h&+g@S`Iwduj#w zZ`aFp!%L7POS~YA0KS$CzNqZs)(ss%Zt7gm8P;JR4nQ4L&mQ7NAi7QS21D4?PY2wO z13OTL-XorF=;o**B*;d7cquFLPyg&9_C(CwTF(FY>;Q-?6}-U)o30x6!5>l&8Ai?< zxX&5T!AMjj!;-HrGEf6OPzje1fZ&gz=41XQqL+AwLXI!B_Jg(7_(iish=RJM=C0m=F*1kaC>xq$H07p+%-PMU7B! zX0DJheoMp1!1frz2uiC9&ITQ95FOBA9sjao9wN~jCQ%3RWd}-2*No6F>~P=okQ7T% zZ@?o2$wJ`%&|QdVAc6@(tWdEgNC&Y(2Ty1@;!L1wLlj5R6n_yIe+E1P&Qe$rW|HX@ z)lQJbPyWx&zR=uW;AdEgHao|v1f*{>}~_lJ_Co;0v5B0IGRy5-T;E| zXR)Y_HgN9_xltbHFc!z$b36))0p-m;N!l6yRB9A(nwTqrO3(lH;?Km1ZHuW~E|bAkx- zrdUWRM0z1{UB2`NAo-+GyW(uD+7rcGjlq;axzy5DHjtjLz6UX(>8Y_El(3L zHzhUwqiv2dHoLOXDn@sL69W?x8)M@(myuS@FHAEc??OCn(m{CBJi{k5((~Y! zCi(1gCy+2Xv#~x86hZq-DN>Pa_LFE(U=DoY4N%|!V&EX%52T(u*Sd>ChU<2kr5s=_TTa-lwa2Yf7I%5hz-;OKi3PBX|JxY{F ziOG)@bmPB)-V2?9^Yzz`}S4=OL~4G}@e|df=*2$8xwRRabYFAS@L>b3;?Hv{i-m0E87!t#kvBKobbU5Dp*@ zI^k4j6ba;%1ag!(C`?1cv?Kzmrj8R=bCp-aRZV?0J6B^#@03FC6j?v@1+4T=$Dklc zRbJu16X2i{;NS}4z%%t}Xk>M;XmubM3sF7lTgg&f50*$1!%aD3NjD%^Kb0UhpjGko zN|Dt{m%tNBRbwk*ROxjPO!XFytmljmm;9B5IJ83rc3=l8L`4)~U-m#17DXQ;PCb=V zK{aCOG-7S`0RNJ;Sr4ER2qF&-;A0PfUKN28VkO}OR5m%uWc3GSVN+#Sb|?&KHj@)( zvo>buVqp&hVhe(251?JYmLZaLSxHqBG`17y^=JjjsE&h}xb;GTv|qE8M?+$2=eA5i zb0oFaZ@-gkp+`FPqFRf!RUd+EBLZXdAZ;;WW7)P6`hXFxVTkZ#Y2~(@>~_UUR&!?+ zGV)e$_x2hg^>0g;IRiII|AJNVlvr1SR5u|Nf+50eK@mumAUJ_P*5MfrU>e?rD>4DS zMsK~c&Ac)$U^~&*%1aXLz&(rNH{0<;J$I4l<52fC6dhGayVG>HcQ0i&b@d`sCDv1q z^=47R3;$jr!crj>kYN@MAQMLQSrs80*x>+zfgsjlO)f$n_U;!-VH5;{$U+RonAh&m zEBXu=M+xJ3p*M6db24nTdYKlTkP}iPm3uGvEK&C!9aJYER$@^?d?WS%s9+X?VH47} z5^SM;FF|7!!4tfp=?SQipx@if3-F~cp}_j72F^a4#06Q0U1_-g-MkY7~vV5;Q)}~0Pr_D1W)7+ zfbag{AJ!oi?5!Yt?Er3|?t050nymj0!)n>*h#kjdu46JHxOs7^Wwkeo7ug}FxLn<$ zMgK>_ihEXsKX{T4;1Q7^67m2O6ag7hffLmBjBQYcKVuD@!5dT$D@uXN7SZ`;@Wf_8 z*B*}Rx^98tQi2tDi4Vw-sTL{-lyn(cm`f5qpi}4WLI7KLA*}e4KX?XuHV6tLnl~T_ zLKvD&^%Yj36j&G&3?UPO!4}p5+zvnAG2^y#iIztY6D8jcPtoWff;GrpbnH?Hzle(dM76(vFn@JTD^q_t-p%XM=oaI3c z%NP!27@VOD&(y2=u8YYI;M}G!zHY;&r8ass6I&UmX{4&BN4J85TCagIDH!yap@Kp$ zxv9anp{F^iA)2XscBv0Q2&kY7CLtI~A!9co7+#?d^1v6str~I|+`K^@F5>iRTd6IXu_dk&f*}>)ml!(Rt6eXRqs12BYao6hnI5jnBF^?c?A~ZPxc_Vpr*Gph z@o$j+8SyB%f-QKrL+X8BTA(Bb>HK%#oaL6^zbRtwW_*y0wMmyt{H8Y5T*E(7p3ozE6C zik}&589Klvx@?tO#+N#pslXBNd$~8j5q`l9&cGIiJQZxAj6==`t3k=D;lX9M+_b<7 zxa`kHJH75L#1f*_&JQC~a>O~KCey^O5wc*v4#mq{_lCML2A3wXre!&p{c%IkGjsNS*p8xF1s=U(} zs>_@9D{(ol^DUrr+sr@x*wDPbfkI+uz`v{cp$%KHhkLncK-D(@3ebxVu0RML`xhnw z2clUF^dM*j?-zQPGK}HSw{DvaB9`koy&i51(@PP@kjqHBhpOq)#q!HNymM`N%*h^DGwz+EP1>(rG^+hlnYb|i__p60O}Sm-Ck-hwL1hk!gC+UK9b(3xy1-k# zznwao-M|g#zzwds+g%eL&m3jY$=2!Kw+pxuGY8{zX! z;dK+Xy%n$Dd*YLx(tw1hX(FK=8sx)$)oc9Ys~O#)xxY=_>gOD2_rV?>FgnmqfvN{b z3;yzeKIo}^=tn)5?E)TuTIu5+#=QNJX<`FrV6hWh-9>)Y&E4;Zn<1hZ-5(kST#6#8 zgIU_%t#28wi(W6*o-;p}yy@173smke-^D8a;_E&pB(~h6J_xQpxvT!;|K8OH+o84e z&|70^szdSj#L}kSEnE}w|Js!J)6pP4;xV81DNFNxTPET>>M2>=oJq5$&6_xL>fFh*r_Y~2g9;r=w5U;r z9y1NRcu^qF9S1fH+(3is)B{xu(jZ792-c}tg9MQ}P%Oa>8(u(_dC8wsglmt=b=a1v z#Y;{L!rcpZF59|x0}E!F7h+$(Gw}w_7_zbBkBB2no=my2<;$2eYu?Pcv**vCLlaH9 zlyJ`*QMY2H8YHV~uu%_;O+8SxSK74)-bhFj@Bf>Dheh)QOt>&`zI%l~#9MLj#eag0 zKTNK?p<=t47(d?LxVrc6;KPd_PrkhQ^XSv7$4UBtUFkNVN_{<_tk$cZ#eA`0}2k=rei@g#>i%m0q)cmfpKBc^E`@WQBS9bg2-N9D}d&I}*v@WXCN9MRF& zB6nHR7G>hb(i%?f_uqgAF8JWeadb7-f#Q@eLZd2sz}8#S?U$(weu;P1ZomCu&MVQH zdF7Y&xmd=0cSrc?sHd*_>a4S5ctK90To9=VS!~&WtfFmVk%=d)xrdy0u5j+QPd<9- z8@I0f^2|5yeA6W(F1MC%2z?3hl5aj3p1F${yh=i1ulubSBfs7A=%=s#`s^qAI=!(g zTGv09ydi$^+6QKDL#%q=JJA8UAO0@381tR4eF#jT0vE_Y@4U}s)58*Apkpul3GhUB z3RnN&7Qu=MaDW8FjsYLj!2c4O@PsH#p-&!&wGN^PRs`|Q2gjG54D#=H9r_;lW(Y#0 zm2ZTmQ=t%tNW>x@h)Tn(;Mt!o%&%Bc-o>O=s=`HL1D3nNR!guyvQLk`tgr|45Y}+Xb{YOX^nqk zh(8YSL@2JOZ4JZWBmYOPJ9_SJQtBcfMIy*fdh(N?q?!(tcq|u^2$4)Vz&{ij!|UC# zhH*679N}onJX!LRcRSuDArs18`tp~+lvff98Mj1j(INv`6(l#w*}1Jrc}rdjIpA;0z5RVOPy89g~?3L1!~vIn75xGLo~*VL5$w&9!;vT-&r# zIQPlVe)>}=Nn{Z@YZ=9hL`0nvVW-`I_s-8PRD1WroJEtMx`A}L~6FCBz=>0-t(Tj4jqd3i}PB;2d*by{;sU&Gb5V{b1 z{S-XBlh_6~hZl#=Ql{dg=?`tHk)2xgs#pc)C`ma_3w&oF=!K)wuJt%Ajo~Y4nn|i+6t9qt ztYj6aS4NGLB>zP1DmC?|)WRBQK=46GxZX-U;mCEao1Cm_SIb(~>A-4?LS<0@N-w^m z$A;4MtUH@3R=+Ctji#NdV_Qqy;u`m9H!UQWWNT1`gtfPT9TIMHTSbQQb|Abns4*<~ z%(x1ds>cnlc*o1G$||I+Lt-v67xG-#+0Sy(k(+MS16oEth>eR4t~MQ;T=M$&zW`R0 zdBLPo%nBr}X6=~=?P*<=KIkpo_3nQ88{i6C_`=;R@IecM;DRDcj)`55gYWB)vVPDz zH3ct*SIpuTZ*F0NfymH&2j6Hen8E5Hv2(arS`@1kwYzk&kcUiUq|y+mvt_Rau}Q~< zvNXix$^Wj7VnTjMz%=K$)#BY`qw zb&2IJ+xgCT)(KJVb>_bMwwbLovq&90y>=4nzHc6EoN*~(5n{Q&d5*NCCtVVvx>B%T zJt=iXs^}YcI5Rqi(3B~}Z-7 zm?WRZ%&Be4>S7!F&aQT1pKmK`^iE`+!N&Ek30qxWhg#J4C1|v7_ub(h``h4lak86v z>+q;o&2`k7ojOhJU2|r{y}s{uXSHq044c^D&bPk(yQ219`jiTmNV*Zr>0EzE6uIl%0@@x-D=1;dUduGY$&1uWifLLr+-cWY4?a zd-?KaayRW=jrn;*H*HU2JTh@dG`j)F^<3T^?|YBDO8J~ zT6p0ZZ+Ax%9nzCez3NeDc9^rs)b_P4LT;$L3yR;2dS13tIUd#6w51k~_Jyu5)m-BU}mt_uEf+iR;5cqu(*dYj0d&p-Y7l?tj z$0x+Geg{!BJ%)JQ26-pggFeVEDX4-k2vIILgJ>3mMYw!YJg5i6t_K zOgDsvHHJJaJiU-N?1{9MsL3Oi>gR;#kh^!C>n#v zOv#uiu(F7<=#0Bq9i3;5cL;-z=!}@uhkn?N@;Hx_0gJ~Mh9|;YfRcsg_<`0IKZ{mv zuw;YgXln52ZS*06W=I= z&sZMmmuUxJRQ))MI{1Z#$C8zyc3@afLU)h|8Im}elQS`r{D_YwqEh>45EVp`&@_7G z=Z~e>a4QLuH34z)sFP3`l_yboYy?$Xn0rZ!?*^^+oS@$Jy zby<=eX_PNHjc})CWciS{0*rx)dWE@}I_Z{gHGa6p;iS-I1gsAy_V zd6S$On>cxxpP4P9hgq}cMyNTNqNt9fczdx|doksXyh(|{DF2(t8IrU~nk8~>a#?BX zM23o497@TYQ4*Zg#Z22poFZqFu$i3T*^QpLm1QX$)q`jzp-y~BU(+>;=ZI9;X&vvu zo!!}yj~1TzDW2Pdlpz9d&yk+Tk|pU_otBAW@##cTRFL=No!^mti`iaEX5hSR5rJ`Cbl8S1Tx~i7CpM#1X{yCR$>UkUbk0uABWlD{tdJ*#mbf=1{eA=h1 zI;@d*jDm`(=Mk&2NbWnMs1gx~)ieskyqBLFyi&Q%k$4 zU(~v&NHwkJT6Na?q)^JO@M?74`kUt=rpV+J^>uP{N_C7Et(Kv#iVCgh2$i>}l+p)zquk;#gi%BHw>8a8+u@w8Q zh;gybL2FwFrm3o`9y_zF2C^v%u3jmYnX@p2)~V=PpDc^98Ec*!i>5Stw2^kAbr~Yg zIXyayi2M4YDI2nK5wr{k6Xn_yMQgN3+qGL}vp4H>8Ws_+0o2a1rvy|a2R!gHXk+pJitpzKXb-TDkcDE60u_YTr zkt=ndx~_m*8G@^>K4*%QYpYX|xWdS|qPt>_`?%z@5`4>km7BJ>O0`Cjxum+eG-0?p z0e_%tu%ny1|5dtYs~K+#5vgmkm}a@5>i-$AD|cE~6ESDH43TCz%C)*1y~f46jY1KR z%Dh0!x~&_wh;h7%HyFRGlrIZ{TMNC?d%ly!yS+gB0j!MIi@kqozXwdT z{+Vc;+qclly*E+5lRCjBY*ofe806`?bZE91?3#knzWwUJlaat!xxmynKn#1h!TPQz z{KF{hs*MO=>ol6t>I1nhC^KoKY1lKODEcN{qAox^+fu z8BDBxJMn~3EX4%NzgN7*9F@Y0c>l&k9KSStd)pJfUn##pk-!{S#)CppX)_ql%du=c z$lavA`J0hkyu%_(yhj9Ko5q%AcgL^}?EmT(5jdlb{U0Q#;D_xy4VBhzFC(s?5s3{6~fy%SU{mV@b;m z%gC2|XdfJzIT%7*M8*9Z%+xGK!)(E#d`-z5$|20cliAGDD2dRlG}2tf)qKuHbj|Wp zjg|SrKcd0QoRm+D%-Mva%ohXB&8W>SY0u@X&kRjO z{LFUB*Uq>+iQL@Cjx21Y-2cr8ozTV!x()r&DfH0GB_UH3&Kntk7RkV`T2aOf#tMpf z4i?D53eq&4Kt8&{b8H~86)`*}(Re%@DXoz!eNQc&#PoTY5Ny6Rz0}Jy%mkfra!H-^ z)Xqn2z!vSzJ6F_+eAJWU%fHOjVBI=S9hYy$jEGg4vRsEbJk)Tf)mOcg+}6W^8P;^o zJU$A`?wr9<{c$)=&keFYdC18!$`U^P)B2m#N?q5A?Ke*S)aH6^h{@G|t=1}i(U?@y zw@lS>tM!zVLywH%Hh9rVet%|$Y;jXECXyz<}>4&w2q;t#QOM{aLHUD=i$lQJxysoj@s4T5QW z&r+V|k#gcFqW`SemX(UsJ6jHoMV{evo)a>eyzH&rY%3VaedB5#=#0YVyQ8iUA%_-D z(G{J|1Rkj~+Ol>`rd19Tyz}HxF6fxvB{$uq9`+zX8Rz2H;=Nh8icF30p{#+8)kD#! zd2{19p6ReYBvfAL$P4F7QD}({xucG?rM{rX;i#nE=s&T)fFA3{ekHShgd_*&mNzjd zPT9O(<~5103TKLUejr}0qsPAOnK&3IYTexuyFnhg*M5DAzSWc7=WV;**0_Wso|)Vp z?rjGpT_aS6L!=SS)8PEOzQe()kf?<3;od+i>!Rqpl7??w*s zZ1F9-`v1Yg-skRm=?LHP9ulDvddk<`bN=kUUO46x@9#44C#2e|GePktf!vnvMIK-C zAENM`E_bP3?@i9`d#>`w&EM7Di#-1ll@9MVpY#TT^NKiS!P{~B?ejk$xAhC`L~mt) ze4I+Z_37cpO~K?Y8m{jx)I{#$DK8o%e{BX0^H7)V8pHK)j~?`1^hHsq)AsaGzdKzX z?O(3(X+LUZ0`xKO_PP@HhF>0Y{~@SOvh67Nl`QaQpS^$Yuz^qaEJ5sFefXLm8eV@F zzP-&8-nx%bOwC@t1@|Hgm>n`CB z;{WnDf%?9G=6odk$p0O4-}}Sf-w#o?tzY_g(ag`x(bKy622D@88rwjW{NAq|JpT1y zZ~Ls@;ZDf><}TGQf7(PbxB;L2AS^uYo%J;T{r1oK-fr4_uGf=``v7r3;J|@93=%|` zP~k#`4IMs&7!lzme-$lOymU$8#)1Yte%!%P9RFGJ zWXhE-U&fqS^JdPSJO-mAJV9#6iQ{C@uZ{r?9rKmi9NkUZ^Z<4(N-8)^+HkQO|^JdB*;&a&JRYi~DW zu#!(91*?)U6a4b)2|^Q3L@`AbS7fn87cD!`r37ztvBC5VD^S9>DEx3e#4_{?y{9@P zs6wnl9FfEqmt?X@C!d5eN-3|4QN|gEt8vGoXbjLkmw4pzvWzeU@=Fehoc}Q^BuP|m zN;ltxGfp|@q_a+is>J9@`mz*~qXYr;@;os2)NIT$1wHe$BCpg+$0QlEGg3(>rL~<=~19CrL|UDZ^boNUGG$tQyg2g z@ikxhOLbM7dfY6~mVV1hE?--PRWV3+rM6mYuf;Z70X4nkjc0>nG1z0jh1R-aS;Z1H zWohGzTq31XR@OGPrMF&t@5MLYuDEqq(QvgKx8Li|9kkQs*n_WKfg25RR(&6aIAVz> zrkJ2ihI!9QcV84YrhXrsPRH;HHuzv=jU{>5t>Sf~#EM^rIcAw>w*OO8)jsBUWSBlq z_c@VK-WgfcE;KVyoaxHxIGUGcx@o7M-gYdWYgA2Go=a}-XLNhcy6CE|_P5cbp(eX* zv(H8wMvS*R`d^?u1pCy_L}r#LBYkeI?y2GqJKB@d20U=V2PZr!O*d_O#g6^tTj*pH z-uhSP5PSPZzP~E2aLqU8ymQU@OL}3b5=pSx*YicMe z&U*$ppW~TJRo^3&_ZV102d>bEKLlbBGljbsnrJP4Q4Oekhn)|Cu!o*0Uch)LL@HL% zidXzf1&e4RG64o98e~Z6$kRmQ4exX#Bw+)wxJEX%(Tzv3S@fg_A@gL6Hm|s-Z)4?7SfQ}A>#kK#2X}bYf%;))mYHTI6ndpkm6b5AvL*4PWn)bTO^Q< z>^K^@K=MCY!y(s1xVJoZ(v`1-CHX$7NdFx1PbX#cHq=_kOlBng z!cUYWM1x!lC=&gTstG;CWqF@SH?0nXwb-?826UhY$yL`eQME}7G6PFY z<}%xPE-j^OV&mgzL08(+5KJjv#dzm33FM>nqqJrj&CwJ;X1hT0vv4lGYF4Wd&d}s^ zd+zdSCj)BKc@A|}&^%F8x7ydgrYE=liO<+*m%9m}bs&dqXguS3*(7tu0?zB+Zi!4rezV*$< z({6gd^XAL6Ehlfgq#Cdkw#u%fZSH+H+~Gg`t;Vz+;gm>K;3Nh&DJSh;s3=^ud^JX* zA3k!Di*McRh7Ou5=WWY9Td=6)F~^^>u7wAt>^qeCK!H z`%!}aNP}aUgicu{*=PT!u8f8YJ@hf}|SKYk(C(EPQxz0oDJE;}|J{{II+=m~o^O~za{VOj?OTsI}!XZke`J$>N2pmYTpuvL(6DmC5#!Z|}Y2LiqL9wF6ix@3VoS3nrM~V{PTnhQIq{)pY zQcJo3uDThNwcQSn>cgo+{v@2&!0ep3LQ$csL`WHlPXQ9qp8!UP@_tnO0}xh zt5~yY-CC7rRyV_paa5^Nh&sEw$lNtj;}E~eTs3Tj}>`F@@Tw$?Wfizg&nq@c`><>$$}$g zHraopVV0Q?b36#4WuCwXm~taACz3zLT+(4jMpX2gY}k<}-ho!B=;Dho(i9v-(jAxF zB_WdJVPHDmrxA|%ttDcQ_enGuOfe>@Ex48y2#>`R8~1dyB9?VYf1y=oT55s~(~y-c%A{Z>5!H3!op)7;S%v?3^3PvrnKj=@BI5X5T!oqm z8;VhuS7oD+Mk>^d!`Ud}T3Z+`^>S|DM#{Vko ztX=J7RYRL-SfogpLg%A%#O>(enRMj|;wEm=DrXArCrs(d!00%7azy#Z- z?7;|AiRD!9-K(#|u8nzIp(B#|TrvhGd@!@lLMxiI)KbfBn5qrBTD&Wr8{2FJ--KJs zFl&eFxhS`V63Ly`OlrRRYV^inEXOSL&_ow)bfg+5t@LdRN7Zo8=0be3#LT@Fm!|Zo zmF&`7>!28&Z`kQEWu^%Twa*(>Ocu)Hmdhr(K_7ikR&v+f)6Aa6ck{12>i=Av$snB# zQgx>KYxm)ZC$9M7ws!6K<52Y^)zgBX4XjDC%%TNFzwEF|<~xuvi!J-u^NXlO8nZRz zkSC;I$I$u-XyvYPC^cY*hNyO0DyOUXRE!5N(9A^E%X8L!-yW!QSNo;>$v21 z5}L44`Agx(CKZ+s?kiJQo87O-hZg#khz#qSg(PP2h5(d6YrkN;K@ugZUzh(>moXI@ zu_^llo7hU@3m2NGP(msc1#M=#zj-TwuUVPlPRPY2Nic8B>DARRxFbP1u`GhBTwn^< z#WuR}jd0Y>5$9+n7LJT$A^MUG>4T#^qU9IAa7Hjv(Fuu=!3bm^1LuZyKRPq39jzQx02%SADKBrWGHGQi!~CaK#iP2uPIKx366luyOAkD#8Zco zGo>w!rAd`j(r|&1WI$>jO?L$}s7CdxU=6FPf=bp0%CvGLiA1rVROFG3Hu5}+HpZ)BJ)s4^M9?x))pE}1;A4AMDtRXMvY5>* zlkf^upWu>jhZ-YW#qt)nUPwZ^o2>nc$l2Dm$eIk*SD~~@HBA3r(VyF_jutgL!u(uy zlc}s6X#qRfR`T|^$W3l{T#L}Vp>=?rGRDKk^cMeJs4pSQZYTQl+mjfSx!~OjZ21}} zQxdnEX&a?W)naeSr%< z{^1$ZQV6b|kSp81>)#4q}XFxwphH zj?*MCSjAk4d!OeJ(C-~vukHK}PI4VqymwcWD5jDda{t<`KNHMi0 zu)G(Y-i%vCp}v&KXHtZ+xljyU<8JxPXihVeA9>>(x0wITsk@^weDUMFWXlsl))St# zRo6B9`8;!a@=@a(SWO0Yup<6snxkarX7D4-kcA;!z6@FGXnE0?&h&f#Oh=u37JQNx zvpQ=F5`Pr=KYPNL)%eFRkg>|66W=gWf1D~0p&FyY$R@g?&NyDHVU9F1wa{DrMgy4cL z2jvCVLYRdcaNws{H{%yVXb2T}-RnCN#;)KF_=TNZY^-`1I--smn;vSmikc|V<@EM; zD&wa=HQR$_Cd{)X&hd_`RN(o;iGp&K@OO4o9;c0Hs%hccA*hHnoun`|SP)1X6IJ5Yuft00CmJ}CIl`#wv1oqF2Mv}`NVu$xcqJWn7rtv!-- z#nHpB@~2OIF8^M_3M&?6Wxrhf!jfYsxEOH&hC0(hIGR%B1S7jrOB z{!mgPvLFc9feZtG4^v6dky-$lGRfgYRdp@~Xb=|IfBrx%{$MTb_74oWNnN#qIGBTs zMrQahzgl`R9ddxP}4~g$N@fXcvNP!i1PqdJ{uiBV`PyhH8!`PB!%+ zE}>*@7==?vD#3Dv#Aj$F0Y#D~MH&C0hJ1o2mA5u01$JzBiJ15=gQzSs@q@$XA$C|b zOjR>T$cHrLSD^)GM!*C{u!^~bDXqakthI^mSBTIzKoNyXVKx?O_+wlrA6=D(nK+EZ zm@2eLD{|68h__;)C@g5vcBXhQhgei@B4Ul%$OLad2*j`q zgzyFhxr%N>C?i&n9cYUo$qnX0*1qYG4ME#A~}*vB9U;CAaMw4hZ2AM zSQb8WAJF)ZHE0s6_y(N71cd*fjmzK<-dK=6*^sUHkWnWX3o?r)Nq7_)CRI3sMo3xS zbUPb)85N>aov>YJ&?&)4l3KZyD0GyMq8KR|A3=z4qg8^S;#-X+ign>@_d$@_NDM8v z44iP2KUtSRDU=%$kzRRyNm(Q!=sbv*Gm5y5n9&Ipvqqa>iCnpuj7c7QsW7e+mIlXI zL#UK3M=u2h7Z2r@2bquyIhUN!3Cl2=F9;WNnUi*zn%EeWyhD_N_?Vy9ml^buh?s~Y zqK1XU5k{hMA=#L|`J34Rn{fgh!$5Lsq<&gBlVtH0LQ`zf0IWECu&+_lu{U-1xF$VDVGZQoebKb-Wim5Nf9D4p8A<|vT2AP(K(V}K3dQ| z?Abn&paoj6p?1&&>thjWSfBX0qAc296>3ZSBbomBpUSy5X8A(?@KeBNo;zR!ok7WgIkOqmGLYkVa8BTB`jxQ>37m7SP(45P$p`Nn}F~B}RR1xY!26liEE&8Qk8m4p8 zr05Z&HM)4uk&i7oqqw7^!?p>6kPO7YkVjglKe>%^NtbrInysj$C_<(d%A+9&B;N20 z!w?L{fDD(A3Zwt93Kh{lvtT|RS`lJesg`=5fO;O0q>O1LX=iFCYw8-B(noCNrif7l z1|bNUunD7ZntSS?+XxpS!;^FQstp;QKjNAMnyG&Fq{m?gZ!ij_;0(|33*PW*gA@Z+ zx&tRFL=F2I$*V6@O~W9gRg+bsRhhria#)i(Il8O*BolQ2r*gmvMrx~e`I&Pm zn#=GHrirfVdY9w$r_>s7zM2xBBSfnZ5zN{InUi#%|>6L+E=A2u3JGAzw0r7`Z)2}F`)4Y9;oUYLtC_H%b<8#t7zMbHc6p&TVqd4ALT%|k~_Kk)wt}TAUeAv zdbGDT)lQ12g{F$L+!3~}TDS!nt1k$H{!qGw>!X|?2TW_Z7WTMpLAkbjyO<@rua&u* zG?o!dqfi!FqYAg?;Eu6$US(={$Ve8+8Q!{at+n@f5@{1Jckxq9;!VvH4mdpJnEywd;M zygLc6w5q4^JC|~>32++6aZJaZhR2$`$zv75U~vErOC7%J$L8y;6FWpiT)kR>s)w97 zWo*U=8Je6h3J1By@vEKFOUVOK1apkZ+QZ4f9L!Ck$JcrQ(jU1OhZG&a4@*JuY!Frt(20@#?^Okf9Ozyz+%-FE+)&2Eg?whhjU z9m2eQ-UaR3(J>GLmPd&4(3b5Mnv&eCf!C_MW;A^?p&i2#p=*S&L!Xn~ug%)8EeWyx zs!;sT;|c|-Y^CM(^C`Q&7n&3eBZy9-$b+D^Xl4KKnb&Ojj{a;|KJVi zun+&>3_SS@qhJRrjyxYK z!=Tg%VG`z}-T&I9%gUY-kqXd&3-$mAoQ_92{%d&1lA`X0_gvF`4ZWg$&1THvwe9M+ z4db+k$65deiYe~vkR`EDYrQ^c^|Mr|Iy6s*szp5+9;<>miPcpbd$gir_#pYu7d1upRL zG_JejrVwr6OHJTQ6ww60s!W@Js2a}^MxX`7p5tEp(m!kHZj{*n4$C`9*zqgqF+bL2 zopjop@C&c=X0P*w;Pc-uyYC_K6Wa z@@SjYTAkDO`|@93@VE_bldA;^kMn0g`Dd^8V9xf}>h^Cx9rb?MXU?_*wt4 zfX&ET{m4n|^@|VC0wK*zCbc#%`IKM#lh5;(|G#W+<1w+b{`AGiIrYmvh@sT_KTY^( zdyt)Aof#OUF|7CmpAcd1S_ez^3~&3`U;AmF``Z7D`I?^)S;NqMFI!C2`N(14qF?;R zzu=`0@LfN{Ek52hG5wuosgPd?w4eR@Z~NSDy8xj>;6Q=}4IV_8P~k#`4IMs&7*U6t zVaANTIgnA~#*I5XegqjZk zlN*UejUGjs6k-vMO`Sf48dd64s#UFCjhaO3R<2#Weg&(w&ZbPGIB_DxMD1F(ZQZ_w z>-J6BxpD2@#d}uHrcHvpV%?aeNRcE;4I>4dSn*=UjU7LR967NTFm4KE!kk(2X3m{G zf5xoEg=EsDO`k@cTJ>tytzEx{9b0zk!?piy-^SgL;=hYle|{u+5~shOzm0o*sk8X; zpFxLPy=x2`Ui|p2WY?HYi&y=6_U+v>A*44`-^E}D7v66B z`+olYXH&L}5YPrBut3fV@h?FI7i6$O2OoqmLfG=7utEz5qNpN_eEaRC;czl$x(-dc zNJQhDgGo9QT?)#&3txmWA_-@_iaZ-{3~Q{i&Pwk+AJ?jDt~ZwPXBkf3__4kC5Tk3}|F zWgCmN*=FM;2`dpxQgP2mU*gSLnP%~b+Z|TnRuV0C@V47G8r{K;NAonsMQ7jLZrKK1 zrMKQBbTq3}Q}3GVEKZgo(jQUz@rTEK*OP-2IRx3Hj==2g>b@!Er8q(tw#+r-&3G-u zkzaoewlf4PCb?vjPeyq*cvp@wPC4gfuB3H;3a&&v$&h3RGRRnkTtMvrbO%X{5L%L) zXBNprcUflou$1?MIO=*i)%X8k_4@7PEK*0YT0K-%J-{!izmhn=r_Yw{R*gUVk`Mts zBLt9MIo=fzMm$41Z@u^C+vKMI)^4|#VMe-e;9#2BXrO!Mwux29m_-hrdfq|MCdx%x z>FWUJT%x{V8$0xR@in+>_UP)-^tSq#g1Qs`QCbOQWw>onORcmlXIFa4N>botAd@iZ%4^ZJJ?(@Ono) zK-9rABQszIHMl_zYNY>tACw5R7Gs>6rQ~`n(jL+T)u&5{3K{=Ehd1UC3}{>;6+z>c z7KV1M7OfA2KYU*Y9TPwzLX31(<6jbgq>+Smf?=B|;;RTFBOz)~Z3Md8-7ZK71_nZR zx)X#JHM1*@%}o$>5aVX5xJEX%@nk=Q<3e1vp~TFDBqX{?3QxF$^uiahQL=0ZktF;G zM2I!4K@hHd;26C~2rmkvcL>Y`A0d_v*B5fa zN+98^9WFJ)%2uvH4sr0^X58jQ2JY^azTC_vbVtEo)ghLf!5}^*I#G(M=9|aN(BPKY zl9JTqL)u!Go}wv|oq#lRJ@n>9p;ytVkkh5GyCgc{^Dk?LYE);5OJd>)Du0Y34)i1^ zOZ9d|&hWDkt$gLe9;&56)RLBks6!k)Q;N6=A`S=zjZn3^Rjy7&rE!#=MmL%#kaU!q zGfU1{Pw1$TmKCL6eO_0e@>06W&zv$N;B@#uTq?iO-NY!34;FY8e>GX~JAr2iV1yWctiyE05aBg~`F83FY0cT#4L_Mbx<0 z#cuOn`@v*B22y@ptw>ipUbi~Z4IbPs)3Qrj_D1opw_VF)I9afb;6@9H zR@8m0WUY$TgbH~;)^&59^=zdr18%gD!5$tpJkmZ=ct!JdW{TE|QZ4t{O$`Qfq+Oa3 zF)tA?DgM_#L}esGI3=f13FRmi+m$`{M<|T(uRyKJ<3gm-&Rr^XtYyt0M>lPbk{L-! zsGJi+AKJpbrqgpS0_>PEIwQ5Fl#M05>~T7!(&||ZF$6Xof|07eZPBS)4zOme%-TCO z!OUV3oC!t<$kngDvl}SmZFaXiHppICgaM5l;W%^9iFVOfB+ij^|;&(2;{a_pw37 zoPc3C*`Z?beyN5DQUCgBLQ-{*Q{`e=*E-h^aPq)6-tka@`=tI{8kayh$~d>YiKs6Yq+#M<{=7eG_&XE+acq4j;C*U7H@4?%|>Qliwx(lIhFlhgT@v{g1 z>^toUOLnMgm*bBb}(I(5Uq5R^XwybzbWzmd2%=2JA9bEcf| zKNcK{ryxP>C^ZAL!SNtHR}qBy$QMxiw5oWxOq(`>ak{-LKM|A`ny@_%+=$%UqW43> zDD=7+tdOyTy$l47w8FgO$eu0ikQQ9QwbHpP3qUHo4FcSX1GvF8{EGkUlbRje1nuL9 zce08gga%FPBu~3QDdZ5J*ubYCkS|fZ-{ZqVbT>21k6S~HJF2%k2`|JMFORZ`FuXG7 zD?>zd8Z>0X_Cf=VKm#Q@isMMX4m=Rv^F3I^ z#Y4oz>?l6Ts2MQyLP)8(4NI+H?2w>{K^fdd!-%#0+QhNx#HjehBtQcgu#r)uq*C;x zS8R+ajgrK`>hs$8^-iWxS1EEDc?2!4#}8NNl_OBeXG;3U(x*W~{qs z)Rbtvicbthu)xNb8Vf-%#YH?tZdAvNFp*ho$cWrHeYA}wYqI~JzFe)91nnOjA=Xo7;wW8(~*QZjc}C6jtI6>tI3?qvyrTgI8m|I;3Ipy zvTT7ewpu%56G@(Yh?2~+Nkd7lD2+vsN~!$BAzHRgU_i)Fi+@=Loz#eRfk>|uOYBlg zrAVfan7X1=JJ$Nhn8Px!DoZM9xAs!QH8hQ>#7n#sNO58|tZc==0upr)OQZ?Qu{2Ds zic6$8%N+npK03-_Yb%e^iRciCD@X$>013;af*VMK^Wn@ZpaP;HA*4*o#8e1(Tei9k zJ(Y}%ymZaiT!gBetGOeKzf?VJ8_dEf%){hOd@{|V$PoV(W6aiIJLDtE(~`vDC@GI< z25>k4aR`wexP^JRg={d19iW1FXog#8hg&$tkc7P7Jk5=pJJnn^)@)7KRL|GkOY;o6 z+O*B9P<Vq227w`)niegov>EN#cCL@v0e)^od;qk?2r_X1D<(xPfe7ge%yGG{DYr zXa?z&1&>GraiD^2Lch193jO2`@-#sAq%HJ>jP*3p6P-r7^Gou>P5Rs;`^3)}H6Rat z2t`y4U2_h3#5bW_wCA8qkhlh7xP(o(glzDHH?W5U-2qXUP;fYdps|NH&`_WN&+w$t zf>60ltVXCW@?W*Ma9z2GgTd6N_LCXHk(wTJB>_r)@K#S5ra=7{M4ExFHt4cY?YT{JqU{|5!R5o z=MYfpNWQi_jx=b8E7*Y>0EaiAf_;dID=3EvEz$&?19ebR0Bp2@*jEodR%A`qYwWhs zLyc!O*n_1?G?*>ED8g&2R*8f%Y}M9@r4|2fHHbL5gznghjL^|3^T>L{yi2%-X2^z3 z@CZc!hh?}0LZt#%7};hZ1PP^{YZ&T+PH;~r4@+9TrCwNtw%i0k^0l(D9-D-fqh^E?A(Vl5KVoh*_w5{u$`X+ zaLuZ)1I0+&$xU0Jg{gvRTTm@4qs2+N_1w8#T9>QZ1Gv+*L{1;=SUfQTBe()%0EcW) z1SXJKGE7`qajh$TJjRuur+D1-q}>1CrQA(5BEKYBo%}`Ouspc^+~u8+&>gL!99Lmf z4)P+<;V{Z*3RWg0)?qc(+0$LoDO--{U9yD=;5Fa#9n*ny6@c5V7S+j_%RJ>}-uXQZ zx}Bq=j9xn`R{#Y=s%62M^;+9?)PI$_Zp(=8t(WkXit&Al$ju1!g#<1Tw&0l5`4v?}*9)eYU0}=oI2q-WFKkx%D@Pd=7QjR!?+x1sNMBp1y zV60%^jd)Evh~OZm+#5N7O-KgJWypqfrmFS0&h6kQc8t&k;X75;JZgy&_O-p;u$r?L z7WM;30Aonl2pHait)&@cgiHS{b<}j6)C108uh`+nc-$}rVj;HUOjTI&*a+e^hru)} zn+Rc9++ZjsWE!?u(d8x_T~!^$Vt>NFj}8K=V(kUz`4#7MX1@RYjFx~==V&;rE z=|Qk+tnSyw4(GIY~QtP*Cgec#_Y7#?8BrEJOabEl*G91ZNsE%p$5>3=BE7x z(A3`39bj!p2gB&X;-*BI{l&dY>;V6`57)^89|jEp(Bv2_UVBWVR>JMp zXi5fbGoFbpNCZe2@7aywfw*lA2V<;8X+)&)m!y};Ch-zI@v|-Nv&|H!z{=!K=s@#0 zS2ou_obvy4G*w#maXzYIoJerATJZmyi7yW0BxjBoknrUsWiGM>^-K#pdh1~6`jsBnW(;Oe4Kg@Wh;QNV3T z*o6$AWK@`gP1r8SmiYL2;6-p;*>GS+@AqnUbglSA86bj3S7ksR_-qXcL@|`hi2-ED zgvyzPRrm$b)B^LddO~^X7mfIxmpVsvIaNo&J@IiIHGAZU-i%OYkPzvQcWphN2Sz)a>XNfcL1TU}$Qhf^0g?-orI=F>X0ESxNhavz3aDawkaEJrYf_caU9k2&g*asa@g<*((hp7H*00(Q> zgeSm$Xn2Ba&;dq(25^A+z^4XM*ad3f2bsSH>--_p_m0Ci(L_%T^|XJ+uiVE6h$I3B z5-ey?;DLk+H|_Jsi3vm|3MW#mXz?P(j2bs`?C9|$$dDpOlC;=Fi;*3Yw5(bs>DQ_l zO)g#PRqfxtU;B*hn6=}l&!0kv5-n=cdzZB+ULGMS?{NmJ32!vVA4Z)|?JnU37qnqv}c9eLC!welqL{EgjZ$ zxGAkW4zNLxsFBLdc=MnzR@yRep0+FW=+dWCuih2SqU_qYbMLO5s`v1Vu!}Em{yh5h z>a!ng?;at=I!hl$lxY1v{`~qUYWa2YR}2BZvC1&U{DRIr!JzZcI?gQhh8?Rkv5Fmv zSvZtZOu4ZihaGzOA&4Q0$dPj;ns_3LD8BXAg)Q#z#wCfl7}y(q$u;AJ85(AoF>=YM z7Zi*+hLk;5ym1aAjAZkVFVuvg86>3aatbMfh{6bMIt&otGnv(!4?*y9gRWJp5B4l&@U zScXo4`YW)(3Og)RfEs%&vdq0zV2!)dc!{$=naY=6H%7ZxUpvxjOpG`N3CR{I9i<2~ zZ-B$kF!mHNn{HO{6NZ$eoC3+bn1zw$TBtDshz^9%G0K>0eg#eux8=4QI4*QS8l1Nj zVVVx8g<*|wds+;Moy#Tb9I+jHToI-pgEXmni+)7%qjqQqDa!vXM~cR!F~g@&G7oZU zpU64u%+XM9h;oTBOYPIpQrEiJ>&{6ly)@HNZTvLU8@usVk3Sk+RE^f|I;~xOv3Rv! zI`-J@wOb?t2^8WQMVLRyw4;L-=8OV}Drzc82QZ|d5@m7kP(ux48KZ@o4x@mRi4J1M zCh(fJty#xzo2=soG*5VW%P{kpgBlpw!1g|1i!Jxp(CxgeaMMT8-WA&|U7y5RrOyI|J-`}04R3qltL(m`T+ zVJX7%5;z^*4P$hcN2luC~A!Di9@G!$2HcAaMXcfkhR!n1kpD z2#MrqEQWs?9b>9^Is~?`i&5F&K|1z843e>oV=SY1!1$gHHiSOE^CBGcgA|(RP%tTs zBOZnK6_0>rgjW2c0cQxl8f8ygg|XfsdxXe3t__I0G9P2mhnMxWuPq5-Vp&3mMT_+b zkj;tW#iWn^Ds4P2YL?aqBXiEQsC`3N~SOy3?Mao@rWsW&yr1F;H zD_#=QV}0z%9u?@xWj<|LKJp>Z3|W|8p3p{%1SVd-2TU(8Mps6xByaqugVlgV3vO7K zIY~i^FchH+WcW%E=%5AvxnX~rlwv2DNfs;k;bNdXT`>bnky$cuMC3t(9S(rdSFW<5 zEjy?x?Lg2lCZuM^%Vh`!s?m~^5Szhd%0@$4sAG~y2hYu2lLQ@nzBf+F63q&E?`7Gv!O1r2vCX`!{jpg z$w@!CV1NaDnn(jWQB!tEJPJ)HLLI7B2)6%nJP?H0SP8Na-(fVYb`^FQJrE)n_$aYO=t9m1Hh<|{%D3L=HQ9VV%8VU@I@!aMia!~ z^m;vI-&l$u5ZSn57{gE#ZD6B=Waxl2Sv1C1=J5nZ5P@Aqm}(~NB*i5v$BJ6z({lVL zoIY&que^-wSgo@jg@R#G3|%XB*K=LD=*Zt?OPW@X796@odbY{;0eQQR}g|!q+{`lSQJ9$kFB}eWpV#QCJGeU$5L~#RZ}k^>wITC3tG@~@P+XbVo1!kyWaLz zux35c3~ogewOzgNdo;}9BxGYC*68pio&b$Zze5M*_{uekpe8NkCe$ag(e4hvpzX350y%V8ab`Jez|&F)Q zY3sb?+b-;wO{#6B6U*C97mH${z0>^O1+t%I@V)Il;CcHZ&sqQaz2^{9e;g5UUbU2l zM_~h2cG= znE11Fd=NJ_OQs?5{k6Q_gJ*f21#Td|@tO4)L4DNE zDO|!bBts@_f*_dE888Mxs8$SRAL$U+jdkDnfnOFi2LMtY`t2YGDTJ+M9vYn0556A; z!Ii801Swp}j!?8@3@7=-C{2U}AtEr}UE_Lx9fYX8(2FV20a%Qkq}mkK z;8}PTb5P;)@E|1a4iV1ILLJ#8M%2j-+x*psBQhb+$q`YM8x*46|8=5YnZ@k&QDJ!s z7OvS!eN8oWAr9HaM|4g0{Ky1qpc)dN8}_0X{30;^q8JRL7Yw5q6r&#`qcScd9{52s zDq|mj0yT((F8~G|{!Tv`0to5hGW^3PWI_tQ#|jRDrBIr2k(yN{;;JzRBa)vfGEXGN zV|xT4MO^=4cp#KQxtu-TjtQLH&21w6y<@PH-V=tRC_-Tq4wFEJ6iHQtnOOwW8A>av znF89BWl2+Hfy91^;fr+Pf9)cIv0*S8V=;=sAfQ4dETc*`BTFvh9pJ%B#-vKlBu%O$ zBFGCV7{VRgffsDS7El33)z2MHSsrpi31)&lWI`QG-#}c$JCNfOT!TLlggO*L64Zep z)Iq_OLmjw+7ARa7B!e5QK-3H(vhvwf}!Lfp7k1 zA3)I-TtR*G6B|q!CtQOybO93(10l4-9-81L2*e!h136ZTh6w~MxB(#ygeus<6HI3k z*n=Qsf(rlwAsA5jVO5DN*IFVb)4Zj8io{)VM?M;v`_<U?A72_9e0sB1}KACg<>LBo5fj{B^zBt=3v;!58cp5f+QObBTc@fA20$kbjB(S0wbgX z9z0_zFhYpJ<}WCtZLWeMz@{I7sEsCLO5Wy&-ex46!Y)+FPTm1<4ykX#fp0?586^LN z7fjhcKm>6@1UpjXm%KKjbKFD&tL332*i$kq+x`?qotB0u+V8lXA)%$b&Wfjy;6nJ48a; zFvRqwLlU@wRVG0uNR$?Y<312VcY>QhNRL;o=~_TuLprL+$f-QWWmV)Ud%*vUCC()p z^y3k>(SLFxyLLzk6>5HV`7F_@}q1_O(x!YbH8Dj>rhyl67M=r6qHETm>1h(a#FLNQPS(eT4QXska_1B@nP z9@OZs=42lTE3ppkZ!!iV29LvjAYalXMa6hN(GsbV`X)FW131h< zb25P|fI~JwEjTd26^MgBh(k8`!#wcAHBdnwy23te!X~(#K;XhPjDtXc!!4x46SRjp z9!uJqh{&~v;{M9pMq=DbhrBLA-PY}pysC85pOf{Qf4CbjU zC;%TO<1&-uR?`;JqDHPwwJ3!zc)~7%>P)&Sh$bT}+$`;CY%(MRs@lRZWJ90v!!INV zsrErIzyeA}0?d}`E!e`XW&_9mjRhnmVv0}o34LLxruNB!C_8dM6A ztrg83p+6jepZ;eWcZFam1OW%E&lN7gt``IEvCd@zG*nwy1Rf(i@bpyA1Vht>NG|qN z4War2#e$v1)}*V_WH!75?JhB@`hg<+!ZnyfFsws0Ji|PA12XtSHB_2$JGk8NWM8Y80f+Mu%AiU;l_HvD8=11>l&;n;?4DkqWZXaku zGY@GVFa~K7bszL>&mQ%Vg2K$6LLrilAF#o)Vw4{8VHh*e7_;dVjocp+)IfuXI$IvT zwy_)6@BP}X?AQT2`xp}XFQH%Zu!BX=sDCGa@E?~x*I?s@IxJZ1tY9O5dcCtP`De| zgBy$ngX@68p;(2tMT9OOqAtbZ)&)dMbYM`y7I;C>%IrUsDrn<$iDxEA_wejy!)#)- zjMr$dck*ZFG_dOKjYn~*`h)DE_GPGe&ML7EYl1lF>N`~XJ6I_x_>FJELOUe0KiESb zh=U>Q!lKd3o=}4!%t4Wi0z`N@AvpgpArJ#Z5JPlkf;=RFq$NRiUdo%Rt6Cg{aAc|F zJ-T%OnVzFJLd-99ys@3)=PS*#k6DyG^DV(s2Yx5IeuLs5pHQzbYQ^u84rD@^e8m&Y zgBGZQH4L^rFhb{S0$9)jG>rOMNb1J(#i{d%!&-KSTe5{vffw|quy)4HdTgx&d(r3m zPw#fo*JgLw zhruVr!OI#9Xpk%^)O0X>c+~%`!_!Xg*s+umdVM#3K34>YC!633XsT1#UUj_alM+}U zGFTKrJ8W7qh}z*Kb|Zg9-N^h|F!W?`{0%wV_Efgcv-)26e2^x;^4~$Jk}A=6@QHu2 zu7@%a!@?-{YK&)pGDbbn4#I6yy>BWta*IDx59x4IL)UL^*PqS(>_Z~>K{CUFI`~2# zP{TM-1308Ta8iSE_W?kl>eI*2u0)XDk%F}FT{bpXm~7(5gbAZH6PXa}LX6X>ef~CO zN-~mUNs}bIEVQD7WlNVWPnukKCT2~WH*qF8u#;y`pFe>H6*`n?QKLtZCRMtWX;Y^> zM;_3blWJ9~SFys-8WsP|)1!;Ph7~)OY+18s(WX@^7L1G}XkcKiy2+ov0~GP*)w`E3 zUax-v2Npb-aN)o^cKp0l*WV?>e|KEEg!s)HV~mX<*1VZ>XV0HOYhLUxQ>MqKQKweD znsw`=FLh+P*7C_bGOnN%Y1uB*6L6VY(t-w?cyZ&$ktbJv+|96m#@_4w9_`u6=qf<|WoZ(WCI`x9AaN3* zW+8EQQHT^zfVtv;PM8>ni37~ch9Y*D;DnQ9{s~DCs#1ca3*C&PYN0UX>XRzh01Z^o zK@0QK&_fYTLaVrR>WZ+nAdOVgNzY33raJ0crmsyo&5O`aK@C+@pAb`wvB^f|sWP6n z^JhHrV1;$G(o(I})?0BUthh}4c|x~3?9qXcb)I0Ui+Sn*Bb!=SDq@&nmWx)}X{l|g zIq`UkRa?-o(+)aVzoX0;V=j3$R`c9TSKase<0nT0BcY}k0SS!6!FwCLH$nUqgwR1T z#DGFzD1iTf0*+?>Y3vOnI^By0Dt@>E2_)F?0uDbSJd(zZH?|Ryfg;JqziePRWg$p* zk++yg=7~g;C;0&;n^5|g2fjW)u~M9Y>?vj+oCN}g8gVi_rx+m2lypmf?v?YZeDX{)szeTve( z`R;oxH0myiv4#of>+Qo4ce_;S5OXZm>#}2vRm`@ne7adpOI-8KH75=*d5JuJ+ zMF(exDWs5OhIzs_Xf`Qi6LZ|C*7n&$JuTyU2XSG;Yh*usnS)@}Zd zkl+9D$G_>Rd0t-$^W9hb?DZAH3n+vLUwk3vKo~lP35WO!942nR{VRT8f(k0mIAeK^ z@$bXqkon0b5=0JivP8saV^5+|{t$>F{2>An2RIodb^?itLF7zB$=cTBWRf#1BvEw| zTj12jIT4OfHF1*)2vK;byESSleskdqA!UaYCZjG>E8Gn!LP8zx5H+5;&Q8ijsOxmA zRg-g-?~vFT%<+(kO*~C3n*ZvAkje%rjTw<^yM#yV!{*hl9*Ll;Q{hC6c{d(nPNeM2~bEEe{kY1IJ_Y+v6;=D zP{%QKaU7_I7`eLeBr|iI;}W%*PIVrDT1c^7*^J`?7o-4iK##wXp7qp$?s(TbbMA9G z-wDsRw3Wv_?lBwD`{N(8@eg;|>yQZIUcc}YFz`KceC6YZ!uIlpWh}!V%{YcHj-d&W zDq>>mqo6hMa)vkDPewVT#x54(2U9{K5r$A;D{-_BlI2JfH^nIe8Th~l&eAAZ%ZO0Nl3u_jJiqiKw-!fBTS1dpGV zL+4oG+PT{i#h!JwYd!Hvsx#rdskgEwsV7JK5D+2<3DE;d zl%f>1D0KAl210DD8O@jj{M1KFC4`XkRZiBlF>CkZBVIG?PXk{t2yURHzv?*)K;_z7C!T-&-H>wy_WmyxP}-1(DM{_ zpaqrQ$f$ve#SSE0eH_sB@&zz~RkpI1eM4R}x(ttgHex@Z!V5OZD3b^x6Pq9{KTb=C z3*T_FDCPtqs1OD=2-T(>L&ZGAQH(xhqZsX=*+4XrV{`N&679$_kLm)*100wi;s_)t z`~jdo>`avJFa$7?1l-^fH7I_7gdx`ICgdvDDqtG~bwLPUHQx%&XkOG#7J-KB&RH#J za7*AYHO^{+w^M6Y=RUfDh6)Ve2B%P~I|TiJJBVW^^5Df31^|Ln{DU>!xsEsUTPw%x zH;J?I^QTp#oSndio%S{Lsj1bRVeIZFoOX3nju%kn5thJ){SV0^u^w9g^ASFem8>Es zO5sOZ)E~=O@f+UM(K&Esq@fM~hv1gZq;s2?tyM*u!oHKQOCV&UzMp zc!9QDh*AdI6rP%_%Q@Td0XZ1S$;yjynJY76Att$#negK2T#2!01CCr^ln| z!Qub|nbMGVrU`27_(}7?*&sspc~t08MhFkCa3d(ep@=!T5|0VR`SfvKQl0oju}M;d zpJt($fG2S_xmJk~%^LEg0e*Z2Q?MGXL5q9?kp08j1fz>d=@V_c5Nuae^I1nlhw zNuf$4XCX%nI{;&9|!YE8A3=;(@swxSb@A>*h#OlVYsIU4sWejzQNB&_S zVxa+E>->=JAF$#3-0ur`MEx#+-bN)c=!oe~MRD|R|2)kOp-Tr!jh%+V>I9I~GSL7z z@r)2K0o!T;#c47e@F>D#t!xK2L?ue~1w#^sjfDm|~ z3H}aI1jEE?$c8#)3+4b19!N_d0TFg#Aj*wraAXkwentnA&>jpymG*&22qI^8a2^bS z1`WYTny?RuL>!)H3123GWQ2hdZXpa|@sPqz;3OpW1P!N356;c(JGe0ZdT~3 z+z?U#2ZT1^BdBQ(>98;Kk%at#8*D%g-a#Hr;pTWG9zGxu>VX52<{$LI5-xzzZiSBc zPhr~TGb)1=ACWUoGIJhMtSGT4jzcI~qSS8k>N;^JZ%23B2q^YS6kEj~01Am75Ie|) z>_S7JV9`A&@D*WE7FBXIZqe>8sxF#g7~X&cp5Oq;CT$F3+UP=Rx{XsR<{x%p7fi+; zPGJ{{0TId#6^a2Bc1A7>F5M~*6#9T2PyrnO27)i!E%NAc(fR-tfPwPTZ4lr98})J= zpN9%<3xIA968wP6ih>gqVIdg7_x@1~V=}rd1u6WoGfyHQal*RVupq|*??51KuH57U%wO#c{-ri0VQq!|o+zbA(<3 zCkGJgsg3s*MmTq2P!R4D!Hi^ zZ!s5#!42FXn2LZORl~#-(il0#2o~@591oRxi#P*(EYT9LbW4lF zCb#oTkAn!RpbYk)462|CT;dZ!F^QU#JWmCVkm8>XAQe^d?fA!CVBtO8vngY77Rzc! zcqBjfQz`nh33&9N$@W4S^$z@GgXHX!=ObBalxEiu`(!c9_B z=_B|d7kU8|U?CX#fDtxTMr;;IR$&kr0U6XI6(}wk6yatE;tGQcR(rw=79uEWNkeZ{ z`Ra9qV!{mNW?9VwnUbkQi*>q`Vs5qq21L{jnyIU%uP3CHFT5*iZN(xRKo*k07?J_! zbdKkI4*vE58#sXI&;b4af!6_6C$v|+d9Vb$|o&O<&6>#!^qu@;I?H#UyC zB|i-#WQ8?Uh;f=sc2iyu1`(k_S@!cp=Az^w81}&%ssS2qp;Ci^5e6a^7$JJmBNZ+| zGl`b42tvzV^&w`JD4Leco;Gk87jcg7D=0-oyS7(76ZrxM2A~Nwt(H<)GY-qvY|l2c z)Zu(b4K~;s6XXYdg+; zp|&5JDp^@HErK-;yXzNq4y4)AvcsBFBRR4;R}hsGs2F&?ppH*w zWgV0e6k#BcffnMUE}j7$oWUCeBo&5Mdix+1BB2@W8GrB@D4@Vm!R#*pntTNsEK9mI zaH1&xo^KQgIhcAv7`rwM*N{bLD1Tq`qI2l3foWkS17RP7Jg@_Z$O@G~Sd|sKaZ@_8 zm*ZM+K@wg%rem6>`2Y=Qc$Z@un14s4d3Y#_*_f*%d6uWB*@YkIMc07(sH=mTm3pbC zrKxX4in+OPf>&h|fq3yJ6>gS|Q^6KsVI6+K9;|_8J9Qw~xKmYit!bpKf8q-2cnbq# zt~s-=8~U;h10a1OqQ^pzUnm`%2@Swtp-0nDMRP-wRr;n0C=eT?$=iwEz)dBCqk9O1 zcjBy^Zks5ZTP%CO2Su~#3k`H3A3nhp79k1f%O~HU31k?wHC(1^nzUsa44wd|$THPwqe14WSc#zn%E9v?)AQlMGyM~~lb%!!JP)7=HoVkBo5MZ4hCy7!eMoS3 zS}1(Df?2o4*~6J>9k;1Nw`sh_>B+Zk1-M_VaG-zteTg{jPkyR<>Ek`=Vlsy%~phoMptzz6?j^Kos=*tsls{4P)DVLd>{E z-~rp>h2kbm)FjU0+?nYU-XScsK^wwC8OWjC*+Ch=;uYqh6+{#luAwXcQ-kZ%CePGr z&=07))^LfWn0e zcR1W};ElkE#@@WS^oF6vjT}3A{MZrV#7iJcnmp<863K>dj2S!s;P1`DnKWzKyos~s zrHPqP`uqtrsL-KAed;)%BdOA*Oq)7=3N@<1V8r68 zby2LTZifAC+J57Va{xd8 z-1A5SirhktKtBdKho47Kv!B-l|z@q&n1^Yp}U#XRuM( z2Ion;`LoP#HV(H18-6UO93qM2L0z@cSqF)XR~WMY+%9AObHFmmaze;sL=lJEdFf>$ z2#fB%3$J{|&P%UP^lda?gAE>_Z@&~mNZ>viZYW_O@(lc-hsqoyB7-Cf6>r26$LpeR zA1#Y<#=+IgamQ|wsZgT=9UzY>El~4MqcGLO0wf~)lQPH})x?;W9?!g{KQ?>Zl9*%u z9MP^qE0%McHy@3(M#3)5^qsooxfL^HnLsF0Nqmx)qP8U!C|YXi;6^5Hp^DNDO-zb* zrM5gXST$@D*0v*_>h%O-Lqo(-&&FUhb7WL(;RR{9dKO7G@A$(Hto&p{jje;@s_U+; zy#{B~mN!Lg(g)PRn{VW5%!U`xMvF*g)m3f?JsG&H1h;fYjC}U{6SQ;J{bU)WJ9^$n>c%V~7;UxCn6xPMjl?#7tWKNIlEk49e7rBJbB-kYjs#8roDW*Gx zBFA`AC4}HeN)4SNL#=oP4Kiq9Q@~L}8R{YlL|{r0&|n9s(W4b80EsJv=#U#^<7`LV z%Oq0qwraGEZK;sNr24{#De~d}3255LsU8WL#BdRfggf6DU;2+RW&;+6fDTJ96S+2u z>5Xudr#v&4G|u%VS>egp6`ZBV<{09S!FiS;m_W$n7?MWpOXQfAQPdmha$|2I1Sg2$ zk7TgRmSj!QJI@Lrc`*c(Yy~AQWYpBZSplIBi0&a-MTc zDP5;JG1%DHD#WL9EJP-BzzBBOun=0f1~i7D13;*P7W2r2ZQY=XVSs}XI>>}Ik}-@! zO{kzwDTFG-~%+00S##Ip%B)9MlU2KiAhMp5tedWH99&ek%IJ7B#n$ou}C(E=44fZ zyXj{Phq#xDk#V)cj7`y~MmDDDA_CzluxJZod(ts!c2t(en)R&F9p?&wgajVAr5rqL zftQKIDia97gsgH^Baxh!SHUXQ-vxHc@R9BOHW{Gj@pa2w?sAu}Lgg^ar#BYcs$rM4 z40Kv~&HT~d$oQuQe&}Md_4_~~jHEI+Psu0U)W|oBx26MJ0<|4eZ8}|x=pDe8&6$j` z9E&gx9SlPq&DBExEt2w@IH=+Ykp{#j+)z&)tiuJNW(Nwj@(JoPWgJD&LNbyfkM6ob z2Y5muGq9GAPrM)o>D@S8;+?F}dU$n_JXYY7k zLkG|xL~nKfP=^460}z@9Lp_gsi=@=k8cDguR$zc@t`MkdNnv#tZmWZI7nGU89&(I@r(6lwoL3Pk)=h9c z%twdQd=%ozj0=DG#NYVt$>;Hs#9m`*j$rSf?-O~n;u5!L#UCttfP4I*0ic-X1>PZj z>RTWCLjn3~_qMY);l$@TuNP|uO>{&X9r~t6y&OlOh1+K096D$Rrm4PZk#<~{rUQ|- zbUI-F3{pcDFpva`Kwi2K3nt(vtVRZ^Kx?t44~N1GZ-)ZAW(WGj12HfU>Q#4lH*Ce0 z4Kk4ivakdD#cY$140mA-cadP$)_B|27mpWGgtidlMs7HJ; zm1BQRC}VZxaqW{a#^F@3w|wdY90Qj@xAzaZcYISue>p-Q!M9}(^la03aU5bl5m6)*r>Kn?t$hkWRVFmV9VKos3n zhY^H+>X#GjH%{|HH1Q{Y?SzL~;)L<^1km6HE|3kkl?_?|2)B?4n)U?qfQp}%bp@#Z z1LxodZjcQMxCki(A%$8cKV0aAY)Dp}I3CB7R>y--U1o-92$N{Ih9-$3gLMF2)d|S*8-?YO zHqv~^5*{cilnaqEj7XGZGBSuGGh`Ao2M}66kwEAqiGRi;H(`l*^Cf2@6PmdHiEJ{I z{DG121PDn12qE+Yyj28%@B~^=1a;sBYxxAD7+f|42wiXsWAO>PsFyO}0$sxu(y$fr zKo43G5Bb0Z%Xk3JxDnEL0QJQP4siuHa0U7G22_v+s&NJ~K?paXnS786g%B7CRtk<_ zgYCF&k0(W!7!f{5C75>^9Tp6VP#M2K8if!Hsc;AScp0BL2(+1-!EgtckPEqhn-Ce1 zLZgKB5|+zpPsLMXA=#7BIUJlIF27MOn8by>vmP{AOJ4~TSf-K(U;+!#l4Tf^=LwTn z0S4SjA7u7%l=mBNc$3m8BX6(_NG2TKsh=8gb2?HJt0k3=VtK{#5I(p6l~uVb@W++w zG=KZ~6U=FU_v92XFb__k1@hno`m~pNnFKI^Lx&=mAQ%H6F&2R!c{E`J;0A6Ev7!$_ zQ43a@rg?)o2t{@g1B%I-t$7ncxEZ6-2fnEY$iN7=SqQdp8H(@=ci@{p+C@cb2F8hm zT1k-{1EI@_NyoyG^eLU3kdw`%5R1j7xHCWTsh#X;Ne=oE_tFvLc>v|9AX@g4=qaaZ zIFsC&d?mp?i1bTZ3Y{W}rhn?64-tt|NsslCGlLeWccT(Hv6TxN8EcXWMgyoIQKb-C z1bZ2>@gHu%UYi18%@w$H)w0PzjuHjPKbIMxcNudN*$nqcYn6j;INFO>im$dU-a% zVW$Bdt01J8u?mAQq=NvO21%RxhzzTs2&2K9LKvm1!D6MSoRxZ!@3b4eVPjevoxQ|J zFwsmp8K&_=rs`p)l{BfyGjUmV5^h=`aXP2%nx1H|o@`h#i)9kTk*C%9Idgce`B|?0 z+8?|E6Jz2Mwn{uX^RM!!pgV98K0`r{`lxIosrqrLFdzdZ!dTL}oR`|Ed$|=Gy9R3j zR{n4d3OEKnkON4N16n~3Ba?m#@dCKUs*>Xpuu8LY15$R-3yxB#2LOcThAVxb2#$aZ zW>BPe&0!+p8ND+9Z&Zr0PAFT?iLE_JrXv%u zBGauzRXplKN#iO$e|oOr85HX3u5;_IbsAW>M7H%xRp+s%XV#~F>aT%|8xHXjF7ZfI zsX5QupO46udjp^_(WnkfG!UB~8r!KBOH5shk(Rr$dpQ<+39`g+KF4qjZQujA_6a$# z5DEwcng9$i@n<_=1aX&ZyXLG5n@(U*v#{D1WMC<_paqKQ5k32mk7EYEfTY2I48af# z&Oi;Qpa_F-3&5GA&_SD)QM5OOwOKo*T&uaL7jYZO2?H0lXI51}6R^G{rt>2Z%_OdD z+qPc`o=H#?Nnir)A-8m^zvxLKfHe`QDu*?4uYJ4!EPo5Qf{VaJ5xH2o5Qv*J2D`JO z6@NVwpbaazis2G4BUVIF1Qgr3o{CA|D^F-gmZP8)Pq19czzKS34lB$E$*>9O@UgqW z2^n|~xWEZzG!doi13jDrW1zCCdjK;)vPb{~tqTl|@^d>710UEGFOV3xJ0|cK1G_7u zlHj|8(J5dsqCZFzJUTel`=g=&4EA6T-cSwdunyJW5803l{wT&vx~yKby;1BlE>?dc zY;W`jw&lBg+R9o8cfd%~OGXx-4hO%&gOX|rG4FA|z-I^hE6H-&zsUC@C=q)DY@IWb zuiBBopPU;&=fDrFNDOQenrIOK8lVe&!Bx`#7{H(jFw-cJ>Jyy%!5az#n2U6JEKkGW zC&O?Hg#cdA00V1K2fCOJx;PA8B?E+@i)-Ktx)=eO5Dobt5BI=G$8Z2W%*{QVp@CyV@q{q6C3W+Oggq+>$y}S%#C@H?=>&LtV z$n8^b1vkj`f=G%Ll!EM4X|}eBJTZ63$U*V8?6DARY6oOE$v-W8l`JuLdJ-OazMg}h zOklt(4a!YjHt{HEElbKHW6J*=e=0Hm&l1$iHId4|01Rw!#7Df&G2;)k>=Cwn%blys zHv`f>#dX7=1uk$6qaXvfpqC)K1~RY)oUqq=NeJZd%$y((+~p4UkPX=o&fV+-3gH85 zuoa1Yx>_*?NU#uL4Fu}U5AW~}a%TjooYfP=$`p0al%mfarGwpetCC@E0_{b9z+Xq&A8gGo73u5bsOV zHGOpROTR+_o+SYWJ`L2}ZE<#sBIc8~dMmbWcD9{ddrqz1I5!iNC)G!zxIAms7i?$} zl(3T9GhPkWmTlRZ;AURA5FMQV)&q{qN%Pxsv~=oFvCIs*I4lF!AOlX&3cAPxYmg4d zkPJF}5BY!&(a;8n-OU=2vRaYYKa6Us%ior*&Rg-50je`MA=;yjM7i(`wosZPRRzLp zk3MUJ=@w!yl@07>D<`HItbK$MDW$FvvC(?q@l>wDJ=`6cg~ivh%1BD-t^B&)bq*ALHp)nIs4}q-Tdf%N zEfB0c!7icSDQ@Vl``@my2?WmQmuuin-ZVvU4KmOUy2#)%zyx|Z4}>5O^I#AAzzA!g z4N@`@`)~}c&|S=s1C?O^x{JLLl3LjIaY{y4gg6UoWekRC?~Jkn7vwoI)bR$gX9@nqU5WnLaH zR`z>Dk?ttLrU%f|X%6q7^e*n1JM`J&5~M$AMz40x@9eFb2e3C8bf|tVIXiLRiI(4A zjq3~Fx_I_8oUrJPF7a#KG1y)wmOJUokm=;G!Yl0HYXI1KO$g~QM*35_;LyX?oDV)A z3uEvRTjBECJmR_l*)wqK{7uAKu?Cos#76Qn6`>fxzIZfl;~#a}S}+q}EQE&BOtSKM zL>_w7eiPR2F&5wdLF*0W+AKeo4in)8=~J3o*ZHfA-<2lKAmg zaO)8ktA_Dz_X&aq?n2Z>O`mWcK}NP@{Vw>YoO5D=ei3Y_BSG*9dhizX%51RT48QQ= zTnP?O3_1KFc`fmbPVpaY^-qD;lP&`nz6PBj1M;AYoRAL05W0*MQ~$6Jz993*(8E%r z58?m^ACUuNA?q^#*orOAmOTTw#tCg8)?*#$tD(DAYzIVN?06xoeQ~4rDD56rIJ;0Q z)qk~H(4uH!PSASopWifszwKJDulRa9Md9^`KNMVE?qvTiNb~ktRv#-#zsY0WY8Cfq zuMvv?5IS`K#aguJz(E)X4=zGe(BVUf5hYHfSkdA|j2R=^Nz&2dN01;l`SZ6-;YpM! znXF{l(&bB-Etip`Npsnomnn7b{+I7jQs<~h7Az7aplgX>%;EdO2_#9BiV^lr+xeUagtHk z@L|M>6&Hq)@M=;WktI*2T-owv%$YTBrd(w4XTxif@gup9-|1s*?yk1WEMLAgIeO;! z^qNRH-CYp$?t<^Y7fd zcD8}i-~LV{Sdse7cVFLrdM{Maf>ld$n48BQ<7_|z3pDV+$^ukyK?Z%= zWTe43iD^O#E41)JCjKIcw30aaix8nWA?cdAD~BhYkd3GR z9GrNPHy>ifm9@OuSmQN%j-xBN

    4qiSCkx&W>E3u|*O-_E1(jH2C0-4o3>PZ(H{w zk*ITPI#bHu)#Jdb!{0sZS!5YlVl?8BvRB;JAk$SF%%iY zE`^4m)T|r;a;E zTBie$aL2U|zHen8H$STT^G98y50LwJ;4kZa_!8^bB=2Q70lH`A^<`M;ngZr9`DOn3 zheV=J>^GTA1i|@x@WGciNFOuS7|4#%SO3S6g$xiUPB$-UO}<9#X{rNosYg#GT|W zuzC$|j+l>VT#g@@V+|7>H$u34E_B8so$Bl`iDo@Zb=`5DBe3NNK-jK6-a1e0)L5T# zohx0L0MPJkc*nRsP>+wXSA-7uM-25#ArtgRzzRsb6Q#&u;bUYYYZRv-k?&(hvREXS zM5IZ!2xIQ!Q4&mcvRKHVWinXAC+JtdCK2Q$Eqhs&t^`0>#*!lvBcM?LNg)YgXpg(( zWiN;FltDtpf*33j)uyr)4<-|897NYztcOKKHOhq3^Z}&!fi{1X&1`>3RiC)c zkK^P_5n%958Hk1-#NbDzQpgW`h~pSO_?unE&c%_Fa~jCLl$Gmhd#(r z4B1pd9N>V%KdF(8V=!?ytg1vfUQ>^K{DX?UktlA2H9}2rXe!Q`7PFp_i`0!#I%H^F zOUvj8aj~&Iv~%Md-4n+`>5g}HBxg?%x`EIzRaw59|N{flK?x%8!o zZ31maIVw`m6jZW&m2?&6HmIwJNEI8djP8#tpb~FDCf10a*YikCCMaG8XacY zA{XXW>2%KM()Y5ITd)ueKVXp_nVQF@_ra;4bXrHAqE^6|iI-pv9F#udtFK38SYex* zyaN#PfhRHv_q;b%3`ccAAiHFY%(p&Ddibj$#?e|&>682&V18^(rI%3Bn1fi!t~18S z#Kc4r3IAllE&0n|5By^wSB$U~{8Lj7GL;NIb_a}Aa+4)XStwK1vRsqqX02Q~YhH6O z+6=8=IH9)D9;UP?8E~1+`AyMS>b0DRtv`OK+=kl!lN!18&?U0b33hP871@kK);3hTxI7V#Wf!u-$#(Kb_rfw#;tMH0f6TNswHQ37slZvsu(Rpv{ zB;it)x{eXE%f>tScAAGqV!zw+!WQ&%u1gShrvWZ=uOky=VEe>)BS~H^cl^id@kN0v z+1VlY$ZSrS1gaUPw)otH)g>LpML~&QTgTcYp}ee=rzC4!b<(mV$e70KE{FgnmN%!` z^4LsRM!tf5?_K7YUSCm&zKhc2t}q$kR(o=k4PM!3URmM25nE@s3|dNY!pmR|Gh@i? z>jC4CZR+#~G5)*^*#>5#_LRjwno(y?+(H)rqsX%>#*uPy0Qvxy+sA9xAdfb{fmM_} zjhpLnQGoq}(7Q2V=;VkLr6QrOp% zQ+~n(PYR{Ef6~f=to1ebX(n8=1NaEo$cxPlXx z;DkMfA&Yt3!Y|afha%Vyj*oq>vLjI_rtnnNzioGbC zBHSB8N3k5;%O>7C8!!7k;L|`nYMUHVCt?_b13*660;0+p10>i7;Npbex`gPfvrce@ zPM8N*kcC^AK7R1NgYX4JL#}B5NR55ai-Tjoc%UNhlD{fq9D2~i-cUNaU;|*d1!r*t zFdzf#@V`k=om8_rM;O2Y6u3LR{MtsOd)D025*_bJ1{#7^bZW|9XAxdCOpQI z7^)6g9uV|9Wn;!OsS1P9BPKYB1_Qhn%*Mlu!LXtvZiGReV6lR*iXD87%A*myO1D=E zLM*YdF)_jeG6vEpwz*>hf7lmf%ttuMgsos8eyc()9E;WqNVPBqU=Sfi8LyB6LtNws z?jl2o%(9+CL*4_7HT=ECC`KD?ieV9WYu)|3NxslVuY#0Y{00&OE23fd-Wtazc zcsW9ZP@H2oCsKwETdq@XYDRJ;!VOO{d_z*oc;taC*(8cRnA1Fl04`pU&!lqvckJ7DxLU85rh(#Q?e zN4u;S0x~wxYbw3m7eaV}1274`W1wqf5p6uoZM>1hB#LeG3CUwCg6P4aKm(M~g`L2e zbc`8xvZ88tL%Hlk zx$UeoAHWq`X}^a5OuvJ>l~)%kSI|-N# zT_6lSQpkvm)-*kT^a?6Gh}kTZTtg-$yG?|=tlu~ZGu(?xupEU5PKfkUeyD^>KpQRt zE#v$$jI_|;Ij7>A!!Za+kXwc_oy0D^3n3Z>?A%W6>{IXTPCunSqzlhnX&lS>Iw*rb zn|l>bbjl_FLeEzL8|9*`)Buiyu*$2f&-y$?{p>$ab437+MX~hCL$Cw*8iZoN#aNRy zUo5){giB%6BR0h&B(2pC{3E-&mt$iXzL*{n-J`-hQDODQbF?I-XiOTNyq4)UQ)00w zLA;bn2^ItcAY8X}d>9BZ2_O|ss0f(oxgKcDiCP`kp_q&%WzyH&0m6!`D6JaC%0hxW zlq-d%1DFAnpr?Z%)0wM;1JGCM1k*7To4_DbGcC?;qPWpY&RKmIHyDOt=(srL0Yb18 zI+d-B5~4lrPCorp?%Y^EMFR7)93RjPOi&FneJ4zOjqkD|N6n2UDxpbzzlZdi1E2#? zv(HWctxv4912X8p{cAd_3(El&K$j9#Y&j!;poZFM)%A!_KtZev+@po9p#meo=q6mVfDdoB-Wx>OqAF`h4`dc5VvwfB~>~Ja(faV(Z+PF zR#+OKy-JFsBBY6W10b>;FoHL*lw+vVN#rh!?btxoU61YE>2rl! zAO>)lBGqVvp^J@28M*km4ak91u#u?mS`Fng&yiydJK))z#ZUWmDM0Yl>>$9QHMQ3N z2}|%LP)Ar=rlr8#nb2XZP}cn&!;N1JJouK=zkoY~} zi=&KlRovlW3c~(ow)lHL-fYMQZ}kW4lZ7r# zN^+Pd+Y*OXX#;kU1>!gca(JA42nT9t1Ka>8S&+XRFr1^4Uf$HGnN=dYV1k(cu>-8M zPe};C)&T_lbGrT`P*HtF_-dV07|T^lUvha>Sf$Vgf?~NrVN}Lim$2V(ZN`;&1B6+s zrRm=X3f2t1<&a=ZWaSC^iQ9v~+ns2o38vr%&WA<7@Ad2I|X% zP0%xNK;xjJtmx}wPQZj5U`lx?X>oWi)yRf17=wA@gr7U<960H4K(5sP$bpnruHJ~B z^;9m?pwvX(i7U8XP%~9mq-5^Zzo)|v@y%pVbwxVZy7YD0*JIyZ5@@)wX01Me`CT3n z*;-e|rGSy;5ecekBwJ)o>lEGPow&h-_@o7Xyn}G7yESG{dXlsb3D4|^MF0aVL4#`r zlUh=W1rt(gCfuzy+{{>EqWOx^uYhVXgNCuQt2VA&@gUg0}aD|u)Pv^1~dZ-7xn1>wy*as{thB2s>n!5+P zh$wlmxnq!pR&lP?C~076vqGv~eD#SgFlwtqYBWj({%#$g#STffx?IS*0Cj{OQ)=!wzehXfUM;Oq^&oz@o4NSdk0M>kRG*wmpfpQixub0mrMn zbfiJNmVr+yD-xFxzKw_hq6w?mF}tfr=9%!q-HdFWm$3+E=nFzr3s(8zT;zw)7DLi5AxIfm()A0~PD9p45jWeNOvr@yCFt8GvLsK7{^)Io_6LL% z?oOBrJJ(o1_1$*x5Lal1Td;?d1P5GThg-mfVd#Z&NQNl?0|)675u{^>#mR?wh=%kY zgLkkeO!x=LS?_wl4fo~;l}(4+dahk*gI0Krc#sE@u6oKamxj->R7#M2oDt?Uv`Cn-u zzR|P=3Z6!*8=O&TeUW00+azGTz}9wy4l#w5fKV*s%}AM`o{8&S300Ig4-> zCdpRvK-lq(+lTV@0d@#aNsk9b%K?8Nxpx?YKnR9lUPxN_J(x zcf`lbd#QJ5-xp~Fs+9oo5>#NntZ@RzXw*7f7JI3~ zHLn(~O`ST~OW3TEj~whu=A#!bhmU(4j)MY*m9BckWxX zht#5_<4CU~KzIHE4lFpZ7b-grBTlSX@taG={0(!%bu#73mM>$btYb6h&YnMm4lQ~# z>C&ckWKOMmHS5-{U&D?qdp2##n>P9X^T&x3lit360}n2IIPv1f-yGmnd%0@gyO;Uf zlu1yM>ejDg&#rwt_wL@mgAXs>`l5X1t$#BAX?*tb=S`%~x1K%y`u6W*PnKIbZQ^!j z{h~#0S_G)YDv~fE$tqg>Ct!f12>9DCzw|Z>8B9c29CI6T*rA6Xg1FUbn`M$)ZkK?# zn2L%SW6T?GsCWsCE7Dk_jW;s(7%*%A0fZ+10Lc_6Km^fak3P&m*;Pw2dDUf2GTDYw zOi{@ckXK>}(3n;mxlSUn39vqUI~BwEap@^4&IxOIlc$(**@YmcmPi6?S6vD`Zd zG`HP&zM&%-?cY^k{Bo16LO znr(XS4~jRCUiu9ynr=E`FAg-RiI5>0d+h%(D&vcH)0nqE%~X1+CTxVEh$8%fTD%< zMo{@ECC@X?R9Vd=Ea?(dAhTRSUU0|*z3gQ`vETs@`6>jzQc;S6!6kwNlM7r@fv~(N zEG-ZljKuDyJ3q1i?KK=5Aqh*^nGm8dg(_TOWj3LoWpLsRE}J0@S@s6y@MkLwvV#_~ zvcs$O@Blm9%GJm~L>_vG5T)`*GN$9SCqj{DMiUy*+>?)-Da`~{j3O7in1oFnAU9Go zPSt?pH71me36qe79fDzt1Np`dt3YFKeldvyVNF9U+#?_PxG^^*3U0K)-P|BWNZjSk z7{I_(-}xt075C%87qK2Zn?|&My=+3mz)SYivA#9a_4IRb*ur2hwR)V)_d^glIR4!kHI~ zYSillZ4uS+8Gd3Bw55LYs8YpG9ZV#)*{H0HajaSz<*0>Vz*K8st7C<}R@1Wu=c8&} ztA|GTHqpffmvgI|TqpJ-WAKBKjofP+BF9NZ@ne!%fl@e2$vI6{;;)|MWR_sFCxB!J5H|R|Mk?UgJuDa(XpM`0y7(l&}zi3Nir`b*dWPnN!UJgX&CiY4(}o zd_qjL4WsxwRy{ykUz63dNn#f3_y;F`K?tj@Vx$4$8d-q@N8;=^$U@f42mz@mxU$Bx zbLFg(|5cPX(e5?MTuIa9swCLPb&0r<6%$RC(n-czIVLpG+$gtvmC5c^6Tmn!W?9+f zH{;E9P;R6mj3=tperi{vu!u5TD+`Oj7E9y6MK5kqirnVbnuS=y@RVne-_LhBE2^uiYC z?F+xk+ph?|Wno@mFGM{E--^oDzRIrekelsn7Me_?0G@WsPI{%>7;GQU@WwDUF^V@3 zg2D$_uvY#vZU}23h$B-Xbec$=6vI0_?h$cPKWv{YCha`&-Zyqmmcy*HxH&KOje?i} z{~dq46Q#Mx1u-N9wpHl#7h3zx8G-!lizmB;Zw)49;Ouck>MhEROj2d249dW2rAd@L z0Hw{$q%QxBDPFEpnaA9uDFxQdgA=)t9!aS=sM5_JA3A9Lq1U~7!5{=VZEA1fispgi zZ?D2dEB>qvT*yKhx4;E-ved*d`p`EC z<+j1PZGgium}?$V```+{xC#KZvWlS4BM=ZCLqBEh_&h{{8nL|+H6js;JmBFh{lW|9 ze_aZ=q=gY?_)7=hTQOv_b=j&nA;w$p`m~wsg)yWy?TI5)Wc;EU_V9-@e&Gz<|H}iq z`+#9CQqj|2;Pe1HUByq=hT%-`JNigfPjxzc#rs&l`cIYqzE9?l%LLpqD=Q;`dh-U& zW_um)L`N`^F^W>8vBy8fkXD8B`uq10qed1aWrl7yV=!4=>CTRfmdGJVW|$n6FjkwC z+L9zr;5A7DE{Ozg8MXwA4@j^W1_x ze9t`G!ZHwpBKU%+iGvSB!#%{qF^qvyEQyrlf;*|xJ?z6hc*Fceg~VA!|4jVC4`{^? zM8zzy!T>#<<3(O>`~x*)gXI}e=A8wv^+hUd9$wf&A;d*0jKUq1p4>FXW5ic}tzIQ= z4E|waCWc6Val(z&-Y5RXD9nR1RKuFUi9bw(GYFreJcIFRMT{xmEZ9j+rO@+nAG~c5 zRLKX@*auUY0EyiqyluiMB1dL~-&SN5fJ}&iNZf=3!#>PIH3S1Pc*8&JLpyC6I`|hI zF@YS-!b_ozCW@olXw=3{h6+m5_c;n7CDI}l;9d<*YkXjpc!Tea6O$kxOH2atNnA|q zBlErCKjx#$*&GLM;F27}%$=O5Db5T~)(eW<0r(B22tm+=Q2?T&|3rmRkR06$64Nc* zf-&6SEy%*;QBD!A77tER)-?kz41;Dl9Vd_^Bj^?(K!YI2K{;$fuW*7ZG{Z8;!a?kV zA{+xt$U+X>gL#YrIf&sH_#r>213R=qJII51#6vw8OFhU#JOqt=REDIPM;_`SEWiRa zRNm#q+5$O(A>PI2^$Q>@j4hNxFJuEo#@XpLnlM3P))9L{8zi_B#O zHLA(NUBxQgUEs|^bOwUpT?MJF!QkZpcDft}LP-~pT*m2@DJ49*NdB+q3u2CxA&-FdjC9rC9z`B)~!*gaRy}WgaF_9}J>e9Kyfo1zeH=8Q8+) z*k$fWBA~S1UV7~CK zj6yrO!a%Uf^6Y~v5Q9NnLnqMKL42q|^onDNT8ZXEG>8K~%)>rN$%@_sJ?MjZB&9y& zs6McSJY>a=3fCvV0Up|DK5zn&+6y3(rIJc4|5@bAzBmE{@e3VPDIbsl75K=NWa;W0 zTPA*~>P_m(vMg7`o}-%SnXU|h97s#4(JbTwG6chn^@2@F!uABi^5s;`S{O&g%t`SV z^bso4B$Y1C2cYU(e2Cc6dJ)vr1}Gj}qdqF_wQSd}hOz-t7$Ix2;*F+iDgfF}$cbD$ z*2c>rCQZ!4{gk3VutPBTfFMZ1Rb0UxS;ZPuXG~PZlKjM&l!=*@nXOu2u97FOYC^C& zZX@}e309;hG{d$O1UTXj0~b z^d==altenjggCGqm?*4yv_e?4f_b#T#fpWJ8mYySue~S`P38s2Rw*5bY|pLPW*JiE zo@`&HtVVh5{iG9pn%Yu@w`r+X1*6)nZ@J*xP5; z2fpzr1y`+!a0u-!s)=mvC-QFz6PdDY9OmK(a5k#g#ufn@phG4nhs1IsHN%T!pKONy}+YL2_W1afy`BMB<)Y<96-~wr9^_PJB)-E0wJO zEo%#MZWRYX=njO_C1`(EE9#=||FsrCA-F=L97IaW@rh=_C1e8tTEiuDLOEPQ^KioN zc4#vU11FS2+KGcqLWDSkAwL|$JIv@kV2eD^gCqm2d7uL`jDb7QLp_v4He`kNW(An! zK{SMKSCX=MM65qW9zQ7Qk&1d*Z~@l!4>eFCj7`|$;kbRY5sDI z2^;gI-p0A?MgTK26X4K(IS10}DF=Ut)SlS(LG3OMDm6n*ZX|LB>RS8p+=HvM&eg|K5P=R=DRC_XrzU*6y6(v0g6G-RI_3@eAI9WAw4;W`z@^ zu^Oi?wyuCLlxsoAF(Ejp91sJm2n6n~N;3#VCxF8>AcTdc-6gm}HW=7Zivx=aOFZa9 zJ$T`a8VfzR12Z_mF*rdExC2%m&M{<#SF;=*hD94hLstgP_ZrYDpG%dL<>f^lHOw+C z+lv?=K{#CjOZ;k-{j#D=;>r^9X_#|hOKO=mGc$u*G2)kRU}khEEjMomk0MQn{mgyj z;=G-vV>69vGRG&XQ~(Qh30q zBlv)<`am4|KtQ{k{}T7rG5FP5_v%9ffqFL5JMIlf^BfxhL*($o@2rM`!fd&Am zbfQhKR@pIv(xp~!som4PC^(FgQar3#TXo^GM9{1OC5g2Gm2%L~!^Bbpac2pYz_nce zlNgLoL++Jx14%NV-v0hIXn4$Lv$&W>8_X7V06%kL|Aun3n`UCRpJKB$7fomq%?9T< z)A-v5*WL{^bBlYeUZ!&wWA0lybH#n* z_e&Q50Td4>WC9}~6EbZAo_UJe^&~T8LnVv>65!lF)M!_(!Ixz9k`zlmWc3&lc<=!*(nR~R3_}TsXih31 z12t}7|0RSMoK!+TI|Cs^=PJD6|9oS6|3IzgDzEBlR`5umSIGh7r&a*LpFcOr2aYDJ z28m1Vp@a0@q}yRM!7n(*KWtktFai+7!Kd$4dC$Uor@_wnoo8PhuG3dE|sXs#5G zFa;peGF>aNm?%YwpE!%BY`_z~xo?6p|9iTV6eo5=CAy|hlOtL#1RfWP%;sf)?m|cno81M1FsKBI6f!;Y;e5E_uN}IxiI<8^~NJJ(iekNGUC+ z_KTUCsEKf&%dIj=-y4=DjeL2sfyz&Yt^z~fP)4BdD$K{cY8blB3*Fo_0U!W`vuFPJ z^-2Y0RT?0Z9HpA&tdk~Sy>b;phVCCffBybetG16{NPfWBumN%s<;ftUE*)_B@>VAU z5op$oV8B2D0xK@{^!XELP@zC?Wy|(2nDnu}kl^Z2OB|zFWZ1;=%4L zyb!|-HSDeq<2ZROxDb20O~ev^V-Cd>Ra}w9%S3w-#uz=z#JEd#xDm%3b=;B19(}y= z4P*QPMiY}#@_`MFMB=BC11c$OFx8-(vam`BVp6b5j?oCJjVgJP$}q(Y|MSa?mON9W zm(UCen94$OY|S_|(Zn)MH1fw2A@tPKlNx{AF-UKM3C5dZ*!TsC0}=vam08x=XBuSw zS?8C1_PNMRe!Tf*9)d_p3DlHYa_JUhz`2u$nQFr6CY`hx3f5SCDk?f~Tv5b}8Q1^@ zs*t22tSYP2!s?S?;ot--Z1_S;!C~3j>#cYAsf${=_{qz!Y_k;u39iN@%qfoK;zThS z%r&>M7S&z%F&W+ctO$1HotNHv?Y&psI%qqNL=*k}w?ya;Fpi_*HbRaQ<=AyjGwA%; zB$Ev##?T(?YH`ClaGppamVEAsM?OO0sVARLaM41ZjRge573&BQ|0Esy@Jk}TBkLX`m}ewe%Fm* zqVvbbKg~W{#~_Uv$;gvtnBjn~+VJOqIKiBGNikGs3fW-{nnfC!r*>s&Lypl z^UaXhnC#4#fSH`~$~~>Tq{{5vD9=5G=yRj8eGGCVV~FvGQiS3-X_YG$S_Kr1epv^Z zb^N&$BYyUI1{r9I3>Em3*zg3Lqw2anRh(wRiGTtCkQMr$ZlN_BTNPOX2_SYo^VcbZ z{Un-Uqv0eEWb>iNEKaZ)HXm%Bb!(S*-l>+_Yx4?4+x+(e|IAy$+t6}a|47Wa2uMK2 za1DW^`Pz#T*gyw95P}i3jJ~3VoHtwzgBcu-O9)1==-i24%SjQ#OhX7xEJHe(*u>MA zwh!whLuJW$&{gOmk6~nE5%ow*5>z1w7g~oMT2O_{2;mQvUE>MY;F!nafs0}A;(YqB zjz55y1VLni2)8&ueW1ZYFMg3b`&!1-GRPZFbfSzVlHeNIsGzeJrA#fUZv61$<6aWH z;7Nv(B`K0+fKWHNcmkEEoWmTNaVOE?h;;sF#vBTP|BE33;TKn!#430hj8zn(5XfM| z{ATA2V>%-k&Un-_R?#+33Qr<(*+{i+w+|*LuK?NHN%WvMy=?fyD7R2V5VE(cD~aS& zk)%=%4iKzY467C4!%807kQVm6Z!f2SikYf)tw`Wce*qaDlRLnifN{<=vB@RRd}d`r8Oq1pRTGQjt6Ypx z+R|>M8K`WAphUq2M*PAhY=8qBR>251Kp~f!5L8`)kqkDtVHKJ!$>az^ziMTp7EEX! z0d~R@ZVsg=;5a}wZgHzzX>V8mAW~)Rni6#eww-Mui#*v^UVQE)6x4tPEEG2vYGfl6 zdJ*V+`B%tr1#o~2)o%eEx>l{d%fA5@@PONxQL=9ItO>@=aOlQCk*>(3uCdKVAjVbf z{IC$TC{Gd=ft3M0K_2wDM@`951ea<-|A{rj1sO)+pC=5>97)Ir&Z6OpK%|Er->?op ztV30!8tp-LIEICZEU``OLu#(U;4(hQuiGG4!4W3#lpp9;D|beYWSi^RNY~xRT4ru( z+G~4>lgVQ^39wypNn;CF*ueqLF;;RUo4{y8(99p#t;Z5RX|D5aQ4%XP^VgBw<4^T(^o}1Y;JUPDv&ISZMkgqbDrs2_c>< zl%lwVx|bMd_O!=cQg;`4Zxc*a+5m^Xw4%IOVM`^lg$ew@0wnH*1wiN9?E3oe7}JzX ze)n7LbH$6w_Yw`Zv)yfPf4fBn|F%t($?dQP*Je3jC1Y+@WI_~9N2On+1upjC3jeU< z7SM>8GDsEz1thf7_?j(co0 z{aDovT`cm*E!3eThZTck_268}N^U8G8|L!5^335n$1MX&NJKJ{9yJqYOlHzoauIVT z&2#|2{*}$p7Rj4mq9q42c1(LjO{geI^*LqIBtiJIW=VOH*cPd>hZg#1=W>8qvXX6= z0hL6Yxpg4ynQ`=sHS|<1t5;9=7P1b)8H88aAw_dYZTIBckl^e5#WNq$5Vm;xatuu9 zArGMthyDJ^7sxkTTioj3|F`}ZZTxORq1LW;%(cxK(w`pnsV5BuL+J7ZGk7Bx%*}^B zq-5Q&3#HT{xh}9$(9WaSXpkU6Q6LG4=yjD$S)cg4_ZzE6UrhKc457i4fAgB+4Lq{#6^HYPxSPw2wcGWI^l`$^HPV z4HS`n2rVko%>6j;km7GJoX#b_gkYe~2Y^88KFa_n!|nVp&qyr*BXF}aD~}*!0^=eh zHUf{l&Lx0hF0Kv&O%Zsi?(HVwYpN1h2A6F$_9kDC(}8st4~} zLDptXc+BZjZW7lts~Mk>ETNGvqGcC~p&I!jzCytovr(XOa7=a(k($9Dz7ZT3DhMAE zHi|$)_!2M!lWWp(9Sd_gND4FF(OzJBNRAdw?8 z&PpMT|AQf$P%r^AB4;jYh(pVGgb)p}MLrTFd5~J*1nEvv>H0<`DRGfDf=)cqCkfCo zOfj-7>r6@!7o8F~ISVOcF(wfwBtRhuqEjjPp*Lv~IYTLUN&-|?!WXB<7^;UO=1$he z;3;KM=V~qROi&EOpe)<-8C7rwMz zGNUsi)I!f{4n;~rNwY!A@ib>nY|;21N)uDo&?foCk;(@>o;5~x91&cssWb05~r z*doCO;W91*LkF)xBmC;!IKe=HPzYxfHT?2vK$TQWH8qs5HV9!tsqYdL<}of5fo$X5 zbPq!uvmdQP4D<16_R&^N6f*^Kj7-B}5+*VdEFljjM%U3)k+4Q3(m3ei0*wI}qyk9g zg^+yU%!*X}{K_PgbS@9cum)o~sS|PFj!3vPPFL~g979fd(iXMula4a%&@@ez|FTV- z^f}d3U)NM5dJ|OK^qB?~RE{%Lc<~p35gZ62ob>c3_|#92F+D>tEQ6;|57kf;l^+(B z?3Uym@It=kt3UH+3C3Xa!ej?Ebt96&2RqeVmUT5mRY6@=W@i>MW|P3^4Kl(J9}zaa^^x4HEAq%(qm&kPvR%>j&i)AK4q#A4QEo#JOvQ9xgFqx6XV0Ls zZ}pW;KXFPuNjrs0V1dA3>og?rw7Q1EVN(JQfPqcgMo_n|VlB2k6SZ!v|CAL)OC;zM z7AUnZG*1Ty^ccpV4N#~DS+;=oGHXK>W}9YqZ+BS<^J>ou_V{cW5C$zcK2s-H|DmMYjczs?4n7)Hb|*NBuTPv6452I zL=(}LO7@HdQPDY<@;7r)a!N37=N6MNX>sv(V9!;!h>KnamtTdFAox~*2{)74^l+cj zel;s@yHXa#3Qol(9S`mKpDWb1gPeGeuiXjd4PP8t&6CLY6P&l1dga+K#Rg zkgPyiR(n~a2x^yUW*CPT^g;OrdpXKsK&r`(19&USVc@N3)uRl*|FC(P#(1-0iJjNN znl?qi3TM;kjCz>ea`@Z0_sWWZ6OhawI^hbzH*Ul?MZTpH>cUCxCVkJAeZwS@@Kq!H zH6|&kUl;gosk4F6RU*okA0#kKtJF!e6DdK#fDhPjrzIo~8IjeLO@otxBamQ4NwRd3 zNL(TBpodSF;9-TQ7)GLjGgmA*xPvd28ZN1Rs9}Wf;$ux0btQ2lR=0Iic4a#i2DnX& zQ=^7iD3^QLAz6>Cd=`tZW`jVggM#>XljETrM)8bxACq?rO`sl;7mB$GdN;GAaKnV6 zql&M_ABGt>d^y{=7>qK&lhQU^vFkZ%gh04WP6H>rQ&?*PWMk<+vo&Zi*6>z zCg(I(Ho23v=aV&9VmEqoOPMS`7y%7!n&QM`F%O0FK!vB|WXIqKW?5xnH+IF@HFkMa zftsj~&}NwsoB>8)=q5A^h8Ua{f`)@1NM^={VH4IzEn;C27GYv~wK74pn!N~m2NJ?Y z1RD6En@uFGvA3uPjGVou2=?oX4~7RiLE4rSN>byId~WCjrzI=VO4c{&-o}B^>HFeW zj~AGME2(}9I-${tN{Q<+mSiVu%`wLGp)EQH;2?mC|3R|_7!=qv>?XGVs`NZP$zX$` z7|FAtCsvdxRtye+rA;}L@PZn8h0GGrpG=rPQ}{o{B&T=UF7L9I4fK}V`Za9$hLM}O zPfvG~+FxLAV2pVoCyL3A10Ok|nS)KMxf(-q6*8katiec%M@U3C;jGvCH{L)UueQ0@ z>aAlWu0?OI?~(`VI;J(rp7EwK8jG)oPW}33D#li?z62!cEdN3gaXu+cB>74E^??h! zva?gN4^YhJ^`T$lvo|{~LSn=B6%OE_7-W+lHu@=(Bo$dZAmb zVUMXnDp=VlA(uh;^5Fo!oEg5nytLXvNEB(u`-`p_s+%vm&$`NiV;QVm$}K9sx6MG; z0F3=%40wRS#B9ICgpb@0bm1f_?C&E%_yEl0=(=@E-lkfu^X(cOcu0*pe{wh>T#_gJ z#TzG1=%N@NG{A1!!=K1pPTd6m-0F-U5^2| z|45$9mIMx5;=|X}B|?D)J{e3;UBp#APQ+9xC#zj|rEUi~0)s#iK(K#7c~FTb*$qQ=b=uhpbjiU{b^|^(s$F8hp6n+IRgs$8g@eHm z?1EG^fyUh>%Igz&z%l4P-9LfdhsDfu^@zcG-mRnFGvVHsP$PcV6I_)!*io9c9o*Y{ zcgtRa2L43~9vn}nHtzch8NT5i|GqFFen}E>O6u9r9K*7TD_1kbT6-A+U|Btree43N;$nZD^W!q8ONpOoG#{esAGI_rM`{VTyPW4Kel9`eKfi{4-UALzN$ z-ZzqUH`*R+@#VU|3Lp*$%tx@`Cno|ED&&#y)2D(EBgQfjt6-9g7&B_z$g!hGk97oP zN|wx@KYsp}seD7|jX)|470R4Rv*rONICJXU$+PFqWhPDjGs%e%C!a`@DqYINrqicT zqe`7hwW`&tShHT$!L_T`|F2-fiXH0}hK#dl)2fw0Y@f+aJmPjTd7x6IeF-c1*vq%C z-@kwZ^F79|Fu!BR+U%{QSa7A2h7Bu>><<_ltxwqiJ9z+z=g*+oXfmt`wCU5RL2FtK ztTktWgqj{cvg^k03Q|x!->(`4R zKTcfvzkmEJvj$!`wRzmY!m~N=c{IP$po1*ABM^`M`}QMIi=+qteg1d==%0PCfCm{h z`|%eEECLSb;DdPNAz>b3Ad$m`g0<1cG5#D=$rwNU&_*-<{6owdYo(~-Sw&#x;)^iG zDC3M#6;Z@TIATQO|BgKN=;Mz-1}Wr_FmAGmNy{9?)RIg#$>dQt5t+~%K&7P6LlAuu z6I5F|6cI$a7?k6fWOfwNNF|wsl1iMgRMQVTIw>a;LDf0bcSX&qXHru3>F1w+k|pS% zgnqSRio^uPNnAX1a)3W>*@c%tdI@IfrGGt^SYv%LmSH8}VaJa`mi1`bW`(V1o_mGC z$KI={*(Mroo1uE0Y>>f06K~2DrmI544M&`Hp)_Z#b#NHhtEkxRb^v!lP^TMYwqB0*alGl zaDw8Y1k2DO|DXsbtZ!1**Y+Kmx7Ze*t*f@V=TCKz^=6ZA!X*@JO~@L1tZv-(#%y7`6*nEPzg3qkZ{^;7 z9pTuDR%_twb?X_p3XMxmxseS8FDdlqN6kO`IS8-3xd$)C5}qM31HOIf+hM;VlITw| z1Bb2R|G`>UZ@r5)I{fhU+;{K&_Yh;8CMQ)}ZN8jGDcK_@ip~_#3obHL5HkgZc||AW zk3zmGoT%jg{{RFaF_tmFv_Z-(1|(ZbkVc5ATmgPEI^R;>0JRDV@$hl*oK$F*hOwIjN36XRG7P&u2eu+&E90xw}h|`HLOCN;f7cn zAgFF}y_rsOtiumb{AwnS69{s4RXNKw=K$c*&T)9PtjJV{afYdm6O$D!Cf4vfq#2?S zYh@Y3xej&-c^85<2Oj?TfnNGa*MH&_ygm-kG(n(24)~%xeucD0geCnWUruCHC4aa?CV|M3mRyudg783PtLz>XBIwDa zaAGJ?vtWsqF%(hOk|&r9rq)78%&v`)U}J;SqE6Te1g?#3ZL7=MVo1$Q3C3<{#2aZ2 z0E`@Z=0)t;j6i;P8co^b)@l&Ak^sHMerdkJe%tLL0Y-VFr z3L*7ON#&)QcOJW+PvXo83>!A9CZt;qJf#>#h18QD z#jxT5@&JcWU?LQyGvgPFK~R1|%X4PDXsFN`8enjfoUmd;VPG-QIR0mL@1UJu3!~9- zaa0c<-6KeI_s7%(5)K^tM>FPdND);DdN56qOwmf+KH2o98L6&zx656d_!Mbct>rB- zII06ILm-`4YE(*wB&P&|s$a^7Qv*?z__FMJ4}4L0l~PKsdKIil87n`0|LMu@8aPI4 zO)y#7x}s$IgBT~2i!%>7hR57BuXy#)US==@APA&dyB(F@s4~RMe7JByWUU($@{fRS z4l0_H?B@6Jl;&n^+_A*0#DU5lTko zR|HXmLFj@7B-GVW`~=sJ#8YfBP_kShm{|zUHIcxgs}>j(!3777^N+5J-HXWi&UnV8 z_%^v;4U*5lE&f|ki*ibt%oSx%VMrie_9chV_bIK+l2x-t1qf!P&r7M`N<`Kq0Vk=G zc@A|{6ijNdFgQgHhH!+@M%U)vr7$zZFg0oCs&O()o3RO;4xiHG|I4(>jcIJMXD(wp zD&v|TPlT~=ATwIVExU~s$#I=%x0d0^M>(KHp@WN2%iz1>zwe0I~;31 zB`~I)c1sHiWGE)nSWzy~KB+L|1uyVYd{-9BnK1gkJDoUFg7Q^Pb8M&@JKw_}Uh0~E z<K!W05Q)1=gA!l?%93m6=62#J!*2?LbLM78voTz!~*yuxT^Wt-*2w~HCP%mXHhq4u`>zn}kCPo}eV<^e7eB@omA9q`V(i%@Uem0RqXn2O)r+u)68-_85=MhA9xMZE9EZB!P zVkZ^yCq+2M55+d9NrXhl5c4j0s2fpB6msb-ofQ3}Ji!~vGGnfRt7>vT0 z5PNnqF2{tO)`JyK z^Yko%G>G?PEQjbsiU?3FCPj{jZIGC42epUYK^oxJb%6se_i-+vKnexo4<9&Ok&sPO z#vs2Xco>Ksz|lLz6=vvR63yTV0B2@E01CBe48~v*DHs)PHC^Dyi@rF6MVXW~xCzOC z64`i-OQDQHK@=hbU{h!lF|laTm=BMJHPv_%P{|}E!;Cy(6sHGs-l!Bx$y4Gej^wy} zT-b#!bVx(jj&Q?a?>H0jXpq=(k7ekW|4?^zeCbz}XopT#9!;ioYor?l2`v%{8&_c* z6xn{@(U6LWMKr*FCxL6<5qA}NS{E5)+qO83xskC!9ts6JdPfSOkO&7LiutA=cyo&1 zaguTAML6mE0l%ID~&pDl)S9)Q& zB!7lMrlb=r!30)mH3Gp9ismJbHjRL?6F+dBPC`MfHx!>HRF{B^X!(@DM4dC$mg0zo zXVDfW!F=Z!6zoWs)|MD|*<> zmXJ{)n!6x6`ZtKxK^fO^H(KJ!@Lc}VQ5g8MD8veL9C6*g##G;RA59r_xs_-odnFa}w2BIpe3JC?G zdK{s!58faTgJ>XQ=2xbpq5mgOEy|dnc~ICwT8SFb+=&} zheayuAsUGjsjibw+A@hugsItv48f2J!7vNOArQ0h3t6#cQ_M^8mMx)0@-gs_D*dV2dmHwy0Qw6P#l1;3bOzOLGT8vP#h)&1;4-u)Zq-( za5w1S49J1@%$ zi_e;*bKnWa`L#Q+145t)KsmT-d$y9KzV7=-)_IM*L=>nu7Z}HKbemq^skcb6uKcSM zQrT5@@*PgNrJlwK=J3AOQ@Cx3d@I7A{@|Z+>8~pEOl?3m|KK;EkrlFW8K+`(IYc{aaCZ3=3chi8GODp`M;)FynlD;LMyrpMK@F#{3yA=4(>pKgf*tJw zAlQ2!kx{jH;ELX>wOfl4UR%E9`v$*htqNSP?5jO_+{fLcrKguvDY3uk6TrBXaSKE~ z`uo3(%oOu0zzf7cgxsdLD47)$j}Run*Nx z4ZVO2|8LM7OJFS3OwCr*S*4>*wH#!<0>m!*cD?~dVq|0H9189R3GUXK>wEyf1qlqe z3#X6>WBedai#KPSZ%Ydvz2zW{XB*A>y;^&Mmq5OB{G?H8$z*$!zo^g-Z814G$)3bs zDIr0r2g!$AClbAT{@bP-{S$TKKStG^jqDSZ{LmAF$(gJoTF9?{`Ud6b4>&0Vo*>F< z!l2;f8Ryq)twMgP>=`u#tFDY$vTB;kA!L&f48O3{TMz_}FbPXA3BOPX{D%y`@C;V% z4eIai{0r=0#8!O(X>iR>Ol|x0Y(2|%F&xe?${Ry_T1$`zz*X0Feb?_C3A;cI z{~nme73BNE4lAr}lUA=O;{6Gp{ObTEOZ}`zJ3*JWzXzG6i;fWoK6JFt2 ze&J6l*-u`!9nNsKzUw>!$W9~3+u3JEA;ACOoh`wH9la#KAPG1z3#;$~|8_77JOSfO zpas9c<170DOyIgWu?jBE<2eEB0~|2nZnsRX+Rwx5eG=tTo^wH=YO_A;PrBuBY}2FS z+fgBqk*ZG4YZ$$~@2s+zm?fnAcdKviPjRi*EQ-sb5C=&;3DJ@Yg#ZV?PzwAP4AtNa z9P1715X>C=3yN+mEBgkFe%8%_3(s5%ZeAVJ;0^O|67w(($gB>K@g3eE=*7SYsW1sV z5Akfb1o7tSLazsVr-1Ja3txN+2EHI{oa*>7fp~BSOJE3^;TFE&tP@V*jcwuaz5`E+ z$Lfx)m2KH!U-m8%(Huk3U%Go@W#shBoq56%sQpW$?Ig@D=A&{&bf?VwH zXa1n4nW08)Pd*s=FEg-ROW0n)(Y#JPK0n2#&DxfH11XA*xNi1R^!`Lmvt6@F?+O z*N^}UyFik=z#oF`^hB=*cR(Exj-*+CX1dJ}$I0~ou|wcMg8mF1K$uYBLWT_;K7<%i z;zWuSEndW!QR7CA9X)m|l0@W4k|j-^O!86XN|r5MzJwW5|K?1Z4(n_(=#LX8COv)r z1nQGh&SgQ39z~i|DW_!y|0(rJY}r&!okn%q$#m*gu3dBbdjnPMPc5?~F_9!G)g)WQ zI7wRN)6OiitIqoTRjBD#zJ2}iPGn)}cdJ4H-LR>kK0E z_U}Nj_v^eJSON|&pztDyU*4dBh9y>UWQhb7Oc0Jd|KO02LiGN@k2-IHsg56Yf^jAo zWSsdW7<>L%ry6^L31*%Ve{p7&U}gy-ja5=vCC6W~`$fk>3^_m#A%`TgNF#>~<(&hl ziR4H%V4-H0Q%Fg~4?M2KGD|JD_WATv>U1KtSYyS4 z)E~wYWwu#8J%ct{X{Wsmh9WA<$(T5|oztJ!|I(DLHiH1ugdyT`gD&0S*jTPz=74z) zIyQ`>jvr9S!#7`j$usY~O{s%#AAo;B=KyC8{sq4chgIbO3gL(_m`ot1VHH6tl#m7q zF+mTodjFXR*nhl1<}ZJ$sU}2VNh}zlXI@3QnqTg9WRfMet2mAz1PMlr0|xnJkRyjC z8kTqbq2|a?U-FGtS+2<0Wq1zpnEKp?mj*KKk+=K0wTo`TNJ7Rrzwp8-Ml*CO>;7S!KaO5`5zq z2NPTcko6yoa6&jj!6Xz=LfL1ZYF^HdA8(w|pEIa~3>YB;87bRPFw_yEd*Mh%7OT-J zg0O^ClwwH1U<4lY5G0~?5ElALT9G1gil!9_YEpuPm9U02L?D6`QWFP1JYlA=rD;uV zdK2y7WSiCX(1$;4jGy8*#FPNhh(|-CygWrR`R}EPKA_zbTMkk8#KXiDb zM8I-pGYRI85Xop3lgLgSeqkd;=m8JE=);gwVT%ryQx6|J04#_!!cdeGYEnzY3c2LM z7w!TUqM%LgYB-y*l}(YgGf3J3IZ%QUv?B{#_lCl;rvQ1Q{C#j;|s z_#wrkC@w37%ZZED0jzbD|FIhR@drC7hmK(QLyM_6%Pj1GmpL+_ju*x06#ZBShxYVY zg#>C)Ei(*Fsc)^iQZ{}s3>wG6WaNq|*u(Oa- zmi4R4+0;JZgAV&xCq4c^hdsXMkN1QDKnYsH8Nx6@1-;=7TX@46wh&Ch!tXEp2*MV2 zl!|KH?tdZrMK!+1vJlBNL|fR|FZQ~GQ#oTuK@(>xoMuiTjc`cl451#_Nm?PD@DwRr zVGCb4rAT-oHndUdZJEjsV(HAdLrjs%X>=!bDW-f5 zREgWkC=BS04OL?w|IXy@GmxQ%B`^Y`F@v?Ag*w>Hic@>AdNW@YmDPI;25-i)J|`6>L;+gB!YlgWZh_9h(4x$(o4{ zGd|}EafrhedIN zZgM&yLFFSsA{0_11tbvB6n;R27@&}**UZ7 z8BilfdCDWxTqXkg(l7tXr5sJF%Oz!tR~f}JfaP+S_dF@}Re8`^_i3VY<|`f_NVmL| zCP&ormX27eC;!+1qUN0pMj!%~Eqe5H-cVXbk^nYugnb={#TZ`)koJX>T}lg8Cn3uL z1=^Dn_v!)W#MZ8M-h(-^gt5pG;0cBVg8&6n$>{Gk;!!Y+<4gnoLcDTyaw%5f2R#67 z5E>*}zn^Uy_S}x(L`y_HvrJn=_`&pE*n*la?um^1;yB95U77ufbbx|f=(oQ;LQRem z-1px19LXD__U3cq7vK2D2m0@OUv%bUCe;2Iwa1k{W-9!`4X|;!?KNygu5|bVTjB#lf*pR(5qrKEX8|6bnk<-21 zGl?X0!Y5paC2Ew>IX+_!$y4dJ~*l+{w!#+uH z1ZOyae?S?&m`;j97%>cMHoGG${Zlpq1dLA#g7gTh ztmo1P3K}ZAoi!o#9g~;&_Z$O90fvf&84Qe<5MPLL) z!2i4>iG+G-mpH`5zi5(jn!y`%IIXb~(|ads5C>6^4PR(M;~^8pm_0Jwp@ZncX?lNq7{EbXI}3qC3-gZcNRLCb4u@b! z>#>&w^vI74rcKn3>j(wsA*JV80z8NWC=sLY0hS-!l;l7fJQyuo^f%-280w$~rs<$W zhy*YDk{03;J@A7&@B&SMyfYL6WyDDfyPao*#zhLQbEL}Qvc_v1iK^7fkYl;Mng6+Q z42mlR%dylmF5JpZOULFDL$HWScN79Dn1vpp0@zpuH|PYCQ4C}V2DXZ(zfcDPLIx<{ zwOL35Ah?1VS(i>qNQGpGVxv0_;|Ed7Ftd`#*Q3bA%nlF(K>UM9Q0l?IFhG!0Km`=Z zVh9C@2?gXh$xz6Hp@9V`F^#5lGNPdd%WTRRG?GNP^ z0)N0ue>fm}NTpzyhGA(2V89XH2)99NI^a+qPa?J;fC%tNh!IP>&V-&#od3w>s5??5 z#6y%!1KmjLFt$s?M2+FZf4C0#0fqaMo+ZG|a$3m`a+kmOP$3afccBI*X{RvZ2i*L{ z*|I_3yb=|<5^u^9F<1iVh$@3 zb6QCjMGjsZ63ttV6pe%_8xoJ%&4$A=pF{+2qS33t(c#%qZ&40TQU8qS6Vf;#Qh#X9 zE7jH2Nm3=v%3TFkBgOK zdD0Rw2u`YcRqOFE=tGEFH5(|B#$|$hWhS&&(RLIY{%#lerw_Gp=`gjJCdH;syQP@0{hVi2RHcH&25&M^;OOVUAD>D?BvnDK^7I1@KeS~cl}^n|+DpaV&m1UgW?Vb~w<`Xf&oF|WD^0Hs79 zRE|STUhOzrciGo`d0SHgSh+2R*fhY>JlGY3R0d7S4LXv)1zaSdhIjY}QuxW)YPc^+ zxJW>REO`gOXcEW863C5Q=>P_=nOv2v+}K@>Th-jvHUHp2iB9P}-~}#}Vf{wag<#|3 zm1Tg*WT*o{VBnr=U7S6ScPjLqMT7J zfd$j}2mF299F1JDGmbQ+A=cv*V_*mmPK{g5)eL6i$VgzUY~wh#li-`e2)1KAyA+U0 z1`C#BhuUDE3N>1_+&8#Yr4&N2SrdeS7vaGTs~W(1eHiMIzvi`<1kKk!1;C0lt74Fz z0i-qrjY-o;)M|soduiB94H8r~QS${otuZ)Yl>d@qfCVa!r`N1etjXfp6j}Y<-!N{Z zGbv6Fvz-7&V}ZcjK1Sx6c;jnK=4O_O(T&nOmS$t&oUgE840dLQ`r|hCF}x9*gdU;i!P1U?&J@5{ zF_H8R8h})L8D+V>zf&HXOWmM~%}uR|gx&PAhMQtk*o8=-ye_e2tRcb0#Ts4?JLM5$ zME-}}5;bB*W6Uk!Y=-HTSY~F9>6+#UZfv<}*6G8@V{7JPo7U!S?ysES(m^g{G9j=v zQN~Ov=P%YOHh}7=#*L|-YLv~S{*_fu;r~eFm@x22pESshLEDaV6FkMz89f|@UHUun zNP}6}OTbuY3$2bJp4;p#tkm>a(n@7dg7Aid~3Dp(yrq^s-ExAS07-=v5 zVw3*mM_Q_{80KOYh+7pXpw{e+m}w^5?9Zl%u7snVCT*iYUB0+x&|WB^ZXGccWXpC( zi)*R_SY)TRZQhV7t#UzKlvU?};q8C|oyiVB5WFCuB|Oxnd48B?pw}}+j|BAvWEh6M zGzbdGgM!7-Ar4sXB`h)61u03@Bbh;;gx_6|RdIk{DxTjh@g~(`8Vz#X!&av)5m9RB z5-}iIr-tls1{Zze9hJ3gXvJ04CjW4X@LZZL@C1)SoWRa#E^X7D;0pd}1s^EZo|Zti zY+L0E2fOVK2ZBH3hp9ra=T&6fI9`P)+lOIAF&uVCe zXD9_xnCe`324L9B+ewJ#sTcGJ1^PM72??gUwigKz14J;@zV_=Whu>%W3z3b4imnyehU#+z9C&jf(7KV@5G~jNxQGFkRpUn2_X7}gCEa(`cHm+~^wXUR2{*@o2c$>$ zjBcKE)gWXZrHye39!yV{-w}@6I56pO4vYtN2)p#?00JmD%t-(OT*uE`&yio#gh2~= zIVHS0AUs_Y1?tw}1ErAUP2TxY3^Bp7T}UB{c=k=L*l7=iiq3;o^>QtdZ*OAJ#f=11 zfW(jYLx@KRA;8@crvC#rq{m+%AJ|w!As_~Nqyik6gfx81a$6Daxr8R5cgxL*%tm+$ z?{@```^^qM;d3b{?Sw5F_~TRboJj4u4A`ZeMyh%s}m`YkG*u&fy$l$=Gb2ohte1=}w;SRl2 z5j6;E@B@lCQ41Rue%KOfzv8P&Y%ZSISJc$H1AR`SdW9I_w;Z%|Uxh9Rw|N9!D(Hpl zLzC>If-WGKX4-^Nh}~`x{6?R9I4*z9zTix_d(!|Fz32PBm#zqR|76GnY)=1#Cw!wD z!$}8-H*bvj^Z(b(mp^`O|-bll=Pk^Y8EfKY#%WI3R%q68Huu%j{NAGIgBy zAcPT0I3amDSa>0Z8EUv8haGz8;V@&#mK%vBnz+M2kIgX$LL|*WnnSxu1RO>h)kx7| zD~(hVFq-7}BS@O~SjR7Q00G4+t6=2MSl&3}&pYV+;>|znOnCq@&osk^AioU5&pW_4 z77RLBnVA(=V5v#UDb$FQkUy~erWRZLy!Do0)KC)`pMCnNS0rM&b(mo!0kc?RDhlU@ zBbMRN#VS~lbDC#q`OCA(4hDy*@}IxDTU zO8-XPcDd@xovpq4`YW)(3Y*?~?Y+04eDv98AhXRn`z*9fyrJNN$z&pku-R(6Evz4U z`z^TPhUm|TtD1{jiUz$X1VV`M10!h&jBVa))J6GYEs9g!Ax?6 zND1vTjWcWc<0LZ3cq5NL!=w^SFwS^WOi~F4qsp0QE`f&_YN`ndEW0Ff0G(@@wGo|d z-8nO2bNzXCY==8J<&$SpP`P8Dn=WMQdQuTvzQ7x=j1&E4FTMbOl$4ln zDYjC+0qf}FM{C(h*zNx8W6wVRXhL;F9D5WtC?RWwhsh>Ga>_2G_;D7?4wnTz9x=~+ zJ-;L+WHZj)=M|{!GKc>&MYJbsP;rdnP!ZBnOMPjjQd8YbH4RroF+aZiG6`jFbX^)1 zJn=b-WKMIqAxOm{r@#d=uz|ON8w7LZzzI^Yf^{Pndy>I7fB4Nl_!%4s_fxnLBCZpP zW1NiURgkeX&OPa|APi$Tp32d%h8yY)xeREofe_>%>kHTZmZ1 zPL?h>H?l}$9J3LA9pH;fv{4librK*55u94|myY;xfMOVrjAcyTDgO?jGDGks5oct} zKLj;L?1|$Yq(B57ZzhH%xFk`7vghso(M{462Q;%_O(`kj312vgNe2iDGJ^38-gzUX zDdk_+;5Q4W#j6?m%waZbGs=)gv!_1o=_*|*)Fk}0s75_1MQZ7uTlQ@}e;c9UN_fHr z!HJk-Ip#5wxrt>i)0r|PDpJE*9BPtva&8zGD04a+&i$|~1$>!L2Cb3a` zn?x(x#**SLkZAB%B5^$}$|V$FF{p(f%%;zVcEXSiu|e~~+JOC4uObm2Rbd33hh#Tw z?jnmg?c2!%>?W<6YgIvdQ{EvHIatkgE(D9L?1qk2V;l^nFGwh6E=MeN2Bx2KxQ$=WR6jf)e2M7^R@yBv`Y*q%Z=P%)QUk9pa4ZNLJrt_{xvbO2D3&U;)x%6XaCn275A@&Ag|(PbJ#)_P7z=r?VazO zmCBAA&x0=Xp&RFwL^ox%t9)%AYwit~=(2DJ2ySq8JLV4oBu3fduS7}2UiUgDyK}UP zT=Whd!SKes*5QmvJ}el<;0HRKfeuPO!ym=KBs#=#ibPx@rHoJm^oRqA#vZmJCIcTo z?C4>y#0*Rsf4rLTummv{8V(-^xyUn0n8)~{83L600X$jAmS-L2F_-y*n64_D1E&Zw zc)bi@p!1{CzQ{iRxddyk``tU+=)9j`($A}2Evps2!u>XV>8r)l%hk?V?>Z3Jz?K7t zy|08=hg&E)jqFRz8QZsqGpcc?VrT*oTmPtvB7)J2z55{;eLw~y!15b4RHWgOHhjdz zLXEoovt`qR{HBo%4Turt@r+x%RuhTI78Qgih2BDhhs$Y^=`r8TVcU=G#?5Jj>%kre z%HHpNpjh1=?(qr;mY@lSmG7P4;{+dBxj{h?Up5(^eSscH_yRB-K~4KUovIt0Z!6a>S7pEv9SC3yo+R6`SzL@|IuD2T!@pu#TTfi0xM z0i?p;smVsrU;UMuYAKeQz``jkUdE{f6#X9nM&9HRV93BhF(iZ&K_5um)q>bst%*kj zx`+>s)6Auc0kNJ%Y#;|d;_JI z9HLwGAS%L3t<~BJ4OpAKSV^ZXJF({bj6;_up0uLtCKw=_W#-&_NNJ7qK zuP`JHUE3&b&eJIhMXX{ghGh{^D&#^nphBsnLMjkkFr>m+C_*lr*qV$d%g-@QjT7>SJSZ-TKHgKZl_xjX4I9A zVy*;ZmRy}cCMZbeIVOZWFvDp*t|X=G-_#|1%> zR7DyD10V#!9{=)|#>_)Dl!_r7046DdAFP7CB|`Iz<`+!bAp8O{qypfT!ZaQL{dq+g zj#w^CV<{j*Q37f5T%3^h49ob%9UkdqqGOLx(dtwL^##~S?8t6Jsd503DsE>5G98v` zDYSCwRaFF-qNSL&DYl-6nVxC3cB@^oske&9n}Ul&HeHupr*G)#vL52PtZQMeh@F*N z$bDR)@hXy5CZQr~VQs-A1j8(>f*@1{9PCE;t;_+S>T5CrEa)UJ`dctC0z~1##jqye zvF1j^Dp3}N9+W~VJP)nbYVye8KfD8G@@kTr1U&tru+rj7oW!3lAP>T0oi>D~Q0ZW% zo^3oUwEym`v~JfLSVXn*(RPO=o@uldtuc7qF5rRa3Vnp_C z@7aDY9*Xbr1h5$f$KX+ePL_fnkl_J9LN!#wshk2Le8r7YLp7wrAWRy?>cKVYf&Y3e ztuiG6?%1&^=R0LM?RbLS(uQ3${r>@M|Y+T{M4^%?$6vPLIFwZ8kKmW`w z?V>R3sW1&!vJ1a(C1-MZ&9Ei|2esX>&|Vo@QLU=*a1UqgZww-{($@{Y>FSxN+u{~`s(H;5s)B}JJHCGB#M~Xld-;I)mfcjV6M< zd2Acof+7U)iAwQs`X5PP^HqR?HlJ)a6Gx7y6X?3xn{@;^TSV3=#*@CIulc9Vw(~oG zH9YTzJTo#UEC?i@us%~VLHDjd^X^)|H7da+T%XrLSL+%K!wZtKHd$?P_%Lw1l_2Yw zVT$d_+1fCv+OWzpAAYkopNU8}XD(Mo$@){^eFek?$Hj=kFkn(I@Xl^@F-um%lmrEh z`avQ5!u+P+PM&rqNF%AnC|G2%Eqq09mTFKJ=@Jan_#kys^QlBM^>PSJMR254rz}-F zCg@x>6Tz%F)$F^XqE~~pbR)7@&oe!fFh1vVTEn#^U-DaWH+WZ&T>rl{HPy9U9}6+) zHHjqeto5}-qs3bpBD=csv1%PkRG(`lwyQO^z&>_!Y7xCA@EDQI6q^i1ptNN8L8-u- zH{_Oe?E`1#);!c3F9wA(7(%}V1E>B1#P%C6vgRt-=2x63Y|3ab6oQFzxF6i1QtOr$ z@wUM3;YHO|bU0Bv!44j~nje+(^O1yr4iW>d94oho=rCV&OE;2-wLf$MCs_9gC-PaN zwIr)`cq?sNV{(;ex!sKSTGx8dIXR&AP}`kop7)a z9C?!OdK=WUA~*Rwm$mL>w{}mtmb37cfA_I3J38Y*p*!6HU%SN9%;y0g$9E@9qQrC&{ zI9LP!WkN7`Z2H{+8E!iKAx~ZqF1?ds7|eAs@i5$NY3t_mTs92>*|;>;lJjGrRA4x3cp*(EADr zKD)O>yR?frBWF8`oa=FLj^Xo3*ga&I%gWYkglqWysfWn!g$8~;OZHnqFdL1I!;phW~&DZ776jQKC3j z{!qGU;5gU`0HP$i9h*51eCvMS@Mup7rRsXZ6Plmp5=l0Z$Ur^%@eF9^XlX-KPJP+V> z?mQ+>e#$d;YzPWYLhlI|HWUewTBMD7(4)7Qp8Wy#@6kh|RvaQwaqkkLPjqURzl{(5 zv!|3`L{TJ|LC`~n5j6&xr4&5$fW?_->~Y2$s;Z&TpK6>@#~)B^S!IbJe4{TSplAZg zC6TmaNG80j_%{A>RjLkRUq{}nVsH~GL)233b$*jhB zjjLnEPznbk*~0CB;O5Y+Hy`;CGXJ+Zn(^g0pcuVw#v3u^(Ld}meXb`?UuuybP`*>B zCh`Ni31 zk?|uKM(}{;9}c~FR@-%u@y4E>&AE0R9}XKoWq|2XfH4jw zx?;?nqK|$m2Vy~-Rs0Nwbfqc;kB*+rP)ZEMZ!5}U&__jAL7#WZ|X{wv(a=-qgy{|OY0RC z6mmE6sXVLkPp@)heG?lZf8OyEs@Ovu1$;*_U;znP0VQ13DBLrUu?~Jw#X>#t#`n=ghxCn4(5qfwBi++$UH1=5iCg*4W9g=rTBo!l4xrSpA?3kZ{%&P0 zAJt@XB|6nq3P_DpM51l!na@7Z;f!De;~D5Emp?4jHD(1Pl>e(nHSDpEd3XaE!9Yee zxMC5ZOhgm@K;bP>m_l}yq({X;SB~D&q8HAvhSQNrb5zHuGWvj-mEhq%{^UBg1QAI? zWKxqjL6v>ruK$Z(6w4C17*27HGbB-*;yE`)PIa!6omVnUJH_eEv8;?AV%*bfVzZAk zQd3YkP$O>U;E6XL=Z+R}NgdOb!lC8Sk9^Ejbw1_L8U}$Bf^6jdZgogRzHN0S`Wh^J zg*ITpClv4C3Q!QnmH(Z{e+?-{F|Gj&P=JCBaIh(O;4r_4W+XZ!!5rpf0#u*|6<#GW zp^Jv8mKeFEm^WI^4e`aOHZYT_t?Pl$9Pd)z{w9wTGzGH^rFW zOJ{1+r9oOGq{@sbF}ys{={GYjui0xQ@@ zMG84_?4^uU6qDt&OK9p_;X*U=zCR)}MicH-5SCC`%LexV)Ii&?Ad$ZVK;pBq3I!xQ z+a5yl?+}NZEm(h=vY%wW| z2TgCdw2{Dr0{N3RJ+wBptu;^ntd%N;P@}`FA{N+8B1agijczP-I*MF(IU33kmNLjDhMlk^&o0;uu;c6lqIhdH))h zm#}5h!%kg8EB#Z654GS0M+GWmmGM-!TH_w}@UU7X63zzKu)d)b*kpCKUF@QgzB=eL`xv~!@l@R1btd^;ndveT8+k}Mn2&#vJN4)8;;NVnS7 zw)S*;0!@ENo!fzK-N3}nny@D9+;vK~z0p2zcfWf~X?OeE7gKMzKa4c_=JURL;@5v0 zsSRT|Ml%SGxdSM8Eeeh_TZFEb_Z2%Q5QSgkD@BsxkdX2}ljYYa=?6rR;%o;vMJ3 z$>0kfor+g{;uA+nLUHM6cVQ~{&prTEEy8t@wBZ;Q$+Fe2UWu&xaN8j1_SXqEZmk$G z8EYten$JFW`O}xJY=`&!@t^;+$X)+wGRqq1DU9}vPdH)U_(AXXt|`9l7_`oe+CX#& zFD+tX_==CI4$r5o<8!7%!m3ZnNQ)$n#aLA&YJds( zgbE~z>V!7%B%F??w9NaWZX~#`AzG&r!0!yF>zTMh`!?eIwC!NsC4y%r#4Ze?=pe_Oxj{@H!@zg>)3d+(F z3R4aYRls7^%wyAR1r}J4E9~JEvkm2D@Wfc92Jy%BK+F%`Lv4ly=Jdb^^I!>xa2JO# z6fhz8hKwIxYP4wS(KILMDlp0%3rDEX(QfH|w6O7diSdXA>cDR!%5MyP!V#tE4A0P+ zxGSqf!VSYs?5@hp>X0-7aUJ1G5BHG&*fAd43=ripOJo25PeTCj4txGA5fzXa7_f{S z5&Ry|7_ATrpD-;fF)c7Lb2QQ6Tq5#DLRDDp06a|(EbD8I#s4N!4;J1*v(iQ+Lg5rx z&j(#GJ=9=rUJl0CPZXFgu#e@uUXPh{htOlK+{!kB4>!D%tS*tZXT(k}ACH zyV_7I2L=v#;7P;^EZK59$*C;Ol8U%9JjaO-#Zxl$k-zZn01?q2+khC1MIay1>IO2q zu&_51GB@vYBns2`6tgHFk2(@dq7cf(BB2B=%Q5*OfD8#V)#CuHg@34m8dR$I%%i8zOwAf^GUa8?Y`48ptMSzhdiy6G4yH~ z_RY`e(%U-WF0+bA!;efMQ4$d{F!3`#p|Bx05dS)cZ8?65IZ%Z_4OG)2!CIhXA6^V3 z;3HS|hasp!9EJsLAmNZO6h2HdK13=JAOw+6u^2*h7e}<$ykn+LG{|PtCkpQ8nky)& z@J3psx>ko8cht&`VYKw6`?7D_w6P(~lq$uqhqg|dl61_jVk?Y@4$CS_ef5c?bV?87 zSBbUG*0Naj!ZipXpAhih>{2QYFjlo}x?*(<|B@1c^1)PuMlB*vp@Y&I4+v0bI)We) z6QFjV$s9|lWd)-J4vulx+q_O3kxvJs_qTKDqmv@tLHl0Vfn$%LVy$h5I;tU9mHWK5yFlV&XI1N3 zXJpMRS2u`P8D?fR*LYaAWz%VML03yKCUon9-dyfD&hB3 z!O<$SiaK%CcD$laNOyos#ydUtF9i;JFNFJY_)JGW^x8n})<#()plj`bKX7PWD8Lpoix(_rm>K|NXE2ZT&i3_o zkZj)rZFgaMf0za=!aGLdH9>(0D>WpZSVe7%U^6v5V$CORLOK>1X`_k@A&;0Fj}6Lj zetQCp!LK#{kVVV}&vT4<0+;y57Ua){=Hf!DLTHj-DZlS$%iyOw`^ zWRwxf573rB#x^}divJYu6%WL~m2Ej8#zRow)-{nB4o2dMhq$(!_(XZxH)bk4HsW%E zxo?3kpo=XFi){vsGbEB3jY%S>o%sw`V!Eh{o>`|Y^tTe0WSJ|0pWc`gD&ab{=_`w1 zovHdw%DH8$x~lIls}GLIR*;=xOVPps6-j zY9h7{S$tt3hS$SFVZn_ax`j^?JvgsWKQBI1GCzD64>-D{OJyU%!ylXmxQfGRR^o{j zLSJ}|ZtH`keM_eh%|3(DBWN_P6Arsbq6~RDjeQ^_fI2ONdYW|zF0MIpf&Z(88%?fSSclt>x0Y$qwjveN>ygFr>~<$IyHvppL; zK!L4cI-mWPv;)^g`qJ7~Lba`#wdr#$k~yy-VztvEo^4y(a{CQAVFxY&VTQpCjyuG= zq;vCF#1lBVvl?K)nrEHc5e=Eg?01l-dv+U5B}_uuK;ozb+H|}-BU$YoMmca=OqnW^ zuW6V-EmXbXL!yO62RV-i*|sfuE2o4)$`AIHWmDC5Cbz(&qwMyx>E|Rg@Y(#+MVO|Z zuQ8}whyTK>thJ#TwcBE2=hsK7*_xf(2S65@qB3@<0!l8S!x1L9O?=R?gv8C6&^1?M zj{7MVP>|7@AnO;#Wn0GYoSBNY#*=X;BKbeiWs-9u2r9X*tyTmD+iV^JV?D}UE#k;A z4|$c`Y7ikMO*ubu5iU@aen8^OgP0_ixNUnQ$5)3oy_~la)*~QRH=C>_nrTtY@U_)^ zIf>KFhZH%Q9WJ=8b?ld!!?@Drw^sketHJYj?We1ilX(b1hU3>~Y}9a$B9xR>Gp z+*zOC*>Jg!hsGPmON7$79TL}tC5DbCrkS8T{nLFncz+!8*dr0TcE~--vyRsyLAf%u z_W#upX~t%67wlnF*!$ z9nN994AYonw~i^@Li=79BDDRd`#rnX_$rxVur|mTj3Ln5{plrR-HjXSt@Pc88zBFr z5u@GS=e(^Y_U4P;2Q)a~V?-ugFeu~*(+=LCNj=5hZcy|x6|sgdK|FI5nX#nU0hHr1^=#L z*Yv?pkz*p!BuhJtqu`n2gmWd~F)E_~`{7BsJtASVuEtOCzC+gr6$W7m=%`%&UM+r4 zjwDVdOfR=|%kYCtzZa={yF6%KO5`CwITp4Wk=pm0eamb<|E=!l0isQ%WB&LVJZP}s zu{J(@9C-M!p+kriA6BYV@u9$l6(xH72r{I|kv=ME;`h*>KTmUnxP0l-lggPhGiAJq zGpEj-JbU{52{fqCp+t)sJ&H7`(xptBI(?e6NRcE|t6IH^HLKRGRiS$Q3O20Rv1H4d zZORqv*|lujmThyBB*Xf^{r2_Q;RJaP zKR)~esSl=?4#jW*thV~#rR$YWVjr3GY=K=w#v zkwzYgq+3E#m1L7nLKPB3a#dnrh6o)~(m{Nc$R%JGG33JxnivQfWB-ToQ|5wdE*8WR zm_E4ctCm&t+!rk{T(o% zbqB;J>_hf}0!J~R1jsD2+ky9xCTlW?6O{*2=#hkMjBvt76|8W>Ns1H~N!D7q zWl0sc>z6>4fZ5Qu2MuN>nbJ+W;ANY2R?up8mIe`=q^btnPXCF(!rGq)*dp9$iu}Te zZ@;9X=xD3tHd-k?r;!9PEH~+z)V-Iu~!x+tIhAoiMBC?UK zUNbSsVOXRYQZdrmWA+dyo5?~z8ClZ+$O32kY z(0Pa=-+Ec)p!E;XjcA6Pix9cmz`W!&WONy68+B&V40;J+bt-AyjDiQnC`xgPV3`W; zuDBH{YH^EF{2dp+2o#X?1SA@}2<7Y|Lm>j@TXY$T$M`{^H>!|&7?cbf;N%&Y#f*D; z$OxPaB);*{%zS)&%`K3DjB}{O8&>niFV^7?|9PVt!9d0^r~!*iMj{fIK!!8s;SW)` zgbI%Mg&SUk%9!}WJ1aR`9y62?RvC+qb*vu982|G&S|*6F?Q@C9cv+mu%yP10C6MErjpCGeA2{EST z@(B?jnz5kJtjK4kNunL{^CM(6$TqpuP5+>nE}U6g73*Ag&%Ek&uSaqxJmJaLzzQ}j z_8hDhITRFui1n={VQh&8IuN=P&Opc57)jo^G2>MXMYZ(QVJOm3ic~Zwamr+9HOf(( zxCW%yTN@@LVF;ip!VjrP#nPI#4tqG#8<8-B9)KeTG4uf#`%s57fSC1MWq6p zA=D<0>L&*o=Xm&$)TL@yG6@2eE-6S<^z;&0RQ*p5&YJ^F6ofu-%<6~c7DI8l*K>&V z30%f{jGLGzjeS|`8}AatZ}B%wi3&sgsS)xHTv1%s=w? z+E8SMrhW(xqpHyhZ#d%@)j-E?sgapftO5!rfgq<8sK85M8K_$;kBmn3OoOOyJO@zW z;kJwB$RIeoO`X*$QEZp-{*qbft#f)Yq9u%oafck57&=PPiaPwjA_iJVDXsvKE36?9 zbwIR4uE6Lu4EiB~5Co$c?M99HgDxfsU0d-2rvExNt^i#?qQ7!gs*14YmR?9lD8lLqRmzNQCL6*e0Y8(aaa?p_cccCf{lY%_!T0iNedo-@`Lqf_ASU4LZ zq|xz1T=S4fz=9fjd53C3Q>P*0!D#<}7&30q@r-9UqZ&(ghBwgh3vc`b5qSU(Fsk7V zU@VZiRG36^U9#MN3tmX#l$|kx-R;bt0a!BQZm_bgWBtCh}$LtZSW~wu5zrw+?nK);jFKQ!KjR60!c0 zH9XKN=0V`xViHjaHFPPqL^x}v7}IRps^vSiX9Ml6sU{J9yta;=U2RCjN$_+Ex46X( zoIb#5xAU-vO7`JMNczJW&zS!Q8|HwFXZRx*$aRSuOi6`V_*)45{>9j!>knhRVF$FY zz3plL24jfFY{2k^$Hg{gibF&&55f4<&ulv6GbU7S#!Fo=F>)l3JiRABh@LrA-^}^o z3cs*L{z#e&ioBvZ@~(u@A##512jU@DP`wXu{?()lkpc_F_-a04m#t2A z0Vse`)OB7LYXgXYuycS32s>i+B|PC5XLKNK7hWiFB|tvv+${XnU7H6JhgHWWy3Z6(dM>6K_KpH^F}kqH)tA zhG>{e4zeQ00DaSEXD0U`5aKyff_;#71(gs{>V{Ph5e%Gw4D!Ygt$=8hwh9NZ2EVWd z5WxzESO>FEU-363^LJVGXC-yxd|^TqWk?zE@_(&^P7ElDqi8S%Xn=)9imBKn3#f_! zQ$|A3f#wljZnqa4C=wcIi*7_0pK%PKAREk<6TsMaqp?xkh7bmlG6ygkp^ylmae4j_ zWHcy^nSn>`;0=@H4f}8a`C}0OfDY4Oc`C6E*q972K?QE$2zGEvFVO|*SP0$#O0s8# z^H_ygh&n!nk4ygqKEObRgkferu^6R;ac7u(BtsDwu_FF}32&GKV*rPkfJ~U9auU%B zftWv?unLoK0ISdn{18$5fDvnukq7Vt!Jv_dxC(XfbE~jub+85QrBXNd zhY*@D6rA`?)KMOx*or|Zls#gKr?@0TiIh3QibjhJO8Gc8 zhoOz~NRNSeg}cX>sI*{cauYfUcW6Q@vjR6d={93nL@!2=3!*{`qJJ5|hBB8wn9v4r zh+Yd>eFpzQE)xlJDQPX!fD9Nh3v1vY`9n#w5D2965Ks6EvPo&TxpT}FP)heW17VXl ziHUb1nLWXiF9r;(bWTjkoXvR_uV$1->73IE7E4K;IRZp=p`B1k6eD4Y$76Q_Wjq@g zo<6`v#FhtbAO>Hl2YJ8~!nhOKW|k}_ocypELq-vADQBb@b#7saU)$4N3@Q=l{f zl-K|1q)$o|&>5XU0;N?-6jx-WH*yT$!4XAqiwwbZ;k6Lu*)iYgI34&#b(aH6;Fay! zp6=$RX#R!lL(;~upn*+pr6#ZcsE2VUNa`1p@oGhOH+uTiF$kXc#jO~5)PUZ z)DfZekr>5CGW>`pl_?oHsR=U>B|3qS^0H|R38Et>ht@|Sxh8Z6@C&biA%Q3%7xH8N z^K-vYh&4J3H}MOB5MtQGEp0GCLs}kq@t{YFq;sVbfVpr?nx)O^tT-X1Q<^)^O05)u zrPX>CDb}4N8WAA2I2eLrbw__(i4wV(od@BWYwDF?`IQF%r|(K*6cIBXwNb!84dDOt zi8zT6jVFVB>ZfPa7(L>P8qX4A13 zI@BT6^f{uckPJC}m|%$@qG(bAbXQ<>v*2=}=Ls)LCG5~rwh#=rItjU&5xm)}UUCuN zc^AS;tT}P4rjrnWd4-I+oY<SrPm6zV$otlkx%pYR&8J&DaIvfx)Jmt zL+46t=f$S%+Me#}uJ9VC%E)&v6K#Jt8juhQ<&&=f`)!*N z8k;r1hmQnmv<<7cw1>1S;iwIoN5zU0l3F?8RjH5Rr&=u(M=TlXOF*IXRg_ zTN#D{D~Vf=NZX`S3%y9$v`(89(Mz3QXT4s*oh(G6_Z37tq_uHJe|eT)#CD7Iw-98z zu5Q|{UkRsZ`>rGi5%(&1{{Rc8KpNW?9>aMTjpwg3D4(G~3PLtyGT5(~A-Dzmu!p-~ z3%j@vTzg2np!pcFLaUQSWuegAE^&>T35n-#&4GDk_( z&lCJz5Bn2r0q*$c&@ zSd`Su6;V8t*lWdWF++jygeGZ++h=rF&=6N}v&S);V|=sB^^#-E3OP3kb8rm#Q(3?% zzE_!I=vB7v`lj#8$MO5V5OGmg^AP62mh$o)so}r>3&45+3y{#K39P^eYq&mzxKs$i zmmI-_S(tOsK#GYIDe_s130|7oS$M(0-FV1&aXAthF`??ABpinySv5JRk{J;UDoG`b z^m4VUhw?y4I;Xp9Aat?`#1c_MlWGu(DHs4t7)k6<59ALB_Ye&0yic6P*Bo|JOvPG( z&7+9L-3%q4+6F*V2sx~g9x(~Q0ErE;3asFgK*y^-FbnQ1%p@eT$;9$vOe8Is6~yq}Ex8V5X$kZeZ}gs_xMP6xoe zm@Lu~%%GeMKAud5DRL7St7dPbU6c!6D0ZhmOPZzmArA5o+PIMCb-L%JUMCk(=~6A= z(}(ENIvzP+X_q__h|I}6d}uN^7v#*5p`_7#6V%M4)(p;D-D=vr&1%8bWcSTs?WG-f zb}CDwwdxT#ce7#~2re2CH|ql_D-o)f1F3)v$>15u@C(z>&~*$L=v%t#>Xq=Dwr_g2 zYMa>cdjQ^6w-_?4`wDIp{djdEZEpFN8okkl%a;WD8J7Pn(xIKn3cAUiY^*9hxei6j zmpZ)Q0kkx2P}~B6#=@DTJF+fR)Yal3Gl3CXrB6$3w-GuR!?!`nJk?4ndpx12)lAmS zJ!@Y5)$!!qvi45XZM7AG5!`vJHHvg&e4}su13tIi8R-KyD#i_w&d0FN3sDKgu+PPi zwSrw|WsA@X&AtSk&~VzGp>PWMW5jteoUpNqn#h>jA(D{2tsyx9#10r)qHHCe zEG^Pv7^}^H9XEwQvE0mR-9dg~(;MAgA>jK^?*-}-H~_MOmg>aM;RC-0Cy5uF;CNGAvE zw)Tn9m3`Txf#6~g1ka2*ll)T+oZJ-=;fvn56Kt5TWZ@LiiP1ut%BLU&#)g;p-*#JB zjI|Ssqb(}2(PlVALxgwUgw}f#!w%yEC0SLw6Y0!c=gq~476`L&1wQu>Ik&=z_zHD_4kc9yP2&vhjWFlcOP9eiXZ|YQ}E!^91Zge)IQK>^pxe%KqsMfpbXLem(bdFqaWL zJPF^jDV}6fzpxL@uw*N1bl*Z*KveFA-M($kzKHFMrvOpzP7TE{NR@*c6Qvt9$ZgS7 z5m2@ni9o=VjlhE&$qatz@+_`#MmZndrVmDdrTQG)rN2GK ziul$h%EhXuyBaYKzn~8LKn$gTWa~glU=j$GMhN@dI%8^QY`W%tjMxgz-^bwY5hY`h z@Rgk5;WQ0yd|KISzczRwZE`0=0n!r360jyOC z7ZR@}BaSgJZp#qed-KsMW#qzof$2lHY)D#{!{*T&o?Af(D z7qjH1CY}D8%@I=G{CQ8!`0@0K_2_%}@#W8_pH!)*^ZCnr!njaV$(sTc@T84EYr`R+ zHZyK8h}xiz9|nCmK%-Gm z3Bd2zpa~~_ZXB?toOb`Zq&>3eGs-@Um;&rbB$HHfNhX_g@=2(QFl#R=tE>`AEVI;d z%crb_i%T%W#H*t#f~oAGKz_M`q(Ej_vyflBna3YuatX#BbezGZ4Ic!VWsNq5aR!}# zjwvJ%dGit`OP=2nY@ntdMR=h949!(-F+Jf#kn?NY^~y8wIi zXAbi8D{l_GrSE7g%FIHKF;BUJBb~Lu84FBP$P>V>62t@`-QjoI}BeLj4 zY$g2Z!iV69UhRyq(xi&kVYTWn*T>e!kzvGF8%fzfeCSN*xXyC9;(qnWc?o5t+r53;S@RFLJjVKpO5QJIiXpjrc_g@`zI1TRDF)s zn_L|)SRrU#?^dvQ_4;e1l=25ZtcO(y7&hQFmfK2{RY+N7AruV4YDsbs!g7Hsmt6~i z0_j8!z4Zr^(+tAo#1Tz=FeAP}n!(+x)NV=M8#Uo4?Ex*{8c4i!y~N*&Ll=E?(o6pf zVTn`U%XHRT_e*uYT$g>xkRDoN65Q7y$%i&@sYV`eE9s@0XP#k%qaR+er5bPcIfg_e z0?9pxF^2z+bT*u0TP+l#U(P1zq=SQHTokE+1(xN)Cza`@kNXEzRjIBzysKr^+E&iP z0(*b2eH|NXVf80RlCuf75Yx6&q3A(^v5097P_4ZEB!Z2r-AX`mu7_ac7~l$#xDt1O zj;M$;3{gmn_%;J1Y=waFnwRD7brKsbOCZKjQm#Iylz+`mhdbn94-1Am*adN7J|toh zg%U&~CJ`(Zdde~Uv5yHk(I0~0Q-L<~jwucXM5$?%_GUwyoK1=v2Y832B7uqU31?H| z`V=fe5eYY{Z)pl_AJEVj3aQD@CRPJhe(q5y1VWcrPX7y=DMLernYd`60LD;$Vy7RK6KZ&KX? zTKdu$oHec|XrVw~8rMh12leKTQk$9>f*>G1+AlquyUQEw`8j+VL!bNHr>%H`PkRzF zKK>({tjxv_U=Yxe7K9`MB}qq0T2hlF!Q?|Y=@CzUax;P(+$cj-%4=~%GoDhV<5H*< zR~k!RIqDHD#ilPN*-&gbOlD1OdQ;f}Q&MgsH?JM?t z!zJ`t*I^7J6K-H{d)uo6_{LYhZpcJ^)B6t&Ddk6cC1}|&0$2fca6XTM-F9 zRw4?vXk@k3;0hgRA%fdrh!97v%~EGw9mzpgKzpo~y0o;WJ#BrIqTbu4Sj8)z3v6SX zIu^(HE4Gy}>vG$a1yvC=)6ybS7uBep#fE1-8y7W-kzMCzik!faZW=>T45OLvjcF|F zS<#A-`kjZZ;?+ud;VQQDs+Ya;C3Bh0d}jDE<)!-_Bwu$@Q2m(g00~7_;|zPZ14k>t zb%RJn85-HiQns=g0hb3cEYb(H$ipATmri6jVzK3~hN#7%YHNIHOlP_*FQ&1kJ)M_M ze;Q)T6iSYPTghr}(Pj`i?n7|nJ@7eqQ`88Rbertt+$c-RR&{Rty6gX4EUPtZ;gxh% z?0H_E>?FPG9W$Dp{cLB`m#%EyUw`el695BY1{4HgVYlUj%$iEiLh#{6AN4|kLXl|l zZf?{XE^*<|>L7EkQp`nTlJl^>g}_35B44sOadW;{dpuLvvGSFF<;PmJ6)Ro_^DvqX zZJg))+0tI~8~EodIOk_rfaT;PAIwk#Q>R%`DR;S*S@dqdNJTr@$Gfd7Z;He%M_IWy zuoqIxeV4Z1{-!j*EzNMWr(Kr@Ke)uy9^-|-onRet3dEziV^sfF+~U}S$fSt;5Gku% zd?-4=hR*lKI3_vqf=}A2ehuuGYdPjzmdddYscf6OLFb$2JhXW(Hfr`r0IqtL5DXL)CKi$qzcaeno;VtJKPDF>k$Z_iZuCC9o@DMR?*u}1;vKLA2%V)k1 z+1_@AHQ%*ymwuSM-5`=coKL3VajI2)@rbwvH^V0yuT>5Uije;yhgUq38K0@{_y7rw z4mQl`Nfnx(c)gwHfB$!$iD?5HpwkZ=_<>4*q715{8$-QqNxE@sJqC-2Heiw0qrj6t7`y*lGBJRwJ{g=r(Rn`T^AZ}g zDPhV%gV8?T0gb%VyEYJmhlmtP;fLaIwf6%j!rPFaFh4aK4)iW5RH(1S1P8BQrYDeF6rvqe%-h^G)a=2(s?qr#+Ff-%Se z$H56lFqY;WKn&N{?`tsBE9ql*g*1 zmkp%6pUBFmxS^L~$$o^7^1`9C98Ti=C9+(Y;-na~OisIC%kF#29Ei(EI0cA!hXX*L zpt#Ee*vRzT5P@h4PVq~?6dIB=Np|FnIlzHgnJ1YO3TDJS#&ou;cue}7F96i9_n=J6 z+)vCDAkEZCIV`*g1kG=|5K<$}#_B`&K}}j(#B^*;*W3umi3sp$$Lffi!0NglS&=}J z3Zj^b&uK>A{LS~^P32=w6irc}AjtpYdSgC)R(jKm_M$%fYu zimSrQrC}OcGAh*k33cMd@gz^dti9lZkTHP6m2`?jf`~CBv$3d8Exk`4AqxH6PcXeq zLp+8k)y4xvH3EZBZbMLOK_>=%)6)b*){IarG>N8oN~v7X4T+`T+t7b&1yOq%nEGhOuZ&c470X3sRJS-+ zCW$R}<%)7p#T#vdVmOAEF`wm#3ZcOnjZ~m#ebe$=yi;WkD>P3hRR}VLLy);WIynO) zAc>-2#)lY&1BlNh(bdM>1hMG^U=7p$MA$OT#xq4Q2u)T%3r9c%C1?FtX#J`bVM-JV zkf(@Et%FuRWh8DLQK{Mi4D08lnM20Q#rI@OkGiPH=1TBM|wL8R6lfr<*{+R98zOE}1eV<0V1$y%!w4y={k?Htm#VcZ7& zTCmN7f>qUNGTVh!+qV7H7f?)RbOV8@+s?aNynS97&|9VGTfhC-iqOV30I6@xsKX7n zH?7=frH+VmFvx|Mr*Mf7gj0mV9AmLZoxKX4jS8P7n9q$t)xBTlW6{!G3;YF(7wg}s zV5-)A-A)O-s-+6%$R3gyQm)nA#$|}Ve81ntmff17kX=}eAco=%(=i|fV@+O%VcutR zUg$01O_1K5pkDuAwcdRgRyZ8lhWJKrJ6w+NUI%X6@g-l#Q5#3BN6iscZN<0Sd|$1I zU#IAm&JCFQU5c{p9@{3sv2%qmcBt z@?@720a=AzhV{^3VC~?v?UZED9nleC`6A&G-s9-qguPYaU$x$x6j?TkK<=eskFa6J zHMPf`P#TF`lE|DN{@x7r)AsBOBhF2@Ew7*T$4a|mQ2w+imf~RwF>Urz=&<;`cJzO8$f;-Y>CPAlqih*~jtWvIB?f*zWKcG)~_;0KPf zjLgo5ZqmVg(uDoxH@0ZY9D`*DC5;Ygj_&Bk{OFK=>*(FvwLNJ=Y+*AkWR|AWpHNV& z24er!jHZy9X-BT<610);RYoZJRv{rioemRuPHM<*Ez%|BBp~XgCTeql>VZxgeq9Mr z^^~l>E;n+DhfY;?Syd?g0SvBa4nAv)NNc#p+ahqC$BgZ_*4T}uYyTuA?=3{66W0M9`v+fVOR#;=)#f=Wc8_BQYll>JznY4!0@n#^)>E?s_hVs<_3f7VZD& zFqOKD>hcy_zCmrx9D`?KZTEg6_`YwDUhC1(Qv1g7JsxS24rH8kVHh@K2qW+UuOn{` z?BZTzx@{wDK2Zw-plU#9W0es9?J@%g^vy5;j`-dn!4=>ArS|K3S76$++oFg|RW!DyCK zI&c!f!m)sIDd!yjk#N5tBrJDlEw3w0-)Z=u@+LlWQzxRM265Fj^HUE$#yh7K-xPZY zs}-M$t{&U32H7@fhAwVzvlg5>j&DE*>Ddk)Jl268ANIU`=AGaK6-H@=)n5NaA4H=| zaz@?=NDrY6vxvdw3QM1%e#>+c-Jg{RQAi7QQ7_R$ZFP2cKFX$&(`9vbf4{5(6|F6r zhPI0GHf_Gq3|&9#hhW=0C+1*Rc97ojV~4L~H~6>~oBb~I+aq$k9&mPntO3JAAN-pp zzm^$zi6__4C#M4^zt17K1 zZ?De4ov&$KvUsDzGX)Q! z;_mo*^Y}%(w+E*sboXg;P5ZGp`43I`uw(lp8K|IrdAsMKnBU)brFs7j2h3a3$iw4` zt13_0qjQ9mXevgbOGM@_jWKF}NYU4eTRe0_Bu^}4@%-Os6aU!6$h`^XkaIBIj-l`gLs z{DLU_TtED@ReYm|Z()D@=PmZqk^IS*e&_}Az6D$sfkTxhSvGf(A|ChHywZ|QX~n%f(8#FOsH@nLxcw&LX0SJ zBE^apFJjE7aU;i$9zSAiD3T$_k|s~0OsR4u%Zqtl!i*_%=F9&`2SUAs7zq}vP%UZ7 z6te`PkD^A8A}!kHm_L3_`R&_xfY=y9#G?93mTZlTu3o=_4J#IGk(Or9>PV}0E!(zk z-@=7Eb}n78oBZL$%ZUfyPI>no8}s8wrF~B;VN7b&V$q3;A46UoQ4?i|Y=CJxQ28T} z&YnMm4lP>KztaB>>`1NJeLD4r0!L!cuDxLO?%t7a-~N3(`SKQl=7~fN7W(uDdgh6^)926jdBo(% z@i4ODrA_%AW7t%ka1vlt$q>U;T?@`tmU+v?6`_O^x&{9OgBOCu$v&=i!WSpIRWev% zPw|5oV@YKs*#Z2q*jPoBW%f{In{6bTjW>QqnrX(whT3o?6_?j<4+=M&ZMgN8 z5@YDMVv9;uf)|PW3`h)K`yi+whKI`FV45dU*r=m#S%@fx8oIU@4}ST1Oo(GJb=XBm zb+l)T8o?-|CQrqP5ss^drekS5N@U~?KrVTutUKIhjFL$*spXT#Nx7)7!xCGpvB#d( zWtq!nhpe+1F-y|3(|T9Vo76bJdxu<{H^5c(gc@-+@ zp^8$w(WCc18mYVtQkqwXnEDe{h=dvDl!+C&7^B^{Qa#ru8|Gyxz<7l?;!|y`w6J0`%<$2} zPnlMlQ#2l6F{>DBj1k8ly#Xa`TdpS2$h&^*>u^w}e6`|>Gu}9|GUFV1n2u*D`9YLp zt`VEm6nsF?ZG!u4Oe!gTZbYKC(I>kQ?Y95bL|unvb>;_XT{~P{!!B08cy;*Up!;kZ zv8O1hjiO0!$DO=Wz#PDa-8WvgV~-r|?Gco(i5d7rgZq}|$x+T8zWC#lAG77>mtWrb z+@(LeIqu>mQP2<#jUGx$=XbigOs!6g|50BgcZq5r?QCbjwG=^sblIIh{`D7sl&xST zGD-1};+c~mFL}xH96u=YJkLb$Rnz-O^*VCB!htL`7vUaWP-wW?AdY}CoFNTm2)Xsq ztcKCSVG?v$zNbvYO*6S)xlAXK{jsZE2WXwtG_o(*weNsZ)B)}k=#@3>ZXcWgSi2(l zlw+VxVHNZN+iV1q3~DeUrs<$2EEfO5jE&GFCFIBnv!_Cg+(t;k`kp^j=EFY%GLS2~ zArF})$lw(6kUKjKMHopDA(F0K`8y(uQs*Ziz6&p|^9Z7#D8nfpu!>gf%3UgTslNcv zYzE`V7>i=DhQTdvYSdt9FylPYyfJUHG15o!sK@M~MkBcS+a6&ULq#Gpnaa$PvI=R) zWuhdJ&|H}#A95O5MuZv%IND0ebtiNYrIP$35&T@U$&yqJnV__tC`Ty+1`-IBAqvp& zKGn((UXWBy!KO87sX-5RCYNz+$sC1QD`3tlBeyY@F^x0Lhe9->&}pVK%Op{bNb{o4 z@@HudK#fS?ge8&$XE^!eG^hWt4uC14izflOPIkIecVOe4?*f)e2_EA_6>MAG@Ch1> zJgk}=9V#$@A-&}kRG|k2Trd^tLX*+Pm*CSVRjX>%k5IItV7h8VoXOQ;4OMvBB-c!q zMv+RYj+{$0XA@DawX18QveyzVtRwlo8^ri)8vjBEz$O%MmJDo>OZXT~Fbr`YCv4;+ zlh45q*3LsKisUKDjYJ>Cut_v5-tl&LoP#~@h)q&r>Y~_D35=;&HWA-T>egVR;>?V3 zv|s+>SUQPap=*p0XCejpAyEZ#LWecv1V1^@g1(xPmyDfdI(g9KDaTVj8VNn%0S}@L ziV=0%A1#BJtu6l%3xmV#C>1O4%pWFEeIav_HoLjTVa48*=3J3FLbcC&J{*vrYa1d@ zR?)iN_2Ue^RYfM6*WCeWq#+&YNLM*1SH^NuJp42+Z<;Jf_Vm`sJQh)ZjvsA63foeG z>KkEgjrvk36NT?_jJs0?0^5;BW3+& ziZ0Era*8Tkdiz-5cLE)8W2f{v3eg9N8HOZ)ur*6x7O%$jLyj!o6bR2{&9qpbm91+J%>Y znk}JsnZ#c?`jL|!p{0kK#iMQtFxYSws^=(fSKr>(sk3#C^H}R) z|It&Gi1A_wyibJEd*?e+oE9;m6TRpIbh+Vg2k~pq z6zX{q{@kXHalE1Y$CaPX<*}am2W@`c9e>F6J`Xt2Pqp>h-+oI9o%)50FSFb~%j;qP z5WR22;5An5Ia#uBoA=)LzYojqgzpdHchLAVW`pFD?^s)XoKlsH$3@?*h|F)4osxiF zj}iaJkYwNZL0|-Sg!g@4Ld=f%NuWxUAKt~phNWNaA%?bO($EE-;O!pi#b1TYU&LL- z@VOx4>7P#t6iQ4V0oDc``OWhER{@UPLwMe<_#Xk1+XH4`5gK7cP+$dKj^kk95thUT z=G;q|)d&7uP7&7ag;@K!pV4h!3bqB}2@njpKqk0`{o&uls03imph{$23L%#OF4uVQ zVA#C@$?QfD3ZVlQnG^D%5hkG$vXA04VIOt`6at(Wc){%XoDVF8=X6wQB%Ew`1q_Jc z_<7+Mu3!;u3r1P~rJ)QOl?a_h4cZ`W(9!c%#~cnv*{PNt;-L_x)Y=hZEt3D< z9|B?z>CAQ6Vj&tL9tcHe+*e}!oQVY8yJ+DSo}dI?;#z>=p};^9z(ptCpYTE5@}Pto zjv^f8SxT5<%Do{Rw$Let-N)FWYs6x?z1zFcVlTR*%b{K_5(Lcf;yY%9A$q|QfW|QT zTqD+4jYZ;FOd{d6UNfr2GcE`WOb9hr;~EtoNQmOb&6;fBMml~+0Itvvek0i3iYrdU zIp&2$dK{Awp*@-;JmMlCwoE;qWJQ!;Fxm(bAWRiHq9X;QS#Y5(8f01^q*y4Vqfldo zfg(plq-mgBH`1UEG9O0%m@49#Y6Kxjj^m;b$1JwwRidOkiUhSh7*P{z$eY6L#L(LeYXQl7*{LLXDUnp2J>3P~laQRO9a z_1sZQ*ck(cBb^PP$%xDXN~KahWv}cZWa_4%rDQG^%VX;1v4!Oa8HImr&~nJYS|(;& z&I>5Xr9+}2M4V>aD5YM0gmMv+8{VKnd5lQ5nsX5u$=K#?MnrDz=6NorR_0rp04HP) zrwppjBUTe~EF)wZHyXui~F&gD=_=kwgr>&EZJ_F!~Oxo)0xIYY=sOUhjK>fB|^kp>1TWK=NdI$Z~-W4P98|CCQ8&{ zZy4xB`sMZjCIeC*k}&A8RAod!sDujXRZ*xCZpnq}W;y)UWi(_*9Y8V;DRT54MZ`|h zxd9ngSR2{RUA|~ZprSYKik*39j@_u>iWjD++-NDQxagQ}M45`C0%qrdDk}A@DF9AH-)Q8s80JH`X`gDU zGBIXjPKlwNXNxu|BMpNaq(yLa=7^$LMmWeNVyTlJ05Gfy@*)364|>E8+F^~#*`ta~ zq^8iT6-R?siLh>Ju?AA7$|I40>TbHxhHg-)wuM=UsIf*wdwqnfx=TNGP}NCft!~~% z%;;dY5U~;zuO{e$0qX)j%g5*dwYqDZ%IWv1Pn|;MsxawsLhDZr;ptsWOE#;EfpEN`@?cWm9cqU*UaY?f5)$@;7!#p|3(hp&ZdXk5k> zI;qG`2uOtH&ss$7phXI1LUAD~OTg?K;_A$HDVaVh&Ie-^~y#$A#YEadh#ns+Q)=K5pF6C>Uo3H+=&Tb6YrpeeI zK+oFk~7ovhwtvDdL)ve2Jg-CmZk_dw^fJfIHm^F$S_2L+mJ~4AB5(z}Fv~EoZ>q!t>*nUJ>I-K? z-F`;~chBImB1L>~-smbg_HVCxosX)JG4bk_tZ?J%Fb+d8wZw3RmW0fm=afdVnDDUm zzH9+nMCyJX$_?>T7O~eJ7_IRc?HWrHA8;1C@v}@Z6=M_)E9RfR@tE|U25;~VdNFL` zMG)Qw-@M^N^YFH?KU1`K;IsMe^K$-cMK6lsi8I%Ra^kK;*^RTo&e_90^g;VA z=!vJW1PKdQGe^tx+g)@vug?{y>`V^}Ku0qP!DvYLQc0WijVdz$!mLLUR(J+O-mR*Lv2(O3s0xCqXPf6^$2xxxSAQ4ayeE+OAkv^A8<@#^;!eRR8uwj zV6xV*wXuZrQWG&7Hfk!fazan#^`Wl1N`zUTbzZ>qM9=kMvxHl}bq>Wf-XeCfXmwwk zFkTnt_Nu95^Y5Jz&KkRhQ>*o3gSJW3^kR!gV^c_IBTHTPG&8G22v;^j`)>;|vUfm9 zMuh3H)OK1MHfr+s#c)$M)Bbj_ zb+htTH*r%NFdKDBxOQ?QrC1ZN{+8$c^#))MHeu`bZg2N{BjI)95KhMhd^<~VV>SVz zgxP)dP{Xznv-6lp6=5s&9XkJubWgW^D>y}rwtUm~1uyu0dzyEDcS(e+n2LAowz81S z_Ja&KEUs&3w|9h-xOFu6Vn6s(m-w^bH*M$f3}s=^@OiBQVp~R zlgz^Eb)HqsgjoU8L^zUzA+n{$}sy2TH<&4;$eTTaa@{aU{}!e=@| z7x?}Hu*1W<#~uG*tfVlN_fAw{V)^D*MmLT z&-KhVgwxwSR-65>Cp^shV3@{6MY6p*pFG4L*DA~XdZP^d?)}|o^y3FRist;(^B_c6 z`u~Ev2^)Uak0c`7>f9rJ-Ag`J<9$Ksed$Ma-@iTDQ#$6;tQfa`nfsW~>-8{&{zH_U zJdZw{tG?;8`4ebRp+kulHF^|jQl(3e7AcYhYE-FHsaB236l+$kTe)`i z`W0+gv17sBGiQ3{26p;(W6P1HtkYvYSlK`wteeWWXHLR4W3Sj_u}E# zmjU-idEn9;g}P5K_D55#ZRN|EH+TNL^i$5$uR^ze9eZ}|+rO^%uC{gGu(Lf{RJ{8% zZi4@=(O32j*x0{?#EZ8@?wEUi{rma%A1$3atNa^~zyb|Ckh1R-T#G)?%xkHx=F}6& zxb}E^Z-+MubEvHi>ys%p1VtQ?#1c(B0KfpD^6bPGU3?M75f_{>yp2YC@FR>YByGZy zT(b?Y9TDnqIpgj_E5;<1T#`wnF^)ll<-5Y^8BqtKXOMcXUc!<-eURe_XE)4nx(y%yVSfzpglZN2>#+^v39 z?bBit!*NtlB~(vUb0K5a*=Jo9uen%d4Hw^h_1%}>e*KMT+|;r(rcnn)eP}OtF9fr~ zf=Tl+-nI@9vq*c9{1@YlHQt!xj;Rb7Jc1h*|cNZeGcN5g|;qf##F-@>Zqljn(C^1()p}%dHk87pxIkD zuA`qzSZROCbk4{lFSeTPw%vXkZj7-ui{~#Zf@raSR2q6Yc2#Z;UXAotiD>_7Wl}rl zxD{WV@x~pub8ZIzJ{e_&SpFKwxb~X-yIY+y~?2L3nbku$S9r)mdw^DVj3B_)Tt1`X!5hrb^C?6u#% zCDm)H+hF7;Dm&uY!+-vE=n6VuSlz2#jr;iJpP&BUy*J)i@iUaRt-;G~{(Kc_n!2_l zn1dnheZ8yS0vXsq2j1*{tjnMN3P!$onU8WL5gF**azL~t&{_`^;Rs1s!fZt_edp5O zZ{}mc6sqtf#;HwybmT#Y*bp++OPmRL*h3%w5Kbr*TI*maz8(3mY}5Z6Pmo^tvcY`h zZqx%Iq<~mOD_#+cA}ZbnBeTLCoNYKtBUsVmqC5f?@E|x8NbN$SL$hQNj&YRZ9GN4; zjEpgZ;sfKn%GbBJaPc~IvEhV1GeE>ykB*5{EGs0M7>OvX*mOvVq7e-H z+9#3TXwr>0Y2+wLSxQp|<&i_oBZexdv`Ur+H;^n6VjlE5P)?DGr_|*xdCALEy6jK- zV@VRV^G8`yD~&6B*kKNd$X-4Zn$gVSFU^)ormQd}5gQ{0p<~Qb?Prt9TqZ8>B~5dl z6P*u?9R7l7#6DicnhU!d=4dz=agHW*-bv>^`Pt9xQS*$C5g-5i%xJcr737tftB7!p zIi`|GGM-<_C;a?bQHx%*aq9#mS!^i~vUd|R!O_H;mOBL%_$x17Y`V=c{l#3cEL{!R+6h}~=# zF|v@20<0PFv{M}N%cwqRlH8)I8s;~v*J znpLbHJK2ze1h<_NS>JN4O2prSZn&aE?smD`-OJ2&w4`k=LqHo^ig1Lw2vo^Hq9rZe zW!EO&mG6A%TNd!9SD_HuX?}7G%;gkxz3rXYd%+sk`W_g;3I54_{hQy1l-In{O{|ud zqahbw*S#DpFl80oVGn=UAq=LlT*pgQ=(_H_{2Os;Vn@CVAHWzTj;v&71Y#TC_{Jjk z>X>Aln-fPDy$x<-i(MF1^)a)?I9BqK>#O4*e`TuhA$S{pzQ#LALT}0;jYr|8~tYKF(x09A^JJ-+8P~wrWFyHbXQ^SjA8FN}J>L zX6;PW%Xn7wqLVsi+FFv&rxJ7#hq+={5m`4qHk@SX+*(F|8r1!Cba)}7R-9sTw`2r# zV*RW>Ol!Hb~&w!Wnt^&QDp|9=smTK~+B>v-wy-l;ZE-Q%N5tsM~{Y`4Y20S4aB>3@6 zE3J6jMS25aIE&#++=-tYK0I^0$cZQhQgZ~{*E1!Zm&nggdl&-E?p*`)ESN-bsg?X#X zlZlHu3}mg7q1`Y(EFnFZZwkrM$+I5#!9U@zf)4QB6b8dBd^?avG$~R~w=d|IwbOxKE5>7ve>;KL*kN3%dUL*&nHK6@QgjM{ThQ#KHrSf9(2e zqwn|Be*gc!P2O+$YziJFzk|v1R?M-9B$UAZv}r4 z2=}7}GmtBU%30o^#PF~AbP#v!33)UmHmc_$TaL=k@ZBhJ4bczvs1Ol95fq8%O5l$XLjn@P zu<`g1I}VSoGSPAb5!obg0z;7&Yf)S}g%oY-C4NTi3M3{jq7SdG6+sFXWAWi=%@&hU z8IuARU671S?EbWjAcFCDq^l(EDj|$*uw-otQ*Rl+5gdV{8Ho_?k`NVhPZ}wN8bie& zw2mPNrWlQ}8@(|c>(L%RVjStPR76Dy{bO?|F+VI!-O`cI;!z&I?N{zmAs6x?@^KNt zW(K1%`RqwMyvF<13%CsOARD6)8PX#^@&NWE7a>wF^ziN`auY$rB3(=qQ&KY0j~+o% zCcn`kwXdYct0Wjuy?}8YBk;oiRs|Dbh5r(ACX13LN6{HoEg}uX;RYh8dh+akGGaJs z8}Cgfc&8(cQY&jwB$M*onyVj0Pa~$$B{}gYVeXC~&)bdzWVX^RL9r{zabaNR9MLfy zop5EO5-n4UDxnhO+VJn*QZR!sF7?s8=n_Hrf-LI;GP*fsZ=>ZPKbLLg45L;UuOND^Vo}Xdpl5HW)K1$ulO;lRqghJ?+jq z34>MK69i{dBQMR2vJ5@MbNqDE2m2F31CK^#PbY4L;RSL?dr89MJTluyRbVFO$MY+cHSEH04qhICqUjx6DP^t$^UuMh`6} zJS6(`ZZ>Yp<=9j{>0&4YhD+;o;)Ya$vP1qB!W}cNnkp1CjH5%JH1htGDsR*x;^IuB zXdBP;C}8qI?Nn0#naxY9^DABPCA3UKg@Ok))loSJ2b)tz?}kTVvAI6=QRg%(CzVxi z4Nvz5P+`yh1}szEVpD;lU7VCqKU7M|12>N4O-D6Odtx%Nrd5yC)?U?8Epb+965psqpevz;s_6|pfGV*a}F;VbwVD{U1d`i6AfP*Hpjl>Q@}4czew(g zgoYHwN&~5b@}ia!l}pSI`b^M4SJh!lw!`%GR)Jz9?&?UZOg%MLVyG2h1-5oPHV1i> zTSs;`O_pc>5sXiWbUiN=wb;um*K%VIl*c?NCqHQ}ZdPWCNo80) zl-)Q}J2CcY`IQV-;TL8>b$=lkG664*0Ci_Uad*H7W+8PC_i$yGB2M>qQ@3&-L=t}C z7b*db^@sa?~`MKnt`0Ax?J{uvZ{9Ar*o_d&O4^enArOq7ZB$7$7(iamXJLZ{0*Omu6M`3l$pDBoSQ5y93^@1= z(7_p=p%m1Z42*ap+;@YOxKO7ra-`Ug8*Mc{WnYaCB{ZUvq-&5Xa*InhG_<#IB>{*3 z55RzpU%lK|5%kRii-KS9DxHH^RGD5 zRY_r3G@8J6eHVu(mxgyh5`v)=I$;OwKy~X_3*7e?rr{sZ0U3V58PK5=zW9bG0(=#> zltK714C#p(c9pw1olf{_VIwE9xcM^8mO-NlWEgcNK_K*&e$BWbMj@Rscn1I>7=pnb zm^m2GVIHp&44Fz^?fgnUNpkq9eJThZlVRh1Yg- z`4?`utqve)oZ%PHVI7>|nGwPp0ve5ZT6mv&7HBx7qjqOo+Nw|Kr4w0CVXTF7mOaiH zGER4ijX;U`6$T@ge$OXO(4+AoNC6{Ok-kQsY#AR($bry)66*r6JN!5Q?%8-k%4*1;e4 z0gj*f5-6A={uw{F!hVg_uw#3Xvbw9aVzITDI2?N{wD+gcT5kgyrw8JJ6Bu=!VH&*Q z8Ia+bGlH&z;TgQ48k_+cs$m|y_M~UGwOw0;t6H|Zdzuitb4w*GeKBDF;dNk_q6zHa zaBsJb83MBtIJ)n7y3xTNGGZUr!5fev7?j%^)}g-5rXpDTY_a0CkJq~oyov%jyv5r@ z+64!x_bbv_h9$fq(itI)K^@d#uGe86{<|IRLBltE9`@mLFqo2&Hc+=)Z4sQsNl3vL zTtZGnY;+qm0L(Uf^=qY%s=2$xdt8KGyo!sIs~MX>Rr|cHa=Ea)21V0?3P;ZWHxyD0{LUv`c=Ei= zg~iVW0tGZ+(<6Y>H9!ciKm!DV1T>ulvimYRRZArLGu+%+&~ir}eJQlrdvJo%Z@to` z9LBd0&{3e%55Ut29R;935flLje0|gX+ypd$lEt#f72P!7JkDfYDQLacaUI+3N7sY= zcnBTXzx@D4T>~^g0t7+>+5iqN0SJ&l13dlHm%Z7;PB+km)kDM8M-w8b9ZQ*Mo7FGd z|Gjj!o!d|5&kMfX!yVztT>~~?)XlvO451U?-~fO?)PtSVUmyks1bXUS3SB6cL)K{f z-QNM88(cKFP)=EVAD4s<^|#f!d(Iup6j=M;WHfvDq-g(e(XEp z0FZ#)QQ*{3eUF0$+6zfE2Sw>q^~;_7>F>U3qF$@d51{a0p5_Pt zAv7TD6aN4zfgl7z5e$J5Zeb&IHS!&$yb-ngO@luFKR*9vsqXE5_|uTM+tpf-A`MY#!hr@>uA0j*u(cwgd6?a_R z$g!ixk03){QbcgW6PdRySDAyxO2y5>vr+~Y`#x71o5P3Q>ILtE(t#1=>VsM{@8i* z#%`jqOK%)DAw#AKL?Z{dlhNXxqINB0?2IqZTC~ZHk#)1YbiF1{&nzQmcJGh$>HkK_ zC*Xht7HHss2qviDf($n3;DfyRwpt7*XdnS!!1=Y)1{)NTN-!X1+I5ciEH+j-+O1QF0WY zT5nW|<*GWA>FTSn#wzQqwAO0tt+GX!W@bB}fC62A1q+g1dL2OQL_yMVMjnyCk;^Zs z955Jhsyu^?GcEpu5J~G?>kKmJ_+!i_Ig)V$LS(FRK#gSlGRpyp?m)%?t7s7$e`+?S zQIiZMh2N*3swLA;tYV4l!3Za;@WKo??C`_1o%xoMY4v)5n{sw^tg#and(j4N*g?ex zOJEX7CeUhvSRRVl63hYB{30lH{>)QNi`EM2k2lDuI}xR`kYU84Mn0rPj`qfus)S2s zmLOHEh}(cg$hQul!<59+=S0 zNHEo`^GvohuQ-i8&NzdPJ^oZPiz6}QM09wJLZpR|O@Jp`lKGyhAk;j0HZ|2%8}k#^ zS(i5U=%kl!`st{rt~yR-n{Cz$A9>ud+HKRmQL!8fQ3#`&98h;9sidOHK6?*N5<18{ za}MBw?_*4*^XAm9Bo0*yX%j&H(w%LcRvvJInD4at_X59lT<8FV0uI0^T(2XkAtFV+LhLkiBju1X2G?1vomqHb;(0nd@;SKl5$3FV;kAQ60{N6Jb*wL<7LljQ` zns_^7CGr4AoE;U^RR~O6B6ycD#4+qqJi>Xy83zcLKR6i-GE`4{8nl$WbkxQf)k{8< zBcUBb6~6q`ah6rXV;)Tt$X@#Lm%t3BFmIE?iH(XY`=T8U^fCk4C2=B;9AY99sYpn2 z3G88&s-C7%@T_VY!%5Sq^;1^vEss z)f!dpQgp)%s6Yow(1IEihegpLA=5HVVij?Tb{S$3Ih4qWZU6@yQsf5G2!#U%V-?5< zX)u0qEp${vq#`|l09OGt>Oo{t@C;8x-dUhG!V#DFT**GC<{E$g^C$-ms!)eY)S~V& zp){kPS7N}I4M4PrL%iKGJ2q9Q=C7GUoWvxAkkMtj3kP8^PAPiv&0kc*8|yHqH>z=` z97#e8Mo1UDjF!PP+TlCUYeG#u=Q@DthhHGsDNlQ<%bx<(sEAFhVi(I;h844~TQTG^ zBN@^DabyGkQ>`o{?=p#B&;bWW+&};);Zzz#A`i#l#{vU2DCjf;BR#X%4k)EP@5I$o zR$yGcBvLK}#Zs0PX;7+;DcJFGs<4JdN@JJH+~zv>xd=ik)3llM6*ikhB0bN9jmYLYs&dGPR=+1{ks!xu*#|Wu7`RrjGYQE`w1s;U+uz z$xx2}GDwh`REl9mBldeHW}o@t?_w6jU*<3na4=^7eJlo-Q0+R_(OxSf1bYZE@Bx}& z1@h>1BTc|wp7Z>m-`*6bChS)o?bDE3CYfMMZm^UW&FDruTCo*YYF5sb;w*2Z(nsVj zG!c^GiDWv=2S9;Fd~$#m=W`X#8>$XS!bJ}trAs>6gYY{z=ra~nIrPPDJr&F*%)`*c(u_EjkTT^dj}#FSO`mTT8(PGdHzcez0_<7^CXXPaW+_R`Y- zfE?sF5~!9NaWO}-W9WOOd&%$4xW+fm@mm2~*pjY_#V!JH6)U^b`rdHcQrz#32|Oy{ zOL&)B{q0hPdsIo92(1%5IrD)|-5n3Q(1%WR1${iJr-sU}HZo0o>pP-Bu(!Xzo3Vo6HVxo1(l+S*L~}xiA}7?weI=naII*zJO1&Ik9<{*E^n&5AnqV(c0}u~vAfuODlz}O zm#h|Y!ES@k^>p_ z0w@pz#YPsP$9Jq2c&6umv_XIMXMceufB83k`}cn)c!DS>VF5@eF-CwfkT?|h0tuLa z8}I@(D1!+2f(}7}W?_7PhkPEWd&;+bBIJAz^nv6S5`(9BC1G}Fmx53jg;I!EE69RE z$bAu^gE4SX~X@pF4G(t=sBhwV{tH#LSDSaXz! zB!$?CclarY=!Q?|h@@DGrdT?V$bz3ZCKtGgGY5!)NQA5rgq`SoNoY&1$SH|9il^9% zzW9p@lZvWnD?Vt3U_ypvD2P>qhP5~o2DgT}*i*a6V8B?7)_9GuB8>6%jIg3@4)=#M zL1g+QWUG-Xv}lCS_ZiXHPt%xO*!Yg{7>^DT6ar|6#7Jb(_azHgd9mn+RKkpJafGml zi@A{`PRNV$n2-v&khwyS5od|CA`>T(cw2&u$ta7jVUEqna5^RbdJ6Uy!*Gz)$dDvi zk|r4!4jGB7sE^_T7d!QS1G#}7DUBPc5D=-31?h8)7a%9ulRo*AT9J~3a+9#qd?}k|Vj5a2c0!c@bTi5Jc%JVd)P?cmVY=mOsXkH76jXR}uobeWbFE?IDVaIG2ps zm?qg49ASvuHWLpt89O(2z7><2_;CDDnBuY&{&+`-W|c$Xn5KD}3t5+Z$&DHK7BO*| zm|0T-7J_FXr^b{k%GmC)_JIk`l+D$ zTyx5bhL;qESzt@bq;;C9(8!-6s*`QXWT85%v`SQrifT=onRZ&Fk}8RmnyQuxqW#IL z#IOp%W=>5>Br zuQ4j4^QwzcW3K>OouetP|5~vY+djR4s|_3fiUn)1_6QkUy0Du`c$o^Zm%65%%A*&% zvMl>G0Xu66OHUmeo{|``a>SguS*AJpl_tBbyg9MS+Ok4Bv|W?2&>FKj*|A0XnZ-&b zl^U$~y0d87vr&t(KpU$>o3&c2Fh-lM8>^%pD=tlmv;+&7{YbWzIJQ*lvujGFp1QSg z8@FSkLtgu}XE?1xX>Drjv~QuOt!j+si5JX@R6rJlg8@2ZMm=G+QBqj!%l&~@EgCG*_=Aeq4*NM z`#T%0I~nySZi5=YF)YLUYQs$2#4druAY3aCOr|OnWE zJjNdZ#V0E!Z@|4&e8R_zywZCA5~+K<#`TdIoV#Rv$9QbURXdrhXtQOTzxvy`cUy}d zDz8j98ekm8c)Z9>tWXJD#W$Ower%r1sg{3go>8fed(5d#n8-`a$e>)ndOXRf+Q&U? z#ck}y@==raOU0zjer~&%p*+je>&Q8L%Cc$7kUWA{jKv&VldQVQ|0uxfOUuSAy|#Rr zwKBxe$i{#i$bfrj6XTiASIFIqZp1vm$GpwFo6OO?rOJ!Tu7{!C`pvEJfz)hx#QMqy z8ia-ld)yq)qU+6P%*V64%ZGfbe_PL-Tz~1@%hxQ;o$Sf-T+ni>Q2Hszqi4V7{50`8 z!5GZSeG8@doE2i_o_$ z&VlQlQu?dptjQrw7IA#it=!DKywV!%(n4LaFkPV$DVYE)ruwX{IV~0=T8RI=)Hz$x zSaH#bJk(fit{iRDN6p1Y{Fl!R&HOwT&{>O7&9wC@(-sYq?+njb{noWw)CxUwYMjD4 zDIZJP5pkJQ`aW@sF1D7{j}3tjD=Kv6@-o1n%&wx%GsT5(@4pURI96_4be2o%6FO4 zmaPzNy_2pT+^=o_Op5K$N4XH*Q`-+mi@|)?l2O)%_s_%%!B3gZ&@0^74V+SP-qh#b2Cm)2UEE-;m*I${oSU?_joamogw|ZyINi?HUCal*;d2S!_bt-?eR$Ym z-{I}l6I0js9NYWh*8m>iQ~lvjVb!e7;WVz59$w-Q9^yng;twvf5l-H?0o_0Tp&P2; zP$A=2UE@k_;|V_33qIc^VVP_D$CNGBFusgX-qX{Wi#Xa9NS@?N9_A-`<2a7Wgh`}Q ze!(z0<(!!4iVhlI&3<-%=ZYNZsBVpuj=z+7 z=^|0PM&8??zSm{mgV+)0TMo6CY~mTN;i>-XrMT)59NmR-q_JKb{XN~gj))~3sJ5G< zuxjeSKJBL{?B8kLcxvpPZszn&pvRs|E&k%M3GK*w=hS}gjX3F)j^BS>zAu5?>%Jck zJ-8~~hT%@@qdwTtZtm#b?{R4D5o+EzVUx!=@2*_$iFxnz?%3p>#HRkq{vPrCr|#G8 z&+hL367G78Pdn#o?bOZwun;Sv1P!i)>&aT|H-s{(G z@;DE9>K^aMYVmi9a2;RivySgU56cP<-eG9-zMk_;uk%g*?cA<<)%uVD4U^|>*B2V@ z_TBRX{qPXq^k9#6J8$)AIQ7us;-kmh6b!?|5V1-RRsA3IU-l zKZt1p^Aaw#boBQ9jL2U9^>v^48F%+e?avXX%Wz-#Lr?TI_3@ZXxROtzhp+gYFLaFG zB%L^+T7JJ3&*ngGric0VeXkUbKI5JL`o6aFk>BuXxU?l(^q+q9r(ckkfB8Kt?@GV_ z^sqntj`sOa?tFYX`X;>4y1)BH*xV!z{6M|0#9#fp#?f;+=@-@X%UGUAX>$vab z%FnRpEB#$R_twAuj3)b_U;D#r=(CR&$sX8;{*f)-d*cFaX{cef&~p8M3_+F zLWT_;K7<%i;zWuSEndW!QR7CA9X);o8B*j(k{dJmLz&W_u{S$hzJ%$rJ*q%>eQr5BNA1aDU%MaUA=w<8&>RCvR2KW zMVnUbTDEQ7zJ(iC?p(Tc?cT+kSFgd7I4@C!xz{4rqDKw(tO!)FN5Ux$Uj)4Wcp=Zn z5sexIoLMp5#{RUD1sz)SSjnYLpGKWp^=j6wUB8AMTlU<(H(6@lF?(QVl$8%({wY&8 zL*BlFPj!9CnDK=~nIFJSwQf_KpGRNEPI~xu?%lnA2OnPic=F}R*H-x#_wdfo2`aw? zb>e36)ct16oE&(~o9>}U4{W;5GI1k20}s@}JOvkIut5hOgfK!0C#(y-ly1|EJ(Y}s z2(iS38;`f;@QbW94;L!TApk*~%f74-gb_OmXQZ)48*juhM;&*J%fjBG(~T$&huTk~ z07FcXMCnW{^0y=(0@5ztwu-Sz(0If$OD(tLvP&<&jLpZDT3Sywo8-Iys>z7xtM5t3 zN@T4m=8C!yO(@}}T!<+opd{{=W;wh(PLLiiYk$ldOCt<_deEk)^{dhd&u zMQ(xBcVB@w=D1^zKmHiqg4eY-VT&Uztl@^_U5ws|RbKgIDKXCf*h-LZ#yMx5cP^CR zC=D(-W`((fx8jE-b9rKv5RO%_d~1%8XQ`*Ax@xP<6Zz){*){pd@Oa{N)1&vwRAQwy z zzI^k~M}Jh(U4RU;qU;z#1(tQS8Ip^ANJ4 zZJDVsOzV|Y-tq=x;Ln2ofS|U3cfG^;Peud;VF*PyLfx!ST?r%{10@)nq8V+4Zvo%^ zw0Aof>ZN}k6b%V=xI-THutM@f)w*x5!VvK&(&*w4Ds5`s)IxF`Ou12 z#9|ghV#3;OO@Rd=Vi&6=zmC)oEnu_Y3^zoQDCTL3RQ#Y8_r2 z0bNUt`rN0`KFO4S0@P0h1!+h{sy-m9Q$Y&t4|5z!QNxKcf*b9eq>3^_(amIk%;X3Y zPv_B8j?||=1*(<~ics-nvz>nN%}VXrQhIt4rr+b`7bgll1d=3%!`LZLiy2g|cGas8 zN~cN5W7MPK#C=L_V4Pg~(zN0Wdl+4l%%&;-k{F6ls~`PpUiG?H?hJLQ-688CS8^1z ze$%aM_2ysc@~V_*53X_bp5>}qk||~Nu3X`3W;MH6)Pz-@MV;xjmXj`r#t*UWBB~9E zqCIZvPdF;HN@XwGQ_j}bwzq|gUlkjq(7uecn$(b4A3G47O35am8!kUT%h5N^cB{CB zZgizv63>ndNxiL?u6`?4(@OLs#kC7h7K#?&#vmYAiMX9=fP**jnY7q}qRt?zf}CD@b{q$vrOUNv+1UQWu1p}v$RfX_Qy z19#ZN({-$c2*v6Sf@LYpSVmc+{#HrnJ z{=N(3TPC-A@k~pAd3s|eH<_y;7IBcVTa@M;P_mJImxQfJVWhcOgDXw)hA-=6GMAa4 zIi75aEt;u@EGM#t)z4{B%i@_C8H|O+vUz1ZW6YY_&wn;1l-o+Qi7}WVDCsY8`^mzT zt(eZ(wDXknl$=I*Y!#|oLHqVvq1hzfbCM9vFkTASZVr=`>>vFwa9 zJ!@L~P|$PP?TvB&1JP?WuF8b90r+~-E#t=rh?z)`s%y#{8swe6Tyvl`be^D^|n9c6Ko z)vn}5cfbX%x@b!~Htf70LEx=#d7G(|FXp!m^9|2^uUpSI`S-F1zHyGrP2F%l4Z_=f zlYvZJvTc&Hy+Q8nEg!orvL*L8J3e!o@2ub`c8$nKj*~YvoY5(tbHr0ECy2LtiFztf z%==t(rZ;_KA7A-mbna z_cmOlX$R)7?>XjV$9vw71@*0?{eu6fsgka~ZDEJI$cZd%-7&88a_imkk3UpN`=}cV zUeL&FpO==4Zt=L=G{Z3e1bf&aKYG%GiSIr~&3(70E0afa@Q4%%&LuAQhK7-Up&xVU zb-#Nanf>gGQ9V7Il6AfDP4k<_{30)065HS2?f~a~^rb(e)1$sL!H4~OTHn3bXW!9= zhw2lFFKP%=8uxdde)`qVAm9I9FWC2okGIe8?k~Ka;J+C6=0A7Yo8{HvV?3E#zX2pb z@2Ec62tN1NBVqfRhvPQ2xSKtPXpaX>KDu(jC6mD;L_)jh zKo)GV21}E!>pLd@QL&NezfM^`OsTq-`<3%Uza;d+FKi1Md=2NI2ocmEzHvYy^g(X9 z!huM;{bRT&6gNGIHCY40JH$h)SVAT&ou_ES5md0_Q^O%VI_5|kxg*4pfVsQN!$x#O zk`O}_3W-EyD#H7|HOxP2>!sL}!=+e6K6}Ja6vd9%!xPN1NTWm>+z{H6G)#=Z-Pj%4 zOGS_WX5}B$Au}jFRQ}Lv&bH#M(3kQ{29NdAxL>dC60v2TvSL&Y`Kx-B#1=5PPB@h z8=Rn!$ei-VK8eYp97T`(NTSI>3M{|W_&=jy#a2AZi=(2T*{7J^dD5Kl2;#f(x z>dX}Xj7+6TOV6uJ$|?%1LLAM6%_NK*UR;m`6v@P6%&~;5e*~wq3`i&Pud=kvtf)hc ziOu7LLC!2qeEUqV6U)22#HjR$rrb-aTna)IPKEeHP(jY_OipYu%;xJwIOIQSrGOtxSmU9-;XEKBKp2&|+n z`(#k{n@!p@kFV4y{>;y0YfQ&{xv08{ihN4?+s)Ec(8g=f5sg0ltkBf}n=)fq|!9iy&m<^@j$q9BuygC z%`T0|6J-nyrIWx5PGk#9j2O4=9G8@Rg<9h(8?- zLABJ!W7F~)E0tI%;;XpT=o_DWQjt*7Da%r;V3WlZrVG5(R?Ryrz0%aX7C6l$x&ze< zt5 z)@?mj$+OiR_>|KbJl~S z6``=nwJ25ebWBe3r;eJ}gPl28Rn~Cb9+leHYMjg${Zhs#q;+kJhgHP+6j6lbSahpb z@eD-EGY)cfAc6f*d{jPsCC}Tm*I=!VJ?Yq(6*ySc)k8OOOF%C2l2cRC6QuRpXQSDBbw{VD zOWFxpb7fR6U0JQu*^DK*uZ7!M3tR7aL&>BblbTr2Gue}6Q334AgT__JG;n6HRC-O~tF1NB*A6jjxA-QV3k*yRrROStz)6rnlW$Aw&! z|FUOxod;0EaP4+wbRw5RlIy&{8iwl6W)2_F{Kd* zo;@-FM%%RQJk|Wv1=e7CHQ)1v4LtQ+CydYGpib76U(}6X=iJ~Gp4kp&+J{`ySUkh` zWmZ&`R`V)d6=vZbb~gQW;HjL|B%)yDUEaPmKNGfG9#&$_bzzMEeOASdzg!yPpe5;rpz!Me}5hU`87X%Hd>=M@v3sRJKsoCCg_9 z=iB<_as^K9yJk?<9aENAZ00C$R=IG7=gk`DTlL?=Kw@;N=AZ!%Q0Bad#5BQp2I#%| zWPDELAVvrYExcMb*7O}R?A?YA=!veQc~(@jg3@#DjuKYm-Nj?g(dKTV=#hS1 zSbpK>Bw~TM6dNXJy`93dU}Z{MX8s6iktXSz4yl1wjUY_WV@BSlt>ATT>33C`VANfl zM(Q&&>65nEi5R{;RcN0^W_~_2b*AK`#%glXX_9O`goZexDdRomX0BC0gJx+F3J3rp z`2+$Wlfqhc?uo+GAPlbJ>R6+ z6vrgVr%Ue^nIojG-Me`0 z&ha#-7%(=TfX(HbH}77$dgpkYbLPewpO?~*Xo_(xS&o=9Yu?Oxqvg+_LyI0wy0mGl zol~n`&ARjH*B(uxRB05c?b|L_*3^yLwojkEk*-|Y)D7(8$dfBy&b+zv=buxXMO*Nt z$Cb_I3ek?Zu=l%s*=YaL#6}1(PumH9r`x?Q$h~LITr#rbK;+5LTkGG?zcTdy00t=F zfLQfs;DHEcL||wp!H`l6we_~rCAx?W#LXM;pC4oHbuB$QcJ<$)Pg9csN#w& zw&)^i{JD`y9B0j>&`NTBx7}Rr>1dcIP>?4c4uJ7>n0KBe35+jEDpt@O%`|xzeDVdQ z)MS|$_gsQpcA43WV1_B?mofrwLx z74mtZQcRtw=Anots_3GO8g!z?rFMxW z85loF)}^W^n{NLqC3uZ>@&8X#ddctXvZ}}4?x^{)92@v$M!3GXS5{7DC z=;?SQzwuqt60S5wwkx;JA*(Qg;x_CsiVH^^@xuhk*6g&xUHELZ&SLBFP}&wp@yH~X zZ1R{ALnI?k@u>%|zx%$t7Y?D)JE|r`_RF2iGN0>7z&zEI#=-xkY_w`8C#|$rM>l=u z$QIMar*78bIbqdP*JKP_APW33P{bL!^w?yVZFY1{tDMPMY24KEx$v5rsV`BgimoR_ zifS{d{~rJ5cVL8hSB1*^@n;| z$T7yE+jJA49cLXj!jre|`s=VGWVuC8r8Q-StsIPsTcPvu7Vs?A#}+{r9dp%qB{3POTxdfJ%6E>etQ$+}B`l+x`6X z*RM4A8=aI%CYQ{*`;X1wN4sQIn7tIwc=SRZ&yMu2|D{TCL%~(`no>0UY0rKb+>!-1 z7`bpojeXhj7={D}!uG+hC~w%rCB&A&7P|0-i{c<>Op*ze=ytqecKB#1jr9o-Oyh@(^J=`r9@pdE@5g+8yXi` ztVCWATv6Mcg-qwU4}r*w)LP#bC3HH^p-zN^A|oS5Ny<`|#*qiwU;q9Xx9!Zr4S<*f zA)H~1QrI#WqX-5YCNYUS-b{#kNs>3J!52?Bf)SHg1r?|uiMmXJ4uwfl04q62p(v4Y z*HaEEn`X*xUS^v|gXH+$gh@GRXil3?0W7xJ4nF;Y;IbqF;5P!W>p1gjuWt2SRYe9FQ@GUoc`0UBD=k zGK9jINWuuKh=Cnuu>(o$KnpGTMJdwYh(k8#o<^(Z8F7j%NHR-mVzk;igGv*P!7pSi z)TvUJ%2e6$)Jtr}Cs}O>rFHd>GYebPm6Lvs`RW!j4zi5dT=p%`g7Hnt~Y~oXU+SK|j)=S>H;>Jkm zPMK&Dlyo9#P?4I=#(MU%^L*^D_$So^T<8*2y$f5v>Ise(f-V&O>N4YHM|=PIGOb{p zMKFHxySaRI79yPzdkEtRf8bRpznFyjVPj-p5gGqnZT3&FGDprD z7v+3{8l8`g>f=x*_050|^!(z?Sb-qfH>kaVmNDhVc=RdW8%YVE#81ng&f+7wMl3*2|9+gcF3^CcQK+0)h2k} z7?_P}XX^QR&9_drvdflhV;y7|$F&W4w}z=XKw3P-2!gh^&24SNfggH{a=j3^3Luml z3cnatFy@d7HsnGRsc36(c~{p0{tncPVa$%?6EOV7r^lz2HL^|9Y{)MAMTDO7NqT+W zISsPddQR^fJk%~b6+37vQK3l&e(;WaoMHu6m_dx2tv96l41@on_Z;#D1WoV*6y1)w zUmChM@{lJDZUDk0W&s38009d0>ZK-nK?rm?Vitwi4sU1ii?32x2uI&9UII8k|IG#E ztIm_avm0`TeOy5FZB%$iRFigD6361z)5VG6C$+DgL&yHQ+~;nxu1l<9{)p3r5+}T} zK5s9efJ4l;J#*uUXUcv2i+D5vj9?(+AHe`dGBjc3NdTQ*boEge;wsR+6rvP4g6mgd z2E0yr>gsd2fvGoPJ+9lmKXhmDQx`?!jZsT<==C*GIUD=l`#xN+&*?z&-Vm~m|aqFF5u$2mKbt}_5+EIRf zip$X~^*?mQanc0e>%R}pHWih*O_WdfxDjzD#}G;S~qIRO-= z27j)Cc#U=!j|N1|#|Hn9X`-@tiC2B&VOs-6f(i5w|4@C^_ZF|x9c1+j$@B|?FbBEt z57nS4w;&2$RZPd%cSeMK@c|-+RDYt;fCjRFUol1ew{Sp3cH{LES(AG_Mkk>2b|4dX zNSK9Ms3t~uG!J-5spf<0QF=o(2mGLdDyU_^KpyUL7*`f<^#X@9mp}!!X~6IgPS#ed z09S2Q7jD28!LSPKwr)hU9lY~9ow7ql;v-PP4|V@@da3sqDn^9**M*m}g^dJ0h%$D; z(K!@naZWf?M>TDK;&$#OKbV+`s>mXim@;m#3IA{j6G(w$h>gTl2W|8Rzx@`!%3Bc-<~|L}lGwwM$6^x6;5!VdE{p$$f+^?=0eOZ!l7V-`2AV>F$w!YW_l5;Y zFHOdfOsR6m_#=Q*eLSg%6?sIRfD>w#95TrfFgXx+HzvH+gk%RT?-PZl2uemlfPMB} zUD=jyxsh9mCMKammv95g!<5A|7=dvvKxueGxjS>@kb2o9fN^cMC6xY9m5I??=plyx zb0m(57j%?|Pgy`eGY8AC2`GSF#}Stl;g-%OCgE6)4)<_oxnp@Yai7yJB#C=$`IfL5 zn`q;iW+Ee-uo4GBRdyMfhe(l%SyubFH-BkwJkliD!JAXU7f1;Nj>tQuf&)-MJj7EZ zy(LHK(If*2YN8?p^JYXlQ;~E*b?yIRjEs1hnTd_G=9!>ra4#~N>SK0i2XRuEUY%q* zsF^jFpm7>0oBY|ISwWkRG7PtA9Rv{*DHb2aNjEyVj7GUT#T9Oh2T_CBDe;ncnG!rd z*ob_mBhU#1H~^g=>Y-4818%TibI=K};tl`c552&Xl(%Wu#vRpZk^AzUGLu7nM2+Z@ zZ_6+Y=&6*$|Q8m0dUpil*YX<=Hz7A-pYn`M=O zLfM0RahyJ~M{0hunKH|46AT_6oo1{@N;)G zhNhP<4oP~i0yyLuH~Vx6`!j2&VT3~eiZm`lXaCovB`1n|rW00}Nv|oTn!2e}L8V>t zg;$CYoKqXRd6%EUe44_8zv+JeLvjYHWV@*&lh8~QwRy8z7Ze2r%5()nFrua69UTfp z-1&EZGe-_2n2(txh^nZI8gh;LB`p$`t(ip`@^*Q`q@V;Mk_r?lgsA(;so)x}9^t86 z@`^dJ5LSZ}2a0l)A~<(QH(bg)kGU5}LVW7An!vUL^r4%7>ItRb3Ad08y$}rOM^>{i zR$Wk{cmbmL2BJVv7<)=Dofff{Njw7ynZJoDVd_86b5}nKq;2-B9l;{*=^NKtUgmX@ z_c=9GSaFxMl9?*5GCQ;5O0Eb0GMDG75LR<$c+xV>Fpcp#sI0mj_qb?!NM7IR`c zOdCel6_MR=nE@1q9O&N zcQK+O8luoiqjRANuxqNsS$fUGv6lG;F^~q#3YYgJvMN%0CS<91hI^E{t$hYh-@3Tg zJF|`JsLytrHlnlHQeKt++di1P6Zkc>OClJ>g?M!1wyxr;@N-R#;k)lgncL9}hKMd7 z8eAA9yL-y89;!SWE59;xqyE5pOa!uO1ez#9Lm~1Hq-#FTD{Rp_fJmy2`Pq`!o530^ z5ZT+22JwIcN)!SiAp>|5>{Py|R~I}vHx#-%&G5hgc%XL4zEG(yuY10k!kZ5pTo2o6 zJ-nwv02l$hriRfY%LBs!cfiQuL>mki3``+?$1aw8g)6(HRg8Pux~+)Y#9X|%9UMLd z0jkoQXXD#Wvbaz3nui(c3&t?UuL`RI95<%2DT_(N!&vJV+}g5J9L}Q5IW8MIRE2Vn`NE`H6YzA-q(MV8ayxuy$J|M_!DPeyfP(x$ zd65akfEheSa+O$gt?V>G$2%I~q|RZya5iyrMEof`BALZC&yx$z=2KLkP|xB2>=tHc(s)wFJhnwOaRcr*2gYSuS6W)=%pi%nN(OD2IEi@n+mutn&w9el zS){JHQOio)tc8Zj7GpYL7|hAJrb&{;aL2UW?8YS*vo4+1nhMjK(a8c@)&V#um#UiZ zjM6eumpoI_#xM*fQ4s?oBQ^8}N!^Qw*pyJ>3nBt$-E3zw>>e#ISt=6Uuu58`b2LQrwEp70e8#>K7r6|>%xKGXCqi&!X zf4x687>~1q%{@iv{z`=8Lf@@C$p2i8>Lp6j5x<|8@Ij7ki{9Mv51Zo zXLhasZEQ<{!KXdmFP+-Z>d8Jv+m}nzE};e0^-?dT1u)eFFy#;Szz+A^J`=~+twA7w z-P=z6w)0pw!6V$lrensI%wUAvi}TE{afzBrW29!;zP%T3vA!7UoyD2q!Q~0totl2q zHJ*Kn2uR*09;N23+vqKET7wfl7TY`#ST3~#78L_0MO|cI1gVe=wjc<%B0_te+X>>| zye-(i4Ia{@lkA-}2#zN>eP2V!W*#h?60RGmwus(2(p-z(8=K)fih@thAq6Aa>PWps zed1{Dktv=T?>vf>3>QZQ<4F`)Fr`Cqv=YI1?i$2u6zK$Tp+v2lc#A8yu`b-^2#=A>TUYhD&@o{|M) zI)^LgNa0ec@CJsp1HbSF7WE5dMg|)bdKh)1;QKjj5Mh>fA1+r=C9tphDUHyanj$N5N8qwGQau4FAvz&F~AO zAO|g_uYKN5dz~egvmpO%PeQw%YC=o)0Tiq-Qp=LI~nafQa9!j z%n5$=d?PAhHhx3LO#a0zcw4aU$5$gmQ#+5}DiKw-1~ zy@8HD3tZ%Uaq(eJJrq*7f;)xjC>%>$UJTygSxIniIff~BI2VrPmtMcp#OzF2@sbH8 zS%!j|!YO;&blJ8}jMoQLfI3C#Lm?h{o8$ z0p2@g%4m=8Dwm(!+rIhA@1LDdJ65WDBEB`*-XYSml*t-MM-SvTA7ifnzuRsS`?%L< zO-{lx5kbyu_!%6`8*VCoQ~Xz7w7%dA#lS<=Zv4?UAu3eb%fJ6n+WY{aL*T%HZrp4- z@MgzCh7BD)gc$LX!iW_uLVWYam@$f%{CN@*QshXIC7b<2neyMpGZQaf)HuuyL7Fvf z-o%+x=T4qIZ5{v`ROnEmMU5Usn$%6EIB8tIgjz9URH_W8zIj?TqcMM7ja|wL^HQ2P zaSSF!n^x^wwr$Y}y6?4|1%Un_*bpP`Bb< zsIl3c$9H}G^B0-la$m$n>OC{(OiPMVjmfN?UHf*}tlute%DXqli5aVpms(zY#Ef9U zZshuPJ;pa_$YyfmUH^Xmqy^{g%dfngE3QD2^os1TqZB(X#jPed_A6;I=?MHgR$ktR2W*<>p8U~2D@8-3FVIIBL2a3tag z6v7u^i2TnJ3aP{Dx|w2xGRoQx&|yXJoH}pE9k9A2KKZ~hPfM%R%aW@0%JgllI67Rh zO*c6!iLb&24AQZ@jN}Kg!ageOFTg}%tj@eD3@f8FHZjZp!#5XYv{6SNg)~x0CuLMh zOE1Ngpc!jCK+J~PgHJ&nJ$>jmG(7^T&I1EX%+CntXojmyGNrZFo>aVYzTUXx$}3%W z#Olml(KK@`64q3dQe{y@&{b9KoC8mP_%X7tKLZQYK)o`g$UMr}TsB;B$0fI1bI(PW zMO)WpSGE~B>Xg(^-RspKALTVws^sk4>p+oy5#kq5g2|JgU;g=pxK$e%Cmj2QF2bWa|w-)Euq#Fvk(MN%-vpeQb{3(dodGJ}#u zxo4k$20Cb=hc?Y(qmQoX-8X;|*(!`g&i5r$1v5z*U_YhyUiVFxW#A?YnWu zABQ}0$t7*O@^+PGy6G)7FSSRzA)30Rs=I3NFOnQtMF=;9NPQGf=wMw4vL8-eh=}d( za&60Zmy*g8m&#agEkni^WZ`$CccZ*VeQ5H@|3>gQ1)KR>h{7R8Jj2NtcfNb?zXv~j z@#W&Zd?^ju1m4V{{#?wc$J1zVAz&Vi3LF@=J(W2enIo4`kV(ZasIUqgI3jKBTgb%B zx4=u82s|W^!|}9|BQSC9DiU;vc`8_)@$v2dRS4pTN|wWq2E{BwK!A{t5Z8=L(1?2- zgkcP2I71qujDa`g4*Jx$KKC_Ac?g7`=SUSg1N~wZ4>RH_2Ih=v>|-DP09z`Y5ey(Y zq=mY}VHREFz~EspO&&SSM%=?ZPX#MjTB@PXiZh%5jgUDAEGR@^fsT6B6P#gCvX3gV=Mq>HWG1&$BDfW=OI`_+ z=FI5Dh5XT6bohng+yF2)(7_JDpn@X=;Rqc3q8Gs^VI1qk7$5+Mh4?XLFoiixVit2P znnb2f2)Q&vdQ2g_@&_5^wvkHe%U56jNg$A_2dhqesf=U6Pcp^1$q{vubHS-*v4nLI zV=60avIAI180Lnv73mWDvmYewxUFHxglFvpXg~!z(C>}YpamJm4x1@2X^N7OWwe@C zu(^Xvs7z34Lmt$?`J{t(G&bc7UOJ<46_KWCoed%Aqkgfv)WuVFLZCw`Uh%Mik?mQ7 zy3iRkp`kpc)TciMYEaGPQE_69C?acU)84l+dwqp?yU}KWZf6kJyNL zr=)j#=2yiMR-w9ybz_^vO0`CXz|}5nU65+_%CjZJ^|Y*a#cN*mDx$4s(jWfNc0;0}-6O0la4cP*T4rxa395c!%Zo4C^v$p)fDN_!-~m0)$#6g zqiQ>h0*gynxo&ou@CHHajv51YZVy&nts|$v4mHGobuX?gxNv%qP^)rr;EN36h zvEE4Zi_|?*uIRY|4$kn8Ou&UUvIcgrguIn@K$CPK;t1%kamjO+9YxUKiEVRdun2%b#4~c(BbI_Gh|zYb{yt1|As(TeuT% ze)rqop;0&6j*V>p^qh2&6`r&+W0EXQWg-)lk>GYky$nLEncSwXI481w@r%Ft+@*3c zW&^I-{ghYIJ^J@%kSkr?*gKoOK1%OWK69GaJmw>}*k2udl-y`Ax%PTBeGo26Q95ZT zJE5`0tioN2bKL1qhdP_zd=apu!Qmpu`BqCFQjyu5E}*6Z# zbMbw}1#Bn%%aliB3;3x!EBii%8bA2Cj@Xku*%+|5s69cD1NLh_j@vd) z=(c4b27eGW!W%&*V7z&`gf+n=2lOb`aJU-tKL#ucyzqor`IY8-KF#w71Z*H3G{PgK zAsW1tfm4fJu{?#V!0vOO@-x5L(2UxGpxfAlApearc1biPJDr$>x$_!5iI}%Hzd9xVzJm)^k04p+chQ#r{aY z^>f5wJiKh{Lf;F<7QDYmj6sJRN39FTxu6!izyT=GuSnWNI2=MzObu)-1Z~{Limb^0 zT`b6qRK9BG{NqTX z(nz&KHEW|yU#K#geL1-X`JXt}PEVu2FM1hn_orKDuxR#kI5KWXu(1}A^`3$6F%D(hV zhl|U=)WNr;4XUilk-Ew#bf#J4%C6)IWnsyCR7>pIHZPpa6|=TuB+O*e$oa7zAW%p_ zF^r)U!fMpZx!}vcR87_FM!|GV(A!LR0W7+}k(I;6&QZ)Ex=pKiHl#2_a{0yo-n_JG;aK*Wx z59Fdd=Nd@}^CqlN&y7Gyc~nWCvAwXA%*kA{`*ca2oB&~F&E{V^gsEs19(ktBrLC8|I{CnnQ>?VI_bgQTd=W%-p5W|9{3HYu^frI6wlDp{QIiAPs{>M{)f=V5I1v<_vaJjC z2VQK`0{{b5^-)4_ghCJmK>!3m5QIW-Rg09>b?vQaO&Y+`LnO^b4b?Lab)UU6lMI|v zDwPsol^j8+&qmeKfi1OSl><4*1VN}0cZHHV91sH0rRS(ED5VPjkAPMf8HzXc)|Fx=W?HS)AP+orN4M6-%G>S%XDbK?n*R&{U)K$~g?m z21yXeI;T;M5u%`4R82}k_=Kw!SC8FBSpwNYa0GLeL5m#Qvh`e3I$I-+SGfSWwbf8S z9iCWxQfG_4eRWLp@z=+(y*0o+WgW&wOu=x=+eH-GgbfP+U=`e(C|7RhW9Ly>TSW^=_ys!% zidE2p1JHt5kc0y;f+K2zh4_U}=|1`WCL31U)@=(Zv)jJuS%S5;PWZOOD>XZ?1MHFn zJCFqIvgGW#WKRC%HVeTo-h=}liUgj}aKu$9w%7vW#mn%^3%+13p58S81dG((q{Lo9 zuw^qATX8J}Kp5ereB)wC|9Tu9|tzErEJnYf}O3;E#)&eG&XPm~aoSp?O2<507WdlA6RA$AU z1RZ~#;zHAmEUrjere$8PgM+p`GUjCsuG&m!o&1N{Ai6430j4SvY`H$b?>S zhJWyeb?}FM2!7Bmm zoZh{AR$|`_T>XPe&{2;cO5Co1In3xwM&RXI2EjVG<-W|`tKP<}-s;n)6l50Ny`c*& zFakZ^<0G1dLa2sIm@f>HM>ERzXQO0HhJD6uq zIGAPl1yVEY!(POoF6E@yXPgU6P+40)oU|In3>`8g@@WzigjTq{Wf%r@=n7FY zPJF~}Qzr2yX0_KuJuoVAr~=IYxM1qdrf~Vnfn zU(0hn3eG^+TbJx|eT!_)jL=R`bj*ee;DPkjoJcpA^h&pN6QNa1?+owG)*`3#@yNSw z@pbr2=^RewVOnyZ%}>1@bhg;;EV9!K>hu+7i!_gQtR@6n2ZLMZc3j`o8JW#p@56{f z1v!BK2|G9%uEmHFzuUx{JIC{57pi10b?kb-w4BT%Mp%S!i)ZIl zS)G@)-R9o#_oSd;9u@d)FZh}__-{`r>Ea=R5!|4{Uo4>#g@10GfxU@m-TEPc$-Ii5IOi49*>@n z7alSSW}4x2ngwWn?j6YFt}XM0Q~Gdj_XHdD;mo*ei_~dRK}xMu z6@57J(R!(kRjfFGxjSAdWc0M~PP3=^v={vl!FjfahzGNXw`XnE4hp#+>7kDZGFXUJ zAeke==7qR>yqEp|Rd|EUQ?^f^iwWJ?1WSVAclzTj))PclJ|9M_Pd~Y^_ZIQokMRhJ zS8-QIim;ve(dT}?8q+*HebW=IQd0PMfxFjVu3wmiK(=OUmV`j2{e=+eRiNWQrZ9~c zNB=~$;^+VV2Z$t_GOZcKi4c>73KueL=GCDam@;S5tZDNm&YU`L?&!JW%_W~ghY~Gn^ynpj{xY@HQmBv?FgvGG zt!niu)~s5$a_#E%E7-7N$CAaV@+{i4YS*%D>-KG1H*SU*d&AM^%$^5!+!eZ)uiiI6 z>v}wD`0!Bw!N%$$Zamb;FEWKL1$(n&)v8IC-jE^FQ<9M#zZ{e9`Nr6=Om3#aZSDFs z?AU0_(ym=Q3GUpwcPFVc(BMIe!YRH%SbRA0hlDPU(kN)^$Rw|AQ?G9Qy3NwsNhe*3 z{X6*Z;>VLOZ~i>`t+Lm%Z}0x(T)K93;w8FQ@TJ8{{W1Q#owQ<%{dd?ZF^IMaI_LzG zpgojXwn}KC?a;(50~&RjKf|oX+It;(_~A=GL}z4SvX{OO!asql1VDLB$G`#$q|TAO4;FDn-JC)UpNhQKz_#T z_oY(*LHRf2Q2|;;reTuIGD|7`?BfqI{>+0+Fug1mjDb6lu_l_Pou*+`QwlmLTu&N$ z(}{^Hx|?r;#JJ*%EFO1ULd#qfsYJ_h(%dG`A-Y?1DjhoNd0_(C(Et9XR!x~p1qEjFK5J9G&qVXhWsrm=@%sMKPcy%FJKuKo!qRlHiuE3UXM zx-GZ3`IZTAkYYLr{9;YCOcHBOBq=& z!37(9Fv3h;yD+c53YMjRTRr?2P@DZLl$risOccHkZ%h=1)K<$d$si^?YPTt?JWxUZ z!LbXGMVu_Nj8f?O!;e3fa`G}nnsVytON*X7^iJL7+Z9k>as;Nv9}DZ{z(h+uHPuyH z9aG6!gD97LP3x5vP)3cJY{pK%>b28)!29 zjB>o&lA>@M-jPs0`g62b6&tg3m}V1I-XPyFZTu$;^wZ9&(3{xV(e4{?B!-;RlIoW04o)B@zF~^ zJ@stAemz_9T{*VcQ;Gf&>8I6&_Qzp2Z?eWLo=%c?!Bv|kNyxR}B zyPLp!K#AUmu%Z}^EQvc`;+`kK1v0RK(Q6+BRZ^wxVaYz=+tN$+MZpV_O?)0JpO+Sg zIt2a%HLP1-1li}n@W`))Evy^v_9w&P1g}%MSs}fO!jS@=ihQP{91eph#39})g+|nY zuQpggh;a}x8vN4t5ZA$9`OsC}0TX{xRYf$d4l74wUlE9C9T$?Zj45*23>Pvf-_0;^ zf)IxoX{AFhnaY5|QWXM|mI>&^v5$WIBY3_TL0=^=BzS3w6ZwTj{s5~mQygFOLP)HR zZP7yFQ=jz&$vHsYri`BSBn)?!MuzB*cZA@F&e-@eb8vE2U)y0FPnD|w#C-5$`SDIG zbE(T+UPY7bb66v5f|xNak7Xk{uS6NmyEM}z+h~#`HJmD$L*LhAbh2T%$LP5RWWausesb({7Y>6gB^6&&Fi989;?vC?j*0KJ?*z*Buc&lmb5zp*bbu_mY?u6NEzazYjdmH9f_7?NlYtF z=V;cB;OA(V9i3(&DY+}+ON%5N3?_ToTWswXC#StGb_Jo4aIrS2#$jW1$#WRRMKLUR zL}0+=8s7D?_d3&E7%=ZS%;09}iLu0>O#c(mp-_Pe{Jnt@{M(ZoP=N_IIE*B*=v>K7 z>!6u@ub|pX6YNsB!nk3XLA1$N31g=*AEnKCOR887leonHUWD+j>Iqyac5jJ(3MsL~ zI#w1BXum^ALpGK%3~`(xz}c_{F^2ID|GEMkx5!2_0DP=P@<+L8GiX;(JSY>x#KKm- z@?JMgW$TPLmg#(}v9!A7F_Rf2Qr1;HWn#hnChnG4R3Zk+WaFX`qZ2)0L^gKN325|0 z5&NLR8^9spX4rXh``N5A)#jBmPpQl-xiX|9o#p*Gy2Hm~WNlid!4Pju%$5E$dl@~b zunH5VYu=$v12$FU*2j`;EloLGp@>Z=!XGyP2P1lN1$$7T6T|R{D1J>#Fgr6t4z`M@ zK@>(%dnD4%ezxsY`#WZH`H%%P>v40U7?EC;odO;IF}1_p*kntI)OjhaS|^v*6(?7x zjA<%}7bRkafEqiueqU`Na6C&W*-%7ic1?x+_(b18`S*|% zqoHFXJLK;9IKqP-X^>zTjly}uGXC*#1KtHo6t}o+r&7%QxcG-j+2hi)zDu8b=(oZ| z_e=2N*~ucV>W!K6c5dMdR2d@%m&nEq-f#(nT;g6baRnH{j^;7pX`z8kJfTBHp%i){SG)?U z*~Ve5ihfugcU&EA`Jo~%$sE3g*JTIxWspaxn&{w{=sD3EvY{d7+z}#SBZf%y*`aCS zAx?mx9hA{fCCVa#MFOqbSnP{c`NJl1$MdM)D&Aswd}8*D+=`i+1F}RfUSiY%NG5Iv z6hOfifZy3UUr)uM9O~k1NS`R07FL)d?WCeA;vy?Poy26^A{{`#iCD*JBRP%-G^T}$ z(FfQ8V|j($aS>zbSqKyuf*(Nt!XQ8bB=~_BB%>2K-|Cb^Se&CuESoe=V^N{OB7B7& z77jLMV;448FlGf`cv=6M;g^IXdU0VnZe&>qX$*C1Xy^a`=Fpf5)~;PKtgiFPj-bh@VN?51_14(HNnJB1|?URVnaIQ6f#+uL}chtq*!QyBuIii9ROnPfEHlJDrf;2V1^_> z$PU;+WLl9_QYB~V#9YGv$1ohA4MvO1#=x}+Z%0u&esM|eTp83Q%! z!Y-sGKEfnFGFVNT!~xi3ReB^05)W?NC0^1_PtHV8@?}*l0(3^_B7opjbjwj*q_dR8 zhy7wzXu&Tq<}BpPFMx&}kbyGBfDu%PB#=Q9tU?o5(F=B_e9FXUmc(5A1If`?&gCGn zT*X&9nLMIpOTH!)>;U*d!U1@}C7?_B-DV`{=1cZwK^dF-&}DD}WLA7;45rLoB4=_g z%5v(2bBd^RmS}WRX9&s!hkD`o>=0^lg{hnxRv1AOaKtQd1TtJgfk=WD5CxA)NT)qd zBF-m~npu55qJDD!5sbyyd?BD={2*zx=77Scff5BiqC&b@pufN*gz95V=3IX4Tuyof za7q_WPT_~fA6M*UO_->gx~X42+KS%dV%m|g#1;!`#V^c4jcS1%#6XTp!Y{1CFTCf3 zRETKI0-*-!I2Ng+LdlVi98@NYMKX-j`rvO0 zr-gPznIe=fcHt*^XmW<=SFmYIyeY2c>U5H#-1uQ(9oFL=%j0kfcUpya9>9$rfFyWC z6O6_i*a9wC#%NroXE5rJKI%pu>0H>5)FyH&K6gp4QAVYRxp4RF8O%9$$9aXR=NBja} zu7aSF!D(CqG5o?m@WXfh)3kPm*~BNduHt7JAb{=^ZGjADfu%7DXs1$Xyq=C_geoNT z2^4q%%eo}I5@Py+;;I^H&)NjO=4%rM-AC~2bp$NZChbt#rLX2Gu$~I4#MV}LCmGnm zjpBzh_(L^RgEu&XH=qkLyvb#*XQBSkW`^t(j%;WONFMPNacOFlq9sR^tIIy=d3gao z{!7i`t*PRs8^k3{2q(~<=_0173mL6=B(35uE_6O2J1kLhg)VXCc{(VSdHt`V$mQsx1jA z>%ySg;%B!4NVqzU?5gaLwB+3CV=^ua<(@C^md_hB!!RU6NVKHzS^?G&@9~}^K`Nr* zy3mM3uK^>iI^g1#2&M=TW>s*bzT}5-@f660FT|M5%LN0SP4U`}>Vz_I zBxi93H%|=6EI+oPU{Jvp*epJh0wj;H z8C*k#6v7i^uFv-DYG{F6xWE%UfhrI}7`U=HLqcwXvm#sqBRm0P)`3G`s6cY0F57W0 z|MD*f^G4zq!h%@jwAfc9@e{jM1v7JXIrHmgl{Yd{qG@sYk_O+#W>KU;P#8lRgaIrR z133Q!B)kJ8*aIXKgBSQiC_sWZ?7%$iz%ZE*=xJgSr#Wk>m;2uCWJi$5~Kp|uT zRBS{MKtmCLLl^*qA><}C%q=xQf+C256=VZ0lVe5C4p2sCdSJ9&YcxmVS24@dQ=Xr_ z98C^lb>f zVV|@|{+0{Av}1HIdvC`ZJm}0GMK)Z*4O~Mr7{Oos!wzJ_7O;aCq%}X_GbS*!DHK?&qv$60J zU}s9V-2CvrO6SpDcSaMbP#~rqG{Ipt!Lo9MB;+_p*ui>ogc1Dzc#USIcN1%#YQ>Ub z(R*8AVV}29rMG(fV{N&2+k%Xc%&$=}!af+mEnLG6hyzXY!wqDE5%2>Q3WvuDfx0pX{dZQhKLG!Y(*tuh&EXOSBHeunxGu zwWo0yKqw^a@0mSn5)@vh2M|?Mw^w*Nc0VfW_QYuLgEx5p!!ImDCLjZ_kb!cN zgkXgr7c1p)@1Yg)w;l4X-|NrDF&tA(db?D~n(ULSCb4szf{hT~j0F=Y+Xi1-hsEqZYZU?|?cu!$16jKTJa}I0G^~ zL#h-)WyU~x`ZyUd`A6G^;|L>zm2|YDu}|i>t^tR{QsIoY^ZT8KlfuzyGg73${QqExam&B{HH%^6JTZx z1jCzPY&B%qoRSp6`NFViEF_;j0M z({IEp^P4q1S+20FV6%bzqe*BxgueaAqjJcLJZxCO8tX4zZN5wFWXqpBr_%)B2R@PN z^Qmh=Ff{)!cx^T8gE9O<8Yq8cNWu-ofO|4u_G)Jo<+`o|{~KGVsFeTh;|l1D{^+|} zle4rYrv8mR)w-4c>(-@qpb}j)maI^+XVIoryOwQRw`0$R zl{=SiUAuSjqLd`*K$Bkw{{36_>kXk_P2T*SrRBihCbRnf%`5WFC4c@d?U-z|a>^Z_ zL5CJSnsjN=mi=Ygyqa}u*RNr#3@Mvs$=b4G=SJC+cW>Xnf#-BH%$Tt^Kusq%eaYBm z=g%)2S3aFO=r?bQORv72J80(DyZeD;C^@4YR~TI}7UN8lW}nsV$oARGsa?aY6}lA> znhsSuAi4=7jb!o&B-&;xD!7Zp>!^<~Y$9;M2`Riyw+k`MP(#8%x6Z1JtQHjGim8S#>2mRXwrIN-Pge);UNS*|l;m09@e>&6^eL(Q1Xf&%Tr z?w}kEHPvXW(#k6{jA*2mwp^)8EbppN%rVJq$&KNP+YzNGtGfg>=rCgw%ImUwL(V%# zv-3{z@JMc)9n9IGlVNta1@`a#7b^d4&SF@sIiTaeJ}+hq5yf@w7>&C3PY$+NA<|2mQW>E zTyQ}SS!57DtkvYKUIWW6URiFLEni2DS>~lgLpQ@WGfR#&?3jbj7-j9HuG*Q2E_yC6 zwfvOJZjJ8J?p!t347%o=NyFD_>#(bLYvsU`QtLbQ_49_z{spZQ?EV?1j)?f# zB@!LLaHBsRZZTDdOjZa^Vn{^dsA7`*&RAodV)6s(GMjGPaSb~h>Eu~&y-;PRT+Uqc zMPPp1bD2+jR=3Zd#kyI%+=Uam9lu^~=+9yI+@)@LGJ5gb$CcVRp<4HD?B4V2TD#V- ztBg5gI=Re~<(F@UpHBY&S<=l*iq994eN6*rhk4!@hL{+dG3K9ZMzKbRbK+1%ltkKz zqn#q$xCIdN;}ArZI4T_Q08T6RP1HVQGKh`k1b~C62=0OtI|VLqHIXCP1fIY;z_5}~L>Br?wvMeIazrboT7jizkWVcRgy z#1d1*WDp4aTL3|l6H%dYfI8WTr)t=n7S555PH`Xv9SE)p?on44tm7XyWSz^nDTlAo z%w>voy2*$TPCq;UNe?}EnM|w@kd?$zf`Y;=nZ=Qlz`5b>c(+3!LXuv?t4{IUl$}l# z@rX%`;wzQtJk>R0d9bwQE0H({Dq2x`8;Qgy+l3u}fYBvYNgOB7D3dfY2ypv5TyNgk z$yHgBn$-kKtYkGJ3I6JGBH`mVSL8=)j&n6T*b#IHnHyv&a%ZV5p$;LrgV&Lhp7n%^ zH1W9;bESzWy)$JzgIT9jcFiBG%;g+znNTQtf`ratr9vTk%Psh_iqZ>>Fp1d`ti&V? zRVjkrXqe273}RFw5g>4^5Y2pA$et~&X34g)%?Y9boHbpGI9;04r}$$es*_$J^CC>l zFl$-5u^Bx7AvsT-E;Xksb*h=r1j(2vXh}4Wo7%}4pDA4v+m*YK1$_MTZ7c1^v6|mo5BC@-W2(vhj|<1O^@~NQ5{xE@_lFhs1^?U5t?R$SYxW zN~osz%aKxtRu=`bss4vPo?6X2)4p5+SvX{+l zsYjjaQE&FMmp$bw+foc0@rBm7%>=QJ;~G~G``N|54^D7m8P{NkIou6z@oJ&}6-mfO zRnC!Ssz4(N^GJdnRDsuV6>v;3=|dc0o_LUv1r1<80~!>)s~Jh0@&{JDYyP1RN>l&= z3gE&!G!BmvP(T16AVs88vNsSv>ExrnP-Rv>6es0{de9>1aafMx%kMrYbr?q%h5?Rb zbU`Fqa796C!5CN*q88w=MjVEM^L*;uD84pb>P$B+DxyvGJ4Ac`Raf@a^H0jA3>Cy-7d8Sk!Vc}uZW9RM z1r%@}(2f%nLCqLJ6$l{-2q77g!5(NK37+5rlfcZ9z#izWx;%(5P~59ZGjQ)fDzE| z7Xr`^g2564aR2(x|Ca3&m(37JffP=G6bu0o^d$_o;0&lh0hu5h2tgL);0-u|3B+L& zTwxPl034XW6*}P-3{V!5p&1xr69nPzlAsmpfGR356L7)a3SkrfHUTR>DpfY(@We!= zpoR-q3!7pl;s$I6#c@S!kTr0yEp$+Gc+eZ`V&iyfA4~xPsNn~Bsve?14M+k34uBsm z!VRJjLr8~7K5VFfMrY_Eb#`sjvhakq&>dB+4)%czenJcEfyK%}3+(U-{2>ngff0zn z1)g9ZK$39qFpl)_){tsi*aeaRk!>U`$qW&S5b?>xfa)Tl82lj{U?CEettb5;6&S%1 zl?@M8fu!OuDML{a3IQpjE)t*;DEm(oLlF^75f%I34(T@e<| zQtYl^BNC7a)@~V+ff^y`8Y_ewDTFRR1|k{DD+H`%$k7h}%JD7Eab?nxMgG!7+7U0q zBINwR;^;BtM1lj+fo;R)>U z0Mx+^Hh~RS^Bfp~4EUkFA_5#n;UqiB##9p5Xp4tj5+wrhA3P!H3=s+x(b=f37y^SI zoYOg}0TzNX7;M1|7~vQ0FBl@>7oIH`;_v=`0sj0z5o`ewqLLblfg1MVIr$+QG7;LK zjTBGO5VTS&y;2nqz$^80KjDBR=D-WiU<(ZSDSH6VmNuoI&n{_ z!BE*VAz+~t_B0Zl;UC)68PLHQ)&Um!Ks!+Z7GMDtoB*`9d8C{^(bzYk22I8jutNvX&;hRBnY*qQX9J^wTti1$q)p?9+ZEMrzb?Ew`) zK^zdFW;Y@c5+M~0kRwj-9U_4Z29yfqAsfVj82Diy)Zq^M?hXvZ;To#3 z5XPY##LF55k0mrBXb%q1#KhI!cAS!yD=q|9(@|EPw&7|uC8Ad1z#)LGR#}ZACu-Cn zW8+N_Nm`@ha91PcNFp>YSVy@vH6U20{{SHyVk;T0A#V==5TF4Xk^vgp3)V(q7=|Gm zMj?L*cS6hshiFDl=*8!PlO))NgNX`-{6TV+2w<(QOr0&-=yV?vVsn=bDnV9ttHB#2 zEl>rO8mM6yo}m|{a}Wx_78Jn@`XCi-;r_7B|ICw7@8EV(A>)3qd?W2SPXQ86k78jq z4}5`QL%|@ zz=+TGUBdQ)kNJqTQ1^P7v359W|Inl}=yG~(wBLQaj!7Iff z5io2QL}C{V0Tudy8VsQi{J{_QA<9tU0K~x$5FwH+Z6kJp4cbBMz<~+~LG0wA8M;91 zh+!WX0vZY-8K@$ax#B@B28LSMe}Mylo7s|N*;VgCmt8~#ZW*Y7dZ)AGm!m^R>%s~< z4P78t#4aS%KKS*L`5+y#G>sZqWXLX_`DtK_IGh4XdX9t^*J`lYhf7U4sDR4)pq$US za+^4wqbw5s)E*30o#Pm;|DAZRtIiXn44)%`KAU$^_gT&Kn0fmE6u@$zy^+=#o_cz>^^zzIn5f%g24yu@fqT)YHn(G=Tt)(GTI1H3`(`qesKA76Nf^1c zdYZzbt35_)bi_`6m`!v|b^LH^&YGB&xiqL?3%npJzfvnPmXYC^+4A83o|3Mq;T_ER zuF+Yq#kq~ed7Q-=5v+1P5qq#>b|Vl0u`yN?0y`8wZX^5w68OPn5dr?%x(_Z}KMPtD z65<`QArkCiBoYP@{~UXgLmLtlnhnaK6Xbvi)?f|1t=nQzXIXk8)NMozPlta4fK0U~ z^2oXYiMNHkM8u-FH|OyZ*vJvhx0Rej{~Pb|h`ZTahRKb6GJKDT3bu3%O|PYeVIbS zWz1FOhI9m~?UlBI=Y-lEt=~Lg)H^G|vd;Ov&fQwjmrXs}G$GIvV-Xb;pY6Y$xWDs{ z6y*jL=70*QzzD+N446*Q`?z}NI}h}rKoTJo-eFDsSxpPo)8Ao=8(mTl;0{niqp7ze z=D>RqR3vm3Fc|d4ui}mF>NkdcB`y@*VJF#z{whv_*`-}Whx+Juh1!80CEQ^WI8Oxp zK;x89L4KoIEg00M+^9Ub#JGIxog#=E%8|<5A-%lmot$x^kKI$n*1&$}SQ4v1SV!D^ zZABx_|Mgwp`+e`VlCDGkGNRMIdygJoj-}A`^K@q&zIE-Ki))MWgAVAL` z<-IZw`e5VpAleXI4_@A7ua|j2ou%*iIn&fl85`qeHYHLq^lx@k&n_hrlo}o4S6(@)mCm;yzi)QGFKP!|T2Zb8ikDo=DUid}A9ST7daA6T1K*FmYRDc7RQO>Hl zJ?k5C?whwL2=NXchzci4tf(*#MT~yLi17ji3JxK2mhmI@#>fsPEL*yK z|Jf4CoF#DZuU;!Yt?12LH?ZKrbIlq)j5x94 z#f%#}ehfLX+rEw4 zv^mVYd;9(kJUHTi{+har@sSXLxZ28%G%umQX}pb(AIoJp~I@ zRl(8+nqaP3lwx1`l+{m$c)%VB#0@& z^oClTbTY>kI7~_LlviBA1QknCamE&Ngyq$jM!_)a+B# zKH1pQ2P*c6gC;EI>|;nD_AHfi&{&z(hd71+<5gH$`N75&hqZKtPpELROk0`w2`FBJ zLIRkikt$1e*=7qTcG_xxb^sWaf(m!snRY6Jr*eaeMiT0r&3E6DrTPd03aGKqKapvR zSF9nH`i6R18FL<~=vlX+e&;PNthvJ)>v!j#FQx;50)k#3V$Kry{}+FVug-ewcySxz zx07l9M(vkqj=Q)JrYmB2RJ0p!@GM3mkc{`{+Xsq9p-AICG)ANmz&3US(vTw^jBqpj zr2A6C#Q4+9F>`d{N+scIqKPX}W32I#?z7=XSU!c^M=`~NLQNk_8`Ta`?+gMA{S^Zi zQh}K`pfZn0fTJk$Fa(;GhKisSBTc?Q6TXT9jHSUMfQI;rR)9hlscD4?Z1BkzTEYpe z`C}7X`^?vhu(q^)ZiX~ORt#^5L&8uBF?Z{s4_gBU+MwZwx3Pm+AI(36Q{|0Qva`l(jv0AwK4#nE(b z^iQ)~hevG@p$cW#gA}TuAO|UoT;u`Quxtk*eLwe8o+fW{*^NLi+9=`}ZXT9^05uG!#m2ZU|5jFPR2FNMl`c9;S0x3Hc)r-u z_As(SXmkTcZ;BZ=%JGiUV%AROIH3RdR4+iyqfr;M$1?PB3QFzcANwQ7*vU>ZhjgTR z7CBQ6Ig)pg#18N(308S=QboxN>m6uhkLPj3M+GybDN(t-RkGv_t@OkzpVTBKJV6F9 z9Lxa(fzM>{V;L#*PJB8ph3e>m`k%$84J}e zktbE9dpESzOQbh*UY(@7%<9Rpf;e8EObEfQ=hjnd4|2YI!!niuzB#-SV|tar*s^lV zOeDh}gzY6-8s>|CETds`G6X58;S*AvA`ytlUs0UAk3l?8lTraiWf|B9C!35P{$PrF z-myVgXd-_!GlVbt5D8GQsVKD#3)Doo7$)qtw{(FEa$_jpJooL+e7>`CMbq3sgDQy6 zjV|1bNEbaT+A`fx#4Vc00W7!*j|~p*|Dt~NNH5mzrIH(OOtrFJMQvCy7d{t!7oF#x zicY^k9bJB{)$0Gs+FAmxbyNLlV5Rbb52Z-Pkh8++*~O^^ou4N^d27l;7I1_Rg*V2GnAJevoavoXLvG?N-ok(oVWM6WIrr#SvNpeN9j<~6qy zEb@DEW8};U-ey7&J~>05Z;0xYH|pdp7w$oy`!+$#98*Fxw52GTXqD?+G5(N76(}$O z5!~S&lm2c>A$+RH1-nr!ZO@`U|1DEwXXg^*RpZVv3daMvde&U;dS3bn_F5m954K2! zEo@uF)~ZGQvFvLX_La zeNIdr@X2FN$aP6gxPljM3o=BcNaJ8?UYG0jloN5@Dk=I2$HM~8#;D~0K8b`NT8{Fo z%RV@;uf0ECenht^bmqLzP2GYR(br73F0(IwRt|#Q$@o`|w_7@+AnE+4dxz9ax8j5` zjhMMl9XeJweiC0zUj*UT>*SZUt!;gPT$J4rWZ**;+z)>+Ji!RUe*1;sE_dx;Xse@+ zdfuT;JoJ_#P{DV>;{|^Q{~v)j2ie1A2hj|}@CGFC1X%$nwx<}lv=9D}LWji!bRtYl zrdgwR6`@rSPXQI0ATlCY6+yvfiEw%#R2GX-HIRS`2jCC)^m?`@L*B=Ok&y&ip@Ttq zLv=G7Jk)zfD15T~ z`K1`;_g}FA16>zjeZ&X3@C>#f3GKIQ?+1Tq@P6-SZuG}tT2+PNVIIdech_fk%tj(6 z!gm2EBQ)}C1*jrkumx1GIo;6=p5P13P#nXM2{yGDebso6flC_53BS|?OmGG8BTV$8 zf+G`pRdIr=cog%K|AKwcW6)hVQbb51yn*C6mhXVn)s2J z;fZV08|t=W8)%a9BtKrUl52*7v88eG0|_CxW*zi`KS35Hgp(um5<96iK3SBUVU|I; zo4+|2xW_3<$&^Sqe45dl!{~J+MK+K_n37XPV(A{eaXH2IkX$*4WO+Ktc{XT?M`)l6 zYuT3hAf9ch3-~xiQ6&gkftPy8muO&+16c*|`ImYqn1y+m6_S{R_!x|tkth;?kx3BQ zKnB~E7U?jN*H7Mgg%O_Ix3_HWd|{L zq(7vjORB8JSAK$IX{J(Pw{n$?!cyhZE0=SfiHaS@BBs|W9CZ|aXo@)CS)Oc~4{k~X zYp4TkX#zU%mgD)Bfiw&cl7CI`o_v~@f4Zl8I;aJCkVyar*nz0#nrsU5t&#CnkNP4E zSDBT{cbAH(4ho@)BB6rOC>1Js9OyB4kcx;Qmxkd|Fk>z zj*7#m`f-jaWh*OHMZ}UHRcROyD<0@trd#V9?dq=YDvxUlr;FgGBd~@pkQZyI16`v7 z_QYfC7kn!oB^~nczAPK3E45g3;Y72ThYY4_`A53rnyJf7>n{(}Z zbX{uU3s?Ac^L4a9}bJY2}mF5s>R*~zx}}o zL;wwaO9%y01c1wyi;%DSs~1H84O$Q={Y#H%K))~qp60m-E8qs%U}4z72s`k|J7AcS z>jSHv)8@ZAI!Dm+uwonbF@C*|y36Q&X42i)L+n*lh|G|#PNw2JTAbd!f z`mxHg97SNln{W`S`%4&_vMjuczW@oO&}IG*4D#>`NCLFK%Lc^k6TdJBX`m=boWvsM zTTI->PYi@n{FBehj8-gsSnQPBtY_}py;un>=>kbtN~Pe6B<1?f!m+k#{9bFko#sqO z?s^M%kqvlZ4LT49;4ln$aSfSZ5B2~C!|(*RunFn_$WH(csz3|&JD%s61bX`y_OK6| zpaZJV4w(=O@lX%spcjWsxB0L==dc6g@CNpv2u45*G4KxiKn37{9m60F5^@QSPzsZP z3;vMMS@sc_2f7pMsw{{x14VXMr_jj_RI^|>ul zCLEk12Plb+L~J9>HwIF|%0jXn$P%mz6d)*qaImvQLCm?(W$Uoa$dC-9pasG3!}}Bo zGuxWIN-EYIaO`pnHg>dnU}q*<{DU?9$@v5bD=*zy&(HpPuyjUUyaVTXaXR=HB1 zwl1K38Sgd8_AJTT$-d_N#&|&p@}~-fPz2!c1lOPgTA&I=a1AbC4?6G!(C`HF04U?2 z1NHzY`%nZaoe!}v0)J5izfB8numYRV3iO~4of5BXNe}TrkJw=jJHQVTk_|gB)1trx zJ0K1_&FYwWQ`)UtW~6Y%ecHCZH+7>>C5f|%%!Qa8kY*ekm98P2`Qf9)$j&( zFbk6K3w3Y`k?;$)5Dbd21(L7|zpx6DU@9y@2wCBa-n`k?WsSx-l$t>skxfvCVFFrV zx0hXwnw{j;^~O{v#-ip$9a5!Mx|O`aA?I(I})W z?cO`k4%lG~F|gk4{oXf_4B%kXmmrsukQMuo{}u9}4(lKf!{E5P#?(>`)uAkhd)mN$ z+OUk|;F1yH5-ua7#V?h~!5WTXnW@%mtu4BoEU7z+a4pxS=eio_6J7ulr|4!|&;&(J zHZIYNIM~=(eo>n-l-=CK2z=#qQ3r$oKy~0?g}@s11vocJ|EwgAPDw- z0Ld^3d^!#aT!)gt2b19RWFX*B?eq%n|EC5C1~I^qnp?Qv2;r_=fB`C*qvbsRiR>C8 z!X576t^?w;a>8(3;wyX=b8rVfF$Y~hH8TnckZ2g3ki_2(?sGPBwaRbhf?t_dF;MR1hc zyYS7C4ZNKR;NSwA5XaC^(7e45#BJOe59rMO1nocs2SATUc~E+b$87ltxS$L5Al~;7 z5A@&;^vK=Ia0bU_1b}PvIPdA89s{001xE1R^RNR~kPTFD33c$(rO*nQ%m=M-)VOfp z1nKmAP}Kl_{|an}yPox!3K0K{|Gjy$!{Cks2^B76cz}u*FMaMzq*&47MT?QLz2oPP z-$#%jsTGS9Ng_s+7rktua?s^Vm2wntc^Kan6g%7uLyYOV>$(1i>-h81^=+UK551J|A zz?cY~^SpG4;mhqiFZmO<%vv+7zHR-TzG<(LWa>nmwfVBWIz~* za6yMfVo5Q@cv7sVo*LCZh3=>OBm@Q z6+3XbrI%ay;G>jY9N|L}KB|zU3NO=CGfgzSM3av;*L)LA{Ma)_AcA00>Y<2EO6kvw zsM&{~e?sDCBv?$Es1H8@Mahen>U^m^n{YbtF$OaostBYm^=Xq${8@&RH|{c(39Pu< zDiJoWKvk?gw(z!;oOp>|f7H#GU7nf!1dCgdMZOiRh%%YW7UNmHAH;HBQ)puXy zH1$_O>k_);Abt}fXdyk3rPLqu&O=WjNwb@YCiyD%r=W;4UXLJSfcfX2zWk#LzyV7x zxxj+^{dZ-SfqIcBFp8k=nkQhGM+O=5vBP8-U`Rp-G=!WnMSAY}hn^H)s4tKdKT&$U z7+{L}g*DYAlMg$pF4Ijox32n4uGIu1YWv#56JwY5gosf`+olK>k2<0zn?xg7v{AP) zf>dLfY8vLI|CD=bdF4(EZtAJ1YPISLHe^*5615&*N%6ZF;-r)KM&(4VWEKC_A7THx zcXZ{1m0=Wj4Bp8v05WtcF=dUNS8HIG@30usz zo_$VYk$C5ozPQm*xBmKk2iJb6Ov*F;4Tj-@7(8V4V>l_k>zvqPf9Oj;{q{O$gAE`w z`S_px`b(+^ll$)5!}*3b5~7T3d_p1GxW)mfg$BUXA{$Qt%rJO|M$)~jSj__r z^rR;oH0-8&Youf)A%n#2b&ouzi;pq7lMwQik30iO&-*ggo%fK(l#-fB$ACdUAjDFZ z_WKxl0@e`z1;~H9JQ)Bjc>qiXlR5@;5P$fSK%$UrmriIJFV_&R8L>ejpr}zkI4QG+ z|DcFptRfhx@WUN`k&0COLLz+##xEiP3q#-yh<_5I#^P5gN(ysuh2s|!p&}J4ZXs5X zgM=R1Vnr(|gcDhePZqhTxlV+qa&|cY6UJCZMCMd5zvSt@(%6&D%<++%`NT4`k(p$W zV-X6$MLPWG)PyuuG)cI{A$7_wMc#{%&x<3y?3Ku#hE=Q$(P+!u0H1*sES2)rPCfmLgs7fNT+qfgL8HPA|Q%oN8Jj*kT(t|F9Wh zwehQAOp-EBFJOeB6JbO!C~{Cn+#wZ(7{ncnTL@%KWVwSt1}YS)!--OqCGhi`rPioe z?I|&3OdM6IPsKgUVckg7oBd^k;0)K^7#8K3Iip{8P7DNZenMi2)( zt8Ls#R{B+n>p zbOU+Sn$n~{TC6Ydu}?mpB$y}}7UR3td9G&D>y7TRvP~_pnKKQ~3A19nZ)>}6w zhy2)4KqC{i0Ea8gbq!T)LKOnKnG6U)2x52~f@{FVfH<*+eCQ(||HLpjna#WqAI!)J zIY7bzW-x{ntpN#so%6j9GNZD!GL-{)g4S#c+ZYnswrH4>BxvCtMu*bT^mH2|ei7Y& zu3`|CRxWcH$_O*$;upbiL~|#i&{69xQWkwr5x?7TOtyMohl91O?f%4Gi%NWNkV||g zV-?2eTGzbBAAZ3N)^sO6C*E$zPzM~XZ%lg;pO}X-GV=;?yn@=AY3foBpp9(jWZM-6 z_plG21WD#p@vBc6+%x5dVc;*W$%;3M57y!v9_S!&#rIrGYtb3k_}{|^!VG4BW;9m< zu>R--CyrroEGxXnz6_k}S;kn$Le`k0FrGOwp$dC!Vi}_V|5aXGAs{G2SwMt1#(>r! z4`LJz9{vzV8+4KbZSo=qXwCu3^YMuwm;t`h1dpLN6v+p7qKOk5C5!Hf5X_Gl& z6ADDSF|h>v&^Zy*Ilz^7HHG)BO>={h@61ENxkn2U0| zx3fNBk~@9zsLi=MA2gM?&pfHY zy*X<%17S7=wa?KItTA6={~V^q(mqP$K2;b7PzgU!0hKi% z1agppCX)g6i!yT91ePO@qtOR?XoCpL37q@C9N0e}@IQJGK!EEx4+;c6lQ#x*i6$tt zq(i#eN;(O|np{YQYQPdc0D~LQvxn)x;F_pDNUlB@gkMNOWN?OH2nKYp2UtjyU>Jl| zNUl4uv`|aC8DynXOSKz}#IoWjeK{O{NSq(6M)f-5OKIP*gsNjL-gT75@L|%GCNUX@9|9Ch`)V|Wl23)|zO_+yG%rYjB0dQ~v zbC8E|n1@avgk{(Vsq_b_EHh@fhc$b!onWSXpa)s>fgC`s9I(Y3!vr7@^}Vs@CR?G27f?@U_b@B1Pg>R z0~nmBl~_Ad>n?UwHJwZ>>me^EvPaJp!oEuienbw>5hIWxGKegeiR3BVsEmbFNZ5=` zY2k@&OP(`K&HP$T-87KQj1EoGw`a^3I{XehT#SgxLz3j1OV~iO`52T;Nm&}imYhyP ze94aJgfZX&9w<11<1w4$8Pv&4EpUTk|LRGf+(hmh1$Ed2ixa<$lLsbn0(lUSFp~%J zFt~jXhce3sH2Va3STlLZ3I6jxUC4ojxU>B;z8e#*6w!uuNXvQKz=Mc^3XDr&Ji4wK z6FW$SXYjLg@)Eq1r)cEMs%t1`SO>xE2*UJ-b9jbeI8l2jhEx!!R4{{nYN)Zxn{-qk zzp=q~>`hEsBf6tU&$LG&6eA+Ei_u&T%E^nB>I>1qO?TN%?AfW-35+W>w%<5N+3eDJ zVaTb9!f%t(+@w-7Wey-M3Qaly;HeVq$^EmMA7 zSjjlop*SmnS&wBI&NwxQxyU!Py3=vpQ;z)@O&~r%6;zRJNkYX|<~vlGoXSOI)P+Nq z-sH(hHKs|OS(*hESHOjA|Da0p0Esd?GloFES7e5Sn9hWlkykwcSKs#32x==}wgt|`<7F^hi0)iQYp_jddsY=vdY*l#lJJkR4gsZOJweIFs!J zl8ZM+l`_}J4jE5xDoVX#C{Ld*%7qgA1qx$UjpO7MX* zn?(fmH#sX035|hoD#oyJ0)@HPl-K|Ncx`tC%fv;HZG$zdMy(8$6Zb1Tw1N61H3vP7W(|7QqNuIRar*Mo6E4 z9)l#|PEMXp_+(gK3Ic|`e_&G=7S7QnU4%$omq1-TjGvRlF#^otkKu<(;0Yj3W<&gl zL1Dh^JXGCf#3N4PyMH zt3+-YcwECF-P=aCJA=tPd4n%7LPCZRJbcvTGK$hx28>vajK$@RQ*LROe%!_bj?v?Z zlXhiy|4V6{-U$_E;k=B)_E}ET;BMdBk$WNW@=Y@S*2YXw~Bg;5AfGWwWoAckA8hhwk@>_oFMCNE4mnx zEvEC@fVRN54o_1(b)up3vTHqtIoYhPzuhBoHsfY>hjmOk;)_1z-#tJ9uAPh~N1I8`*jjM7UjCTRy2pM1pal+kV5)|}Hc>6)Hyn%>}0J^&NYHgb!dD z_8#2Z7xSqYHnmgkjtTEBZc*8Hg(qO^Zu5ADbBpn$qE6kq3LhSI zrRN01J@<(XKLGMRfR6VGLLb?Z-SC!6bZ9nWMs0M5?P?}2-uy1gDE5bJ|DXi|w~4V< zg(Uw~K!?Bj?_C4F>MHC~g58 zc+q#iu5hyD|Gr2~}u?QaB**|1X46$Ocy+`sO3` zcTfbDd*0 z4jGamGbvRyTh&rY;-hgRpDG+XZuF=TjH8k!9Z5QAvQVEpE?>gDlkFY9n)~);gB5cp z&z?T-c%iamDAA%ukG?Tx%-=9K2cANWDs?K=s#dRJovLFi*REc_f(7?+N?WHU@MsZKbOq~-m9!(v zL2Xb|a>mC{!)Ffl$WzZvbmD0zJ%9Gecc5bsBn`?w%y4L;`Tf(&0gixSM?@4^G|5M3 ze8dMBnw}&H9hz@i(x-s5v=gbNnwsiAre;HptE&S=1r;|iTvSp_W#SaR&+(kQ?zi*a zZCrEJC9UwoGm#Z1bak>Ubj>b?m9&vfR@uALyW6|)^&P|2+IFd-tsuyZ`^cXDN2lPsR9CxP(CEAXI@+TH5dw zk&P^ZV;UR+Bg6qqDHMt*vv^(d(xBS0Ja|@k%0<)$`T*c1|JZF8OOLA-t1I~9QY|8 z5YkhjCgcQyd?E*3q);1xF+etu!Et=B!x|sw2uMi|BpbP0r#g3%Lrmh1d2|HmViJj& zq$+~^phhtw5ee40$_uap;Ov-UyZEuigpzy_Br6G>-wBI&nl#o`I57%T0gn^Odkgaj zqn6lEkMxw?{iV0w#Z?$;hYy3q#(a4_Za!PZs&VM%L<> zSkWh0$s*RXzNHSENJb_%=~l;BrCR>LU#gr%E#<`(f6p?^@FJ6#RRS}xvPA21#Ff2q z(ekiTiNzwq*UQI3mY2ct|DIq!BTNnvHnW<=S6Own%zuT)D59YzX-g|RYqEi2K)~kd z_yG!r1OW(zOJF#~xxm3mB?nUJ*y-|?H-1b|ox(la6!%eyAH1^@V~8hnWyT5f$jA+y zeUS@N2+$%~qo6|@=q3h=q-@l}6}UJ6LtEj{hdMM9NW8=*EK0;R6atAGr4|w(6jBI| z^g$xcVxa^S+=C3HAT1S?fN|yY8^Az zRH$-JB`%q2O{kHRL&79L7&*JJZWdS5o$*#;Y-6lol3H)wF|w*6*YnJ^uAv+y zV(PS4(hTn@)KaBo|0-MA8yCi~gIx=_6dQ|t=t57rSVSyjP_D>=In3&stdlWw*%3iG z&1!}Yja}3)V>GipYcZ`+5JqQ)&5nTm(L@z%qKO0O7SIX2Ep01Em5%K+g1*fraD6aF z0}mHM7c?$AmD3^Se#i(fFalH%wiMb)x6Nhwrz(h4q@sZ%8Jk!Gt65!#9)35x;5a}s zj`mPOykZRK&8U1gAqV#g0;B7lZzmAFAkyWx5+uzSLDm3i0(;cafGfz!a$r*i@3c-M zeQ<=XV27as^(kxQ93UKZ5tA^rb4t~tNe-cjV)%m^hE(y2SLfBQ(#j2wys@Y|yXJpO zMXhYrF^_rd|KlG6Suu3QTk}M7m&O$DFOR_sRG8pb$~3vmzyvr}s!U76xH2kP))UDQ z9E(qY4-H~oIm>zTOJJValpLQq&8^b!?0i;XRk<_I{g-FeR*cW*1g-<2qFdcIvCzYP z;IYeDMLe0aCfqjJqa{@J3f+X#E!*ISUhslsUE1LrDxb=P?A7AbT9c9*%}-KICzX zc^Kpv*$~H=+8_>c+#?^n5XUj(;R7eg;~w&OVwb4#--B>br&VnH)Ft$TZ%>$wPw5;W z9AWNM|D>YBApY>CZlPj&*V`vv*g}i(%@i2(yX?tCOU-HiJG$7V;BWOYT@yZ6y%Mu9 zdzpBWC%$BiYdo;kuVoV0FPd1UW)UMVIsNtYiP$){<@(=$W6=Nx^|2M2t=|BypY)9y zee@ii*;xV(#m^N`LtKo7^ciqb#nIJPq*X{IwAP|A+Np%h>tW#F07}PP$Z@@s%e=r1 zaN1Mcz*Wc&!kEX{)lR7G%h{owj0{5#-j8<}1H_Dij%)&Z#RYpY!U4eD5vl?>xWX+U zOebu@tqI91oY&i_*AZEvMyXdP5W_II0+QT`!nM}O?1LlKJNSS-(3CsK37@oqEO0_S+ z@0o-o+CnK@ge|B9=irg>t(zmvfv6;(y)~cDiQT?Mp8=W>0j{6GwUzd{)l?i0kkv`U zJx7m`AH`8z#pNRT@lY%RR{F8h%w>;awS~vo(jw3w${oNb#KQd5pDr+#349sY{C!fh!C#Y5gwshWn@M|Arv~4Mn#l-MbwCN0y~J!qTyqbkfG$Ui4W`p67Y#X z_yFMO126E2JdD8vWkU`~o)gpqJ?sOZWWzB;kvQalQ5K4V>`gwP%0H-71p!L&MB*f# z1SML8qW%AH*Vwg1&=Fkl2k0&EFRgi;MMI!+`%y! zFt*aa4WlhZnP)u3mC@fKti}Pz0A!w=Gt!?f++WJ6Ts3N@`JjOeU?XPHWoX8wT!KZv z9Dp>9^j-Us$Hi8v$(pB#fDAVV;)LOjsJ zKODp=Ji{^U%`7PBDEPoC1Vb?VLNGjoJ$QpK2*WnC!Xn}p62Ji*}Tyw540-n<<_mY3__@(xqB)$gtq0COriqOojl$;$U3QE=I-0RfZrC zW-#8EF}5GbeOzY9AIZ%hRjfv2F2W~JX31IRB0xp{ZDyMO24%TR|26{Yo2r?QdWHS` z!)c}_06C05^dM@+$HCyoIU>q`u*I>BOf>|#2U=PEC_;2O~Ncp!WAII zDp2Zh3COYG=c#a;fTWCq45vEP*F&(uaVDn_FlTe#={N#m7uLzsz?~Dk-4WW(D4ga~ zWWsszs*r#U!pv8Dx`Hf>f-CUDE%1XE<_&@R08h?gLS%zS`J}bo!%g`B=7EV1c*881 z-XsVEJ?H}x1OkW30yg|YKJ0@aAVY$fiZh_YIs^ke5X3JCmx+o&9^h-frf5k>q9nHH zzqV*KRK&TR1dZBJA(#R3)mu=EqK-ZvkJ^}=@(i55sa0=z6 zV*KKiPLF0u*~cMPVqFFraOnZq9}!#y%sxe!B4hpO$;q8*E~)9x-Ugd)ORy{h#R_f2 zN-S5b&{ObftHQ?{c%Q!{Em7RZ#1znfFwj~MYE3vpHOvD#EGj}wLf6*8Ecn0`%t9bs z=p^{SxE{nW)PWC7!YW{(f_$olxD7&p>e^iGR+6gW>=`I|f~q2*(lQ_;Y-iCJ1Ck7b zcLu_D!d)PcCspjKdcGY*on%Y4L2!a@feENq zLO#%gHsnAXU_uU<9uknl6|_kmI72?vLnf?3E2KgWe1qy91OF}{L(A}kH#|c#5JE5n z7`;-Ez3PF!LNC5D0waWFBx=~ej^#zr=!bD{9s$CQDpJGZSt)j7(e4WM4Q<5+3&COR zUKH6sJc}(R3lH(m_)W#dU5k{GEcKw($s*<~eGg_ZCP8!=5!~!!W(5L==>V5pEFdrf zqbbjBCiMVq`dYANnXe8Ut(^*PtTZiZE97_3@nj^umwu-L*seFI;4s-c*B^~ z0V}M6r3QkfrY+nu?}e_x6`1YV?r@~t?b(nh1PRipMo8g2;6w14V*Kr@K5Yj>(;L*? zcR`IJz}*-u?iQ~>9TY-TfEKVaLMB8;5LWIeWF#lJLjU5K4hPnWJ=jAwoRm1of`OLI zn)pB^aNa?PgP+8MJgCi2ni!v~!8AAnHV}j`Si>uzZ8XS3H+TaKD~DDF!yHT=D=@=0 zumZ{)036(F^nxV>T?TBB9GBH>J|J*gATTpJqcU1W z1WRzsQLu6ZZ7!R$Sl#lQg`*U+M?-!v7y`pKAxbw@MQx?9V(df5?1MK1gFN^Hyz+2D zTtP4}>M!6hEBtVy!Y!l?&JYVH-d?RBtuToaj{grVaRD{4Cp@utL@_(ZN+W&W(-f4F z)#?^&ajU%=7^5+;vSj5#%`NysHYmkpxUro)4JRnV7%W&i@z;a|!rNxqHhcmb6v8v? z10UvtGa!REDB=uzEh}t;CQ}F!ECGs!@>T1rAM^qBmIREla`sllhM`*|u9z$<%&fpA z$K5g|opUbd7?Bp-FJCONq{SN?548X$C*d!)D09iek}Ux?R6z4HKePJeN=Rylm=z!G~kcB9sn{p z0Yc2eFHpiklx+@N!7n5<*)pn2@pf<4UjN8Eg+w2*LRj=gUvv}u!yKq8b9S_6BLzsC z<1JLhu976H1wtJlZRMWiOUHEL-HEc+bgXtlPKThLwA6&$c0T;VG#GCxpo20H#5XL% z4kM~U*OYok2vu7(R`a*Mj`Aq&^;)}#X16sf zvacq|wUGwKEQZow{t7C|RWkSWallfznD}W(Ghk;aYZ&%rXqn9taBLI?Wfm}7JZ582 zb}!k%^stXVcsPXv`SoOQXFE4hG;N)THbczTJeD?eoVIbbwl^5BKfHr8SSUi|fFOu1 z5@6~iOu`R4>TX8}pfGd>=9GVlRR2UvbS21^al1J~AooW5OOeY;Lz?4$gh5OA$nPcF`m-Y8w#4xo!h56oNCra5rp2J`^-U z?C=`E?Y!c!e)spOLvJWhgFXDSH+*$P6hbQa>x*uf!I}hHGT#)FZ-h&@b_6+)TdeS8 zxWUC$wag+Y(S<1exOMbZEavZszss*&sfue)XH>gjt9Z6oyJigVBEZ1O!MMperdn)i z$&LG4zyMU(L1yN-_*|pA#7p@7`n=!HkShiU7r8svgnnp3JUc{1+q20;M;mynGO`4{Cw7&f~FIM-575hjO)+S zutFom58yVIZ9}u}H>#t0Bv8XXfYLs^!#evdI(E?e zuUj}=_eCkSZzpx1!YKx_-<7Qp&tQaj#zDKb*vhmM{$OkSwxb4%cSeBaLlUfp30$*c zYgsgYv(2V^X(%ulwEMZ(feFA%%MkP1i+;V>yU9B@!Ki$q@Y#a=nK&T?Z&CrhqJ<%Zm~d32mL~j}$AA2B`z^^s zv2!<)#3VUGC_-Rdf{-XeCLoM`-pK(h+S6$FE!bT~s{dTsgE+K9wyq67fI}Ut$x}Mo zJY3#EB;Gp!#F!kF#Eq-8hMqiq$9%}DbZp--PPth1x|c5>y*8}`Wm}VPo3KDWNM4yl z66GXe+w$dc`4VPKnKNNVqUO)vKb_QIMGB=SPaj5(h!!>K2vAX5wyLE{MbyinJ5%p? zp|S&OR;^pPzIkKJ-!L}^$d)yG7HwL!YuUDSYgR{GxpV2(wR;zDUcGyDy!HDRaA3iM z2^The81dRooB#YRhjZDR#A`caMoS2^ zzhs#NC9!=QcW&LgdH43+do|i5WNi~afSWk*;=_;MZhpMEZjAXpF;AikV=Ng-7A?X) z9Xv)|u@;?;1^(0YPr=oqvC|!XeEIX~*SCKke|I#$e>29(iM;>?9FV{Q4LmSFz7$-L zK{tk}>=LddoRGo_v--*yV1Qu*hz>h!;~#$bsf5Hz$U=#vvrt?yMZ-#3B^YF;0fwYD zDscv#X6&gZm|$}GA%`_qnPrtLdiM-w#N^w2C#PV+>FIz7S3mT|-c!pdYU1no_W!F=`I7q5H${TJYX?XAN< zPC(Nswbm3~m@~Buu8cI&QnOd#1DJ4_GJiJ7gujkG{`j}ma*J-bj!7=rIg(GtZIS6> zG5>)$^@u?EfbPBvZ@TdoInU*mF1A{)mz5I+m8fp6MFahM;>JSY;fu)|B>Z+|? zi{GsE%|tXk;r)6m3R!;r{zc z8;?0nL@d?L5*ST1F^df~O#|jlGtKS~(U$Je5NF^4n$Kz|wW1{rh(VN(3T^YW|40yt zNmSwz(b7OC+J$R42^|3~B(Je`sBCCK+u^cAq64f5Er4@NmjG9ZEVbcoBHEij_SQGR zz432?>W zVGWgtMtGv}ikP$lBb>OOwX_wAP|PnB>y(Ke!qvZW5rqzpphGHdp_3`@$$(;EB4VCc z&;`^y$&F?d5sA9!RkJ>cL}{BNKm3?SF8`hm2$fsw;Rxv# zLvk*WQY7Fnw6KFF{DKSxLMXi z@P|F@5u}TJFMRp9hpWgzH-Wr@ebZ^hOU9XxHdrg3G_fE3-bp`sS_=>19m=>4F)lig z0li&NoIe5T$^#x1FiDkfzTjJ5`$~<1j=4-k`Ma5kPHdtF@Zi-tNm19Xwz{%q zP5!`ZURw+{Ef@hSs}MvbtI?D=06`FvaMKl5kp@lz!Lp4D1|u5BhGiH79LC5-HdN_Z zKfBHsIgyki<`4v3sD}h>r$_kS61Z-B$R*6PWD=ve?CZ@`^EH zJg5WE_%B7CYm-IvkFw<0(q#eT7mpk`u%gJBL{?i?OU|OHs%6O?SF4i;%&3R?+!2p^FoPNL$iXLcwG3p!;Q+G0ME^|MFl&skZ@Msnh1zn$4_;_Y=tX3tWGf`!sQ! za|q*u(YV^I*#`g5{K*K9$aJjbysF3;0!4<5toY#oSgzz=?k!^Oj;2hIPRA_X&U6|l z0#8HBitbMIs*1j19;)FPo;qW?(5Luae%=S z%jVxRS-vopE%3{MhtoqK6;Lu<@RA~K{ArD89 z6yvK7x8_kmkV3>}Lm;p)45$CvpaD&!b|3|i$U<#+%l``SjqqlyR%FO>3@367$@0%H zfPiu8%1q=0kl2b)yu=7SL<7qN%XGpQfWa3$K^sTI#W2JlnqhYQK@`Mn5+)%IJjoHD zpd8siCw^fag25ZSp&FdQ8$!ezkpH3TEN%{b@Dk8Y?Z%MfWGos7GOip)L)c(cQZ7sS zPfFH63Y|qD+As%hEgzzR3*V;=q6-_Q3l{7FAjuF?Oe45@A`P!a4050ipQLQuL``%e z8LI95PO+d$ktT>#B4LlkS$E5DK~WHMj4CKZiA+KeGXj)4ujgya$<$7E59OeA|i z@~UtVSa|WQe9_1fu!~FtCmireE)W?H9brR?J7eyZBax7QZW&& zasKFv;>rd24~go&_ax01n`Q6Fv_kD?J0qK$q59bU^QYOTJ4UvpD zT@ofoQ7p9vEW?xGHUTI5P$whmEjXbQ{-YC|PZAu-4i3N$l7vYl;RUo{NFIqS?7)#E zfh_QoN#gS@7RD?n3Z#mXD1`$#8c{G@$TlvKEC8-BGVuVUu%!$HL30BJHuOQk0EqU3 zi2TDJ#FIox@jDmfL4*)O3J5LLa!a(TEek})RFp0c0OauU#}p74`%*MW#7T@%FxLW3 zGG~v_L{9by%5L)+&;O!KmQm&aFc+t@<6;byt{@H~OOu@K7vf+JoS_;jV;_LQ8&-i0 zDC-KK;7k+ivP@}}d_k574=1G4%9Ip0@n|=Bb41Gm7=9COun;|tvn-M`AF$zCEUh^) z!tw4QxTF&#`GF@?&pKTKJ5$oD{BJI2qdRNzL=~h&J5}Mx^Z3rQztXcZPU9XoffH33G6OILEu%Qy}K^%hXWa&~w9yL;5Vp1vfjV$$1h+z$6U_(9iTk8V& zx)p1!Ex*iDR57S6GG-mnK_}1w8TO$Xa=~DnPgeJnR|WI{a&=b^Bcd*f7z}Y*6R|89 z6fk;&LJz>-zE4>rbUHXJK06%kAAL5SN2UVkQuY&Q3CCAnr<37&@^Iq zUz7Ar;J{*kw_nLZ7S`2hEvM#WH#bN0PVtm1>~wjhs!!Vh^E@vfTH(5;115Tw3c~{% zUA@p4e};pHPB1sByFIKEf5VYFy|~3;S$u2r~8UJTZ z0)=()v>4z36x3KqmsBtj_5u~n6?Ug~^~j0qm>>nV>1C{M_khjlG@!*8iW5~DgFn$;4$FW-KKa1W!Y zyLuC{Rhea4tpCNC6$F}DS_W*`ABcem)>DUfI50`B$KJw8Xmdn<^K(t*a>toP^pc(J zh@X=*=Gba+pkpUf&VHsXk3t;sCxce83S_{~tVJybH z)xwtTwyT{wZ|RLGt2$_S2x$6k{Kx`AwQs%iI|-6`x%-=}%la;gz_{mkn&G#tal$NE z4qZ#`ZJvYz$Erktaj*G$C4tW4(Bh#BdoT}^t;9rj4_g4$n2&rH(F#_z9H$s2o3ed{ zA8HO};h?f(926e=%A7bYG&@de?ku>Nw4s=e8T)ZKj{iKou4VIF0-d}t zkn>;{mi#47ff_J@x93TH#Q+Xaa#qaB300K12fVoP*NObw%!#VGbMmSv zD8ozl;TcxdRtbR+ZnakRyn^L3yaj~ZLg>5=ELios-5Tscu{x`JXfVKUn4i)w3|-QT zsKn0P(hCH@>mr)PJgsqpt$CnsOK+^YimzGZ!3$?Z?ozLru++^t|MnH4YgfY`^N$oq zOh%g^4_mEBoN`XbbTAOb4*?pL*n5UZ}!a;A7q}GMz3qUCcxM)7|=TXtBXt{nWDr ztWE`pLj>f+8OhEy=tMlReU8MJF^X+nNe4Siw4F?*_l-xC>KmsR_#vOS@BorM2v{8G zKmqK*e%Wta+M)f{N1Jh|o+YjQbv2|(>y+D1TX&6+war4@#of2dooMZ09@rfdFd-4h zU88p)eX+&2SI?2XybZ2_A0T45Q+nUgdP7|xrWeHDW&fV@mk3nV+~6w)EsWqZd@_Qd zFZwD2ms>uh{uWx{8!GF2(anPOYyUQ0zVmaRplCiW1f0_gJmZ5?J~HgfPNpU;oIe zZ+-2ZxY?;aa^PM!vDocjw(jko$O-li)&d~#2pmWd4=if$_$getZy&;U`(VM!lV=w- ziWoC$#HeSZ$Bkl;2wf|A?)TL9?dKn>cMA*vYe}&!0ep3LQ$c zsL`WHh3Z(!v}w|(P@_tnO0}xht5~yY-FkIXGXHQ4ytwg_$ABw8R;kU& zN|k*4R2326zfd$pHuqTl7=+gsXqe&C^h3(bLSKt00u=(oQ0DBL- zrzZ6JfmaM12Lxf@fe03eAc6n<0|$Z-MhGD&@S)ce8#`h6Q+hkC$3}i^u(w}$z-SWU zhxnzq-iW}UxE^`@w5TF_LEIr!K{!T2jsJ2y`g6c^z#a6_kVJkY1{^tzbeu^lvBaEc z$;@=ylsOgQ0&7@iX_Ql1cIoApV1_9sSDS1C7AJ44rRJJ!j`b8=ZjIT~Ty+J-2`B&P z#n)$i_8HhBk^Kc|KDzMPSU!J6HkqG{HtOhRqAermq?A@_>6f%+s_CY(*+wNzxxKVo zZ@)pePjEXesp@gb0e4IrDjlbiLOfju9CrM?%Ek=mS@oWHK)GifKmW~0pRfwG=i-d< z%@-nnJeIeUu*Dqkpo9nR6d@ed9#9On;7&*(v6^HUpoSY-cwUGvju>N!CmK6rfc~`T zqJH%jJ7bMQ;aHH4Kq?gQLjU~O;Qzo1Q3FdTMN-sJ!xV{;25F?pdDc*O<+azNJRhbgWqtkp*(Zt>+Sj2y zC#`g&Ux9`4(@;lkDW_CdU0cVY`ZFpIW8~FP8=U|r9K~cKw-T(+9aqV))Ey8lKlO%q zfP7W`Din;w$~#|sz%{GleR~V*_S*uxJ)nd?VGByF{DkZHf#cd29=hqK#~!}>d8oI% zBF4Qe=F8$&qZoPwz?FnlI-5=4_9 z{`>GB*7PzlH*f#__!njM{`~7u1lGFY4XGMZi62zrR0@es*(m0m;A5j2M)}@L!oo5!v8g9H17G|M^8`EmMGJm3Uu3iZ2J_KF zG3iSJApHUcLi%NqegElW`{l zKpt@7CHp9#0TIX#2rlrJ6|*IiU~;e(?k7a$5();R@+%bu^8g+UA_(2%uJY`sL?mRE zz@o?x0tp3N#qbdvXpqfn+7J%h>SnZxF)m_Va7FKdQRtKjBJkMDhm$+v9Z1)&CE}rp zK%#~|Y01JCDo3A@sA5KFrxDxTPF5B>#xmM42A23^V_yX0l}LFhGHQmR7|p0gc~S>6 zvGI){y%|xy*C6Z6@lKtHQ)6y;P%w~S&SYZikBpbdrL6m-KGR!fS9Gf+8$*{*sulOOAJ?6W*K zA9u!l<`n_2G;Kq90319oFs_mR)29+2X;}lXN9v&94PXU5r zQAokYI`(htf^0AkM$VvMRv|Am%D6xQTF}B_I-506HYq4YP}C4|-7KQLpat6}0|;|Q zln;53nW7-%)(=FnXK?j^2R`%JAWx(faEPnV--e>KLLPzC?^cr_4?>iJ2uaw4Am;G|Kt*`KxFAG6?s1P;4C5L}7)4MsQHLb3qYz1e zhJ!~;ZozEgu4XlgNIlJNwYvD-O!?oZ=Gw}x`QvLho~4d?yg+$gJh{gxc2l= zJx5Vbg`}A*H*@Y@0_s*d%^VbNadupx=yI2b)srAxnc##21-8JM%@&%7%?i1#-e&vD z#pX>ucD@6ick3_UM&i!|(a{sh{KN(U6h}B8NEIK(XjL^yi*5KpL%UdMOT%EI?H-e+ zFBuOlKlRPFP6XRamR;}@bzTkRL@sI@}hEa%5)c->= zYbeD&+8%B#3|k$92r$}fN;LlNBNLlQ%suh}gHbrR5Fv&}A?4AROa!>xm`}E7YKD|` zU;Xp>gEzckj2qFglE$!L%J*XJ1Q;zTF<<2-Wna=9r zS5RUHiv!qmVFC%dKmZ2vguRX*ztyw9ilm34FDZ+=lXSh)Ak)=!GywxJ0D76m84B2d z4oDPP7Zz!5UffKGTaqW5m3 zcM~#3S9O(o`St_HfIvI;djB>9Y%m?eVsHn*2GK%6zw{F&vU@;KIrxD$<98mwCwxGV zLhd41E0ladF>%Vb6PP6wngx9t=X?o5ao*x1z`=c|#Se<;eVrvvJvT6M=q%+oiFG(F z>7jl=5jzNxF#iGzdT?_~M1R%+P@)(K10jFmIUCC1ldq|n?Qqofo+zT5A<*kpFnx8aCh>U1g+3*h0qFG&qp%fC8FiVLp7uPW(K5w2J^w&4Gv;NGE%g=}h!$uC zjU4!DoskXK;1Air7r2lO*-!_uKvelq2jq|p*T4(;5D)s04I!pr*8mQF1O|?o43(D+ zw2PIFKTygrl()2&tFGnHmiFR`NC_WhIfV z^gRb)kzDwCK)@?t+Ls~vbFg|w)oJ?Afrcs~r{aOBB3?@@h3fqm3h z6a<2lNI64b_I!eVpM8MRw@I@05{99r2}MRH@1Ze z(Llzbp=z2U8-$&G<03pEH^D+UJm*W_i60_)LYu=Ljrv#uVl4+UW_uVRRPkjBF{sc7 z2cdvv`FW_0W1ot8EvscYDg>!PB&j&Z6PT*53(60oh$CF7ioFF1qN-=43Uf3N1W1q) zj>b@{+6)@A2Cv$5Fc7QNDs{9vvo_m2-Sttr3Nuha8e+#4DAsv!`3{FOCQyaDbl1hd5Gku>Z*yS~=-uG|-d7qOgXmr=4|_69OL*JD}-z z2kmzNplGQFaIvnVPYNRuv6Bd&NTFr)AD~4q0l2DTAYCL1t5$0% zDXOBeTe~QevoN}|8~7A7L!7`Wv~A*Qd!iZbgD8Fhq(#aZgJLvEz_d@Bc~L7VUt$*J zV7oVqwf(c4IDw`9pru_)45fl&)A?`a(T3&QD?cHUZ?hj|_;6)gd&==n@*<~^S|I`A zE#MR`nMECl3n5TJ1Ad!vpmhMD@O*hd1Kgq<{cE@*cV>@Mat&gy%A|gYz{@5@`xxufv`E?+>vN>fJCM<9Gj$@w)QY|Q zGbP&!7F|m!Un{=Ja&SoDrXplPWSf$WReWRyFF<50?-4p1q&G0qLaAj#khsA9ixk`> zl!B_0+)}_lsXFAuz>b4MhYG`tNFmb_e04TYNpz{b1q+D~3ODC|l$wftR-qvrs=?(? zfwsXVyuu@!BKX1&GEBp+JO|BiS8`ctGRwsaShKdA%U}|LXkx@iJW`|Z56ci1zN&7& zyTmW!QtdUof)N==IzEOH8UN@LG?tXSS3FjA;7P(vn1`v$UF^kHGllflwG^okV;}^u z3?FWYzIXF3?uty5Q<6d?AJC$mAoL=})Nr!Jl2~TAdE3vAa};?np9q`>$KWlP5DGsT zEqLe?imX}=EFq4(#~zojA_8-iY_S!rv7TGWoP0Vux2c_rbAM)1fi^fMJsq$E%B1VU z016)d&`7tQQoa!u(@V8M&7$BO&N;!o-aE#Zz)PM$!=4}-h4gAqcBb z*>bR_2jC3O@DJi-9g4~$Eu?%8oqZ9#Al*dKi%VqCf+9#%xuHM`n!F?aAc{Sqe;bV* zo7!8U_-8?P+nM@09&AsktgkWc3o{G^K>!3aoX#(i3~ta9I_-2k9M%=}!$3^k*j*Yf zO4LP7Jw<_xNR3`8g;w<=t-C6`QXQmG%o)y%Y)N{oSUpx{wbe7))o6kx$DG}HIo7C@ z6Jgw~TlxYoumc31)-SQvZ0!lQIEIppa6|FV@@&3(O@~oN9^sdr&on}mB_0Y9(GzDw ztKbL&vI?niApcOX3c+v%Z?Ou~mj<&C20@SpzrY5I^AFX449+k(;$Y00}d<(Fee1JYm~n2sc*#4v2F{RqJiM9>2dzk0$=b?fvb7$-I31cr&chkMn{2O z>7X6-#$+&kc({_>x0;Qm1B z_kQX=(%|@EF6%tMP6RJ*1|ulfpR>-0Lw@VH4lZfX3xefu?{8q>!|>ckkxD#`@+4#3hC%t5KNJX` z@M}?OUsoN;__KjN6vcZd{GbexQ8clz2%Isbm()JY>+wsI&6_tB+C%ciJQawU`3kA> zni5wvn@{5A75N61p9OXoD>2TaqPH^%%8a|2TAR<2#Wegzv= z>{zm8&7MV@R_$80V2cz<5?AhAx^mmz#hX{}UcP<({skO3Y@JO;IdNi=Sn*=UjU7LR z+!*ZPe@6X%v}{;#*~DP;eg5?E(`VA9^XZDU$VA<`q(8|e9ZLpl+O=)p#+_St?K;UU zFMETRQ>T6YI1#%0c=K}R&7D7oepiPMt<$Yv$DUpLcJA3>6tV8c@|zvy&7ViV<&7XpamJs2(D?-&bb>(!nQEM=hDAn#nPe3jcI1)A1A64q zABsQ$rJ`aeM6yDLB9w?BhY|wC!T_hl$RBY|IVBX3U~vf+o_K0$$^&MK#3VmZI>{z3 zE!yczJbda;zoL#($~~r@;>RCj-bk>rOrircP(cTE?ycSIA~aD&7iF~3Lt4}De^eeF2`~Qlf@}dE|($d-ZPix84@VqVwgr2G zlgbV=D>ASrr@V5ul*K&r?!+_d5@iU{2=of5Z2!Gw9l&rc0tOfaG7fQ^$x@_-0ShQlHZgZQPCRF40}p=ZH!ZV-!Oieif zpiST;6geHm7j;_NQ+)A{J)P$abNZ9zG`PVnNdIO2xUT}a?`3+S`h)t|w0|Uer(TKV!%;K8UxW{oqER-5y6s2f2 z%~jEgI>^L$KKD6k`GZ=c6GG|uK_C2l#6DwWT^hkfCI8vYE>5x22+4RS$0Ye~LUyDO zk&471jqsxy!HC!|yn#J$tmpvf@JGag;S3M?!y6IH*8$GJqhL5yb&XG*rQ4Rc;q^+@(Wga2nh6}&=T-~KU%izCK?gPE+B!3n^8kZWHOTh4Y-k# z*eoRr3<}bkF$V}n5Gux~V6^fyj44*rnt3tQ)~>ltZgvwSCCt-tRya;5p2dkyOqAa~ zfy1uw;05pOp$`ie7t*Nai1);&T$1Py-~@^gjx!EAxl$=_7Sy1Bxne>w$1FWeBe10L9LYZ!Aia4lq0lf&T=SCxz0y`1p@?tOFf1!rnaQk;;D{ z!yD*m=`X@SgHE0y2*D5pk5&PQonn$lsX&H{f>Di}_~RLZbjdW5`bb2oXdMw#Wg2D? zhAVKjlP8tsM`}4%mC+0mr+`^UY$6h&3Dd1*f<*$~^pl|wr6|pKphSg$C#R(+bpA-g zK?OV5Y<_UChea&cHnE9tPKun5Wei$^Bhcvd4K(Zw3p?ZKH`E9&ANd5W5$ljEMKLj; zX(MQ2Rl8cRDAcu^JHTb0=Fn$#@rz&-qeeBskDO?9qXvTA=~U<2p@6Fxb_7YtdS_CU z($8HAL1iITRE=jK%o)#c2KMYhqsl-}5&wB`2zY~02sntB5a2xkc*_fiP+%eyO>*iw z{5MJ=@nag*Kn9EesY-v~^r7Hy$r zTfI&+GxgbRo+?V*-zLZ(vh&utLb|&MG53xo#ba}kBqiRaav$rEkw%R2A{C8t9{v!- zDwdF=CD7mvznJ8Xf&mDMxfc}gE&m2Z6y}e0Jfj-LQHMa^{A(2)#V<>15F;+ZOYA{^~{dP=R0h zas=t-vDD)5;~9&z=|4QNiUa>*5B_UbK9VtlXhqL@=5ulWnBQvH zBPMxzQE~Qx-v>`}(GMOf4gZ4hFb{pN(MF|#I#_87A_2o-=CG+FS;_QZTs0V^{)H=o z;0TH3YeRt0^-t&U5kLF_4_X2C{X+4MF_}c~$d1`5)Y|N3!y*x(=tD7zasZ^P7>vw( zri-^Itqexo^293ap)S99&L05Xhf(*s#{xsgHSRBOScXyV!32<*pzb{O;f-pb9~n>pLK=Q?g)96b4M2cGFyc^i6UUArA6YIA z`3RDlx~=#*l;X2IasMC7IIepk7>1|}Q0S4X;}Ht%9<19DP+%!lSOrITwN!uuU~mR+ zu!sNJ2YZMSe;BntN(G4t1A#z-5}AcFxVvBQh>r*cKgc^;f`xbRhni`bNH~QH(*sC= z1(+cPULrgLLIf@WhJUa&$CD_&l04e73=*)uEL4=t8#gWV!W)AWe&Vsvdn~cIvPd}$ zg=-6d;->?Ur&5_Wve1RglABL(0VDX zBff$2hkYoxG;}wRcmd|?8pco&L5se`xQs9KL`T6sFJmZw;J$}4iii?|IG}>1=mPRv z3P+Fx@X?5{v;T+USdn!A2K<{p4G9WM`mLL5hQiDi<8Nn-{B}@rp>%n&b1{Eta_n<f^#7k70O=FON0uJiC$f$&lP<$=U@dwW-#W9O5 zjuQeL5dVTM_#RfA1tGA7PumBBd8%rdhsrnrdl-fsfdV&}g`lW|UuYe0IRNEKh^`0% zV?;)$}pK3NVh@+QivI9fCW#; ztA%WeY^%ajv8Bh5iOo8d zQejE3kQ>^|hjn6!DAgQ>~S zH@yoktVlSe)2}HZ!$6_ygsiX7&Q0M?G!)4LAW6;e3cb;rBzr^l&+K07XfU`CSSRZXJ^#iYi?TmpmmhZ2k!M_|W+FijkF z1W3ZsV1NP;35H})RiYau|3T7TQyJrVQv3-MA<>9@ET$c786!k1QrIw+@KWCdQ{U_Z zFL;mJ(yNB-)bxNzOBGnMkW=U!*n=GwaB?_3Ekiu)(@7mlej+Wha3>x@NxOkVkSNbM ztei)MRL2lXKSbD({R&J~C}uGRto&Di-G@@5mR|tNSV716Vrr{qN9`Y3L?>+%h=Gc;2nohpZdB80u)x|(uzHD2?<=$#q1Gh<^L_Cpq~VD zuuhneV7P>0xGET3q{=A4q7xEW7=&3soR$2Hk2Vknhe+-O0DX@J5I5hl4=}ml!le$`gJFg+X8hMUY!s5}=ppBYn)bC{Dc6w%F~y%3IyZjojS$;1O;P%f;M1)rz&@T!nehvp_QP z^dZvKAk*aom2-74ao?c?C{AcI9ZIb?7Efk1x03Z)>`y?QW7_yso*0xD=b znI(>s`=e(Nl3mR?`WcI2U=WfK3lN1`jEISt7}g{SQ4Ed7A<4AFG^)kq+J@K>@-0zV z0)-_Ynw8;OU*aRX?L&&N(pvgo0Pdq-!ctl)V7~>^cum4Y@B<@+nMAmQ!d(hqcpZx< z;>hDv4sP5Wrrd%RVNLdAzcAqwZrB#uG|Lb)N#P4a-5blIJsIxU_>})oN|97QEI1fq zf^qm{OWk43(V`zl4lRGD2@TlOQR(V z4Gdt6;bN`07h|MeDxtGI^M~ve2%npm?!6d)2n9I6!0>hB9;q*LjwNUutJz!=iWs>2 zeTRJv!nzHYb&Z79#GgX`TSWF!JQzp@-X;IphcB9gNu~(MYq3lI;egHM$K_<)$mou~ z3v|;+Q649dSewp8rx8zT$km zIhY`iN~WRhMBN$2Tpf!&nv&b$)sJ|cYd)zc;T=4hmtp{tc`5&Ap0Y+7fM<8681kj( z^|c>=rlou2+kDOlei-Bs(;18)lYBI5Jt*LVM#4l8+@J9Y_|pW4q83k>WXm{Co;DAR zzG=q|VU9lR#V(7Cyj+n!n*;Djewsw(Yhkr8)H`%(u7PP{Ss}*(jyzQk#%|7>#vF@- zUBU)fP~EEt66${->I$U~i_p-JF~D=iBZ(doIbuebVBS0$Yl5f1{Ah+I9JDBnfVLp@{CSn00RFAoK+bqOTxZa&^_0xm+n-Gv3A1}yQ-T_SI{BATB-?~78iqyS`X;{h$vFkDUy6?~2%FaBk{(k*cAhkPaLOD98~HoE0AALRdsBVR&fN+b3DVm`V`ub^|ocJqQmAO_>;gaO|sGhdXl0jO|tjDIqlU-v>dKbGb6VLBf( z_JE40Kpm~%^KwtK)4}kS%H!&d7dS`-TLXkyfOLVlOo7+}ppt{{2?bHGzc`SCStE!9 zOM{9~af)$P-O*=~!NB{KkWlAAl}Q;=-$C%+hg@3qB8P-XC}0Lg30TOJnjuJ8Z!@FL z#Lm@|ub}hfq$X_FXv1N7`o7bJ!!CD|W_=d=X40MTqDENw*h&h({`{8?*34E3L?np3XFx`bA zw^!=k_+iQuxhikEs(N%;sqp{{DgV@!H+sZ&`OZJ=P!{DcUm;|F*guVwkZktL9u{aH z6czGs`qacu$Xw93Jf!E2tWf%;f0j209lW}h`6#13$9io^o#7{U;*a{MC;s`Mi2W%3 zmyjL$cr%a~l2GvQ<8fMK*aTbfwPHX9Tu?lT;0J_xL_Vx97BPmD`-e{75$MAEuofQi zAsBHW1$U)}cd*iw`R-H)2vPz`ojU)utKhDIry?bahvkps8Xj=t!niu)~s5$a_yS4NRcFB$C52;Hi_4?YS*%D>-H_&xN?(j+GLXxCnkFL z^6l&QZ{Ih|j^+hy`0(BXc>f)3e3Y?2en*!r!#g+Yl^2((B1TL|vSY`P@pkUJ`84X( zs#mktspB>5*s^ESu5FvP8=J<6^6u>$=o@3kZ1VFZS4G zRdd-rm(z6JX;Km!2Y~xcqz@3MP3RqaZ(^gc6C52n{r^KnNkUON$)wgCmZ5 zJaj-tLsBH9z(`VL5lE46cH zQO}m?rXE|pLvT;ZroIja3eLV8X%XMR|DshXl-Z8NuO@WOt;Hh#?5JyB&F65|iB-P)fej6!3V`Ki*uzCd05F z8q-KWGBwY6YJ4LcpGQ5y5JFCZAC5(lk*o8InmFU_NscLF(~*eEf$ejzs3z`^+#H_TNL3? z%o72Gt6Z(alLFTDR7Y7ARrFe(T=sRKDOpOy#B-8SH3q{+@vD>mLClhXX0tTx>}R8l zh#0j~GNw(6!YId}EnCMU{lo}9V~eDT$nGD-pc1=)aYZKq@BmWs?g4PH3P=A)X%%kJ z8xD?ps!~xw2y}3$5RO|4b_4?*Rx&~pbfV%N5HF-5el(=1GG6kMCDN9@G|bk^sJx`_ zW*+{up17*LM1?O=%h(GQzM5bJZ?X{blSF};z~BW-crOQLf?$f4D4Lk^kD%@hri0BU z5|7x#Xk9echzF$?!`Laitnt?(lR&1hM1=CpCAriLF{jvWg4Dq_xXBZlC7aDUpm1{I zpd95Whc+RJfQal^dpaQ!am)7B7eK|VZ-=3RL8{8-U$N*Cn9QLmckTiX4loHx2w@fu zb%Z3Skcv_O+PIFG1r;_?Xm3=b6k^fV;T72U@)ffk6^@lsC&sICHXRoNi<{TMjH*x=cn?i-;da@G&YJC zZA)fb%o9x+6|}of931PU+B*jKsLmd6l|aXKEMWuM!A)+IjOyH+UFS~LJ)%><;uMI$ z2o4!EMT+R_-uG73Kk~hA*P*ss{zkix*{nOJOu~_FNH`T{;bw;m;a97u?kp~UoK^f{ z6@3P7FrZ1O@4Bf!M^q+-9#qf#Nnv(eomt9lluPA-qHl}zLaSZIyinH zYofy*`?#h(oRNyX82ysVEwEtJ1AO&`X863fJ^0yT^{bya#UB5y>v=@PfNX&_w}9;ZkW@B#+~d`AngQ#Fh+v- zgFXBLI;clsFxVe)f*kz9D2xJSAj2~lLlSbIh8-aj1R)$!#rU}r))~VaoL|-uT#dz* zxFp3~JsbSl)#KG)+F=$y2;h%JkpHQKCioi%9%BAUkh%ZWkY|ZVQ-qF;kU}Da0wmB& zL5!9JhN6qSLqaIv1%8B*Oi;abU;q{r0CCY%EEjMsT;)lE8#n@Ul?rfqf-m?27XE@G z3|F5W$1ljk#weOv5s&f2Av2~?51w2zMkDgXOl7#78(yQ%tf4hp6<(O3V@!j#NYfRn zLl*ACFRa5fTw!ITLNL5RDy+d?5S6XP+Fvwb@wv|^xDRD)BdAHEKf1;o;!hpk;TU}i z#l!?pupief1-6Y#AR17<03g~e#{tO7B3`81L{u<513K6QO=J@Zl~6>@nMnx3BdtOj z?1ObMP8|Hg9QZ+s=)oq|NF;b-j2whP6a>9&BIp04NQ$(RBQD6ORA4b=4&TX(CURoG z=-WtG(Ev6gE25o}X%W|1j8fR5POQQtP=O=Zfg@bpBy<5G%t9w{gg5-cK5%4Y_yRB< z7oZ(iC(Oh#9smv!&p+O!^2pxo;U!;^OiQsBHU{Q~jhf61P5g9%Ed;|b?87=BLo}t{ zGa-W(27|U_f>R;bDqK>n85lhZCe8FEGX|v87~28ZVL`IkvN46%%mHh*CTqHwYsTh7 za#311NkG8!$pJ6oMus<|P0_FL0rPTthJY z!Y$@=$fz`OnGKt${auDiAF(^DV4$oA;W>#gEiHtEm)r; zb&?ij5^`k{i+(1Gf}d#W&xx6)@N8ZCJw;uy=4{TUOw^`rVn=kySS0Qy#5lqz*aSM9 zV`N0%St5>v;wV3?!#Wg0HS|I;0E015Cgy~~#392VAOcUUn^MS#oi;@%>;eFGAT{U# zEI@+Z73zrK!RByIe9Fs=kOC@zLYDs)l(z9rb!=HAArTO3E{u=&kN5Yy9P=4JojK8X?F*CwQYx z>_ZU->(KD()Ez0*7@Lw_&DKo?FUdqzMrpOWn5m>nZrO?ijf-w-sY<*Z+Uyly{ewMR zlQE`cHK0Rq`olD=hc}=DdqhqQc|kDL!Y<%JDWrlL1cM?hg&IWJPGn9Z{LoUM);v*z z5+#D55)m~JjG<2Kx}^vtGz96$onK9mkadT)NuEq-%#$Rf*DOWCEk$x92=FZoO&q{J zTq|w$QyvO*}|5AXh3tf#tZXKdb|oYLJcMhj5NcC;(?c3_>vc zP%sRFPN+fN>0M~?(4HoR9-vkQ`beS5PH9oB;YL}0&Jg5CPPbs2OB`Z25gbp*giQeG zPFQ7C$OIvh3(WG;7kwzL(rnR=ZflgNu97b5c7?B2#}I-g4p;KfegUFvz}G7 z`VVR%BvmwRQWRX&Lfh2V)fZg{+znHt(u!W0Yp!71gM14pNC+H&i?=M!^uj?J#K9z_ z0vj}DM}8^dY!KqugEs#~M#NTE-=V@PWCGp>LmvQ9i41JJk-}1p$cjkp#Fkm%9>Qhj!5?VmwnsASyqxv)-xB!_JdM^sgT8wBv9~w_Mgrkc%QR zVs|_VsU&1q7<6A>ZUoD$@Hq5CGsQ>OE=Mo6>E`TWM>I8NvPMsKMnCq-9ClQAbVzUZ zD7!%>41=ba^lzY_)>s7%F9mBVvMaarwZ5iID+my8tPk^W0~Nzl=rR(Ui%-vx-337! zL{cIN!sAd0H2i`n46Guo0y2DFBFHT_SEtA2gc$#V@hCztBt zbzA?(bCmh7T>o_AQlzWE9Y4FBKWB(QXR23-ioRH`U`weE9{@vRiD6^5PK5F(!+>R1 zbYoNUfLHQGQ?`P??tx3nY&^v)B{pYI_!_vBFiN4eFVQs8z^=d$9;I3=d_8jpw?cveN^#3^W#8RW#oJ+s{^0y6Z0A}E60 z9)NYD!Y)JtGHi7&q{1LDf+Bdq8QXs{C`$m61G=Oh53@t+FX&xK2QUJ!cOdQZYvJDG4VO68=eNy zjRz6mA(t(Xf}L8oA3XDMGlJOq#~>sEDfB{h{z57EfgYrSe;|7>TzQmbpDgrEDOyOci=!=v*6z(+bQDO+k^g@*^|sqmq7ycM>ZxGx@Ls(`wX?UuMr>Htzs zZ*NwrM>_yV?~_?MiIfPe>x79Q5iWQ`F4%%I*X;pBLU7u{Ehs{Ha`!5n0xJK2&>)z# zBB;TU8@t?=0?4a%pq4kd)SX<@wPmSyQvd;$ifg%|IU!@k9P}Z{y0Q+-sw3M3G4O=G zD>l7Da)BH8*T-&Tzo@*QeNB!1YUEE&NKK-5{U|efzyCYH*FB^M1(O;)4Og zqNbzD!!t-uTo$(Xvv*|ainj|NcZ;gywv4+vo{D_Qi@Z*VmNkHN7mtDzdjsOU6W)r# zF93rx*g}r0K`G2_lyxz)kH|*6wRtxVVj2Ca=eE)>J^zI(O7vepr_Fm;uH|}rQ$)RL zi#T%Vgt!OA3%tO4`9m@!Mc1dh+GB9o^ZE3ruCJ~r+HZd8G7!T) z_`BVwf8D?S2(hkFi5$|~Mf=6RwZj;rOF`07Z$}s9? z*1VZ>XV0HOhZa4WbZOJ4QKweDn)T=+Nnpp8J)8FI*0*uz*1i9mcW>XnfoI;d$?Y;u zoR}n6zMOe;=g*->mp+|(b?eu$XOAA7dw1{Ob?Xp6o_u-p=h5pZVwrt=_iK_hB{rsU zef#ytj9KQk*__gU_nN~OVA^WRKu-Y7YmPbKI?6!@o6>}?vnZrclcuVwu)+%sj0hox z1cJ&T13Qd}A&ZDgk*Gd?DTS0%dO6@6x7=Fimv#K91{rkF@y3~4^ayGYJq8I14`fpD zV-QAe`UxXH6uAhaK@=IpNsVBc>ZqqgWU51@4w|Yet3D%(%mdWYu&fC+WTUGKAN(gU z&^(zV!8`HPOR%d5OH47w?&IMxe?9j2}eH zQwRb5AyHX=?Cfg}Pa2GKDiW*GOwA23bn{wlk7_DJ5gYPySp$m+1r`-Gx{9a+GGa2A zV34WCpMB=_$HsN`*$0_lehKCmTh#C)m0(igR}noFS%qJIGug=BA%i3snN<$X2#-*v z{Sw?D#1-hEgn+5mG_SxqVB5{kO6x0rv^t8vIyKYN*qH(J8r+UTQ?E<(~unT`$Vr=gBo>feT=QPfni&RYNLt+`Ha>aW2bE!MGNT`%afWq|M3 zU3bQBnPv7lW|=mAsJm_)IGY*SaY^(=uLYsyM_MhH6`8YbyJF+33=uy|@vpk&hs%w{ z<@*4a`JpC~P&i^2BX!sP9FIuEu?MDPQQv1Cn9%vfn|bEZF&mxmC}ovktW+ZvTm0~& zlvLEn$d-bKR0MaOg3@UTf(*=~SxC{s>Hf{wT;i5t5K~tArulqR3m)%Pl{nU(jG+KUU6^rmVaqCMQ)>o$i#9 zbpYk3MCp&W9j6lrOyyCLsx_W2^)#<^<*a0B!DOt>mOC2*As&;a;qkhawGyWo=W(l&SyR1YIQ@ThVbb_VxgCtC4%2er2 zH){ODX(p+gUF|;2Q<(s2{D#U2LcAfVJ7Q#>~cvKdFX)Bh@Y;R?|mEkm@sU|u;<*q?QW)c0WB3Nwr6tD3tyEsKgUUUi+ppReGViQ zlOPBvf|%M5Q6;Tg!7cxjR})cqFS=|bZ3MM#e|pj?4@X2s<%N|Wop zM&|30oH<)`*&Am$E6Tdp&FP%+oM%RL_fs7uWl_m{UO_W3y~J2X{Pet3_mT~&@tvh8 z?Ry{n?B^K5;_sz->E8qa4lc=p5Q(s?6=lBZz)h~pSvJ!>8gBVoab0LM`Doz-{7{=M z)GJ@XiKVL`vMGckA`x>nEe|I`50E&;E=YlhM4aN-h=4_s4df4d1Opu}&P6T?mWoW2 zA{ZBm#6PI*3}mEaCC)&HGpa$aeR$#*NC*YJ!rCoUYbDl64)tkf8^cql?B4sf5S)xs zrvNL9W+TLO2+{xC2~ON{KcVW(n-d*ziRb2~cDBvLF`n_J9is z9gUKa33F(?lZ!5!qotawNZUt0^Agqv51w5ElD%1PlS^?j+ zLMGN_4L3m~#7fTXmheS#!Y%t~vzuYca@DV%GZnYE(^wyS*?-2T-t{<*{v7g=?>;$& zZaB)5;nV-wYtrQtg!!XoUe#XZ_vWB?e%&}7mtrz>-d8yjnaH$O>w8A~nt`yDE97b> zM|~_oxWl)rez~!OIO|x+NS5-rYr)kz{#6$Ti8l-h50l~_t*ge(sv#Iwhh7d~9;gi_ zoWU7PCjni?bb!nsyg}~fcaUd;aAdZXBx>Zh{2^$&sN}U_g@F{?gxpm2y5@Va1Z2o52*_6 zHxT>`mzH1z|R9g1J%4Q=^`)u zCS;z6e8=NL*2*Km7Q@F+mgGaxTC%7O$- z&;&K=hC*f#1xxcdPcL9_Gh~pZ63KnC${$W|2WzDVqi`9sD+q-U_LwmmXYUA;A*jNu zsFn~r(rX*Xs~bxWzxJb}2qhB)K^iN`<>0FdZ)K|XVLp@(Kd_1)^otAm%L|WTAFkpU zDxnS9zz1dkE6T7l&@c^YQLPlL>Ef^h%_I)VPb}!L4)K7At^yXS=-5a>osdXfBEkO; zH}cu8VsqZFoG|dBnu4%E5+jxk7LW}iH}bK8vF7->YM0%gtQ2Q(ng z9K~|FTu%tc@+@PI&#Do;NNK!Ig&X0L5RQX=MuDhC;cf6TFMrP_QHO8bViE}@_{tG2 zC+U?MO&#BZzBu6>8)MS=q0+XH9`~yah~XX|^BDTk2Q+gt{m~2oQbN+I`(miJ5OSev zv901z4!dV3SuMWGI0OcDnLsV^+XR0h;&p!oJj`896vqKs6ft>LfEu~Q>;UF*E&VROJ#Hh&G+Jgr-_;#xV( z!@l$nQw$Pv!q}LN*g9hCNTe7*p%|1!UC$Iv4PsrvqD{vF7#b%l8ZWQN6VzT2Ag`x1 z8d5CU(*&VyS$yE6OH7zuS}NDl`^1G+-BV)q9?EzbX9HFje;wx-YnL`$_Y zXldrIDyy1rRY9m#?-51$F;;2RMrn0Mt?w0kl*)G1ws;Fz=@m8SRam!$SW(F8#_j+% z2O{+#5~TH7so`|o!kny>8j8U-x#?T8uGpAuS~CI>pw(PC0umHN(b7=XZd#S4Ff(Rdb~9nNblczqI4tjAR@#ze8YEL%XV4ZRVtXwGwFhQ*0W~IB513$ z*Ay?dysyDlF>n8kq7I-Ej)DG;fkpv03@c#_M5AyEm6052G!~U|8Te8#He(w&f+cu@ zyF)#$0&~|f`Ihg{=5bZ+F<&aJWlJ|!NtZMEv40=44RG`{d9-FVL)F%n!R9rFd21+n zi_{8sS$H=TfcF$W4A@F?bF|_jU?ExZa3n~fc`-u&mKS=_WqOy`BD0qxItC zgf$azn|3}yqdph2SA@~I6qg4nIFY~OQ6W{49r=+V`H(SKWZBUjCGBlclo$@+bARB2 zFH?j^_+??WWltD|AF~oTbA^x2jBU1cD@tc)H)m&fNWb%jDTHshX;~psoE$M(GzSv! zpf2js0;(LF3gGp>zF+sYBOx~AO3fQ`BxrKnQ(LNq#m{_)h$tIzbRR3NDNNZwFf&&F(S?_;oa@(D z9Y<&9s+MD!E6gtxb|{y90wRGITlI=_vO*8E0{%F$En=d?L}HqU!kN2Pic!sVO!)eM1DG+h@L9qNXFE}Yx>G`DBe-dXzw*9SDC62Ky(4>n=*IV<-$ zUuv*EB34&)5NI4t85R1jKf|C88n5}fuO*eCHTRN1SXDi^GC??`(b{EGmw%6e1xW<4 zU3LacS|KNULZ%0$d3KGpg{2$E{KP;fHcXdkdUI_0Hg%dac$z`;#h8;gBcPb5GlFX& z!Fm%xN{HfF&tV_nfT@`}OwM+-(iHz9XzfSGnT&C^vRN1{@O7=!S(&<;oN0H5P%vQW zq918BGg7w=up*;vRILY>Ge8f`4EKHN#gMfEG40x~)jKQn8mHF#z2Tb~F*mT`@mD(d z`Be6>F*>npGWpZ~0NlL)k_HcVPh;7~6U)?}HN%$@I=U zWYaso`AU|i@oTVI^Z;J;&|X!$`J06KcW@5MKv22P$(piVnU5M= z^YZAwUCV}oU~Q)aoX+N`Q#)PNS$8ZybRBFSTw$*pOwlXc5yi@RBf*C`oL!(dD<-{I zdDjmuQY172ie>w1*>C?N@IVYgJu7^O)J@&D1>!1tXvSF`Dx_MXu3FYN#MTdz)FK23 z;8wS6$R9cL*F*W9`Q{k*ciFeQ=FM7wbzUp>S@g)8&7^%YsD0Z9y1m^S>6yOiJIT>B zx2jGwMOPH`Lf0*Dp5|j!D@d5#-QBT0I^GjovPp9m4ZOgz_1)!H(ATu3$)ex?ebFsk z5a9^%{^4Afxh{ygNV$n~Ho^}e;nGP#sAHSiu6HQ#fCe;!)_NO#J*F^(5Xq!&QpdL#}v!+R(Z7LmO*)gMRmX%c7 zzD;rlM4xPc0rRIZw(Nfc*|4#Q9Ac0=c$zzp6p9+PcL$_LqSg?$KYqmj!Gfemk3l`K zx_gukE7HO6?AyE7<0sK6QoH7}hji-Hu0-zfEFoLWcK*;nAPol;Qw(v%z!6pu4nFuG zCGJIBS|s!C?t*?1;^1bfCkE_ zNxJctB0s)ux8ZP-8kbzA3N7bcbI?im4nNjKqQ`XyP->{C)R5X2sT2zz;mVPIJr8UzXra3p9D96^kQ;e#6;R1AgDMysJf9I~XzhX+{{ z(}*CJxRHwr8K+6QE2i3!CNXw3V~su;+Qv&R5!z9`2m!g>KKvX*Btm!+g=A7pHT9G~ zQccP5RBk>Dal{f&Y!F>yUYr-j8gI;T#~yzSa>!+66{kOQ@-W6S%h)+EQF`*}XKMeA z`ruV1+olRIs{bxJbI&5ZdjPuRO4{uKovtRor5dnT@w%2Bjs~Ih8jC*N)*3%h{ag7@Edx~vF+v)=R3}Fr z1!coo!BB+Aw%?9>?gvVjmM`^TW2fRI9lgZd0xL)YuW$)w}%Hk zqz!GPh=kkLvMkvgz;AeamP#53x4liMLeUbOwmQ-`3koD%3E7QG+$WLAF%CIHYuvda zcN&kB4qlf-4USTXGt1c~bfepmz@lfAqp*$#O?t}0WJi_S8E=S0EFxmQzfyETi{Y^C$12&s#t^A8?cg!lp4N zeozY){cd#~;^+)k(CNyqRzDK|F^n z3Pvb49-$x{K=H^8nh*%#0^#CDSwiHfq+b32n7+g!66~qwCY?JJqA33dmfPIqDgLsd zL84a_9r|NQ2zwF`p@__6D$^%OOrn^U3C(CqbDGoyOfoh@j80@GW&1e5F+6j+E$Yyf zvJ_t!DlQA46qO^@NRo2+3oiHnJ+PBy^z&Q3Ntp5sYBi;-TU3LuM^H zh*Sh)706)3L=_?0%%-BVqQ$H;hEYH$EJPEi8tGROc&XzoYUPa>)cI6;yT*_XnGpbo|rh6QdpC$LVYrbU!?y+4SG<-EEv(A)*2!_sYt~j z^iYab48pUi2w)$AQ3^biVitxV1u&4|3=BVaBcPz0lbuW%W!JjOaMT1guu4R|P8Kn|EKYsRkbs%P z^CAo?$)M7tKMr!gG_%oq3AxEnj`C^#88k1mUZ)#g;IANf;$*3p7*F$>d8hh?tF8$> zUoB4<>C=tdxpi0A1MKiP_Mn2)n$l0q*u}Q(p^+FxFjN5xYFGmq!{|jYvOx`RAY&cq z@CG`7<0OCZ7ahp(MotW}k6|Dq7tH|1xjljRyubYbkfW`TnlT3<2wn(tn1e5X!4l%| zU1*Z~HjWU4Wx82NgC0RpygUDh}CuZyxbtpd{?0G^!@n$#LUAe+^=>#pFJ*`cD7Aw%CN~;cHTNkJKZfD{5o| z8AwKlJ@oGk)j$nicMa4~4M>J$nl){aa9POE3prs72S5k2unLnv1%roy80ZOVr*^+V zZgb!XAb5DEGG^ko9YK>R<`X$orgp={50D2N3vvJyq7vD{5}oIH7eXQT_GRgkVU^$` zl>>wVp-$PuT?)53wM2wL<#4Y@Bsc$&Z+fO+j6y@V7ga4oRh)1My_bAl7<|J=d}HE; zV@QT&s3kzLMa$4d&o>q`BO|VNX9s{1(6?tr#SxfyhdKv7;S(q*p%Kp)DCD;g=2snk z^c6^Vbn_Pp-;oFEXMdz}VvALO_W?EBp%d9q3bs&VJH`k)773*=cK%Qezu*l9#0bBj z2zVd{Vvvc>@C?HcctYR?jvxuEKnEF!i-d=E8sQ7am4^+{45uO~vUX2wu!4?#hR_;5lPadcRY3kHPa zg(rB26qoP@#=wPUXpfLKa$)~ieD}zY{pgQuaSX)pR@Z|T;5b*I_8J69YH;XHMEFu2 z0f>#_hyUPxjiMXpvl4|!e}|}khnNUiM-7NLi3&wF&~Xa2_D@nnDxES2$Y5i^z+v3B z4hL|6_5ceK^$UgI1wfz)``{#(g^O`?+6TbJ4efeJbsE@znmxD=|ehF6vX^=9PGq2W$U=&n%$b%3mepL7x89|m*h%Z-lMRtV7G z4ffy`M|h4>7=3XmUfpyPKY#;vnSpruob_0k|G8CQ z7={2!papt-KrmetS5yvH5;Avc!2vKb1ZS*KVVS3gml-d$L>%9!SD6V1Un7!<*qL6D zP*w9-+Yy?+)*kpL9nYznq0lKY+8n2-2-h(W&fp9gffU>(4+k(0q*ypiUIu}8M9H81$(IIdsLCXu#CNER z%BYEkptLsqxZAoCAvwb`BPW1F;$3TU#_b+fz31ZNQjX0u7x2nK) z0I-mCkl8h*l7Ch64@WU7@X;K4AfqxG3C@5F)ldzuZU<*h#55|C5 zli&!eFbi%Vi@zWVwD=25YLr590LJhJJ0Py(Dz0zv26`EtEHa&ghnJTUIbWd=g#)IF z(=97_Tmk>GjA&Xxamt}z0e%r`SKKI($55v%LMe21R7Yrz3fHHM0wd|tg1;Gy``MrV z*{BywM1UEX7|XF8TTMV!hmk546-Ka1)n;GBBi5xaHnDl(_hz8;b3uZkCjl^f*amqp z2B>-fsj3Hg;1wade)j>ZwkmGxW^1vsn$2Mlz3Qu<=_KBOqt$SBI)|*zU=RF-tk2*K z(*O*yNC&I13X<@oLeK@1K!Jr|4C*GO;YzM;+qQa{6M&a@hxb_Ps)0HI3>0CET>-L( zlVLsx5n>vZl^0W5mV-Hv1DMbfa{7jm3Vu6LRQS@KlIlHiLuM?o9deqfB%yGf*03`o zbc+9zw{I7M`#Go<>#?b;I~uExs_VM1OGJnxp_4i&oP(6>B8TR51qW~i^>Qx;fdp4j z5?Am8t`jr7TaLmjydyy<-c+HGJ43bfd^xZLaF7Q+d%Zo2y*|sTB1(x_ClESwy8=NC zOl!WK@+pXAdp_x1LZYMYt9Jh|v4W?c8CZD0a1`L`w)^Y0aQmA?Ilp%+SPfCHB0@@H zu~UFse(549dsJNcDoKbd!HN5(4eDv?#Eq!|mY1qvVnnL!a)O!*Bno#EpKBX4fCLB; zUEzBwc6*lnDg?y*rD&J&VTKd%aHASg}$z zp#TfoRw>EI60vf=y?Py06Dle~W{&3%zEF5XiGfB5f#%A;hupSr@SM#c$V92Oj1v=) zQ(t(=cOTN+( zE2z*d=5sES^MQ>FrK_XAh)mLN`AAw5pd~Z9F!auecQ`TsVNHV%l3*v z#efN;?9-*(5*D1wu~Z4@;0(dw45i?3KuDyekj2!x3W1OVR2;=hEE3}U3t7$0GI0}_ zV-PJ^%W#IvBY|q7>Q1~o(}7zerxMKUiWF%#3~s>8bG;_4+q!g(*LiIi5itXfxk?i` z%_i%-K0`kGvIc>$y9O}}TkQjNkj_nf0EeB}2e70EP=N;#2(w_szkmw{VGncvM<@|V zBlw~y5?sA&jM@dQ+G*^wt>PpW?H!O19q;hacc_xQD$(eR(f)$8{j`$Kv5HH8A|42M zDc!AwT++$izbBp2TN+Z6Y!GAG5mXjA8x7s@3KkNP$+NZHCj^#9(a#c$1U{X(rko>! z5~-2u*tXyeqgV|G*9p!*iuOx4 z&+N%+Vf`~aT*;18B1jRaLNLsQs@EB=C3Zca8t&mAo)+0CvRr+ZfxRvcP9xsr)m`D( zYcLY4aM+OD5Nj|C;JnyIRnE)c4Zna6u9OSNz-g<-IW}wB)*H}goT_U7T+jras#zn) zbG#vjlB*h(+f7?QFuJR+3EaXRxE}b?ja+!@_N{EI++}Xk6yDs_DG<rdP6NFwyZBVe#ODKna8)&T-5y8L|j(2Jc*K!Twuf7<_+-R^)>$N`T z3&F!Eaa@7@VA025DG`2j2)3+H2QMzq=+)6fNuS}#0pT`3&EVr^XVhS0Mk#Fg6+SQtW-HG=@Wi|8%?6(JODYnD z@C(yWcJi$mNHz?(kP5Rf3(OmPW9;pzZN>sk?nzG2p-@NZ9vmEEvbXIi?vB2pKnnfD ztMV?R^llL;a_=C0+-rLf{x13Bs>n#e$jv?Q50BjhtU0OwqGayVQ=h+EzyY|8auchQ z5k1}KiTk+iBr`G+wpZe-~+252syM5^1umZ+s@BE@@qf|SZvt=?)HKJ%bb1^ zG#|z;lq&5DKDhzmXc0#~kEKpB^h&S&ZNcF-y#3#Q!D8}i-`@Ru`0?e>r(fUxef(pK6iL$G z|9=1j6!5?N3N-LQ1QS$nK?WOi@IeS8l(50=n5s^!HV#P0IeuWetgo?DI;M>b%Y*ES zD#8}n>gucV*b;P5LEU;Qu065hip#*p;|oOW*Z?A|3bl*MIbbxAbW)bMY|J?08sl;w zsWeN{vr1xGNHpSnxFWY4>IjAtfA(>vmrBA))gN?_apr(4epw@|HH6C{ui&f$71YL* z!%d~%V3U5Mi!xeX2a?3UMTTIGV^MLXrC#7_`B9X!j3(IUG3B@9l1nw}Vk|G(COlr*hkeW4z z5(+3i;FNPtJMZ*P&qTFa^eeE?BXn!7cQEEHe-N#jtA!eM)H%I0O-$Q6edebUF8N7G z+Etxh_A$7-D%I2+IP(k>&{mb~0LrdlWtIa{dFB^ns>u~LUVq_al2yh!O|N3F$m{N9 zle7ETV-BEp^nh2w3qH0}f9g^2#KZS>*khM{_H)&3_x1s4*L`>1d-wf!;M1#6Qce8L zE7j=S?rX$0CTsQX7AN^_5@E;xidFJsPIji1UY-etV?u-j?iWIik;hkD2%&9dI9!hT zqbO&VpURWoDG8P~UDh9#zy%K4qNLSCOgV8*+;o-*n;7M3M@foy@FW$g?a5DG$=Z6l zc0sln3NBUCid4#0p6Mo@L8dWXxe{hh<(awpBNsOc zOR%mGh(I_(dck;xH|Ft-QRoUCzgUMeSdp5rTy70eJU|_OF_sv{5IJ^BRZ2)lEljy5 zg=1s`Utr?8;H6QGYh)w3_Jcb(2B?j5q+=cJct<=6hA_kf#-=v+7=$QqCCsA?;Ra{O z7+!&T1JRrzNz@A_E~66v>#)UaoI!}@`5+Lh2!=Dz;g60PghpeKNQo>Wv-rs@4>hC4 zJFY|x{OM1YE`x>7V7aqd+N4aX>e4@`u|Qzrp@9yZT2&G?L4N=$J{V+XTfo)~4$i@Y z{4m?u{BoB~aR-H|Q{L$2Mz^lja&Ep&6 z_|YVARHP#%X-Q3rI>V^2kA$Jj;MyQa<`uN1k9l4U^KvXeB19_3sKh=>21*h^1|k38 zQbSa>vK#=gBVm#M-^*C}4yaN?XS1YgD5%jTsZv#zI=gCD1PPR2BBf5m%#$(aG6zpw zt%CDuW?Ofl!LV^~QPeySx3a07#B8%t*K!-_+*1+&nlUp;8y9 zH(bIPD8eLELWzD+Ek^#dI!m0qgC($p#VXJ1GMw;3y$|)7FT+}sVM+~xW<9G~*J>ZP zG83+1+f!ZtxO6%Y7I%0j)Yc4q5IPrf=!<>3b6}+ zW^$9A{N(s(O2LKMSB6UD0}&1~sDGp>O`!`az2x*qJk_#L6GGIEp>rY!P-Xl&^3*G3 zBdhPFDo(Bhrbx6mmhX*kmS?OIus$un`ke}Yvw}=z9w@*Ve8blcRW$=IWVP6#D1)`L zoW9x^Qf1B}VQF~SB>4>!{+L^cuhY}F>RAGS$I-l3hGMQ?gamnYd`q`GS)EO`bT^PRXSAvV`v4a+U!2v^hnu57bu2opZ zrWof(ETnIju={GUtopDUjtC~c`8Mppja2?nb!gP{Y8)M7p%Ip~*;WWqTpL_lc>0r% z3k9|zFI(m_Ut_V2%`TefT<1IYodZ?)6yxSaAsriym$?k`kS}E6O3!4Dl#V1dQ{-hJ z8L$1y8;NxD85Xe2YA9ggBzSw(ZTGA9eUlOdC~W6}VKcN<(5hAm{kv;$g=V56EjOnB zj78*Yb6O59-Qib8`g28PSR0i$^B^wbQXOdfGUE`z5wy188zk(?Hi99(;xoSg`LU|5 zl8HT|v%H8etV1vSi9YFzL6xw+8$2(w)4uJ~H@QHx?^BRBNJ1rCLYE7_(%Ya!nJZv8 zzsYz%2rH4WSh#5m5tfLl%81G$LPI8sYI&xjjVvyKy-p|`-onhL<;n1QAUi!wT) z0_2bb+>1=Hz4LpZ(Hjpzd4nK3Jq|2HLu?P5yFdXsL`H1H*K4ig8jal}LFef`%wq__ zayo{9IyIA}DDk=&43l@G!5WM=e`v2fa5t}WFFLa-ERjL;YCip0pnJnB?mIMo`@{TD zLLf5+Uj!Rq48~py3tt4XBy_??0~-R%io4^()FHvj;3Zz-sULB}vCu;QYdnDDm^`GT zKiE0|`%98hgRTGb#?aWdG_*E2oDAy7i#enerXVgmyu&^cixaZ61vHEX)Wtx_AeeJR zfDFj;us}s55P>{Mgk-WDb1+E^!_hiHZ&N|0`?gb=2#=tdt?NOl8bwmfi;P@|ln4u0 z7|B)oK{^u}uQN$mq$-~{yJqu_Lc>L0AS!-*4_>?kUv#u!l!{^KNg?}5pcJy6OomJt zhLHy}(KU6vHv(hmAACbV9>&WWRINo6lLt z$C!Z;qqMyHyu7f(6S|goR3Ur>JwLpJBRmfX{Ktgs%YY=vg6t3fzZ^`$B&l3uNcqz} z=z_?J)WkGn!HIamlITJF8H=pDj#|2=5ef@x;K=t{MbBJGtrDhMB(w3ljV926tm57^4=a|OEC>X7z zKQNRoh@-zUES3AKI5fn#<6#WTNHw&4j2vjk^O(bTB%w*srn<~AmUF;mdctohO!(YD zzzodztWWz)qr*HpFf+kROhGLiKFG`isjC_J!n07&i_5f*%=|0tKt*-SgBcXftP=wy zK!TOKMby-rnnaHz{6(f7(1SuF(*`cysR7~#yd+G6HoRa46$&Edt}lkZLPK2Q1{qN)4NYAeZ52s zO#ir2F6~l#Q8{%iK}2FqhDa`KWWl~!0s&p6jEt&{ybi4byRnD_v4}5_49W4JhB|An z(3DWEqR@p|7&#=Xt~gC2w4fb00I={-o`lWWJW)uER7uSQq-;VAVoJG~D;NcW0My1B z)v_-ZBZK&k}|f5(p|j|_aww) zO<5uvRz*}mqBl@JS;;KKFd zx>P*Z=1U4vT9!dwPeV;j>sX6M^Tn`e)Ud$K@z7VW&DWyrO;TIYOKs7n9M1WZKMnaa z0kcDG#CHu*l162?GA=lyd_=VZ?s}3`x+=S>C z5dl!*gM$nyhFZZAsj@ii7+nO#);Xm<)Sa-PX_K!jVA!Rqbd4e3O9->F-2>>=*6hjN zJrLmS;Mz=4di7W1eYC8=fu8a>>Yd*I=3SoTkY4EAKe;s+>OGE|A(cun6~H;iy_F7j zED+E;A%4gd@;%+RxCC)Y-}p`9jAGfARbnUZ(goa?(CNZWTtOD(-)txupsCDjr7E#- z9|A5~*!mfVN*;drI-Mbp2X>hV=A7ghvoZLAAHadFa93ptL`L<8Vc1{?@n8=gTX2*L zvn7=A!vQ&#<2E1$6u!3epp1rl+fXf!hke+OJ1BL8mQ+ip{`r*cW!AI|L2Sv#kPRVk zQPFY1-3WYQRh}azzQ9#}Wx}+}J5)N$a8}HX2%gP`jbpdaJr7yb3)3azGN!LyR^xL8 z)P<4Yl3|E3XahtZgJlL3Jl0A74R(WZ@#78_UfnKqv)JuR?F=mbDW9SS zP;d{?Jm8DQXft+>Vzx~GKNSPnon1IC>1C)De@JN_NbDC_X|u>$-34fSiRrNAS3$N^ zvv`3QNbF8{3vcG>AMk08a~^JdF6nGY(IzbHShx^VuKtq`r%nk{*@qjR>hA4Mz>p8E z-m#YO>U}oia`9)WK-sh&?sp;RnQpP^(|LpnD6UscUA1Oz9|YmeNhfcuqEaz-~C~t5U=k^HmFg>V;y+ln5ET$f9r)G2K0OFRQ zG4#Oa_4Kv>wt%ZVe~Whk?(h(9L*I4-G3&+Uc5pXL2O{N$OK}xv@kc-Le*lKun{+s+ zbW2}jIvwMMl?hLG;FSdIQ782wM`Tn#099x2F(3qD*tld^gEf!=g_nU?Z=+ey%_4vS zh2I3QxpiFE?C;?6Z|-jw9&G_nVGJ?z)G~JT_|D?24o#3ZTVown!D@G;^AMt-+eM25 zz{zU&3V6YGZ4Y;zr;kA=^qvoTI@%*VnHH5;^mBJ~Q1IV{VCxTL3U`P1cz@tv1`}B7 z@iaE(d=GE&7P)>u?|lGxB^UT*IB8Nj_=QhU#ddUzcu0=1WcHQb?VqYP#Dk_qGPw_$3NS4*eZi<9dmXHU5WjP{bHc}2DP3!m4V-|#9Gdd;;`F91xvd{}4<89x*{9pTX(64{@=zNf}fBnZ7;woQ&_$QDbzhZEL z1c3vmSTTPDfoWm`WFkc%L6+RXqwxU8jvhaL%p-Cn$&w~VMxy4ATDC}`I;Px5kRUbx zYOr2{%-QiI&pcv~GTJ5w~Z>1lG4Ofy$uo7F4M;}9m z%$Q$C$}?vQ%&d9yKz{!S9;+02G~^jGDx#*?QIn?2pD%kJ2uxz?+O}`A0p`%3u{Vu7 z?$}}W(j~seFa1ugJZJFc&EFK~n`t@q>ejDg&#rwt_wL@mgAXr$eDWeilAuqoem(p4 z?vs#@FMmG$`u6YR&#!-f_Sl^n9s~y{4b3zgZK+*!haVa-h{ta|L0D2G2T%k5%7h-p z#7|8(DHmZ$V!#oU4?>YfR2xbyHAWlF>~p|WRb7?UK6)iX%vX2eI93t-kvEr*KIWKX zUVQll*j1eHMNm_RwL#2G$52__U3SbdZA?j;X}6{JQERTb)|n<` zvRPYheD!8saA!eh%yB%X<(zZT?Ul)Ncmf)zpo0=xsG)|Q_nxAQws)wbk3t%$q?1w# z-hTovL?A!F7aL+(|ikvs^t*FS|F_QNrX@zcg~v`Sh3B}Z9qxg~6% zfeCJDGkDadY96tMCb!-+B) zv7!!BT(QL$W6Ur^pk(UMrn9vfL`I^LywO>(@^oq_CansKOV^?N6N$9ix>O}&G~*&M zoxqrtuU*;Ltk7X)tgO*;)itzO&_+8gwMk-oSYibE!3`d-L75-w;b2_35Cqglbe`_BV z;UmQ>Vlj*7E63XO$G1DOjC{9TC_@{nomk3} zQ4XCbMJtLOF51S6yxb@r@^GrXP~#ny0SPsXi7M^?fDR}eX{J&x!uCP=a= zmTh*^aNi7J(z3~kP2{dGf2o#3fagN1H714~8Oi}7c&?`|1}T?>V2Lv69ez$EURa8V zZpb-M9u+hv#0l%6?50qQqBX4(U0*~4r`ET^6|D%;B}X}$5`RR+TA9(wO<>`jQpqd_ zE2Y^nq@p#dMT;2K3>I3l2?JxDZ>J%&DPDkT9BGZ=bc>N1w~)#ftPS>^gLNuY*J+e| zO0_gd7!Oua)0(b{vQT8@$lc!X2H{M~tWAt7Z+nYHh_-cNz8x-cqeu~r)^(#Pu@cul zG815K2e1u1fM5yRQkTMXv5nziAKxcg5QfwLr$L3$)9x6xqb5h69%1TeY3MaDp_WRQ zjPFopuv+o7);65lj4=j=TaTdf68}9VDtBAl10(owzzwc@671jy_f2GC&_iuv8<4Vi!x(-wdt0^ZPFC!Yf|mq>vL*@z|2uz{vE{$}yrH3i952 z+DqbdzM`?}ck=5dU})w}j}i`U#W%iVnbl6xfiRV;+^_{RcyLzUGM6D`jtVFDt{Cpx zb6wR&2rcu&QgY@@PAF3wQKy4hWbx5l{Nh6Lpu~H@))=nat#*z^%^!gzGkZ)r9R4`b zZI}&fjf|SyWF}5;kaEEM>*V0r)|8h2-cu9Z(B)5qdQfc5vT#Ff>QmDP%*v(4n5{>R zmnE|&X;w37PUL5Do^YnsA(o2gOlM{Fl(KlqU6F|TJI>C;vuc5iP6)l!cMioLU#m5J zS;G-)7unHlL$W}=dH{p%tE`vS)3??m#`bo!?L*CY z+aus6)VQ5|P_gnw)B8zxpXlxKmsjWA@U|k%YhH7EOAg=pCi8_l)bD@OdNgcCY_3nd zoP%?dp$boyo$u_A6t1vp5>Gb&pp)v(cd~{JtI@;(a-$uOPXyADE}}tCsB-+2eB9qQ zrNJsKD3%}0=5n9APGk;my5s%SI47CTcYdx7`CQg2)iJei?dH~5hu0Nd`j48vM^22h zoQI@w@Mx&)?!=H?@Z$Q`55V!|fIXnx{)aIHe8hh#dF5$WJNPDjc(=bDm6VQq-fLg; zQO~?lw%`4O_uinskNNLreh``mPk5n+xXo_%%5@H&Q;RZwE{@-$!}qeg-tna{W8l)4 zyyH9~cmCR3|NIU;E_TxU#%^h0V#*1+`jQ{u4X-!5Yzr)%Rq{UnrndXt_3!_<`W_wt zU%3dMOY~226d%w59P-WonDQBiH6>n<^qN{l-?A{=STN1*5Y;|li#iRDb|{rvU|YOg zPjY~rCXC)!so(b)N9pm$``L}_&EE-;9lF_H%l%&th8q8onhyG)L+#xFdeUXsgaK*< zg-s4y$l7!X)&fQb1QiwyEgxe=ARiT11=`L9h6N!_lW`mydR@o&0YPK1LDsnj`RRoD zjUM{x#0sKb`{4-;P8u1_APtHer>WZy>LHc!V3zISAF`6Y31Nmk*Q-SW5=zcmpqT!KMLgGBo{0U1lrJqF(PAyQ4UYcT22&R^?b$@VuvnQfX$fjlTQ2)0bUP4@zeQ*+*-JzPOu;BkzB!;l0CW& zfsIcS@#8@Hq%8qtaQ);^T1+``ltIpmhA3nJCZR)4m&G|_R6wIlN#iuyg(YHSMs6fW z@(f*d|JMogky>KV#&Tta`j2u|YVrtM@N z66IgkQc$)PU=n7f@RC8+#6E1uAu?sj$QmOa-%&iGh*4xk^3n5|T1M(XHa6V+$%G|= zVq~hrb1prb%^1lq9Wy{zF&QioiE#K@fz!02Ue;UNwdW^QItFZ!bU=;m(@3jer- zO~8W79Ajhh&xaUaGdkiU#ztjY=2g0!W^Uym5!)fnNF{VaXg-^|pas}@o6o&LDcq;|CYo5(L4rIbvZ+C9YBBf-)#sVCBncB{o55 z2^oi;J=Hy7Qu%qDZdl2N?i^>h=68gs$kC;LiD=u=q)y^ZPtNF>W(8M@|Z}w)qk!q@bfO!P_C2LKFDsHOk zwLZ+LHW;>Y>j9)hC>*D&ei5wR#;n##t$xOg;i`5ts1GhFlR{|qd7-eD#@Csjf8^Vi z+Q+hf+omc}DNSqrRqK3qYr#&6npTm)j_NsxD=+nE5ZFs|LP?Sp9J?ZEq2}Pb!fQ4H zD!prTroJMan5+$!62t7tJ}PX?LW-$stIW=5!}91IECE&-1%m$R zj4@xXB55#c?62ld1A2`QKq_{OY^&|1z&ghpjwzTLRKP+la`1&J+3eO93eBGXD%aL0 z$#6u&k}FotfDia=W~{5w-jq*XBV_q1gswryo{QFn#|d&xoSYogo?h8~Db>bixh>3| zqqk z1wxCu25abEmA0|LTehsDEbCqV?UK#b-ac!k+$O>1?)SRe?Y0m2=BB-gffzunqj?>^ zN`LT!yu_y%N@OFsr_~x)bZqx*~Bnn&Z1-pR=WrvPnEPZ}32s;)x!G#-;u(e3B z$JnjC2JtE`hyVUB4a0B@V{a?ojp@ynrD1KKm}w8A@o(&~;G{7y*6GeduMk@<2K$Hx z4=M+f>Jobd35oEJM6o}RS^k0^1*hO`xo%^$unUiIzp`%YK5IgWvBD6psJ3w>tMMAU zl_l$8$viBcs;?ZYEgdV%k;*^^&!`@E#OuV)(L}MWa)}@}Mr)D(?$`m?A+LoN-{Jv_ z)$9o{Sji%Eys&NFP2rxgCL1$IIB;(sa}GAh`R=SIQ!Xe2swmSAih+eGvneVkFOI;# zAN_IHz;ap;@(P2oEvrQ$tEet_u|M=O+Lhc`jq#*Ct%`yVB`@#g8*?` zatfA81qK)KAK7tEaB%!`D<;A%>_}ECBP0sP@)c)BxVfV_vtT>Z2LLy+B99w9gMjG50gN?HxA9J;#ba6a0U$RZ zt0r8pjZ3~Z7%N9~STy!>v4~!;FQ?r+7cPq0Cf#uVcX%IjV&@)$huWi|;CQ09X6nE( zhtPIZAWvgS*D-e?V`^QWg_KDJI;*xid+C42q4=<3b{BX@Of`d}^mj{?i#wEG{U~)% zMCER1GPpr{V~6hHaOrY?z_Xlhpsl~?(J zb2(z`^FH@^D*BQ{4-jcgtlXFB;AIn$Q zV;w^IMsK(G20CJE`J$9M7Ci)ci=Ia$x}t~w_gmZta&N|(c&IzS-=`Y~^Bza2_sePf zH&i>yiP9pdOR|BJdaBpAsMHB)nh z{Nd!Bk9hW0x1?Y#9loa|KN%Tmt+N|5vp2iEn-3zr^@CG;L4yQZ+k1U*J7>_jc&xVf z93HPLxvz^hurq7Ab1EaZySp3smH&J0(mSA6{NV&Ep_}EjA3(KRyG~$s#@h$CJN&*D z{0>-pxd)8G(=}|)Bs;q-U|a9&4SY>bJjqwGf-APp_l=az1fgH)$B%Ve5Vy~lJmdXw zY^mOL7yJF<hU;MWIy~~ojd?Wgfr+so%_~7fu(qXu; zZ*;-0{H`A!-QzmdbNbBtx1DG`$t6+OGk)y`zV3y7_{blizIw=0$I+BNe<-~z=10m8 zcr99frfYiUyF0Ybjm7jmM;vbJgD=>JJ@7vYrOC8*Bn$ELh})aEX^T6=&!2PiC0WJ1 z%SXQMTR+-mzw)1{@b@403kq;2KJv!}_~XgzL;j?%-bYNn%3``luk-d#dYER6{F{G^ zjy~z%zkZ~5cmRYBfd>c{GS6!;NjNRcCT zWb$|N!b>%I`ZU_G<-toTk2ZDs6lzqd zQ>j+9dKGI{ty>WmN%9qJSg~WtmNlD%Yg)By*|v52(QRD0bLrN#Ymj7Ky(Mij%?k8o z!K6BE7FFu^u3(@-`zCfcSSMn~lPOoWd>M0Q%}0xPJ^L9n=*^=^mo|MGb!ye9_qGmc z5~X3QfP)@{Z0w|Lp}G?tA($O7%e*OD1d#3*XGyVh|kiY^BJa8)T zT61HVf7~0dHl!kiC_VMaQ>wAi;v=X+g4Vk%xcd+sk;D>BWXL}NRUGTY7F~Q1#uznI zur=5oylTS7a&)Le$^iQ}bx)r6Y?#U{xyb{YS7ot%w z8&m3S$A)?w@_XEyc5qno8wZi24iy!vWUi<%r`T| zBQ2(-)?|~QA0gS=kU~-ET9mLG(S%9S4-v}g zGW$54l~yJzwG_brT6Nu(S6w~*^h~<~Efq6V4`@$S3xQhd4Oa=GDb&d%leO1st<7&v zTvfc5+itye@>h|(dKpZ0 zkqs5ra%-l|7-I_38Dq+NKES?5mp&Wqhq5(#8}5Rd4sYj{C8D}&`ckdCt*v2_ z7a_2twQMQ>jmaJ;?!@0-n{Ck)e;o3U=hnf`+!z*gD5$k=_*j-E|g~e;#^0 zY4_Z%m=l5)IO5kr_3FWW1RSE_H9Ni0)T2NDTE?3<3;p)pe{%YovPRhYz5CKWE$go) zmoDRK5?*KcYYX`@;Rf@)4}qLg-}=asKnFh1K=I>S-z0{Rhv`gr^Sev$s8^T5p@bpg z8y^AT0znf>ig^qK%L!T7!s|3`Wxv~8%?ffs(g_ep9F(E7x|a|Ujt_)~JD>}Rn57h| z5G_UjRN@k6)U?{w#c#tATmW%cmEK*jifZwlO}-XD(jcpRLuBF@VYEObu8@prRHIy+ z*unfou_fJ`Vr;S~6&+5HhyNqU4>towAtG;$fkcoQ&zM9(9ukpKfnnutqCpD6(Q5~= ziG${tLHg;fb95w)act)Qj;O*>o)VQBY2yw@1;-rCk%}|aTleZXKsmA! zGan2iAXC}P>y(m#z7*y#6S7J?a>bR7EC?lGc@kwt%~`ZWO-?%Ly)Oo_Y`i4qHc>;! zLUI$FsWhfDWm&WHG&48PY-O1&c1-nT(w&v@V>ZKC&(wJHjFvH^J^9J4aa!|{ev9P) z=upDUi}CMsg_0&}T;jj5eG;1`?B_)LQ^=zwW}g(*sILkZ!+7Q}it|G!LNB?Yg`Q?O znX6@7z?cboZWN}I0cJ4k@|Bq0bXNadX-|?V$thBjq#JbANl}^ z=2I>st#N58GHQS@o;4p#~`-noA4+t6JZ7 zB&}+-3YC6a+!nF+qjofwhj263+}bX)w!Li}p?15v^wl3q4Xtsxi=xuHt}4Xs?sy|u zu&cfilh;cahB}LtHEDLU)RmBRJ!li{k{7=a`7U^)BHsM|S3l;JZd9aJ9%9jUJ=oRV zY63eSbvdSc_XY5TyJFFc8bvG=)^K-_`_RkrXs(zw&w$~Bv)w7Ceh?;XZ#PWg;0kvo z8E)~6u_NHt3iZH<@(p|uT%ii)vL-(Z35{L6-^O*sc|=w+b2`e%5X+^&?0GWqQc7Yn zQEa)B!EOOryyW~EnQa?MvX{x68XG4!p*hy^dU#CRrKsshy0!0+%lu{k3!eoeW3Ka_ zM{{Nm4{2&srgBi)oS8(yc~Q9et6U;XXFhlL#Wa;j10P-K%@mB0043AZ+UwfD6neVL zLUf|!N4Pn6+0ws_v|=Gb=~TbEGJe)Hph3Lo60_OL33V5iE9Nzu*qYI&mME-!3+6C0 z(MiC;V|;fiai4Ncz~3VP5u8~9eXW~z~=rO}SYxLd^yHst3hzc;?|4%4F3sqv9t$*-Kvy9(Ztj_od~$k)zN%p31(4F5BT7B5E0PxSHI zI{oS~qW96$tY$VesCzV@@QEcpE1aC75BJXY(np;2#H_oNf?xcKP#*VI%&J!Bi1zBO z=Yk9F9T%Mb^?@qIb`|8O7t5c!oyQBr$oN=&5x&2;`c1C#u%=pJm^p0%9g zE|Tz5H1&AC|Ngh6boVP)Vva-ouFof?t@G-I`VO#Oevkk9DgX4W0V5Fk6cCxVX5k2` zk_fOP7UTcY0{#lB1A&eKBe0&l&)-Op1b=1h$V6f;FmN)^{Pt=+LJ;LXivkz0{!|VH zx5)(kYX=)}0(%eVfTG=CNdq?`QEcc4tKx%_Lhh;mQ|*RYqmjt|+8 zPnM46T2LY65W#W|IOb5Eyhagu#ti>Z_(}^BQP5NW$PW*{kTx8t`BFpe><~VfBk1;U z5>IKSMv)Q&kp_9noG=iBmg8@f&^dO(NI>xsO|knz!xmEz6~j>Z;E?$WqextlRZ?+) z4xr}x=z_RR?s74e2#FbWkw!Mo6A3K#z(zLKj|Jn17(L4v*K0IFQ52ss4f{nLC2$v~ z5h^MOdtyVGurV8@t`VihYrOFr&F~D%QHd%AAI*_QoGl)yu~61=78Pa*dl3=Q5dn|U zHt2D%^e`Ovag96!B7yK6FLCG6t8*gBE9%s0dDyBKvV0 zGlFvpVt%4bK7=uNc#$%UqZ{W-Ch1}fvrGH`?olO!QYhV~A}!Lr7}6j%@*@qB^AM6G zi^ICIj3n)GD67&cBc~{rvMH33IauWvwUPP8uM#cOGH8m@1p$k`I1;mR z#wnk2F#M)0QQ{|oQZ4tAFRz75q|qp0h9Te*x^U7a<#E(#=q^tpFZ19SRZDVLJ5F(K14KeJl6#2=+CVWf{H? z2+}zwW{>6)t7Op^=g$$%GB#y7C@Y!x65Ajkjj1xPv z^Eed*RDiSNa5Fbs!Z4q62w7#+1h6gt@6bB)LOa{jJ!3>PTQY~1(=<<$DQIt1tLn0MpYTAXLSKb2tgqLND|=qHzT$lRjNj z@KBRMJ(MHdrRpS!KmSqjD3tLqlto)qISiCMD{x0L=Q(s!t3-4Iy|NGs5k*sUJp

    LN9Q7)JGX}FNPFLvlKJ9WJ8a1ma->2ai)vv zvkVU}BK(0$fzF2V()6^{P2V)&xKlo zUnK%kC28JH16xT)If~U-6P9D?6+8q{S^kDn2|{1ZRg=&pT?tmV63|_L6i7Q3W;L~5 z1D5ZW#Ul7fJrILt5s-BMkP<{RHeO>^Xa#g;BlaO^Lr6+?Uyal)b=GJ%;$o9TAqy5S z;WcQ77HhF{X1x%rULul4_65(5p>|?)o|Yqe(inEK9u4+jv({}1bXmo=VR5w~qP4OR z)KvF~YpHe~eReUqwKd*Wa9OlyHv=$i4QD6QX|Y2V`_^wwjcqq}a3_~IKUQunPe)nx z@7S?MB|~LRgIPReYJb)qGnH~r7c!TXVQ*~-A4e7~SRwi@I9r%dVHk*?5rJ1%IUZPn zonj!ZV|HoRf~Art<5zxzScxoW=tSs`SK`oC3lL$nEzxLdTFMF_oHH; zBZZ>~a=(~>#Tbt7j*NGo(ok{hpzFSj}Em_PJbjT18ykA-_#*n2nll25t#=D2tbH&7PY z)Ee13{uPunS1d`_jo%oRa~a$+d4?}iC$d=1BGi-d_FZ%bX&X6!iwBCMSeKg_<6HwU zSDBTG9xx z*@u6aobUPN%z0cXh?=`&Y(!a-<4rfmgi_^so*S~Bml2;ATH;)Th`X{jZdi6fk3$X` z_Ey+L529HtdM#8Ha7~$^L)zT*nVe!7GF%yQu{odzv0^A0s zM+}(%gIOmyIyj;AAzu2L-W5D*+Ne{Fq^p@FULr~TnW6!DHEu~zM!AP&dZv#WtIO;F zlt630rhD1b)^UXQ*l@gglk6&pe5j{=8lkOPkh7YtiEKe0nwYEgPSyE|g_Wx9VjWjC za4Pz)pK_U*xvc}cySDnAPcwF{kFMcPr8gt5n~9m|4WQB5vo0o_#aXZ~JGBUVpV6x& z+7dsNn4-nnmIqdk&RVi3TZ4-lvsW9xS_7^P4tYOYd&^q1N1L>R2+>^iuK}C2d%LYP zn~qt!r8Bw^{VEnI8YlX?f3_8DMm0A^GI`Z{t$mxiMaz(Jx}7K1=SWps=f$*7gSkfv zx{>OZ|1G<^&wHbQTd5-=bHVln(^$7dTe*3bv<>>S(^|T(6TSEQx4Q(pVS5K8G=%V~ zc0n(ZtTYW-nUb7H}(I=ce-sv+FO z)7!tZuvCY8bSwhC*H&YU`M!VE2t~KR6WX3nT*v$Ay1Dv8#d9MP5xgIUuVufl;BO=p|U>SY}9M3H$uG5oJ z|A7&-|J=w)a$Y8Q(mQ(2={(Ul9fB4;xC5%%{+l`aw8$@gUC+bRYcSItoYPxfd7@m@ z=N8yh9EG*K&6OO^AMAf?gNIY>)-RQ^xy03n{m%2^kV*5ffp^baHc6n8&~Gw5$g+up zLfRo2gMWP^+KR!#tH@r6#Wr3}|-DUFKNk!L@c-8Cu-XC6RzJ{d$2P<_5MFIDx_v46At4^+VaM2G-9q4*Z{#aK&b{N6JX8|?Lyn}{|9Ab_ zQ#IIyJ>`Esc|3jDs|I^W3gajKY=Lp+k2EBA9g=k(jtYL~UA*TH9q6xqbynWTkHV-_ z7UuCo=9fM{P0Z=7-QYFz>C;{-=ABQl-t8Yp>+{?LYnVB~o{P}ku!{ubL;mc^V>oQy z-Wr_S-=6RXChqOEJB&&{JaXY-+c$5Xiz69*u{|o5yzL7g^Uvn+KYe&JKGK1s@k6a3 zjDQRdKoTV30LXyXNM91{pb2E62_#_^PJi}KUkhGB3r@fFZyzXPUlO#y2qwAe6(sYE zKWRup-|<87|Gh90bIk}M_E+H-W?>elUlL3V_p4tLn!p&f;1{NU7FL1!|5t(ccfby2 z;Q++{7sx**j6f2;zw~4Jqlw@6>)&KHKinCLVwt}$LLVRw2pmYTpuvL(6DmZwqv4JN zWPYvE(qu=(S!51e@^@*65lO#(Nvdd3q{k*kjF8-+WfsOAO(e}4DbS&vSs^nn+{v@2 zMt?wo4$GvYsL`WHkNRB7w5ijlP@_tnO0}xht5~yY-O9DA*RNp1iXBU~tl6_@)2dy| zwyoQ@Q5?6hGf762R5&n5GB+AF zu|uXwO_r-xUB>G-XeKvuQ!5?Jy0z=quw%=fO}n=3+qiS<-p#xB|7+F5{?#@1#&^^m z8}}N2`ld9{j+Ju<*3!A5z{iVgY6+H#Oyq_)?Nn~4CA5*io(IB|w2I7Vyv_d-RZV}n z{rmXy>)+46zyJRL1}NZwU!_LZU&;}vo<<59^5&^V$?EO5;D#&ixa5|rr(A9XSL=>}3i{Up zZ|sWOWHDJtsG}VsXUvj24D*XK>xB7?J&aw}5>2E2qEl?~)wM0RMVTw{#1vO-@x>Tt z%oVM65m;Famt?~TlMN0kuWe08R9;9dw@g_>jqUJ;G4=!lus6s&GY>(zC=61|Ezbh1 zY^Fktl*ULWt@P4NH|=zgaviwte>=nwgFq-8fC33w|C4}&)>@+wgJ1)i935;>rYBI! zt8514+aS$kM-vpDXN*AW{A&+7&LE@CK=xFluoiGbiIZq*6J6xP5I^nsxH#;5ohk{e$c_`J%)@o{7+*uI{P>PI*_qH{yjrX`yftXmPeaxF^*f- zi=YH2NWltPutC`SlW{mFkk5Hf0tYBx`9P=v{|N|T5OA2o1~ec(^=V*hECSGj?sl@b zYz9$XYER-8g}AjC};rb#l!Vn4sgdvoG2oIo$O28ouPfkz7VcZ zjR$yvKs2BMRcZhUo`8cJD***4xG-y~EE^ujV@JL;;RZ(N$s2<558)KENXT>$FMCr- z=W+6x(2S-ur>V50xS>dQyA2pixJnYD|B{s7Ok?>rFb6oq(h!O`035D>gc5p=K$kEE zf|jWp86gvy`*@c?_(d|_G}CC*45&Z{O3;GZ$&=5i%?`i^wlJD;Amw|(3fK4o4V*HB zY*4277Or%F|-k(2sUJ`X&VL1#+Sn%eZHzDbJIJ{gasz z8iu-4sHNnqYDbyfzK$Uel>jez4H4e*!a)`Pm@Y?nOE#^ZOpj`bCxY0^Slo*~8`!`bw56>! z3YH+1@CQ2(ncjUawpZ2p{|t2?vZ9A*W@y18QK?8Q;@ij<#kex=ea0G72-f(_Xil@5 z_k$Yh#V}s8s7FoeQVZzDUR(?KP+RAzboT`qnnWQ=@rqdl zBNLS{#6T2byaRZn$pQh&0E6)hK}hBRGa-YgL{gD@NkT-Pa*=C(3tSf4^Q)=eFMj^% zOjCRN+u#m2ZIF_QHz(9Tk8#8efIwbb%pw)!4Ky4!@eF4;!_e!n_W^?O>r2Q%CU&qw zFe{W1f?vp9t(n;IQeL`+?hnXxfs3=%W7vv2rp%lMJMI`dj@=c@y8SC&JL4b0^YNWl;_89b) z5~qbiQwT$7S`WfuQ}izPra33Zwm*t%kWPy=Tc~mR)ECeA##_AV=GI9OVs(&``!;U>YTgh0T1fK_aQiPKf@I_eEA!ToyBFDeMI+7^QkQN-Chd`;i|&f*ip zIU$CxXVd@d|M=n?|M+OGI>f)SgBvh-Ae+bhX)O=^0|4OwbO^~T91(`Gx4aa=D1|Th zQ4L?G*B?9EpFQ^B`hOV15eJanK*|Gji{ON10k>TPMQe1dI>+M&5qy+1e3^xO26%u7 z$Xt+@bYBqzceVjRAbrzE1E>`Q(KmfP7J&y~fdbJ5WwHu(00%9{30HCn)Iff|Mnr9w zNbDy(oe)efLQ*Y3dn+Rvj3y;0<$G{-7yZW{Q6zavw`~MiRtZ>yMtFoYbrj`hZgC|R zT1RITIDJw`0~ol05O`WqNQFH{g%Y>{LNE!x;0Usm3aO9@c>ol?GerKddd`3jM07x< zP!W%T|AT9@CBcFr3uAD>C0dtOU;5z}jj+@269O1qI!IQawu}T>kOt{AN0Bb)7Zd=<70w5N5UGWfC=e2PiJG{9P&kDfFbR_& z{{$AuiHITuLO=+ckO_x$Z`I%p>tINSR1KvNbI+y)^p|&rF%vg{9f4s4*nx|^I5ofc zhgS!DgXn2eG>`{*lt`JB<)Vba)`(p35Y@|Urxj#D;09X)1VFF> zVsHuq@ek!UL;6+5D^FjIDi8T z3IrOM8QS>|@_-I;*MtK>A)e8XbaQ(?jyx#?lNnWet@n_pU}hI*)NH5WH}Zd3>L2+Cs)4#3{n!(wx~DDr7cOR>t@^Cc8m$Cjqp{kkS*JeEi4f6w5UABk zH{h#R!Krz)BQg?KSjwk_k*w9$CIM-TW+tuh8n1;)txYMbO+k5JldT4k0tk^;cS;q& z`me(Jspo1O@l>Vis;q)qh>9n#4*RhCX%xXxtxx#^H_%E!hJ^#c|F6oaoGXL^FMz3H zA+7>Du+&wsz4x98tFR0EY0e6EbmU`%Viw0* zvcC1H#41CuV;kSK(Bzt?b2PU}q$b*HuPss{da2vOeJG!KsaYf-~YuBVW(zle0 zRY6V~y1UN% zyfxOl(?xha!n)-8y2L9X8j-v?+ESmpRm|Hs&^x~5J77gIv6A~EzSgWfuJ2mD`n$iJCB3S3 zfGC{9I?PEFToC_zBgqlNK#5}oynm9VOy6t6E^D9nxx-HU#8spNsJnJ6+#l{4!UDW) z?wcS*OmsyeczDDZH5^>^$;3?z#b}(y)YHRMtiE5gAzm>eotUNJ*EF``MY@BS!QJQU`OrKx|#>m9Ew2Y4=tjet% z%)(qQy452(2yELs#y+^k@HxjLHp*Sa#m-!5Wz59Ge9hSGDz6MA$Lt`bY^nx}w25rW zuz_^YET%$?Ex!!R+1$?VtS23@BTGui$Q*2bsm%N+&cvFyi!1@$VR-x*8I)} zeb7HL#XvI8Kyd)|{7Byn&NA$jx4afEdd`El|C{`*&XFw12>sC@og^DAar*So#azgE zY^?fR(H8B#j6A;@+`t6A$01$QHXR^>3{NF(Xalh?D?4V)+|21r8V~mux-6zvYOpPq z%Itj8PW{xkamivl$aY+oJK@tm9nLQd!$VEfl6BNS%)Yv}IE!1*P<_^DT~8ye(pBxy zJY5j8oYKAwaV(vsMGepk5z}Mc(H@=Fe*M>OK^Mw|BLPVe51kNk-PLrw($nnKDE6Ov zz1TBN(|}#smQ9#z?Hh$X5Qlxz4wAe>%z$;>q7SFb)O)3w-6reY)R*1bu8kFf{YYYM z9GlJAZ;cSM?1P9r&JvAMca5X|INPP7|D}EX+Qxm{P!Zd*-5?Cz(1r~anY_ru@t30w z9~Vu^$eP+QLe^%iS;+m};O!I2?YY`*Ut#>*2I1L0+;M-a&->iI#I$@@nrW+jjNyIX z_rk_$}4st6OClg+pgKH|r{-_SwfZEfKfezyaXr}8P#y@%8a5!oHy;G#?7IDXj&0@n+E z%IXc^>mA)}Jsgt9;S8S9v)bct3sc>_Tsi*am5sh)T;8?ez6epz4Xxya_>4y0CXJz~ zNlxW0tH)*x? z2k}(^xaLDH<8=PEnM~tijupgR+h4VG3}@;89c*_4yf7@h8=mOYeCI|>&b`UxO@79x-s{1vkeZb1N(!R=+F6<_&PeBRmAtvj|4&%th>`?0IT>rRgLd{4SVfAhMu@ibraE6Vifnxb`Y_jiv>O#SnH|M*k8Q&T?noBQ^w z+wQ!r_}GG?f|>Y$|I7|k*4+*Hq(8TqGx=@r%YvWum_PFQtg@bO_)8w*dtUms|FDwJ z-|Q76N00QE-}>Ut|94={wz04Ii?8qde*4M~t+|iVyx*k856Q+U_xoYzLS6i_@7T0Y z*~{PkteX4$#QRH2`OLG+GameO9KgwX7g&t`JXs;3Z?14(xy!QKCeL0xwO(h*9B2jvYM~yyQ>h$V{1ZoJ5&Yd#s=?l`FQf> z&7Vh~Uj2IZ?WMXI_HQI*3>NW_EWDiET?L@a4R884)xfmG}&6o8s=79Spv3OZ@&dM zTyY;1b4*ezMbB7j(JZjHHx%8dO~;;`Hc9H*UF_0ra~-!|fBywIV1fUFPg*id)o-MK zJfsw1+t!TN*?gy!Hd46oofxlu`5L%mk3R-EWRVprcf&Lj770$a8YXr$cq4A~zT$D}_ z{Wv+wrO+x=gGmbwIX^@?(v+t}Whx6&G7&Ckft18!iU`P?mu-@hokWoP|5k{^TQcT_ zh)kp^g*i-OK5>q8q$L?EIX+RkOp{@>;usm&$50mXd?JBi42!u*`D90(YbNfu^p@^}jzA;ki;CzA zshj?}(Q{tpXbNRvKj#$^Sb=gT&1|T59-6h57S*Un^^`>~YMYFbWgzB6Naz?kPMn%B znz$UvE@J}J^`SJSNCj(H#i}Kx?h!Igg%VW9cdwgP)u2oDVo5bH1Be3ZmW4%qlhS5 zlZ9<^mAl--XqLFXv@JpY;Zp>n%&ntEtqVI!lg(ZgDfMI`bHzJe@ji^UjFvizdzw0OaVLJ=vKr~!VOVkc`4ud1{cBd^zL_8 z`_=ze*uod~$a&p+Qj2ktA-rv`ZjbfA2-nKNkA?7klOkEX|6rqcuw8mwBoU99U1qK8nQrox5vnD>37RZryF6z)hgG%$PBLS_7tba;xjaa^t~>pC z;uK%GEarfiP9ssG+cR1=uM+}#X^nqt(Cp(MUuKu zseZ64pJ~gr^}4;qE_J89nrLQs+uJpCc89E;T}L5r|G^9vsgJQu?(b%FsM`E?yyaa% zezsaa(4KVJrcG_z0QcPM&bGF;QggrFfd)2gi8E z`9^Ap6BOSl4$;0J-f>H@Y2p;GII@$iahA6nYzZII!bx5m_#zP92<^|wRSXsIhS%jk z2Rip4x$6#n+@$1rv(XD}>;s`n=XvJ2yW=e9pjX}M|H`$bQYG$^vYWtB4mQ)9zVwMW zM1-_z-K;Nub+)(NR~#=?*BS0iuv-=74b8c;^tg2@seO%Z2Yldp1$VB$#OoXut=(_l zNt3^2A)CIYKaRU{!B^h$fO@H{_&y}L&mHlV|NghwyDB?$7VU6BrCy6Kzk1exiSP>7 z@!>x|BDq4nv>=YlU=J{?SW`*rQ*V9nh0i07&s;ZZwz=`??(mVX?KzMV$k~D1)q$^l z_}9n2gI*tViQnCepbxv~`wo{B?tSxpum0b&zkc@LaOgz0Pxp7;@Wd-#{NuOC%*+pe z)Tf@??FYaBG>$v_BI%PonmaZABPfw;z9vDNxT%Qp;UjFa9N-hc3&gv#F!H76if| zB#g}C4~*eF`%}PbtGf;qLA4;kB_liU|8ok9`#&MH!Yc%e7fhGCV3pIGG5)~4_>#fG z=q#yeJbObw|EoeQWWzR8isDl~#G%1!^TLN=zy@p#w8Fuep)N5T!yA;KccUOTB*a2A z3N17bby=8^n?Bm8IXs-eT#}kFJTn_)3Wi8QpEJZw#0}Lv(zD|V2SlkE#loSIzMaO^}mC?abbi_Lh!CN$n*D0e?TpZ}iM0=9OWK_nD z_{1{Xtx7Dm9&#bpFXPHaX>I~!O#x#g=rB(z4Kc*0cd zLqFp&ybwfq3&(nl#jGofMjRcB|52K!TgRq&#D{C0b~GYN1UX;&Js-5kg@na%47q7~ zAAfAZs0hek^t_`;D5)97IV7=oRKqo7$dI%`(BZu#^e70lMQroPbmX^zG@^~Pwi}}y zZ~R7)w8;x}$bA$ZIq@NhyvV5YMT?BXio-@DBDSBTNSai^n`BBBgu|g+$>_QyiTplb zTgCaK$fAVEWiiO=QZj6rM|y0^u?#?39FdenN@I)`1OW-O+`*`{%Fz2qp}@rUQAO@b z%TDV#kR;2#9KNS~$eCFYUPMQZG{w23ORa<)P0PzERLZ6F%g7Wyz?8NR(kO%I$rJ2F zVpPY*l(1BcOPN4SjC@Q@|CG$rTs?f0DkFTaxM8yW`@_WmG!TTu!+5i`M38q>H@NIU zAN)bo1kSdjOyJ2z&l(_oL_p4L$uvvFuCyw+oIKwQ&gld^k~Fm6P)zYT4wLjJ<*ZG_ zxXswXiHV%TEc4CZq|WqYx#9dDGBVEB#7f>YEz$HqzX(r3IxWw<#L`4Y_4H4ddrGKO zjO-j9k077X>_+btO31j)nt3%c`^t~x%m1X%Zv!2Fa7zJA46TF}nXsv1X(|UpLl;UR z-TW#2Tnbm5&Xa2}a(&hDhm<=m-QnNfJ0$zwFl7WL6(dr=Rnmk#}i)%>-X zG%RieB-mle6V*_?|5Q2Y{Lv}BHPwVo6#a`bjFU?03IrX&+!WFJT%U@h&nI*o zRZ~R^QXSIB0*xx_^3pF=&;@nG{diEBiq?Y^)yV2oKgHH`RW5D)!XaI#Q5}riJh2ho zsT|!+p@dhM|EN~TRM&pREGum@QjD8S^VVBMAA5zyd@WC*h#uAyI0;off0fwFVpkf~ z#@w4%g{4zxeO6~0*IqS8F{Mjj4c3V@*}f9gfNfOqB%XJLRqYB&8=WtL?FlQpPEv(f zNs6DDzeOc8~FM|*ZaQ#-7 zmBLn}*_!P=YCYHLk=n9tG@DV`!ju&zqejp&+FImVCDpE_P12@y+Pi{Uv(?*(qFRAn z+l|Otm)+X9jZG2-3Y82p;|fc%-P^{!C+kexXW`hmXxmS%%up58s+9_V1KVhH!m(vs z#}!>-|1!&;1zN`l9=Qr!ywqGCd^LK7u5mrb&qY&y9o^e?q`sw%v2d_HbJD?O-L55~ zuPsx61H`AzTijJ%MoQVp#l@OfUDh?&93$MqRiHI{IwAtyL0sPMjU%7E(nRHs%9YlW z#N5oaLvYRBL)%x|_1^cjA*yZNh%?o)2~krOURet+pG;a0wUr7CR$+zT0k)tE4PWtH zAMzzvWjSB;rMYe7-}%Lf_H|zZwqX5{Ul^3$=?%@{3fFi=K75_s~uQWI|CE_UKL8B`ZeyB3CG8wSHFwqkL;N}o)-+O1$O zhGV_~Sj{vQGA`o;o!pKku-bcz9){h!)vo|%qc|qyeR@CV4Y}79W2=SX7)I5^70odz zNzZNLoQ>E*#^jenTRJ|E5I#5Ht=>f@ie1%LJR{6jRAO|^WUp!2B}z`iXFktz|Hfy5 zG1h8Mm@wr|i#=MotYwTOSWgl~VaBplR^@zVXm6QgPBs&NK0n-;%_bFSbWUPg)jvl3 z;Qefl=oI9J7HM!f=U2Yyb*|(**5jr@k#;oEko{*87Uyvu>6(7KO@?R|E?!MdPLbA}kYUXEs<70aMtwqIR%fL-DbW&_CYNM7?w+3uIIcK1b zRn9%>n>FTuuEBTC33`Fa=0I4OChQ6RUtaFzz{cz@f$N-Jj?`UaaL#64|NUbv22G!? z+sUSEH(uh*W^EpMXwD{1sQ&4=jv$M^==6e=$F^<7tL>To>(&NtEE#O{2%d#;PBwmO z1(w-x&TYM}U(}x9wceQErf%WJY1nShPm({Xv7k*@Y?-T)tx3d18F=*zh8#RhMVkk#hC z*zr8@ose!T@$U+^k)G;@v;_*@Eq|1tgi^qiQC-o8Cmfm_p9p;aNWo#{5);s|1R&{R&Z1XP2G-G z8V_poW)LFB@(AH!y2j4DwsFbM;wE?UyN2?YT+AMK@tSa`AkUO6cXM*dO)k&wtwf&) zj9|6Z=AU-S9Ut?e&2QhH?l%{7_dDba-&D&~#XHCIJRjmTw+n)tmY4qB569|l8T3nU zkM(BnBXMw{?eO?s**;%xETd|eTw2Dq2_QdjOlS4<*ym06jn0yCKNeYb7WGj#>r|v$ zR9EvjVe=+x^~!ceJ=#ue*+y$B2MQfO>&|s_|J`CC7xrr(j~1VHqbS42 zCLUOCSLcXq2VPS5Y@nau^D^9y3x9c}hK z_FKP7O0V?1vG|n74S0`t&frv-ObE0I`JM*x5U&%oavw=2@7|WYcT@SFzm3;cc6r}- zgpYZRNOzAe!78hDMpmJqaQ32bC;-MBptt(jcy(|$_@ZaaN8gO3PtjSvalW1kXearS zH~HS=nX6}e&R}_aXHfh8h!p~RRBUHGztNpk?4744zia!ycfmp*dY89LqgM!#nCES` z`?Fu^oY8wmM|->kNMElXz_ABD!smF6E(s^z%US*4PYeKWd0gatgFt+@U5<+0`_IPx zLwgg(_h9E=aEB89>o<(d*ZjDD)7WQr2)*2zxA~x@+Xc2rr+72$SO38f`oZU{;}-}d z{rno2esXtt*C_pa#r5LSz4Zr(0|EyUENJi`!h{MJGHmGZA;gFhCsM3v@gl~I8aHz6 z=$>N2pmYTpuvL( z6DnNDu%W|;5F<*QNU@^Dix?s5*vPS?$B!UGiX2I@q{)*gQD%hb#!Z|}X=1$DL9?dK zn>F9)d~<0h&Yw7U_S~TpsL`J~FBvm-sp-t4P=mfnvndV?H!HJh-O9DA*RNp1ie>1M zgq){GC9Sg4WQQD@O@6JCL}rzds6dPIM2j~kUV>B8#L46)rQySf6OSCrxUu8MkRwZ; zOu4e<%a}83-pqNk;?JN%i&pH|O_7&zbhh2GdNov@#{4bq$v3LdnYH^K?djB~ZlgM5 zRK41{xbfr2lUK|X$87GSckdD{`a9@Q>V15eC{Z%MN5nM^trrC50P=6jm5i41y6y z--aA^=%GMvFqcMmzwxBhcC=Br*L1oGmEutc7%|XP;t`hLjro13*B?xB8r8&Ib^X#r zDVKQjk1^E*^TsbFN*L*wywT>{m~UWM)tQL4>gu6o$^UVQm#5BoTZz-nR;Nu4(l{7- zj0U^dtHc&-?6Jru>!GmBHX9ay{>k*5ZnH>Y#2c%`AjyJiu{Mhqz==AooqCd+(^RWs zrR=)w_89B9N12FXQ?sgg9lSQVsFapJ^$K1beKspFN9`7D@WBWtT=2jQ`}wR(Fv+AM zmp4flgKb2aO0G`xPH66QRGF#p$RxwZoO4^6iZ7hFtsIoSd;;6BuqD@Q^UXNtT-nS# z-w2i)kESsyUcC7u8&g9^m~pM-(%W0op_Zwk&Qw>eS(_ue9Im-^YAuzRK=sO}jXg7J z_1S2rtv14Cw~b_1(EjH&QgchSG}Lz1ZJX4ruK(@#-=>YhOL-sR#^p>s!S-xNS`#z45)( z;azb~W6P|$&#(tC{P4sl^!xFK!5y^jNS$c(Qq149lU}(sp@o4vfJ)OWZ2jV3zKnBs zII8HfUi|s!Q}izRA5%Z~b3;E4usJcqbSV zwoo)j%%T>z7?vw~@rBFNo4in@!7YiaeSp}+Gi1{XXc(gua_F8Gu4gO0aq*5>#F`T! z_(alKC{Nh|k9g?k#l+z8kcd2FA+NZSxCt$FUy~u1AQ`W{pv4Gxxfrcfb(Pj7@{>oD z9VMqT%6#EwkEUEom<}*5vDJu>i%bb9XGzQ8#j=GNfuY>^_&F&;P%pepl>|Lm%VKH~ zgZ4U+_)y6~R8EgxIsv5Paw5op-O`Z8%%(OIcFhvzGK{&?*XbT)MoX5GnyLh0Fv~Z= zZMyT0$c$odeyOskBxDEDj8G>!G5?1-cw#D6?4~T=Nzj6(Nud3^h$CfaolAs?p{Hcp z?Vu@9TZL?D2F)lU+e89pZmoT|^A1Czd4Q$#QwS&(f%*7OW z7SW}&cxlGFos)n(J(nG8N>p0vag;NmXeql!lZ5bupPujpFq+|yfBYk=b4aOHw>pP2 z%;6FM3+PRURn)SY6)a=Lsrov{&~r@>l3i;n-E0@sobZj9XU!`pML8!X9*t{Ux&%K@ zx>c>t;Q*d!24M?ZSbyH26PtKtT1}$Y%32m7ll|RV!KtDT9*tjcBBfmOqRe^Ki)*WE z=Ve!0%XrqcMaCFxRI$ofga4@Xu%0-qKp5LtPn_Wl#^_yUNy6IV7Ie6pn}|+FJ1t2j zZnTOEs!oP!-0B+CwX}k*Vj1gCPxzx5ShX!m3F1$G@&g#T?I&${>)SKXtBNp1u65_D zMdT(oBD#d`Pe~cl*Yb3_>7uWIY06QL{v>=(+es(3%UhKaB)6LIhb9!e*pv=Ly-@{* zFaGgeUo^wR>uu~A9-9>S+E=CnPO^A%Y5K>|k=hJ#QI>4rLoO}c@5mn6Nq8`;t zO)(mUv&vhB^pg$1U;_>`aR4FoQ@mUya!RG#;I7`_45u_Pi$BuiE>msGZDUF2b~+}e zd={c-45riS3D~=O`Txz84Ut)xX*zy3xFY_<0Vp(~2{z0Dyay<6gQq;+f(+WRSk}|O ztO@3g!1>Y0YINBilHdK3vqF>fZ@Ge*TD(H~(|X0OP8LjMtzH4ytbZldr!NkK}wp-piZ`rj?FWNKnupS0w(#)*}hR( z`drjiwzlV67Nu0!!V2jwKgRu!4+A>H4bCkaGyw!4yc!37F0Y^+9O&5sL*Ctus<{zc zYTuGrI>lx*vvsiTf~#lX4Qt49LpR3ll##~JZQhM%v(9WA{Ne%*(J-2EgT+Ebw}{2+ zVehZey=$#rkQXGYP3A7G3p;F@0KA&Hog< z+8`T_r+Low)qW%s9c{{pE6kAI&bFV2b$PF~%4=A+d)$+B>!w8wl@g&puv6NsE&KwiN*Sz z)y?j9e_hFb_O-2b>xswjIw4OM$ZVUTcAU79b#E8E>gUcdg)H1w5;Cv|^$u8QKJdSt zR=w_>4w^bJCk`7&H{(J7-~*W37qe|OS4|EI%Ugck@Ro9*aq9`>qqo%v@n^`JF;x$9 zCv0v1RsZUD4{Fx8zV2*=tLb9%yoZM~&DB<=!@*WTM{irVe7@ih;5prRuEAY48f3Fwm=A}V2h+U3qsHZv#<(`rEmO@PV}NU|1yXthKX5ph=>RxFLrl8 z#(qsCS4G!%U^0J07j2xxh0OSk@6Eg9*_Is@MshkP1yU3v)0Ezc38F@C&~H zcCl!AeC7!$MFm1Y2q@JB{3rzOxCwI*41_QTjxcE6bqNANO2&{+2SOKZK^Hq92?kOK zrLYQB^wS|E9kuI4{*TftQDG+Zkb^d1%&i@b$ zIq46;kPM!%3Ue?EZlF@3=v}~YkL{L^DCGve=!3IUgM^7WE_6Otl%0E$?W8v}pA29j_9IrIkHQjs-rbCBbadpR<0=`0|qev88t#^8vLSW&bhiN0BX0XCb& z8IHr{Qd>z705_O27;*_ARj??FNCpg=uxH4C3`Euip70BKSPj@ok5qYtS^w1xvx7rM zKn65{p2L6+{$LO5kcyW82-B1?u{m(XSuC~LEF{@iM$>+>CpvUld+cXg*T$0fd7#_W zXvkR*z+sb4<_}Soea#S=bqEZ3_zwN437)`!NY)I^uz0-nXT}gwH360t;~F|K3QE;V z;is1Ng`h){pUe`MbMjH4LVHH1l6QGg-Uy>Uibx2T3B$0JO_dNaAP^2^gL_C`e+CS2 zP@QlPrBWIMR7$1Az;3Trhp)y4LI4CuhIQYTl_M$?&CrQb_gh#7MRsy}F1nUK8Xqzm zECRt9C^~eURzy_(HshVI5IIs#(X;|r{cwpL9rs`E_nyS$hKP}37eaabe>VgNbB+~df z^3sUYHe=OhdwZ9HJ^HG^x<$_D2LA8{3y~E2lwO23Wr60U>z1gCx~QPQ5046qu%-#r z`D%^;1(o^>KrjhV00l?@1gj8h-jE3(ItQ)b2<7DlmpKV*I0^jd1_{Ys%`ku;mR|nk zRacfGBh;qD6|9UAtBisbOA?%llTPi&TvxbG3hQt?I-CMKu|QgzsAv$QHdt8cWFJ~( z-USMv00+?;1aQC)(V3KWQfQTYp{a0XN`2dQudAZl3ZwN;?!TXQfBVFj=OE4BntwSS^Z zwOXTGJ4sk*l19g)c}cpmdqQOE2B^pzq?WlTRegD=q--myJh`R9yKWYmt=3As7TRa_ zSglEEgT)(R5GryN#+ch81f8G`&2Wph;0dEZ2$LXr^Z%y1X$yKIMhw9fwNm@0rh6on zW`%%wPORH^z_F6TB(bx5zs*RtnXn1}AXtN?yCJ%s^RQzYZPezl)c9BQ3%2cCd42?Ll|$tQUL?6Li%YmcX4SJzwpX~eU35F@5`=PPjbxtA`i7%&7LAy^x=!>~EL zPK>jn6=%Od+{Z^$yUE~TX`8v~g@byyYxahNO8+bbZi|#1s*nbZfDCNKlNrUeR(%}y zVFKL6qUulJRjT?Jn!e_1-IcFT7Qmjn3}B^ zJjUYtPiHU~sF%JQ_{ts85`K9Jqrk-}l~@M$pAizEcd2PC8N0ol&lL2_BYF@#@muaJ zo}1@nT$OIrTA>V`&SG~xbe6O8I%s9ZUIMCUj4FsSamAc$zww6AMqOco7QP*=ZytuPVt8w3&<<=5 zbnn}`iiVQ9%*TXX-756cZg6;Yvk;0lLq-1$z)antSog`tot5Xs(B(a7%$+aH38I}% z2QvVwS5U5`m^93|AF->CJUy zz0A!`PBqzaM+}v8FqCQ$l~f=J-1-YpISKR)1p$~+IDnM3-E#7F;G~>yLuS`g=2e&Q zQc(D2nN@g@(i3N(vBivG8peIji{50tki4O$)m9rK9Hd{a+CI8#h3y3=!guS;0(Ty3x_F?kSmNR71{wF;A5S6 zTh-aInCa78)!U53WZhj??%Nv3f!74X2fG(v9?(d9uVqZYbv@&nn_KC{1`FBOJ1iR^ zp3_CJ({VoR`jelwd)Pmfo7DJ_?K2zS&B&-mLeV0vSgq6`%7V$r21lIra&t2eEqz#ZcdyvV8)RukKm%L$C)eObp3w@U9_O4Y+ zKGvc=@4^v*a0cAvj-o#I+p6WqNevrIcCpKhU9?T@F(UA*h|EX=fB+fila zQl@VpT+x?q?_+KBP^t8wz2u?#y->Wu9 zP0!x&$@kF@Us(2j`6&N|`2oKD<)y{@?&s;9SfI{LK-PR_$80ZP}V7_?4kSxpfO(I&;PoTDN`K z&hZr3mp^`mJ*Az)*Kb-JLVz%KECk2n$!zv|YIa%iVzr5dc>de0Q`C$RNl;{(TJ`Fs zJzc+s9Xlgy+7Vnn*Th0PPPxH=QFhMH-o!CEdyxZdFvEaZ zOWz$m8OSaS!K1ZYg%@VHVTT`vIAV!Q61QTDjlxgA1E$(E&{Q$fv?Z=cGqvPbSDiMr zsIJ=Nl35RRszfk}+&5ss{^18r9QR^F*kN}ZjymO52CG1<4q$TIC%>KYVk;+xx+kW> zQ#b#O82)>slTO|pvqtJLD-JU@=S=RhotvwfUo?|MvlwZ|PFo0qxtj}0grmkgZ@u^C zyKle$KEP?gExt6=hC1r+Duq5;oFr0{&Zxf!m)xOLlV8+JZn8GvaABu1N#l)_(;jXx zUpxaX?zHB<3f5HZ5{X-+FG-_BHwI4)aNSWVs>^jl&-9Hmw${xfY8fOeI631jQ)skR zpU&6;50k8C==*ABpzjLZy?gJ!2S0rA#}5g2^C``EKmJYv3(y@r;u!vsA>VkR1Da@} z{w8+7e}Dc9^2a)kH6Y5F>@LGdM#3WIl+catdiPo$XNLAVh+w64fkIkIymgw}op1jr zY%PT7{mzv!{4YzK|GGoC^1MnT?CCJBqF8mde6HT*p8K~Jy~yG$w>^1V5GH9 zJg86#1Yr`DxI`v4(TVBtU=-<7kzs^NR8|2{R|aH^kcs3W8<}7HE@B5QG(i&go5cZs zQNLg8U>5#B#xE>LK~8aH7)aC`14So8pvh}FHVlm~=;)t0(nWG(F^0A{B0DHase`zC z;_lvH2Qu()7CX>_9hzVVM-*ZcwkU)fgfI&sT!c)W0nC}wbS6Hwz^n8FxF zc{-YmEa#v#Lyk&AcZ*~&g*i-O7Sos-kzz7elQGM^Z&NL)V6Ft@k4r%FK<@ve3P#9y zfK{v_2ESN^CM98nQlw!AZ8V^ujB&>hf^LsD1P*rop`GOjX^`G2)di_?tpGJhk&Ap1 z?KpU`W9F?KJCMZwx*3C26v7sB2*v?~utp(JVHG$i8xDtarepmB7=Yy03yISVkUlUm zYYW?uO3IeW_{uqn;iXizSCN9&)TTGZX-*@iOr9B=Lq- zTqFj77=m7d%GuPaa>P69q^U7K*TBHG zgj`6$dJS@QXz?E_~RGHG6pgVftFvKQi8t`*k=lB z(jfWbSkvk)OM&20H|^>{65(8KnLA(l*4MuGMdoJp+mtG*FLI<6szJKaF^3q{7zH!g zDrRvB>^P$t!w7~g-T;VS7~!11SYt>IvbI_YV@>Mw6NCAf@G}=(uxX_4T7sR z_+?ZuejywM&jQ19!0<0-VPhVzLI{qSg(T#*7KuWzhDA~i+~WU69qn8vNrmx;kkUJ> z_4@2H!z*ITBnx9MciGEd4(5KvT(}jB3|q*f8|*|cP>wI(9x9EEwvg2%vl--TO1*TF2n%`l9+^Ay5I&XP(dxJ zNaSI_i^J%JxMq7XhQDg5vz1N=2SEVBV>*Kw4sZF-V%}7MZ4k8-$z|QWoMD$Z&=^s^N^fqNT_$9q(c!(dqw8PqYhasp~BG@(W*7V;D+K z+hlwMmqvUTt}Yr>_nXBd|S6qO6Hk}1I^RG!0*LgeR2C;WK-tnwTg?rGtazmt>Smg*IZKt;(YR5 z6DNyKIxR^zJ7XMi(Ta-Q_1H&@AW0H`D2}j68Bv<3RS1S)ScTF14ML!TgA)P-{I217 zEV{^=OL#l^E|KrmZAp2`^K+lYkFAXw=q0(!o%@)Y0_ytDzpw0J!ingb!aK&+CY z`a(bV3p5@Ci$W_d$ceuXgbB6qnW|$c-w+Zy*%?0Jj7gXTNpJ*Dc!zaB2Y>Jeboi)W z0J2f)LRSI|t+~L37`6>0!ZSp}G|Z_GRHpx*0ydgx!7WOf%LBYqNjZB-nN^qsPpAfD zK!$bj1!wRpwAejIXg#Y-q)gba^BWOd@xgtR{2$SOg8=Bb+QaUlggkaBvB?pOZbOw4Yrn5RMVBD5RPqI~fuK!%AmT7JP#i#>h**#Q7BD0jvMZDYVyl$CO|LO-Pf%00zsjj3YA^QS&}EyPQB)AgID>!4gqm0lvGmKo1kBmcN%O%wkO(R;LcwyQCd8S%`5{V$*vG`0 zkcBkF8k`1X00v{|gM0eOZB;WtTq$mv{1)Rf4_TutbU&Wr$pj=WDG zIDp*bPyS>BelW}a#Ld_2&EPW=;P3@XyU_i-O&%3c z0o4Qm{Zaqq%{URPz+g~QK~4x26n~J(@`0osmC`BQH5sj#>NJTi+B*#cw>peQe^io# zh|I1M5(_cTI?@p3vQqy&gHOqeMsB0V|L{o*9nw0DH8mO1*ECWZ35-8E)2~?41@Q;v zOC~Bc)I)`_H5Hc;j6eI)Qpe#?W2+;_^gBdiISNYAHVG1JdJy(YQ>;|f``Stt%ub7} z#|yR7Aq~<1y-&1s!nnB%YWh=#a8M>~h_L|G9NY;l00TED1VS)FL>1OyEf+-%mwDvU z!z_)&9I#{^(bHPZSyh!g{H}()kSwAm`5cu1Nv>SAQv4cKaHAZ%lv3OLQQl8=RWXwZUey9$Erb#ASAQkefECzcHP%UCMH1{u(9#HE1JfbA zoS~dgX|+Z0R7wA9z1E6kkVK*i3!4jRnlo?l5^w!hQB6&4Z3v)@&H_ElwB$aJ^vK*m z5>FtBAG#5=K+;Z4h>pGFiyf&H^f#6rG@wTavLgTS6cPPFMy)c!RPf+p%3- zeCk%tWz+wNbVO63TR0$IO#lVogiU$@+>MxnDB}x>;)}%KD2iPSBqd9JC=%$fjD65p zyC4gZJ)e&F*v&bQif->%- zULzR{T(Xn5sE`{4pkdIj0|0}4Erjwt-x;Q1_O;;~Zcg`|4=i=X|I(oNHOy!I-^-Cx z_QNfwP+_|;f;W&|+9iYo?t}q$vLsmsPPp9##$qODUmC*@~NHGYh7UV&OQXOUuMkR?d zUe+v{rqOj)gSlGvgNW6%qdeo1)J$SRqg^J>V%%k7PUwVDsA5p=rq<>yyLcfTzGx{V^sPF6haYNMppZs)0@-I zNc9+qWx-CFPl#A2OI8Z>%e=Ei;8ONx+)ZF6xZ-cd;w|1?LXs7?Rb^Jb4Jn1?+eBjk z{96~2Og_ye#L!f;=-yW$3)}(bU>@dxCfZ^?=7L_|WL~EHKv-9#Ps9Y#VPoh(lV<-G zoTd}?%8|k59fmxKOr*38XL1JVkQQkz=HhWnWrT)Xg9f2=J!9uZ46;bC!+_%eWP@TT zK*Kn-6i$#krcQv}2!TFdKoEo&CWOjW>7!0sl%ASp){6P%h^H;V9`w?Z1JgtkO5D1L zaH)e$5Cl1};*kdHvgKq>4(qZtXOoU#r9Mrh)*Z75zIXo5l zf}X?O0bjltE!fMB0BXuD1VIo4Kr-A^FIH2Oj_kZajOt+NAC2eLiL(EE28Jga zK(eGB!Jws?ZWAOO3p~CU7Z_~9?ql*Lgrc6@#7>37PHaJt?x7{<+UD-Sob04v>ZWEf z0kcGvkmy`F-LaOl))%NB$-~>@#2C`UCe>ht>(%}?~}#qx?5|Oh;P)UZ;-a{6{1}Oo^RDY>yAxl z74LBrUlhMU(zn*_1yAE0x#!gxvcKpmax7x&^9OaN6fO9OOkjjeAcX%ipIkz~?m$rU zq0Vl9MeGo_Za_fup>^^*M@1&b82Ghps6Ex$K{*CxAMc1{tX17ij%K&3i6mh3MrU-F z`0*nTav`_fNoU}aKADrA>{Z6|cH@jF&+S+qROR3Y)c+~vWVG~ z3>dlT6LJJ?1%dT&aRC!QfLgb8Ily&6ICeAt_2_*i!Z)r z9|}aaCj03KXb(!po#@N6$o+NTE}%6&V*lG_@TaaU7vcP)_Op|ddubc zuh%$@Z;J3<2^0KykdJDcD|92CBTByJls5^Mm-|M~iI=Z=krv@KLA_5bvdYmV=o0@|8?u` zdNV)lLP&T!5B$}CG_eN?ju(|X1CSYS>Pf`*8_)3raZ>-dFNwML{n+4~CouQBU*P=K zZ^H10Djw%`=VDSxYu9IemT0vJ0d*iyaK)dH?+ZnsbmjxdInN$c$IA#f=X|HX^*GS= zHb3lJm->KC_UMOy=5qa?c=nor6=^~qwDq2r+5t@+HieGGV?U#OY?IWy}2eTXu6M z(4Z|37%4jN&80M%GP%*=^eNP+Qm0a_YV|7CtWXc=DCzYp*sx;9k}YfYEZVecz0MKh z_AT7Fa^-sRzt-O@bnnG*V zq!bjV&?d{92oVzGnX={7s#h;9wDvXZ*s^ESu5J4^?%cX}^X~2Y_ixF_UxAJ?-7?)7BKl|tv!Z&?#3 z6PES&Ga*WpU{Y}~WgLM88km)P2`acCgS+7X1r9g>A;g0b%2lC+efi}{GkP`imnVUp zQ5bV-A$Ey*DI)Y(WX4T|oN9~+!WoT%0K!^mtm(L8CayL3BalG~IV6!q8hIp=Nw#<( zlT8xm#xTYZhL&~`F=v=`%QeSXVGb3h;&=aVSXZ5t-GRwvL+Q!J9-AF0Sy5;z>Bk?P zFTG)3o%>Bxlyo^ZrB-$*s;R2FDyyx!`YLRK$~vo4$VFKqm5m*MtBG7XB&ns|J!TzuUk1xi znh~wpCbLPn3ZI;LN_!_EcS<|oo<_XENg4wFNh`Rs!a6Rwv)0gnbU)Jx3a+L&G$!?!*{sgKoLSr;r?8nS5KT+ z8-9NjZ42svzsrvm@Acz$IsX6odm`B9WgRr^=wg#4$ed1kOT!fFzT!IANlkXNvz`4S zD8UI*u!3Hh-~7OKtFet_QpZys@sNVFF5pa{DI z9Q$T+A5P?CCqCgs4u|5tn~Y*97(8NCET}}U)L6Vkr<;sr5?@*5)YN2GhzCxyoaQ_yI&%|EnnCGSV9^2@nlKSE zNTdnz90(c6U=V%&Z&GdS)yRHjOOYLoFar%19((Ca0|E1PgDfUQUsjQu$RRX!NWwa$ znNElKlQ;9?3EiMW#con>btEa(Cn31em9n&@E)_{eAr`htf`trrIKVF?qJ>!);Q*^J z!YX3$3nOSj5=NNCFA6fYYO?Zr9V01tpvp0Y0*O`)^&U#16;V621aZj}Tt#dmhsFs4 zqZo}T246ZZwMqXZF_fZSyx2OM@i5Phb=zb}I+;?n^0lviH78nWWvf-1Wfl^dg(U15 zPk9pL0KvF~FMdH&je&<_F6`z(MK;y!70GK?)!Ioip%Nf&)g{~F#6L2ZzV(51h@6PS zCN`mwy#*F>e`OV0BPE`-ETnDnl1*K$bGoEu@-f5s=0vnW&f7A#xz43vZD*B6wKU-u zlJKcd-;jz_BqJEc_=i7&F^}uybT;6LUS?BNz4YFTWSk`u5I7Mjr&*K<)-wh@wPx3gSPT;~c$)9s3+CQUGgGpymt9XL>`?B8n= z`wOH7!xsOz@P{|n5ng*}v%Ifys$HiiChLets>yoqkYXy|t39-sJM6?LmH}Sy1u?9P zZ01Ebvb_!;Xv2j%2nnwvB@#VPBHFx7Vur=uGnEdxPX02O!;C5>J88PIkpw*rI}oE@ zBB-kvg?EXDQ{KKypcam@l&dGV8zYI#I@od5LaWu%wnTlzl!+aFu?i+=;TMi(^eh(5 z=wG-*62H)b5GP_2P889Z9nqVgB`4-2A?8;G-OXdJNt?t#bs%^hHLPPTYXybcKp(Co zSrB4Vc}heO@@#?~LTLv(km0(-wga#IM-ad8&O#%IPOOa3 ztgZhvqa|U7mr$Asi?(!2BrS=V79XF{ygsKZAxK*(2upV#qn50=nQ4@{nS+u0w0{*A#`Ysi4s|&ME+o0~=E}KYb*q`?Z<+JF=l{m|a8x;2gdZiO9i?m?n;k5pW0sfH zt~StxQ#p=9R12#Jc1uVu>7+8j7pkilfa z^;&9~N$Qm8T{%za)1i)g`dRRM-EP@0>~M8Eh?~-@=*2V8p$>2S!W;8Ihcilnj3QHH z)14-}N93JW+bd|n4OaaL|JPQUqXkoVK0xfd*>CpqzyFb3{&8eNl3p6{lSSCoBUo?1MiLSq@c%N-&eBu?gvQjsGQxLEzbS zxYdKnAF#MyVjLj9`NQ3%AP(kW)<|GgKnecw#+A$q9Km1xVTS^~5H97CL0SLNW)TVx zUWGXcTI7{hwQS&5k)NhfRB|+n`hklM{sv+UmlCqwi=9q{6-}14k^arz7q+1rHp~-B zg$ChI(picm zXn_$V)($j*xb46!?4l$X#7~g{An@YhxfcZfQ7h6Lb5&qzeVZlj%8`{|v;0|;ts*8( ziVGGX0r^JG?H@LVqc~R8GR~o4z#ZAZ9b3^~MJyX*xSpMPOcVT~FT(%R4(Q@941^I( zLYozp7PK0lIpH!sg$-$#6iOnYMbyfj-^uU|Cl1Ou(#z3pQ#an6Dc0Z(Mx;h=q*@H5 z4zyE+p<_B$2^+1=(cqu-02jyT*|Fr}D%@is0NW1yLa`;)CCow-_@X}1BNJ9!GAg4- zc15f~-t%=FOIQo$fnaM*#0Vl;LptPHB@suy6?AMPmVuN=uG&SijTODxRDLB`hQ&Y% z-7J!XNP*DXO$yr_jp^7G75z$DicC)K06YbQT?RukWEnl?<2@R|JmAXI^4b%v)nj%AeCQT(wH>bZ+=l@1XW zVZ?Ql768IJ^cOpk&1FHAF(9Hr z`Q;AKXixfs#r4jBdZP0oq>tstffCX}ZsB@}=vrio81nxF$jHWa#MMLs*9>YV5{9Oc zR;lTgV|l9KgGs5Yc~Bj~qnB{0v?bn|G~uBXXG9(+VkYD=Y1>9fsFjXIq=2GTUS*~{ z>1=G{DQ0Ax_Gy^4qAI23i=p087!a5W&*2&0F+O0bcw|9>r4$CKQ6iI%ww6nXl^pn~ z#e8Yui4Ldk21fF!rjF`uVd(&-XBkpb^r$B96-)9YDw#UlbU?&U!q<*YC{b4GBr4=Y zm;Cc|cef$D0@oK}$S#KbZvorGs5 z@Wf@Zk`xUcJZjTfwk%n&<^6r94T@^XUTyuHtiJB+#=;CYkpvaELNka$PaQxS$igsO zfh){GPhCPY3`2>yD6dehslBKJ;;7Bq>N3V@WG?Ih^k_of2axTAxynR%>cG)rY;7Rv z`z3AELI$gHr~w|}Y9b+sVlC!Mkk*E&wC4ZXlU|8MY^Fs}0XQhawt&M8P{BBu?l6o4 zBiukUxWXIE0XQ5D0sv*PRJELzP#o?@X69`WkcB$#8o^b_ z=4t6%$E&X4v1Tsz-pMC`*GC;~L})D4(}BBX&h+yLff zLpv;$B8IFY1}MU|;-mWR@BVM_@@(NIBupT$Qyi_F<*9Hel(A}Z8AoMW_X$BINYhyyr`!#IEgBY46vOhhwu!Y1$oBEA75WJ5cCXQI~G?(**5 zYU=;)@JED(eGTuA<_8muLv=<);=cc@STscUvZw;PB^u7~8ZN~JPqD(p;jL-rrWWeQ z?h#pB!xXuKEW|)V%tJOP!aPjG9AraJP0w^xPwwXL4dZYl{wfdGF?)n-2o|vsYbYIt zA#ZT3KY@@d;ps@&Z*kcj6({nmSh2oVFCnLTy&+$v+_Rrv7mWJ*`}M=_89ool@=f zDl#!Mo&=(7wKDPZ0tgH4aYdJz(A%2`jhqE64xy$>eG@Qf5^ouJdk*VqlWKd9U)Q#g&K<{u0#47PCSB zh-q%EBY*H$)XRww3l}f+LSV!joIy5ZgXc&D6=!VByGBXD#%9}u*HB0#1I z)v(Gt)3H3i^i$&T@zU~C95JZM9jF3wN%FGzh6LMO2Mykt6dyEE)7mlXUa@X)SO|@~ zRK%2cFGhIBt~kUpfY?U&hw7%mK*T_est!uS>cO(~9N#NUm-YWfYMvM{RoFB|{va;< z&m}RHARo^idPQM0GxbjJT_JK&_qA>$^ajCfPn+f2h_5n-#CbT;iH`3ufP*ZYgDcc9 z#nr5<@NdbQHD>cLeQp0j&#D|vR|RcKaCR~-NHJ}$n2k$+)TJWJ;89{kDnsrr|gs<5w@aNK1ZFz5a zN!WI1R}56=T5u(`Tq8DXUqnMFb_bbsX%j?!Z%1+~HxH65f7iHk7bp>vrf|3cb{)oT7Cn(e?#-jZx{czGXnlrSxk+jVD7a+R3)U_-$c zC_*Ic0s^}C(x7u`&+Db=uZ+()joUb!J2!xXC2_FMViyg33;C5DHd(~LEgpa!ltM5Z zKvAV*lm{n44>Oh1_Axhd=&E-~+;uY#bmYFBNI-!h_yHtrI;Z=A7kGh}d(5*D?3C&5 zeGlexUv`|YdS=i0R~85Bgw!_WxmvhgU9SZoHe65{mLpu)$JGrDtRfrPeiNJ+b+g{{8^ zliO528KNMR!aoedFI>(q>;rc2Wl&MDu?zgY0^n_%`N4yQD025R8^p9@yu=#<6ifuh zYrDH_!KY_DBz*c7aJ7oOv5om8xr{s3mOR;;ymSx8x^tr*2`k3JyGSG&Qd!9*AcH^b z!!J0)FQ5Z>1%ne2`iLQVu`9aJ+bhv4w9&UbNnGXz&vj!!{IySf)K`SYFSONr0oH3h z*Khw!eUr?oqq>`8Z`p^w9iRM09!T0(_iIlXH!5x&LVDuEQGcBelEQZ2kN4oKb<`F8 z;k&(8Ao1dRN7EkwBuE6dL;Yq>eq&Vr<$J-_)6t6~U%BM>1&coQ?=b0WB$M#C;wB)4 z(b$1EJ9WR~T6{NnFMD9FPPpGbo#WnMnKl-4XYVcbFYmPDZ@Taw0OYf%#;3^DXFNdo z@v`O34ub~~CRDhPVZ$A7jQJbp=0HV@7cpkkxRGN=j~^@Q5IK@$Ns}j0rc}9-rAd%4 zVaAj>lV(kuH*w~)nS^IgpFe>H6*`n?QKLtZCKXyvXH%z7p+=P|vt`vx{`|eMc(DH> z*8>P^Vik+kn6XQ5v`)o%3F{??UZbYf_?9kRw*E4y)w`E(U%!6=2Npb-aL%fS5hqsc zX4pSta_1(ziS|<2h-4vejoj5>N6Ap27=kpKv>!uI=x*IH+Dl!9m;UYAMVdAwfvsKV zb_h`-#lm|P2NyoP+Z z7+kP3kh~DBHb1t2LN(W*7;TFfbc5)h2xTLsw$W~@FE`#M0&pe*X{=Es8FBy2@jB{w z>`^H+K9bJIp{&!<$Rjnf(Yy6jdv6EMoI;DdzIb~KKE2eN&&AyCL(4nLH(&FAwMm$(^HW%voR~Lyf8{9|GEpj51;%EQr8^B z%QsYc?bX*`Q^izRmE2$~L60ib2|NcOjMK@tlr;RQ3)c|QfRDN?J8S6{s@z3PDV7K-*M_1OR9tIEu3ZEseK zD9iTNg}U5V;)yA)_yBh?9tq9IoTb%Oo#N~`H477F*s?RU63viB&&91zhGOtg&$O8)qgUx3_Yx8f7>qI%>8S(kw=Gu#c1jB^n%GJU zBc9yaqOH3=pb4>ak~O1`<9l$dv>vt#EBvUg+wQxwE4tlc5u6a&f+w@-N-YyM@v$4e zs>lzWZ`e~&4QV?7-M73L?X9!oPUvRHYuouCpNGjLXq3Lxn`pdI7i{U(o3j@%>Fii4 z_1T4W>8 z95(>lmi)Ja%~69iq?nD)B7us13@8_aMd=(V38mO-x+| zFU2>odTE;6*dGd2Sg$i$^pRI@M92R zu)?}7b|WJ}aad0D<4isnNTRq7JM8!)#oV$f(A@$k51N zlnsbZ5h9;T2DkI*BE;r)NL8+~S9~nf#^m#nWHm^Ou@qc`EF&e)bWvxZw9gKx zppG3VVhi&y1OsP74HZ#i5aaO2J|IC2e`LcRHFJm}7_ozKyrC0}ctbO?>6&Ixp&4(m z1{GX!gLx>z8t;gNF;20M1H9t^;(!DxB4H0J45JW)P{jphkuVlh0poFd{_NHQq|!H;};~WH6p%4$gLxd_8etGcwd^{YI)NduEwgj7aX1~&1D$LC+-Y)nlcnPp5!86j4QI8v6G1K~h2 z8q_dE9ACW#BW~d1OE7{F**K9sngI(hSe1d0@CS2XrHYcM}nynWP9J`D;u_((ZTL`7aPBj>Ao8 zZ>255OZoXCZT zj8n@kNN5@3WLF4l7J|Q)fjs}_y&2s}Qmn@}hr!)+_6ygAqxB66onBxvy5Obak8YrW z0t(o|F8*-Q67bM6Ov%W3RYMgZ3Y1x*CU4Y;3NFJ zUP5&K9KQNZaYqzdAPZ$g;R5u;h622Ri$62~@|xfL0lsr+z7(9Oe)*(@tasZY8e{gU z#d`OTX0JG6`5tcih-I;2Pxf>R<1Wtjdd3)HjmAI;fOvyo4#E|_${;!cA#NcXjKR3T zAq3Cr9mF9FcAyioVHp1m;tc#jA+|v7tYsiT=lC*00Q1fwte^|}pf>uB=b*v>598(l z5O1z8RBS@~u7mrA@FuV!0WfbLbYTK^K_C90{QRLFqTmbo!TmDGcFcn?B*X#_4)o}6 zGn&Fd2&ITj>DB&k3HQYY-LIg4FeNtT)cz*bUc_f|uk1Fi?0hLvMnkLo0sg+jE%?W% zJi!RAzzVKF5sZKl&Oi|mq8&yf8>rwbn2QSDU>_FZfL>7eXk!-)K?rM5?{H!ya&QNs zuMezXj3B`Wn_>=I!VOcW2tNfXkgzb6kQQeG9ymY^_(2~mq5QD$3;y9BsPF>#A@eRG zro7{e{z45g$Nv9JPhlWLdpzxw+K?B01rAG*QdCJ63uIMV3??cBSM-mx9PswaVh;8& zbN=vusH=#M5gZgj5n_N7Z(+ND=__2}658PnVjvqvV;s_ee|EqaNQ4s|;(!z(5>8>~ z;!r1Y&=pBz5d5GOE5Zs!0~SwF98-cD?Zy_3a8q_sBwu3kIN%1*00MU53OOJV-T@hh zQ5-hH89fZ(q#|5!YY_P_0d3;`@QBdId^ni6S<;s8i8DSjgt zGr|sV;v_4xBlLk1Kp+#)00Yc`AAC_J|3MxsAp_{?CI!kn_>xNY&rm)ODuj|KUkoQI zL)8|JDMK@{Tp}^RXEHU09D$NI2PF-&rzU48B{PQv(2RpK zF~T!r0yO;-Bm99GEMOPjK^}C$3BS)64mvM=Q5v zO*j9OQsF*LI1}{1ZUpb%1$Fq->+G=NZUqhB1UglUS>op%sgu>Dq;mYAA8W9@u)>920(qpKM3?d;q)c;Ar>Hj8kR909sm-OF*dW%9=_oKtYH9W^LF&294~@V zpNbCJt`R#&)29M$sX=c=XIEE%NM@kanLDtb{jKLj$^et3~t3+c+a|8I~ z(GU`1LV1hem;uN86i0CaUm+;med6<*}DM+DR)lhq^q0UQ4? zfD3#<8P@M5v4I294-KU7C2%tSNOUK+CtQ^UGZt_R(gSY%bUkM-Byq0Ja)wNu4_GfUGUat6+^r9A?pSqz6x~%> zKL|4g=}YQVBM{V5_G9mqAGYux_(7h4M{oaKRwD)x zQC*4i<^(V#b)>`vS*XNk$YNc&$7kC%IfAx0hW2bRBHLcVa&=@f?UhkwqHrC?L7J8w zfx#1eG%K<5D9fS~n!y*E!4o{88Tes!=RgRAU=Ci_byv3&%))BdNHpvxZnE}C%EEl^ zE;u^kVFhzdc`!1+@gq9YBPf<~9~W3iQe)w^Kz)U7pY<4@!Wk<8$q$hBO{& z9mj(IR1}GF1uv$TKP*Ucr7|NnAsJp`6zms3jCQuzXM90vW>eL0P}Our^z2lZbzOH3 z6nJ)Nw}ETd7k~#VWY>WyxOQ#Vbv?lqBY}6xsu`x#JFnpyn&B4o;3fYR*B%Jr37}zx zlR*d00UCxu2N+?6H{mcQ(pP)1YNR(Ko>w;A^nE4fZF$0ap+jP{7l`-s{SJUH{a1QA z?OEDGEYuZBK!zuKGAptX^;i^%c?Ey(cNq9ebCt7yX%-`J3S9SfTKZL0wP|jJpgI&higG6- zL_M^^bIEs#sraO}Qi@T{|F#&GE2Vw`AsfblZrorQ)WI46p(6iAVHl1%ne&D!t@2*M zu9h81i>}cuPVd!t6o4b8jeP-*<#>Jv)474iXbW(Fjw2BVWMK|K!4r-F z9L6C@5rPn00fHfcA4K8_GJz1ffC!S{2}U6a?13i=K?@227gT`|YK}WPqVK?VhaGb? zn3rvdnR-)MGZ&#_f8~`!nko{t;I!F#aLb#^SbD0FN{+IW?ogQBH>Hai97e$n>Hr+_ zq7Lk#5V`;mz@ZQhU=(=Tr-8aLk3)>7XgT|DXSw;MOLs?ckB!LLoZq>tD|ilIS1eYS ztG&8{$7l)m7ze~b7Q&!`?|BYn!4>%7C;@Xc_CX}dK?nZ`!3}sK8F*qJctQ~DKpdVR z3C7`~F&b?lA^LRKBS6`db^2FEIw@SIq%Hdtl zK?axc^_1FI^*H-THo+dApdvD19*STXT)`qX!5osh9iE^uciUoL3nXb&s;9amV(d-C z*()LNRHGIlaB8d-xU8w$fx+4r%6Yo0dyhrror|G?=RgsJAPf}Y7#u^1GQqBOAPH^( z7hsqt9y$qd;gUBY2>?3@*r6wi0I`4WB3Q(!k5`o6Y&4ElxL>gS5E20qgp$OCgsaM<{ zDj6Cqq7Y<48*_>n7!Hm?;sMIJ=&XH*~LJ~tsOK#Bdr05 z$}5=LX?G5QVXL?bY?y%72!RupAsIFy6MSU9xr3Aem(N8aVyV*916|OIA}0(TClXy3 zPZ=9PKoL~o00uw}BJcdt?^<6riOJ`oS~_s3`nc7?!#~?KjH73V+1|5b6N-cpY#SOj z!6GtY%#_+9Jl?>&m$*F@n@9cOb$waBnGc&=6WoT_jeU=`9NDS8*;64HQlSqb;TMGd z7Zkw{6k!&Sp%3n$6ox((4&V+L;dlJt4)B2L{QwW7o!O~9+3$cgya3y?-MV3yV-kW1 z%--y;U^LF&?9ZJO{$bq(p-1k#DjqWo1pHzDJ$WS3Ru(lLRq(wi2wf%&{m=vLl=s0N z2Js#apa&|n3bCpf`N1C+KJTE2HU$PSM!fz${liPEX0urv*&=lMUOzTrAD$V$YT*DF zVI8!<1)jjnliD6m9~x3$Er=Tdcbvyx!a?B1U)5NvWVhIFo^~w)+mn6S{Q%mhp63}M z5*Q&EfO@vEC1CA?lkw`?H?e?_l|v9S>Nf`=cEZNZ}M<0Tv=*AhzKB z<#O$>U<)+F57^)e*8c1{0o{`!697U`l7R#Z8a$Y!ND&4h_NBY zixqW9q}VZ}$dM#VcHD?ErOK5oTe^Jz2{We5nKWzKyoocX&YB2&`uqtrs8E7CV=g*+ zRHvPbXo|92q|T|-sZ^_4t?BQgzj{%=9N_xp-#>kSF7T^rGOgN*ZifBycWH;*xpJ?{ zq`SlJ#W$Dy!Ci@WuH82(-w;L_II-fza{Kzrq&KqU$&@QwzBuZZs$tiLJ#kS)m9=En zRAJUUESqN+XxF-a?YiwSW5y2e3=EU-rNfMS`|i!xnAm1><_I~CJh}4a%r`=T;zf)Y zKh&#Jr?!tDHCU1SMCvohPoGtOepSCysu1;6gKYKbLmkhZKIZ-0!9)Fie);&V`#~g; zfB%s}ASs62fnXmOy{F(DVa(zGheQ%i$c7h8T!`U?oN%&CGMQ{LR8I?$)P+P=jKmQ` z8HMx_Y%ad2;$J?&+I_}uij7TAs(^6F>bz_l6+9;MjmOwzwR~#hr&RCXQ zAdXcqUg=OKe#OO@WS3l`5?+xx2Bu4NUA5Z*!5QP1F@XIBCtZ#~c4VD)-ifD?Snla! zTmRH%n@+gB#Fv^E#fj)|Z_ozJ9KreH33HN8deL*yO(&p#cfgVzKc0RH3oP^@L)|aI zr1Fa>sSI+5AE_vUDyocBSD$y0L;?#n#ZcoZHJR!WAaw^2cnT?g9Dv|_2SjqfAmX5s zharhf2uUJrR4Cy)yNKieM}jUggKdjlY|!6Y?4e8o8WRw zAqXiHQWz%k8PP<14qQ>51|N)Y!Zz*5aKl8^`Qsu=F@+OSQ7MdZ#wkhJz%Kmw0}lsk zh$W9D8NBn3l?1z}C0ub{W!Rf_jk)DZc~!NhUpnjDQlfFrsd3Ok5A9UJF|CZWNN!{@ zTWwMe+LB>xrg?zRRtL7|pN``7C8Uu~y4(TKNhe^d)|qV|9+6=8Y1^Or14|~ss0~Xt z=;TrjE!4eghIgX;5-K&nWb=;OezgtDe$-8y2qMH9c*g;K%!i6Nz#L$YJ)!I)4kYh% z4hbpm0Mmy(2e5Jf&LF@T0?95Cl7b2wXApACh08FJ4HJaeOI%d8&m$fCBNkU`q)gTY zDccqOT3Q}Zn{RquVoaHcow>i7+3aRI;mghrxU)co>1vGOpFf5{r}Ig0f_W+lOX`O~ z9ry`QPZLvNa;CF1F_3{$`_mh4&>P2mZ8>8j+u1U8p8im0ZJlx(HL}5-QrIdO_F#uU z_^}UXc%vGLV^63;^$T4I&TUNWRd=2k2>?N&SO-d$$)d=^6de;wlFBl_uAD_Lh%|{?4!|W3N`_4#q}rhX zXcscUWM(^g6aw2c%MmIDXqoJ#FQu}U6qRyiZrGp#1*J+gNsTtQ{EIHFCN*Hx28BQC z%h#TRsr`gi5ub&6oX*UKHek7 z_rOB`LZ|SDM1a8tYg|Yic+`+R^tg{(*|b zZBswoq--~7n2m8-=T^G<2N1pCjB5OY8rP^sF1$evYFNV-w%|@53XzIJgeMiWwI|xP zX$Vpj3l`HNMOOCFsq9eW6sK^VZg+7CL)Zh0lJkclE;0y1aP*3>Fhn0n_Z~y|;tsI? zqlQE}_YO#SVH{_01rG=@hhz|f82?xXJ2qqwKMF)BHyuPml=q@T?)4#f?XQ22l!WXB z)ga;n0~*j^hoKVnM>+Ws7>=UU|Nayk0RVu75x~`d$m11LKmZ61@Q(vTV>0`FNXy(b zRssf)ux;86EYT!DGYzI|Y?YZ|=TcV*>zINi#$Yks!od!{I3*55VE%5bDB&1mYYe0U z6}&LHO?gVP`nhd4%hn%i*aLAh^o}@hwaqa5Aw1N95369PAIDMAx_6isBKnyP?G)=G zU!=x6sNs*xnXYm;JODU~Q6)o&!&w&*2RMLnhiq6k8`JsU)Bz!-sKOOk-#1D~&`M)}?% z#v$vT`b8`l3GrL@QS1X8PT7%hHACDG!i|tst%Rjb%w9R|syN1J15ELdZSp0WAQ{JO zf?%-EEi`8nOg7f0N?;4)zpnY?$m3p2)}}eaCwn1T{N5C&xP#@h;YUA&Yhte?D`ri} zFyZ#$rkV{@MFzR~jMIVyMv8@Jzi>wscVL!GBF7-{lsOL~KY$?+QSk|ND~}m!IUzRm zk4QWKW4kB%|&t{n&&x#>u-?^4C`~Htbkilr-mlH7DmARZbBf~_YDI8;VB6bg|L3a2*+q~{W#kPU=G4c{R- z7!i9M2npVDdl|AJ9dZjF5hDB|5-n0n)3bg>XoR&k5CWEjR*`GEWjK*lNAPb=adN5cFqK6TacM&INc@km&2wq@&ImiTxAQ7lQYB>Ug z4NFq_Ca`prypYA1zrFIP=FkBkXZa63tK=1VXy^n;01F4WtixQHW+(;5H0qwHYiwK z_Mm!xUDAP!kngA;N9H)tU_ z$OaN|1)VSoqgHA{p*+u1KjBD~);E0zV2n(N1~PE}V3c$)%gBsXd4yKzKZ!vZ+*pm_ z$A$j0KxXMyf$}JA=Z$12mWwnnH!)08Z~*C822!vGQ;?2TKm=>CLGuV$@n|TC`9Jk& zkN22wUa*h-$d3Yec%GGbF{E$?X^5GkkPPXNLVyDg*$logZ;WLGwum8Aa0OIw23v3j zVIT%<;0JmTiBz8K>G=PhNXV^sWHKnR~pfNN3&B0um@$Z z2U1|6Q&6E8`j=HO5^VU6IT4S`M2*>4kBGH@dG};_D4CPF4}Qo*jD`yRM4YgYhyz(= z11CeB`5ea)n#xfe&A<<}ahj-^Ayn`Ks)++XfCNp71W@3lv?m5OC=Q4)2%lp{43Z7v zPz-(W5ATr;*Tsh~`45?e3R$5Ezz_HCeGqz`$DOq~ zi)oOQkiY~7FsOy9I~=lm=m`|e1AODippP1B_PLCD!IcR%bTT5Tiy(!NYJAQHZ8cMV z+Qyb?sg_b9OWjziG_g!9<_{q{myf~!sR`p6d9@-I5hD?*68l9270RpW$e|kQtLHeF z&(>G%b`{BF82kfQrAexDh@xkJcRr(UElRDC@S<%aqqmYQ?-776nm9R%nSw_h(%}U? z>Z6hpq(k}!MVcXRP@bL830HsvPKpFqK(F;GueFFFP{0P1$Pbm)IK|LWec)P=_fdTy z4w0Y^+F=jHfC`jjItL)I%^3;vUP0AQYC{>49fxvlb3;gFqAfU5rayo zx3_~H0wO(e1`Y7gOlGA(jA@TbW*AKdnUX`TlF5g=B2H13fs^@fgh*KlxscECqhKSN>dLN6;I71= zd(ChR#X$&_;0ctg39e9kNI(TlKm|Ntq%GGDff`*m5WVa~|@PNl;(=f`(Wty+5V1)hjVs zSrxg4YhHO3)ho2q3v|vFR{EnC2b#2qSrn&w7ff4Z2qcD8OPApLbSm;{xf&9*T7_q4 zG{U5Y9nq_M@V^;a27HkJ3bsI7cEATu&;&716?kD7tU7*5d!ml1w+qs@)Ea|PCb$=j zEBmk=lqDUXd9IAxxPXEoZ@?kTK)JDn(X{JJ6?`#RttxKgwxECfwfH->TYH!Jd&v&*wJ?GPjY=>948Ru32YiqV zwonRSKn4d;1$@x|%B}naPLXx(d!UGHx64Ft()wfj`tv!boa+Pap#>Q3o=Y3^>dQI=sUeVg$73k%&ON;p}-B;fbN52|XFct0&Gn zS1sM?of1(YFY$8h<%3Y!5JEx8`J6F$%+E!Iy;Z@LMyC^Z{Jr`dYn}>?PP?>H0l`~> zRsd?M*k~rHs>soZsz_!)uxikqTreH&(Ot{YNrMKTpbPns4<-ExrT_yjfHW?Ej=Wl- z2apQ|oC=aap{~rzu8an*?8;ye%Qmrv_J>MU#~Zh-f4Q6}`i2p}yoU(#9el^s0O$o& z&^4a0LdQJ+2g$q)hJmOn?94xaAy4qrIZ@5QgU#A(i-bTMkR_WO*f`d;&XTwhvfwE{ zM1toW*Y6<_h>(G>c)WYt5)uIli8^3%ywUReFm+rF z(b9Mo%X*+~$e-4zb(#INi%HRh;w~`P{Xe%n=Vtt2~t=`1_!qOwuNe+qr$x zv0wr$9m=FE)2t;4LQ(}Aq0>BF1v~x9K7G+yh?W?^7Z1&t_ZY27y^x;A)O={8{dOyY zyTMW2Z&OVLT;ms4%^X=hq;RneDoh-6zyv(d1ky}%R3UTpa@LTGX_AZ97lJJu7<+jw z*9SoVnFr`8BnS(59pHS;tqgLq6Ecfeuo4mhnVis+E?d|JVc9q96ONR8cG1`$zO#C~ zmC4u={9M@?E@7BGwVGWO%W8E4x?-n2(Qb(oZ=0acG|6;K60u#|m~6@X#Zy=^(j~3i zCQal;z6eP`Fnllxx$q3OVACjp(^HPz$gSKxZ3GP5tZ+A=&Wg8>xge3r!37tm+kq=k z4c<~c-VIdV%YoiI(+sQ8hb<|JKm=Skl;;08)reBn%{-cKkqpC-25vwCDv=O7Viz*!4;!+>eO`&+9O#06 z?+BRalNTY7a3JgK*Bn?OX`qxVQJ&}7yoIgm%@|ZlxP)@7=`H~SM2KLbF7r^xvp6#1 zSZU%X&wj2Jb#iDK?Jn!FB+>LpzUFrmDGt<*ApN3Fq&E4;Rz-C z9#RD8#G8S%NBJl#&zwLEgq`V$t@GEn`kEdTHxctQPy3Se&r)#|x>j^Lo9eB9hCDy? z{5g%bPLG4ZN~dkK>1*S+p4w!n^qdU7TbsWyF{>^T?YeytC4FF7uLHx%5L<83XaED< zuLIYg+tdD`#hS}akoIXm?ihjg#SQo2PXDbu?pD6sV{Mr39(L3X5IY3_4kTF6AQdlO z4lG=F$KgYW5hXr^#n0l!i`0t2iWF($N04_CQZZQ4KrOal`?f|sAtTf%l>W3l+*5AygJ|R<=fZqU%-I{4<=mL@L|L|^Dbsw^MGERdJUsN zv&iyg%$YTB=G@uy=gS8cB^J#Y44MOI?0_~$+VyMLv1QMujabKR+_`n{=H1)3j!gc9 zzkx}xw#!SG_77`+{-)fB_{2UmV7P529b&2PzI@OqLWfasbHj~c{>ko*9Xctf ziBk9|8 z(Fn7YGCL^StTjYK6?IfnUt8}~RDYxJAAg{8sU-5WyKy@I*id?|FIZi>E+yf5HKs~n zxdTr;-AXl<(BEM4O$#>)$wUhmP&EhDA{ex95&mF^Hn(wfBVrK(4a|))YYT*Lm|;@t zQNxm+fJV|388Wd%5@9^?MSD{`QAS5ndBv7eQn8~&FrFwbSYUVM5#fOlTBwg9p)4|z zeX?OPqCO-pQc5ZjzLF*KXj;@uFqh%vjWN|)>ddCnjPvEH5^3ryv(Sp^iaVe3V~dpY z{A_Q`~CXNLjj2_2F#W|VAnSkT%}9L%kdeQqhDmSwJS0}Xxj z`Q$+z=v&>|S8lOzo?)8#wV55tG3JJLc6j5OYcAR0-FI(+1{!eqaO4_mS^;rH5bxEO z4;d%1<@{=Fsiu@?0+wWaKDu7$Zy&K!mwty2fVd%ziEPrNsq{}`Qlj6-vNWhIjSMzF z3Cd7?Bh(Z+M7H%L!5emTwG7RGh)5>EZRG|Ym+@cT>dcrk`uprCaXCaG-MQ+rg13Ht`I>(5(fa=0g|zh z7Nv#{WJpCS(5F6IwC@?|d&c?R$D$K~A&oe)pBDc%C56C5fFOwkEXFB70{+cbSR$3k z6!@Aih3SDt*}@#~AVHT^&?-&ApjBM|!4G3}f)lBjg(PM%2|pkMV73^AAplX(S=fOI zc7UivnXrmqgwQZBB!)le!owcUQKTb14@gbQwAsM%05DKZ5Rv%OtT6ot1wM;5nuFo87Zj7MD#V(n7X~t$FA|AJ)1LJ>qeXe>CG2_W8sMn%BG?9B&7>+(Gj^(Trh;!l8#?nsBRKW|jlscFQU6T zNm2p~O|St710Q&dWgH$i5Kbmr#c{)NtmAX{xLHA_xRAjy3>|D@AHZ=1BUAy6E)1gx z`=~493P}cNJYgRHg-Ax~z?F|ra5at(;v|FQVIO(K!yT*50V(zi5xLaTR0-O@LLfW zcDqfyr9|k!eb`IJ+39y&L@RgTNB~6*lH`_JIH$&;a{~okFgcLA)iu*~DOi@Au_4!X za>{svkqvtQ8y(ef#y@_s4;dq46U;uqdz-CMIz8JpK&$q)(fxX|aa;C`p$!~$yohj* zTlZNjH|%{6dv){lr+zz_QlrXYx^0Kv^}f|>)OqQCV+R;6CV2I$4~&DaWN-(tvBSOJ zaEM1ZtP`*Qc=`8Oh_mrdH@t%e3|=1du9^TrXc!P<@l$_#_~JUsCrHuX-kty30fS)( z)>^yynuM`q5q+rwNk}wAlQg%ZD!GF`9|5PGIHyjt2!Fr`i+}}GFs{Fgh`FATd&jG ziK0-w#Na58+Ar7pJt+*8*{ed@s}0-RBrw=LE^M$V{K9MtJ}Gj8Ub(lRDzRFLDs^Eh zD;fy7DZ{`>sy0lc;n?8ZFK0T~HP2h*@^QblWK0*9GIr6WtVjS~JM6;qWm1Bfq zAOsozu!A}SKNCoTQCbjPScE{(24ZLidaw_q8VLJfh8GCH9O)YH8J`6_07zSi1(dY$ z!52P|MQk#~9I-SC%n=K`z`M(aclZZC^I$c_qplZx z3Pji+HfV}1&_SKKf-M-PW;=jVU=<*=hhSI+LXZRbGQ9&JJ!g9hXp6SPfT1`0C~gBo zd!!93%*Vs4jUNJ{F8oK$=)HR!$gdJZDPp(iKts}a179(!1E>zZh#S}tF%#>z6;l`& z%fmg~NP=U7WB5a%*n~kG$sEHep7JrWQbd(>9B7H6BG9Uad%1jw0EdGkBFM6QsD}gp zD26`#hj;+RP~3q9c>#opf$(v__c;J>91(0v5j23G7kNc{!KNxvn7LyZAmNGO!aIvV z5{%G@iwQxIAT<(HM#7UY=L(g0ipF`GMyK$DoMDT%#KD5n0!dhf(vyTu;Ji*qg;lUi zN#F!Y5Ew}qCM~EhJ3u{m923M~y-kokf{aYU&_~Ktwc1lDe*{P_6iCVJ%qKF)D59c- zoJcl=ND_0y*s!;Jvq*xd!>Vkt7vo6T9Jm>n0Ux-{O7I6(=>%fngnbYSk_^u9!=XAt z$(1}#vua6dfk{D}#D-ggHAn_xxChD#0)o?oPt1o-2t^}c2K!)`CQuPHcr8i)Nha2E z%C&nyNux>@GlqqsJN*%^t@OpOEQXF~k|+5)WUNZFJi&;wGE!l|>6)jtkf6DYiNdr4 zhL8~jT?htUP)QJk10Vz$DNJwl3+gHi)|(+~^Gpv_jLHnrcS$V;0NL8gfZ~VkPOa29L}*R zPCP?q+lhBj!0 zQOtqr^Ui#LEQltC#vwv z4{3-#2nOS7rd03)hbRPONCk*U1x6qtUtE%oFs}SO#{I0H{`@`On2Aw=Mlq4b#=8?g z;6|Q!fx;Mt1KccWpn*&kl}r&$RvJ2vEKH5nI8h?v%wwI_uwl`&xv&?N zL-H`qSwYQ-ghT$rQFZz^>hsZ!v`ryR*L1CfVdMlJP*UJz((iN9V<}GZOT+`1Qu9kV z+(;cO(}Hne(`4W(CLjk$+y^F*0dTl6PFMqJXeC)l2P5@|V}R2jb%Hsa0ots;HNb=z zYn6g9f&~c#TkMYOn1oaykplpqmCYs)L5=iOPeh$c7HI-g#Kmv_${&X4gI^fcRj`GJ zNQGZeggaP;Qn-U=LRz5Z*{N8CX6iJI5le^|394F&v;5CfDMV2LidLhpD_{aBU`*LK zwqpwnU=>@xa6)>lM{1oyWmTF&;H$TFn&W_)mV#EQk=C}|TVt_Svq8wwj1?J;2^tNt z=MYzfsl&LFF&P5}bJat1RaePPS0bHQVyJ|7EGRfm}0K2U^SNQL&5T8W_AakX0i#9Fk0)vYa=7Cc+Dg^i);gtEm@ z1=dhbkc+jALcYzmxgDBOklPFvl-c+;1j{|V-3-0GU=t1%zeSbdyHRbW4Q}n$7EX*E zus6i5pB-Ub9R3GQFjpX*Tpym?+~kLS*oRKw0V9T2PVn5%6_qG5&eL5sh?u!g14aYRr6Na!3 z29#SE;(2g`nt&X2NCu&aTP?taa!7_dss(iz1~8~XA3A`3G|>^xj1t~uZ61^qJ{2-- zzMx#bdVA4%^H#$!2obAc=}?#)Zf9WJ;XSO)h4^852I38z*djjSPWa6vR^pOG7PN8V zCq7O>5Cnq;1VI2KDlV%{P=#yAgfG=%9AkoXV1gtjW9a0>Ar_8*IEG5Nho5W%a$pD{ zoo73B@d`DZxw_U;;KstyRkgYGqem z!q zbLV#E2aS|xn5bvlURR6wO@GK|9!OGt_UEpm*Vt%cJR04BR>?vT1R7cHPm8Q_cCj`JWEVxcf%BNnLN25zsC4W2UY z<6cRG2887{=!7nW=RWl4mH~PH;Dl??;)RugeQ3FC7-H}4%67;Gakx!cXoH0q1AV9m zec<%;4$_6V4<|rr;k6HXaAVr8z8P@ue250`*3B}yO8njf)L=VAlSQfQ?-MV6z8r*auWVg<#NdMo{*iRrXSFg!mmUj(NTi7wfUs z@&k!gFzMP9hsVR1wy0v2iH)*at8;Z#$?7 zLD+|bPl8NH2Pn^AW}Wigv+{he_`@)F-f+<_$C1Qf$XeGTG9UBNu9DT}tvgI}*>q_? zjO}CSi#V6_i`ZN{=K(zbk5}LpZo}yFh5mDbW^Ni0gyc5pOgQvIcLE$+15QYW@2+$> zC23M$2w49F_&$JiU5Ff5kTE#*Agwc$zRfqUK3I>28Blo^xAlUE0fSM%S!6q1|K3?7 z14)P`TM+jDc2w`k%Do_xOHGBU?u8adhIQ}<&WmtwfQ3RRLZ)_KK=@RkMW-ndcPt@y zbHn)cNM%IfTDDww{CczFllQ@>aa^8Y{bE~-7pWe%!ky^%15gHlXNXpi2RnF$Y@8)gXYfd19tBnFI1>Z4J`Q0 z8)N>4xpAX)G2_OLA485Td2&J>mM>$@ta&r%&YpD?p)7jzflZtIE#vft3G3FbU&CfX znlUF%|NPejDEey)8xbjQia zC2Y0tlfqW=K7D#e9*v-VV3KD7r-eKH`u3k=ZwzC9!bNBn0T`fw0}>dZI{6`(pn?lB z*r0>geHNjFon?aCB?<{9lY+T%*kNv$?50(QBa%4PB_EbZ6Jf^u158OP!5E{AFwQVT zV{KGYP>!O7)T56-QdEgqXLT|L4@dIQ$v$gwB7>7pLK&r$FhDq=W?E>KiI!V(*`=3V z5>kjDgp4W3n455EnwY7GDTtVDx@nr6o8Xd7I{X|!%vu5s)P_M6Wd&$L9p$6TMhgjg z5kzDEXvGXfATfla4+X7+l1edZqKSoX2o?iReAv`eQK0Uz)2Bz}qLeL7nc6C-QcYFW zRgm#jYb4p&Q`V3IWm8NfzYfAxAAJmB#<0Q~TdP-o0hVH5D;}2EgVXwErM1^i7#g*W z)p43XwZ#^0xYOCTOo$5Y#tC(=T}Pa8g4`Ex65G;Sue}Y7pLYNntz=^d4Es`Cad!;z2Ll>*{8ymI2HqR8$Rm?na%9+|%vpuF?KTs& zhIyFVOXoJ`tj&R)=#Md+l318Az-Yq8j6=s*qhvZ(a=?z10oioZLh^IWF-#(Pq>@bk zN||-mR92U=4qzPcrPyPGDJCI-kV$4Cgv_aCn}s;?wwY|>;z~B;@Z%3L{OEZAo>KqW zqgH}ipOY(3Rfh0-7zfg${wpMvp1_)ShR|n9J1HPr(C>3n>Kp6y+#Np#Q1|IycTb#y!hjjOtECR$ny$$)@Y-CE9ta?a5{kmEKhmoZ4AEt7B^_Z z0sd=@V;>vPfyigT10pbijX|E*-0-2u#3Vm3li5p*0YTtla3(qPN9I&yjGwvxh-f0L zQAH-Rv^FR$X*WV)pq%EykW^wx`w)^pI#IPGEr}DG&>9b)#5L(0k8DC5+n56J3PPMM zZGt$?oHAjiH?he~r69yGvSGz!{KJa=_(z`%A`5X;q9F@u!#Kj219pgm9dPi$7^oqO zgye%9;7N!tvN48(U}79?7z0E;;ipPSEgldNM==7|BS)n~ge zY+;8;=44c^+Cf!Z_d3{tB@(dc)vturJ5ZvME5FO&4tzE|1v-dZhFx0G9{13+Km5QlnacFdeflMtSCAte1UrB-vLTOeO!F20=~!687G|D> zDFh8@I3_vc#UTIruRk3tPyv_e&UeByL9;~J$}U8&6U{6ugsB-T`ze#0?W~oT0HM$n zIinc>i86jlVM3OckTyt7AS#^53oAM)vm8TDxUpf?IKiYH_K=4^td`dbF~m$Tq7Z9H zh?c_UrQW<^4M~h?5({A(CT_w^ZW>c5T2YHpj3OCY{0H~42o8fN#1{rpszTZz3m;%& zk6}DW4&>njr&bjr?>K-s7)1>q$f6+W2nR&sA&;}{qaG0HWkP)9sE>@qpqbi~r*<+F zoc!b_rK_YQGzrO|7{yhN5KSug0+-zFuCS@}i$7h77~;jVO7oomY-ZlsE!=?Xm*QH` zZhB)q&9>$Mu!#(Dx|fM^UM#YzMWDQjCr;GDHhc?8!o-y09|5&MO|14iNGW ziWG<`Gbz~^aey_z7ru2MgxJz{wpPeAiGo-|6VXJ7QuG2By%@z5RRIlfWFw1Nyu~f} zaSeNb?vIO3ZmJta-4JjWS zE;10^6`!=8T?q%Ot)PC|l5(`91DLvMW7ytDSB+khFC8;lAlrN6+xL~u_e(`2L`-R_ z>$_Re6^g&xEmV>0VSwY=w}|#7I8ph%i31^k!V#jfLDe@>b%uBJfjADJ4T#9&7+i!m z>kr_OW3Vs>56Q;0T2O+rkl|BOMu91<4{q#SvtXIP>YUnApK0 zc6!P9#!<;wkAE;)Nq=?TWtsEKemUjRLy&E5leb&Gyn2htC3c8u+V7!u`|^JbGMlr` z0UaPf2Yjv2;~yP3&tCuvV19JpX4I3tWXPdaU5UKGKmh~R$w*6RoulP|jeHuYWkuL& z#o<)K>apGja?wOB#@YdisLfD#jTd<#$=tD=KO_Su*xi#90Svf60cr*qkj<=(f#1oO z;H8bOwL&Z4g0$6*-DJZ)WCJk}LpJ!s0X!S!SzZ)gLMPNl8(@OwMa}_?!BZi`wy_Z= zR02q3Te*S50gwYk@B;|K+X4IoJv>VPRxD0Fd_oQ!PNh+mz17~=^_wEm0U0DjH9W)U z6r97E3Sjvd7%(66Ndl7{0>vqWtz-i~oER)bAI8A~?j%S4;zlx{$ug>p*!?aGF0F5JQaD4vNqTSQ9XbW&#&jvnHuo#r{s zANj!SMT0$L7repV0lXEy4GKi)0s|mHI?@;)6$%~lBuPBrZS;cjkpUSDB~ey`EgV3> zrH)PT0U0bJ^EIU-6zEbG0wm53r)3uQLggC}z2z9}I2B;)} z!F}rIGxTSXL0lpp!cs=ufHGMa1j|=YC4**H?NA?9Mkw$IkM>olg<46DW(6rePg$B} zb)aR3mfx|6q0w-Jp5o`oE=QkQXVL+&Z@*Es8{SNr%^*O*p4XyYp~kugkG7B8mokmoVq52Eq#l$ zGOM$qrMZX}6FkrJOh>g^>)zO+w%V=9bZfYZYvXzh0tus?oh!N~Zsi^wVm=UKP@}VW zXuS?bkwRd;R%S!wtiT>b8;~78tV1<8!!#*GAWVWnOu{MzLPONSD#UI>%x>*QSB`k# zlAay^Lo6)AR+I@=f+sXX-gH7%ynsSn>;XJ)LQrf%oWU6kRBduB$|Oc&bjdIbgHR2X z6jI5l>)FzC=Cb+_&W>KInVY5M`%*wCKBI3@e2e>)d`u-CC|fWazT)t#rKH-;Q5r`O^4R#~YxU%V8`0mD3F0OMQH+ z<0>(@1|!fRE@@PZ5lgY3fu#dkh~{o?iA+%Ef=EmVkC74$3EkcR?`!_<$~pvtH=slR z!a2k*#O@XRLLgiL!SyFATtOhr!U4ds9OLdcK9s={#HDsxkoX8h4X>77+amdcCkTNj zWNu?LuVfI0#&U@FdM}q)@-TeROB5Gjcrsy7LEEISoRIIV&FLDKB$!+i35hw13Bme zNaTPp8xlx(ggCB6Oad^F{6Kzstp($!k~sn$9Dps9!hQyyfpTy;KcylvA0P|@B1B>d zQy&UHXkVm!$@?HtT2ka8~e=aBLQ7yg@DM#xT+1;rgHdK;sK{ z0OJyC^j^AX6YozknvX?`^lGu|6+dGZkH{8#=yFNs2u)fEWhZ;up%@(i>I%d#Ov5{% zMKJtB(#!(v>Tw`!#2V!BDy#uQ81)^4-4)D&Itodo2njIv2t;XG)EH8CA=J?5*djNw zNn1zoeDWvTOem-CCCG_cr!V=QvV1{97S)0=2&&}C@?6JqEpx&xGfFyEDQ1S}KSb*A zwgaPNgGD%sIMAWzQJ4=9!ym0dJ=6m|6hjVdVOHfs=FP($eboZzLp)H!lK5;lJ53I3 z%u%eW9YoxcB?KTO#OUm2Du8V}Gor*5C?MQQSKxC#tI}T(X>Iy5G6MAfXN+`Y;O)y9 zG%&?nh%yEbQ|m81#zVK9yDCJQ-C}T8hka}e{xvS+GVVr0E*j|B;@W5wQ}=kg6Xvpv zh@fX5f~rT3zcRIVW(DTT8^xPz}-eQlmbv^1??WdFI+)FOalG1RUoiJ>2_C+ zPy}d4NXjVH{(95`~1Mq_&Kz?_)%S+^__Z9*XYV=Lc+6)o5S(DjPT z@}lDMdS-<@$U-2C12|mf2l7KZV8T9tl`Mo?7`+3BF^Z$i!%Bf^X8V9De8U~(gFJ*o z8)(En+61 zoU=);;x>fpHumxMiT-wHkoRQNaB)Khaz}=8mzm7H!9?dRnxW-fR&<}w#)|IZbC^JK zT(|yh^re4HM>p|zJBMKMkE4S+0-3jl$18_V#d>$hW#TK09Kh&C7wKweIx>c)y}~ab z!#eDPH$1~Wl)@xbS|I$wDg-zkGqtZD1XEuD*iDyHhY?ltDxW-T(?~du`Q+trb%v8V zWth55Fv2E$_=n4hE7Zaf=84@jn=#yi%qj$nv->5yxBzEBn7>S4l`Mc^)PSdzif0>m z9vgw_@Y(~1p%6yMgORrZj|W09*n%^xf)6x#IIO}i_`o{<>iM2;MyQVl zLEG>R!(u}FhH7wvD~g6@J+wmlt#D{hEi!te^E~}2M^-?Gc2qjgVS3gVNOyO-r+<3X zgT2Y@DCTVYh;&Fx0}YK>;04a~Hwq4Y=S?N7!7uE?t^b3rCrzahbwaShED#*;27<7M zghi~Kf-{7JKYMs)X1`51wa>^_GjfK5$YhlLOmw@4d%G*=i55MiiWiqwwEJ8uLKrLo z608K0UKLfF-;ICZI6N~#R00@k*zod$kSmHjXatz{yRgdw|2s5wlSjiOIJ`Zq0xm$r zFSLPQ=S?ukgFpNN>@mYHggm7!0UYGP^6gEB=PKBt7}nT($y45`hB=7BqP9KthEJ88&qI5Mo4$ z6Dd}-c(I{Dg#{TNG$9a;okb%Lj5N8ZB*~L2S+;cf(j-QiGZ~^mBar5SgFAU9$@vp# zP@zMK7BzYlY0`x{m^O9#6lzqdQ8W4TXY9=mty{Tv_4*a8*Ed#yv0(!QEiho3j!E=! zz(?G-3FX#}`*7~VE3NqPtMrSIvuDnn1*?Xx72RKU|5?@XQD>E1$v$#Sw(O%#CA*c5 zRpNZCZ)nl{{`oyH;{aOKt68^p4MdYwPeO!vvU*8kSlzpMr@6H0_a;}_tQyPqFWa(P z2`}MR*c^Iv>C-PMniFP5YqOPN_x1M=e0cHy4rum)DMz-rW7wOI%P;OR%1-k6TjN8% z{2Z0qa0=#wn{a+1<`*Qg$swJ5@(JdceMs}>nP%Gfq7USXB-Pv|RH%kL%q1W7fR}(Os znWHwV{BbTJSM}AG3NMFC2sz}IV-7lksXG`t>#zfY4LI1)1ejye?JHtnz#I?bWBl;} z4sd*t$A>Y*@kN}<#K}xEk+Z?Xhe~A0|A!uZz+pKDcCu;amszwqMji}{2}Ygq!H{HXM84=9S@OqMM=)~Vvr%- z9%W7rN7*1D1JX z&xH2O9I3^V$wZJ(MF$n|(tlz!A=Dey$s>?r`NY!LWuNr!m(ZAK^g&JEo%h~-KZ@_* zn{vb6OXPMnNm(_a6)n^j!ZkF|c7@0;Uw^fz+FzVmXZkjJdFDHB3PVPrNq&jUhd_Q= zfBkOl;&!rd{b`F_g}#kz1|NW6|Hv$e*-+?R0d!4l{4tw)T?IGCQ(#yaah&jE!x+oK zO~DR;FbiJ76}Nx`D2`E#V&qCR{wNDg26_?65At9fDUtNOb17ToD z84U7_G8FU+V|)u+OuNq~oaTfX#)U&-n26P^rUyNc$VDp(+Z3xIBN~@FFU&FahzC&RW3&+hiq<5Yyy;^ za_1>F9+D%eQyuPDH;_f>A{GitNGv2ZJ4;?NRF<-dLkh{0Lw*vJp)6e*gSRSUgi$PG z9HDBQ*N`@pa5U3%NcF5Y{~4KJ!a;30mc634EBF2KeVE}4KO_Q-N&q1{ta%timiNEZ zXlE_V6CiBlMXv)I50wiX;{$KuiV9xvg10aZII=-Z(pY6Qp;_f>fKi%sf+vN*oXb4l zmk@f`r9zllg*Sw;zJ3N{AL%$o523aSsQF+qIrxMy@^Mffa0m{1zz7pRgaY_HJbjkwS@F9HdS+Emgo$|%YwkrJj;ap_E-~e+ zauxw(Qu?&VKy{K(H2s@K8aWV}2xJiolBz_{f)SW05tYHSS#<8z_&swd-XDAg^pQ%TUp0i>D_sy0}vy0~gqDQqbxRajGKfWd%CS6~l+Sgh`? z(pj;ouk$KN|Fy`>pIsgDR>O{mAD!V(E%S0$%Uq-qZ{lltLinb@&bC{GMJ+$r#Rek7 zlE@LMEW{3A*w#)nUjCSuW{cO^R~f^dDF%WfMtea;gkcFtNXTiOY!(1AOcTp%O`2D^ z;_JyX2U5*JW*Rh&VB9$u`?!aKT9GYi`SZAPQ6DR2fuU#w<+;$MhE*8njbzlQyDDmt z*BoIBOIHJnH!6e~dgQk9%I(BtR4<5gBI2@=8r3p!W0(kGU&Ixqj^JT6Ck{aCp9~c# zefrZ;IgF50BPEed?J!LmEQ2JxP8Sevu!JX!VQ06*D9>JrO_2I)YhQbJrlyh`lEJtV zBPmvE|Fu=O9s(NFj;pY7-RoR?wGa*E^-cazpBy=Dn7|xi(YF04`F2CZ=!6-$SzZ_;WFYf^V zBQwRyk`UEE_L%|H#5kzog}RJ^8sHeioU=iVou>yJZK%vKz+oOtutOFWss}m5ag1Y} zOkD3k+A&(8AQ|qb6K$Y}f-Vz;9B_iq&6P=_qswUUP=gw8xZjChU zX(MS9y)DHyMYIjmz5hKTHVu>ET#Y875aLg9dP74NFS-8Wx^rv_aIbw0c$qL&*fWW0 z|3Vtfx{t)rs>)urF3=!t)1w3>KRLZisQoF+zaI8l>bsP_BWtXLMU~4Nx3(q%OQ(AV zVBkTmJ7r8)cjMJ9Io4HO?Cl+^{21SI$=^d>8=ir)E9UzXcwd@)ScZs3&F}(~0c+C? zFn#+-l90p>7`}e3tO6O{_y;h4!3ZD-!V#)*M91fliC|>n5=tQ$EXX<(AqdQ31{|v) zPOIf2tFqc9fY`tn&;lHq#|QQyE->K$#DOv}a2_f{J!D}Fd_We$g+H=E9O7Zm+JG94 zVIHFAe&{0~WGGzV;kT?#hU5aG9*iDlBGK{y78s2hvSIBK4T>fW32(&GuE-I>|G=ca z=+pKk)Y2>VB4YN?2urF^3+JnF3NKA);!ePXzapaXX5tGEV2*N1bIfE7$)t{Wjq(so z3p>K8HlhwO;*lKe0Iq7P?$87dKn4!r6GBh)tghKs&)Fj7A`p>MHif|E5E3JCCay3l zh^O}2P6H&<)1mN)+$n_>hmryd^XOi{3oLUZ78&Y{hx@ zN6F%4{`d|2_~!u9Y|PX`7=^KN6k;?g%Uzt>J_;6RBOLP4l?$jmCD9TBTEoatTQu{FS<9lRi!;9wrS zpbd&42a*my#^4>|0uCx+ACBQ2o{k?XqYd~$9}+?z=AjL;K^EX3WT+uz>LDNEAs+H! zAJ$VnTR|HdtQ8JTBlCeHm*}}7AtXl<7DkdJe=utb0Y{RMMQo%OoYA~wk}cnoZ`x84 z1rMiqQcWJ>C&!Q`XwB9x!qt*eDHWn8AHs7$2P&!Z^@7brA0pXoYY{%eDs>@655NSz zau8Qk^giJaALT4DtRZ&vlBkUx%mG4&6ek_DDbDH=QwT3+|BEJu>4aiw###t4|MD$n zOZob;E@Cmqo=;mA^EG4w7!`uephpuPA|BD=nIH@0AflZL$P?y(Ugp3vUnNQQp&F_I z8SHNrpa2Rcp$<;-7njMq|L_9=2``P6+isw;AX9;0 zAAmp{Wx+Z<_r@;;Q%mU7ZM^G z+5p0awIUZH6n0@W{&VgA^Fv@k?Vy!&OVXmW|As|$gbc2Abg2L~Gyy!gwJU^{NoJBJ zE!IjXc1U%S@Cr{|BQH)M=UpX&C);pynDQt^RPsm^UkCQurV=MC!YZeV^Q7t%_|+l) zFc1%R!5V^7z(7YKR(sDaGUMEGQhA$ZSve!|?&jWgP} z-J~@7;zId;EEZd47B#_T11KoM^s&lRY*)i(zcl4k?te_EXBn7rtgjh7fghe>7|enY zfurIAsdQ8J=VY-^g$nr|MhQUh92&L89w1`38{GZ4n?6iA(l7U9!!!BfRa*A^A0v2 zuo5EvP+=K%dr$e<)Zvd;xxm7Ad}RQZV_62yH+{!okKBoUNmefI>iB3vFVii?=64}R zQJ3#`GjL^P`Bztdk<7q$IB`~HE8=1LM=czcfT7tnuo-|CVzT)1ox;NxfWa5c?`!uj z4zw}<%I8mkU={#j6r7 ztta2k7xN z?08$n$Qbf?k0r5>{g{^Z6pp>lOd@^Ey7=mZ6@r%lu=o%Wk;23+N@^^c3)YR*BX|S0ZfR2 z2Reb#mN_tQtd}w3mxZr0j)i@J&wh>hGOjeR642bPxtX2WQf+o-|CtvPqBn1rI4x_; zMx%jQj(`ft{K^z9>R=L9{~-<9#S!A5d{V(1nqf`jz(lmMvsYmi6oRo2%cI3ZG*+on zA@wyRtDPc7n#>|yaAmJABL^bdc}Fk@#(-+_pjh)EmnGr`rRpBuA)viBBt@DeNqPyo z^nW!IpzB7DhjgZ;A`8#@djpvX23ZY}Vy7ABr_iZzh`QB`@(T@bUY9yU1!)rmY?40= zd5t$Bs)`^mxp|dMs}3shgrmx}s~b9RWHSx*I~jyKf%6rdMr`6t8y+*{9a~P4EQ1=heUH_0NaG zUY)u`3#^j!RU-VgMF+xPt@;x{8Nvp9A6hMJe6}zATc;!;7JGd{hgS>#-{K>;FvWOA3R;$Y2r=ocQ z!tC<^^56h&|8Th%f)lh(^ymS)$-FP78_m-k2`c)CeyI)A0zBTFNaZ{#O5MS^a6&0G z^3>a>Fm#dY1Pz~LMDhEn#cIF#yTJQ!AgFpEHa#UIec57RB$lltq{@?zB6~kwd+i_z z#$nVIp637N)KOiQ*T7ylfd}H+)pZ5d1(Vzug4W^6Wbens`6JiyM}O*A#hK~p7lOqL z&No-u-H@&E$A;}`plGJ#FR0o zz3dkdv2X=4wI6_eR-KX&v9rGJ51<&}Anf6QVq6ZhKq2hwU+h)f*uNd^`3Klt8z6uI z(*&d-kOK$}8brvjVMB#%*a-9oETTe#5rI+Eq)B5%HWx!0oZ-U<5;zVSw#vtnWwZlr zTsGuHucb|TmF|gq$M2s{pVX+q3Kc1j(W6L{DqU(+43Zorqe`7hwau|(KZ&i8!Bqwf z{}?I5iXBU~tl6_@(=yb-wyoQ@aO29IJ6EmUyLj{J-OIPH-@ky*Zc65l6DKB!6DwZK zm`UIRoc{S+_NHNFPJJCae%z1{r)B<mT9-v*2e|X+(4$MAPQAMI>x=A^R?fY<_wV4ti|0rEpPamdO(1;;PG?0rJb>vSmpuiEt|BgHs z6X1p!7NaANMD7U6hY8VG78@Nh8I~p>Da6o4XJI5!fFGeKBSjfeR1u9K1#w3ndX%-& zO)O#422I1UL{A%`>|)P5KnX<@Q+Vd7lv7Yq=%-aZ`J~l)>47!gp?RIB=%VEz>gc18 zMk;ATgB5mIW0*1)SY>2!suyAhY^I!Hl5H}YYN)0f+oWo(hLEdgEz;5frhU>947{BM z7H~G1Kmg==7Ml0=Dj8;n*41}t;$$S2c5g!l4__NP4 zKinr^B@Fq%pP&5!IN((h>gV5q5E3ZhKP(=jV1*V^nU;sZh;$`CAcl1i|3e&U^dXdB zDzqX$4Ra)-jR*(zC zkVRSwbn}QFz1(mROWc9S(0bsJM_GBC+2(NAsF_Ec`|v|eB%$bO_0@c`J8vZnX0=te z>lr%jc-EH9=-6ndt@fmq8kXtXiLD*#V%>QLnyIShovPfhqLvnNw3bHOZg$C;*J;}>t`Q;6ntvOrRg3VQX?|B>Fd;wNcZq)T1P|{dhQw8sYQMDm& zyY<@JV8;#K+_KDP0i2}61D@y*$_?@Cpu`OWkzv3zc3E-92eb&0|BX1J#E{54a?Bzq z*keyJ!5Ff+Owq&Du=bSJRpl7(5mYk1=DBQ%4Rd|joCf7m1PprcgCHbJ+b#vSOogX1gvg5t zTSF?*2tsc#gw>;R^{ON=#BYJyPT+1xL(&*7AGImX4?i(E8`>}|KXeG-oJA~RAp{MO zi((X+CBqO}@rqb%%?7R2InRM^AEJ|wxb|T>`=Cx)9 z??nd)(1}v?q!l5rdCZH^zy=gOLJkNd7_;61y0;@5WbXj~|2V*q7%8&v6)Y@H65kzP zM37CIEPWHE54^?j zoJSmw4s&?K)UdOLyjhJ9TXLEot`j!25{oWo#gHEgYiwWvL*t}KQ0hpoir7r3LKjL+ zMs*Qv$!O3rzQuzvfQF1eI2|F?6&7S_?HI6=N*e-&F9KD>j=T#|O3C6ovG|dG4tp5G zQWVIG*vNK-EaZTSAtXv-4-Uof$s&E)J(67#ArjG~|0fS})b@1*j_cz{M1DuVRK84p z?sJitV0nO8dKC|mpvF5;$B%u?gBr!4#x9P56inm+6T2v;T$gf8WLkw=&3vX_zp_xY zG}Kys4Xj`vRjFl=Fr0Mz4ktzdnY$o1Zho;_Xfp9abizxf{qn5BZ1tzF5 zS29&N4|R2*GW~IkedJZI(2OQ-!=l?pjrhbUeoSEx`&dwQCo=yqY$sBvg;mUA7Lq{7 zFMcr#9&6zMcChg*w15~p@OTz>K#Ue{yb2<_m@nisr)Bj9p3}1PvN_}-Zw6-?m@2fd?X|v@gu&D^eG(R z01BQm6S_)08I^dZv#G9>s>zd|Dn-<@|DOd-mJY!~N?;jQe0kbloyONbq9zo%60?{Y zZrxou3?MyE5X2##b6M)#7Hxa`+i6*GixWGl`9#eh$f(9*aeRPZq~sTN0P-)GU}Pd2 z88Pst_bMR!7s*O_%AHk?l`RWTEgwKQi@+6WgyT2U=2OfENL)S|GQ=#hxy{s}qH4g+ z@s2-++vxG!8o1So;EusP^~vZD+7Pt^7@E-R(w7fNa)24E%#DfeQ2FF|>y$uxEZfC3 zOjAU&fhY{TnVyJ{Sgl?HsW;TvV+c_F0SX$>AQS@P9@LAp>QgVR(Ti8H2($*kI5> zk5j9mj*qR!0Mn^l2f}b*{F4pEe|xG;1D#e)30YXIE)G<33mgCSoE6UBwW>mKI^f zOa#(tQp11)GBpTvVMq~p|2fbn8n#Rz)d?Mjc+RAF>QMwm-~!b5cxKahJNSdzMtPO@ zWSsFC`>+nvfDH3655G_i!GH|tU=P)h3ZqaNs}OGp5oD6U1d`B&zaR-tCQh)2dH*(h zr~()RcV%iA8=3V^$Uy{MhGv9gTDf9n!Qxt>r3=@T8qFs~vM108k%$54L#K@tXGFC5`9I9DRJMt^DHXb#a*)x~RiWPkKCQ~Cu8rbsfTSV`Q& zUZe&G1!#cy!hesXQ#yrHJvCpF20u`8bo?MbG6Pdv;&z}YN&}`4V&Z`xXcxsMAVEP^ zd6#HGK{d{1OmNVG|9;|vK5!rqbQNRJ28Wk;Hn<)*sDpth7S-Z|<(Q5rCWJ%S8lw;l z!Qgr95De(B59sg<-rx<+AQ}Gf488DUl5k^5whHscg|omAn&BOvF@#W8qS5#}Wzz9@>iR*XAYGFo*92R1ays9>-_HIbkPuz*v^ zR#MSe6czS&|3|@s*vKwcv5jrejmz*4G#HMAGL9%o7UuDol6hk6Sb40W1-bAH-0~is zHw~I8F2R6>2*G*>unJqKV=0l4FGhx^;*byd7q@p$WsyXtVNbGY7OHh{Wae5{WLYDb zanSdglR2EYrIK&KlIamqlYxlw5ia|13@UdYH0e<^SAj+u7WTqE452a=$cv%`l>S9s z+c|-<_CEfgb4aN?d3S!b7+*ZnY6$Uk4PlC7fpw>rl?B)!TL)A=!Vo((Nvjs1t#%_h z(rS3eenr_l@*`d%;UV~Ej6oBZa)}mqNi}710A+%gmzZopQJ49X2S!s&fC&d;V2#pt zSKN4*|IH8@;K-O=fsVw!EegpZ>{N?(Z?6fGC5_DhwSu*G=vrw$q*6;l2b-o&2b$v5JNSZrhR3c zZh@R!p?xpOoTTG&GwE`zGXrQxfeq1=oyceib4gO-ohAjI<(a2Y<(3h1lt`%&=#^6g z;+|8Pb@CaXlPXC;B_#M+fTlJiKoy{QbT5(gX%NCwq$-v{z@Gu4cXgDYTC#Rv;-F!| zN(bNv$S7=7Qx+8(3J7tb3;_#vXFEU9mwNC@UL~SNQH@JLcvrz;-PnyQx|lAS9x$q= z|E@u;*1AwP+G2ZwV=qu+VE7A#zzORR4Bp@m!Qcq;b^xi+Wa-L!09krwp_-Q$87@Sn z!r3bKgr#M{Wm_hPw@DTqNqokKMfO@6&8KlDd94ZyLTu_5U;{c6#hi(Fo`5Eub{dJh zQ(a2Mr|JhjeTr*sX@cL$px7x&z=&N#wD# zbgRZlQ>T|@Noj!8Ysmwv2C;#>iV#CXH47#+VUep1k+cWkt1LnwK_L`(NvsH_KYoX- z8U`rbxN>7)4g3JD(aIImy08v`ga4|wZhJY|`dD~TV>hOwOWI?$&KN41sV2ySSyX8;bx%XDX3z zJGz$Bux;U{Bqy;Iby3iHI^!1=Hpg=YlU*sXU;Wib<=G)3Yf|nbYawfY^+$A9!c!>m zbOvZuxh4Osbk@@#=Cd;@}L(3KgF0L9ug%5Hla!zRtv@x z4nhqG0ksSvwFeMZEaDHsnqYUiwf4&taIgd>N|?)f4Bhwx&T4Hn=%Q&$x@-Hm2Asgs z61RvY9+#0Bh&w8WCwrWWz_76@7Mv2aIZqSUwqx<72oa`NRKchrx#*<8|0s+$rmF+U z38$(%I_^QIV^C7GE4!TtJq=+;Ok$`hF6>&UJ=DJzVezU2?xr@H1w zMnW(L&9JJQNL?k8B`Y&_Cli$ABdFjN#6qkP3X`5M)g{C`7DrNx|57PxWN~#-0}7#l z30diiq2P*CoOM{-Uf1KZT3j!y_<&Y&f$6C*y4rzeOn2w&pV5<(|G>s#v9wcT$HZ1N z`i#f+D+WQ(KrPtEvD3em0DfXi$P+ZcjQPrF!M3LC&=L(Eo3IHDB6^cdgx-NdpRz)% zA*HM=n~odNAIz_lOJ=xo7ojzAnfsBe9MT0l(K0O_v7CL}5=Myl0x$3e+~NsBAOxPk zEhd5%Fq4Tz9czB!#t)Oa)@&^@Ju6>9g?C`QN|68*4ME4$z)WPpj8`iZurL&fK&xhq*!`?Og{|0k z%-A9k1TIR+{12^`Xg`4v^z9HnWvZ%1YGEfmFl9eO z6AJGjzv~;|1#aMVNfcB=zO&lC9(b2^2?_Q4RSgc|uq5FGW_1w(gBiYZ%K$-`eYR*@ zz(^hzo?YUTJ^|E=xGsP#9cT#;OM7rBjmE?qfAF73qr z?bBqs>Y<#(Am!$s+&z8e>Yn9WeqTcQ1aL>Jc{#Q3+s+>NO8krmdQdcj{j_*_mqp{N0n(v#+3K(!>q`J8{P_>f;0bep z11jf@y3XOeE(4AU?hhT?P>J+Ko7@24yr&Jub>b5Ko7X03gD0o|6oA&$p8+FbpUmc4cQV)3ky#>{`EVoctEu}b$97IH9jBV zL9ccSBl_x&19RYwp~3V3Aw%Fmf&~o)#lR$QQm=JPok3anpyK^&YU;-yBu2dXws!kpGM74 zhmMA;UB8AMTlQ?&nTQ(Okz4m}-a9T4_2)^*aN@*05#^^zQ$rxloj(VniOqA2)PW)8 zmz`fjVA7#~ht5WO^z8?<8%3|3UokjA+`m8Y-aRPopyb~Vb48V-RPKQU3uBfof)Heq zGyq`)4p5MJ1|0`~vB#fz|B&&<8E@F5A;S#e2&EYH&NC{zV&c26L=)$0&qO$iDaIf6 zP7DGL1z9XA#Ow}WBZxcj2n7#VA_*lCJ$(F!A6SNr2oEKfR5B83ii8pth9WsKk|CK? z5|$!A^BTF_r-DIW~Z~t{L`#C~l59nxSc!Iu4?<&LUF7GfzD=0x7FK{{%Ep zK?lWCCYo$|Dp8&;6ACy-k4h@2rXo`G0478WYN$=H>a5ePG9e_Sbw)bCo&z4ED~VA+ zjYlnQz(|J-hS)h^pN7CGWD|xq38Wb}7FjEwYzABBiF(|*M;=0;Sw|Iy+M!I9TjVKg zPfxGK7TZns0gX^^|Gxz{TyZ<1tz2`2Ex5yuJ~nRIBdDt;%fE@CKzW< z{$-tgoaxw^Of-ZUW)98E&c^K8BN4uc?vt@Zh#6LKM(nu!=YXOQfF+bjzSQGNq>DV# zAw3)d)5#){!kV9dk{C~$BS&Y_ZVqahgT#QV;1 z_vV|VK11p|aKQ&B93?|*x=B&RFa0S~M;|W=Yk!uZbWw&bWt`DQH_f)QQbJ9FACb%f zR;^FuVF#Ba|H7e1tx*Ii?|^K;u$7^42q}dKsR&_9Eqy+@=74ML_#~cs^0A{ChK3bH z*I@)XATK>Tr@nfwJ|n7d?YHN?`-#p4KYSfBVaT6$&wm5BX5?j`UVpk9Sl{m^0`EG1 z845c&P4LwOV6?A0K#ORmofpAJVlg_PiRhCZ`@AO(s|bQ8pzsR_7AP2#_(d3kfQ(-3 zV;|M{#e__DvS6&E8o^Kn1>c~dC9p7N8%hrWFT%5l$*4u_nOKZg)S~=-$Y>$5lG7Xl zwx~%2OI8aTQi}8rSdfiKJsg`8#Y852ohePem_u>g!-hHd;wb(YM%^9)0~6qlAbRs& z8prh!|39hGjc>4c($$c45MolLD1ZC6yc26M0mEqbkYci58L6;u&JE^YV9A?fP^0&;v{}} z|7mIyS<(TXv{5B$?MqAo8<&vwQYV_NOjh(qGq9LNd9eWw!1#wT-W5iQz~F9lLZdL1 zil@H;ZmCa&YE*YM6U5cgjxWh0)Ux;MHko!E;VYhvl#1_bp z2Bsnvtw4q&f}w~)1Y;Dr_(ds3@rzs_BN)&4g*t+P3}=`u7&Lgp8vsE;L2MzR{|nX7 z0zuIb`bg{{534A4Sad^jn)9J7dT4y*3kqsbgCX_BZ+=g43Q~ylX+}CJO7Vcijn?-^ zJqlAyZ)8#_;=!ihIoNe_>ZWG8$rtZ?!zGLXMlo8%r~@%7W~!g0}fZE@`g#F#H*p1iXbyVNa~F>B$-g%Uk;!TdYn!Ra&1MhK9R^e=!FnxSqAxr zcYtv`;jA#w!eZia4^4u>9{E`1BA$TQ1Egcj3`xc;Yk8W;wz*TgtVxRHJZJ4~*3NE- zF=#^zFVZ>_H2ZVTHB}1{);t>ye z$lw62U5QtrY!30`x)=%6#bjk8E-$zHfp6tBYVGQN7dS=&#|B1p=;!wd2Zs6e(K&P5YPr;`{6KvNP)w7CB1j~Jk+Be zM8`9p5e#osqZ;TiAu=39_-Z`kgiC-!82DpPgr4C5f_Qa8VfKcKQ8yVf3MU9X%@1!N z!}QZAQj69RjB5O29|aX?8e+6}VdJ6L$G&~;iw%ig?1Eb+tw^=AV_=##7^YhSciF`4 zod1=Z>g;=y7mbl!xdYW7B2RkuVNzo4ci;OP*>_F)?QhGGhK~X_xTU_TsjyP7bh^+= zWDXDu6Kv%oiBZc#9`lLP5Z(XPONJQxz5ygalvp~=!ZV_H{{yJoGiD+V3X%kYDvnJ+ zwIW%)XVA2<>jetJpf~^mj#&i^N`oqjyYC1Xa$}f>;3&Q0J4xFi8uG!#$L~1>B7@APRSb#hbJULv$*f#x!l&;bVOUa3Z zYroCFzkFDPtVj%opq~Ac%E!1Ch(N`ybTd^v|A05h9QEtTvCKYMB&MeGtXgcBH;}ru z@x@fCZ2|04kY7l7vG& zfQ3Y$!-!5-w62I3IPJPOT=weNBvm|+KGpr9CG1Y`h(Vc4gCU>R>{O;mdZ3R%5s zSb{B>1wcRodlG~+fS@2)g*U*11Mq`cFiwg^fG3WzOU^JI}NzxL}LQN*%5CU0k&k|!)l116Ufz(JnI7a!0 zs^El9u+&D})J%m4ui{kp(~42-M3Decs07t(*}nn}iBVM5qeaC!$ev|zv6OY%H=qfe5O!)vkixQ^~DWC;fM{q)lP+(G+S*TcB(j{O7V4zGm_=RCGy^;x;=^_f}D!qif z7z6o*;0%H{n69S51A=XcVCVyl$h~OWn%uJzu4x)bcvv;0SUB_&Y5=N#@J@3R)Ip6& zsC$<~ecJRi+1>@-aamcG#gtBP6s53(g}qy5iD5>QkP3F}4L?2Rm? z1r4Tc+TaCW!iidQp~b3Y7h6CFc=-i4@KC`sy=oYSUq}W~m;+Vwglb@idZAJ0c%bcc z5yQ-gzH6X{NRhjB{||}Mp>Wz;${bg3Yc`B()FvL{u@ z1xNS=MM#BGKm|~E23y$NUq}T*IEKOVh9l7f&}E2&-H2k-5|e70Ac6!lgalxKSnPaV zEJ1`sXf|>92Vhv6juq68#ZcWP3PcUxv0T(Cw&Fk;-blqUP5_Rfpoz(m6pVmRqg2YB z2nwR0hf{&StN_J)=vi!$-l9EF?WN;F;@-)r&nwnraT#CQ=qzM1Uv`PWvBNYfzyVR9 zU*8&zRY(P2?bTVZ1yAsWF7=0AK!*KcWRsRV*tRE{5=f zUuaWmdlDH|PG-}CIz>*~W47iDsfk5|Wg~@M5C>SO-P`q8LVaQee3whuV=A`4b#~{{ z$l@_}S;+BXeq#!!xKtav9G$4KdT50@Fi^G7L~NPkB#7fWM(Aw89z4$DcXnu{>tosY z<3LWP2s9aQ7%d@?%i-vR51oZc7>=!-1qwO?QAmapLWXL%nINzTzH{Z+*+w5_h+EUB zhSD)9B7kfXa=(5A%=J;oY~eEjG^1sI~$5% znWC8yfe`}2tp)NB&=6c$o@EvpCl7gG7?CG}QsIZmg=u()eHgszdIocx24^r2e`unL zNd+5j2;Hl;p)m@xKI<~X17_Q=ZB~+QW?hfuFH-1(Ie>!UfNi?A>p|TPkfms%*z3|p z|HMT-Spr9JjSy^_jf$+&BciBh^m~Y-R7$aA>{88#rEHzY$i%4ZjDt=B?CtCk--^$k z96VZvfCI_|XYr^w?b^s5)kbI0a&3>DgX?%LGa)zfIv^h1JNm%K`gkq*WrF{ zhk*kTp@9|g>B3DynIYGIz>p?SJxObzCCCFYFv(5w2Yc8DbM&aADH2FH06Y*Wj1)c) z@nZE}?=rko`i5AKj08jw11QLEdEsxneiNDiaMjl97Jo&*7W6`=hy^FV2Cs?-2ac`6 zR7sui8$*fx;{hfZB@V~*4%ZCLzDl)NgrFtyP&aW$FXKiD3PVSA1AKAUNI+v?{|Fg} zVtBFL*uJptD8Xr64)Qw89|h7PUk@C`CWa91;@)Y8(T<ps|~^S&IOqmc0lJr+Cxh0fyiKLg0sbIG#)wXb(?< zrySLQc4ML?`Gj8R6L$!RZ-}WFic_zw!C!foUk#Xlh`vuI)<(Bl$C1J0eY8n5<&Y*u ztF$e#8DHmHY3J#rm*9kID5c*J=4OvPP}k-!_7WLGhOka@FSby4ngK$JAlhND8Tyi< z23UwT0Mk9Rm-BQ_ggVEPEAaz%H-w`YtvML~55d|#_pG9{{T%=Ze*zB>EdOZmAi{(S z7cy+<@FB#A5+_ouXz?P(j2eq1>F6>UFr8P;J|_h6E2)k2jawv7c*|`IFrCj3wKbi zZ22ZXD3BEpVptJ3!+*c<^wF`I{=R82_B`>cew4?taM< zJO%aWfkpp5{`~ssM}kFd>Oa)*M~!W`trVDgmE$XBT;mRCo8QYXwY%M527o9xq9l{Qr*Xv97H z{4>Ig3O%%=kRlW?(mT9SX^H%th$5!tX`)c42Z4GuY4-A?32OVgrU{Aqf&vO7v91z_ zakH=*#1e%B2L~K%fTBn+aKkVpw)9n=t+kQZMvc3qL^2_T6eq@3jrV{X2nxPR1JBUCj(NOOSHcnSyuOpVsKR+`wb z0T|^0#%oRkw%EvqMeP92It20zZ=mBB>-fh8y-|&6lm{Kb5Mecj;lKlU!x{fT20Ef8 zxbKXIJcm<{x*WGSP&h6=n7hwECYPVfS<77Ms{hbCcELGPbdExa2n8Zi*CA8EVs%!e zmWZ$>LG$FMHUiOJr08dv-1)-|?K>kHfi$GEq_K@|9NzJAmb{ykgn0=0$;LDSCGRaF z5S+lCKfu_K7bt}p-ZKg@GO>yAF|v_uDc||tFvmZ=v67Z#AN(@8n4%d(j5k^u8JjT& zPpBw2Purgm`Ui{x3h;mi3}7p%_DX{!5D07lf+j>m8ra+tmaYUFsWf4WU<88@uqnhU z*uaQiD1r^lnS>*95ez8AVHVItP8xtfglshu4xqU3Kua8? zxDOF6N5pOks9Z)21tdThx^`KJiSCL7BLAX@2v}6nLwb-`w@!D^E3z(&T121&Q3WPJ zD#VkOd4oWPamkHxR3yOjNJm2|QYFQ4l2FoPmKLHHj-iw$Jn-I8>QRrXR3s1~>rzsV z5{NaxL?D~UgdiL#)J8&*Dv~rQ#zv~tr6x&}PIbdD{^73!Sd>zo@kcX!F$W>cp_D8_ zC0Jo3HCF;~BC$Mx1GmPtTcYNG19U4bQxk_@#6ehB0Kye&1q9}h#uLA|t7#lDi@nAH zmoW6lc*?UIP#8{Mh66KHVXIvADvM4DR;Xo)tRdNDM1e6i-U@J*xKyBNCZS>J z5K}sxNJT1a34~b);xuz*)hwtZ9d8&84!|=r8{C%H)jX~7_TgHA^)ha5xx}tq8c)|TsphjRL zo6o$)mt@s4*q~XORXE}bX+Q@$yzvWf*aJBB;Kw|Efs0bu0u;9tEEE`li(#118;W=_ zwzFNFB_z}zncYPq2C*SLKv_NoF*h~dvFd-23(5%L&;ba#AP*5_bqk$xy#5nJD`r{C zq;g=F7px*Xhxs7^22-aKF1+P3SK$t4>co~IM>sQN&J@|pZ!azJJym2G`}p`W2%)k- zqsdBmIS6nx904m_+G8Ib zoX0-a5sYex5E=6@VKoRLSX_{&8Nk>_FjS%K!EYN6_lbm%{Q-<}GX(MbVmIXy(w_s6 zi^{q+=(sG8has!3-(i_|G!ii3dV$nbMxIX~t@|Uysr!4_$ z&CinaNmm+7=Knds&+!cXJ|W=>JV>hSRcZ1t5y(j{wRKL=YDlt)Bc{;gY;w@L(Yq3J>kU8BSPSNMM|$feG)037!?i8?;=Q zY!5+<+{z3Z6XaCLykGMHMMgkhdcg$sS>N^DjP{k`rG-iQah%XyO#2BR(RCpsCKvrN zilfL#fd36xm(9UJOr8H#9X~jss}0~mz{b~UqQ0zB0WqMKSxwgL(jb~2fGA!r0mC~$ z5L;zUi9C)9vW*W}3nak8Dfq{b*@r@y&TV*+Kgb~EHCYe78;1zt<#h;?*+vy5VILF& zhAkn$^+GC0f*ULtG~ob>P=O;zLN8E(H&THuJVQ0C1Ee&8BuIiCBm@=eP9x6ak1!la z&?7!NOwHUG7*1DCkf9)&p~kVHm^1{LyubmVNuX^BQ`lkiEn@U|OhGV#9&&>75FJt> z0TsYsK6a!fJ))wx0c0G2BvzIFX%$1HQjLjXcK{$Ks!}MjWNsWF0ivS6$x_y6jVMCU zKmSPBEG|%M_`@y6N3~>2Xzc{Fro@*@IwwpUXsNNGhQA+feRui%V+q* zPd*eA&cP(if+LKjB%qQT%)(g;0Trx*BsfAaOafcFr7cv0H(dfUwWC|YqeTsjMtLM) z0)`fDVPF=flI$ZI_G6r-1V9F)8QR&&NJPpQUsmXX6UYEkRYX5dBqhZeQn{Z$8m4Ft z4@f$O{au1dGELMugzT_LTu?R5mR#+CqDr}<=5JY&glDz zd2-b#I06oYBNU(rGE{>8oY!5Ll%HS>f(FIVfgu(6fW;6fh&oJZHimx%l1072CEO26Rz!id zsEfX+Y>pnL)MnMyS^_o1ZjQ!?EDLVnMg(C^Ze&|77ALyE0=OlolEoXi$e`&wCsYPy zi{ut{UfyNpK{G6i*HmL_gk=EI!7PNQaJa!FtmP`uK`PCGH?rma@R}zegEyRB7|{=z zl~IV+sYM8=o#tsu7-;QL97;5%IK2c(5E}CFKvO)$LVPGhWT=$*31>1yBLCi@o=$3z zjOb#NXi3UxC>0orT!ba^UyO!oD%FP9)S7SQW@s_X~e;+t^yQVlc)Ds(}3hNBQ@7>fMDB&qDnyFJq6KOj62!((R7I#KKwUM@o%EW(xq85ZOnK?RU3W<*-(0q9I_atZpf~(OI|RcA{lhwZ(==3r;rPM{1qdl11Ji;QB>yBrh9rWyoC|(bj_4$1 zL-(AX@$;bK>{LBXNUv=YJg4MvgB(xklwoN0Z_p&lq=wlDHR+5&!!R% z`~npe7%4SFDy#wy%mR3Jf(Pxxhd#})*`Fq}dtq(Uk5!7mKLY*|Y@ zB|?uO!uvkn<|xQJVNTn67P9hK=RA@AHkAMBYQ40^0sneUSBjDn$EYKaBSHKE;z|N@ zsH<=|f+l2@2YJKvwuU3Df)Mm=x{d1cM(8!Y}xNwj>07 zKtks<9)Yw7H6Wup31fl~X$#&59^8|US%`n20x0Ct)fBHS0q|4W*%3dp6OyIh(!nnn z#2kQFR%sv@2LtpvLk10lTb`>a3xVNA4V-q8od1e2FjH#f?)2pH=}~R2LjYuCO2l<7 z12HVxN_CV*N~}-+a$-aTV+?aKS2gUy08|M?5Z6zN5?B(O#Qr#hZ2B%Wzoa-FKrT^G zH)AnD>`OR5*4Wq$+`Jgv*pR9ehqI-DAnXksL@!^wv#@0l^ddvJM1n1(0xzOMFxas_ z8-hG7gc=+GB#@5!N*;kE$U-zoloBat`@v<6^R_||H_u{Pv6Z*_T^Tk*LU3YQrr0l7 zq3lGjI6Xr!;Hx)$9Bm8jOrz&7tbzvf511637 zO<~0JmEp#9LY|!w4J$WPH%3D&231?Nc>k}#8YBZhY_+7QX3Uy|Gl#WA$Y@z-or}hf zCuEgdbk*j*y7%&0AP@*KCL|2^>MHo3(Q8NYG_b7UE1%1t` z891;UgmDSk0VoIpasLztAk0D-q(byo!vSoN31x$SD8ero0@EHqE}(+D zaCkIDM=JPphXsQo5JZLt!>99NbkIsLqyoCcTZ*fAek4>7wK#sfc!1OO*nk35`hzcA zO3WTHrmXjBk6uHxW;oG!Ylx~%U&4%t5g8Rsm>+jqTzize#FRUChOVK>Fead89CluJ zb~_B1Yy0JD64D`t>!LZlm-ke#IiK;_3)qPMA$v&_n2MlULyR@Pq?(TVf^CR)6*uzM zl*R$tVnP(h0StP!89JiB7;hwas~|yK7RPUqF*U@otVaSeq=GH5YacKzDnNo6sDY+O zM?dqk9~c6Zjl3a50xkRkD*yPiB8Xdm=)rKv$c>A>GNig1*fBBL0x6UNtiyUK8~`Gu!ZK|--5`X>Pc|$t zlRt|BL8SN)9mEf%OMOrg=J5K_V_RJ--T^j#Y+z^N|9v!r6+|%mzW4$XyX@72Fz$kh zwZr{@R_>E)|9^r#mH$iEmzazgn#967rehk6`*}aX%Ke$seVWhv80bCy*ZaMnB=fuX z%2Hka7z98F5jc=wK_PSIH1qY(pT7gm`0)b<>;M}!Krm+1xN)N-XEJbHls)Pv^$P(5mZ!h)qIQLkX4)Euyt%1^LC z2NWUeqezjTlciEA74=ILs$X0c4I*mPXi>Ir-@=LnG!(UW|M)F^i)YDBzkhMU^f&P$ zkcj*WhXle#6R?KRvfyOPCp{hJhc}`plmY}q)`)(8fwOqIbs_q zx6DXHl>em@PaMr3(^#vNHP;$~jlWGf?bOpxK`qX>zeJ&%K7=dxH>E=UY|SVTmmk)d7(mu)qTtY}VNW9VBL-2raC3!VINd=9n>X zz~NEQazn@$>`3ek(u3wuaiJF3l_;^;XxvCg>~4%VqmlU0X(g6|Z_$D zmH$+%x$fHQuUpM-JM_kTjFVf@_71vP-CL$5Uk`wLQ!04)+U~pYE;iY{|1098X8~`J zlLx7_w!$$8A%>rQwr%5w#~(K_G~7TGkzCDA@?{Q#Qe2T;7D=pEquK18*Ij!%I;~6MhRw@U>H%ukE%*p zE2v)vQTa_+PT6Y-P{^&F<{)hDQ#PGZ52@$Jfc};@MtzYDY0)5RXz8Xaz2q@BbhxYt z1!0gk0S=IW&KZ@~j#EGdE|7u33EQi>Q?`cKDs2_)&U4GD`a5_UC6>1F6RyEXy6TTcpJX)&2Iq=+z(~21_$vYLJ~6EwU)6A zejH<4kaObWa4bb0155|qZ+-iMK!A73_hY`9qjN2HFnX9UqIq4C<#U(43WL-NwSV` z!OK$kVv~O5i)Q7sh;4Ls5{!t_j6i6NV}2I2p}p@PK}*#92%Dj9#4OPH3p*S@3%{7fD&D!y1GsY*zmNod>_AU@qC^t=q|JDi0iS3(gqQ^_ z;0}{DwZ8!oaBGkjF$!lm#8H!RV{qIPG5RO6jd4u4bw8R$?4I*?%t zHKc+nSUC%t7-0xMWb7?|5Xw-d_tm(>>~%#tjQDQi$&}uP4WaZCN=iAX#yqAOziA(B zU>VED+;5ht(O*OOhsz)8(x8Pktf_z*%)>60v8mcbGW@|1WipepYX9R@26aU%7BytE zmn+v}pm~yD^`@QjJSRJUF`3h%wuI_D$!b?|PD#YZSJdR}Kep4s^$=nljrHxY5Q;2? zE|j6oiWU(gYOM?@k%?o-=yRQ@s16OJikM@GWMmJ=qTIN)i!w*NV*zw0KWG1 zugPEu5DEKR9q+g~zeJ#NcpPLQLuV7$(avNmTiH%!P=mX2^8c>fc7W0TMxF<-!z`?f z<(90X%Cnel2~Tom79POMlL4sD+QSfj2=s065$6GVJ7hWEC%6I{E^&*yAcqpJ6Gl{S z;`~w3i$a&skvqw`(lsuYe2zso0x?T=bW=^Fbfw~5Yk5m)5%QK7U;HR*P2Bk2!%$-` z^JRwg z`>Ty-C7)m@@~+*qH6m**v58-5N{_Uf#kSELZd@z`rM;oAFL*&G8e-!c4|dM&cDJa0 zoWOU_o8Gc1@&q|?o+R(PQ`pqilbsw|;s_!bso+E@kpJ z1-O%YwH<-io8!Z&bAXnWV?5^>LD8BPhK{&g#x=3fEsrjuwW#P8kqAbUNvTCTeHfg9 zH;lZg5nRoyqfPHDBayD%CcR5)I-2?|JM*5O9ZE+zy!( z(_XNH3fWfO>kgdAJ05u*Cw6O+x4gTJ$txu9oAdi&GOaFNt8ju)HsSPl68*6bWc^)`$iw0Mw9-kqG>aInViM3$Vs=8GX8*}vp7^`@IDq_i8ItSym_?Lm;`XtR zWwgP$F1NlDqnO2Xtq3LCwa8-T`dyYVCPpaf^v)~I((z(v(j+cj-yMxQeCf-*H>HNs zmyWxp_p~TaN8`--;r?LZ9X11zfTF&rLJ$046*2)$a1AW_fT|b)D5${|kRic{O%Fgu z5ySuxegO(V?WW-F+2k%FYOe0=PB*9xG4c)t&#UiFYU=#KP-f%XW`pnyA~H^5#uCqP z7;iEd3i66?2!+YV;*AKA@VD;m$T+VF(E~sH?c!SE1;7cM*5ffgs|q~@ zsv)Z37xv*7MuDGZizQC$nU=vBssZ$Z5C7oUED4eD`1c{cz*F=4$6AgGSH`)8tQeY|4u6FA~~B zd+_1_l!AL`tu6eIM8x48PJz~VXBWuDAKHOToI#SnV!*Hm54bMoV;^PcDVHx0XgK&e%M&aKAZ64Yq z7|`J#RxPsp%N~kRPS2X+Q24M3B`ixH-OUaOBo9Y! z`T8)qDufU+B>JYW`V7(KsP7mmA^QA*i6$*E7(?1FW342SHZ0LLGQxB;5nh(E6N%1@ zWNO(0FcLz6CA8-xFpN$Z;v{0`{)ZuqEPWy3!F+Jfk5x!5t~26QVB}*1$4wOeI~jfbOwWUUN1XsK~@-^Zqe6 zQ_`6@;jf~sH<+vxB!(f@;r|!bp&F)vA^ssQ;nEp!OX5mM_gJX*PGaIp&kDIIA+3oZ zH;*=Xj3w`kHTMu&n$OQH1Y4wUTUa6|p=&3PA^Mo84dl}Y=+g&OYACt!5l`?E^Ajmw zuq~UCHW*{*u1zC?;0|D6GY&uzt8x`_XRLfCB2dC1l#?n0@cs}fEzQ#Gwo)_fLG~2R z8JuDDRzVR!CMnRtI9X3bpX3?#!6ElyjaI=Cg5Ywl3%l@w?us(fV5C29<1qG9?`Y&C z7$fH-)QTQcBTfwP(&aNk^IUKMa(eP4O4BsajaQV9-Mn*4xyA^8j7z~3ZnyaX9K!T%|$!5gNb82MuLaNqEjHNmaoV5~h~Yh%s1n+sJ~_2M+n^D9&NA9BH#mYn&#NuPuQn_* z{t6TbZ08Q}01vj3MZ{qj&eGK0f+{hyi*CwQI_njwAx=UeLD!-68Um@j0Ucn^8x+YK zlHnGDArcs(c+_E8^VAul~h=Ce~fwNf|L2W9{WEW;>wqg0i0DN!{*WrHcdPhRB8BAiw+Ue&Ac;AJ9$)DS@} z%Ti95BoZK@Wwr2HI3?x)!0-TyQ>pgB8J=Mspenzj zZ`A;)A)cZ2i_tXuQtXrh+MW>CMwW)atvsr5Zj;=-gD)0R%flZdg*fp#t(7D$XwHP{d9CT zG>u-O5+lg=Bd8%81dtj=Z7f596m|iT#CCqcwrdk%dp_#D1kftkLXT|q6wJ;jtdbNo zHZGxLVje?oC1%ysAujO?^s)nxR_!>|#2L^b3>i%kU&Lv3W81VbRC7bbOf?0C6#Pz* z<^*NEB5QNIiywT!#Xi^iD&ZtV*EBi7Y-A%~g?ESV!%M%Ehk=+sT1E40w}@{AYmE4U zg7|BQ7Y}XYc!h{?9988i>UpitW*J9Qt#^xkfM>Z_dq;I>z4vjKG7}v)Xy=76c;A=UXh9cL5q%PZ-EuGr zGL2v&l7V53Kmim`p_0KzFmx`Z2Bk=s7HDr{+ghZI7}u@37nFf+?;L{~%Xj?@mqg~r zTh{aXEHxrWw_5tuAO1CmA8(0$Svp)d34VE)>thKQHi?n>34bG*lbM*QhIm!CC7?JN z9%_ooL;5Pgd1a$!rT1pBmy0>|n|HQS{UMA=b&O?XbX=+u$0)r9qaw`ce9M;9=0a)} z5D)wpe(zTg4uBNJHWE$&6#@DF5?Mk+YFGW?9k3&j@9z}}*;X-h7rxeh^&k|oqyN=F z2QU6*d|=0>=uRY0TZBkMj9$c;j1^;0Qn`%T_5ZRfB03i|Wce}*F?6$u zUjt1$XhTb#IjDidhY?7qjhZ=Tw@jINshPT|E9j_G<>L~Sm-lebkn3f~;0mi)Qm=Rn zm}noCNQ=Rli@msu=~F%{fr%mlXR}xRKv*_PmAo7`rdF9%QRgCJS{yM{z+!c3-xosx zI}9U>B`DM(?$5Bb@&HajDY}+xm&ZYk0usuS6z-RI%5tCKf_8vaVZsF)rf!5<{=4p`SxxY9k?5BLNnu!BsG{7*bJrYIPUr zIFIR~D6SHZCu4WgaxK}yRw;Z*AOWmp0uJ(k250~jLLn6WrIPWaG1FNiG&6nNHLoid z0JZUqFGGZV4wW}?jNTPS-iuv;MhI>@H=q|aNt0hA@^_^ymp)1K3I~v9gpO$8|5xUs~ZQWbuz7Oizg3&J}*PO&zgyj!T-fcM7^z-y}y@) zFC$0fI%(6`6YV?C%h$9oG!p8$uLB$s4uE}6k!9KfB_M$sR&5`sp)7X+5l~_&rlb@P zJ;L9jEX^|Q*g`Ey;a1@y4~)daMSaviTqa1Ql3&NfPn>CCiqECa#kWgUS6ltyT79xj zNm*R#8iF6PnKyFUCwCi{18pC68MuwS%8|Rc@e$dX{Q!oT38y^Tr9H`-{W(}NK%Tg& zdmFoX0Qy#LyIVphy?T1%vkl7J%+DO0%bU?o%FVxc&e6Gq*DqCNWD##hDDV5e)8{}n zBUr7nuK_;52fS)Y?J6$=60+ei2poPDywvzFkCEasj6w}Gl>Zb0_$@l!R*`}&dVbw6(m0GEaeO6oq=VAD4ivyyh7^e+;Ol~Yu_IV%O*W`jGu*OP;a5&t zA}UVp0HT7yE!!;b7$_>A>_~0?q)_6OO)#|&0AFC7 zKUaN528H!KBDOVSQ!Ako0*%*aST}w>$gSmuvDA2bx&P^tJ>Co!_>p`G`_Uh%VCj`V zH;Ml@o?f_su&Sp%yT2Xl2@Q+OJ-pG~%(?gg#6E*fs?Ekt9Qc3RR4szhZEL1c3tz6u+4>foWo+FlWM>Iuio<2{hJ?}ue@mGj^MTgK*nRu>RjQP==a0E` z>)QQMsjWYMop|{D%cGOOef~DZRVX8|;>C(#9RGd{IkM!*lq*}lj5)LB&73=X=3Jym zlF_6~kN%80wd&QZTf2S@`*od7$y9RU#3Z-w-Mn{G=?y%%@ZrRZ8$XUbdGXlHn>&Aw zRfqKH)T>*+F1-js#@xFrUQ^p2u`z$ga9TF_*qAmt@7`@w=@{E%$J(&(nKr-v{0HJ6 zQ_0Ui0uD$ZQ#94LUxEtyFhfvSbyZb>0~*LwflS%NMpzmKafcXq_<=`=BH|GVH3Cwz z*8$YP!eS&ET?Gj>08+@*Q+rWUkwrR5q>&zpBvR2uJ!VA8Ic=4MB$99x^Hed#xCCXC zLBzx)O*UzQ6_yVQrBGL00>wszSSG~=PyawA#D-<&H&|P6 zN#{cSnrW6!ifN{rZpvwifXE=3fF0?t}=&Rtg=!EgQB*Ar_y-kErT9?W3=bz4{eOmjC}hXQ;B_8EqEt; z|IJt-fdW#9AhXuy*WguNAtd3nG)ilwRByH^6o+CQFye@jz+xhubgHOFB&UQjq#g;` z3rRLK?n{$EyTDQqBndqXLQ}{H-BczJXsUVGRR1}VOEVB)Evwdl2ehH!TZ8d~ET6&Jl^0>04C)sr zd+lRbqPEHa1Ea4_O?A~)b6TmTrCrT+*Is`e+oyZ^bK9zBpN)3f$$`yw+Xu`FcdWHO zo!A;{5JQ-*gc3qbdh01P^sw~JSKoa&UrS$E{LTcffz@6MIa&?UJk_)n8)zX^dgutL0SUks5nL}ML1Hu{!%@NkARH2tM6ty! zX$;Eo8*AKgl{4{#)MF)U+f|rP@uP`XEwc>sRo1J_In4*mplnt?AY|u)@v-IBo{tS( zS0&4+#23#IN25 zzq#aPFU05zUdOOp&Qha3f<^lO@Nx*q;#)~-Ky0= z5SjR?C`oD5@QOD#+0E`!U0DZW)Ml1rs3qQx^|u4~NpQxZPx;Je*8O-jS!4z4fl8>8 z{4&cv@bLjj+fbFYqA4nF9T`{R+95sAm0eHi<`Z>tP9k2#uj&j%PVz+)C%Pz#IYDfR zvuMRrX#a5+25U%UrGypWsl=Z&z-&qmAW+M2_5cM9E%GEZ(YTz}WYu#DL^Xu669t!`Dow%u88cLwEuh;`A7CNP2Z zGZvt=L1t=o@Pqm2xgL%#g|VX-i4jsFgpegCGbwdXK-}Sby$B-hJnZUxM37u3j3If@ zr)0BIB{8PNcrdO^5SVnj&nnNyZ48h_6*{vx`h-oYtz%GtVM8TjuT3ZP?fLBUEWdKg zEdNvv@U?ta$SkXLk@W-2mzfq*=Z-ng^saYhs9W76*n8jnPK}#s6CODSwa#}g_}cod z%00)b&;J1Q8!qt%L&29leL4Uy>-)>cFj~L%N!D;dDwz{nI?D7haDsN5KB6R8W^m16 z5Uxog3Ln72BQ`OrsUc2&1~JxH2?Z%UoLGg)`qqsF7(o)@2VWN(GBRoSN_KpJHA?0s zIZsHB*{Ect^km57dMHx9f{@H<`=UYNDnfQ^6`dH!m>-W5TFSZ~bOWvJA50{>yX;c& ztl==u<<7hj4tRv4S!;nWyx}V|n@l7l;B)2#!3_@i-5mas3a<{s9exR87{edFX#WPq z@A9i%()4k=TVep8o5&z+p+HyIf9ud>EG? zTkSYb9@c3>%$QIXd(i&$nYJDllp$obLMf9|&^dNn;cYI2c4@a^OmQD{2X6cTcL`Dn z!6jT*p=E5b7hNV8MspQ?XDfdVKs9ir5_xwf;7#?C6*J;$S#c1@rxT123}+Y&sgM(l@C&xk5Ty_ds}KyxFnxHC z3UPRbiog)IFbil{3a6k>UH}B3Ko~OtT0syQ<5wl(ay_7Me$0jy98-1UmUdV760ZYV zpx`|87i|nhWcMdBt``{B{m3*(0m6l2*JPz4gX<~sZa{j7m*sF2znSV za0m&PFbV`A4(RX;MsXBg$7AxRoAL)xHIWoi0h|$%JZPknU<4&lcYv%|lQT(BZX`29 zW`6?66-o9y)$=ji;#GKpgn*e7hN+5b#}vTzI>*qR=k^~FSc`T?fm3;bOmme_la}#W zQ(d_=@@b#-mUy%=mO%wxXBk2Fc{LTpmVow_a+!lS*bKfIPA7JsC4b9Soa(n~NXZl|L4K4-Oa^j@95a8|gA>phovF1)c3PcV;h#PFWnQ3Ngkpq0u=!>CD?s;O$0pKu0L zx6z;eNgSIxHL~Ic1NxS6X^nJgmrsEqVX>#10in316X52dOmv}wbS+FcWk554gG3(! z0;1N^AS4<@``DthhN7DZ36wc>_EK~Q@R+Of)sPFnKnqV438U}}ZCEj!$A-U<3U6?O_y203*x0IaYCSb*p!eztz5on0Io9SCv1%E!N~@0MAC04FMQNDqp)89-o=#|};f9!JC7xku zYc{v6tfNf<0t-WjYNxQ7G#W3pV^?kAM6I)$selZ9K#^`32|qd*$Pf(n5D9)@3#%}F zcd!MD&&w3FYrf)3LDK=XQk$Un`lYUl zLwuyQk-@du8LT6VPGV(x9cN%Uak_rRj{4ODIXY1~Rq1@axBIgQ;ou z$Ae7Bh1?nC0E2!;zjRr(3VO8|l~EuogdO+40Bl1SnqNF)#>IOT$TX~2(ZKbQY3Z{d zlzfi$kq4M{0D48iZ@Zbxx)2Bf38BC)0>L)0#!-HGtCpNO z{(M4?5Da}N2xWy3lkf{yfDl)J)3dM&xWJB+unNDh3Ri$afv^fb9SB|}g@yAh!)jo! zxSe@024av0tjx+g;-Z(yP6@Ft?D7t6s=?hPFLo6m0`beij4mOv)_9RJZ3Qus}L{|b@(hLUc547Cq9`r6Cd}0G|`kDwX1y!%Kz~c z93{t%R&MY?vH)Fr4m~z*p;BY87Gx6`d6K<~(Z?U{+^rJGg8bamP2HrLBCWa?C%xGk zvcGQUXyobAmb{KvaV_?d3bQ~6J`f1Ou+#}52=A)XSMUpya0Ner(`(=ZhK=8bjSy?_ z3xRM2{#^*iV4(ySZo>+}_LT!mFn$!A)mOdBt-RG0tPpd{iU$C|0`Ww^9L(v`)^w$X zII6gFs18fB7c*Qs&kzjGFo*2W3}-OZL;VYGkb^Nk3-gTwbCAvsw*x)?1`l@$Zppm- z;tAHc#2u@X+yBi>zq!!y+!Lma5U8EnX}8ZB(zULgs|8qPk>gPxmCy#_4`$r8Cwt|4 z;@dP5$7tL$Pa$0DNk2!^H(*xXbB;AOyU}!x=XqX?W24QAMI9c@>(a|A@ek;L4&HzcTX;Rk zz787f56O-W!yuPbaH?JK!`7I&Ztw=aprAb7tTC11QuoBnD3zu>IlIKj<5!^pwlPo-)ry# zlb#TU-3Gxh4M21ZgzyXWQQ%J4z?#+uIl$_%9^tb7;H<0%S6!o87$E9&FY==6y?)Mv z)rG>IO`>zlGa|L>&N!*tEx?ekLg3h*tK-c8XvXjcrvPlNtY1kHpz)(08_`X8q>uWkFI^pvQ6HZcAe3=w=4 z0t+#MA|p>DvEw4eto5K{S3qPVSWgYb(Ai|tOsjUeL_C*Ys(Eey_WchKI|L5AOWGKXwL4KMJOgzAbjYI%fK&Zcp88sdN($V8bkRd@@{CH6lFn|11t}F)1C7c66 zWX_~n)22*NDkoO*k6)$F- zu}BigktI)VT-owv%$YTB=G@uyXV9TVk0xDMe}(v&W)J zjXhO&o2Fp{t(rCI%EVt+e5^^%bQSSB6DI{5CeK^2UzG^`@+NN>cI8aJs{Eb9{E{|e z^5i+NzI}W4?&HJPv%dcQJfW!ZJ3w?c?SJ-xNH(dcfhCeqD8gew1{-vcL0G7fFv0^v zi3C9h#aJSwi%@FDmpK}0XpRs6F~*oT22ycF7F*oGE`vM~amHr&NeQEjEYgIHygL8d zXtj_u(F8SpE+Gwbiy85XrrOMLsO8*EX(5jw%3Uf*qE5Q!k}DrVZd+J77$oM!jMZRt{Jtke{w-&Nb!=v1XlWf(gc!XM)*h zo@!PJW)kLp8c(fH%{vbcnBJ2QK4s&J55GL>i&npPproj_|28eqKm;k$hFMNLYz?{5`8fdMHl<^cc3@wl<{7MYE+5G9EJY`2ACbk z^3h?{E&}o-g)!w1NhOywc4JKZ2}{b1s4OaE+tOrer~{zv^vhARqR3^T%G^rkzD%|m zH-FmX#}j)SlJms5?tFA;qKh{AXswC}bWqBWcKT_kqn3JVs)?TTY9QGF_0yv=#dc-c zJ_WhupvVgEr$CbXC74-$ar+lmmD@U)YPddTpLd>dCRCsZ3Fa80K5b*;C17$^S@;g0 z&%S8$3ni3OB-GiTf3(sRKnX9@!;gu`ok(2J$u*Z;2HVZ>jtw~kW}Ye}GXCi*E9NSF) zu&ksivP|YGH?U;`Q=_azJyWPQ{IdD|pJq5Iqk-eBvreI_)_;Hg`yXp*rb)(s10-Mp z4R}BV77A+%90@Qi!iE`W1uEsE%5Qp7wxDG2DnFS;Aad{%NBqJESNMT)(zb>lyaE}? z*vB!F@rzU(z#HCJOB-fUhvgIkD*JFo-9SaX!qw*h(rQ+F@IyrRJT7w7z}q{hF^@Kd z#cP`4N9HmT32GQ*h@fkb==4Ckb#YM)s1perP(rVs-3xYeLXlW(_eO#UOm_}}$m%v? zMvDx)K4LDs?#vskU(7KQkQxHU;rVrOJD|5 zn8PGy)fk91GXf(d5!?t;D5#c7@a=*w+u)e0Ih{b%ArQrB3Uh|B4|D`07p>?;uFye@ zRLo)x!$}2HaPf<2c;gxBBwXPpa>R+O$61YQ9OS@4jd#3bAJoVOEG!g?Vt6bgQvr}l zxV1ToU~xa00++ZDL@qFLkwIfj-ALy5p)`tUjk4Pd9N`EfSk6%{5fP+DT=`5r+Oc?I zY1kk+G^Ew|fGa5x&@nJ!9wa!@dR5|NS=NvWTRj6EOY#3fCD8GUYAj_qzgWd2D6$4g zunky0S;gDhwgyn)=94N(30Ov%CW?eLE1*iNrHY!$vaAv{Lb6sY?RP&r6;rQ!<*Qzl z=F6t_Rj`94Y+()imt(F*M-D`dm~>h`!4(yi(|lP|rn;&R3hNk89R^pDQLA6<4Jd&~ zsyc|33F1s5s5vMcd)|}JZ$-;njnf08G-e?R<$elO zM>29#OqG(WCc%kyI0G5$U@9``W{^_+q7GMJj#d9%6^P?ZViw1#>J=RPgRqRR67xOl zmcoY{mx;AxaNW`>13A~dtwwDu$R6}af@C2Vi@-?v1Mc!NpcDto{TDw zbAan{4Jcdz9Nq+1y)lRZ4vV{wM%YuI$K7_I*+39)dF$IY z?btw};B9gDQ!Q<+lFoLfgoEef`JYJRf3(*c!xi#@d}D;^8mxS z>Mz!CfDVr8gL{eQS~z?%o=lJ`^u0CAw37cCSN5kF^^?;-f)-)2jCY z?w#-53Vh#@NSS}Aae!=4L-M>OcyD$*m5e$!&Jb_l>Oe}}JCl?#82=ZYV&pox96-G# zKQGu877~(|QIFUL!Wp55Vfam2=0eQ@rf(jcNlaoDIIM&{oZ*dqc?~cWF)H`WbLYq(5nvUz-0Rv(i#b^$5kc+YXF$}fmU;l?GdjR+U ze*g@?zM7P_^M~0hBW(kMw>yowi>A9HKMQ-G1K5qVFftxnGOHt&!gIGEG9rz*k1V^q zdjmK!+dP3gfaA&>Sbzl+bdUf2_&hK92Wnur(VH_^sxy&FJ?pXz*7FzKnYdZfqVJ-q zPI)^<0|}Em4UjV*Oi7uP0lu55JW8`PBsc($>5@^p0#=xXRiKDmcm{jehiAxziD-j; z@CN@v1_)cVUr4^K-@aAf~C1Q#Qd2=hdjIfW15GY zNQ$gTJTab<=n&etmQ1v^2jWDm84E43!}I&3-~v1*vyC4Tst)|X-ijQ&!7YQLh+Fis z#0iBJEWuthL5Yf_@{tg3SuQbxE*h&GWu!PAv^dXj#uf>fx!AacSgF-PwAw2)KWe1} zloX8Ul*`!^?1>Fqd!MtY6HH*mD_jYApf9-D$F*@AWSECexRQU6hhG?mROmvAh&7E! z8?m6Ix4IIp5Rd>a%7)rCgJcZ&s}le*h+DEq$b7bl9F)kcOv}8?z`#i3NhZU@ z#E-PZ1Dr9D3=SZ}!>IVAbknKzBRt|`t=E#b+FBw-8Z*jUJf1uNGTR7V)XB)(JmXrK z38|2UD;;7aO4SjuqkNszdjq8m4W?`n+#wjLG`X>;sod*`AyGNiz#i-oNW+v0LW9CI zF^ZV;hf2G&oT&z9z_0_G2nTz$TtEkZaE56B1*Lc@S_y`X_ytGM!lP3ayc|t(6VEFd ziq8B_s_>)C5JZU36tKfg2tBMubi@d)Pz$xl&9uY=Z7AQ9y^gH5j!4W>`ODzQBohUd zRHVRSAwK`~5QEr~mJnoFJS}1 zkz!6hdCnElxM<{^^5O`;0I}3qrKVb_?p%oj1<#duLO;|Jmoh)Gc%HIbqzq99b{ur*<~ax@lM*oW9qiX5Agaoh)^ z7zzRLTEXZw44gWFg`O$0*r`y^!vIks(UeG?Sh?Mw32nByy<5Buri%RbnLGdS z$v}bq6r(WFva~{0eN~On32ym|6XaDUdRYQFfSBDpGOO8}y+wC1P8&p4pN$^Q{n*&d+n2KXmTa{o`!^qfbJj8{~TkeILhlSYg4PWt%noj*x-t*hP zB~i_qiV0K-<<-E6VAVFDyc|u5lo>O@@UmUa4_NTYJaWQ`s9gQcgI>+t%@YG8h!i~H z*^pA!#30?eINj8}pJAxrWXOaH&fp5RzX_g`x^P`*d{&Nw2->x&N%=>xh^GIiz?8^J zKTjFVe!Ml@h(GfjUPv+%QQC>_saNu-8M1Av%0b&NwU+dgh?DTtm0;WV6V+;*6VjcF zVTjxDo#I8QTfm}XEY4y^+0g1G9@|APUXzr8m6`=oUu4Zc%4Fol` zumIz~U9vHrz_k$E7Dil0f&*F54PzUqmIaJ5voZo^qJ#uSuQ_J41#AG!$PxkyeS7-fmL-R&6_-QASaG~Tpg zWeM_S^|hHxA=QhX&*qDfW&P{gSw?2MnvdWe&1yX=p!F9G(eU`GI zGMPdCXAnV3&;{DOAm~~;=!9-)xt?pfreuijWQ-HxyDGFWZjJvV%@4;c}1sy-~8-+t?t%Zoy~1$XqEi50@T9 z&wU+%){7lD0MjMf1E^p}j_bP4Ztb4yMiw!HxCD%I%GWd6I#P{4l)y>iUD@Dh+-M)J z@aUZo=~4~Xpc7u|xnYB#naR$c{g&^M#=1fNh>36>0>P2t86Kpbv1Bp`)uWw%apu;J zaLfSeUy^VOH*MHXaM>=vl`uf^U}g9=mfX&U-S&sxR=oegxWx#0)bdp`I8O0fOzzCu zI}`1h`TJSu-hnr`gaa@Jim2d6UTDMEZX%y#yr>hrHmT?&Z=wiQzqV}kUKx&F3#~Bh ze}$`^NJ#Unx!6bv{q_{_+1MYRfhr6nD*YpmOjwmLa3e0^FHWoiWN@~ohzBq23%_&3 zpzue;b3X6$4acLb-O{?-h#VO45vL)kjMP@`YR~r5_S*&DNI@?K zWC;R|$ZbqWC;@>cWSKG)4-Cb-MJ$?^19)_91P-Cz#wgdICyQZdB1W*YPNZuw`P|oiXfH>>9L76DEIQLp*BE* zDO+@zefR#*l&|beupzFMH9;9qC8!v@O33sd`1fWI5MmgEH!uPR|MX85vFdhYLrHkL zK6NCABTzQlFwb}n(_sqoWh*aUz__)Lw{QO^`J^)0Z>e}kvMu(^d>CXOaL)cXK2q?7 znTs9NGarQTouB-T&~wVa{L6H6#9}*?2=wqO25_$lH~AY*+>>w zRIst4vH0U97z4OkO|9p8gZO$L=zSh|ffe~=qP3;RTokqEZiaXGr%VVOa0@dO_F>0$ z?&%b_8jJTPld+xqTxaZ|5_Z7vWnw3M(?A}o+>wjcw$A2!$Deb-kak4Ge9FIe|AT+} zcgTOp@V+2GK(Cxl0eygg11AVUfyIjXpNZk;5Xyo<4iFId(wdu`xe>v>DUPpFd(_ zctDK`^~D=w#+dpW=Ee=pu3o=_4ck=**|KKOqD^}?QzooTFYSmccW&HEZap2%i*(<~ zN*aFx{z-Q>w9^5hK@|Vg0SOg#R8mVd^^{amjlsz>SPi2Udd#VnqKav?D`op<7yr=H3cL0xu#YPYAL zgA!V(p@$-xD0wL{gdCb`!lx2H#eg!9K?o_7pC)Xu7sMTS_<;w24t^vOKP8z26D$d? z^im|D2A=6sA(%Qt73~-y*SqkFGSS| zQ+%~?;}1C!6`5o_5_$h5hHX$bWRZwxg~;KiiU)E zXpYGmFlWZbh9T#r&N{vGPEEq{12k6|=OEJwfoUA#~S}TROVyLT9y?Q8B zu*3{&Su$%ND}&ZDxDfJ1&4Rs_i*M{O?XNso>(4&>*mz?ln+cUsU^JDBQ6=rx&65vE z(v;ASm886+aPO82kzd5_gGrT}VQIK$hkZF7!0c_h5T|J(oDx$Dhu3gjZq4bn=%bTf z`gRy+oSo^bv)=!@>#q|UDI3DIcXFhYQVItsE-$p{<()3^Y0bkMhqFf_QIpN99>GG5 zJuXr6>dgYqD&d4nS8`0s8Md)Zjvf9w#xl#ST`bmHqrbK3VY9Epv;J^$Hi*R5sO{S) zwX1jDbcf4--ahfoZYMd$-P({crrhl~gbSD9j=>MhuniOU>dW3dVZgQG1lWq8+ zIk%vSJf7P@oQ4rP*r70mD(qOFQm3&M!Z3z1oM8+j)hMyFCqK8F)b4nfpZ!eEQ(^$s z@QOIISQ#%QF#(B4fVQBYC5L)Qv)=VW6O`>0r47yap0A`PBCI5X6In|i8MW56^|fzB zMc@Rnn9~0V`9URZ`^b=9?x&Fa4X%H36AWMi_#{@jMQ}`dR~3~Mr8(B?N{p%CsZyp8 zl6fbCl7tj|K!_D%oX2yQxC&EFNW)KpGL+##oeKjc%2T2;m8zuEB_ah$ujKGO@KKpR zT=v7?1@R7I(1Q_sdBg@8&u2^gNGM?ODxZO*cmaaY0jSs`rtu?--m^>>fh8n-oWiRMg*O+Hj3iNt26Fo7&o}c0O(*6@4)H zW*WuGO-@9~ALl$FdKzliOFR^!!0{+w`wGJrV)QzG9V}rB%euIr3?s5}h%9%w5dGj%l0gU_ODkJ5 zub9dtG%Xb@hS?DU$s|D2vk5b|+S8xnYMS5!*7%BgHEkv}w%v4H*oq+AO@MH!znT$- z*2$T&nl_&NswY^(DyhEgGc0EHfs*XWk`1=?k#LP`4u_%cD2(3~vpp=0qortg0cbBIkdEBcMOJ z^wpIZ*Rg&}ZdaB&8X!P7K?6mJbdN*b>hhx^x!L4Ju$x^v>9v#TT{4peMP3&+Im%L= z@^T#JO3XFZkpr7=n8XwtArdjaViuLDUa}99SVSQ(5%BRkYhWlMn6wJ^)@gzIwqb#f zs8&1HML?Y4J~1_He%{&|k`YziN+oR%Y}<){Th{(9urLQWM%;=U<5_wTOEmxHDdA>- zgfSh6RXpx7?S4!fH8CYOzQJo$jht#bB^hE=o;9tx1K7Y;r`EdOb*<+T(tlK>Q7YLo zmt&*YFYA(*V_vqY5>^sSvxFJ|4#j|-li;0#tIqzQ^gi%>fHCOVsB56fptsqlGolfk z<1BYMdxdCV(T~wb;Z`(L%*S`Nfh7k3wn;pA>9CGEfi>>ujWsB0lsNLOI5aip*7OG5 zaQ9)Z#w4s8R>JS{I^!CL%#)$K@sESNuW-7^KTbM1jmSo&%U-!i{+-VtSLBIsZqBv6 zVntqE3C~UuANkhyTCtRSwzLJOS=P<&Hg+O@zmg+AvV|kK*?YNrvuFQB)Z=o;4zLY) zgy#Yae$X5zNKy*#3d0+IDuvNRlM-(ztLqeNjE6k#Aip)PGb;DH;~kVc=q@J{b}E9+ zW~9ir$jX=9yoI`4A)!{tOP^EofioEAh2df+s8+rU3&+pid>zr#V)Q|8qTNzedZMqz zwyWar(aS|^kgs0SAPI@i?~2@y53u8~J92hpXSjPVsok!;sUnwHyF>5v_Pis1;~h_3 z@|*Ac)p1hQoK#3;cc0SW(WLN|H5KArFSL=+93-WMJYa&tE0#2+@?hk%abml96n5V8 zLDw25Hi2}~#}O+g{(&8vu6nb^P1SiHOT?b+^+@C#8%kLO*g5~w4vk&eF_!NU2VGnQ z-yIpA9N+V4;FK+2#%$mRf}q5xnq0hr{uPwq0f7)5fFF2;_VrTBxn5We4XlLUO~ApN zk>5|4Uy1DuF{q!oEk_w`7`mxY{Gr9?v77yw6aMi4Z$*<)97X?a+E+*&M1+vP#o#{_ z;E)g;X?#UoE#N(+Oi8^G1a=T^T*B`Ohg{Ia@PUvTo`}VHR|wMKdC?uN)nOj$q1*XJ ziJhQDq=pdbfmpcU@W5ae-VXRNhxoxk(%4*JXdTY2MEdcT`HY)#lo6nTk`bE4hs~c1 z)ZhJ;-eu&46#m}=)zg8*AdCed*EI|`;F`6kBM-@(;DqK&i7s}|4t&K`4$4?6Sy+PR3Q=T5hGuCJqvu@3&S;}@;1^n6n$Q?iD74gQ zafBEw!5HvU`3VKpfeHreDqY_$%(ka^M{lFOH(-f*?k0_0E8Kq)q zNxtyQPk0)4nA!%Bq1mNcLsF$?E@ayQBa8^6X{x8|jHc?W=X*Zin^1ulctJk>LnI7h za#)sYz8>^M0)F}uaeTzAhy^58+GezxC7So@XEK6@1F5*LY=l&FGDW99_)k9o#`5 z^g$$8h6gF4acmzfye9O-X3Z#DfC5unPLXoy=7p?8g8tlsZjCsZ*Ms(D`iP!#UW-*( z=+?Otgj=TCGMV?1Vf{FuSqjxnTRo>XOv7D_O3lC0tAo^DKgVh5iBDy_xE zj`k>z8frGYLt(6@aBSa5w4Qocgsb4^eJvYg+{BYYsZRujzENpR;^md1V|qR40c`2k z=;S|~6VtU#|A}dC&JDO^gcgzukx2grQl1rQuts^@VwO3Ziy9w`YQ)2dr$eGAL63HcGgQtsvb}(xDroII4QYiDo{{bsFB3_ zc`9&rQ#wYOyT0p|irzUnAwL*}y<#X>^hCDxh$gfFC@dh!%vB^&m+hnk!XCiG_-e&% z=8H6JZ}?&-4Wq?sZFx+rDQ*Al*P>F!Vr(C*%1JD03$7GsB?2ty0WX!T$uj8yjB7Kw zYK64yfmj60sw?`iYpvPj`@yRW;1*WQYasDoVMYh763#5X(!tD*eryN9!iSuyVO1cc zo+#`^kPy{YEnTE1*n+NkC~GN&Zt2R9*k&xE-o~|}?F+_)9wdTn!tJu9tZA6*xhmev zDrj@8Ysl?opOtFPq77D@p3f%kE3QW42JG0a$I@om2rgvt0pmx(30&N1vBs$BYOi;6 zt=Dev_mU3kVr(SbQwV83g^xCrB1@n@Lt9k zC{lAQu4))?SGe}t z3JGJZ>N4I%q%bwG?@Ap&3)jpG%Z9&Dp{8Dgb@5wN{pS73fH>*!-PvqKz-!KO!nL%R za}LmQBqb1dSrXF(8<>fAj?4mwh4V&=(^|w7(}V=S1qNPm^;U!@OK&D&?`N8ED(}Vz z+np-AGM=EZv_}6zHe{N$E-B66r!nCd;SpZ@(lL9GC>H`n9#@@p)i3+)?H}hM4`W0j zBi$IZ(N9|FDSC-gGNndHGQv5aC1=Fao@mn!>jCrz6@N0ZhBBOJ@dd`=DR1yAyK`5t z@;l3OdBpM^%um}w#TC>3gC=_gCueafkHL zdRNxY^DB=r8Rv9QM+XVt^Ui29} z0e;IR*PiWZ^S|{@N2c}j+Vx7ebxT+Ac3p8*T-Qv`wK>Dd!}|3*?=_HGMD#s;=v zrx~!FENfPl7~H`UlwHB#9Hd5eAFC@MgXQmP#6%+a+1% zb2tCAIYM`7+9bIJZyOOW<6wzr<10Wi+-P4K$^8RsyjLcZcSg=d1Zy!Dr#E`~>P&Aj z=E8S7-}heEoqMkMi)*ZY@3$C^A?rE^@f>$@)5bw2mP;OZ5I(emuVW8mc7!%mOEiXb z`q(X6c#rR!aV7A0ZwE`CcWbYxO&8fri+Emnu5G`#8PoR*eYt%9_Kb_6kV=QB2spuJ z4tyMd3DtpgDD$3Pc9DM~MY{!(E4dR>*9IkYr2M(-tu-^6cLhQ%C|fO&nfR8Qa*F5m zn1e4Xw=$&bwVAg{F&Gmqn=N$YxQ+usLOtc1Z$()Ud2-Bopw_va2c2f~-~d&#b1?s$ zpPQ+m&*_M>VH=`1Z95EITT+MHy2IqDR#G~Pw>ZTP`#jHhHc$g9L_)OsD36LGKiK$j zhyfs)_ARQ(zFmY?s70w0$Eh=Gs;m0ZfskSNM4K)L!~J0l4m!gW`b8Z2i&n3Z`TDPa z&KDnh7>Bu-=esJiin9Nwp+@WYa;*6hhjF9e6KDG#i#oF$hqpuQkbA{MA2~~SHDprP z4bghNCnN-GM7(z{d0HR{xi_NMHoo_}2upg(r}9bwd?eH}kCJVx96V@Gl5J=^zj1rm z3`c^4t;A1!Ul!Wg>E8h*1T;zq@0E3owR;A?yG4M!6=$v+UXr0Cx|g$j2e1Ep)^~6@ zC=blXeCj4D z`4gzgm@#SA%#HKWMUr&&`W0;0Bw5LpHG39qTD5E0 zw*7erZd|!@>DGjJS8~_J>q> za^=gJH+TMADp#@7#X`4!9eZ}|+i}+Q{(UYiy#J^LSpo$}(~$oX3m?|}9)4o(^XWs4 zubDH;(ECSgHi!^5ksJc1D%Lvs=(X71$jzlojA@Rz9WF91IOcw+inO5(;oYsSNZeK?QG>_iNY4K`r@NKcUVXKU&lmlqf~bU| z#EDZw5k>4GNFDnXTC@$Wy%*nnn=4UQ>h%2=;D9d*wyt3#G{#td2waH`PIJPozB9*0ig^SSLFX4?>B9))3H=#8xz8UA7b;`BhuypEL zvLn(GWma+H&}ORbzB^x@d-e+NzWu(AV1tjwE#3cyl%}ZZ9-oF`6e zJ%%!5lfn*_?WE#1>1^9j)otxF-7e{pc4wYj*2i6cJx_l31`GDuZ9i*I!3RG$;e`|T zQL&}&yPfJFo8mfCO*5~^Q+lJ6xaZPrtj=?<_V?zycf z(_72j5N5CZT@Zu9ksbQ@mO&4yuV6-l-w1b*t^n1KSy5@s2Y>dgs%Wb;P+Hgl0vI6d zQ6+j8A(P7>R6SQ+?||%bAgPSQL+TaFf-L`3;u6WSK@Ktzihh%epGa6ml+*-x!FwUa zqL{PAWCe!F6A3VC7^)!RFo$aUk_0W2z#lHKha;p7Os?pqnw+sM;j3F0`Pj#uagcU? z6r{lJK*cJKu#W!7qWuQR!W3d=S~1iV8xADEvv6r86+}o%;`lk^-0+B1G)4vO=p{Vn zaVR@XVk24EN?e_9cCM7=tqzIEQ6|Jki<{*xpAtqxeM=+G17%s#DK$$vPKcIsra6rW3kh3lwCof*9%`c$LD;ipMDiqv`{ag{oi>dy>%(5YTEEr%2*E^n$utm-t9*F)PO z;rXPdIyEcy6lpUrgQk2o)j6z->R0Isu&VZ}u6Z3G{I;sdMLtrmGqoH(+p5(A3{{$; zyQEr=s?zN-)t_j6>PlM|Sj$2Srs%uuW`Q!eH`H+$f8`=)a~jr>lC+Ao@lv49idxmZ zk*x@f37JwF&BV5ijw~hZZfE~>S6%TIxD`<lm$;|ssq+L5*Db!^$Bi`x=9sG}Mhif$3y;Sc$C zP9DB$LJm;e1B;lV$u;6~NoZSt!nd%?j9KZjv*9BCv&KZRZ_QBLWA6NSZ$5UZiG_S# zNTnB<`Q__-YdhUmRoHY`N|RV~OxgVw8Ow13q|dT^PMmgGu#j@Ya~r(7vdYs;iXE$r z*ScZ`dT%$9jj?`t3}*j3CkMnKzVj{tyXP=33dwSoidIW`Lp87YwQY8D+tilKDi;Ty zd-U_9(E?qr;=mX4GJ4O}soK<3!?QR;@X36u3VqI%n zLkqn?EVJ7r^wC2X6=qO=bIexF>K#k^*2#9ttm&j|XFnTGVqUOvlbXg*TiaE|{xq9W zU1fP`yE3!oFto`X6iZ*a-04;~eR9pN?i3QeTk^+?L1i} zAW`LPod==MeS=s%zMK++!fw+_3ys4l%! zlic#Zmk?1N7zGT|H13{pLJhRCJupNjKukN&1X zPwVlYzsvun?|rI}PZl?R^7SlsYeSFO{;23!_OC`irJeu${r_LY04@0PE#VG8lN^om zF68?VPL9e1pl&OU!f*BfFw6Sy_9zeo!)sB-Z09DdfC|n2s^a|yaKd&cI3Tcx93<%Y zEd!g+0#T#|W01Ghj{tS;++P2#-*&1kl}nZg3>x z%&sQ{lW&c&2yO2I?NARBY6EF53Y~(4ZY;vqCjQ*7dZ-Y)=%~pctCR|n;ewC__t3|R zu!H|3(Gtx`3El7w9c%@i>q{KbDn@V#SBAE5;s$dp2s1(dF0l(Ku`5^+7WvFbkPOC@ zEJD7=6Kw(%(P#?sZcBdc6j6~qwlEgC%N1X-7?aVDGEoz&um?|S5EE+`rSP@VE(O^r z7;8)g>rffH5D$&88^ckF7R3)~>R=cVv8E9!5(p8)t{w|LW4{I2RQ5;Fj3!Cj8 z_c4E%@eh^anM`6wUQ8YLsuxEwt_rWYO6ea%aULU)AH(Yy(?^ zs1_5k8hsHvN+PA=k^2<#u+)X0vMmA6olww0o|5lWM=GhV4gE5! zfYL5^Ya%J~Fc|9eRqY^sR4kd^)t@;Trn-ifD(>uenNXF17CkWmOurL2r(=y8w zGlx?|<}o6&Qap2NHvMlt?=w3{Q!|?`HCGQ+ShF>?Gpz&^KcNUb3lu@0gFM+Y-#~{z zsnI&~@@0mTFcVbS4%9+3)HW`q9NSZeeDgOY1VFRLJvG$p>eD_=R7KN*G#|7n2&hE; z6EGR{;jZsJD?-y&bf7R)M|+ek7W9tf5p)(YL{IHHy^T7bgGhZep-@!um=sF+2S~`! zMVSIdle9W{0{%b*I3);1qtw|FQ!&AmOqC)?I@Cku&FcR1NFOdeDMGEVLlw*PJC$=e z=@d^{0!YP99uqD*J%nYpluJd_Cz^01DIybcG*4xdM;Fymw`NM)^yB~fQ$6KMLML>N zKaznZmGSBg(=9ONL(_RmQUl~4ORb5P4t)pHKpk)75R*;%C4}BItfy7j4 zwlY};v9Qz`H_Tvdv4ob?P;jS2yQ#KHcJ&v=kOLg5^srBLiqMFF1IBz zS92MbXB`%F`{;9LmoZuPX2%l$OqU@gSGZ=@cR|iL`YB*7R&x<%aNE{)FX(XZba}n9 zYrVE+aRX|r>%QuiCsemLXlt4-!gXI4cG>oMwJBovb$tJ!H$JEobyGe9zZF%a?!AH$Fz!3?;603+;V*Q6{ukIoOh62jhFWV~3LWe+{&D zCwL{JH%PIUdauxcIW~3W*Ev{s-*Q)H>z8K<*MdI?Wm7hV#Sw$ecGs-UeF2qlj#We$ z7=%OEg!i|FRd|Jam>)}3fuT;R5_YwM*K@dJi0AjlkT@vvmu;07h>7Qir`Uzl_kq6_ zK08=xCu|2nqzx3OA*7C+_=&qWiq$xS zn%8;xI1Jesk3B1nCj^gWcD8I-MF{nP)gphbR*L@t`K8L&d?ncq??ZrfS41T&jpq1h z=?sSL?U0`sip|)P%O{Ob84TIDk&`&l)G&wArIr8kX><5Y3~-jwf{afXg;kk+{1{h# zc?hxCmXpdQI(d}IhG~nLUfxkfc6pD5d3{n@np-eFiWZ3ra8w{DnUz@)nR#YVXGO?3 ziX*w2`=(LP83SLKgx7B(*fm?-RYROPMWES~)wyTKc2=8F1Hhq)EDCyScOIIi>%-gqM36rXPpde%hL48l3s_opCxRgmpiO zRtTQlx1Erl!E}|EC znNd?k{`7a_v^j>CrO#TS=@PHe&!IzkQcv!rx7x3>^{b!5t{G{s(OGX2d!66os%ebM$$`O3Z|x+xADp+7rlxB|8T zu&?RXKaEMU&r|tOyX}gvp`wYkTbrjhd$x;PjftAK8`OJ}+rp@_jVbT?=4K&-Tezo* zxQ!dTTNt@3yEcnr{XW@h9W;_95 zqRC+PpXt!UN3Oivm&Xme#!DQ>mt0&gd`$@l9#6MY!;io%L+XMeA^7_#ifF=_+{>HX zs#RP!V~-*X1<3uA%5yu6yZ3Qnm!q`YDOCD6zU<5E{8QhX=GNLAch-CB56%g;!^N8| z*4%^(_|L1`C~Vx$7hPAw9LE0}{EaUnYJ2k0w=K=*gL_NK&_9IB6`j#P9ZVft%p2TH z+?<0YvrjLbKIELu`~1+GB8)Q{szIIBRaDd~-86UiCpviEAQ8h|)#8yS+efeaJsN^6VF`xsS{R-EwcN z(6ju8ll-;49p0G}+|ixvikL8y*U`g0*L}RXaQ4^j+ucKbR7uM)+KIyl=@xb#{~%ghjSp$+_O`@6qeeUN7m$ z-NXdw5l*$LUTq(!=o9_u-yZOjF~zgE22TyXv`_Bc(!R)^C8ArKSH0v-KJX{Mp)+I0 zaeCY(!tNQrar0i{sUkx%Uu{dC@=Je>GlS=CI%f1<9#xC;rKhQnS54Gg@=f3N&oAy@ zf18iGO}5yg`~6E|fAq6n>u=xqtC}(38{pmgT<#w42}Ac&Q}hEj@{iy8k1+RJ=amNmgAVZ2gc*&nhlbLj=T&ZKE z%a<@?%A85Frp=o;bL!m5v!~CWK!XY$O0=laqezn~UCOknQ=BZLsvP$3B*mvQJ$@u; ztRmK$5e;7bI(>YiuRLs(@?*6J z%%Tok&>#P5$G8BWKw!TUY7RcPGfLU8lPh1&yt(t|(4$MAPW^yvm2MFG8#tOVLC2?e zypi17cI8U~4|rcZT=QMy{y>MWPQSkW`}p(g-_O6l-|ITic9MC6;f5Y}rt!8KcTI2Ddm(@R%zvxL0#ttRkfAooiT}- zb|PyWAt@e^2eg=%lZ9dF=9_TFDd(JY?)M>LMFOT7dSTY-l1J!W;vj));uT?xD*37C zqKr1`=%bMT7S$u3L23nNh$f;*+HhrRHD*GE8Vci+k(O%esi>x^YMfdkmR@DUomAD3 ztF9QRf(wNzs#~P4>g%t-1}p5a%>l^efTC%}9iDjx_NiiKMrM(&?_KIyuf%4n?Y7)@ z>+MpLb_r{e230j6g1@n*3*Yqyn{ZLA^2#i?>~eqM zA`7jj2qi35h|LNnC}5o_WHUj&Ayo2vFe2L0%Sb1!^wLa=7IVfU0&3BKIqMblcktFV zo_1INlbp3(D5u=?*kqS&_Supa)^EFi0i4j!6NSjOVms&c2G@vXG&IAXoRQ3dm1I!eYr@BMxeN*Vb-ePnN%-cRckcPhPxslj$P2-pkjGW;1$pFn z=Z#R;mh+ss=AYMY`|Y>`%de|ZgZzc+-)pX6?C zJj$FoZbFp$>PLlX(l||AV5o>2uV(Zi+n&xrPjercKAP=}e2J(ew4e=QMj3`4S8nG=G%pl#Y)i=Kl z@{*X$Wanh_!_>t^h_4Hgw8+%GJQ@lmg`GJ|AJZr!SsL@0$W&P&i`W<9sPI(;Nm4Dp=*Sew?3aBppA9XU%x-%B^P9n{ zo_41B6hx{}M1TUKks67|({RKq&SW7m69vwC+Vh^LT4o*Xk|d9LQJSskB_362GFoBN ziQD8RJ{QW+hDu4FaXciT=2#FwkyCc1bSE^`Lr~+*lb#L@sYpj!BZ#V#E_oE$N$tqa zRJxNg@x*9C#YWPa+VrM&l1e96W6^;6ubtL}=|LsPN>}3as7Ot!b0B)rW`1NlKE+^6 zAJeJfAjGO1T@icSBOI>k#E*Yes#wQL*2h3}qv452Q~lDjfo{s8?qL#E%~VkbUDc~Q z(PqPLSk}J!^{;u6iuK@^*4(&8pfl{KT=ql}wK#UJjKOMFKO)&^;*}@=l7k{h0n6FW zdR8e+WsP`N%E*>Z)i1&6R9zpG)y#MYudD?MSi}0++S>NEgo#SOMEjAovh}Afof&4v zBUH%33$_Qb>riG}Ox!y6xzGiPRD48QSRDYZzxiomE2UP;vR13!jjeZEOO(t4D2mZd zuX@)@5W()0r#sl?f`EHj)Y`SG#(hwY*QBuwKPQ!+m1MX!$6%x04En6SGsY*d9@U%Y66%Vaq54vbvkkDTlh zWEk@=EUe`z6WT#jmPD3S%w)6}K@x&4vr)_|;5J+O(hJpTBzb$F1=IPobh)#lIlARR zYi1M9SVe@Ze1I*_f($DX^DMLw0~C`%3&RO?k_WvM8*diVzz+5?-@MO|#lRpaAP5R> zaE3G-pw>jL;ivsu&K($`2`SESgkkLwBdE9(wpfK7IJ)gD4@V0Wj@F$^EMiF~#n);U zw!G&(NZo3OqU$;~3Q#}-Wgmdw02cy5`u%TcyA!xAqIOgNxN2=Juz1u2F>;hk5e!?P z7}8f(HMjR1jB1P`$*OjELAG4sQoH-zPfRntSI+V_M#T*(WLz`#&2J5mpyvJVcd~CT z1Vsq^03@(E3SJOxkJ1;^)z*rb2~uH^x0=FDh{2R?A*fOxS{X zmpzPUtN>W$El<1Jb4cv!e$wAIzxe?)AOV8Zo$hnj01~bM1t{Dc1sbU6!Tm=(q%&nW zr3SGioX%xj@0r69`FPenLWT*KVjt58M#m}Q>Q$sz%!~I(*}nqswVVF*3Dj-Oe}wO+ zBpdKSkATe&B7wjY1n)1&)7#b zkb#T=iTM|}-nO1cPx>=!_SdKnzxZ>fdIZab-*%t<0qQ>Y+82cVfWP}3IspemAYtyl z*MJF7aO`ywKHRpWs8?> zq?dB%HGUu%f}f*la26MUw{shCd+TR=x#w^0cK|Q20eQd)2jB^C&x9l zGh}kn1X{p>5w~O-HepA0WFR(qXL1Pxu@1rT4C~+x$lwfBK@j_p3xj3{Nho0wHenTJ zbbD24B3OoIXg1|1b0+w2cK3b;fp>JL0k((#0x9?cH~VOW;fDG$U5bN*^gQf+F7>ahVVUai& zdR0kec!sLDiY}9eC((LGv4cCP0Vx=G8xV&DL5m3Ceq+!Fosb8ePzg790E&PFNT7cK zs263M+U=PwKffQ&DROk$&pk+H? z1zW*=bU|sU$cpkfj}XHWFlT;Ep^FEw0V%kG8xVZ9M~i_ckastC1n~lF00+Y83BY)R zia>u?Km{i@c+*yNHqiuA)?y%Mga~o}e6!GD>R|`LfDF%24b|Wb9k&kqZ~*Iok|jBP z;J6P%_7U!gIi3+<@koz4xs%=Eif%U)bch0X=Y9fti!WGrDOh{A*pIikj~c)R2Y`nP zSr88i2M2Hq4Ms4Olvv5w6Nt!VU}y(UcM#Wj1IIQB-T;%q;0)fdiJW+nn)eLeu#(p` z95snXGo?^GxtDyIDn99BM*)XU$&cyRj|ORbb61P)cY7Ofhn`S_c-WAhpa_$B3qO*T zRFyX~`4ryP1lQIOH&779@DKc852h)ObZHR#Fb}7B5KE#N-X=gE_k4K`C%TA4hXnHRBnH!)-puQ`Z# znU}P4o8TFqi(-%Or4&SIl)7k(1!0u8$9{;Zf_FCthM=4b8I_Oumm{4g_;)(ub>EqV4nrS58iM9!H^IfQF*Vn z6+3WeUTBRIX>HO7hJ@Dt6a!kFYr>=1`8sLRj6~&~G=-#o`llVDq$SuBfyaJPs)8Y5 zdrUB9t1to6;u&(6)F+{iKtTg5>w^~p_v=0@C&bCqL8Tw&p>^_ zfDRPc8=Xjf$bb%`@CKzO3H`@s4(D*#R}g^~hC-^Du_|r-b3q3Iqy>s{eA=hD`mXRw zAA;&nK(PZF@T+Y|6O(|A4N(acR}GkY5R~`}-jIm}(F-bO5UyqidzNkov8i97s-je` zc5#X^lsp9bMeR!eTk+bl9-AEVT5L8En{Q|nH}G@&xB;nf0JcyNm@uii(1`@`GyXt@ zQuqwdN|zmnF4wqcE2bH0dUA3~t~y$=2kH-Hw5mnRH~ugT-v@pl8?{oq8Y=;Fy7`ka zk$c8z6B){nT`*>sfC+hk35Jjh$bbv`@C*k4tw7U>&VUXFkcrUh4_jw(262t8#${ru zWf(V>SRt{EMX`8cu@^g8sM>)Wt4341xQuHWA=|4Lfv*Okp_5ys9%{J+;RaRKsBy4| z2Y?BsunMK%3lzAi3F8m;Fn!)I5B`9&bE~#_h7eUolV7G{A-AqMAvrUNyGH>-7aO=s zTP+`@xQ$!?yv7R{Aq!PI5d%~@oI!vP8}Pgb@VwE>l+)Xf)O!$)@P(2<1zsSwoUjVE z;0gPXw!gr({}86tu!;U4xAt%etcDqZ7EN~shGWL5{l}ma8@ywL7)g5>hl{w0dt=92 zzy?eg6MD6fYY{V$f;2Fkh8exZXm9Vmz01PV%u-;G= zZacTFiwwQcB2@-!vWsmSW??aah!p0xoH0(U$}>kh76H5#XP0L2cEChj#7w~wySke+ zu@%`%5Yl@94_u`g48_(9y%{_M1px#?Kw>z+2nSFKmGBPykhT!`4|F+~CxMb=kd1mv zga$GHWui(D*H&c=Yp%d+qpTw<4D`bh3vWyU?1oVOQ_iIoQLB~CvOLQw z{ncQ75G>tAHqn3myq+_S(`g;WYW>m%K?jU_b#4Fza?BMbQ4Qz2qG&Z{rC>Q2*@Z1u z5HSE@6t)UuR*Jvn(H{*MTVo9Vg2#4@WygcCvF?7}qDjGpt=G~oF-P=@E-U2S5>io1`t>7wNyeg3i zH?zS13EvcK5GjzT$+qD%A)T)QABDHrfAMFTF-!xT;wxU{Qo9n#-O?lR5iK~>3=zdO zUZoqrf6tb`Hc=7@2OHsy)qMn*1^$k+N!&(0=8N0nH)F^b0d35idpvOe05gEayllA` z`j0SJ;$(`M^9A5sZqBa7)kB`%WFF|ZYUUjS;|js#Yfg)RmwSx<0*?Ly1}9s>wBy<# z-gZ8;BrfDP$(XW;}33dl*LCwaW{C*ORf^&m(CQla#!c!eVpFu zpPuUwO6WkdNH`JeApsn~4#brXUPeOVDK+db0gscd>&||pyx!niz8zn#u_5l`e-S7_ zei8hO6!5Xm?ELKFzUu)p5r!^6lkRD?VeEF4C;lbkPGPYqPUPcW@ANnoG<)u<>TS{{HXGp=SVTHozX1i*vhOMzeTJ&)^)-}waA_?d0al41BVg)DS`9+nPD zg-`mu3nR1&^`0O5pMMz8(My@nQf<%rDD`KTpAZVF`(cm&_?$2M#E)A#klb9M9GCJB z_yzW|iYcd$J&^&V{sKlwGS0$Z{MxTxjW1`fVJ+VQ>v<0NTdx;`A}Aw+5Wi3P!Y%e= zzy0u^(%5N1T(P@YU(%+3`{v&s(*)}PvE#r%f&~p8M3_+FLWTw}8S@u0VkR9GEndV} zvEfFJ9X);o8B*j(k|j-^M43|MN|r5MzJwW5=1iJ3ZQjJ0Q|C^eJ$?QJ8g!-`p+YZ7 zJn*mJrAs@UK6P4D=23|eFCBmiRjNv;S2_9{_$KSqtskjYrI=Bz#j;exipQSb>@RX=(79!Aw0(Q;o6TuEt96}R`EusXoj->j zUHWwD1Dhs?4Hhv$rjkqN-p#vk_Nqu5>Xs~!Z*JqqF;<5kU;cdh_3huspI@$ygT~ae zexoXalp;tw>(V0)JgmI)i@fqA`o}HwZ{}v@qq3a{7gX{ z?J}`OD<4dVLai)(kjEa61T#!A$0V~%Gtcb*$PE>fTy4n#XUj6Z{|bAkJYxuhvM%DT zYJPFGjnV;im{Z%)}eFJTEb1H(`YrX1HO8TY^@?S50%%AZrhp^dP22d$C)*0RGj= zUH#>GEogiIpvp+MmlMw zmku)KrGzdmQiLwf7-OIle9$YN^V&1us;;guN^;9(x@@!0Mmz20-jz_S)XGbUYJ_x4 zEoaEMCD=lr{qb|#g2JZkLX_1eyl}%0M_ewaxsw-XxW6js=9#m`J8!+cz8Xf+K<2FI z#6Jf;bkRpYY4HOa@9pua4bsjSM`_gB@?mr9`)-5qO`T}ZN$0(H-+w<`O$p=0?bD6W zTkgf6agUNlzi)@SF~J81zIyAg$DU!+os1qdsTCs7pMjUN+p5Y*mfm^u5$gW0t|dBo z_w47Vzkd4}jo3iNO#41=@d;}G-{hX>G3kLzX9;0m;KoL(`!&#k4}>6)BK9=YHHKPM zvkuq-n3|3eurTjCAObh2tzyY9f+s{_3RM`LcNqjTq`4qNj-o;4C~s?lyF}k4caRa1 zP$CCI*b0R>L?RaPGx=j&1q*f}N@+}kN<@tfW#^)*Jc@li?AZbtXhbe{(TiU!$^?^$ zwNFjVI|8IfZ!gF2sT#5ZzNrR<_cW zL%bySOsS`cY!WzwtXvKM54k))hGs^jY$O%wNWE7U)0oG+UMy|nB49S8Hqg`M^LQ!8 zaWxZq)cn{ZA&E?GcGH`Nb6124^1|ml!hC z-KiYqO*4wPTnIi(R>GqBsGbK!XhP4GKkY2DoSmGdFw;3rY-;8bj1*x-H>J%WD%7JN z1*xf!2r7Xp37`u?r|r~PQVVWuBP`v^^oSW!n%2~&U}75uH5xUD?lgB3^=I+g8OqH$ zD1LRkX;PKC)D4YPmOkZ}E%BDp^{q6bJsT=fKLXRA$aJPm1#4KvDjlZ=r<^C{sv)I$ zLpO3HtwEEESK~SVR=U>JuBZ`S+un*BQeIVTYi(otvO3j>N_>x>&|GRxf4U zE5*?2R|NvrusC$<2H9E^xo*+1p9O7b+XC6h!tj~EQ&|7oJ}|agKHTQT{$v#ciGOk1qvO;hM(6uwBfZ=6g!} zl6c2YhO#$%9Iw){6TAK$=zC!-sGdp&jT7E-P!_z(D3{sH#|)={%z9R!)tFl0Bx7a~`tY0!x(0Va}qhpkm9!+!@aVEvTO*J?Sq3`n%TM zq<8ZP=R!9~(Z20(rxo1fJyY7$r#_)>!y?_*P~{&RL$FCXjcB_#g*aLQbrLoGF&gQ) z)Tjn_u;&L|JF|K<4pKDw)Ou)I*X1c!u}!XZdfbiP7{|iKcD6@nX=AGXF*%$hftcMhQ} zX}sAShjYu5-l+*8o#>=C_|wHcc2*JFDwjU?gDw_1i4XnjEEly~_GUnyhdSNPeyD>GQpl0LAtAvE*rmUgTM%6!678VyWqdavo~NF2=l|3gs2qv!@I2i3qd{E zLB6>X9IQd)>NWc_nj-YVFQf~S%Qw~Ny%S-=f0MBan?CCEKM{;Sep4rk`yt|63ox|9 zJ9G=PE4el_JSN&e)|s0$+&7)UCvkv2Zuz976dJcPtZya^XXLYd>aGh`h> z9E}@9vLEC)_2Cm~`z<*{L7J1qQ$$6X;J<)_l^A@Jnpu<0fsT#DUuz#*+v^Y&gY> zJk?9ZUj)WI>cL9H3-yr|SR|h{G%iN;mIZteP25HB;=b++#%i?2j-bRW)C(mn2quii z44cJH{6?Uw!l4>R$eTvby2f>6M}#;+ZN!T*j17w^rQNePWxO(GDvw##xg49T0)I(cgJ`JSD1E9r* zbjZWYM}$13y&0@?1iD`I#f^kXNz6ugWH*JJ4Qpb_tpmYYj4M}z!z;p>)YH3|B+4&b z#fY2>P&5et(5H-Q4)$w5ig6H8#I8ZCzkn>tth~e5JII`L3#9}V?hr+P(>xE#Wn)W>+_6Yg;c5X_|(YbKt=y|rXZs}wPe%t*O3%=~*tnv@H9 zL>`3Lu3(ZylRV3|JVf2lOA!*x!NkbJ|{@;`^?((G=`+i z(jj0Z^R&>l% zY1Nxy#n*gQ2`bgh*Ywwjt*c38*qYQuDJ4Z0yVzz0F?;n?bEQv5G)0Le*`+d7ft8WV z{M68tPj@X(idd^@yFpa$Du? ziAJs2Ewcfb+w!0h*01jXaF5V1w;rnUY^JQF5aXc07!`zJCkR?4Avf&&R z;E{ddAf}&_MPSmP5ytB|5XKpN{MZoxo{Be|#~S8fGo{(=72+$-p5!fIzBuBSt6tsx zJpG+l{-p^8#6=DKVg_~g1D@ix;NvLnKt^`rm*7N5 z-eR2q#YwIuike(1X3$5}7_=OoAzg)_~d`9 z6?Tq`8|=}LZVC8%Lr%?TjeccVX6mqBl{m)SP5hRfhLfjhwVx(osutm)R%b!YOqn)Z zv9{|~A>tw)W&jikqmJBg1nQ?g+Ov*pxem^EF6O&dZ2aM5tX@CTLu=0S>ra|!R(2n_ zhF;*zSYl4>#rAANQE12ihH0*gYyc9p`Gwh+#tD}GnPHvln!UfzmTg4QL&5Fpx@c&J zRtVP#YSzSIinb6?Jmbku)N&TDY@O}oJ`<-F?3~DL?I3AeYHq$I#MHiR)Em9Lh1dH` z>OxWO?;aE8R%x7g?pHO@l^p1rU~LZu=B*lUS#@35?n3aUZz3UUea^fc{zHL2?L5}w zxO(pC>}~k&?qjL%10RyS*6W1SZ)-6l&5q39w(Jk|?{hkA`L$V>7sZbvjPjNtwZ~1odAMcRb#%9V! z;ihn@dwp-=^Ka4rUTvaYdYRBomtkMr|pOVxfr zL@n+tLs#VP^GA0M1qXDR$ZfyuS;g=ShxAfMjWu^1|0eVh zH*_RNbk16JD1B`VH}zU~4OGu>F)nF^m2+M1=P2@6_XhRBHuKoF^r7qNA_+94P5^(k%;x}rtu1&^eGK?VbAkXCv|Uk_q+i2 zd?AT9a&4dgrS?r9*gFT;bszP2_xHc}^K-|$XqWbOzITCFZ$*dj8`kr>{`ZHk3q2H{ zA%~7}-}hE`b!JD+Yp1M&ccLoxaflaryNLJGCir20Y;#BWGFJFBqE^B!c4Hs;nIEmj zuIJPeaFo}<8V_uphY2_*iO72OdGB#rr}?8V3$9#tjTaSt$998v_O*R_9B=vjv~Hiz z%a~?&r04oDvUz;xpPcV?b57|D<#;t(`3Widknj4o?};_X`t{5CxEEobw{g19)2b&d zvK{)82xPW*`@o;XuTOj76MK7)da3t#S=IaEE^FUzc!wAK$#)5fUtPDhD0N4CvR8Z# zYWxKM66RIyHNgDJDkl=kAo%`q~ zF0lU>?fy|+US{M^{_baghJbs#-wBJqc-Q~gL+|^pYI#OJ*B{2p_6LXq0tXT-Xz(Dy zgbEijZ0PVI#E23nQmkn4BF2mwH*)Og@gvBPA|Gb*XY!=KOFLGwZ0T~x$e1B78G93v zrOcceFQGhn>EX+kI)^6Y`IBPMq)K5Dy~wktzf3x&QmtzBDpspaw{q?3^()x0V#kvI zEo=5H+O%rdvTf`3ZCN+N{y}}S)Fs@ZZ;TyvC^WCgr#))|RSMYRrM?jFGRFH>FiNRe zCsV$9_%i0qnm2Rq?D;e3(4t3^E)B6HRF#cany#35@!!@CA^U_KRQABViW#o%&Ga$U zsFjCP#%=sK^5n{wGjHzvIrQiZQTJ56T6#gFg>g!!UE8l=5B|b=SRjAc1!|w^wijB3Pt> zyNS6Ul)p&{Rg6?t)+L^K>bWPMefr6n8z$Oi-k3v{X=ZZ*BKeYmhB`^mpeoqCGUmni|+9$!Q<#vGbQqR6OtiY+x@mbfhh@r4@e zsqG~eB5#B$r|6=wDOoB(NfHF?sBlqQtF66Sdo8xvYP+pjp~7iwci*iUt!$}Qm#ng_ z(KH}SY6=7`xCboz${T9?=b>uoHn7hqNiX5`5rmL?1nolM4?ZLCs zY44r>T6{6a8Efoinl55DuSx%0!lXfQ%2_VR=PJB#X)7KeWKRdx6sKm>QastlIqSSL z&po&ItH;u%Oc$93o7||XD@Up1$O5Gdl|k@|dD$B_-;9;dS!=yD*ImOEXmF8E4c*gp z8EUl2CzEC_N(HmXCT>+TXyQrP9i5rgSKsS3-+lZ2H{copEwFMhpJaAQZl=9-%W2*e z9&W}UPIuk!-iaps_9Pf6kIdIpqgP-56(iYd#g| zx$C|=@A-NwD|DrYT%Cxhvr1aRtsjp(N|VEG62uW>hMt4Bv)4QS_StK{{ho3;FDl{4 z3GdJMr5e9{Xsd(yINYJ3_dV=l17CCI*5l4S{`u>_KZc@@ooI02H@n3#FKJ3sTW6l9 z!1d9rcJ;F#{~{>C2~vyb~g;5iJrAX9!?L8=wjTQytqJP zyv>cBu^kfED9Aw)a*4kS8gri36ZqL}j;X7o4?+0IwTw{xi1AB^AA8u7>Xq?+h5RHa zLy14Ic?glpQ6veWmYpk_@{hqG%pF++m+=Yliz>q;qFhPFPU=9EzWgOHJJ&`VE(evc zLkKG~={`Fi5P@k?p(QQpwt*DrGk^?aFte%6ZEkFs#7vGc52wn5JgI|?g9 z&z7t^6cB4?%z9~#oA$gXKDjl+8h-OQv`i&R7Lv>mdXSkvoMc+q2|IWCgOABt<}M+a z&xumBqMmx=G zL->M0B^gwb2vrMBEXmMmmMor}fo4zWNv-V#1OOrV1O*BJ2LLP=05Jf`28;s$2>$>N z2pmYTpuvL(6DnNDu%W|;5F<*QNU@^Dix@L%+{m$`$BjBdiX2I@q{)*gNxE?pXH%LO z0(b0y_~y+eWB!a8yA)HV&zT2n9TZ3h=VnyUmals3m#0ku;Igq6DwZK zxUu8MkRwZ;Ot~`UznC+pTnQsinly5OMpSDMEkU8E z1~R1_T&tmFlyM8~upwPW2tAG}dV2jX35wS&KYw z=0<0q4ds(W_T9vvX$EbGABPDUSRaK3P9>XyI#y|=R}gxJUzEfNq!t+iNfM%%TA-&|m7A;}J93WTPK0)^=1XM4HPBVbqd>F1w-1}f;Fgci!+o`{b0o=Y&XMNxh! zBAFU+4RI+Gl$O3VC2fXw>M26H706|OZ;bNGC99(#I2IN zkqR!*7_*Kso7e&=L3RqXqMmzxs_e4NHtX!O&_*j+qSSKcSsFcciO_x)?zH5vYbE*A zU6ua#Mu0gjnQ2rA&bFYm@EWQcrmUg3NiMUIM{T0-*|N$iM!kvM0VB@>T|@S{rqq0C?YH4WPI{>Fx|$}) zX~sDBIqz8`?hu0=GTCu}Bw~_bN3D@Mn&yV!A|za0rxl#$CC4V4^VL{qt@YMiOS|!& z*19C*PtL6(2^nXad4LusHeH&eLwyS~yEJoIlg;mTt#^)DrvH&}l%)RVw!kgNJ-9(P z;pDB`#pabKqI*X!`Q(&WZaHCJgUu47V-IQ2FOm#x$0eCu63jEkl;YIk3Kuu--0UWv zlX7*xm6yAh=WZi}Wc^*?O|u(wxU5OJJ~vO=7VMMbd_mlz?$Ads{q)pJoH>tSW7`wd z3qf}>iG`$ci5#iKK%&yE`^GdxubEX;?Y84x{rofTY^k^%B6S*nNCy{M>r(U50jg#- z`Wf(m2uz>?FLS;2Eb1lM;-0|VLaOB*BnCdi;L6n3ANJX9dGIrr{1!;U7ugSROT*An z07x*H9Uwr9TNptc=DhZl@P;_dp$>J}KnMN^K1N|n^8X6bl;j9*KKe^hS`61erwt5U z7YgC>ZbzjZTCqV{B7yICa{vno$Xot#l$wT@mYV?3Aa+s_0ef`CHoEbRaD-P6-Ltv) z5RYXJQ43M%g+#glgK>qD7QiYPaPG>&SI3nn`E$^XxO<`9{f31twAH=5No>1kEy<6_=4KB1y^BFRD=uWc(u+_#p#DwXlO< zz)z`p1FK-uDIqzGGpdj*5~VT}6#hxlCS6QU46}N-e6n${n9Zza87S71%v30T9OXi~ zwIru)%Vj$iWK^88iBuG#CX=|qH+$wLBmda#m4V%?ZV5Y~TH5DAk`zu7fs@*@4m5wZ zy%aDnyW8eE_qoUHtVzfUwW%g#c-DoaLMt*AnYHpKfQ7DjUlgI<-cPDI)$U^78KvZU z2%mjn?s(@*->*v7v&vLUXq!n@-w=o=85)@J(CbQGGP983t*?S%^wjhAHswI0?IAr(;}|t~RB;2I z5mDUO*BwZ)ti15@Rutdo)%eIrrXGk@l3&&6Z-^gJUvX8-ni$h8!AZ_?jnru%?MkG5 zTRL!+opgy#%;C&)@I+o7CSNVP`Txzjo)1YRJl52?4)=rq&6P`GLCz|n(e>4NwkUq$y1p@4545N8% zmbJ8}%^gqcfX=x-Yfuu)K2&04VCwp=%w|mOa#xAgUG@@FOzr9eEr}_apb zz}{)jcR}jS?>U^|2E^EeWixH=f*U+6*1mR=3xet-!F7n#tfxiVDsDrX^WYf&Q>fZq z@!q_l6U~4$ut%QkdGov8_y4x{q)VRildt>+XMnGUGn4U}+uR}6#&)(JT*Ma#Qoz;x zwkv@*AmMRb##ezsZg0+XjTiRltE_UFA-(K^q`4XV(8QyY?Q(h_pwhtLM>B*yhhsl_ zAXWdmCtzM#Os}-*aG!S07e2x43Q!=V-RW>0D|GPQ2gVqsqSBWh_reD%i-&bLsb74P zknh{&_f|U&{s9b4gk0WTKXb4>0SsUKgCE28h1usY>9nhT4mR=7RyS<;)-QPOopA}1 z_G@Q6-;!1tX}O&lupe4b(TNA>ymyn8#KX&18BYY$d@$fgN<(?kRI{_ z@x&Qop6J!H{`cT->i^u~L({j7SX^!`muR<}`}e(N_kv$)_~*YY-Wj&t=Q1hW<_$*xZaUqw0r#Et2*MI(Za>9lKpuh$KSZN3NXaL9$VdoE^M}4Jt zW}|0y|8@p%kX#w2Pbt`h2Q+?+QY%k(Moq(Kf5dko*kTtYZYD^0PWXlJk|l9)Yzc^b z!sZJ=D0==NdcJ^cEZ23)#|A(E1UQHTl(vJ{Cw*xqY%!>LBi9UVh-?kGc1Va}%VlI> zn23>cfj=aBP5(26*R^7AvuBccP$1NC;1z#fsEC|6F`1AF{_t-+SccfAgYt$D_7-_7 zHwVi%hjge3IKT#Ym~Z`-ipaNr29ahruqB4L7i@+}ofwRABxj%|O~d71YPDAC*BkG( zUKcSF=i)7xXmN4Sd%}2)R}&$A!xY;$iloSI#Wx3mxOEAka%pCRayW-M$biSsC5#w*py4(Rw=_^xTI}UY9+FTRF?2g&M5_aJRi=sk zIFVhGMWetEop1);_>J@iY-q?2z5op5h;}sS39*=tu1IO4NQ=n!gZuz`T(@jASa!{3 zk3V5azW+FLm_d;|sUD0-e*H6$RAqZ2B^Ow@kiC(3e9&s=Xmw;>>363f` zY+^T#o^W!?rwOh&ht4O9-pG<>cWf!AiuMLc6=n=U#)Y?Y z2^!^^!bv?40-2FXioo`gFFAIkDS4m(1O)Mwo;ivpCz_&Zea-oJ!UmV7 z;{TZt#Mp=dS(u`w8a4r3x4CQ1n0s+yA%df5>w=iUIiC1wKoIfU~E2sm(N z3*rc`pbBhI3X^sPalo1CIGsBfZ2SO(FnM+i(UIFXHS$3?4AVstxRd!QoaG6WvUz^C z^o-DGYj1^=tZO@C%;c3&UUxK>7^LFbX*M zl}fsN!d7p<_6)%=3SajNLJ$nW@C#Hh3yyFAtKb~*Xnnx;MPFoLqhu#G@u7DqqrzC8 z0Qqym#a~ZCm}RAI@7Z^l0+CMgoA;@ve0oDV5Ft(RZ#kNPo$w3$Fbtg#45T*;LjO>x z)i4ZJ>Ito=q?_q{z(#LWAOy4E3BSOoLXfGyFb9G#2WI97W@u^4Lm>3h1l+U(t57D* z@dmcw2(vH=lkf{Ju#bJ}dm|c~dBzs(WMaK^kTS!58?he+iKltGDVw;f&bmN~QaVW( zH-egnUN>*pfegQ349##0qClmNkf}l-pmX34UP*`PSP)vbl|q1}T`&h!+O9aT3hgRs ztI&?#n0*7HXGoz}Mo=P>z&1fcR86o7;2ECJDs4-~mvtvx__Lk{xr}itrybIe^Qo-n z!mJ6qv2IinnXn0>A``Y{6Wy3>zc2{`N-_uF22?Pwbik+&<)r8Ol?P#I?f?2Qr(z79 zFmkpquP%qL$%d-0@g{Gg1rntNP$5xovI=j3rfJHtTGp%a;ekVfn>L!>UaVg$) znC-HsP#d=YlqaWqV3ztC430giY#l!A7YA0k_2zs0krytsLnII+18lqPRXG zRK)vQHt`Cj^DR|JGSkS zy1MqgAbF|Q*Sc8;3UCm=@(Tw+P`~wC4F7--I9P`SD2r$|sM%K_$hx|#i-cQfF0bLd z2wT3Jq`7SxTsifZU4(0}qdvvz5wz)Z?gwbF#=ss7t%xF(uT~Rh0CJgGc?AIq_PfF? z3 zz#m*f((9|#t1W!yL>63Aq036)J4m<{#b7MOU*iV;U}gK^Yvg!~X9u_bpu#M?!fcT3#`Y9{0tf{K^V6M>+8pI(v%8 zmu6=8b%1oo}irUddLUhd9H|qK>!E6Tnxalq-+2Tz(Ao{ z=X}VZ38er9&WEII5XiqUhm!yWX#fP8;1ASn5I8UilK&tClOO~>ECkl<2&rHTJn9L8 z@DN}sgEP2tnhczv?9K!2H6X^YEH+Bq!k$H`U;4byM&giwhhQDN)Lbn+0ObbBV02|> zW)6{jA^DL(xNisG55Q2zbqu#1y}uLf(r{gQIH;L4o1}9H3LMSRcx=u@%?M{u2;p-8 zr67{2kf?LuT5bTeLLHOY*?|An2`&J%Kuf=o)KJ{jI-gGaSBtfSNl6_+ z7vbijTaDSOtvdzn2Aj}D@kZ1OjeW4|gB?xGb}ff&;17_NZ$Q9`U#ZuWI^3O!$9R0# zBFS$zebbrx$g2>fzW@xUaxWyugJdUcEoX~|>~%jZgOLBWi%db6`gqx^jUJl2yrZyn z{5EXEnk{=rvFKM?wbysO34g9!-uN9oU!4rYz?OrWiVe}eW#ka@(TF^kh}!q9;y|7|t$hG5?w_U?q%KL!oEMU8=?k{J)-yZY z8|`=r;gX$q+!3DTbI1=t8>Y6~f*1~t+)a`s*}lkj<|NnK?^wy32Z$b?i$(l^&9Did zh~j<`g`(hps47mneo7t_d!n#YGr&W90EX=gC!C$6j9J`sA(7cRk#`p4{R>vftJasyw6z~)X4M=A%_ z5jDliuB7b`fAU*1>6;)*3}L3LJMW^`(Z&DfgRKtWY5T&V4(1rYhiXaWqW5Scp51E9 zikhkF)+dX<&5H1Diha0>Lw)o(00sIk^Z=i7@E^yr3^$m^mMp|~nEEIO zv|)~NTR&+bF5;s;Y1%gj%WxIrJ%K?!qNPm26~7SCH@IJZ)@f|>k=Ad5`@fz5xp~je zwoABPYw~|T{a91be9pbMbVurD>B#^2!c)#{!$x(+pNqtNikHr|05%kYiuwE&^-#dF z0!jtHu=%S{3W-_`fC#UTw)w-&fB8^VLK-@BILFfgeiivO^Mp{~ zMvfaLo|&_3Q=Ck0beu$)Qf11HEnU8Z8B^v=nl)|S#Fd7B4V9o#djpYe;V^-e1v-nFVGI-oS1h8vQ#Gcx+88D9uO z4kijK9FZ$ee95Rc*^I&K61t25uCAzzkjg>V&YExzLQ+{plwdruMF=+>nnZ|Itg8-+ z>2T;12Ou`w$j|Q%@Gk$Y@j5(Dz1LuBsJw_KI?E=B_RFLsAW`bEQ%^rtY*SGel#5HR zYU<4@DgXJ$q71LRilKr$!N`|^M9d1yEFEg=EtvEoaz$ZTd}FXU3IjD+WtU~PS!bVx zHd<+U67|2(MoaQ9ouHx%IB)$S5~w%KJnaUBc4bc>VEFNepA5USa1LMEwa6kWx$*~0 zyyCK}U%!mt_mW;P3TBvLez6CgQL4dn4l23`CRa(hgMtlBBx0k_mIR$Hyy?`!D#SV1 zXcSiWCRT__`0h(Jqf0XNZ_{aKrWvzpH&rT)OGYuviJGx0 zWSRt()IwTW^;Q3`Y=_1AuNIGev1YHo20LuA$0ob%9B)=|6EKrh>@K+u8+YxNoIE#6 ziYlsYU9w=~``!^{yCiF2jgVv#Cv$=A&Q&B?rD6Ewqt6#9=kvwXjBMkl7+^Hv+>?ye z+O0brx(g4hkw3in(VA#wmsN~1!nNfC($Mr~vu__8?H`qLL+4RW(woxpG!hf^V5k|h*;|$*Qmool%X}}S5&Ep9l%`x_6Q;_E>DEOrcTLG> z%6ko2DCIo%bSNwaf!ck@G8WkRO@D4FU|+h|H5gXWidV#97PYuV84^V)YCBQLv-H z54+fDhqshg%MnR$fO!O`6!*wYQj&##7Wqd_00lB3KtTu}6Xc-M)4aOv%8A`AE|pR8Tt%ZVL5Tlt zzLgO+luo4R>Xk{kM#a5$*0Y}lZD_yt(t@t9eQA{DMpDZYx6LJ7I}ztM&A8fa$uvc) zF&A7TlCPa|Ycx&e>}1?fhtM#E1ahDYNG_HYMfIk+jZI5pAu6Shq7pfa5>I$6<_S%t zP=)!lskiDvM&WFvSa@xr3q=dQ1o?FmtM~Y zX_MjxFsfFkrXdbToSD-k@idvVwaIF(rpwmUGl2TC;mf=?BN{Sg7~U1BM>791uZUuV zAZ(Z*L(t+I>^dYoD?5&sIw3cXoOUijC2x6&!%u(e6~#3xieImqm%Wf-2U^gA5q`0X z7_35}!7#`wx*(7}nQk{6nGf|`#k2#{3Pg_7O1g3w5qa&fBJ_dXbuSD+f;@=LQqe5$ z&b(<(ciPjRzKM#B*}fvdct|o9BV4GdqO09+yrd4NUhpRye{7;8%UTd%eO$|pn3Gcttm{v9dSPgkRWUBXs^n#t$HgS?tFj&-m5>>Jn>U8DkU42yV2Z`jlPs@m4?+ zHdh2l*D=S1=5L(wOPDmIW|tXl1+P&#^7w{U%(>gMIAJyRfev*b!&JX$iPIR`!Sje^ zWx;+PM=8Y>_N=Ftf(n8?sd9!-2AOL>M|;}UzIH2$dKmh0vBGyErto@;G_mdoPf;@y zNi;zc0+|J!|9*fbXyE|C@W(BXF(jl8eO$vxIoMYIhL*=%dgnnG2piv$Pks_7IAy%f z_1Mq!0+j8WAs|$KF^5!i!65dX1Qj+>^f_ew7jCfqf8Wb>D}DdSE5ZX&rGkx2&${Ps3RpOOSD8Q4@*HXdTEtMqcE()Hz3eA^XPKyg;m&yj$@qp+JRM& zKVzW3ED8;l^Msf)oy)Nv>$$m(fF_+1!T}t^mxzn~pgaG&h>4v$FQ4;_9dwM|vbngZ zis4%b9B>0Dqyr1w2nw7tr$dHn2nIqEi{97`MpFoeaKs|g6ZqN)sJjmM>O*7@#9(-a ze}FWvi#Z$!f($Yb8VoTTq{CB0#Z**9pm4j<0KilWiiRsf+5#seET99B!cM3jkgJA& z2!=~2g*uCY9gu`t#KOq4q%EX8-LfYEl111WKLOmQH2js+5<-rELo&-NqF6=5uqnD= zBUx((M~s?@;j;sn1RPjBPsjz^$fkLi20XJsbdi;Nvzr6hGdG|D90I}+m$LEj{|Z( zUAnZs7)CsLJiBBmo2(gkOQEwF13^c6+w|&3x24a*pZYB1JPlbOg#nGU=`Ne zNzrCvQozi}F?mHng{`=8Pa1_4Nc_WGX3|#KGdy8BL{6HT+a@8P##E z&S3=xL;;U=^$vkxgLi#bO%OC!xtRVlh}Y?ecOx_xye#4*B{+RdtT7jV0McPK*n>sb zPT|uqy2#HP7r~@c!u(TkY`p(Nb*zaoo#;7>|H;2dwtqzcc9%GZf7&R-~nPH+Zi=*3?^25-;=A(#clSsZ*CuS~$pkOkL=TQ+mG z(gZA5l>G%ka0L7Mg)3NvSqO$Wa0E$o*La0jO@P(Sp$*P~*O(QEbzK+E(S&zJRI{ih zUOfZ5_@s^$9H7O48_>m}J=)I&-Ox3R9?U*!WKm>Y(ohA=pmNX6-5zm`8|Q=DaP3Sb6;}J&h)LK2D69iq ztb;4iK!G4!nbia!P~4VaSMZ>X${Jtq7+l8%DO0jE@T7}~@>GfY+0EUHY!co3#ozp; zmY1qXNp&B%u~Md`sX|RAP!&g5nFFDDD9LpQ+>4IFnFM5b2Ty36#!(L7bkGs()A||S z=)_dyORGm}-9#(U>TY=~=D3}C6n1m~EggL9t19;rUZC4yVUv_nu9UfnJ z<*qh)90MGnQdJR$xPkbaQz21UmC)ZOhGK!^-_rF+)vbvz8IxxOO(UVZF#5^Yty+(8 zGJZAA@tB24Ac+58n1ob#uP$%{b(Fac2Gy5g2@jU4Z^a`KCKGC!PuDHlQV0gxKnBk# z1W_1;{^~Xjv=|-s;T_flelXu32I3B4(DBTspn9gi(A*@JB7b1w8fn0o&;l@kv*?TB zQ$}Th;@|!?)?>Aa5eBMdwPJ{qQ7?uqFm5COnuIQ(0uAkgPC$lss0Mp@hJ65zP0*9t zlN)7|J2A-wZsbq4&EuG8AOAh0(b<>LxbmWR5QSd|25$h4Rsja^-QjqBTy|Aw&k?12w9yhAPPTAHm!N0*T@f#v?QX)OngCwPVA(In!+m4`1lAc2n&6FW+ z+lGB&bvS?^2m%`5>%Zn}I4A}ls+Y}q+{&^Tm#r6fSyhRUD4D2|T8$p_P>776Q<~cW z@v!G%>0rswol(|;ejezKugJ)3 z5~2f@4OW z;0U$^4h{shI>`A4MD5bYdNAOyi1bDaH~<{C)*AR`MYNIXf9?tUF746Y?;scQ8$oDS zwDHd|=P*te+vp03a5R&&R@$v(n8*lzz-SC|r%9o~Emx7w-ib}waUd58AGc~kAM!+3 z^vzgh>O68J&pR3YmWFe3n&K&29>Tmc;H+Wr;C=82hh;kT^S&^GQYTa~QSLR8!%(j9 z3nw5A_i#7}0yqHiMOIgI{*Ffu4F5qn`6U+740=k6s2JX975hWLOzSue9;DlvZ z22N0SaiX0sM+y_g)Z?vpgT-!I5ApEj-i^R@#$9pk@CRFw)qEWht39MB+ZF%IPW3q@ zah*Vrr>2RkehFv~XlbwZj|cgmm|{n_&Oar>O^0+fR95GGWrzhwk~`FNhwz=c1b~6} zd0z%XI1wgbf&<|BQa5$(@$v~TX?;&_O+8q!uo%ZpTtVyJf(H*x*!2^_S~BK3TuG(M z@`#Rz`1SS+@cd+)KoG<82_JWfOkjjUC9a+&$SFotAkT?ikJHy{LJScXRZ2V&p^PKXJf|M{TzRk>JoRuA)|_x2NQnTl9J zyxE*v$8}vtRNJt62JJ%O(~hrrFxp_1bQMz-^7_4SYK#Am)ZX~2&VB#Wb_u%`gx{y? zACLRtC;ovVrfX4Xy?>)*-D9Oy{@jLg8AA*p4E&OVycfw7S3klxzAmsx@&>jBF_b2v2i7c>>1IA3uVc zH1Rv=4j2Z_vyL4&C8-K$pk}OG52g;NxR~9lkF%!&~nM}qcWHV+- zL4pc75(H?cOqp6-xGZY)DAJ@#mojbY^eNP+Qm0a_YV|7CtXj8n?dtU_*sx;9hFxj) zELxRr+zd1J=FNc}a_7>O3-ztBhkEtGtytIU8)L>U^`&SxYvKR6br&;kJU8&LwG+>} z$rL9IVaJT$dR)ed5Ysn=IC1JkNVG{Ns#mi%a=?gYx^FI}iId4qTC`+$^X~2YH}K%X zqY@N2=lH+_7>{er=&2bnO>BTruWp^XCV$N&&Ur}jVnrd!NfK;m{yaZT69;-S?@4*{ z`0_PA&+Bid)7&eyxC|<@dI3a};)-s)ahPIK4Mx}jiMbdXk99#N*#RP^RM};j z`MBaGpS{7FR5~KH8c9Y-$>VI7*p`WqDt)*mmtA`KrBnat@#70H$5|xA9P?pBkU!F0 zcO4tR`1778+JWbic;cN&5pr`hQ{0(orl}^O@f~-DG5_3`pO9MMM^a3T%p~cf6oE!a zAfOc@h=CN9vXg=e>U3pLErEF|s;R2FDyyx!`f6}lX1P{dZxyw}j=0`+)Qc$&<`$1n z1-92iH!9X6vLG1~nH!VIiWZS2{v#S|)mGaiXs8{<#6;XiDJ5*0%~soO&%$~xy6LKW zz?fx9WK^LSvANKj)n!Mgc1z`{Cl2skG$?)X%6FV6XLNGLTQkmeiAa?qm8A;~It&vb zYpgNg0R@sI2qCYm;qgSKQp8A4I_dNiAP?Z4Rzy%qW(q7`o%FuR(44;f^PW-{;Q#~_^Q8$ez=9vzNhe4n%do>oWhpVF z2dq(u#d63|5`vf#!tqXmFjCPbn}+I>AfyJxHtMOXzB=oztNXNmv<7VwjVY?=(qdHs zZK7X3b3MDzO7{p^WX{5#)=_nAB8VJVYn}B}Z!DviXPhK;?Q2sy<`LCcqU}2P;iH?; zQSAxzU7-ietI6GaH`y5 z<26!CR>|SjoYzApNpduu2%g^m0(ijX3P6N*@jas({hET>kAKs@kb z=>$+FC^g7T6!Mq$yeB^M`O8wSObJ+&CkR>Al9f%m9+SK!Htp4gdoVd$mh`F8Lu$ld<{{!g&f^O+;YncgVgufq zF*kxC4q=+~q(@E&(KYVRjTCuY<0>{s=1K66CW}KoD>6_2thB0Dy((5`c2Shb&V?_0 z;U$yuN&Ss5dO-VUB$-k)ZMOeVqT-@x4Y!IC-)MA)9o^clmf|gu7R5D8e2gwpn$oNi zmTl#rCJz1v1jHVsA;l<$anuJ)GO~#uMbzm=24b)?AdPlP8EQ8dmlvb@&yAF;BWfF1 zl1*&Fk4KrRP>534+0wSQwv~`vb#SwviZCmn1tmk96eCM&1}ZEXOu`K6)+WN0lozE? z4x7h`yW+K#IeKSNz{c0Uk`yF?t=VnE`zmvcCvNZJ6C0?RUc_3{Z`J(Ud=T3lf)ue} zi0iCWf=iKqLdBcIXq>Eyvbj6Pp{Y}WZA_Xb-UTzb!47`dRx5)uUIC_rJu7SUOqjE< z63t1=ZOka0TS^XbY7_sdbr z{;-dl>k=DE?MoWvXo{b*jDr*rA}vnM0kmcmTsm==0j4sbccV;_$Y(n|7L+G`?4)7+ z_Esp`vXNCdJjPYzab0=xAOo%GO>;VYas?rA8*`VSYSSN}<#1>;?C4P!#>i++^DrvP z6d|>lRdrS6U7I2r(sTkE#5l+iE7DPremA^n7U3%=rbj=U$Rve~>Mg7K zScj>dt|@71kA(Ww%8Ipusj`woe`O9EXObj zTUeO1E@iDoJDRNw{uniDB?(r)dJvlDx4PL~_Pz7H?_~Kjy)TSAN#gs$NWV)$C0$&nm=I|NfAz3rofWK8 zzVcab*_;1yT}y0T_et7)iV@zx2`l+Ir8@9?lzFVTAm1p3PHFj3LgMzQ0KCX6KQg$z zV>7ART_$+fIqHKi{NXD+!a`3PL-ku`F%KQMwu3rZVIRHdLq0E(--^^MuYJm6etCB7 zy3unKme6xT4jZ2_@d~ncS=-HCfB75yO@v2Gg*VY0MookZAXxvg+yBL& z5-$H?@C6;t*~jgPqGp6!Ng!bb=^`{nqp~?6 ze<{sZ5e@EXVyZ=8mOY?RINj4BmvU7f2BOL-q9WFPp!aFs=5ftvcvU-YS^05F9gP2& zG+vOsl?1WeNFTBtQUoF}?qN1nVKOS?GJX?D$kshBBtz0zgk?gl^v*Rd1{p{K8R&`~ z@P`pdf*nkRBuD~9NP=sKA4wWsFhZIZc4INhp$Q?^nT?|LmEx+LBRX1L!<}IWwxUy< zM(26n3aVh(gcK9Z;V8gF)HG5zU+9%HeSF;!27cUVa!U z!VFE;WV+xaJFb$~+23|`OP;OZUNvTp%;P51K@!-bSE@~37ER;b;8N@%AnO0%S9pX! z^dt3c&qE;MWu~TTBGN-fB!wM?5uD`#%mNvZK@-?PZBE-I1cP8W!|i!v?4_hArbsrD zV;IiNV4@?s+!`z9+EzG8P(sgRreI@o%V=0mCI~`hRwh!eCfo4VF9u`|Vx|6&MNy%q zcc!O$u8t(uphPBxB+SBFHi09USTHn0HK2o{I0HMNP+U@ZLL zBxeWSqz)Zs9Nxugl%Quo=hlD?EmG%nRs;}b!X{W<5pbsst>>%cC02N*Fp_6^?uakW zUr~`LjK-+i7~h1Iriqe76KKIN?C39K!ZYNBH|zs4*uyfw#VP<-0#5&-aIPrPcv)E5 zs9PndOkxm&Ufs)p;B<+gQk(`Slpqm3#1U<1J1(XtNhW22Xc1VZjB?41MkQ&2(mxL4 z`z@s>y=hi51~aayp6)5DTvS&*UO**8UPJ|tl!VS1(Tp~kwu7Yb|A>wgkH*ON* zRiUJgBVY=Kf*R5oqK;uUXDx=tE3TmlHfME4Xi{9K`Dy3XZD4ouDOil=>p`lvsc4q9 zor>mT?7f_w?hiu3DzFCYh0tj89Vm+Sl@`e5Tgc@^Bs21=?v}!@P1Ss&RB&~i{ zv8dghN|co5)50;F+At@?k?B&LhUhifUTJ|Hs76L+q`Ou`M>hYf9lStEkcJ#k4Xd_l zn!c*AQiYs$=A(HM3WegV-l$XtWVV(N%-JfYHpW)|tHe(1Zun{7y{4`lYmxOMa2DB; zVr$3NDX&P~w}NYkL=EaV9H_>l#Py`1O2P}crCWB(EHJ@ZGQlj&?2+2Ryb4(Pt!m{R zrN2^a{|v)FU?tP-7h4%@apEcv_8_U1n!`TqW<)H}UM<#21+hM*?gWPYW$XQc#O@qm zC5B(vqFKq}lLw*f+FatAfBITCqd}_Hyg^q&cFYxRt^ejlul~aWNk_q z?&AtPYn;u2ZnvgG$NEs{nl`>K>&Ns-EyYw&X90nF_IXu&KH z0y6AFHLSxv_`@$KN-%IjArvZ5YN$sY#l!*a_67g0;I64z812;7$d={T==xyu0wX}R zsEbzaX-2RXlc@1sD%EcAXML_gW}&2J?BbcR6MrLHxul1|Wb2~vR*9=2x$W#$ge2td zM6AN@$}q>g0x|>xG7!T)JVQ0?gJ(1uEnb{F=4${Sala;UdY*;h-eqWQA`~O+0T&_| zTZONp=N5mmF8V1%UTX=bE(JcN#!lhbN?H`sg(UofNP1*PlEEy@LXPI_EQn-$rb6Q- z7q+483G37Q<`dOe4TLH(u~kG9a4Bh2kF?Q}P7<--7Owz@C?tC&S}?D}(&+^^u|F>G z6pL;zk_5rMTwd5|E92>}f-*ZlqMx<}XZHV0_+q2LMsef{=r1z{ZqDbke&h`ls%*}u z765_~kU{6V@uv1t3KLfRMl)0Jh&FSD>~ZT@i?vvIb15H5TBo*oQ(0S6ut!UU_cmZY&$P#S@sTkF z8N_8U48ud%!!-CqFrY&PL%aD{Jw)-x1$2GKL%i)Sq&l|b~WV7HM zO=bs{16GHK82HgRM6BCaqc}#%%DVJ@X+xXC)^= z#VFW=Ua+3yK`C*wuYxDiLht`wQ?szHb?IIxiW^3>bn98FN;daxxQJ-=`-Mhn&on@m zIE&Wbi61y!s5py{Ic=r)Y=e1?dlCgAu57Ozj3b42A2ossd6h9Z@iF!>L%FE(ny&#H zX;@ry8%2kH=xRR8B#U$>efMX7d7yU11Cu$VUzLk^Ov$A5j8_xxI#AUKqoYVTm<|_b1=&@ zDZj1!&X2e7;03dEyq%{f9oO-$p!((3%%KzG279%aMg6TVIwvom%u}+hYh|zByxYqR zzh}BUcW*YK-O-kV!kj_FgTv>@#XMYrDdz~bzh3t?B?=knC~~~j^AoU+y4GJsx}qSr zXt;WM{kp@cQV9QCoX>i2zC2Nx_?M&k4v6{Nmp;qnyn4&K(b+_J){A? z6@5F*LAaO$?HiOFu5ws+qOfSbOR_t0D}J3bKGBZ5std~y`8lE|WzBTB=Z~y0o}8?6 zzS&#vXN7(`r+5~dKKP?cus_m^zxfn`mNh8CMBKoPT!SK@r6M%^Fo*(dP=P&A0a`|} zIY<4#1{^>byY%MG0fPq-Cfu=*VMB)x9TGG)%#E9b7cpkkxRGN=j~_vX%&3E8Ns}j0 zrWCo7WlNVYVaAj>lcvEsn=*~!#ED5ypFe^66iJBKGJi*p{yVyCXHBP1p+=QDb!1Ab zC5QdHL^b~*L75FXzA@%+>&%5*FG7TP$zLY4Z{fz3JC|-#+5 zt46gCMHVc4Q4u&QRBqkcaVZ;>GzY-#xMD92l}pVaW)y3TFv!CW6Bi75nsr366fN?V z4fStrlSO9d*1cQm&73<41r-i7F`=EDmi<%eZ|6DQ&!OkFeKM23(l5_`TTYq;Ooqc=v@8QRnKVSNEzZC}$Tzx=o$T#OVis1}!#<_$cSK7JdjcgW5 zqZoBu5s$osBqB|Dc`&Cs=x-@5JQZz+lZk5 zECk62hp14Ekz>vRlD{=6B#kgFJ(|!XP(-E8b}lQk zvedNGFe=u(VLO5}qe>qQ&7fJ4YWFB|%S~^rCbg~C-h1(F_SusH+r(B56Z_8HcD?^i zOU{F?*hG;xV&HGm3Xc^j*2Kmdn5>9lP4=*5^QCQHlR6IBM4YNM^xB_9PMIYubA*@6 z))Er9U1M1?_gqI~LX1N5EY=aG4%Jgx=%I-&x~`8&YBk9?VcN7}qzXnz=aoi#v*wqc zo|&|P$klk`*Yq^HC8SHjP3*IuOL4`MQAV3+mT^|Hzi@j#inN-6z1in&;Ph4!W`~5fLgHuBY%wZvyRoGj>nwX_xw_e&XuOZ@C@s7wYY4p?i8njTh zdnyO@dl`-U(t`#^NNWpS-pFRU_g*PYzx$rJ2`!q~R6H#V(n5LUmq-49;f??J9M4c+ zuipCWqhvfVtEC5*>fEKCnqu6)_5ORjL3eGUu(3y|bRF7{pDt?G9!`E~xz*~cbGP#x zea$l^JM=lMZwS%CEVLjANfbm2zd)V?m3M&U%|e2!IN;+z#iaXfkb@nh3*!dkID^4# zB^cWX6rf-TNUZPxUhsnW!eWenh!BIAiWGO!r#`_jD}L|u;1AzIvikJ|h^B&@Kfw1n zkR(xedDC0e9!J37odtP2(84NWu!CTv0(lfn2pR0q1TTI{Eru)N8PS+Vj4&<}Sz@C3 zI-(kvp-_b^%!muOkVPl1t7=Rf&tU?F!yGb1bocY28W9PV6cLIL<4FJHpN2#1Doz03^IHOkobQgCK33XzI}{Gwr!NF^E9qCs*Fl%V(m zp&RkG#9q3~mj{4?7wX8&0~8YqSq!Ezcd&&PF4K-KM8z@)v%6b`L}u2x+y4f+O>UO1 zpe=Q&zHZd5oK-Gn(tH^^%Y(`8{ZTDsXu?8%AXEyJVnQ48ib;H znbcL_%jQBP;t%#2a<8U!?sG+SqjN46kO#5YxUd-{cOuIOP4I54-Y|+y&BGo^VaHJn z(p|o(0fV5gSCYG#N9Q{qYo_jTXyohVOi>8DbJD6ePt&upeZbMI$r}BrDuS zNYAXxA-grfFQn-Kk}T(xO4!NmJEWV7W@SlF8q$ga?2p3bU^O2Z%_PQQM<^MdC5fui zrRHmlvy{oXF*u1S9P2an$fmH2W`#Ts^fVnZXx{(&!G$_Ap~N7}-I$ zWB=8h8}=Q86U|}mMmsudcJH#WElW86dP_An@vQvFTZ8oa&_O;XB%pBUP43c#h#)kt z4gChh(ipFd{$X>oEwW_qo8MK=w}~|DX<*CB%$!EFvyr9CiG{l0ue|oZA-=&F`zytk zwB(nZHnaNfV1>L^rX8CJDTx5%Ur?yES(&!PUF?Ds?u!ffEkqbXspfAKr7RBhHp>obi?z?54VDRpAV&wZk@w z;AU2h+a`wu%9|(>nf-$ryEp}*Lq1ptYt#SU9xPpyr(Um|@15^f&iiaG{Xd=xmLYbK z1Q{k{Ab%Rf@c%SC8IpJS=-u?p->LYWGR3uw1O4d^*;Lg39(s|*I7~#^TuEz{JMpa$ z3b$ozGIM+YQi$OWj9^G7Vzq@t43nCZa>XXA>8=@CLlkdds|t4^%;bl>Gqw+Q-R)j; z(d)hM`$hvAz)*c;8^m?fmrKB@JxzE{=#z+_1>!GZ3kx3L@Tw##^ z2$FG&Rq`-q^#1>0YG2&I>Od^zsAgRdtyo-U!OU*99_9_GArknDm3T}WAP{9|dq2=0c7Y@K4451iqAshOD6sTbjo9+OH zVJr55GCac=oNotwNfD@k7>1z}>|qD2;SH>T3e3R^vSAm*0TNEZ4Q3o~!Hw6NheCRG1ekQS}6N(4~G3NYrz@P+~_5D!B4n2GLYs345t2GZaS z6oCnLAPSSA4~zj3T5c2HLH0;N91LLxOmPf5;V~G2Kd`Il5c8IZD7g_N zV!-U2=3mUgSBhc>=79>jKo+RL6|Nu+ykHYckQ7dVABHI#j0~sxF&)Y5SdL5)x_}rA z;vf@pA;)0{9D@o};SB%Y02N&5A6DocI?9<=5PoRxWAH9117#%r&M9D#=NQvt>|?s5 z4P160j22=QCczn;0U4a3vT_TQ!pI<2q5X^iv}T7H5pF6r1uCrVC?|6^zb_jRO4YiN zPQHY?s3sCt$mk~J5**1IK*M!JAsMLP0LtVBz~Kg`+bN+fgV9CJUX zf*ta+CcsbH#1A!A!4BS!5Srl))^7*_AsC3tpU$tT5(q(oZOlUOCtn8CpwbLQYZzoR zKt*&Wz>q0REI0r8s4Aj3AjX%4Q~yOQL6D4B-?|Aq}YE z^~CKIRxU{mWIV)=-ge+uY?UE?Dk6-5AJ``h!XQl#U`#L7KI~9iv`xw}3K1fi{6LCEDkB68vTD^J z6oKW$ZXy>3N^kA?W=9?Ad!AT|L` zAvc(HE~s_g>~GUh)J1YB2nbwB128AB zw`>i#j>{uG!V0XQ4>+n{PoikZW-&jOJ_c6O92FiofC~=b6)4~f_~8KDAqxB;8H}MB z-XUrMj|V#xC_RGP(nVTVlvYkqjaY&Vv!ap&4#~3G6`}9O(wGfiS&*aAiRt6u}>WXWYEN-C_@}=8lk1 zaU-lC3EXg78-yW_(2|G0Rm*V9#{Ypmct+ZK`BQh zD>!eaIL)izR`6J}2bC-|@(&u@MH)q`QB#)|BefhCt0lVDB~i9qK|+NFOf9Zp2OdLk zm2(GV0eqVw4d#G9i~t;ti66Eg8!kb7-{2s-!(5w5+?wfTy+&s{!V3JrXP0RZc-9IG zqCVlrbVd(gqt`@M*WVs>A56h^m4X>0_8;JZ1rk9VltVev%y*~5GR3THiw;(u(Zv4> z>tdBfD8K4rUGgFPZ-I4C0N-}wHrDBiZoS5*^hBav)uJ4Zcd7vhO26;@bP z?5G%;^0j}1Np!c^B)a$@Ot)T&wULdsKhroPEHoq*!3$Y|0uVp|C}0A1A&>w6VIRT) z4JsHq_?XLV=#P6whmBV>zzQ~dOofBjd5sd7r_MI7PSGT}t8SROE0DNW6(J48!Q|Z6Koqi-vm>}1;#ZDO+~6(3YWa$9Ie>H7bl_)~4I+%Q z1I88L~k+_~EMmAseot84iFQ ze$*9KE(XAX5q#kWsDKdoVGe#}aFS)eT6Gr;A!sqe3c3J*g=usrnk4@&!lJ<#F{9;| zgE~Gsnv6F%nz4Zc)Bu{5!ypiQAJE|dpuw8CHlYkAQ$&#AN?32?*(osFr=ORR1KYyT zc^ltJ;ozBFOg6MAMtjX{JYaU0#Daqdh988aAYhMxpcR0!=}6x$_SSTw58!h{H-P&f zul@QWLe~#m;G*?9RRBA*-$PD^d4c~y9+IIK7GVH-;2o;F6)xcxTHy~YU}9BevPDgu zoI>3aRZ$nUaOR~Np}Vw(db2l_BWPvo9t>|KXH!%*y)UBH*1DY-s<<}fw&f~kWe7I* zRqTG-4~F}$d3IPgVuiwhmz%p(o;$wXW3bJ6YCC`mP=UJ-Kp+2Dp#%Ux0iv*j%eyjl zdf>hlkp=5`={ud~>Mf-LTQwZIM!Vu<^(nWRhAUZemO6=?5+hhIz}v)b!fYc99A{+? zL=3_JZ9tO0n-)Cw4x+e?yU!q@!kPQH17(bJ96qF5FN)db(CYw@qIdm)wyg^z^!Pcn zY{q4xvne^Jk@xAoHEk6cdcXX_IfBnAtWU!5uvROv6!2sfN`?r-esOJcA%gYLuIT8y zZ-E8Dn+(1WV#*;wfT2YsDBQxioJutM%LN-*zg)$g9L7HVdUib36N7GzB&x=BG)T^G8J#uEPJf~FBFJ+vZoy&y?7u4;aEZ z#A6tI;TCRS9vpE8Zb25BK@on-p`lzPtf15T`qn?<+`ZV-A<4^Yy*-e1y5oIDP(5rr zLLfAD%vfDqiv+b9ik$Ntv;$k+*C^NBbX5YqkH@uc@ti{nVuozA*we@CVgO3*6}hrO z6pVlo)OsPf`Yf`6&kg_){DIncz!erok3d7)B}5#uC^Kle+*yL%wY;xgg5AHkm&<8i z>V4EX{5=5o=lh(+>pYTis$v2%vw7!wyKdIAu%~5x;N#t2N#Y4q!3~z%Uk&03Xh92z zHf44lH^DJnG_>rcXyg)|;@J!1gwhx~!B{Q<6;|jptO0!gAEOHvf(m@4+OI(zF3=DD z;f45~5z=7qxwM}dajLE1d+DyyWul9}80TApuX(;k;GO8BgVgDRVKu+#?E`qJwL=gB z8sn_hkJsr{3{q6sVql!u8{&nbTO~^33DltwwqC-uU?1v0Xcc~j0Sb=T`RorZbcTF$ zzXWiqvJ;xY7n;EnpnneLz!Q$*`P26R=Aan>*b|yR?&basZebicVXYBTEen8#)vSF`~qY z5gl5*h%uwajT}3A{0K6n$dM#DCOL^RrOK5n4K6DG33K7Om^5qJyoocXPKFeF3e4os z-=&Z{iW)tNlwi=MOoJM`H1y+9hL?gyr8)KB8>md*U_}bHs=rKbcA7nlHm%x=5D7{= z07hIP7Y8b~C8%YeptXEG`uq#g&9HyQylw=Gc!$F`Z;bgfEH&xD#5))pBmCwDWyFlP zLNx}uQ!`)9Jei&|$Kjl2{F?eJeLxH(NCbu0CWzXTCQqQUH3NOg-lfi!cifn_gSM9) zmo~W)Wn@RYqN14W7`9`aV}EYk^aL4Zw!w-V!_#&~$1T4?n*A`SfwJypR8+ z!smSqD-i*f38?*wJPQF?I=POkH>w zSOs<1m@&W<)?radf;O5bsG(+CmtJp`6+$fQPy9gv}e z5EfRfNLf{A)lJD(*eppMip68F+HPzAlZkIVp^i200b-9EPna``K!w<&MPAUnS4cZr za0^nW5_LCNVMHOT*po&PbmevrR%?-yRa$wOF@Q1{aF(bY@MXjjPi&hfWICLhYP#v zKl)OBFj$shrkUqkDTy)2rk^hV=4+&BIfujtK!S+rAD=#(7dQwZr^QLiO;*bo6#=u& z4&gk=&OB!{TNuWN`uJOoKM(!3MVoq&9jT7EboAOIbPpd}@G|uQ{?x+)Bw+_Nt3TY@ zODu+#uk~y~ZQE2fLTS^_Ahz4@FKS!<3v@0<)dd`z0E9olAUtqnA}@d_hyv*nz2@lv zU!a*B=iYY_B{gMp8R;BnKr^L49i?HuVBP6Xh{Dlu>4X|X;R&~(huP>s3|qi~n1C~u z-svDE90{KA5;7YmZaSzdrgGi`MB|`e;nW+@L)kA z^fW6i0*!sq;>&QOn`wO zbtuR<7(s;RNicGZ*;g7F;*~QJgex4phzC8Fu!U7-bXqIn3S9_FkZH++n-By_o}eF%054{*gM{*G z_QQ=Bv1TMnqI>9w&1~-EiBOEm(Jay`m{3uhZu18>9&idRaDjmEkp%91ptOPnD|j#1$!LkZI_l@bc5V8a$x$x2tk(hof4X+aVJ ziA3B14@14f0q)RKo+8x`)bK+#;NXQV1OXAbq>Ua>u?tenh8mDipC6){jWv{m37g=A zD-N&>d#C~zT1Wykv>=Zp)S?h|xWxhHp@m_9;Q%}=hz|)e%@ZlnB377<6`&a+Yeo~H zjBV^jxOtxeN%14&bS%BhnZ+>v<7sHf?9je87_r$iq-lwt{ptxvBdKvXyK_oO;y4z| z%62Cyf<_$NkO_4NZWt?bgDS4^1a}Fd3#!P*UO&rG-b#)r6uO8cnQPk3MCl*EAWZ3E zYPwS5^p!gQ6+<6>k&0lX!Vjs)MJiIk2=cBX6|2C5BE*{tTbSVvsrW@7dP)$WA_5P1 zNNQ41K@D*r0u}EFg*~_`4smdG7t}aFb=zT#aqIvXI6FlyPeBSVuz?WSU;-1^!30;l zffM^!$0%A62QaYXB=dLzAqX-Iz7iw}30Y=goq5Fa7#6VtQtWJh4CI4AmL=cZNs%`a zPK#7F$f61xJ$^-y^r^2NQBXtIghs{_1kc?yTt1}!ZwsB@MPm}^LSLCWZl$!rFR z7RpfwRg~kc1Svu$vQZ9IyeBVppv5}g3PE~tR4^6%C}l3vNHk;QSPVf~%KmX(>{3j- zJMHQJP+@`Tq!wZngYd&I{IH6o_8}PkO+_CVQHuHU)YSG(>H&Z%)c*SS0C*4wPxqk* z1VdsMr-1bVFl-N0C}Imj*a0{^EC*4r0TLFbO*+}&g=H{-6HGY3KCVHCPPpP4{MbYi ztO15VoMaivr13(!VAz2$6C;wMW*w8*=6E}H$Snz0k`uCId5Q3TJZ-9_`7cOd^p4p-DTH6MbRDy^J!i0EJk~VOvd=KnjJH@ z&kLW49L2KnzT9Y)sH$?Z65D za0|s$ZwGM(v(W{9^;a4Z9>wEs>S0YTGkia2HSV1Lv=4ffyaMzw=$A$e)2jzLo@;b=6lqAHq)5k|OXSZORB#4|T88$9W;1b`<7LowPhaRhBu9p2XoeS8j}uu5Tg@91aUBX$cGWLa)0Pk{3E99khe!?C(1^2m0I4tvi}(xk@C^Bg z4#BVv$gmHvkP3s43!*S}zhHB}kPV9X52UDd|3D4RmP?61iwL;?fTUmucMx=Gmv$L} zDFuNkW4Q&0&`h~R5YYB^9#(Azp^eGFjVdvNG~$9z=bV28ab=X@U51ver|uzz>R;lP>3SGf55Y@C(im49?&W)li(lpbp0w z49MUNu<%{=1$5{23+t6sv(aqLln96r3ZwuG3qHqA3aGsH%o@RLf zXDOCvsStgD2r&P=QJRzYcYhf8 zay@llfe2LMkqCOwiXy0hgTRUYkdHHGrr$S;H5m!-rnHC%TdGTbzy@zg1=ThO z%b=&rzzL)94;D5EL&y+&8BGSdSlt3|E2^kY)SxF(WDxqGOrv?IA`XkHqE+~iHIbUB z6`}@-dt0^`IRRUAW2vQT5rdX5o4OEO28Wo5IWLO;g{EbPC1)5WRTMm`N__y9yJ}QN z2@AIAQ!z;p!a9?S_ab?fsL8|-kQ$-dq7DzMpsg2jkzo-g%BdlmnVNYyqB^P= zdxSsZ7Z#~pu*$I-!LkRSstLCk(B}!#XRAHx1!ei3yvnn%Fmn)C5W?zm!s?`GiioKA ztM%%vgJ@JlO07p)q&;PyxyN&_Mec%s$K(?BI3ZSsAeUJxs>j!y|w}wD=offCoN)Q^RpMV7kY|sRRzzM|Q51Wt) zhWRo@fNqeGumsAYiE6T!YZHxH5NLn~Pr$k0M6sAFx&)%JU)Hf3`+9b`9jH5I1|b<9 z3!-5W6u~#T`oQbTL(e}RWJorPz4ClqNAyhtg1$_i)gf}qX&bt3ZcAFdG5`JV9EiumfA2Vl7Rxu1eZmjo-Z2GMTg zC=wsc!=;=Nnu`%hfCeT^!Uv)M!aYKvrYvum`nww0sjez5btq7)TX7u%FmIqau7RPw zEW5EK%NpksKRm<-um@#O22xN4LY%vWmcud&NdQC4h(@zEYf?Bnmf9!9U>USCS(Ar| zlT=5W(7LpM=yXuq&e=>6t0?2Gyl?YyW2ZjI& zm{JV-djJ9~4tl!}0E}r;HkIS5SvNU$*)Ry85XtSph{f~AWBJW+DyQdB&u{5r2_bll z>&XFnm!y&egqpI=bIdhu5vc4DV1NdyERPNG$^;V2HqBmB>1DtGyJJ(1~*N)LrG4^}^UK z88f=w&9~Men|lejd%~Q{7H7;~{%(NT6GWiiSdGZ{KG>PT?vP{0PuMz!YKrWQfPvyu(7XjJ66#yaZ|5L~rdxt0WR(n`MMEjSyZ z;J8svL{tvvH9f*=!MUr<+y(K|XW`|~&RCerx{G!&Pc4VAONZUP)Tt#u5{DB7_2$|R znx0a*Jy8XAUgz$;2Vecnd@u>;g$oU|yU3!WFiYqkdBnH8%WT-hRpQNZ4aLK1RFGca zG`XASyr#$N>%59-_Rxq>8{rb(N}VnQw?i?j;R~4I;cq|)#IOv_z#7M(36;PGt?ufs zeg!{p091ewO~3?OAnR0XwY7c_nve}Nnd>sC5SnlY3Ek^Neh|QJmY4#;xSgMHi4e09 z2?AUHml|ASKIAj(j@(z?7pnZ+Jw374ZWGzg^#^s`1D_b4nmK1<<_qcFA`2~sZp&^? zyJs)wKl1JrG4Jwj=VibLsZb56Uec4q_<5hN*5WWu#f+$v7y+Hone_3QUqNLM&JWOlThDBu+s(uV2f*8l+qmAC z^__zERNbHi!nr(M?F2#gBw_a9pG|3B&2>1LjsfVF$u>*T?Jz1ICCmPM?=zeW5TDTh z6gg1P;6a253+iClu%U}Gdm>7aDDgn9RJLr9slunqL63Z%JW*KE;0}`|jT!UT(xtyk zDPu9ELFNnqt8X4Z3E+S9=KKeQC z>D8}i-`@Ru=)&a-&(zYG^PdQB8ocDs*rhjmat|nz`h%&x{YttdCIo}}$-qqDlW;-` zD>P_64Ch1R6I~9-=fe*diRHKq9jYjzf^w-Q6-mfAfDb-iG>8xF4(O<(Cz^=CB$N`I zsiy$>vrju)!bW4U9!w^%SC2!(yIaRA zZxQCutMyl4gB7;D5`}YPn12rB&c^~7OfNqLU2=9kluUYK+Gm~I;S!eoiEvnO!Z2t*JUNkS%ag{z{Bi!#cEj2K_^NX8dy?C!>p06VEi%&t9vNQ4kB&d48; zRMIDHnF(zH>XJUCk@b*SGW5dvEpPZKyu~WtXisC4g@`l`S!W`66%8Q{O2FgH{ z#Vj+~mFDtf4nq2x6TUijPUdGdV`eL%E7tw5QZ>sqyrqbq@z2=DXe!k zDUh@pbPxh9Xh7P6oCs}*nTD7PUh!H88gv0Vb$KWsKU~EB3RW3NB)1b-NrI%p<{a)v#z@kVhUcK6NXaB1yVxC+ z_m2JPuX)d#UP`Q273`JFWRF8xn1nC~Pc(xcEosIu-jD_o00ua)LRIW-)$Swb@uu0cy$+wibw{mF#41_2|NiMg; z5@8OAo6DRDh(H8`6afYW(S#T zW)-Vws9P~}*|sEnM_0c*rdG{**5y#{SjnO$bWoTuG)`2S2{BOO+=|hh_@`ShsU{6u zG7N8`Rao;8Cpj~5*a+p2T$WR8I?=E>&gBCQCO9HP%$38>5kUv0iUnldHJ@We5kNr! z!$PshMeV@oiX90FA4fw8zroQO}P|shUR<5=xQo zFB{ZAMf6UJ(xYH+U@Wx>@cc0hHz;S4HbvFW{9%|(GG=~09TXluIg?O4#;8z>o+gHp zK&P(853LN^L8fYu`_3e6#PCN0uPRso2Uu-f?P`G!;JIAhN^ZJ3M>z!iU_`nMm0YY_@dZc*2Y^tBZFwB*-FS*C#Z43xD!N5scVD8g^iepEThBrEo+kCUJn& z!nU;w1;ZW|+S=}L@c^qMLn>0?h)F#E0SvmGE8*CvB;irFCUI=aQLH3Ns^Ki47f^3gB?6;U~83`7p8Na4e|zQNwlxV7E((%tQ>7! ztF9q_$$bP@;=r0DL#3K$urKS7!n*h%hkY?(WlZB!Ib?es$=;00zYI&aJ(^OYdlqiU%>rud#mi zTuyjM%Wl#^s0|ZkM`yQmb#^q3w4k@QWW+_HE*t&vk8FRtSOt-%3=D7hZl{>A;}o|- zU~Fy|Sk4Wq(1A5>aez$}0UCtJ1T=K8k0Sg-$2`tPCJ50E9bAJEnaG9?Jg4t`IJqH3 z7zQDVkPJo?0vtrp$2aH!gIqzDUGzA^Fm`YYUoZk3SD3OQT)_k^E8-T65XY9g>lRGA;_Sjx(#450Y5_og>`*4Ah~&8qZk&M#2vUjvL40*6Qs=Up}#l)zP^6-+xM! zhY*WdIhI4Tm7*@4xGqL}51LDrO~|Q9%P)lJsh$I>0Q{-PC^}Mm3`2kdJwdhbaytCN zF9=kQs)9ANJ3$m|imvmz4nnXSx)t!a6>%_!6s*AsQY&O3Hs)Zdyi2ydI}VCEh`M^V z=Lo_D0WoXaK}A~$U;qX-(1d?Tmc$~R!aF=GM7+ckEW&Cr%y_)Ras!932OVe!&ucw? z!Z954haDTk;1EM~Si=#ZClgqNPY|LINdktb1u`fCYX}Z#c!G2Q5zW~gdWeQV_z-4z zfm^tNTc`;}U<5_~AcQwigewcUo1mge@Untf2aPia7|FgDVJ%5`h15yEQb-+Cw77c- zzlDlFoR~i|y0gZ4xg7{Di_wy$ATBF0sf`*ym!ri4lsQy!v`3?mNCPiQgCF_1G^ObS zR+=9}a3w?FxyQhR1K5+c=s*vow4F*u=h!b-!wwr9M{+!f6=cEkI51ukhjA!Jchs9< zBSIj=s~)VjACy04Yc_c-!o^7#1A#V0rif?DVT z9e{>g`G$P|kOx5&qC!-LGkAd*cmdAgfm={Sl$ZlZoP#tVI4m26OE`mNkOVGExK=2I z7qJINcm+q01cj;*I7>xTBt;fs#WQOPSWJijk;RY$uHX_tS?V1lM9h}GD@ZDfMD;Dk;f1WEXXS@;DqV1i#* zg;`hyNq7M}=*(Zx0w&M`%q-10I_QOk9+K}xf4PcdLe7s$F_`^YcYm_BuIm-&VqzOh4dDOa7cd+faDiGl04*R%9Z_0U6K%&BCW3 z(gqIEhYvwe1pN?ts0W}7N`wHN7Z?UcTqQ_kgr+nCV%ULps0n_s124l$GFS&0$%Ysy z1l9qw1DLG?m;|rPh-x53TW|!0Gt1dYiL^|Z`g_hdnwUBIBjs5Xgy^G2uSdQ*FZH9Of|O{ znt7;(Y50dhC@g7~t0 z$s&YUEfuv+EAz8dvwSfRP&6cIT1$o6r=5Wr@B#7vmD*%!2~IFy ztG(J#O&hHx)$Pd0OpviarJN#=0RTM!Lb!%&AOyn$9Xt5Wtt*08V9;VHhQGT6W%!U! z$lJv=0?-KrS5(rPC^I!Ph$`^PHLKAp>KBkmGcOXeh0+mvRm&ZfVB!&(;_@?tprc%@ znmbA^%Vn=4Mbhj^TIlp#CzT*#tfbKu%n>w*_}PM_t1pH4;e&7lWN@D5nTKE4huoE2 zLP%LDevj9T%~vx)=*?mal3ARI$Xct}U(#YR)-wcimE4i(qpMP+$h`#}|O)e1PDD(3Tk3TQ#$TFGC2w-52d((J)%k8HpWM%$*E7 zwmVZcS|p02=mS6dW#Xa=qezGshGA+b29%p&yR2c(UDBBQToDT036WA{G-8AR!Q=={ zls$k^XbC5F;$N=uFf_1ka~DyW-$U$hG6RdiUGjDL`ewT59Zr}Qc;Do zV8e}IwX`V5#i%&?$rEDmMjww==TVY>>p_dCrXy&CI{>v$)(&+dF zDw2d%P+2YDglcexP6&pwPK5&i%{Y|=J_%k437e?f8LC@ndlut&&YLWh=XvgH!oESj zaRWBa7BsHjw<_929Uh=vi71?GO*nvqwqu1hiH2tAN?0U_=7BNzV@?QUnHc2tO%<(G zj|hRW1IRr=D1<^F1cQKIFk}doYzS8Xj)x=!aL9&aI6T=lyll9JY>)v)Act(o26Hb@2q1!qH;9SCK(MF9u@Y33cE0~P_?3ijJ8(hh~1v(qvN z_GY++dV<8&(csZ)kwf8LPK96y21aOMH#>?#*l$MgWkv{wRY--)V1!@j1LZ-bK?^En z)?Aem?`V7G9M&pnhL1=qjJ6m|=a7V1fLG6iR}de&ICX2pm<1KjOb>sL;l1KJEo_{v zAR1?zVqBHP+fzQhSsCx~-^AxM2FS%`>=x2NHC|HSnQSGWZ0f9I@WqVH)?+>TE*_|I zPH>)NsM^w2-&V0mE=*)EJODu$b3hOTKq!QrA-BgXgwmNYH(-KWkO99S2g8$v!&?S+ zkO59u1Csu2l6Hk-xCaES2Y+aTl|BeOhSq%l$N?Y7Y$0L>P1b~j{EweF#Mt}f!Ktq3 zG=_aZ2i4gFHFM>I3dPx>;J^)a5Pm-$O%g(-aEbAPUQUXP5Q9GW1*9nORJelzM_ENs zgaz*dH}iv3D1={71n3Fa%$0Bx2I!dMO99L9_rR&Jwq^+tkjSi%+XzQ2_Ho+04lU?Z zakTLpua)GT*?G=QZcq1c0dmK=<%0?Gj!VvFGje?FTx(l$d_SrtuTDotjwl!3HaG_T z`MW-@a*=f&EjJ0%MwR)9ZTRTg18{^wka&rIZTQtlhA4t|yoQoa2N?*P!(#$@FuZY) zfqk&TYd8i=Zi#PifNMoSgi}O^-yQNR`(Rd4nY`)*@P8ZDg3_%mvYx}7Ia>} zZ+z4)W0yEifE?i=gm=E{XL`?G4`V_~mGpeacVH;UCx4EAcj$rV<0=Pj(VmHgr;vu1 z5HBPIijVj)cZ4$Myo{9Xh%^V2H@sxv0V`CKINt<5pNBPA6H{^?egFrRUW0q6hj73I zoA-f&sBV#-ejk8VNXOL5=7$9T&If5Y18yPC5CfvNi7#W$ta&r%&Yn5z2rYUvX*d2(UrNk! zrN%d>U;8t5DK%o&H7~vYroD4DZJXIPu|{Gy(gkeED*I#}NC7E`53>fBdfd zp9zp4!j1~1DkMk{AVBhu0!W@XGVC+n zE#;BN2_f>x!_Pnd>;v90`?PTYH5uhlPd?1Zlf!fx`H;f_`Q)>Ph|)1bVh+WzsL3}Z z(t{mrGaBkiKHF5*kVgHZ*0Vyl{--3 zMMiyWBvMFyFjC4YU@p{)EwGsJi$V$w5)31X&n9jpQHVXu zsFKV)g(P7IKet?S3p>eV0u3(mTmx!Wi)FM38j}$VS!KQ=o2;_SGW(f&&x)1_YPI!= zl4~=CJnD!f zkB9BpBOhS@G>K%AIu2=vB&k%BiX@U;o#VJF>8WK-cz(1BBfkWLOfbPbV-G5#9MDTD zr7U#7AirpI5tm)E?PW=O9&q+bE}bS*vyb-_)TV=OGE8<3u}>{R31ZJJPb5KzJp`X_6AZ%#J8ZGU9vi&!%QN46 zThKl$Ex6QHdoQ+4UqYo?w$b$M^e3JD#wEW6hqSut7QIou|2PM4V)IgGoxS+#+X=s% z_z+u!d|TBN=NTM>gK^ z8k8OXqZ0dwjx5^Y3lSmVIT`7OKJ?KB>2M@OJIja9fEFTMs7N|9;K*=D6pu=F z#FY*pBqkk(YX|5Nla8dd9|tehn+ zYq>1wsYiPL&>pwO1(WNY<|S|7C0n?+5ypWleB(3MxejnX^vxhTHsnYfDgiHRUIu>u z@k7}G@>RbGabgqx(%*OjmYHWw5h@M?3n2n=fItwUfDkko0}tRp{U|IG5d_c#$Fqht zB!d|HKp6;+Q6UiBj3X(^$Gkw4gE5du8X>~a41G489kPK9nqUKon6V;u@k2I=vr;;j zXvD2KQHw)5X-29THe1+1i!zNtwX(D&ofPf>aa=_(oB^TJobfcskQ*9Nfs9q80&oNg z#xHnU$B>kyN_o^{O!{cc(uIb9oEoH3q>{Nofeu?tOJt-v(I`t{3M`_!DqGw7luT-p zbxEj$JOc3;Gz5YjZjcor#KI3d2&E3}SfyJtvY5sgFP4)jEMpt%SfAjsG`T7Nrj<7G z%hw1qT&n4oxV%Ti)rgOL8O_Ku)3rl{;%u54X&E-L`95vZ%R0w+4*m4?o$QG7Cgd!q zW}a0rgAt+-?0Ll+h^wD?I&6Xa!H>fDvrhnRB^mx8hCqoyP=mhE2R791b`i?mg?b3K zP9V`Ieg?A{_RK>q^MOG%vQTFd2RRS=>}tTU2PJ6)NhuXl6r<=hD`Jrh`Aw-7t&}#O zh$JH)*$6Bk1fJ`R)gRfQ1}q{GiNP^sP95pPQ}ZO%JPvb@R(-6mpam38AxgSjDI|K{ z&=p`R@{yiGtLWfD;v3fzuA{P7CEb|J9xn53cq+`1TGRVJ~D z1+ryuY~?G{GP0wQo@UEpOq6H@CbA*sY&gRjmLQY9A!a6NOIw@+oR%iil%{GAV9o4m z*L^f;g9@_(+vtdJpc$zxcW#Tnaq7>UiSaE>5Xgu^{BsS2c;q_uqmg!EdOz{W*mCc= z9|!^n7p}+#Ig-MO=}u@Lvo$CTai(4PZCATF5Sm4`xds@SS7#*R#H!b;!x=2}v@J^H zY*rG3!vtxG`qkP>5AdTUR`H61*$9DU$_JKo@hKkZ$Q^1Di4OksI@Bmeg)h93I$@;4 zAc-m-6&GSa0T0WA(sEX{+NeRUm{I6?F>E5G5vNe9Q<2o?TIFs3aLDO+$E?GvJX)cV zSBT>ipLmDEGh&ZGD4EFxcPsIVH|5AA@8BXIxw7aT8tEBhGhogMF)=eP?-}DC!D*(O ziIYB_aF@>1sRX@v-t&y``4}KP%bzRpE_m(Z0Q%y=7z~Z*L|^7v?9s?N2@&Z?*MVV` zh9_|e(RFwlFoIx7*nXB97*S^!9V-3GR@T}JI%E7ERREbs3 zgJ$^%2cBJxA`%6Ghw;?}YHYNF7(9VTMS9{AtF|N~e$62;g&KjYU0{^hRKrB+Hcr0% z4t`K08|B_ooosR^Kir8Vh#M)0#|LkcqsQdx`4m?<;njfubLPd%ASRU_32@*yYTz1g zGVYu2nS`f~5dN6G6*PSsl(_Kl?GGdtJ7i zS~@B7Wy1H8<@jTxH3!1Yi}L5_WS86l5kV1@p7|MU@mYjeQ_^`8cX$VQ9GXq+mZGtR z)NO>rJkr%g8X;6#A-K~4VA`a?Q(){9MTgLs z7rGROCM1$<>;Tp{Q54n0e}#?LP@A%4%^GS=mJCk+Pi!0M<%ET0LnIW1x_N}`eVDtw z1faCvX6PPiEDNHXhNS2lXT)D?fM7;UN~h46T2ay;O5#~SU+M?~Igo?HeS$VvgEnM? zHeBDtRonsa1NgmyJanJ4p+O}E632BMEGd@yP2w!lB2nm`X-tb|tem%WnOTI7OPGr@ zC5LkGgC?9$oTXMWYQz@C(EqX5-;tvH5FpAJ-~nn=b-0}fokjz0#{>F9GK3RN>=ti5 zk9rWyI%$Lk{!`XDjHR{H0T9;+hF!+!(uFiw%Rh{9S!9G z64XSCFdjc_!X#|XfGrUjOu`ij7}sP?N;MIZFbR^-q$A9MoDh!db=$Vh;hfmv=;7hv z?4kYbQM}dSS_GnKm`>#o(jj_E@lA?VfE6deV2#;WRElLyuwubU9QXy9#A$?DuH{Cc zB}bqE8o)p$;+U`yi!6?1Uh3uhD+0pji*K-K-z z0XTuxwdOi=s zNCF+$)2s65AxwfmJk_^d2d;8Ng=rgua>P{a0ORnHu!gHnRHzQHRf=8ZSAmLBbiybg zYlc<|CtM0xjz!vHnYD_=iF!(0&L#BmZQ&X&vzQz%eviwg1WvrfxzgU1^r&#SS<&?D z0SFxdhEPrT>%YQQWNHMYF6ni>D^GX`%m9tu$xEOugTQiQmA=3W7{LzA#xKDK+MWfY ztrH`x!2y`;7z6_U@cvUE)WJGs0xoOg+{s zV4CfS9d1sn?PK8^<|ON&_=852)uMckS9(Pzq)rLDmESU-vSh2a+Hep1@Hv?rmjNbA z(8Ohdi*BT={*{*H!dgbu3jvlcQ~)dx(JQ1*qg#X*poSMVR>BWxBR9tG3;ZhW+MYk$ zZUw4GAsBD}CTxT{u0b8B!fp;j+DRBVtV1%4f?hzaHfTF?-_yUc~V3*5KLk_ge5ypf3EJp}|119(Ydfo2#`*}4Jl{_qK3*|FMfqdW+`o(5Urk0XJ~z=dce{%|GXa1sD68_Sg$eMLY`)? z$kOyiZ10|KYLQM8Ypoi1vJ9WO&qC45b%bZmkn%DLO{{sBNYcaU%307Uhq(a3|L}nw zkO3devO*j!OlA$%WW)n'%d8T2O|_@^WQbAK`fNYrXF6SOkdVF%O1Gkd`nfbdlP ziA;EO4`Z{)5#rmfuxIewA$_x{HIj@C3bg)%B#CG|lTJFf;_?WtJ45zmWA;Y}@oOaF z_VDP8SPy1pj~@Mo5}yy8*~I@1G|G6x0XW0lyqXV8!Y^o-JFNoXXxA^y!fj_nAT-tg zFHC}*DKs%=?$9A*ldA5#U}Gl;fhSChMbpF$NcRCqcS=1;;OB>>2%S+6VH!fy)XJ>z$3Yzz02?4Bw@8;rqDBVaYn z7D35R2(ea$9Ny3XAl*GwN9ixj;1Gj{$h`0!iRc0YAR~c)@_KdZERz9Nhqx@0fkH?L zOoD+U+~iqLZCD?`O;&9%uXTR{f}9wo>7~pxj@#OVsh&Z)Nl(eXni z1Oqxe2r{4p&mF*RM+a>K4Q)?CaL>6r0ZvBrc}?`}%~Z#85cqZAnQLtXpRGAg#P_vKB9F;3vZ-Zd12 zC#0fxIQ+~2R>xG)YIRm`^#FoEeZK*?X8~6&O-uqE1b2Vh(~S2gG1s_8;J7sIxP@`a zKi)iIIGCMnBGoymvf5Wx|No1Im1hQ|Jv3l zhjK}ayHLxji?Z8PQp(Do_>f{0wfpZhtZpZw)2IH0lGhro-X z6X0bQX>@d|x_F^KOuBPd`dSQA(QA7443jkPi8ukst7pul5ki?}Os&)UEu>wYVsB39 z_tB4Rua5x|c>KL6^L6nVo;5l}Mf?9crc*zrrZ$vPlgKF?EJ&I?{4jxti?}4nvK_dp zBLIRe6hhLb!U52MTGs?wAHX5>J*@VpoS0s`+bX?((Fco5zDFp-_q$#WlA-{7@HP4H zF^r5Ad}cJ_O^~xWPds{%MZ`Z=WwT=H!~R}wwvD#M*%5hYvC(i?i?D&KU6zC*Jhf?{3RV-4U1AVx{^!gR%9kFA{mKE!T z3fLWM*|v4N_Kh)r!-ly5dlzqBy?gog_4^la;Ji8r7dCvja1p_a{~0%S{P;kfP09Fi z;=}|q6UdA?EqinKGa-_hF>n4#y0l+H#Qe41lqpGU*`{gNwtXA7ZP~KXo(%b7QK{yaBg={hpC_IK&_TkUeK0|Ukeh<8mufXtYIn`Zi%2mJ9nw&vG5 zZ_nBXtK@^E5BMa1t(q0+7nmkl#V?t>O0SapW^%|RlK44*p9m$KP(k%(!0)`f$lH)Z zAT;5}A5Z3(!;{vqgHAg}Hd&FyOICD|#Z6qv=AUd_xh0!yz{%#8zb^R^NJSJ0BM2lm zR1ZlXWbs9oHvV}MN+^%;N%@&e9*E1bR zpd^_}Do1P~Nvpuj8g(o$&{9jgRNsheuDYOm6;{5co0YIwZAETHe=I}oRf9hY2LX)VkR>rON+ z)wWiZ>pSqs(?k!&v;|LWr53mk7WJ8nIJQ1Qq6Q4_Q6Bl7@|CvQsW~`AIV`${j6~BNCa>yA( z=J3Mw?mgg`C*S!;!YJFRWDHEkpa!8S=aI>m14P14oE+A0lb3|3k>$TNoSEdle8TzV z8JT_w1f2u6iKY#72*D*7dDi&_9dwYOcO=yf9;9%sZ0|4>qaKoW;ORO zzB*)aOMw!MR8mb%>#KIPd$(1)${qc&bEhL6b-i+3hLbl)%a#*mgC&+P+WUH=v(}RR zijdr2gEsZxQAgw2;;$9{x8Pvtwm9USe;)ei#WlUK>aKgtbGG6##yfd8JnxtY+v5jc z+tkaCre8Se7ny}CX)Ty}_W7j~{(e{^;sa(`{}|$t@+&YV={dmAXwrsC{Nor2sz}Eq zqzT6SY(pRNM>FPtGLC%v=EufBeH{H8Mtz`m(bh2`LOdgW%6*P?2LCAY<)` z(hOY!k}({h64_`8KYZ{Gn(!kbJ{Sj;^0ALk$mte=kO?|w(S{r_BN*G5hJIQxhJEDY z0PaXfzvg2PZ#d&6fd~dcf~c>VETIiz$io`fI0wQNu5pKJTu>O7ic%287Lq%JR1RQ= zqd1}}iwhNBGB+wOY=LuL$(~!@a0$88MRd}W9`z0*N#{wXHM`18wn8&IPo9QXeleEr zKEsz~HLH1+RONDrXFOLLZ*qDAVx`!Q8#}~BN)zj7=C84ieN~BKdTU@!(x&bGvX&f20TW4+A}4g zwE-0L0!Dir_`nsGEJQ*e(FK*G9V)D7gEH#i2WzCGoR!doC{$sG4$vVsJhWcGpcg1) zI75pb0~|L*$VCn|68zYMCdas84!}W@eCUH7Imp2=3gv?Ng$^aHcRjuYvyt5UPBD>05@aHcLit(` z`h1WOWx59@2Yixsl!=hV;OCqbbKy^UOCcW^Q-xsB1j#rQvU`Gvf)?awZanwT6%CZ2 zIMa&>cc##v9RQ-BI0i7-;}wZoXF?W*k}s5*4V60ZBOf^c5?;6unY@rqO(I%8=n;+_ zG${w;c%~2J5eQ-2LyGIT1?c5@V`B3r% z&5Uh8CdZ(ZPV=p{nfn@_q23pveMqRbw>4u+Oe>)^Kj;7w{mMhT2a|buXhVaZ=WxHW zLLjhVp7~Vnx@r?lMhq0F21RIf6>)|$!vUhj*zTV@hF$N~i_}m8$pBv>iyN8*6C|lp ztZ^s{B~cS$vLHw_xljE?IjPwSDoGCvB&7kfT-OVpuNI|1JDc7^OO*Ge>R@+%!`5b zH1u&NSiyaI7BZk^)sv*lmxOk@=qYC)$Kut{4MCb@CF7V&@Zvw1nBC-vVg?x#vWA7V z!56h+*5@?)Dn}fQJp!VXIs%1y^5D zjRUme86p1T|5Z1|g+UzP-SCESjJad)jW;LXr!SXeD5FV$-wLSRg^=!)B^tbp65*x% zjbWLrWz|csIB57pEC><{T}(W(UZ!l8f8TuPmy5H>n5{8D3$KTQ>@K-IpjQALp`z(L zLa0q(p7jjp0{WvQu|;P1_(6Wb;1*E^oF`tqBlM&@+B@jqIzQ;ObO=J)WQ0JuplqO>5_KzRBuIK2*p(gM<&@4$zjqKX1E@eG42SFh za4+GML&**cHX6mF**9LVQJ4gz)Y%;Jn4;SU7QsZ9vt82qIY2q74> z|8X7sVIPzsADAH)NTLpA;TME~AbcQAXhIN>aS{lDAX*_XgzzhfurCd13DFHG3Skfm$qL6T##n_eXsi%TqYG1#Tz1TL#!xwe#jwthCesk8SSJ{tW8t19 zu~<@CienLUfv5J6D2uWWkuT#c?&4y@C!5kK|ALoV14^!g-Xy9GO0F-M34NN$5)o!5 z4#o$*Z{<3sC4jI%Jdw590M90-6us|#P*D}n3Ah}s|6)<=woVs)ZhZ1${~U-ekxKye z=@(H&-rPb9exV6=fDC?tEd=2n{{a|sAr*iC3RYo5>@h$NAQ)`HMS`Iegrpns|AHJD z&F4shLp1O^%F!Fq5rWX{1K&{+k0BZe;$BRmU;M=-^yBPkLIjbdsh)}xc8%K(V2y|~ z5AZ@F6Y(FY0Tv=56sihwdIAu{DpEL-D4?Pc%zz4A43VzTb3kVpG65x@k}+r6pn%M?MR{k|f%j0rCiO#;nP9Pv^#ABr4*j$T?c zqWq!$1dZwZp@Mu-UA%J#nm`NILJMXgE`|XahQaH8;b($j6RhzPO5qZO|6~=?04#it z981$HuIuNd)YJrRHCb~*WC0a4K^)GEN{S(eKv7KFAtA(}BF4Z6&{P&GVjlPbB%&c4 z>VX{kg(bjpCKl!ZjwlD@AqU7o1o_klnhGok0vq(AIFGY9k&_x)gBr5IIbkBh+$cH` z=W-Ya^0q4T7>6t1E#8O`0pDuI#xp_v!aPfrbn?pegrzpx6D;17L2oj44nQ*s&d1&p zmFN&vZ-Y335{rhCAQl12NMiW(5J3B8K>e^l(O`K5u^h@_SEKdx7PK{pq0N3n`@%=O zlIdV>4lPZt&T?}UX)ZxLrb1W|LiGY2P4hIz1G`SNfdXUX)^#-f|4(Ef4XAq2Mz7-y z+6oX-!5O>(MpMBJuD~*(U=|!fU`l~rm=GF*;Tm=X7>Z#Sf`J%fbm)pU?m-?7;2zqc4OUhm@~aZWVGQa4 zrJSI?PO2W{0VO^m8pHrB)`%eJp=lQnIYS{5U?CK&7Q?#jjS@$3t_qK;p%l)73O;q- zgh^B(Nm>EpRMR$9!4N0c(=l8%F9z!-gYgYSqsML)s5XHoF^+8?gE;h%Sb=p|Ndn5C zEEYb&SdUdes|>P|GRvU#Zzq?_sHX_lr&LsjeK5|IMk|Ko)mLo3mTTwks&6{s~5 zq_k{fUfdNXNXGsgqqtzAp1el_pTrY#S448xM85N_(4iWfp&Hnr4km#zi4+Qcfe`rN zZuS8koZ-%bfgQ$2Z_vRWP)njp)6o)*BnWMu;4?MV6$ngIWE+YNKmit@U_-@zaI-VmPn`CXUYp`ZF&I|2J_LwK6fe<67VK@c2a76c)A$M+wC0Ud(D8@vIVykUC1 z0U6Mtd(Lrti!12HGJN@>xW-o<+kr#)p=6POhd?oZ%W@&wK-ALEJ+fg92>25)0vvj6 z9@g$13izb*0UN}D6Y@YDc*>+4IK!}kn4>Bbb^#VP*ej~`073zSsR5f8Bg623Qs?NZ z=zt7LK@=JkR8e@wtoY07N}Yv=_0%(O^@4^$|Ks3pST8Q)C1M~>QGD2bzKBI&md;u7|p&H`l z7v`W4QemlsK^hfV6aFDSjQWy)p&I_7V&@=~GceG$H9|_+p2!0Z$iovrc^}9F72seK zWuX{eLM?j>H)SG$<$=C1A{#hC9@dVo^C6f|sujqAIH_Tc#9@sbk|kbj72k(&lQT1KClwP%EWzi2T0W<-YYR$LCz}KH)57hL&X=HY|vtPL>XK9YH7eE_AHK^&Oj z9_VYw_xc^2nSWt{B$64KqpB5(|8i-aIUjaG9Nyulg_<9x`I;}7F@$jO#NZ9$z_ZCf zoT0$NTX(b>$t1PVpKnYtp8I+FZOB4tp25Ocp2VIPg9(UiwgC$|;_!#PrHUgCK>2e9 zX(=yu!vu;z_<;5JNCE~9Akihxp^2EwBpS^ly;mp+qo-TCS;HSXfd@DNq_ew>CD8{C zXhO{UV8~C6KRy2RuM*DV>x53}=p|nLB9w2M)HuebH)DI*`=`X%7bXZqvKOCxJ$#`+ z-JAj@pdfz^K)|cP7={a#jTZ>gMB3wkJZK%zV;$Yj_#__-%3 zS2q505Bc-uV_^{v6efUDC>I(m3YXCxI>#2l93Y+JgZ?=vsR%56y4S!uIDrSoV6c)2 z)g_UEWT^c@mzq*BFjf&sTG4@Idg->F>q$Z!ae6Q4vYtNIz3WnT?R8$nW4Q3?0GdJM zdXBepF{iUmLNsRA@mt$HoZAiUp^BjxV05&44j7Wg5ntk*{__Bsfga3K1dUVS*+}4t z@*aR%!zDz@`6BY8|4IyyK&3#GCd`B4GaRVGQ-!Ozt~OriElE{pdoM(O_n<*{IH40p zp|x+two{31WkU~*JF4j{4e2}SILy;5z0_!aVLkz9#K^6eX_jTDD?Zubkb)A9sIR3XCf_jc5 zo@BHD86f!a0|ly>KYp4HC|t;}p~HqifE1{Numk=$ zvWd8mjY)pM{_*<<4A{zuGkoaW$)5kv*UkMd_H*6C ziyu$Ey!rFx39APzqrLn0?m6xAJcb94PM$ULtCU!+|6>Q}7vO*j0m$D0$7JMDC6%=C zkPip=w^L3eL4;9&AT^YcCKYOekw6?}7}7{1eW+hXC9&Zbi6kCi5-`OS1BXHU+!PT= zpah{~{}7;Th!{&ExuuYbCW5G|7mE_r1(Qn^zL-)+FxfN_i8)C)h8S%`laE3{ zwF1WhOGTqlC1N>64?V`^L)BGR3A7bnX^KS_S_?@iVH-77B^P>t2CCP3>lr5Kp@=4m zsAQgvmKhVAc~%)A=8eQjs_1B?Z6XMBik8|KZLvhP2ynaw^~rT@9+#X6 z%q=3+0mwzA7z_u1frfS31$&*Ti)9BMvB)N??6S-zM(AKLz$dK?^37Kt51i!3;64H! z*q5F>$#f!u4ffPv8{%dplT61j2(Axo&A?EF5CLP_LndB15|WzO`%#i3vWVn~2mv`S z{}3WJJa4{>TW2jt9U2Vnl2Rbij@r^Z1dHcTv=2kOw5Zki7us#pFW|qjZu& z`?}~aM>B)mFcLf=0Y_8Ov~oaktt{mrr)iGHW}ETQ^CnhWMG{J0b%u3kL+|p`MjOXi zmCPE=b{*QY>Uk~p*k0GMNizO$(#bL?EdyGhmU<>PrUywnnx}%grfF=<*+w?A%|*p) z;6bf=z;B<#LR_ptA-4#vi+}leRG%~^!$NidD{QcTH>BOMorf;^=%oJzHek_C``%>x zEMuR2#Q3vMB|lWc?S9|txlp?8M%YFr5;6#&Mji=NJcDiM#MY7(Jv4GiCMMLd|BD`G z6k?FgGgKr(SLz${kWv=hFc5D=EF;GYSqu}x0*%=*#|0f^GDH+D>0*i@kI!;V_u5EO z`89#qlNdI>iY!5A2hf8;!qN&eF@z|b2-D7%!U=jXBUV$nhd=(I6|Q(?FHsu{9LmCw zs#)zAS*r>$*6LMpBOw6sYFLLrfXtZJ#1dGBPo$<1@9+U!>rR=PMKZ^=Bf0DMD@HRYzM0Jy$Fm5{g>hKT5>^=n%F&K`6fbLRqZ?!Ak50@nTcx4hwz{<# zorGj3!1E8f(nTNi5gEMm7P(>|qG1klOU-a(1E46t9?%$I%9%ry%2u}q zVF`C|2wmyg6inS5qd|)FQZ3smw?V`ZC6gCfsMT-e_^1EYT%CV3Q33At2 z+}l*P#yCc!X6uO=&%OqT3*kg+_DNb|foh0FG-8hHLYrtNl!*`R3$2nsIU=|gqFo%% z7cF|xM1@hfOAfP`+ZjWVPD{Csnj;TlH@hFW*>)`L&r4aHJhfECw<7p&=8FwK5|?jdvK*9{hmC0W92#|D!~O9+iNFg`c*-uax*9C!U&F zR_udvzSyyA;96vn`yNA$88J7$wzf&PW6s*s$O?H>kHsBsa+90L-#)ir{)t*8YdeWc zWbIy16`dxlD$9Z5t#7k~o{NHc+W-&vc-%>C`Ortr_}Rxk+Ti9N9D`c`qOKpusgprY zC}YJt5zV}dQ}7DpteMobUB=fk{&BY>02|+;8;fUtM0&oHR!A#bIbxVwwPRS#Wq-|E zG64^`z#tp+_w>bJB^BMRZ#CvaWF2c-BUNMkc*i^BArD!|;*X~|fGmg&7Gop3uv1IR zim~S64XQBOb)mL8T_Es5xwGwX|68{^YpTn5|6APl?B_zp%}>6Uo5+hXtv>+j?j_T^ za8sTQ<@mzdgE~}EU)(o#DC+OHTmJH_S!2QHStUc;NJ_!$ef(Dqf>+l4m%#v2XuofGW6x{|<3nZZsLP<9YTm2C@@+(Zvtb#TVd`6A57& z>jeakq z=$3$w!EP2vTuJl^M8HH7)qzQnDpunZaL8IqWGlxT^+sENQ>l854ndWR^k;V29^isqJg ztMQ4q@f!YsWUKg51Qk)O$au4nfnUNzJ{daHp^N*b7$xY7CYhAmCXCZU4Ax?d*rF|> z7iSM*f6vGk|K(m)B9FfWXdxFO)`&e_WqWNEjUqR4ZsihD7!wXjRTa}p2XJW(0SEW> zd^7S7p}>ypXb=^{N^<#-{{t~GIJXc1IcoaIk4FeV-iU05nKf{TEZx4E7;#+2}ZX8r(`bR;{_wTyb?j6DI3D%WU^_9Xo! zjWNS}d6qI_*;W1m65N zpqVCz#cX8f4;xttW6+xX_nK-KfV8{+EJnVWaFo8{3@Ob|Eg@C)m(45JVXf}jPz zkV9triIT7im=T-@V5SOT2a>=Vf|s35CQtU34^Os%JlRCAwSh}SLqmz4c!8ejX{CrN zX72eOPFYg&IR^8wA8ytLd9;HEATM75imIO3Z9=DI26lkubqFJdB zSdp0@iar)+F{|qssHVSJAsRvFYSF=W$^2l;Q=ny)HLTxF&@%7qd#h;Vh}W@8{O zF*PBWT54{{pBlGw2$Oqd7^r|d$bO5V@vMI~C(A!a(*OaDFjPjW+&*f$hw;wsHs^LhD)wokn z_^AmKs!$RV{-S-{7(K%Te2^x%Un^-_IEH0gwh?0$W?R4dI}`kHw!}KMW8yx>2We#3 zqubS~E2?uglRc-VR1sl^u|}gfswsL~qYU9RkpKyPpiJCq!IUY4)bK$e5y51FxJqG> z|M!<5D0D}WJGq);RQ0H)5sx~1U^ zK63!KYr6-KoYN_><58!*>${}GowGrUwMAogA)Z$Du~_y|L)lx->s#uH!)Q!8)BB!s z6SFew8MK1~&5)|zOCsA7K%FX<0BRANx)E|qv@q8lI zzcg?Fxyp`r>6VS0Uks6cJ&F+3*Q^Jzn3?JpAMwD(ga;dZqoF_znxZc8rw~q~5FKp6 zG%CPXtcoA!eYmtomE?C1ZkoyBo>KR)D!wf-*u{pz4`c7&5%;5op|GKHA zlyQ5&DBs1rLhdbpt}nJr>j7*2k;B%VX-$EI<5GM^5(I#SZ`n~vc;vmW&FI* ze9th{vhYDt)+?WHKvJF{1VZ2m`9YvQMG`<#C9_0o3{#*077?3TjSHM!+Q@|aQX(6I zF*Oli@3RnVD=v(TX*YKOq42dEI>|Hu3VA>SDB>5GOoqT3d>KuuiW!!nd?O#R1jod5 zILdyjJT7{hK;!xllzGdX83~DyKzqS-O#x0zpsv7t4H~%&4EF<(>nCUjlGGNP(F+(h zjL%@r7-rKbSxU{gp#|hT&YX}5*c=S#K)V0XDdsE*cJKn4@e628&Ug(s|Gb;dVw01J z7lH+ai^LnxAc$KzMja(v#%Lf8<`CA99Xjp_pKkmDFR%lcy#tpZH*+8abKnVcEI%T0 zgn%4Y0dvrvIx^a5Bo47KAQy5es( z(igQZeSF2&tM~P*G*S$#ByucjgbgYXuwcqfm&z!i5MOvmupn0>thXV&5XTk?T(Q)V z2?t{E6YQ-g&ZeZpOw3Mt7ybu;_golX9ohQ57h}Cy>ZTiJ>YM={oLVpnMZ6C75Dd;K z3Bm9Judvt4$pmJqyQ{DYFQAe%IYfQqH(i6pej3K^ym-QkZ#CvZ|Gq-TlINV`u-`21 zHSWpJ_F>tXJ>!_Y*`5*50zJ?K?HQaVbai3S^g~NSA|m~=Y9jM#ZAFCOlT^%VRHy{f z%bmzlh1_}J+j$VR99j@tTMUR~$$CLCA@Qrr&8yLk5dTQsOcDgBU>e_jqgvt9@Y|n3 z{Scv`t;gmN3Uue>7n!XV1VDf@?ETBvg+l-ExD9vJae>UqT;C!Y)?VG>kj~%IT-My7 z1*;&O(s{eTunL)=3U3OX+FVp1tFoJjg$8)B5ri{}{2L3<_5EVif~sXonW9 z7y~g96PLTa5V-A*Y2Xdszy|0O2Wdbtf&d7DAP8?21Ze;W>E1DnfD5%v16eC##SjV! z^3#~v7hwJnwtd@Sn5oETi{XNae0vctFia``AReYz!qOp#rr+qq6 zwGoSPXY1G@oiU&Eiqf)000TNO44z>O2QcizF7>I2?8vU{utz}6j^;b{Nu#!XOad2~ zj3OGxmIpw57P{LV4epb$3bud@V7LXp;0QWm&W_*+|C0~~LGbpDunLo~BQ)R%!B7p& z5F_rzvyJ6)dlB$+DZuo#G16Dtbm_JOIerSE$|0<+6i@LMZ}Awc%QmV^r!3Um>J^ZH zw;T@(kdPOVi3cGM1uW8qK`;Z38{bwv2F-xglUUzMe*pOX`$|9al#VQf@CKsjlBSa3 z6}al*!SiD4QT{{60Bh`M#m2LL-wqiy?+Oa6*HKy|6oFz{Qmvp2h-qAo(vuKJV3GGz@Bi5 z`O67s=s<-0G-(0?gbf>DP@`TAaz_jvKLsOE<3}x$p0Nh~;6bbBfLc9m51@tn7LQy! zV_}U&3#%oy1F-zUf&>&OT*8I%h}n2mG1iI4_%-v@=Evk8V~#cZM=aSI!3Je~1|1qS z3>ckFpGKWp^=j6wUB8CCQ-_Wsv2EYRom=;A-o1VQ2F|2Q-a50uMwmK?N6Nut5h+n=L{K|0Ns-J7WymAwvx})bJ923i3n<5l0-+lj8WP z>VT+B(*(7}UId~h8Bx@Pjhz%z@kN?|XfdXQZn~+aV&L$pp`M!JM9XS@N^o*`*K6OK@d;b*3rfK&*zC3^}26s6`YNXw&M zx^t<9n)(MAq!I!Kt2@v-V5~?&i3BHVy5h+&MCF2o8o$)q$*!^5%B!WBkixDwf2gq( z7EBA0)G)*r%kiqIfH~lwX6Bew$TCbP{>6Rp?Jim2^DVTT2ewqS`xHd$qtW%jn= ziaSoaW(#71km;^n?m#6xja=`h z#TUSF^X0c+fBywIwh0H;!3|L(Du_dcGkl}C141M*ViQkPkwq6_R7}trXMBnc99xY_ zlQym5(Iz-$EXGbEnZz?Fnv{Gfh%{DN<(FUL80d{zQu#%rIet07<^%Sr<`-m;2__|f z(6PCiXZk=hYNqmYrrJF20@X+Hdxb!-Jra@&C3sboXTNUG|s1lUVi0AMGvt)KP&DUOwfWd`;H)obM z&OZk|^v|C)4!P)-?P-S1y5xn<&_19;={o4p0 zxI%v}#BgDSjVZ2~i1(iusUCrP%Ec6Cqn&I_MpMC9k7}fe#vw^aJedfQB8VrZBxFcM zx>*of5sX=E0ST)RM9n6lL1e6B9|u4Nn2zQ&XFP*xz4!$nQo$3c)sSi?dmvCK*pP_; z#Y;m9o1TsmIGI=tNd8#Vq;^s_Q|;t%b)g1Mq-Ya2U}5aF+ydWKSNtkik5XpappxKoGer#4QeR4emjs z4oQ&56Y?RCd_-dt`!N?0+Es^41mYHqVlVWD1Au{9uE928rg!mz#7!XKw znadL2cB&_S{{<&V8QkF7v^Pn`N{d{4;$iNP7#P_IRtIQ?Cu$|4fdD~`z6eztCj`fW z$T2i@L}pT7V=SdM)v2NLW9zboEJ1pzO@!oxA*s`>ZFNg_ixj3E4v-D*+=6`V916bRMDP#(4!T%%!DgGagTfGgAl5? z1}+M63oQuZ7PkP$D4zP7`4Drnp9O7bQKL)>S*Rz_+>nPHMoo!XlP8+Enl^#L%@wJ% zCgAiKHyL-6avmw7oe7&mw4^1P05J`d5Je$^k&09>Vil<<1kg5d09!aC7yxY{GJauD zMuY(n|ItmwDx7(MhDHq(NTJ9@5u%ge^3Y3mBHNJqL?p6l(Y`e~fH+P82}pSbEQRZ$ z+)PSD`wj{(gvsKJ?!r>JeK80adzGLdvr`fQ!6>3C&M@3ykbxb*sJ{|zh&zKv5trD+ z2a4+Jh;f$2R04YZB}M2JTox3+B4UEtX*i80aHCy3htL+z`D$ z@Z$;J$p#qq(VcM+A`@w?$M#y0$|TT(mY=Zy>EV}W)s9Ior;H*NDLPTJ1@p6 zA((ZX;%En~tXWSs%3}{La3>jQO^-4T@PthoIUk?U#`p>{3PCveJJ)!^lnWvcLJ%T7 z@rVW?Zc*k%(8I{Fcn5c&0fqzQ?v&q|2frWQZ=x4HUvi$!!31;X45@ZjBcj48|7J0Z zRdk_5MMH-_fPs#qA;TN<@JD!S=7@sSfo8K1#K#H}6%>JU?N@ncG2I z@PZ#4#;IFYSN$Qo8mF%{62I#!lQ0i;p3uJ{|2#2vy&)@ zCrAfDP=@rV2VNiqYq*6%sJVN{hrlTaYXAcpJAgV+r2_~$ds`%6BEJ=6K>$wQwR)GzdWxi^BmUSJ|xz+n)m%{}Jn(pEr;SV8D({ zXu)1QfZ5PDUlhjAGQWTWB-kN1_QSAcK)`94v2U?4)xbYHNQP00t9UpbZFnU+;0xo) zhh?Y(FeoK37>5IRtPxCxRT6{)z=cA10$Q3S87PJAkOyYS2Yt|mp(zMxAf%lQkuIPD5ut-w7?D+QgIORBGsLicSO;{tsac2vvonZE zm;}MlEnonKN7EXYNs`@=y&18GUm(K1`a4lUhoSL@YH)^qpr=(>f`mE%NAO8BS%P0! z0;#D(HIa#>d4_$s36%((eNe<;ph`t_%8v8~AOsVkv6{{))>OPoOho>>JbXow}q z#M9WswWNkIqy}Za#^-c!LbVf%Ec* zVK~SZ#J6B<%*foMV*DfJSg}x1Muf3UeA$+UgU0nRjd@@Pe_#hefPq3thh?~rdZ>q3 zkbz+UhhzYQ^w5WNK)^c425VrzOh||2DG1oi1az@Eec%NcAcR(c0WdHgeaMd!I)I&1 zvwv(rfgDK5w9f17i5HZgg=EM(%d;CCkuLZJHxLm=kOUzB!Y`?YKXiuC+=nqt1|A&2 zRT#;VGzi^dAi9e^P*{kbpo!nIjhDnPQA?U&XitAY|A>EBhhSide=sPT@d6rn1DXkj zRXBqKkOP|e1*${KsL_&8z=SpN5{~pbqyQ7^l81Fr!;Z|lQ1dizC__=;r!9DcD;S87 zFiU%qnPBjOFH#LoEQs4{lu?NU-CMRq=n1hX97ws#)5yy%5{pGiKD2nnM)QZ9qD4Lv z0$OPXelP~Z+>kTCj&{RN@)N%@Mbq`6Os$$K2jP~2;{~pkB`%r1L)Hh97qF6(?uOd?KG{^pg|j)gIUn0h@^s9pn^F-26T|hA)E&o z9X)=?%3xT>C5!_otWc0y3@hxdi2_gp!#hcv|B*3tn1ax}F8soMh&;hqwO!p+Sfc?I zB?Cgb|tIrxW7^@nG0hSZBm)U%1j42DyU1F4&YYON`h)X$a~il9g@TaA<4$U9tX zlNm`Fcw&m;INH_#*7I72R$#&)m<2|F{|Q1=(VBJ8V3>zscm{ufQCn~XK!Ad8TSA=~ z2uGNqx3Gn{Rm$wgi~O)XR{3f3k5w$8$Vzm zn>gG#FbI0BSD-RX$6Xjby8+t$*UClV6-JQEHP~Z>SaWn8XG|m-11ntWkN7AT*VR~z z%@6T#k44ZW@QYp9W#J>{Y(^$1vGhbL6g__NY zX>bNnAOt{&gJ{JWR0D=ou!RE9TxhRBOFo?NT15LEszr|bN zvrE9(L?h+Bbd9O6AeAcW|6rZ~;lg|aXM!fkMdG3Z*j(mi0&(HZl`-mY9Xq8ePVmeW z#8^Ka)Yj;ZWcH3^9={?s;$EiaJ(4qKLfPECGcuTkq>)L8p~b2bkyN0%o)HnLtC?WH zpQ5p@Uf72#WR0bOpqxO8SFPUQ8ZMZyt-AvvhtT7G&SM-h-(6iOf^J_}g9CQBu3;#J z7#fN&n1!7Ag@)$JUwDHc2nIz60z%j>f-+ElfSXcCg^+?SL_oe#cHm-Li%?r$+1Zx#p9F4W=`KCfEd8^@M`p z;xrPGh>RG#-qL+whh+deN8`_UHj%F{a&ZNlbvuNS_`fOP1=Fx3Cct0 zJjj)sum`b|rzPp;8$~EbI0GPv#2^T-Vep5qRYWjxm_fipH9&?Wli?7I8xOoSh zIDl|Hfb!)D+6Gq%Znj8yqMdFw35JEk?F^!>BE#&ATP_Y>Oly8q;pw*S(}-#qZWgK@ z=4)B88r}{c){h;|htyS#vA$UEDLS*Zzw37Iep&1J!HtHLCR&`nx#qLQ#jTKmtwBkd z!`7j&vDF~K{~C5$3bNq|`vT}AIVZ#(il$%__&p6^^%}rt69koKgJ{`m4Te%!ieMOq zBit^XEZgE}!%@M5xh(|d@&n+mZQ?sADjF5k0Pfv}g;O9`xiRjZR<=m+0uO!|AeUvu zrDfDWY9@Yfd&9RRXL8iYZemUr)>(!ruWGCQZk&(?_gIfbFo;F?p7R#eAVwGNfaZQ< zZ_sS=G*2cuJ6Z004I0EBd3_jjvp!f^G#GgbAqi|Y#^+qSyMs`YI!SOXx}d@4iI+$( zNh2bdpaFj(-##8_saYr*AQGGyl00bi$=D2&kNB{=7^n;y71V}h;Wg~??7=$U@38DUAA}?y^ zP7Ubx2kBPxHEZf=Z}KN^(`2ct4@tNgPL||&1B{~wPN*?1C*8AVGcxZ}^cK1^M{{e3 zcLllT3d!c%P}%%>9LUhRskl$t;%_1OZ;BW$0XGPhB5Zb|2tv1$dlrnko2any5_Eds zq&-SW&lAl42R^BxLE(w^0tHl9f;`wnzi3N;AaIkpni)R;HK29kYgz)sA*68W-*)la zO9Y-4?s09lNC5UPf&w~U_WZWKdv#*_$*_2@-F!oOHOF?&y>hE6h;Cn&=x~o{;Dj;! z|F?C~g+%QM^8R6UPY?5^PIvc?bX@wgua5Yx_xYx8J>yauA+$pCcOH2P1`=90_QDTA z0F6L$zi=YzjHca~HU5bsx#!4klTd*4i#iIajhb7FFHpdAhB~j7bnvqj1CwrG+V%?< zGoaaCOHzb+895nJ;d~dr`2!gCX0z$tO9Vgg12KStpQjaC@r2or9A5wiUl=#X;D*T{v>bug$tEcL@BK51Y%JR^eBix0C!Hv9``8kMW{|?Hkb5X7dRvP z^{9hn@CVN-{_@9-_-CK_*T#7z7kQexPV@9LSLdD1ZF?g&GK_*uQ_p;NeuVYWcZS3!t!^#F=iNVQGNnL1L^PoKM=r(#D;$Y9*`1(DH&DFN(7~Hz$(84Q&WUc zOa#a;s|2&k0dQov3W#aYG|4Y%z>!fgFS*oVF-E1-phqflgb_c*)MOJLaKWsja&DDy*?a#vZNi`TqkSXmHY3 zpJDuzDTF7zY69ASJ@vd}GF;Fm9EOEdj zVN~)96x(h~(HkJX0Zc}4$Y>IS&`ukpj5It|(-JrR1q&p3IM(A*L_q}!HN7s`WnA}!~jcoO+4qhu6{j3*VfQXZIyq>{k-&M4AMLEI#U zkAUq68Nolr#1E5Bl7dK9kZi?OS6}TT8&`-Zj|gBHd%5vI03JK6KXA`6az-inWAfU% zzM*p2;fo)r%;TGXKKhQ~th1p#F9Y;!Zc6%EZwCx_G;z!XA_LDn9N>Q-n&!0QEMgG^ zaSn8blfK4it$|6{1Z|el7fzUCffl?V21RqW^`xzP^LYcW@G^%v_#!TIvrDgl!I`^7 z4+xsbh$ff?xPbtphRf<$41vHmO#q`A-l&E%>`}v9^r9KT82`pGZ1Ie01Opk~@I^9y zk&9pi!xn=BMm4JO4`iTYAfN~Z96FSTWBlWC@`6i9GI9Xd?G6iQx_h@r(3a=qOKwY$^y+TW3%vCx6f> zgP#24W%dNhQIhgzsL5HO=4YowEs7Hda3vvna;Tw!rZvnM2-0}qzrXnJ1utOQrU;@y zT{wqSrF3A{>d>{@xT%!ReC8-Om>xHDjW3sB+g_?S!UK?SE(iG434$Ip6lO6AAk<-> zY~bQP81yXd)hHC8Xh}y1lExaz>m_;=2Pyml6rboJCjYn!@KOqiP(UIQAtjz4Pthc< zwA7`_JHVE>1Q(|uW|3rRRo+{O;?q*Q9*%>X* z<1-1u#g(och-;kEd(?v&`4FaYI#spdECL41@gy=+rA*rBhN^!3 z>&v9612+sqFU_2c_d@82IlP6Nm6XZ>P8iO*mD8LA5l}|y3dI0}+=1^}X2s0|xKEx2>eJOFJrF>>v8_= zcHIv8@~YQm@;AR8{_uGOOIX8F2AkFM1!L#d&5=b`vU3wBJ0&AMg18eHDN$Bq(g_#; z3=Rqh?N1y^vSr71zi9SB&Y z`$sVYl6c}!&>>R_JU^IaO9vp!Kti#jBmZsp&2WaJPGG@Zof5=gdN!|5Hx`6%sdv3K zzRyH$1K;?%9gIz?8lw-pgh)Mkv`8W3R<7cFSEdg5$+R@&J6R;p+aO zLddZ2KWr#PFz^Y5Nuc%}&*Gvz+7S$N>_gn%K*ukJ0XS|W3ng1rMPsl$k$xG>AI10z zBFunOKNtcJTWT{|A`zwRQ3KF?CJ2y{qR4?9`~Z4z(w@i5j~$&CdW>1G4r}-}6uZR} z2y)wKbTu0{%7yr|lPUWb@${0^OjcE$rw9g)OSXELAn8TrmGVbAz zO=LpWu-=W)lkOZ^>s;kdf4bQ=IO1FRTD~FVxQmI6Jx>he*pnS6Jokny%yzjbM{ffJpmG$kze`Im;7N*3BkqswMDQD#1$FHUpNc2#n@)VQzW^Q3(bYXIEu9O-2vDT zfE)!}IN(j>js${*A^%Mr3VKPsWeQ|Or`%3nMth=TCW zUvMBOW(;>d$vcR|#`FP7AR=O5TnkoDAp`@2&;j{5!Y@!kTTp={n4}xDWGYBVH4FoM zXaU>J0vS|>QvZR^H~wTO0i{s(NiW*opTvf2a6%`*Trnnw|3KpaeL^5$m4ww?6*5Ni z4d3%=BUefv)1lf>hUNL3p=?~jIQoV6T!Q#5mOIv=ioxOt#bsQ!<6pR?$E8GEj0}#g z)7jW}H{SJ&TPMVqc1+ zDvnWTaUSPu6y@&uNzRSL0pJGv7~^6P!ZGk2Gb-V5*xd0sjs9FEWHg^z4V@Nt zC3$v-Apg_>7-m8;a2Qx3r+dmK*kyvKQ5@n}3+e}dMA8+c z!6nSYkRZrBpo1~s7!(xfe>`X!z!vNT!4_Buj{LnqcbQVfuaKe~83L!kDGUiX3@_-C* z26#S-Kdk3^W&+Wjh8EVrd6uWv;Awht&3e*?qxi!yECVs*Ml5A1qTWdnz<>8TkiUsfDS}}_9bRuoIYI-J0OD=WrR1-9XkA7FZ9qe^uhrkgDs$hHw1%% z%tMjo0zrJm0gx?Ea0OgU3|JfhBpd)sB|?_m5h+l^@kB*_Jl;Qu!#nWNl_WwaWQB?< zM#U|GCTPzmQCh0HCf*bH?7p#I1#3qogf+VbhEr1A1UhXf*W?QU6 zE;s`a1w*_}Y3fy}%C@fS+UvfOTA#4eK>SRj@Rw2^03i@V_5sE&L1q4!Rh}>`!{!Dj zKrAOf!^l=F7GA7+%4x_3jl`1dp#sJWAi))Q=j(1SWYEe1Fe=Q3Z=)6gt^atRS>EiV zieIH(My6VZjq)rvMOM&C7L4`HI!zmBxRW~#P96?JVU>|HOhXy1LoloZ7x@D^AcM#h z!zgSHC@?}W_yb5$PAQ}UBIv>5!G%%`gc@+@S0uv47((tuW}>ADH8jjmBmy3})E`j{ zDYVoeRb=Pk(BaBsU`j=e35WE%z`B7=xd3>J_Lg| zTtW<}?qGb+cW^HjXYp~yuFRQ7Yj`RA42iY01QkM8m1vye$dr9?qggkT(mD`81g`{B3nK#{r?IJX5ph^yb~Vw z4gMAtJxT?Gtd6}ELo-}LDj>s2?87s71K6U2Jyb&}XRRsAhO{g}k^#~n1OpyaFko!( z0d%m$;M+jtj=@+`M(oJ#IGn?wlpd(?Ky-z4_3hsx!t+?%dgWyC_V{=asa%A`{{K8`Vwk0|m#*G2a ze(-M%O`A9M1cPW)m?Vx$Q$*s>7F57N5NH`81j8>lLQH$Z0sq|HxcNgh{DL>E13CnQ z053@|`~oUO3^FJJ9xwvq5{;`2kSQ{pav0?1?IiApsnr0XL za9eZ&6cw;P5Oy`JL)W4M0kDm+0U?);hEaBv zq9iEsy%JbC;{^dUWn95Px47%3_CYJg9<%mH5W^Vg5)b@1K?w4FUWOtsG6~V;&So^% z;ioIIB7P{$NRRXt`6J3a-W1qti&m1nIa&;M9_dEtil^mk*P|EH#DhX6kIUq z!62kUFo;5QC4#AHNazN`ASi;N7dlWB`XJ;%SO36*C>Xk-TVy265n|RiL#D(q^9We? z3zlh_w9pnm_8~uHoC`8C4GwK&xIu)h!nWEWI~4Fh*uygfgEOE*N~AIsO#(rmq+s(2kHN0C!a2p&+s#X64X2X+&h) zNQantja=Ea48%kvP7tg@woJq%qyiAYfo*`>HT;4o{Ddu}f-U@l-rd3rSG6MCYAWb~ zNrp1#RyCi8axm;fDID12`({rDwEuP?jvY11ppsMuYU|!J~-Lfj*IHl`2#!7qU`*4x}oTDpe*tt1_tx8&**; zNU(Oq~9Fb_}rAYbV49yb=8%;h{`t#(8 z;bzw&EqZd;kv7NIust>7r~mSjYll042M3({Yo z*S?*5ckkc9AFs1XB_~cy(5GkOTs?Z6bd+1btpn|^v2`tdS z0})IxF&!9eu!sX-SWbosDU@N2WQf^^m@&qHs33zlAx5ENI*bmsiW&lDx7vJZC?=5@ zD(N48{;9D>mRw>Zxt(mn2^cm=6s1 zEIrhS1eIQXLB$X?GD*b@TT0O~7+Y2eCY7)fLBc%f!;`I4FgJ1OF7zemr1EU}Or?wB1zlM78HmtjH7EB=g9(PBrE2IN^eOBQ@g` zY}M6QVU3l*2W73*)?0DSb-D4%J1@WF_S+0T`QC7jlV$!{M%e=h(JxqB{d*3HD_+pm z+H0}RR>1}xgpj!kDZDVl4NH9J!!ZaUW;YUlX!i#koI8;rjcTJ!wuoSyqojvytdXNg znd9l9n{v|efFOnJs2C`ZLaG?0CTdcmCp%k03@Q`549f%f{3Vx2)EFcfuu`#w8d&HW zWRO&lN#qnTb8*vDEIe=1#CY8ui zO>oNe-sVW{DF0M`uD%Vo)OvFbRp3-riB)aUPFwA@k4u8>x8aT(ZeIN{@7b7sb&ZqM z>Ynb{88JOz8S@BvqrC&7jWzM+sFmCC$04_sTLvGD@LO;##85*HBlh-80ix|@PBZzFQ7hvT`dx+|SrABxrg84ZBl%kGOa>k}M zME4>Em}-#GBNayUfW?+-W~2s^u>1(qn_v*p!w_I-yJ<$(l5--5e9B(RIZAOwEav$z83a5;?|;SYfr#EDF< za?ZhA=ElW2a}|UT2MHa!N*6`bZAM<6(8xnt*O57RYG3@S(QI0GJKPEE0GA4l!6xE6 znhc2_pn=!{js%fe;n!*!MKHB z^r8nv`~ofzS%qO-BR?y_f*Or6+7dwVlf)>kc%cCpk8~%%%@7bZ3SrH1MDmbNg^D?( z0-M;zc8S!u!6B2&phJoP1Ir1Kn8nOi5!_}>WiAtPCG^$d5SK!btk56JD3*5K@It<+ z#Qz~M#1su}7|k56=Q}*~je4f_f)l0(BI-dQIkCfpaxjyg^@Io!huNGXu7McI;0L)p z#6)6bXc=uNmlUOlgVRw&URR7r7CEx7jrdCLiknZ5i; z521L6p)#`srx>LelKDrGjKnZV!2}{1m6R%dLqLwC=9S2~2t+0=#7Q%mQa`w<8n!6pVf|s#L^>lF$Z&?7^e~83 z$Yqda8EPN`KvT1Ld_Nq$gqfY zF$>@6SQ$eThtHX8wcMja|Kx4Qo0Z68A)B6gmYB%70&R5mnW56M)^h`$$Nw=5>KoUR zPNA|rQAudjFN$gcVO+InfH4X{hY+kK!{y0Kipvwx;15bzUG8#Qcd}5ZAvq}x3m!^Q zjcRy^ z@H+F5QnHySrNr$j#XRPYfEhVEIZaOzyc&nNXd(@cNNXU>)(L~8!YUbt4m3Ow%yqcP z#rCXTjh$>|N94pbhKP!JRcIRZ)(7Cf>q7@PR_H3xhUHAzT~&q+Lvr(xjX3QzYd#}sO#ibJgP-v^WJELX zP<>{W_zy^8b%-5@qFg!FiyF^uPD&$D8E*EOBm1z2BArohmu5&b(oHi$Vr#Tc z$CkT>2nC0u5@NV!*zGoZJs*VZv#eD zLng)QR-+PlPfHAOSHe{_>h|J|+HGw*{v41~<0Q*%8p%^5j{kR%A`#&G1(y0^hF~b- z0DYM+`~Fmyxr8MZxd@BM-Y^t66CI8tEtF(98dj#WVb#sCRK;(ClYTuIUs`_%uBD^v z3Gd(lV1L05cpxHwB*QmlNBsXs2$=wI0P$)Q$fIta2|b|AR*q$xmH5U%OAPis`-fM~5EBx1pGO(aUiA1=ZE@Q)zk?l?G11U(UQ z)b0~SQG^VzSJH)>tO?v0a7KDhh3ew~BCrC_tpjC@3V7fHH*j&j4Hp4x6n!xwNYFY& ztDiQfL?ka=_F)-FA(Bt9TuK~PWFM;GyXNFd z(qs+QuoQlQ5&DQ_{$U-EVIAzDx}@+7RzVNPEC1t~rci1NzZwM)BZZCl;Sj?t2%F9} zRuA@eYY|HlQ&eM%+;7%sjqBv^5`p9XB2V&2YaccNIq2#ag;HBYY$%QLaY_*;6VS(G zB^Hl^6S65jlto$0qZ3Aq(8CT^;TKjx zEtw!J7i|^DAU(98EeY=^2{0H-P@hgv$smsfK}U3`gLK-U6OQ2kqH!9ju`wG{2c9bY@us-oq zZ8jkjSg1ZgFmAHxg_tP7S`hzn9>dozz%-FEG1zU z96~I$-~b#{EN84(;^P7H)7bb@82^&A0u!}3;Te_D@|?pkO9UE^K^hOhF?F;J@~s*> zGa`hmJ1(=h28alW6cK6SGubB#CqwvlffV!zQJm_{RPq351SMK$Yy1Hk{ox&`VHaTG zxu}63ykQ<_#2=7B&zxaRk>LQ`qW?}JAu{aY7bNn#49yw#AsEo1K;>jQsZ(oiBvQWd zs|*nlA!4J%@4!s5qUxoL)~JoX|rO!fh2KfeC!oAso~~CBY6b zG$x{wZ<@RGdkQQ$`sQdjsePE5F&KcF&UE@tuZ@cf-^1C zNMkQEd4wFpk7`b1UUTFnOz)2FfPL^F4%ZP8_z^bqC?X;OXcB=6Lje{bK~M%xB2J<@ z>xD9?p$m6m7mBYjY%@(aV*ee2A<($#A9TtdvLP6HVK)p3K53*Ho;Z;v*B;lQdUCLN*~Adyol6$ePC65vx)-E$y1 zAvM+@IsETgv9>$zGi$lFRZ3A+|C4R}!#v^xRuStM1O!+%%UL906>xPG3PBJAp%rXs z7A&+^-PS)a^g|sYS)c6`sjWupV;s7+o}#rnM2lKYOY&OqMrCy0wzU!z^NHFZTqB|} z9fBHpv|M%68cicShO}Lk5P*sc2zi7gOA00Y0UueHAE;p;S~FpRVPcV9O@F}~;8D-);W!D6dXPaKng%6$ zuU~}rq6U?X!f$j@5>W}!)l4#rxD4T9twoX+BYXiE)QZ761-1?#ikucxpmrw~Te0H}_)mk0=%-cDEJ5sESYKxe9h*4K@^Zfpve^ zj9GUdA`;NbbpH|mY#nR_9RO{oK;<|k;{fCs(9Bdcy%)E@)2lSWUvAc2bGH1PgOyy; zkb~qjRM!!$h;_Ir>*{x*AOe4%wsZP-Oa0*|0k}f?vV}o;Ge|X*Nf|p(wO3XZasm{) z66>0@l3AQG0&D14rZP3Cct-XC&{EDH)}c)OVIHVw9)6(}9-?hUm@QXx8fabYKK?-4k9wVc6vZzZT**4z6nY)m6 zi{W>9m;Xyi&Nk?1qm^eVJo=-L#8HZ2zf{RIM9(EekB|Y#JNspjv#}7j(;L}$;qduj z5Qb71x;7@&%Ir5Lq{wMiVt=ibCso2ztu}z8IjJY2fR(zbn2Df(Ac6CnjS-eU{{+80rE-10wDh=rLs^9SCftwC8SNwVAjatbP%Oo zLjN;CMUZj!P+8|X$mldWVrUT#c)SQ^Mdbi^nvz|^k}sKm38E9=(^<(5spVR!NBO(O zTRaZ1Zki=*-{uOQtpQ`zIRX?}(BY<3Vjq5CPqmju!g?OGYj9Xb4pLza?v5-)`1sH| zKx=3ern0Kzdc3nGuDV59!zEQWMDmj18Hs^gx%n`kaWRzxb90nO4`2puB%{}va~;#M ztAhx4C$hz?bQ9wx>ecjOf;GQbEaJ3&*l{;l7oidQOKF!BTKfuv22m8FF|Y&@4&X@< z;UQj|6ex{L!U7U(kRy~L6dr{(M%vA?>JO13Ck|#JhXdO0qtO~ki5;l68o81Md;}g3DVrrq0lRKG0sF}eJ7@0zm&=LJ1HX&6_=xzuk zvwUM#r|A`?!$DKQJgOlW_F)=y>L1j>8J@u&!g^0j!ERq*7KRl=EwpcsPdT=da1*^& z96YWDT|TE(-X>@ke>ClcU<)Cd_`3gZ7E99?j!f&A)Ry zGG9{GS4iwxW@m)`s>71?m(P=4lZ{$JJUQq~IlOHj(dh7UVC!`V4BS8{2`>eZ1S82fU!zA;gJN2rEUZVMP- z_O@>D2GKwLS*IM$ku;PPW9sK2`Z>o}x8u@%_gY6K07Bd@Qo9lz&~qT6!h~uR>UpR~ z4Z?(wPMsnZ3F5?rkp}L<198d1ku*x0Gzlk^Nl>Bq{d@V3A22o}7XkrN^8m1#H+%ME z1I%Adenk0=gc-9aFii@5E(|I&r_`xbn~v0^$!AZjBaIS0K=fGAN|mabt@$IZ+DiNU z`RkOBhupb5I<@u3>1<9JeEY)C3plXg!GsGNK8!fA;>C;`JO9>OB+28+lq*}lj5)LB z&5t*2a?6PmlhLF}a|TR>$7#iH@~(ajJGSiERCUYDAa((4>i;fD3wMKMMBL>^O5JzKGdAD%PEj3BvDQdPE-+w zh#UlwLwY2FAt`u>WL8NEokRmma1=vSF~xvV416+iH4;uWvB6YRTHORBR+<2VWRg09 zr;vQ}F{PD4Y!sEBWjBq)Mt(yA5hQ}-9dL{fmGHCAKL7lb)tFjq-38YHbjj68h5Kw` zSZ^}G@E2`*?#XALe*RfRWPc7yXrYE4ikW9_EyKwhr9G+`6NpYqX{DA{np>v2Rb}TI z!TCdso5m3%-7;-7r`L01a91XG+Fj>^cHB)^RCxByN8Nc;t;Z{NGvu_TQ?|aO(0oXF ziDZ^$4H?88VjSSde+dN`AS_6|qhKVFKoUuVA42#~LSE7OU4<7GbkIT#ktoqa6p><4 zw+Vd+5hA;Y<4+!d!H7~ZF%<&`96<~`FdR58i4{#(*0j^I!3LWpkWUhIWR~tJ1QkD3 zTIr)gJRUG4RG-3C;$I|c9@-cUW#+hI`52FWRmd=bkIT% ztydkJBmLbktH$Et{rR>u~czok|C4aXgH{Npjqwde#r8vg(hkx)P>d z8#6CCUz1LfXI@~v^7?C!5Ce0pmqv|8RI(dS#q1pmQ5#@^2l_MjKCqkui-+`r`<}Rd zQ|MiS9-U&)LLVv=A}O8E>mVLtECGjG`@nG)zi{Mn%)bVMA~3Tf3K`tH9Ezh;W!rS#IHWtLj}`tQ&G0smKPsDrOr4_71QQ z?o{V6cblG2Xq6LOO>i(3WRFd>0u-SXi#)f&4`BAwpTkir60o3#P~JhS_%Lojo}-tw z!X?74kViob(gPmU0Iz|NVqOPn7w9aqixH7dBc@wI5DqY~af^%O)7IGpJ3%C(K`Tp$dZ&}*l|73k<*zL<2~@b z1!i-xONHoEr}Oo1k&JX-pnlfKNJ^4_^JA2w?B}#eYI2j3{9mSeGr-^&@N3IR&T`1c zK(jrtExAfe2d}rJsZg(O6nv!*e*fi@EFnoKGXcVv#v{1)_@r6Siq;AZv^XBVCx%7& z&OZh;xd=(6C_F5XgBD_lL}W-qBr4GXAOSB8{pUj~a-tWV8H$`#kw*If*uZka#gTaN zcDW-DSAfEp;GL0pI0;#njz_$N2rD5W{9R#!H3PDYBs~kM#6R??5MG%KWeP=1AkE~K zPKb{aZovy;Y?d`nigcud@)=1_iqcCN4Qcelz0MV|{G9j;8j8WSVu_N*Fd1xHgKTIf?{W!~qi8Byb4v?*k=wWe| zi=i`(BG!jM!i5XjAvFr*x&Ll@Qz6));-FF`&W|mc%Hwr4UkfFbK_?$+#EMnt(PTy*iopDr%UEW>kDUAV!7! zv4)TKCZsa0t!*3g$lL06x16bDqg=`~)ToBH#4T=MXzGSx45Mp0B~<|{;nR^c5KL_W z(*cO;n7cuz5@NF6cEIyT%7B!dX}A@(5G>dtkb_Q@Ks_}4J<0}g}r7Z$ZB&nLnY6jWhsV|C|} ze;hBLW<0=T`O&2c;|*LE8*{4S!0fSdgPLiZn8*^Vk}2eY zoGGvM)Z@^=ArA<;{7$k6gF^q{L2+R5N46l5hYvxbxp5v1HyR& zygM0hsg4U#Gil4q$L{chyi<{=X}6bJmbuI=gsjVJ5m{uu(ALV-KIxLHjcwzuG-*dB0Dv_lr`afh_L`mTAf10<-l z*VR2C=AK*lo%+g4t`Aale)*eDdL;rDeqMND=vAV+W=M1oSrMuk8%BT3=wG5X%k37z z>7vAQv73%hQYfYveXbbhmDNg+!j(Z<^=`(+<`tU1JE0u!iamaWZef7T3GumhAIXSq zw51L1sB1E}Qm?v9eS67nd)w+;#{ z_*RlL5s45AmA4RszzDWb2#Qb>ieL+Vpb&#l3aMa$3c&~+s0ibv2a3>vjBp}B)Dh?K z9jbR0o0cOIQVfT|SSc4nrz z`xrEy@hSemD4fsvBBmZG`71>_9 z#u@$Bf7=l|dGvPU$VVT^BqOAVZ`W_z@e;0Le;uSZbS6~-CW(MCIgm3T3N{i5;VuUd z38%1llIKl>&`qEi3JzEb$Z!e2APSKn3c)ZSumCTxfC{zHowe`_w*U*Z01V>559{y? zr2q<=@Sg9PjO39!^=Y4A1RqJFpBW>JG#HJAmPQJZJES)u2~n16Nj$Blk{5Gg>D4i9 z^p+rGB*Mmog3)hm2B3749(_omMFDRTC1%J*g=(^FK?W!ExEOYFC!NWnu>poH3ZsQW znaS{vrIeYQX^=4*eV>^S-*sd~q?`{(4cX8Ozkm+*;1B2!4C~+x zb?Ohj;0);C48c$h^UzThasbZY41qeQges?o+EIX`Bra!mkLnAMIx|aZBlWqAIl)+2 z381A$SYuf$TVy+qMKKBrEN0}ELAWqLxNFjr9b}OcQQIuW2{*@zBi@W@gAoI zk2!&KbYV!!XFe**7rUXO$BG${iLA>?8#8*D0XdL3%9+ecZMOk-3)!Ro0DeJw0G`li zXY@fw+7n2)82AQJ;<0KYX`$pOCTWI$dr5z<*^buH9r^d6+W*Cx3P@muVPMKBfc#)_ z?t&1@c>tlXE>f{A$RvOW(hI@Rijfd4sZa`Lkcy%}4b>0~&(I5ufDE)4Abn7Z$Z!kc za(2HE46{H7bEvXu=Lv4XYP%#9;wJ>*Cy~C;FygXmbIG6NaU%mtdWY>2rL4&E6(xoPC5Uhupm~%21 z#M&3s%C?m8NRZUFaSI!DAPAL-G|308nklVYC%3k>ec0-wby%8Fp`hYgVufL@ttmHv z!=$csZ>1G3<#DBW`6^*?l2_ZRdK4C+Fs6u+oC?uG^8fct0;`;-P_PIqY1uk}Ggu&q zGYGSY2OS6@=EYHGy;BTMVp69z!hza3` zMI~=~gs$J1GJqjbWYS|{s}NNv6jwL~9d&+Zp|&zm1TN6G3%nT0%D@kN8I)<6c$=A7 zx3?FJ!FvnAoY98Kkgd(&37+5!eYO({v%ZFVk${o7FmV*$B zb8v^^F%rx+LYI?#GJ(P?iM_F8pgl{QH8MN%G@EBxsTfv+AVx7u+nWr^Pd<@Q@S&IS zE5G$uOL+;%o;numN{+kQV`iaR2XL6dT8}kxzzMv;wR{*3Y|FXa7&BU<0jakc49vki zWxD(r9sCmC#}5?AOUKhO!i2))niJN+I3L-bwTAvTtB=Z{2a1ng0tGYJ)mY?8Hud7~kS>%|sMubs$@OATIG9 z2SOmBkP#ZF5dVQVu*e9CL%Vib4QpHt2T%>`K&R^f3`+n7zc2^A@C@s)t-l}$g^&t_ zK(nfN01`Qoz|aiS44S2!L5X1?3+4!LH2PYIS7r#NXS_9)1UW6mW*PUENim{ zYgwUY)RVtcx)Aur7#F&=rc4x8n-gDaCWM(vYC*OL=*ozxI$D?z2aG2QOw4Ny7;nqg zZ~Yj~O2Gp8%ff8e1qs)Q@pT@2%z;X{AcGh>4FpJ#6A$!qQ{lo!Oc;dl3r-gZzc9lI zaRu5O&OWdTlMva#u*ZQA3^RNM!T%5l2e1Z>9V@AT4D%q8Nc_URmboX{204H_dZ5n- z@WixD+fW=Bf;J!#!c5GIa|m4^7MCs!9U#-PLKqvT>wpZ%&{6wf59n|J>(Ca2IuB65 zigRkmY4^=;Kn2{Kc5d(sZa{wTL2l=!s4Sdw`$ZIuiD2ztg%d=pFwC_|D zHxe)cda0PodPv=aIUO=%!H8|3BmN7@CZpgqTodvts~BpufElax#=j!^QzTj@387KQ z;TFW;bO)T*Ar2Wy0JkD;;)OxCcKfWM5v_Oa;=py{38@2akPJxCQ6&u6j&aDp!bd$C zH(Glu*9?5J;)DbA1N}GJH~)+svk(ZYP}z0h1UZlplduYwJqi7H08Q=#R9+VQK)drC z7KKQT*5TT)9ovCc+i8B=Yd#e;v_ucmLI)DLE_W=ewt!?x6%QSN-Z2l=fDFNa3?qFP z6+*k{z&PuGv1fb>b3g@dpv~qi-Us05+q?>na0Y&C6y>%9o4)C9Fm_}|gl8!(zCeC1 ztG;ac6S*{(7nI*PLOZ0k5G(hB|1Eo^%E`YnCSQ?`Sf1;!T5M0)P-t>vapvm`4rknj zq34Jg*Q3hC{=dcd9!bXo9Mu+^K&-SJeik(@A4tN? z&HNZT&8ltVjEn0e>i@ca??;Gl#@g8N160mXtS|#kE;IcIT90w|3k z_BQsAfMgP+ zMF)U`0$Q|2O;5Exd*S%*yiVXxead{O z@C&Sf@Uws&lm8IT3-Jp~-udTj9o6s)$uJGG&<4$L0NyZ_Ym*&7mok{}+BtCX6QM7% zt^2s`@o6sG3Sl7eLB(fkAbwWUdl^=Gz|eWVLQ@PwaHBlZD--$&AO7GA?7a{=&+~Uk zZd{fVLof8`*1T%x(jwfgE9>5|R-{Vpe@BW&t3Dq+J3E9y>zhnRc{A*_l8*9A9$F0$ z2M+ikSdd_)NCeJE^16ju+2h<4=Z6LS<+-ig9iXuK&QX_ z?c2u>VaXpcV^(UZlGB)F`~3NwVV^kCGJr}=^A(GTRwGktn<=hQ>(qTKz!KZlkZ z0u413&v`tNU{Pa#fIT%>@#9Ad70JG#AcTRi0k*T*oHShiBJe^2n}LXpi!@<_L#XrooLGM1vAh zL^cwtqz!|P`3^E9LpoA8if}B5vm6h&;+NHCsiO|oCg}~OHmaFrr({w|rIloU*@vQ3 zCJE$ILV#OrB8rSVt_?8+dXA**t}}MJ?6T7%6l&h_2Qu(18ZTO?(6crYJz%lVT0HdV zwp%flSVBMk{PQJ13okSfK?NBk3PN~y0COjFEy7UUo%jK!BoaY%DzJ-2?2B9!C6a8# z7K8tiQASJ*b_vUkI^7YX9d+bUB%p{qh}ugbk_cjxmfX=tiz<;w(yORk>`I8WjH!)I zqP=8ZF%z}EV>yzdQ`REK9SFcNijsT_kB?7=8c6 z@T4I!K{jD5(%8M(-eufzq1>I@4y)ghJ;4=_2(b#5Q; z*atOOa=FGZMj)GG2zw$S5Ih{fKGgWf=YmonYJ=q5zEme4iL9rII|$YamF;jLx^7l0~y&&h74CRi&elz zQvArpFOUJwG5An%*LfV|isc-EOzu7Jpr?CeQJ*}7q8R?TNM$DV5cpur4`iedH6k(@ zSp0-O2Y>{0PFE6colzjHE7uxhM<4@5#29ddiX0s@uV%Cnj~Z$SF$WW#N`(ZFfjkKz zF+w6V9&e({Ta+SG6p~_K;v$f=9`@4bq|E^7l9=38D4BUogq#p4pv3>+_)OWplKoUF zT^h>^gcu2tr)JBb88wH_%}Zyn1F0K0w?$nWHQs3dA|`Y!*GK zQH=V8f;yw!&V-_9sfK8)Jf}m?5u4?)$w=uUWDH6~mk?8}B?xxu!szTa>MpE!R9?EX z7ar#TyhUk3Y$>f2@%-h|4k>r0B>@Ip8D+AE>_n#);i+*XsmY^SY#r-B$2v;6qm`he z6BoHcdoj{p#TMiWgiy;c9?MT@RYs~2yU0jJnK$@N)oU}D!HNHL7ob-P1W*7}Yl9su zG+aJd!V{)&g>~skuOyPCtE(vxO2h_Z5=49&REown`J@x-gd!(AM))W)%@eM~AH~?9 zKzx{k>R{HPK{QrA-P740(`U3p*3K?;l3yuxPPEiv?Rg6N4u~*>G7?b_bAV!7+$Pd> z|6$`DF`7{YT>`jU5pM4Kv_CxR54p)5N^{w|I+6fGx^NbrAPZwmghWIqm=F>Yx|@UV z8WpGnnM5$OiHvGs0+W^S#sR89kt@J0ZlTf0Bxb>iZw3MhKKR8ff&tE1tl=XF8K-_T zCbCmzB-MG_?~pV`U=A;jdH$(Tf>q)t23uIyyG~PtdHw%uU$x}r6IygAl= z`4C(~tPqAICcq_@m~ZwrD^d&RHy*LuPB3E}8z0BAUv$p_==qM$2^k|q&I2r%Sdu12 zg59Haa_8QmlGr})S)DTvdc+{nnQB=g2kNpbzwFyLjQK0Vofn!%deG#FXwIKhsj@lz z(uWiex>1ZcAHAj!8HaDXe+INqNtmNGgnCESIKVoZ0jVEovlTQ*CqCwm7Gtn!YpTDJG6+I|^pKI;T8SOrI*36?m9ojVPU2(?OE1y4~MQaP3J8Kp-dzmq$r#LzvF_%Gm?wy7%$ ztAoF0@C4tvHCggMMm)Q*YeYzlL`hU2$S^hmbUOmv90NQ6Me>V{TR_2}x|Demlo5%% zd$GI;4rRg!bpj&Oxrk*cw|gtME6S`89I_FNw<8h=6kNB_y1a;3s!FjUjF`b7fC3w= zC||H6FVi~IQ@u0ss5hV^f2cJ)`W^ox3^Bp;Kx zLNC<9?!ttkLWmCflxRALbr>9fs1=aghib^Cq5;n|vf z=?icKMY@X$zY~sz$h!@yh;cfAOd$z%vJT9OMJ2ko60{DYn74$=rz&f_U+kO~{E5zi z57qL#GQtCZOU5nhGB=_fXjGFRti~aHrF@w)B)q8_DJ0y}k2#Z~ut}*^8?++PvpsW1 zo;p5}IIrvzgjJZEE0Def(GCBPI0kg^hH40gI?#x|>?=uN1%e2KQ%N~zTECKkK)KWv zlW@x^QbLy?62pj!_X|b}(Vtu6$Xqi?)I=+hOik8oP1lr)OMsRDI;0@kxguPLnu}G0-gQXbuhpvVdZ|p->NrK$c%*O37O-Vj(RjItlj3 zhWMxtZ^46sa;R5qGOQFmLqfLK@dP&N%63VVu=IyHNHc8I7aKe&Khl?h;g^(*wUg?n zk^qk=k&KT?M=Cjsy4=FMbQm8Yh);n`o8yFahz;`^2%7K*Z}tXf9oWw$`a$^gsClVI`pg$g^iP>Ok>?5?wZsTE=Olhj4xIP1{4jrBKqMxXFH+ z2rLmFNukmz9X$Wd%F-uNQ+cyRpcpM)G$?a?h`;gVQKG%^7K=Mnt?uKD9HM0!Kl8DcaKyk$FLu98kx|%kXMCy2L_A^@nOe2J_Mg z5HbkqTM1-fpHvA3hz*AA>p2lRl^GhkXfA_U7hJw(mh?&RjUX2QKCRpeF<9Q;mz?mQE3^!R8v}?5H~o$R(@a)ZSmHm zI8%J%Jbt)Z%F_<5E!Uu6SL(pZtc=$iB->^L5QO{6t4KKPof$FHUNOU7>|KiZ97~MK zm)KK^jRTA*^b4f(V4f6bN+C-)fjt zlUWCE$OTjR0Zgg`w_%&7Fj1!~Mb14`WDSY_%rF!2BWMZT)cs(bF08!dRwL#TF%g$OBugu+pgUG8%&S|_MoS1C_&(5iijwvjzQRvxLV88+Fm>gHWdRT z2wSn;8tLt=XGCG6@LuiRsEr~NECv)~m>DT12|V=^@huSY&EO{V&ykT!kUOm+&CK+x zF@@wL9$`mJFb*!{1CfW-jmOX@hJa& zeZ91_$p8Evy=%~d;3v0~HpF1xkf7E#K2R&+r@O>1jFBIcxwS`m2%Yd`q^Lp+tGy^w zQI$$$wuF|hn`D1B6A}JrfgWf%agaB-1Ro`dmSkb90Yx_8WQUOFivVR&?i1f#GHykR zHoYR#B2ty*%!`Hv<#meDie<`TKW(fii-KYw%;l5VXt)LoNRDf|uIs-LvlC9?V&g=8CYS$mc~+wp z3W`1kQnn(D&S;H3Q_)n}g9VR}ZnqXV4ieZ3bwI%;kFSFZtyhLAFx>`aX@82Rn5u%@J@TgM}t<4Ag*tyTz> z$}?{xXRDs379$EvsV)!G1n?+iuvqI9X_w(zM7!Q@sR(H9{%-JAig<}l$bjwYW*sNi zJ&Qn@KqiU7&KJYxTFDmPVC3V*p6=f@Ua6Su_D18uG$CoLP^CH#t-y6)727nVk&+aOL zgXZbe5IH2*dCxolDEd=%geM6hPk4rpWH}=5$6#oz5s3bnZp?A=T9*;UIfi{wF$qKh zAo2<=N7*R4O?ahSm(SLoZ2w2;}IQBZ;Sbv*L7mJ2`2an{7QxcNbsuJc02D;IWn_4>Ye&jKc%M< zvIcZSk5WTF`;G@{?YEa zS9M&v+2)V_oR!7`{0e`W431fm15lkH@cVsQ!WHfsANYF0FZ>}}kCb9x_?3(jjO?M{ zZ!J{F4VwG|c$sCe{4p2<9@u{#cmaSoaA3!qHv$hHaH9hu!-ftYLX0SJB1Ih*FJjb@ zY1lu19xq)&xML*Al9xRCYbInROB|K<@#A-lVnqKRHgDRj^bcapp2ynQY*@)*o1rw1 z9>96CQYC)-JYuSpV=5+?F)JxGD)U%Oe@2li^)X`x(uY9K3S^^6(^((_*Qzbcuq|C6 zY=HUW=g*iyxeQIB^q0vm;lhRwBTlS%G2_OLA485Txp0vrmM3G*ta&r%&YnMm4lQ~# z>CysAqTX@oAM1Z?Fyr0XT3|6yaDp6w1E*NAy!?OxW5cE{kRW0_=SiL?61AQOdqR&X zks7r~p$;n-gCqyVn{5twJT~UQj~`=>E%Qih%orZ--}4yrW|=YY2ZovcoN>RKOo9D{ zbWmy}orKaHLf}wdc`xwRMmtuc39oS~HeK+*x@WA+2lh-RCbw@ zQ&L%_l~-b!rIu6JPvp4R1%{8XZ# zf(*vAqFfOApp!rpR`MNF2i??A8>$`vl=f8(;#{n1r$& zP)u&L^%m2#YwB3s9b(|&N1SkGMkjLuQ3p#X$t~=VpAXZS2X=W3I+dY5APSyLi~i84 zKl}W%9z&86bId;bBty&^Ysdh@yM%FyQ6`>#6l!WOyg`gdq?*d8RmVQqA&EYHCD5&3 z1x3-Uk##7YMjP1l5DEapL+l<4}HCGUC9^5#>kW~yz!xTeI%{~ZCT(QN83A)61 z8*>bvKjJa!s6Qqn6yE{Mtjz!N%QCCm!u{Owb_@o%E_k z%k*8-2t9ovP0jBbmWQH8C8AXVnb<0d(HX^c*Ppo+{cxDnZ)1giv@ma<)4)By@8~|pqn_=u^wm;ixBrwLf1n(mC zp5OVVRHkY}@eHGsgXoG@%R^%KmWU{RFyt6s!3?i@G%`$B4~n@m(NK&9l$$8aGT=4i(|;xUg`^5012)tY)yM1T#6jsoiv5iy9t z4-AQ*ubpR1c#5+<9&jH$So~IBag)4NFKseD5 z8p6_sH?$q@I&lCW{_tnH8lK9oV#F7P5}3>zO05pUl>;0@S8X8CKa3Z>tihBfOWP5T6+$8(~Se{w@tI@{^acfwOHd>qMYTJtxE01_cb z`%NJYX%^fZ=OK)2q(qp*4_G_|VjM)saxl3`$bk?nhZ;&=#AC{4c%)LFYo+Ko8WC91 zP?odIND*MSiNODK0+;XcSzd%_s$ObsGE2l>_Hbe!C{E2cBuXX~rPmacR3a+=Kw?g| zcQk+8b4g>wi*V`%rn4QXoNtULRjaD5`dKxrTHR_K=Q$DpvPO{l94kL(q$7z4>;Mv! z$UqMU5rgXGpbfd?br6zChbbpv5tV4@O30M-lq`h;x!eJW0mGw!bcQ0$A4W<_Lr(b0 zADw8AN`a`fpuyCcP!lFi!!ncY^<a_uDvpVEbus?QXW`#nn6RAW~0}TR@Jl( zc|p-Zz_ibn_IEK5Vu(Lf`xYQ*BD6h8Drw5*)Y&5BKmO2GX{0LL4};h?;$y31UR{mbe7sP+htpt9({7Gi}wamSSBf8n`tvIa(5*Nvvan=NP?t z)r|1Mk9|@YG{k8ta+Ay8|8Tg&1PaVlPi*Kzn`>^qMKq%u?P!`17l18hu0N}Vo5i$s zVgCO}vuL5?0g9SR((aPmt+z05b zxXW$s6Z@|q-5M&2`~i$g%Vn*Yh9Gm04JKo~1Jv4?3aNv6D=EqZCcYxZWLd}V7)Azm zFt9c4Y{zhc;98nPt*l1`0O$o-Y(kllAk>Py}?UAD<5>_4Vi<% zBHK*AcT5_#W66ZtFC07d=&XJ^TUOjQ_X_u&|PwaZft4Oec)Nthj? zMTf{;w444%@sD@%@Crol6khq7{~no`51zxQX(P8CqTxW>mLT7zJo%~G^YWuV{cuzF z*)lKm&9m4cZQ@Lv42t~G|3kZ)A(Yf7viebi7D{viOR?LN(ViaN9`1qE8qojOQ*gqr z`3~?15AZdJm_f+L9bZI@31}6W@QK&Skp)EP$n^D{-~GnR6-LbAh5CTsUlgAA0a}yf zochtA9-Ute;$RMD$alkL>rLyTRn9Y818R|K+~ORb&VDVS-UnFh{Abo_+L;avz)#0XBvtEd^Z z9mbwXOZ&ATLxa~Fq#E8WuIgG;eP-k&M~7oRpUm!4dij;M}j0`5LXcT z142zA9z+a9I7jJ`KAE}U-R5KW}wdg&v6Ng&9;;BI;M2G2x0zoOpUdiM`U|Now1y@h{fBtMMPuL}mA%7~hh;Tpc|2xMDTQP%VF`91h9nVYLM0e2BxjCMge|3kQ5ZO_Am)WeX$nL^ zWJyLAnr!0dl6Yi(@@FEJ1Qn>|9SG=v3MedCmq|JXC1(F12l@$I8VrrORbfD1LL#Tu zWtc#)TXQDdJcd|wN+(FQ+M}$HG?9mPTE$ZyhTB0K$bD8&JPq`Og=kD=ngvHU?P1Y* zC1=Rz0e}RSfMtIIX@0rn{xl>5yh!60hnfP(VGIrHXVud8Q3t6 zCX?)_pbn~P(AIq}>at2k{X`zKLMw;`=mFp+q(UkzNUB^JM*YFUDd>rH3=~3mUPF9p zWV8WI0w+V1s&k_1xveUz#*Xf#6qf^mLl9SDTQB80UnX*Rq=k2q<(p`@OiLMCx4r{ZPjMHgQh z#;M)ZLuhC`7QsTKs=L3LpcBI0V^>6JZ~gq!=_Ct^-c^P#ARr}3HR#AdDg^t z=tZ_=ZOs;j>!O5xu~hJkL9oQ)XMm9~)yM&)oU^Uf^cb8}uxNUnNyfr0#539s zdw~?0q7<5rj92hu3b!5JeQ*8NFa5rXoz3uK^sWtiB@Uwm00%IS0%A!VL>ql2e@*%g&qZ)B^B%Ab_?Sqy^6bAtmxG)u0vCtw@79-a|yc%Z2>_)O~>rQ8NDkkut zF+f6Q90sG_i46ps(Hy5>XiEQ!@8&2rmXjVUNwJ1RY7AW-2QmQ;utY< zBL^-W@2?H}MQQ{hF6VOMf&?4YM-2XQNCdMnJFX%7b3j*#fI2XNWli-Z@n}r52wL-5 zEQ=H^C595v%QEjb-|QIYY$rt4c?3~oJfB=lC7Lyz5F&<+67D}7>`~yc(-yC4fJFBN z;)d0854(>*4|C+&bWSq~K`%2D9dz}Ph(Ap4W-Rn7Q}MOQ-KHG`%uL2k%BDqM^kYR< zD#_|H_{7heCqoj4%*j`zdH^@e-+M7*{p z8(--a!<6D?A5?2@hAm@AG9@d9HtV)RWQ1dQF>o_0fCo58xsrx?Q7|F6RH}0&rrBC- z_DOqoWLUQ^D;_41fQx0j9rYG#`W*+(EM^ z2H_$^G9bJ}D150S@NWz8!zYH71x81}JRX(?EAu%@6EBzGbNih&ffyc!zq=rNx5*!B zy<`8q0`vP(xO}olFhbC`vzG;DCs#7)x6jv3wa?>ktGxmXcT`I?a-rSNz%qK)#qM@> zx6FEel=a6;t@y=s-;V~oi;lc+y`h$T;vevU9>(+b!Fwk(eY?0}aCU~F{lX(f&r4ah z2Xvh0_?Tkorg?~x`sk6#8?&q}2!+amK zaA90NPG`4gzlB1MuEEgBSQQl(3oHg)FR(%Q-%x}ck9y4bn)Lme}TOMg9-#O5V3&+Yn&Kz;7GY1 zDTc)8PvK;c1`kNqERmu@j4(f!Hhmg(YSpVb5;c01b!^$QY1g)m`l{8em3O?s=#`Df z#bwc^1={v@a^+I{uDyFQuZ)Jxb-)BX_@7sP!IvghJhpL3h>%6HoXxxCMaTc=IeTWm zL-a+`%jws*e;>b4*GBXA_x~Tj0Dsa=E8aruiXX!wT8yj%k{PBr0VSL;D(ar=D6b+Q zqRx$B1Y;~a;E?i;!SE>KEV9gGL+>&bS8UJ4*i>TaqL(PV5yu>L3~E3AcKi{@Accf# zHv@zPLeT$#1~u>!1Px2n zEaYq*wmwJ~%8({50sHbRoW#_G(@<%uC`CC(ZPB(<+f;4FRf+u;+;I2gGu(2`J@)`y z3q=@;^nmd3}oRkGIJAqBw^Z>>T*6GuPtX-JR zY+*E2C2vz6nrQmQEgI>hY4c)>bvGLnRE!`zS?Q{k685KmF_oDkf^8NrD1;wIZOx0u zKCPmJMTJvntKEJZuA||en{K4Ca@r&VqpopL@mZq+k_~xhL5@rQcM@+1mJC$nG0}53e;>FGO*>Qn* z16}vs*&faL^ee~sa`oLmH`ki>K7d}o-@kt;)BllPb=KoT4@rXI9@(zNxQ3yrGRY%V z>;4xxe@qO25k#8sBv`>lbuK1vm|y)Y*ukJQ#|_B<5ir>B9qX-*fo~b#W!O|cxbUV| z2He?5dSjk}TqcDoEsvL);n1q z6Gw?e<}#(?%KEjDnX9CwdblW;@mXXc4Wbhs<21@o4pWCB49nC#|cU`Wnz>e3-NbkqMJODRu-CMT6XI_N@C^3F9rlA)%Y zW)^LkJ#0z@lhuq0FLMbwapn^v8f~BhAsA7Uo@SjVHK{`#2}_kqvoBrprAI$^5{%qz zm)@hOE#VZ*g$Q(@+ss5sUs}|+BosDAJt#|G2~DL+G^T(QDfVv3k(+9AqdMJbMFD!# z7ZH@GPZg_E#-*{bGV`G>Ju6J>QqP(GvNu1?=1r$+O^(`=tK0JGSB1J(zdj|Ue_doe z1v}5E;x(s!WC&1q1|O-ir z9qm8O<4?$e6|}M4NnmALTiaG`qBympCAa^XkvE_SRCV>{9_gCek+}A?eZB2+QL)7JnCL}A_CwpMqUjGV&w*M9IfPwVhdvfGV*;O2I-`X(xRtC>ClUl>?RIt*}9Uo^IU)OyojL(m<2*r^mWzR==9e zXAbX?uRQ5fLkvzD7UT^z4QqLBmb1PVHjw+W=gFcvd~6o++`3`> z_CPOj#XCYg;&eJE#tjN=mcReJv)L|ny}4=YW0!g)3N-D=_swgVx4hyO|M}3L`tAkq zz=neXB*&G)OHwhNw7kV7$jiMFpA(&(|Hk^(4Lb0~G7ygnrnjnYe$P)@^&(WSIqfKK9n5*~98VfBV0${Cy0hKcYW<^mlLXR-~se z3gx2h>h6#Jk`DnF5O8v@zMu`4NUfr*kNE7W`v7m&Ox8E6eo-%5N!r1q_V|DK^w;%fTV1I|2Z1&t8vx0|}eZhicFZ!*F99a00bZBdDbcD=G*J zu#U1%J-RIhJ5LPLX9?%f4$DQ)oNoe=PLv>H%@&U4{_nfstb$Ox(eOA+C^Y!-tE6n{||gCq}2(4$VV+X9glo6gzngA?U&7&8ah zKrkAsF+g%K#E>z>9B3B_C=FMm6RnYWf>9jHu|G(WJ|@vVDvu2z<{L*TM$pY1=}-~p z(H`xi7E?eB zH2R|M(h)`8(UWx1ACUqeF)I(C@Y> zG0kK&Ez?oj(lh~6BfpX`ci>Vo2@}b(G}+JDOzz}-GBp#h9&|ylW-_1CG6mByM~V+6i%o`elVr0sl{1vIGi;<2aQsp{-4Zja zv*7>yFEfd$wa|07<^=7)vpmlzI_GmOR}&^pkBjooxcafNijz)+i8*UyFYU8xP}4w7 z(l@tJISX{>GU7O80`rVBRRC1`eltOri99n@C8;w)B@}~j2{zvYDCLJRI=XG0wpU)QKEc?^fWRdO6~Ms%G6MY(JS-w^5T?F&5ocR6&(Lf z>rVl7MiUifrm;ma^$xGp#ysM*0MW}Tl_vz1Q{RqCPxTe?l-_eT-wprO?@yvB9dxK5uHL~!dT=R8W42~|7<5CG0UEI}TL(o|fHf#(+ zq|ydrJ%yA)RziC;cQ&yYp550C&sg-19!f4O7P}vrdR#tBj&u3fmY40g)Io6t{ zmOd)BZ`pES6W8thV)e-NYlC)feaCFkmT_riZ7-MTxRy18R$~97OKG-lE%hKQS94(n zYfpFR+}3jg_ns!VKO}WE?pAeeC39={;+U3Etx!)_1a=*EbOH5d^A>mgBz22-;vBbW zoi=zqCv@|JY|GX`O&57jlW(iH-8gr5A<}irDF&N2EFsV|?v{G7_fP+B*L;PIbs@Kg z-nQqWmRz|DJy;_~$~S$D_j>PFeGT?;y*6sVmo)DPfDeX~+;=C)mw5FTm6lb3?@W2O z_akc*bf4E@9|Jxu!hjEWdK0*TqomF{*v_<9Y)y|w1ZaRk;(Gx^XYlE#GFT@zqCo8z zgzscOW*FAiHz;M)Y+ShGDob`_qvR%(A$r#>5ZHzRWhlnsh+pl2M|hV+13L*&iGSFe7)bim?}X*6jFqi-``C}QIFSD%xkLGPd50@a4!IxA zSTXZhi+1lM9J!f{)?_$Xl1n)ny*QEO%R3(r15;VMl8%tKbB|F1l%*nu{*{zXS(jx| zjw_j%90HS14i|k_fM>3!1J6yRO%QG!}Yyu$7|r zD61U;s{v#r#JI6LW2?WKurJ&5652n329{H3uL0z-0|c?C%XNbARxQ4<+{4Z`-cBjo6pLcTB8@b?`T3w?zqF-w8>k( z%gk|`dxB$Iw&{enIc%GY8@}fozA;q^}E8C49+`|)Xtj~M9%k8<>8%GqpX#e}eSA5O}{I1K%A~5_QPE@#$Rl_%& z!Q-37cl^IxyvFxU#&spgxjL3r!>g%=$CI4JG+V+2BoZm)M2mcOzk9)PS;v(e%b6?0 z(__TT%{PXeAi$iz-Mh+F`pUB$&1K8Shy1f~M9Phv%2Pb0G5XBY+|CPY%_qbl-ds(@ zeA^P@#&2gfru)tdeZ73VpKU3vC4|pW1I7O%B1DZ`#SNX(pKHtc6|^@(%n>}n2KS4SS5 zg%P6GZ9T_z9oaDp(VZNMcesOK#~^I;AZWcdM%~Jj9ozlNyt&-DZHO!&l-YxwATD@_ zi{04wQl4==+t;0yc-=q9!$EKReQJm#uGrj-{o2`G-&M-p(>t34xYfgQ(;ctBi5;nt zB;WU4;dedN-PFYC3XGKD~T0xR)YOq zUOpZ38dSBXKghh=&psl89_zC{rPJN*|9*^^n?lvvCJLT4s@|_J!|Kc3K6+{C0Uz>R zzB=|ae*fs`7wfl4I_))M?YEjC_IdA}?MER)Zy1wZXWN07pJrACC}3CyLTKWND5j|5iY&I+qJ;E` z_?BNEGK3v){dp(R4%1oo9d9MNDCCet7HQ;>NGACda|ZGCnP1(3)?rgMVpbK8oBasn zSW0&3<(FWFDdw0E!sz6a8sgYvZBAhcB6&eoM&_J!)@kRRc;?BLnHP5E*M=NwMWuF8 zt@+rG<>{&DqKr1`=%bMT9>AxJo%vH`XgPXUXqLB86lA2JhAQf)q?W24lcxc?*^QVA znrW8RxtSTFahhuDt+?i@>#lC`sj6oC@n@)yn{ql}qP!-n?6S-@>nvVEr7GGReFkdK zt8W%NYo}Yv`RupghAZy4i^7;ylur&8T80Nm6xR zx{KLY@LCDyr}-wV@WKo?44SXgrn#<&0;|U3#eZIG5XMq*>@h(e%et|~G=W7Tmky__ z^2#i?JQc*D1uI&>!&Vq_#vNn)+RZtKte?(Mb()DA2)k_b(MTt)^hV~QcIjs5enxG( zHM@0j6Lv_liX@W%XyI327&pN+8Ak9(#@4H#&9xQ>T&xAxTsJ}6)mpQC6Rkxrt@qx1 z_r37G{r(E<0fN7IZPjdpDi z&HdG#htK0Cx!B(7z21RNX05z@rud;oV4JwyMvTa0vb2~7{wSy2^>HJFHi(Q z-gmkR>dm&lMw!rPN4NF^Vf-QpK2p%z!fvk((#aL$xLTG^uHB{mtx3+^P{$zZ} z!lEQ6Ny$oL#v;y{Q2V;_yD)aqglCk15C(AoI3NK9D2RXtc1Hp^#wCWX?1~YxrZq{h z&X1Cqg#yXI!%pB(cxm&TEqS!ZYD^<-jN_j7AP71~9%X#m z#WaxNjAwYm5q9XDBzR;5dj?ULZ-gSZC^JQCTJ)kA&8SMEMHCN~<$bCo2sjHe&M}%$ zoCHC^22c=$PUN8zr9=Y#P&^s8VEt5^@BMNOVXn`exlNDr_9Grk~a7ZM8`PBEmxPGooF;k zOWyLDH+|TAN*7IPQjwxjq#J-QTgzBi*y3QXFNH%Tk_QJxK%s2bnvGU#vI8d$QDfT^ z8{D|2x~(a&37S)kKhQDRb)bWw_PB~Ysem4a9f8W;`Qp$5~e$BSEi~=)(aFp~iE0 zIpZ0zbXJ)MhpTabc{t-2-uQ<<_JIy(1Y;E4i(K2BnU>FbRmE_Qvz+TyR{Cr*Cp{MD z2HqM@Fw(faHXi92+3?c*Rsyf2gy}W-ap$_wY``)ZtSt|jOXML0dIS_+F1&#bbX0?& zP(6S*kbw+Nd!wnKs`NhP1vfs(IBl%s8{c@}HDxOf@<5RNx^%z$-K(qrI%_b%PUVnU zW8jDnf=I(UWgXr)b;i|QkbT$#9UAw>ICN(%yIf2xrjLtXqSiB# zRNt<(dA>=S<9&}437W`*C-QJ;+zy=+ir@#g2zQ+|9q?z-UWv0k6m_2@#VP+_3}fs; z@`LPyDP4E?Tx=5=c)$GYXivM4>YNo^r$o;Q0l3W_vU7sG0D_!5z#u9ibp00O!kkUW z166krtQDkmTzMezR40k%{v<>9tNKo&7?Og?<=x{|yXH5~`2*P+wYe@xun$sqoFl~N zY!x0r4-kyUT|($WKY${x@eINzL>>fLok4_mME%%-@Wc!JQ>IS;CCRtWWCQw$#}b|S%sC_x32 zz%{E-2Zm4(nUD&pun>S)4cE1V*9C}^K!uRAdk3(1^G9M@*obcNA4}H|x(FBhH-MQq zjKo-sArW&~F>@qQdO?tb{>E#hmvacgFCYdvGY|>pgo>(=6?*s_p$1j^@C?D=4gO#c zlTeHFQxNi`j>iLHhiH5+L43cMa>yqrTzG|tA~Zx(iN@HE{`il`XoD&d1PZZp%}9{0 zMFR)Xj0iym-j_B7;aH{M3;d7}dPs71*bD?Q3z=j85XLi$xzsgHFmY{`i;|dvkLZ6? z1CRHoaxeIgFd37Xc!sCdb}f;P2ceJ-fsh!n0W(k#-Zu+3_6mdWb^fq~S+R;8S9^e9 zJXS>;S2k4cX9YL)dnH(sS}~8nSdRyAkG{i_CP;~}CX-}YmNB@AEHQcod63eWkfryQ zIvHQVZ~%^weoi%)tT%qFcb9m1i0n9sQbtb+p@`uXd9#v*khm3K8I}ULk7H?;kQter z7m&)hj5H8mmr0PCc>p}Q0X%t`oJkOy$uB^_RtKPvi-QAkFbTHs47F#0NeGCqc>vGw zWvfS$Z9@jbBUB4z5aC0GXd#a$c^JqiW{olboOZ#BOhHjEDVfgsoGllSoTw24L68aw zn%HR&8vvSY#hv-Kot{Y$R8X1(Aq4KoR(bGs8AcQb;Bod~4`_A(+Vz{Nr;ha*KBhBE zwFrzRxtLX0j}svf{<(-^*__aMpa>dkG^T3*OF zog49)n0cWQ3Za{+5OrA)b9s(u1Y8ASetjZ5z0eSLvnH$Xdt=w1gyIik1|Tzj78f2j6fg+j^GG_;0WG_5K6%mT(*HVk~M6TBTlrR z6K6NX!$834h*|lihXNKhdZS>Nd1N}NlzLG@At(ar5i#%rpOlb1NqQ0bsUBezT>1~2 zlo(2pj*Lp2TKXA|I-p&Fd^u{Mm0GK|YDEj0h9khiG# zY8Mevu`4T41sbg!o3lC_F4oEtITHhPrIsk5mflkny)zo&s+G&?K=yO9JNvXyOD^u( z5(B{_o2sn@fs;7#t+Mg50#>t+lqN9?LywrTQG2#%8!nmpt_I6*59o42OovBW_wGSnGfTXJKYf=nAIPOGmc>| z8yaG|u`0Y4t0~26xOOY4+nc`X+cLl#yjl?};M)^}F~0F~7371y>zlv&`y0MH91#I+ z?hCW=J9%O|wzSI=^_aW+yTA+_8kgD_{NcEd`@Zy>C4YghK%=PV%a0A*!5*9|wi~_4 zI=~cEy$$g(F?t*K%fTPq!Y&LdV1pwgJTn(uGZ;gz2Q0rS$(+gi!an@NK0%GYTXHfy z!=OPhh1+yI@)y%fxz~%oKpe$V+!LES9EzcsBuuXYJTsCjGB<1xP3*+8+QU;^#%9bS z)WQ^|I=rB3#8OiK!w$qFGNQD&ShmP}#(12^MKU$F7RD3&wU1l6Jn}Sb?8N?{z ziu@oQVw~Tb!(Rx<V=%fK8QX>1T5n>?qi8G$Rhelp0{x)8^V z%KrMV!92}U>;}2$vi|oRUFgR*D#@5}F&|Qsx$MnkYsbD!&FH+yog82Xk;{*~%QBJ7 z&ulSE3=;FqpXLn3>AcVU9HR(P%q&AynyIXxg6O&4j5x*6fl7j4Lx+|y7U)kZtcd+`u2Z7`z@ z7s}a-4Ux;-EVGEo!%{ug*-Nksce@K=(+YvZwH&?~P1LUhpj55aQPtGYT+;eX)_RS& zDlJ@{LDB!56&i8WteVxAC)W<4lKVO$_N&T!{n(g`hTs9yE-}m_O~+~xMT9N0DH+rl zV%M(}){YI?q+Qw?Vc7^R*h}rY5^LCVvDKk#)u4UXhdkP*ecMlK)_!d`HLcnX;ZcQc z)NqaelAXN}kw@7m(aR={+sqxXeLWlO3=(Ubue$-i$nC9&O%OJ{&|??Yjw#K}9p1Gn z*<10~R9z54-5RXT(1P36WI@tg?c3a)r8*7X;(gy@D$yXj87;kq3IW_oh8v4LFmlbM z3O(EOoyyCN-waNsRSexgectU15h5(y2p-p+otX3e+Q_%UJKf+Q?wrp}#BU)6vHhZvMSa_p5@N@;3SS2{aw|`12)%vH$7hERst4X>ZL30)V8hv z=?2K&c}~>CFD^^tS8%`|8$?6+Z6CHGJ&JZR;}*?(Tke;vVePF66OJ!#kty zyv*)`{_gx9Z}Gn9G5AH!bG3f}JhzVNf=?6d2?iXQB5eeg0%uBSu)@ZPHL z`_AwjpJM;+TBe-_Fk^g}QA zA71x_e?{bd0MO1KZSwV`KJvU1_KdH5JN(^cU-*`PL1`boT#wZwANiF>A$|Ye8bA1# zU;62z^S`_Km+|E0-u4!J?-NY+-fsG|?>9&;xW60mBH#M1zb%j-_?1il`Lkd9#J@EC zTi1On=AK{jSy$aX{cef&~p8M3_+FLWT_&zA<)S z$3%w}EndW!k>DkN9sLQsG*P5Rk|j+lymV>cNQEL@?l>7UCP$AQGwHyYQ-@5RJ$?QJ z8dT^|qD74!MVeIUQl?FvK7|@p>Qt&#tzN~NRim3>{|df=snzKll`O?FrRnj2F|cOO z4&|s)pj(12Q@VUxF|Eg&I&tO&99ZyR!i5bVMx0pjV#bXfKZczDG}Fh86eE*-<1r-N z%NO^8eA!vAT#1(Jij=$AwBo%ThxPR})8x$jUU+QBzMvHC0ttWmTczE|pYMwFJ7-#x9}DkxM~o%Ma88Dm6&dQ3)-zRb!7u zHd$qtJupsPE3EMVJAuVC&n-Fa%tu-a0=BwX6RVHd5t${oTyxJwH(kS=^^m(N3#v6n zY-iK+)@(T}N!Vd6EYwhS{{=W;fd?kIA~&KHsIB7OCCJxcU&@rWP3?tDTZ4SyBy z6L;K#KL$Bukw-?=Ss8ny6kbaax@%W@uci30K4qH!m$fQu>X&4lcjmcgpHVbd@*CzaFgT@ps+_^p8yK>7f z$2{|ff{qxsn-6lF{Dg@0oMo7`}MrP?45R z>BLc2ef5N>P5bc4DaXBe=bwjO*{B% ziU+9BL9la|ArI>V+s*(sG-|sHYgRm=8c7 z#9Yx_!!VL?aEAxWtdZ4T+Db;qs~m zM?x0TkZcTLZs_PmJKph#e`J~x|IsZ!;s!fWl;R;Zxk*m4?^TqEnhLRJkS03PLTnjh zXC%izEk)LKQI;)QGMhm1B?fEaP2r?cG=a3|Aon>@idHmHx0Dk= zcZm>)$fckL6(cxR=|XzeGos_PXi8PO(j`IDTf)p(5o5%bFJbePEaVYK7+O-3+JtU( zV`)%@I#dMa%6_#G+*(jF(3;xxn-0~bHwhZXlirZ1SH)^p!_!ZJ{F638+z&%E=H5+ z>|#RHug-?nwztLYP`J95*t)iA&24g(yIhOV^{C>>3~I@<+U}i| zN0OaOannfHH8R(`-vw_$7E9W923ETxtch@WMAHr7h_m5^Z+w%x+vfsTx@D~{Q~^3x z=}?s~vU96^1w3G^?iOy-wNG|6D@wEKSC?VxEyu)(QUX`l!a?0_UCX=I^8(PX@FDJk z!&y~jUf9GZ-X}C`R9{E`-WR_EweEF8>|dME7R5Klu{r4*;ozZG#7P^H1v?zcg7Ek{ zoJDSqmAvFa8o0IAaxri%q~1Iw_%t+bYk--&WiIb9!z>0*bbf2fkQ&)$5FWDJYJ$mo zcG=Bu{-BDRXl8CIxIC4OaZZc;V=^Hb&VL5<26s&7K1Z3%tR?he#N1!^PS~n}hIFK# z=j22?rlWR#XK*3L=TU{2)7y28jU_#5Qq%5}b53*Q+BsP%mpRoOn=zJ;TWVU@T5l?5 z?5B|`*-C>N#(9R0r?E^VE!*1I#|GJ;Uws)X_j<7TeKP5+%;-jwxWvfDcD4m(;A`HQ zy~`ePM=+)9!^JxPBjlz^2HUJ{cDI{crzUTveSGJG0z24y7O}IHGTXws+u#3I7OrJz z9{z$GGG+X=gLiH2hA12`{O&HmB|h;}DI47YB&fmJs?BKk7~c-Dw*;-7WQv#E%S3N-uiq`+YQ#zi`5#i&W)3h;tnu(;4%13teqpiMnwih+)9ls5w!2V*6 zt6VTNXLXnSsC235Jj?5Dd*B5>9(Z#+(;cyo%v+sa#e>)&`0-Sv;Qkh=1Ag$A$9!*s zZb7GdW!!xKe|EwruTW3pOY(L{O8_IDdDgc+H&}-i>P0@GxkpITA-81dO)Ept_Z{K0 zc75=LKO2jWhkJJVe3)I4{(CcebRTK=8Fsy?5h4lKb)by z4Rpa5)U8~pJLTIb`l-KaD?$8AjK~YYia@B~`9BPV!678Vlh`~DthN#ooe{)A(UZNZ z;6cp)KtcVvz|||lE5t&FFu;Mcy=cK0^K(EWnzAsI4U192`cc6Z^awVyyexD>H|#(i zj12B+n??c&??XV!yT2!d3JCWp|#Z(M6A>_nZd_nh#J)Co_ zQ0&3Hxe+t3qt(6Hk8F=yuP4A!e3gQFN8iORHt4n#ijtpwc({l zY(-Z*Mu}3!Z)`tBBt{FYK_=2gY1}nx?6e6Yp{J>ox~s-?t3pi#$9il#Pvk?fh!58P zK|^$uHfoH=rP!lj^ucXZ9CbrRdsN7_qeW;7$hV-w`7t4}!b3^S!F)uD{h1(sq(FnD zLL>{og%ruPW5y|*LxRl3(eTK@fVq$G$EZU%Y-EU9#K@%ZvdmsAI4~bjr#9G|fmm zwY&7MYMMYx$x0Gb3$BEn2_mM05Y5r-MhZL4-K4dKAG-=vb@e8ktJ!7Y(ZAXFWO0!zmv%Cx(-=p;`#t4#2u3bs@TUkR)8 zzz%q{Osil@k6`Z!5%)5+Ftnd%#EKUA| z&;j#JA-gW?WS~`BP_)aD?VQVn3bF%5uaVQw2qjShn@--k&%49Sx4|yFRM8Iw(b<^K zn_5XV6VVdI(HlF@3jIodLNft*AP)VSy{J$4#4U4#+=4d>)r~U$3KjMmvjW}F z812v@;V>8NJH33)CG}Fon$WIWjEIb^9}SQowNj*_iTa#3!vx7Mh12jl(MnRJ6&0N; zJJZ9gQKq4hof^9%J+2Xr(?LBf|6D|kve1nnPAv@#G~Lt2FviT<%={EoLbX(_YEm&x zKs%+tx6IJMG|)%guFOJD2IbPoywp^Ut1w+oH7q|0M6*(5NrY>;6eUMb{nV@&OWjn} zUe&5OZB+?+RhGe3Al1`g?X!VewVH#?+~ieXg;t?5RAjw7>~sj0qc-zs$y#Mpv1E(a z?A9#>$x4mZa>b`irB*d1J7a}WQ5{6F%hq8FRCA?QmSR;~-7GWzJ&$YT)?7UcyqnU% zIaO4x*MdDKV8z$%iB)zD)pYF-(+bz9*wtq>*otkYCjCJml~Mww(%4K>gMwID70ZED zJBu}0Wm;6{D6WU1?QF1-ntM#(^%h)_!*gXANpiQEK=vk-myQWN1tVP=n z%2}sHov!uThJ9J-o7!eITY^p7yUn4smD$0dIkx3nmyO%D6iETiS=>+1JgB5b0OomB+aqKh?8B-BsS`Nm>*Q-2PZr zj-@xwlwEawJmQ54qQ%|i<=(tuU1N3Imi^l2{aebVTGBk*?p5Ec`Cb8mSM2@Q*zH}} zV!G=cT7*N=^j+Wm%^ltaTOe#&_%+4I72xcp-GCL?apm6ywj9_K4#sU=T;1EiXvxMb z;Ou?N_Byu-?g{N>;1BlR`O{QA!&8Qx#Ojrp-D|9|HHos#U(5yJ7$zCL;TL*e)h;vtq|l5yZZ`r(n-7J1$D5liyHRC%rmeh1YHx>(Q z{omPC;yLzR74DpuIL>f$*2Bf)MSiy+GvYZ(3G@16g=%9SzTO~t36-#5WQt-&_GEIY zV&`RHUDb@?HQ|dSU;QEEu+Td(RzvjF-%plhM4@5#E#(~sT~r=r4362Ch~7g+}F1BQ{ z+rME<<~IZjw-jU~TnKKOseC24ZLbo@7{)W9+HsWUXU&2Ixi6<45)l1w_7j z4(G@8UqOzXqMI4Q*~P>(+@cNWiawKV&Syxq5KsZwO2+4wehUtX-roso ziJfSa?&+v5kb!P$lOF0A!NXl9+l8*`q~?&&VViyq=1jO;7?$d@RuGof>SnINfr9Cw zfnuQq=v#>si34B?5)o0y>{#c`Dr61 z55NXQka%l1J!->_icH1`N-Algwu!Q&M%~9IZS&~sgq8}KtRP6lrD+ZM{G@SM(vC&Y|VxWIw1+yx$8!KYN*!j=cbL*9`3RDZQwRX zTd8N)mfyvW3Qo0dQX*=1JGlZ_<#!>PDsCzhDCk9!$8f;lqd% zD_+dFvE#>(BTJr4xw7TU2mfl`yt1Xsm^Epxy_@i@!@F-&BZW8==+d-kV^6Ib2S!%R zxN`>2Ik$1m9upny0dHF&b_<$@8H9W{~u4j zy!rDUudDZ)wI$5A$e$+%9-J=mfoI)1JxXyY)1LMHB%5qN(Po=g=p{&=8<~t%)_^nl zhFo!JxklPT#5pHWbUIB}-FliSDB_4DmT2OMD5j|5iY&HR5r{CF#8Moaya!ikH(|Ki zeFaVB)=zHrHx-0L+Eic~wcY08l9n+@mViYXsTM@4KOt@imsTW9BcNZEVge*Xc9P{Yz4<#I(*0_amy z(MIL(RRDji^F<7f1to+`bg63 z?e*7Shb{JsA#>KQjharF+(2~kO0Tc}we|KxLmI_!&B)@s?AUxm|Mck3ct2-H6IV+@ z2Gd$dV#F*{D}Ge95X}MzAVz5Mix#WI@O0F6;3X!RW%n)m=%kl!`somrz1heyl}yyZ zc+I`CuSYRwk;#F_b~9h7_wEqE1-~(gBsUmwcoT;ou*%i5V5=YO0!{skB$BLx%q71V z^UEcL?668`14(>|sG<9A{`u&qul}2=YbI+N_r*7_(hpzy_FdAdCaAEu3OyXZ$J(8e z)d zOrZ)_$U?)k?=S6I1sUF8gu*3m6^TP$^W>$IrmW0nX#wFy|A2V6+*K%918kuZ3(}z8 z#HI<1Gr|tYFcUJ&Viv1t0uBeYFbWnV20BXHUBpK*6T)hVXiTFT*QmZ1s)Tj%n;IFk zpuFZ??H8-SVX%Tkw;Z8th;E6H5%*Pg01~B-JmcNzH0nb336#Nmk-;r&2H(zI%J#*rr=o6r& zS?XmBQOxy=td>KS4$Yf5@Y$?dPeiWpN5@}iY zs>lX0QkXU~)=3$%7GyTlp8_4Izq%DoGx7DYkd5rA&PtNAy{o5ci=A|m5}`@~3VcYD z3)}>|)I=#uvZytngAA2BeNix($IQv44m(h{|H#y!sm-l!cMBfMj%1tNe5*vIgG(;K zwnr8P79R;Ri>pbndQqcZ6RHPB{J14Jy9y3qi?q8%@%Fo_m8v6gwbkP~uPs?!PE{=$ zS~7wax8RMheCOL0-##>!8X7DgVcSo;tyF_m69^rzCPOVqu{EU4U3c|L-v$HILED{Y zPrP`MOMNyX{HZ8RNeDWNIrzgM4zX`_VA;9JZ(hr#YiFr-qlrvS3yzSM++d&FWT*?aACEnUuAaXcbq;V30nINAD^?e7gGA65%wE0~(<~Lb9h_MacNxyJ}!N z``NFetet9er?y;gb}l}Fn^F#( zmfN22-1yG7ieODjMt>8N_5rn({L2w7wG?HgCAYp8&XGmFc|cU1nI$Vy=apXDxDTf{ zl9_!*hI{3R;i}AtL~# z8NQ%OCR8m=nH&A+^_BKcFDqPY>4$!H?xSI?n-TIpe316+CDOM(FbEHl-K_~^f_3Mc zxpZO^{q(qZRuiwTJ5LYC?gLtwfOc~Bw5$C9pvSx~Ji++`aK7^e`TQ9=F$`{! z-m$sQ{*L)AYgrgR(_h#0~aDfCfZZ!mwxcMvXkf5!j}nqY!g7=6eGdcfcd z|KJb&po09cg3Jei1mOudxFtK-Y)?3cD3p4!MskeyeJw+5ut9zuAtf$1ZhBLAbXbUv zk!~Y6Pq_kg_!klU|EGCu01RvpiJA9>1A&5{w||+4d@cxmFF1fXI2UnvZ-!WkuXa|` z_JFf@SoBjLZsU3gCs^KAKP@M23r2{hn2V9&aDqpCXxE7p@qC|$1E8P@ng9iJ01WtN ziT|g6FZhU?_lwQfiJ&-q<5NOBsEgWIE_O&tLbz6nb_oY1$BYe;d6NhPn!pB)7>$i6gU@$=o-l@>7mWh(i_7SOb8v&5 z@Dv+YF&zhw7Rf%S_&$)

    _5SNu%iH+|{}D#-iJ&3%BgI`eo}0lS6srvQ;KS z1S-XvoI?j+1BvNWvS4{}$&SOkxj#A19)Vrs(Sbx`2IlNJD`aEC=8N|HMCE>%XZ3TN%yVv= zRA-_*5cvXz$i)K4AH>;zIpQ#^&<%EX~L zJy6sgXV%;S^x3%4~%Mdvev)!ojYv10j^5_LruwzxHn9|k?!%ajA zA<)K&zU|6u8^U;HwNf7m$80FzBpKy36d$veQQcRPn%SO8&e^Y9kc^QSjTqy8YrRB~n7nwC zT_sM)h>XOj970a@nvU=O-qLG`b7L^c-E@!bgZt3xq3hsWQf1S~F~hmXuwbd{syo=q zGBxkt`z?Vk<#fm4Bcw=?EubalxWj6}9%!Gs%%{7MsCq!Fe0T8Ma+mov^0O1lapbs~ zOKBWP0;5ic67jv~j&5JiaiPi~_F@&qoa+H&bCySm#n?0}NgC-zVZ?$RYUz4dnd)9$ zz=iS??wet)EIU&*22+%8Jqp5V3~HK^oe~&xmy(zM&bk7`DXtyYHhXhN#Ahn|Ex%_> z*ac5_YDq5+rUs~-^Js$VRT>9J3P|gQ5hjQ_lkEqOjh{_K9r^WIA19?84_EI?9=?)Xq+f%<%s`|%} zsS3v2O+`TZ`0INg@i_~MCb&Y^YZc)P<|K+4_{IZFxQTST3=%@;lvr7mCkZ)WTN3X^ z)jF~*J<$#wKtnf+BNbZ9sav5_c>HiMJ3xc53z!roT~*q}`#{A1^+Rd^4+gj*sRevR z^z#-&nV%Al1W`u%K>#=TQ-~;#A(0X(^1*-p$zp_a@(jz^CD&x@6QB+pc0rBb5<*D$ zg=KLB{PkWOZi8Bq-aVW|m=WdBH6!8` zZ+>b}MQDGfd`|s4?Wl{T?@g_reh}8PCN>2Dm$xKiop__xUVEkU0t#~f`fwD_yvO)8Ig zuMNaUj|ac9vVfMP8Um;`QbiM#6Z(wN$`Y%91&Pe<)aoC0`a`Vm~WQ|Ff2Q=xshVC#J5GVmFtHdo<7`Z zPVY$o`QQwTs-@TZV`KXvOe({4%>MO-_tiBl%NO}O?|1pN34*;!hS3k`cehntY`i(d zBR2V@MByn#{`&cXiN|j8nZq0z0$+KvFqsYQ8lj9F{{OIT*yV2e`95fDY&JQQY*zsM z(?3}PqYI~IP=T&8L=T{4HG6ij|A8@Tuv(4POc(It(P0gxln1``**7oHj%3FgK7>t$ zuRO?4i&DDbakXv#41T@H7w|9gFWl=j&3R=B$`3Mmw z6-2Zv!D+3>oe3~4ME1gD6hV#?Zi>|0uIlS{5)7?+nH^yY&a>{&vB2803WkTll;+|0 z=2`-HIm?+QU3VM^$^2dUwnIG*f7MGBl@(i6KvBzoomW#%G`78FZCbgzZn{N9Km}wG|}A zXc9k>LS=XJv% z9lmTtKL7t-;|K7-JOOnWWq9x@?p1SfD5ofV(koK5TdCbn`|o}d(f`A}5Gex1l%JZq zn5oEUYpC^^y5Fn(u8f;h6;EQV0T?VzbB25%%*mw$Dc>);-==7l8@!(8U{k@k`4!{L zOaZ*DPzUJ8AAqHb-pU2MaTIl2`5~JVk#T*@aU+KzKRJplJgvAsm?<9rz|u2OZ8_z} z)Ylh7W4$SzE-(`xPKQ_moER8UZNa^j^%!pWN3>&lJnd=b->dAMP@^Wk_|-aDXGJ3m zht5;rSPA21TTSYTTwA%BWgjV`&Fqb0zE{cST#w`J+<8U{xI`iC1s`VASzZxD1yQF# zm9zYoHhP6fD@;eI?Sra3_{Iv&ZKn!<-9gaj)+_Bcnp_>E&f3@Q?0;@Nn`)GYt>=wL z9}%r|7Sa2|_!ib~lgdRueHM+|R`Y-hEz@s%#GhLBTW_j{oa0LA5GM~+R`W6@I2x)g znbx*VZ$;jhtUe8O_r5>KS7xgA6h3St-K_7IIL9Y$F0Ogqp_fpSasKlX&MW(NPBRa5 zsB(LyQ?p6oF#q)v6x0SR<+G9GfGN@bc}+gG@EclsaIOGWTX8;318rTU|P^^Ww6qO99R?mDw%>j{0HQN}dB$`oH_Rw)7Vx>}D%Bbyr8GQi3t0EGB| z9cM5m`_FOCJAUZ3PBf9rr4PIFBQgvqN?r5)mf~fYju^&~6LR(Zmb}kOuo5^T^)CF~ zn6>kKd|sS&PTkQjc^*fk6+$`+oY7md6F4%&ABnPbHBQ#J>rB;fHBLC>Wsu;_X~EEd zcBcAM+EmU(vy$c@1C`l{ktjsJjgjQMQ#|+AtB(w>E}j}32bP9>)QU%RiB~=5zd3av z!~&|se|cK-T1FJKpt8#@)c8qgSSne#P7#>ua*RLD)NpC-9MW%bUshbLty7z2_b zP*a?2>4IXbzTsg_D8Fkvb;Rb&$Guu;8n++wG)QxTb!#iUIP2!7DC1tp*>(=v5oIeJ z-H%W@sJhTllYgWt{EhgVjF`-i{gJJk2d(3KmADq5^S;T7WlH<^tM3CLCqKA7UzEa1 zzi(|{b#JY8dTqo*5hW6W86=Y!=aAQi}_he-tc|HH$K>7mMNC-aLAN?v;^B$1hhEjok`h=JZ zq`p;DUy=;fbI_UwMc`Y8VH;%8kAnGfey;N4$#dlPl!ObLjw>p}bk=uS%DA5&Vzd%N z8wOR9q7^WTkZYEGC!aW4Cc<&QkE`QB@+(Z&5k)>99lc9Gu2?6Guq^dkQgRo1YEe(x zl*VseR9JCIi^!yz71>2{+e6>Er7{vdJ{rt)Zlg`=FAB`4&Rs`b>#G@~{PYXM4v6o1 ze$u?U-)@|SesUU?Z&iJA2x1U4i3>+qjKttAX20G&cTB3_3s)_ZZ1IWRV?D1MNUrZ zP@)em!_x5Rpu+w+Mefle@)SPheRdUl4MoKg46LFN@sOVCeSQLlNE$YxJ%D{>&3jx1 zb^ZUc{FaHwkJ5p6W$Ce!%E4;F=!R;KnM0RmyW1Y>$8|><|#=7rhyV#*ZfbmkZcewFNkMOugABw#>Q%LI4w;hws z_SHkFcW%Ey`&wAfD3pX5y&b1NKKdx+)lQz9>twdQRj(v12}=^UW0NJd?lzMKcvt2R zh*1?RqB;<)1yZ{T3P^b{_ooU(o*R};a0zd3+$Lny#ND1-(^I+^)x37p$@jpgEft@R z1BgLVY^vp3`B+39IO9re`SO6`GHw6ocxz+HZ#?!YU9RJbg_9tCg4p%dTjKbdCu@XK z;?Mp5&v*a+K$?bR=gF96$=%$Ki@x91`hwV3#Q?1CN2;s3XYaDZWXkrKemOUkGwKw8}icqbu zKDz*?mbaGmLR0o;>U?RZh0ID z!%-BC7uSJuhIEL>Vi>3q=^(W}rk~C0XIgsySk4TU;*AjoM2y4q`G`fT){IipDARDU zA~;?W%5#NEmb64oSZ|>vD>x%yS*O3GWV4B~xB~z`dR{hQzkMf71Sx0n35m7*{KPSQNgf+dM|}`XNv9~QxSKE;^N-#=$NjSBKz^z z*jS(#<`nXGUNZ?OYh9nzMV;CAmtI{uugyj?mTiY-m%7r$l%zJeKiU5NxjCG<)$=%N zNHzDYctBWV4|b}@v;4Am2U8I!{=D*bG9qat7tKYhQ29rcz8s_&fp=6x`>T;cF_eG4 z@(&{T`-AU$>bBGB_a*ZubhB(j`@9y{PS^M^mxP!O#5c3sF+Jx(NAs0vf;B*3RG0Am z4VHZiz=E;kVub1~9`%N9t#?<2)?$`GLO|5n=*a@yH&dPiYiS2U9YUr_KmAxiV0s*# z=8y6W7sP6et&{W(rP#)E2V@F?agk>diufdN+0*OsqVXtYkUsycdYsSf?s6weicvR> zKtp@`c|Q^&0#Ey931EeUD?6am5=>YEWH!oFz7nynwn zLA7*!ql|My8Hyoc+Pifx6VoC#_JPa$qQFvgT5qxRDaK8b_d#C4`f4Dl%Lep=_1eWn z+B2(~yqcs8vKLH|!Wpq|*bx141z4pkXl>KyG{0tQpq<`y23&&WE{!3@gSXh8Mv6$c za0|ZMQNbv3Q*X(%e<){6;5kx^iFFX1KzadtlABVu`ts3C1h31mNox3zsQIfb$o-qk z-}1|8r&^89%Q=g(SS^&V>qJpW;Rg3j;@CnH^ZfK(t|#JVHW&6z_oZCFgyRl-^~4A0 zoj&w+Sbm8>nPMW1XI|NxFQB{kEli^~0i{6gFm_~|J4gIbtlE~@`SQ7H8j1b_6%K>3 z=>kBie-5(=ED|8q)KD{!%MvD#1)Zx?m@CSCyh-sr8brX%T-q&3^Xg!mE1 zx#Nbc7Edj=^ZtVMafth2_p`>ZJv`VRF?tUKCgR3#Gknc{1L=RbbDbwhLUU%u19Q?p zLjvb=lKPf8R+D)54pKEBM*x6!CZFkV54`JOaG-^7ZAxyMI_MeANRZ+np%PM~=q#~b zfRUv1kj&u(Si)GCoM;&?ify!rCg$iM=b-Duk)+q8WPe@#wM*Znyf8Wni0Mh1ZNFH4 zo&43iAG5x)p&vXLIUK_O0$4{0A*Otzq(3P3lhXPWXR zX`I4clrSqe4rsI=qc1sjFd!Vb)7_jKdsmCIdwmnELa!G6I{d{qaG!9gmeRF$?KPBG>#P~a?@yJ+hoFoU(mk3R zRT)gjJSoJ~8KC1Yo>!gj&?(!7{a_RzjnI)4RI_{5&GNftu@ zpv)RO3xQ+Dgc^tIJdIT%Yi;4}x4TM9foDe0opk{Vabe#>hn<7=m18Q$Dtm6mbjHKi zgx#Tdb6NM-H8@aKXufBo1iQjJP_gD1VJ80nxHD@YnTKdMg>NI;=w9V}o5gRqZln5w zKvJz(dK%m09dN@)U)%tLPOh_G)Mm0{mB0zSoijzd5xeIFw9apzbbp6y$@Z(F4&)#@)c)YuleD`{a1Nk5P7CYd`TZ z{=3)ET@@R(?D8LwFl_!UUo$P&)u&sob@+Cs~Xx<lxU-H(!ap|ic<$dD3;|7r2ykHckA<8v{ zYd;J4bietWW}9{?MUS9^h+TE_&{8bOv+o%rINXTFAcc!=?HCkaH3HHpw*@3s8H!ZD z%F)-lP!OcGUZyRxYMrv(cPlm~5}4=dCLZD&EXr@L&RBDwN7g0n(kfr0C75KU!|3qw ztd8s<=~M)=KL{x((T7j?z+HpJpc9|f0v@E3VuDTy=XxN3o#A}Vuc&;uTez*E92Zl- z$@W!}!LQIEYLiws5IsPp1=w;w*R(!%Gz}Js|M?o#g4foQnk|q?@e@7Cs`+7;K?Z5z zd<4nz$m+K7ibNa)-pvO7d|GvOU$Lo^(F^Rd!7L8h>w1i1TzYETVLurv$yf|n>g;s0 zd+j7qkWtIU3JR;sfqoRTo{&~je>@{S$T=ts+dee`0JY2zke*ymIr}5RdIjB1SOkbx zYpLep9)ZzI%m|^Yyca43v0-rI^&m&=y@D$k@Uv6CGhi`d4aTN8_%i?%PHokvvQA;5$O&LLHvQ+mL((*Rg3hU3Cwk1~N-s^Wbw4~Ns1axV`ygg3wRqHP0J&z?nvwQQ&!o}*`2bZe3{T@}eRxk!A} zgqC?B`YB8nYI4M{BfJj9#$5C~5-yfOME6anwfICckB{|6^3d_u_r2fClX9Xgki4x# zXF$BHfG$k6u~?cQOWg++G)UXz#aBo>#^Xu8du>{QuBcLJg5se8D?<#=0t0my0)I7m zc4>y;fdvoQiYIHDH&E~A$3E&~V61f!bO?G64jkO?cbh-HJkK}Wt96wL*wD|d$U|*% zL41>3CR6?FlJ``s3hsv#_otPEY0EGYNtSxUp+<7=mit*tn;zc6ml|*;vTL25Rkr}C zMIGgdsvsT0puvlz3iC#|U6K-pwQy0-b{-D;edV2!21Y86-&HE$)(L+}ik2->ARqrzUi{mC_OHz?2l2CXHJy|cd~KqS8N?1( zy5Ni6Eskh~E44*(g=4>f0OzvE>22GNue${cc1>(g0tqy+LPzQqMiSpo$YN;~UoFh# zKwUuJI&?UVKNQHpkb=xYa2YKIdOts8Jpjru95y*-^i^8KfafshZPlMv@sD*sfy57i zRpUx9b^R1H3@~AXSIGH8JO_hc@Ag)+2T`w?;bQXFtit&POdo+?YAU`5{8Hm_Jq_Mk z)TIC!D+agy9{ZNv@_8TI<+?jm25KrVUYP(!gZ8Jckfyv9xU;kOl~85iaO{( ziemZHYC-a`?nwuqj*u6U-?O14qe>LNW_yZ#>;v`s53BIy#+TbG6MYc`=~gmP2B1&Z z1wA*xd-=9n8w0=7{dbLuW7vhs>HlL z5CZ|~>^XG!O`664jwHtCCV4KE7amH60}d#5}n_c(nPbilq59Ryw9<{o#2)Q^M) z?h})e25}C+MF}*a7m_au)H?|^Ir|oH5+l&~vT7c5F%{?R{3KK$5jSP3kA#@R32mwve{w>n0s6+$&vdKzxAVHx zQldgry{jt$$fA$w=dzQ|Y=}g}0>x6CoBV!Z_Y~S{AV4XmIvV6UQp5QmMgB7^0j|p=Ng8YcU)sy`*Cq`kXQf-N_;AI=B zHSy%pWs?BEf|zIwy1D2*tc%EQXTokhw+Egtr&%(Z7nZL24e=cH6$*YxP~ z|Am}?Ff}z^WAP(XKXkBqon=EEUrOR^I8l1g7m?zA>`VErP zrWwE>6#p2IThi(#)?__FX+H*1HEb?nX1Enb!~n(@-l4dRRmMmCUxA9>0EkO;L%x@h zA(~yJtfGx1i7t7`5RRTs7_;KS*te#a94bQO;7xFVM;APa{F$K>&iE!3Bs-|4^4OCb zA^q>OW7dQ2xX|Wkf+7AJR-<=`DPu=)ko_*!f2wbO6?Nv`VD}Y1;LBtmHE4u?*Q2pO zQ9(m|w3vAHiA?|F#Sc0}l~qwx%lI){Q5JzTx8fAs1WxSUR;^tPjL&Q@e`_`vv08f; zYQG2Rw<9v5s??S0X)+OY4IcLBFKsP#F{H$PZDQ+wxUUG^3R;wjmzzsbsY( zKm9C(cl@umOo(lU(HF*g%Q_25@h(MwM|dq!lW>va*>wd1kS!vl|guH7p@xj#W~D^SDaMg@sU6hM?j1;TBO zse2t!5zVH1?OzyISg#6*NJg?^i#Y%&58}fC&apx8)57 zfp-;Ej$FoGzY(&Z&N~BAOmP(WWP6HmrKi+sMi5LPVHE`7K5B7f%afm38{mFh~5Jb~H90$Z|a!XZ!e=%X&2J{>m%NOr7S0&x8T&e8O~}LN&nwC5@%> zy5qPZ)Y1{Y>mm07QoQuQLsa4%v1aMEUyqkrn%pv=$HDYACM}00B=2ebO-{Y4Hu)6Qf|kNQR~4|;k_bCG^adGe1a_NU7!zGHia{@=Hp__k}h z0UHZaS3=w4FI1(^e8zzr$-y_3dp0?(S^uGcZkw1@pqiU;%<5C2U5`pBO*hZ%@j61_94j^9`KZ z4hn+jN*GoIS74ilCb64_fEcz=KpCLi$f}m zW0Sm2K0lk-56XQrN2bZytgg&k*yOVz?edgSqbaYhZoxlb>HUwDnUXGbu!Dz=ylQ^q zupZ>>t@v%JK!CP`Qj^qM2u?1B`+ciq)9nggCq)kaf?L3sGW$*_fS*m|Y9*=g>CEo$ z&1ff?J$Ti1S01X2{m}xn3PQAYwGR4UjWwD+wqM{i4JG$SA@I{d6eBAm^x9xtxt7~N z*nQO$C3Yoo&+KG2@yg9cM(abf`|b5gYs5S~Uv>Q)hUUx9DCq}iS|!pFVp$%5hUfwm zg46D)azaFcd*fs?%@SjkLH+of##cJ+AK4(~vJ1gvN3VHFjr@7=UcN!(SVqEsxec&{ zzM(1fz1;w&*h!GUD0*9?S24jOEq2u5@&gR3oX76VX?2F%IhhXG4gm><(^@&o_F_N7 zys|@BQn;cKR#)HNX6R2yv(MpoC?S3?HJc-y-XCiDXuni|8`f>uX@jNbeG{L{^~nPi zjD7N4{PtX+Pha$anPZ{>r3SUZJ(HFV~AaP&9F zvkeZG+Tm>%m~;s4gVrzr&Ca!;zW}ma%8mLkbMwgdOM!}L4kSjv+j90sJh<>B5r!)Mu)&Jr=l_2`qZ}U5`jN! z;s67Pr?C_m2hIlJP8;UC2It+a*k*fg!04|4J|FWr-+K(;4fMo@r!PaeRRJ9a>Ro;a zcGU9%*$%^uDscO^uDU$lkXkkwNq>&|VWkUc^~ohj`(d~G9!H-5$hF!RVB4F4oG^tR zKsB=CEx3K1tuipq)-DaPCyD9DUabO0_3W%eS{hl#tzlbvhn&vm-KJ)9U2^jLhxGdR} z5-i8~&_6wuHo?EZ`%1{fI6zA3pf`CR^R-+qd4%)^I9wI=O_wa=PoC%&<^*1V^MHdf zRxkqGil||Z09tO7gy1ls_I&Ksa*6WKeaFd|JA%>NVOjpeeyI(vGqgm>WBT_=5m40x zs81w2gJ`fPhxF+htL+0Y&01C~ATs&!PC?>Nbcb9rhs0nCw_Jm1PA(SY9yqjRg8CVH z5R|)Wn==IhOYDz+^?hO7^4AhQNanQ6y6KG|VTO6ee*-yE9ccrxv=nH>0xyz$Ze*Mf zOsr+Ty$Z%`H$}ukgqZZ!MMzwB^H@{=&wz4M7Ki{gbvyIbgbF__QTU21l|XPsw@Ai2 zc!Xi+OavQJ)S8`EFS{h)TjWXpVBfMeHGe-2d=EL}Xu`O2zxKry^S3_-h7WV;Mw#1K z^4eX39kx*U)asedn-p&R&9==i^lD;H?#GKvNy3vvqOGZ1q5a_b6hHmE-%i3cXsV-x zG026{$%V0-mjxZOf&JJ%~992EO{!(J)Ke>SVb>?*ZBy>4}L{XBXRxpR4aM?Nv+=!DEX8t;G7hIMcb+_s13V8j*DegHPBh( z?IOJdx>|QBd-=y;E~+%CdiQe!>+Hi}u-)shse$mXpBZhF{r`dCG=(vo8&H{{ist+K zW;iiK0S=_WgsZ@+=^=F3iN`>I+qN|~Es4?p{td~V+U^68rQsk#l6!ecxciQ;8AI*{ z^8UUVBEum(!cOe|l8r3?+8blYL3qNhuM&duLa9pSaK#>J)9``*YJr-dRF&;SS9O~$ zpbxU|<5;-%)Q?NHFM?m#Qg85D&)LCHRA#sFlh@r2+1*&^s17=66oDr(TLdo;q)qT6 zDt?IBnM8D#n<;@BjGZ-qHD@&|)fiN^|DwGP-u%^De{ZNcoB0~WJlz4fw1xi2l}m}p zX76gu!JDYM2N4939ZL^ari!)HB%cvGh`FY`P8IUJ61NAUc}(oZf+Tf8^aMJU{)6`@ z_Oy^%*3Bye~t~g7W8BJpL>2mAwE@S&r~EoOT(9wjk0s~ zby4Evd-D{B9t*+VQx_`zI}X^c(U*6CjL|@dYZ%0iqY1sO z174OPpyZHz_nw3luS7XN8XL%n7AFvJ4j@)gA9gEP7A{xO={lIUX6kldi&HC#2-^mU z78384#wLf}xpfQyG{OUviQO{nAGgRAn_|JXz-#>`Ifggt& zvk{1=h?Dw4vhK(j1CAfU*5;LH+f~YH(l!LmX^`(B(!u|EtcKd~-(lit;M~Y#8$Wv; z73@xp@d=k%Q~fIA@yoGO6g_8b58^ww`eg<6=O`Ppgxh$5PAe_4E8P~S_c;=$pRX*T zdFdDC$B)BL&xU$!gB|JAVprCN)1-E;t-czjy3AzkZ7O1V7!;eBds zrSw0K{=&a{(0uyVAlxX6w|_8+T?Z!<_^-9QxWr6o*)~&kHv$L7k0T1hFuP1Q;;l|# z7noHC%C^ZzY6$JHxpl5ox8ta{#8KlUtOlP5UctI2$Y5{@PYW-X5Fl11aRnzp@f|^}p_(dVc@!c%Jh;_cvg>@kPeW~H+-k(x%y)o zqGw`kYXY9Uc=BY7&ryE;lFl|W zwLgt72BGj{t#3ilpiGVi_4;EYJB5CGwKni-+d?U(>q*3F5brpRGmamTHFhOk)i_9R zr<&C>7*tcH62D!`d(2kyBZAGe`|I^qC=J3gF-SNs`ex3R*>NtCbN=uB{OA5P;#o}2;V1{b~jK78yh> zKO?@#{jdYm8AqA5f}9o!H2IHN9IUIjZp!Zuty0I&6uP@q4`oo7W;;tP8Zq zx6cH6l|7ri4Xo(v0P1s z+=H=CjkmDp3!kLv-j zUjCEA#fQKCm(R(6%;(Tp-omH3g`PJRVw&sQs%B0^9ad#T#n_#vrgd<7op%B=o$QK+ zf*A7Dw?)!xNS%p-CB{l@_hp(lyISgWzIDcTg7YlJUK?(+Z>)wp<PzxpD9U6!?FL2kig8>prmp<4RVOb?;D|_N;nXE~t1ns)DW>zS;gGe-oX9 zjSnE@Hz*SWjLFiTN&jU6|NaG?2e!fz@`D*E2fcq59o;tJN`{aFDi4;zfQP-GJO)i2T?y*=ZFD$STNGn~$cw$&6-fm=_KKn8vPQt~9%$^Nc-mZNlxxR*eT zpsKw(06R|V<9ID;$Av^&mN(Dm>=szwX@675hOM$%!aZ@!O}YS`b7j-&=TEv%V~TBm z`7{LD&$=kD{b+yd<-Q_pkYHqeDBgkc;x9+DZ&G?azv}i>!0z%(H2s0*%h;S+`AG-E z8)f>^SBX*bhVpQHO#1oTT3HH2y)SQ&aYGlm#9>mRU95mG;{t{kQQy;j(C9U!GXyFS zRi`OOq9?VDG>R2?v#;qH8#rn6f2b>`@X%ZeJ|`+C&|PEI|-)6X5m^pZ)#Os3AbrhfeSs z*iO@mQ-8gNso0xPAqDb?i-9ykRvVRMt^C*tQ9A0mgP~w?~5n5I?Qu zZ)R?+fV+D$?4h7y1DIBnWBr+RVbsG^Lz=c@Dg0oV8BG!*QJ0iPrwrdpm<#{y<;_-uFFKW%#&fdA2;K#A3G;6P8uq7B74fKAPQxj^hvC~C|df_YR! zDoNy6_~o=r)Di0dpLB`%`mh#gYi_iVsG>s0W9UGHk+7&J>`Vvhg`CH*@yhAYq741% zq5i{_{dwEUVJ;!NwJC+k7y<6gjwl^95vV{XgK}q2&Ai)4rv4o&a6~@c*lG?!hgkgc zoFD(kIV)?yITxNr6dU|Dclw{^zSsu4(z5my0jg$Xe?(;m=cb-B3Zx>o2*BeylCkNJ zNHO#YP+Ak17y~fgKy=~q?Py#6r2$3kl|(vnnMr`oZd5jIZNg4x6OP9_kj!eoQ#W0@ zeD+Mt-<&d>Xc9c4MeI~E#`4dY_x`V#w=bIg&6d{RJp^M0BoZBne&}EOMQs79uW@qX z)2*PrF1aKg99E3mjf9v6uQ;Ymk4sK|8?|ZgSrjLWa87POC}-fOJ(|Blz80AgJt za5}Aqp>%7c2B30o!67&m-uw62#zD0!=#h!9LFP3AHUjrD%_uqC08M?^Ow9q{5#yKe z1D~~byZz6bxTM!-TEm#Vl;T;ZmGJQcQRQsw%MfEbw|H`E+4W0*8|S0_NC2f1j+yo$ zo;o2Ob+}RsLw*R#pGSHIjx>7Cx5Rot`FDI$pnC$u@c-#hJ5HTGx&FEhp=W*_>I>PB ztbH7eN&rYB-)3Q*ql*6A1<*kbAFLjvje&T=MlhU5^MMIlz>X3$&&=Jb?8iS|Z!ClH zBA8WEtQ_;0Pm`u>y7Oag(&+IG>EcQ^rSNik_qe|e!U_$Kpp~2Yeq92`(O0oLoqG>R zyuVEL*Ygnxm|gqpI20JsQ`0Suj;_A=4OZ1hmN&rb6BD$oNSS^vO_E#bPH^d8iv zKAiw1>5J{|4TLxBT|K)ZrJurc_i-2Lcm!P3P$;34oY=4jcT^t52w?n^yAmRrI(SNQ zae@VHm8l3oTOI=KVg;0%DNIEV`N-DGdp}9_iM?}>3 zoIJwL@7IT}Vie`3%pc9xw%srV-oTad*gV19wvF;(xknVe2y+|76MuaMa~GU=8@_8mFHMzHQN<>|Rc$ z;b^7j{#@}5bR;pjC?@Jer(e%b7x8Bu-PrR6XRE^zm2#mM_LDl6oap%4p84}rVs!?P zi$3ND8TV5A-0izF{&FAHOh5a_M*hj^-kXp3uCv|FjoyO-RwiKzcrY2x3!fX^f#=ao zD5>BCk^z+7k@rbC^lnR;Q?5#p2UV2ng66S+9+1gkRcqRNINnde{%5f6Z4HfMq(HWT zIco@;(JPHXObJ`!x-jf_HpMf0=fA1%;k+_305Sdm#4BQFpp5p3H0i>E#DE0A{KOgh zHMBEllcck@pqcQp81T*5XDPG{9A{=^!)-ZE^L5KUn!ntFO{J_41B=HzQKKvSt@J+s zFqyQVi~=PMYS{J5!7G~FS(@Yj`CetA5FSllvTDE52HY2j@}xJhEDU~K2?bfWNS?_` z+_w2RxdG`qp`l4c zg`oX1>x8(|Ob}{q`+1slm+LU=_|j3^(Bq|)cg~p}lq+m~1BxuE0b#%fk1>J9VSp=Y zh^rQM$3(j7(2gMwR~p@OC$H1`^dAgYPt^O?pU(z^L&1ZUj&l(Tt>wVYh}~oZcu?s6 z*U;qr6?`Z6{mpL?LT(ctIp@jjs-xw zz_;GLzf!h5jjeDjtG7Idg?c-o0a6*h>E{IZHatd9G4uR!qWW)OhZ^Nxced)YIG_K0 z%3vOhr?;?|j@>EuilI37Xzj?>=? z3*%b>OQ2?V$N~+3a1c_Z`}P246vCiRU{4ZgqC3{NeiOKyqWkaoOFehQKTM7{!tcAQ@mI$5?_WgYpoS=M zDn9aDQ<7SwoqHmwG!o?jr%hrka|i43r$_bZ*}|o(!7X4!NJ}E#~AH>xpBD+R=r&vlR*~y9Hf`mRpE$Z`9tGiY|5-)6}I( z5Bvr_jr=*KA;cdk3*WmDMk&|f)wTFSI4IwT=KSq=SobT%XVV4c*nu=x6D$~re@0Iw z*S&6Kiwc_nxYP&IL>AoDD12SBLd)6o%G*HB1o7)m{t3DM%b)(d@SfVTrO>-kSG(}T zmNLqudWqGLg3UV3ffz?j|K%0+_q-zC(tvACi(9Rs-_Uwsc3eVG{PWY2@iTj;g{;ov zG^qGDFaz)11^Jv)sO7Ni-YIN+X@TOB0RR#KiXM8ZTQM1=tOp_*%`#w84@ z_h;XIcM*6=n*sAi?l)X#p4a%ID2)foklj)84wm36um=EL*_s?01=rqW*O`bKQ z2VMNq+*fDbZM0F22)()g4L5-$8KdzkF1nTGSKEZOkI4a3?u6{h>3^Ft0J<thKpeS>jlN_17=DZc$R<|d^a%=+KGkle?v*Ye<;x zM!<^cLX?y&eGgBqs>30=+wl5kCmQIwqLz-N&auy zR>@KjhmzGg+0C;4)mTw@V9dG4;fVsMAY{j4;r%-Z@j?*F?h@l-#sh%@)+r@BG_s|r z?e<^y84)G`5&Y_h=>V;#$0SWNzfr96pS`Wu480>gdrZ+v7{EWz+V`RQZ21pE+ubOC z(_PV7Dt`m~&8u=!RekX3u_-85AL;67eiY9FH|Z-4gBA6!c(JGAx78P)KKara?RKLo zyPTYIpebJ^+OLm)zdb7Nh@&21tv6?F@2C3X6SNy;szD^%MwpmN?ka^ zjlhvpl3HOw7DdY46P%5ax{R7LkFDdK`Cn!f?<8>Oft@R~@_UTH?T=2yAU-~HE)Qg! z%@G5*gn9mx)N3BUhIhLYSGMaTsYOK+4uHDwqzS$pKBagg$-@2n`P2=q!f1hZ@Q7@zi-A=aZQy~sz z@fY{n!Dc_JoFZ^j3|58A03c1IDz*{iK9_9S0vfJN5+{3R8?Yd|wGShk`a1ezH5s1t zI*gmNf*WmtJ$)^=RK=OW!*YO>EMvBEG6O2omE7$lMRjpQZ^%nKwtOe&mO;NKx#8u) zBvW=V0z)HKis~SduRcol;Gg6hl2HuNH?F#sRyYdBjLc-;tWi2T8pJ4D>^&D5p1ujT zm=Mo+CZYoa9Y*mdPwa35X8T6iup!YJ*lrOyMu zdy(WGZ3(gv1n{d@Do0xqjgSjT0<=uDXg1U{A{x@`g9ZAnAiv27YE`RwU0*w%+$gv1 zyQZ8bqDdv{`jLbjH$Z&abc!6IcKB%WH6u4GdK{g9JUtAyzC?1h{!e4->^k_6(=gs8 zov~(x2mefhdT?%X+GM$VsGR0=6!8a>DO3hpnQ^fuYyP(jgU#lZR%6vA)!!2ITe1}6 zFm_Tm_9Wp2S!UDirMXSS9N->ki0w>iAU?)i0%i!eM1`ejxx`ECzYjLb_F2C98OcXH zoWLe)fL=!{bo?SD*=s$7p%u)$I8?;7eWt>wdfyv38DW41dwh6mLLw(spbF9g(CNMA z{QZ+O5OSDjTyKGd*apDHVITot|;T5m;GrS{7k{}CK^o9KTzJFe=SGIyzw7~ zy+N@jSL4b_SLw|eU|twE(qXErSrn~{eD$t`cAq>lDIm zttR)GqWdvwcL>R*2iDlg)X9VXHYh7h;X^K6!WQkv>z@WM6sXoUS%$tjP7ps|N&n$> zDc|e{9b$M@41WU$r{$qv|Jhra^Pf6&5GZDL@hYJCL;@c`5~0h9(2Il~U&3S4eE6u3 z`;V5Ase306J*PjuOf;m(=US%}b+!FWxAE3@fW62Al}*KEvm?o808#4JQ*IMF1sP}L zc`i;5l*+^9P7o@*z>|J@vRmJHav%0+1><*yc%sh<*$KDbC2o>al)5ejUBHGXBj}ui zv`bOHD{9i8Y2-Pg)E~1?v2d~|(6&R+fI0xcmXh7%GM;IU8>3u-Lx{(N^qgi*Hg#f|MDqmV2)X-5SyZ*nYji_ywdm!)$~ zHDn-p8wLI(xUpPQ5(-?3GUm|x4!yDaO znG_oE&|VQ-s=f8;k4fx!7_8FS1v(TZG_ekTEMy)p^=5`xeJOpJ3;U$r$FZnhlYdb zvl#*{w*|N)bFcPL$SR5#5P$BVH%?VzfsOj?PNJX4>Kh^q!izjDT0IImK**kf)kKb( ze&AV9d=aaMjQ~X=+*h5U$0irNJ1Y;7S-n6-4k2v#&Gao(bT|gXcZTVV+)3T(rmdei z@~^z(-(bmxdPpgDxbO^P{FJ7smmCye4Yy+3UAGaa`l3xSp84$PZrAMIbXlLaL`@03 zBFNSu%XmXX3>g+}mS@y$L^$`yE;PahM@}?{hQ&Jh2S`k=G9#buCn;Zfc$7ucXz#fAI zQW})5jM#%5thJDO6J4MV3xwP?)|M6W$F3SjxktPj2H3f?hCo zHe3(zf|*fd@4v-8E>V7Nku0_5GK-O#!R|-NNjBSKG%hlHd^7)yQWFiun)>30fxf_}Ej_uTL3frqWbi?Id06k~G zghDKJk_|s>$p)s*2!7kvMf4Asu_Mh-?`3OW#%$cMLqpXfe1&QVs*4Uwr*)QvvtraH zn@sCm5TRtzwC~|n>-gqN{?3JU%29VVIgoE7%64RlV-PqXEZ?ksY}i}epfZUPTC3fX zgAPH2AU^;|W26o0E1wDC$%Fg*2F>$_qg!m;pXAB{l^HB-BlKROE@ zwY1fZF`U0|H*gXr;ZZ*0lIQL!2do@3b{_z-up$6;Q#LAVI-Xn!gRP38AvB%}K-m1k z*X0^qaQU@by3Ih|-5Z(Ew$Y$~QmORe#{Jp7joA$FBr}CItHcN_U)V=B1N^X0m$)Cy zDYLDCFIAkbJ6ODe)>B4y$2o>xPM)%P^p75(6{8WB!t^dNiuixNy)&dagpktO0K~Cp z0`NGmF4A9*q{@H=(CAH8wH_`aP+cWELiR8YXsXB)oR_@NlI80d?!g}nD1QQ{M9Y!&Z1o#~pkPJeE+ z9Rcgla>n^rK<-4HCbS89Og7#{K>Fm$t6OQM5i}|ICjQ`f?Oq_Ew!N)6Ik5s6%I|zm zx)Aas`5*K;c~Nxd2P>tvC3M9-2cpDC+Ii@uNTJ6NHyC0pCBbA4GQ3r)l~1985$zTA zwUKAM95g#5;#(hiGeBIrP2%eE%a#e6<{Yu2xXPwLeSfp|v~raO6t<;3N#%%Vyj8R6|8%W@L!s#isOLE8!wJ z)P|Pn6(EeR2vYNENto;D<(;8d+wZLVF1>z3UsO^=KAAq;9O^STTpxlAc^3e5 zWNwUaC`LQDOQ-kF{UOH26*ef2Tr{xI9|0&$?uD5-p8h?N&V9P+p+<7CZ`nb%5pz|p z0I{Z*J}uHOxgUxh!$wNl@2-;0RkO?^TfFd+Pp2VZs*mmFk`K0+@5#O;qsP%1Tc7O5 zd&-o=P|XR}!#`dZ+wQ;BCRwIMI$c;)J%hW^B{-QB8Zd7~b~{=Pg;skuHf0&Lqi7G` z2%PxNVe4ZNP%xF6e_#+Fa+2{fdh7g(C9Wj;2drdxTNnZuJ#Otq_E=2aP`<+-3ud7j zE<3Mx=_0)$w6_BBb>WpVLRUs7KRX8*EJVs+v$fK{_<#kbqZ(zB`Nc@hkjLBFs;8Z@!6iV zP50T6Z-nVgE89YJ2F2($+nQc)zgeY_WI`3-7Uduf)CC=zkeg&6pyw!C--3o#%zp}b zvZSpcw%@~ENQV@i3KnvQEYn;PdPxnKY38N!>|(fX%8~MRx0-D-Mc>9?SYoC(do`=_ zzQJ4JZ^0fWI#d%YD3Dg6;o6k&(wc%hTH$_*o(4x$+vBC^u6__$ zTtAD`lJ3`kF0O8iX;^AGr3uNf+^%s@G;6sm{uXLYnbio5unSSgmU++lQjbxC@T)*j z{5;1&-K4TyomvuOiQPu&UEGKbdousD;CZx!V>|;LY9rl2}c(@pK~!BI~Bsz zy{kqMw-MebUikt>%aE3r>>WYd;ZNHVx1RI?>VS{oxHIFr#+T{@ue}}T&N`9@Hz2Kp zkXx8)C1@txG8FZ)usTCe@M7$%PXacGxKyy+APh#TEvMToikGnp3F#SI@+}1xCIX{K^v-)GUv@1C$8GE;2V7hREEOz z*)^~t@1?u@R>G=65Zy2#Qs+qRVYrscbm8>0uFoyqa=gn^ggxbhwbLbi=ff5kSrT?9 zd{2GY*1!*tJ3M)CWsz^CP3Di!_a7Lm&p|^WVUxcP$E}U>tBi-O*48An8dk9=wLO}z z{h$=Y604ozu$f-2lE5-^|DZ{x3o4&F>=kY8+r=i$V@YINSMNy%u$UAFTsIzQQ%k28 zB48F1AZSne`b{41-m}yF9^a2yR6Udew$Zlj0d$ezwO_M0gl)Z2>)wf1NIC8-I&Xz~A+ zX2V~lW>Dq&hKm#);B^r&f--WT{}~vO49AL(Hy~@|Nos)X{}pongc=(o@6s+pVd-$PPR?l zURJH03cwTl7UpVtp>2`;QYM{_Hqw2q^+fj$W$$=kCh=Co4TQ5v>S|-JT5e##l$!I* zmhvraYY_s|lGvDkXlI;bJnkb(w=PLtL}{6dO;>Ef!^W&m)80E`#O!&Y0(mEw=E`*{ zcYA|c_mYh{KK64!#vO9!)kSrh*4JAWf2h_BfL`J4E&p8G<>8WGoeQV7s2M3xjMdd? zc3tdOoa&))gI$q>S%E_!!FkxY29r^V9fYJXKujLtYurfSQg7AEfF^AOSqUa7UH-?Z zmfyOwJ zzxa~e@IF8o_66uG{EMOwqz}?=!$ST%sm#zB^>Yy^K2NvY+uYS{Ecei`I%7|Z zp$q3^9Mf3qOj{qL&rC4iNC<_g3kF$ie<{Sx@*HtGD(G-^450-J~b5H3;vC{8+kfr`Mdw#UXJk5}atiXMQ5t-(@#A z|F#7h?H36^sq=03C=7G-*u*LC{mqN@6|Kiu>=samLj?c(=ljuMM7|2^`q0b}}`-*}OpU%vqC#3>ulPxb|baW~VGXP0#YdM~`$wiW>~y z2=>t!UfLTri&8ways0&O=B&xf)lfisyr^S}tj}~0lROd#_Xz`n&9f3!{6pRxo*n;vJB{I|sW|5vZl9(KtJW8R>N5%akoAn(p>m$tJXBtXK@w z7>$rg5=5E^jyVR#BSG;ipyy-dA+%r@@`88SG5SR|9rT(~73dIG0?OCqDU~c0Pz18g~7`9Tdrh5m~ zdWd&fKNzO%se<$mOs5xp8?fqfWD{m6!vIE=OwAxi7ryl=`-Cx4o^X7+3Kev6Ww8|t zTzp{8BjhOOg6$OlZJ(5j7#?rWoTlpawe#x)i_$ILmVXiI1p@+jM`lz#XJ#y4cj+Lw zTMO1@7W*sL39GvqU4iQ>`}B34I08=}8Uk|fJ^jcWw!18J!Zpc+3ogpa;l`9y*y`L4 z{6nPQACteVKFJ9Rpo^Cu`>B1#w|NFLTWjQ4c23_vy|_jNYb}l-I;~ULWk+qnr2O}! z>$SAG0aK95T&x7%{iu$bO9!p#8j4W%P09DlP+fnk?uh%J@=xj^$|E5b`h8GrklTA4(_Mv2axvsAS$LD&+oV}y{FQ}U>#09R)kD60;# zWowrk78(M01jKc=ns>*bsRA!86|N#al2P^=VtJTKHgg8AoAX0 z|3(Z3=4XZI|pgZ+Ifs`npQP2yM3ki)mz&7;pSP#KWgd$G4_^I+nzP zFQYdT$|B@V(PZblG`rAb1T^!p3A0{IM4D&&%U`Tj{Ghig9e6f5%Fc2ikgc{{1V^AC zh6Sp&Zzgl|ObnoWzDy=ryU@Wd*qu8MBPgSfKWtEB7{5-`!^U*E&V+Z_LImVppPQ#! z+q}|viE%>IK8ibD&c-WVW$CWTzg7ASrr)SF93TBKiDJ{>o1Nh>1H#-Vizvaor_&$H z;#lw8{KFwU5b-%Ygtt~ilp66>uepiSo!0fi6i3WpwGPI$@x^mLOa?e>2fDjncpmX@ z_2UHio*uh>xD?bXqnL3HQWUS^Vi54FJ`=WPq1(kP_CS<+afWBYd45if>?CHW=^-9< zCK7t?0yPLMyRice>^tZ>tfGL3X6?BLX7-`2wOM>|k^l&%Ir5v1_d_f%8?mhsYxe6W z2#S_v!qzC=*) zcW~okHbz>_>@?()bqaT7OR}r*pz7AY^UIwIr=hKO7PgARiWsD;1O^twc{$f>-z~M% z`ts3+h}XkFk4Ex_YD%~Mr3r;sn;xrg=9{vk{y^9_F=kOrD$30PI>&`{uSu^sLhO48 z2NTkAu7^}5o2W~(bVry=x0a*Lm~R&tYI!*k5VpIUk%>jg&`~WG+_iW+-7O-0H7E^I zGd!{Z_sECD11j!c2B;yfCN!Z|;dH8#k?lh6$kOTnqv8Ur6LL9q>gOh&kJE$}ah94o z-E>2#MaJGlM22kE-n)4wjCVcv^=2PVK$YzmQ@nXs?yjen`GqccD(msfbAIlmTz85S zMy=Up>-|_SaLG1wk`%M-$eQK8POFe6RZLC1J2*wB^;anVddUS&j*vtVv=4bG%RFm;3QY zQcgH^ly2Jv!&oT>Y=y1*uZzMT%x*$ghDimbDrYlGm)jyy4*k8`AD@Zqqc{?k)yP#z z*||l-3iEZu5d==9aBeN&;!m`76dk9(-+O9P7-M^Hs4%UIW}KjE`y!z?t_ULmI< zMi-vb4L?#oT1`3bzOT|k_0YqD^&i@Ze2NDl49HuvzPAP+HQXD_-*@o4s;zC{^w7Ml zk8(CO)?cU)h<6$kB0V{XQ{8a^|4TaXcev*-iC`cH%765@Rgp zh1UcK$(aJZygz#M)&^~kGLc{ICgOxrC2|>YeoCmNfn_nUURjL!7SsWc3he2ns@?|( zmUsvQ-pceXu!?h$^fHPhz($qi;j_g{s+ymlCYHJLy;l|&E2b>*47!7jMD-v}Kq7~} z1s;}a%_EV1Ou_K$C`P8u0|0XAo?w~kRbi1@jne=^8@q|Koh>@<)(AwvC4np44ijQ* zT-Z)7l@f=`Wg0^6NfMqva+kb|qYEl8=9C;kBPO9qtI$B#=2q^<0Rf7RFrQrK44>=- zVc8)~9a~}rP4v$?@p%uQkN+(+A5Djv`9-)}q{L#B0{!j6;+oRlor^R6(0b$_NzW$- z9uo+V8y8&&@>}ez=n1F3f$slD8!>dY6i`l);O!lQ$A9!>46b?qSkj>Zg9{u7#_^!X z?86Y9?RA?|mY__>RpSD;WgHhTDLy1j{e%MS76w6AR}7%Z%3M(Be4YG#C+?L=emXrv zWr7FfCWGytU6>BF$8iG)sYRHs7FCYSTzh_xUv2#KQF-yaid*g>3DICd9A%a^R5~99 z)h6s+81$Bz!?#Nur)54|!p=xLS8+6Kmb>+-pbgbheJR#JVEsn;b_naur+iM~pg_&| zv|7A)=N<3Rqtw?|*YFvi|2=(2Joe<`qtTDUvBfGFJAm!$$p{(AG$ccF@xvUbD>MrS zG?QrFc87FwRAvIzrjl^4Nl28PH|Ynbm`FFQid?_Xgs(`6GZRV5|A}2%YwZ#<9}g)%zZY3Sl>NUi*O+BDn^!jU|QmtFcVa>Yx5~6 z@o_w2dFC#In_1RQs`#eFWl0M-?XOAf@@TByxief#aNkO;IOkMAf&m%9VWp$}yQC}f zVIQu$G=8{ZrrGZaHDhZFCqI!pN9AT~Kw;mDLr!;?H%ko|U7aOJ8mx7U5PX~$auA3? z`t%(Y)B*t=aB{P{31F2 zC;Z{p1C7QxUPp_>O$=O6g64lZnSg;*ZFiV{JLyBRaY(iWjOq zPt&#Gdu7-paZCSLkZQ1vYx^?!ELP;rt8Vqpxvnd80^tMGkT(veh6fmr8|H!M(v(@A zKj{I=qJqzvE%7v7q7PD0v_}XGFFwUoz)&^bv`0|RC&~S3SS8x(X=bwCi`%TgLW_@# zQ_~(#*QvOtsjB;GB3yPwRT&c`D!c8^EokYq_L7%UQ47 z$^>r`cy(;bfT-G<$c+2#>eMoKbPWHtAw(QZW!$+eDfbLfh6Il5i%)Nmq#pv5a$8VM ziw$5*;kb`+0JLvjQ$gc01f0F|A|?4x(^U|)_rEFe>%8xA_j)#Pww#xJN0*TOvQ9H} zIJyspxA|+y^!ubI7JJ`3uw)A-<0`Vyv*OC5^8$|UoY}1R=2u1i^nhJ$u8>u`SbNOI z8;P9Tv6{-wd3g3i1`i@~e!%`0&H}M!=-DRh8He4CLN47OFw_=mJ%Z zlmV*1Tx9g9UK%>#?aP9?*^D+{#5J$`!qM0%PE?(iS8+Pe;B`P>q07en#0!9_$X4h; z=D}p#PLA$AbQ-R^Z@c0*PrD30RcSwMpYZX!aqCIQ8KdY+pI zceDeo+$hVN=j3<#_D%=I5}As5yM-9p9O5NouL2(^!~bL^vSr1EODVy7h9o`d;{y;W zI5A>A@FuN~9jHsQS2Ukh!lubFLdc`vm0)}Otpt4J-I#cCvRy#auBT@#*p@A*DGq%) z9)M=v=c5bFW|6|#u!NdLY#Qf7o$UbQDY+ZP>XTaSc!Zc$j#V8aU56tS_bg954o4@S z#qTPrdVZE_S6E8wnAELg{j$5D>g!or@O{jhL-PGBq&Ug>Ea}P@sXIN^czeWnU+pS$ z*}q-Lj&wQCjB)+V*66{acD+d7;`JSmy5|?S6-ijrX)``qI`yy;KwK~oK^; z?fv%QDssZzq;|1OuXeMD19qYDltuL}R^DqRvD)L>A#%*NtP9t&CrUMZg^-7UN1_B5 zrxAXI&W0 z8l><;(YWc(wn$N&>7`QQWDOpnSS>Bh2%1t@UbYm0HNSD2bDff-LmM_O`_@l1wG=D2 z>vrF9Np^-8Ws+pQQ`u?Yhk;%iBf1J_)LZc13-VeBCN{-+Bi>_h{UwhEwb`@T%RU zp;(lWo?W`(cAmD&$2cPkfub;CvBR4QG|pc8-Q`9{Gi1~*k6Xs2vuoDsYRstRaT?{R z^I1|Io9I#~7Hjv1llY&Tk`@7DuKJ-W9D%Z>)0R93jJCrRP= z*W%sY{{IZnen~N9O@s2G9*SY zq)XA>mLEMD5T4V}V)i!*{al zKrv5iX$JUrv~Hm;y?({c;l?1z?9}6Ir%2U&85zeGi~3s<_NE5rl5s&($oNZws>u3; zf{hHZZPMuV_)B6NQ}k#5^j6P#&t~w)8!Sg;E*QjPkScl}E62Ql!nIXwI3LH8XmJ07 zxxPG(G4B&$&Zg1MAv@|n9aBx$n(yhMEu`dKr24icEt%ul#~x#8`@HG<%BXy=vM76Y z-&W+dh!#($;LN!ur}_SZ%8|Tc6(DGMPCwnkX@p@X_i68U6CaBhmysu1=`3Lo)M*}m zyXW?-Ys*sd@XH6+8TpgdS7o{my*wMQV^(e*-Pc3bL2td*C*fjxyVEnH>*_M=Ku`U` zZR8wz^B#p|i2j(J$f?;`k20iDB0as3FX!plyoBJo{YTn)IQ`d!Z}S)}4qTpE*Hw=m zROcjjeBCNPZV9~p!R+~j`15<$|J{esNf}q8@1LAZ7mkl$D@QeOMqHacWL}f(ppn!v|U^x^YLg6RMutl;%gp{^ozDy1x9V-(p(00#b1jQ zZdew`#B_ zq{Haik|Hz48i?sD?z@dx=jg_?-}D?=q7WQnecC200dHY)*AFhD0(+0wN_*GQ{9U_t zR&4@ICUKWb;@l<-zfPJi!ruy=napd}N{NgaW7kXjy;+pF0GmVI(F2b(Ri*Az9vyY` zVP!)&PkD_A`z3O1nRTJ#$F?U&^OBZ;Xn2#R$wv7sn~|hs_>fUMK=SC)oA-3>CJ%kJ zW-ipwe4>E!h%OQz)>(D1Yy~$z?*q=tWXZc~{d7H#^&XXPc3g=v z*N4SQ#-*1oK`2R0^@#w85|K+lWE2A!ZDSLt5|k#t)t};B&}01q(MGl{n!v`c7gJ2jIz;@Hte{`fjCb*HmQwctZSN{DD&( z${#R`Ck9OcSD&BF!I|m8op{1b8dMlBE!cgx=5waV6}Yu3gX-~eq*thaT8c%}<8x2& zIIEv0n+rKi)E1@%Y%KZqdg$;yp$7{ogdJ%7Uxx5F%GF#)?W!sy4A+xXu_MhKKaod% zZ8$2Sq}E;OTQb~zYyNCcvrYXbcuFMvsQS}m#xJ*f-^`9qp6p1C9`vQ3#K-ef)i7UJ z1Ml~tHp=6pS*gOk^cKFtb5&g4(|C$$%`C_}>ye_X-(Qd1RmSc<9hvRDPCKrBXT);E zIFNuiG2?*;Rp9>Yrs(9p%Hh4s+hRtEO54G#>}crwTSP?vl12Oq0taND>Idte2;=<9 zFI*4`Bfd{4#?&*KCV+`ewJxibF)Ukg5(*6`UOusJp_O@5ZR9Uyk6*dRH($mev z`tYpbrTj9L(t@LLrNb}ZA#BFyXRjJ+cFT7o%!ui3#C^9L*qjIQt(lP` z_oO|7x0#SG>;70Y-`~7-a;dhfS*d)~Lz2GN(xkFy|8U%){y6qqr(?)e#h~65wp&$O zj#VP9hx=b>e;d5cf6Rzb1&N zqxGl9{cc3bkgZAd>!2^wMVFr{i6>>sJPf1sYa!5?v7p=MW|bGTxCpnE)Z`0sKo4w? zKbO3oJN(^C7NSQ?@ zV6~u+!x}6VTN~DbI3aX=!0Bz@22J{_os;90qsV7AGLFlc(reu*S5^ZO=Am}^*|9j@@p3ms5sfSP~jxzycZ;5H!I6NTuQ+&PdjQg zH=uI9!Ei-MD6BgLnbU*ZDO1!ngEX#j_Qz7yviz1f1nMt^nsz8vQ+;)BTQsaG(`}3G)v3!Ey8C#koM@gnI`-b48c*p-cb?3I2y?mEi6G-;I?AtF+1w(lL%CyhnjZ&&efZ4Hw753UnObAoOk-9X8j zWhW!hmva~V z+mI7UD5^?PjA<7>VHYsS4w@ntO`^@&0{<$uVf~IA+yVSf<(USjhxMnUmpj6vK!U-S zbXHW~m)n(Bk^r2;R{E*8#+-s_H%t0_=ckhcugOEhQt#zNup4k0t<-lH1bfRhbI8+^ zXdT82Bv2-E87_VO4Fzm_c{yR)t@&>;gZBBfz=VK96-#RD#?*m>* ztym(t856}M;AHt(5~y1~4p)d*H_0%@W8b3+q)3n1fVxSx^dQpFm4qW<&U&pcnX)fO z@2Ki;ofn^rGlcHQ`^Yb6Z(`TMvYgWIU#%y(n%}0_jp3C0yxS1#NKAiB9ALEZSo^Ex z(*D6CRd2`&sx$8+A7?Fk-=AxT3jfGf*5i(I$f80tO>224XAP5!@8Yd=kxv%S_CH!) z>TE|YLdKGov|lsV#xuFsCU|zlzV{<4c!+j*wTj^dYoN=&i_o<5pYYnBD}h;lmiBh_>(m44&+Hvq2#oa(MQPH1 zWU+uA;d0QFs?XxB4+4-eZ%5kgc$$GukWxYvM8D?|+xQ|#{)9(nx#P^wj6g()y7e)4 zD-qtxR@-p7bhc3UNMh7{%nt*;2s3X}n;HlaoRCaiAo}M0kyi9f6({@uJ&|z>xQ9uh zrvndeVs{&1aFo7h5Eqqtyy)CQblqHZxmb3~^f>Qz;pL~ySCk^df~t_&3SxIGlJ63a zRttSkkRz=h+o^6B=S-F)Rz6IgQE8IL2^%L4XrJEgG&y%QKHok0(#>RDY+0!#AH$V2U)FpftxVLb=H=fYm3BL*%+cHVz3}tlbJI zkldN)IGBR2L=VFoHxQ@o%#Z*lrQK`$g++4zgSlu-?&Rw;Y55qF1<0 zKL5qO&!8U9w7#mc&+`a=)&7z1>ti&d3#4&iaMy6p^_oGt1}&Q10uT zIdTF~FUyT)1W*U2=)wr?CK9YiXG2pMwN(8Y5SW|u@8}Ch^8QP`(Qhbqs<+}+f=m1> z0YSMN!E%2xe!X7d`P8@-z(Kl7?r>{u<(G9+RJ*<|sMMP=aL(z2Ko!&i*-Y%Dja`KDvJ(?9A+@IL3tKz>gJuB4aTPcvL8hr;Cz;7cRY&iNn zQK~(0Z{_j7<(RNw_)g;)DO6rGyMK7oII23bB-GCA<_+75*8}PX8ZiZygp@_bv=SA}GkCA}XLrNtZMzNEk?$bfa{O zl;k*=v^0n?DAFZ0bf|Yai4V}f;oBVc$sG7WWPoa;vKCRXm0;F2QnuA^txb9g@Uq9h zGYSR-QEGHA#s3&&F$W7RH{>Hb*=e3#^8}W|d`R*A+Iom@r?J$Tg1UTLWPS35LD_>` z0G2em>2-8LMNH#Gjz0lS8JkGT;cgr^IlJ*5kaKiX^M+^L9AuQcvUjcKN{YG9*(0LU zIqHA1yOaXucMLYIJ=o(&K1($sr1y>A(?83MMcP7iBJPEc3A;N7tb2GOayIDVvV%PSb>g8&G~fuu-kDz4u%z8Khr+rOPJNe(3>-?zz9Z*8=j^B9qO?Bkd zWk*ZwwBwCI;1LLRp;Z$6gG4YB562H9J+$pNYVU~l&hRU^T^SQaIJi}#35X{2sc!|Y zR74(HM1N^qM6IGXP92=FGUK}~SbpzKA9GL9n$G-!5W{P#bbM%`?S(g@vf=uVz3Fqv zs3H+Hd^>E&5}>}&8BdKjr+t^k4|v&3cK(upmbtV4IHbUs$`(@8uD5iRGZ$a@4z!7` z&BAHJK3p1vj<&2kL>MD|`g!*#g7- zkW3>V0UL6Clmm8)*_pR=SUwc8#9MHxVL~WIQ@9rA+svx5ny!PMkvYq?3>29k}D0)T8%4&E=t%!LpwK=RtsXSbllkVgWUrX zf;b+zpdr$_VAhPhhqcAA%OA!aw(0ZT?=C!)VGk2VX9rqm4g(#|pnLTCt*z~O7_1gK zupGO#!e-HDSD;$aW!O=no@7P0?KyOkYGNW(Xe`pO*oIZ`>hQUO4C^XGhk;nvsTAD^ z@AH2&>YW*?Ii$dv!*nAsNwCc%BcbdJ*hU1b?mDGU;!U+bTSUv%b~(Ti#@NsjN_1`7 zk8bVlZ}et&c@tYLP3wdZ;BI0mP6C`CPqY8^3K7lalKFO?-O{J`cun$7Q?n|AN8EX&?W^JP9zsE2dxIbW zvoEQRB6`gp9HO)Xh};iOy} zFVHN=)(U|JPCx2Tes|?6>lNVReFv zBf$ZN{C_f;E>x%%*!hEKgB1Qw$!0RKmm!( zEw*5F+K)nWrR3f(W|irzAB@X2+yoJ{e*-{z({0EBLn2iWbiV}T1_;d0y;oSV(H9AR z>_(pm1TZb?i}01(Q_F3Ep1i*Lb%fs~>HIzP92h6o`HG|FB|mpS#H}9kvHx~w(q~!h&OA0YqiF1XUCuULs>D{6 zr@znuGJ+3#Tkz6%q2Pw$+LPCVcwycBXyZRN)9`KB_>yE|EVELnej2K=JJqt+ko~GK%N+x0+@C`8?mr z|H!FDu&=krapOo~Z21k@5+6l<%I4%k(${>eD*RMPAmL~4oy`du7dZ+b%-YnlG)x1; zPnMnk@KqRzAx>{i6)&Q;-^I{R+i%p{&XG$m*MkK}9;5bd5O37QKHhrNr$JvcHCoWU zBZ%|><+ORWHZ|k%lvostm|v8(ahR%LeFcc_@z<)vKKVw_WS192r^8!g2Ye-U*SSi~ zt~vqA8wSykIVMZLIzKK0E>Cu16evaWnE?szO^>np=zDz&G&Pac8aZ8V8MPXwe(b)B z_OOix{oqt!7aW-7DA0>(Kq>KU)E8TSH{V*a+H18&J9CX(NRFDf==U{zB3$)~fX9k* z6B#3B_356DC)qdOVzl#Je9@oizD>)IiP5tA>FT$vA=(b8e7LWZMP{1okC2VxWv+{X zJpQnmq%B88l5sa$BkHxk*CEJd--!KOpprNVX=fSSH5`88UMAXxZgIdKA@hC(WQ_v} zLFEgpaVU69;%yDEK_;h9mQ+dH`T1;qza+I~Kb$X^rguCh#b$WH*QouI&?jU>Zujy; zlD%w<&cFxbU?XFC!!#TW0CMu^coDWhM?=o}O4+m36*tV?7Pr zYtj-pqq4nkM}{Joq;`Tr2j(5H+iRwFq*LyutFpZ}Hg9`!#trH_Hag$*pE~#Tw_=B; zj>=A#TU!x8{=}P^#r;yZ#scM+yLh|jz3u@17#%dD6Dm27D$zC!+Whsf+3c);nAD*p ztUmwXrCgh@n#d%SIb%Q1uU+R_`9{d`A-i~(4CVy#ep@u=B%fGA2Ke}&3k@|* z27gQh`sa|n<=b1!c79kZYaU|PZY|4*bG%P<4cYdUK$gqaH$bWL)tRVbrg51X|rocWUbcra{>o1dhAb-BuZpnR>~+y zmee_Eh7rX%*K>uSAcHyhU2j3>e3q<#4@Z5Fvl)kJ!MGA)y}B|gQL?q~u`hdY@p!jp zC{dr5?baXdKJlA^*OnVrmj#Lch14fDK>|$F60ksjkt;i_RAq&(PRUw?G0s_Bb$&%@ z%2}iOMLq$t6C79j%^Kf<;bs?T|Tl`0IN>mADr zQG%!p8(QD3s6;q$WXfH4sY0i_e1`6#*U8&+(v%hQD80l_<83rf;0_FqUlO^%&-ZG$ zo9?tQb{5!~9@`q#Uf=vDq~N|L7f;}HUig6+PgQ&xTRlDk<*#r8OjE?7~bxqbejnR!5K#np(tcWZcWx1=Z&7X&@-}~L~ z<6B=0oJJ;^NJgr`Yg-zjfKTbLHDyKY75{{bVZ++iO?yzF>Md7@-N`Tz*C~+d zFNS<)_n{aS;f7r}xoxRkL4SyK(P+4otmje)Vn)!`eW5eUGk-jrg{F{EfBCzYedWzw z2IP?w&)@-kM!N7?u+3frWQaMg;;?a zuSWTszhBODY1_uA(qGpUASQzR>ZYKZ)1zh5&`>`69~^UPJ2Su-+D8I zVmEJm8@}-w=xEkR&>@|l;}7kkgFj!_kL#KXqOXc%JX3hrlviy@#Xuu2Cz1?dAearLbydZ*PO#Of*dGVh6D~!W4kw9 z96*MnpkUi@aj)qQU>I%oCKXPb_t6Uww+=UV1YM)#LXR+t-trY9LI6#KkXXAnVtQ=@ zv@GpsbFNy1^rGslUU94H^0#!$oW2@6J>BJ9vJdB+%fy$rL06rY0Achmwz-$&6kj1j zqn&%s^J@0BS_!(T8oP_N-ByW(7uSGF7di`~AWiyT30pXQt*wCt-}DR^4fA0Ab=ky; zxiOz!%mJTr_$_o`&8T1}#@!^_6_vg$YYN4=jr}UT7hzm_EHy(_kp*O|Xvpu5`Bf_t zzCGt$5$)*sKzN7EhU`lde=l$C{c4SNGJ6t3xm{fqb}<;$2T}-5zmoG~_O+AZQkw(J z!7@Pg1E2I)uVFGQs%HkILihG%WzQS-Df_)RQ$nVF#gKAvquCklksAV%3nVlRZ$I{X z9P&L{#(qrSyaju1I`s%Qf;f%H)+&41d{%^<<5zii41P(uIaEA$E zF)ddP-^QA)<{Kr*MQh@UvZGDtB5N-^@xYJE1GteQ#dFL&8;vYCY(QoMf{A8*-tAE+ zFl%2Gwlx5=r|Wi>_)INXD;f6Mu#4f==ahoyiy_}FOf=6Qgy$-gaUIN7ZQ5HV+ueyZ zfoW&oll)4C{T&Dv3pKvSCt@lP+X013tu%@EELECrOw)6cz(0G4hO_tJ9}MxA!M2G% zp`X@Lu5$6fViN@tHmi?TBQ#*|EwVRY0o%ME8}A)5PpK0WTC}Cy?}%>S?eodhy8A@j z`NLy{e6cNVBe&BnQKqq)Zh`2{W|&AF(#QHDHD{#Q)8?yIO7<6zB;WzxjdTT!SeXjv zpFIT@&U_I>j`OLAK6&k-N2MQ5je@+UrK00O?CSER){lIKxt?eqN&MI{UEPRKBAssG zG(E@5g`iSAWWH`yc;U^*aY*zLK zU?GUOwMP$x3IpF!OP8M8>vLH>;nb06H`<*rMe z+NuYeJERg^{D1F(z#QkLj2HWdrAPs}-$%14>*e4Aw%b~mBDW1xA7gXjw!w~N(8}!gQBPBKv51s>T=ZcIyXk}uw8y%Vfmz>`oe(D%` z=S^20KVfGH15TYw8iV7*v&RtcFmY=I{|)nAntcF<-lI0hc0Ou+Be)MM`-_~OIoJGo z6Aq7h;zry(OB?H*SQ#1oxjLRODrx-K`u@zH7fA|%_akJ!cp}|B8TYDX%fUhD(eG9~WOMN5{aPjCM<77c-sy;HT0wE@8Q`=xcKSxZXargTIyr%Q9%BSZS<3}sbs=qVkDJg~;6|eH&yRcsHDL(^ zvKrK|o%c`dtYQ!5Ia;k)0zfuZ3uk7KO|g5}2F;L0t5x$VnQ`x%R$Z{lTLoF*^3a1< zs=z9X3&zK{yk8F8y4Ym{vQ#V!WK@%{qOq<<_3_I4};#HONzwf zr?m;t5I%u(@6r!M!|OtewChK(Iv85f4NzbHU^UADJS8F2fATp6n2v{e}ssr0z&4z51)-Peh|B;IPbsmkDIP6Q~=Xc0g@eAKS21q>hcfZRG1 zQe#n2;GG?~c~Dm^(}N%#3I&oXB0Ye&x}Fk5Y_vMd2J0tUQ>9oH_!3pA%?A}&y_$Cfp3D5v&&R2X9+8$qt?&|4)K=iokYO&8)iIUR*l(=>8FzvAoCOG(5%#Z1? zl!jmy+M&sJoPd)7F#AH6ad2>oXCZ#=MMLg$KrI^Ja4dNLga+?#hqDPVLI(FXgXP`z z##w=niACngb9^A*Y>h8DkmYYs?c)Ji64;HMMK8%d4j3#!3XavVK0r{N0uFXFpkQ?vjd%g7Z(=oO!WqtRc=VWB*D^$6+UIRq2>ti6;<2fpu0 zGeFe(DW~n3uI;_eNdlOuMDKcz(*aSyiwGxLuQnvW{dX4*pTeJLeeZU%;VQnYBE)yT zT;o5W`h!CUFUI)*N=+^74vjj1iyH*Fm>>#i>3w9929QGuq_asK5CbPA*h75r)h~K` zTT+5{X#Ns)27Upk-Ja&v94VB>(5r-Ti4Q0psb)C`uC9CkXf^824&nlMJ!dXXgng1`%`^5)8$&w%TKF~Z^2X3MmwfUEBp)#r2 zeLdI{mkw9q4x!@ZX|{KH^V2#?j)xrT2opGQfcT~r%a`8ACoyllrCHIec3dXP+k46D zV*iE~(!`tX@8$$fJM%l41%JBmqVx(6R@sHa0({D?;#?#NF9Q0lV} z)(4uEA_?3b(_-mud$64zo%+dIvxq%p{Gcu6E2!^pFVhiiyKNocp+kON4aT)^umrke+?~-^Q23 zzhT4c5+NoIVVQV+dgL*`tG^DgjLq%ttz$rW2ved7BFUYPD23p6F8fFBN+^jxXU5_3 zLM#j#JnT$n`Z0q`Q-i^Ah3;JVZwF^00fTG)7x3%!nJwLb`#=Zn6ROE|h59476xd6wk1^lp;=H1r4Tm&7>^8Qai{RB~8o8HnXI15A~ESGhTu>7xy z#K1%ZPF~lK;Bkc32cno-kqsJrU{da&^k9XSnx?R@ZA2I6@&&;0FEi&pK8F67d;$IC z%nq-+6Vt1d|#n+YKvRnrQ&HB)!`T)!S0)Zk4AZTOM#riu3eEVp~qi+Dt zFP(4l41Reap*ys};1X_i1(;j4Kf^q6@>`%JW=Td}4mo5ThYw`52_EPPWgfm%Rj(&H@ei+z*MfFXna_kruc(n0}8w;!GmqU>G znm8$!x^IoH&@SX>d9Z^GfyBKFA~a%gFL5>u3tx(>&>gergv&tA^ytPL9J7kU<>0#` zg=yB`(gsX0svpWRIlOZq3wg^R$&fb!pC~z0YzN#x{rmEPX8#v?RlWp?nsU!h|2jz2 zJpP#a@dkdy5|x5@QYUYjRQ}%VAYX$Y5)QDS)~KC!nB@SE{oWi`KXfm)Fn z!iAJ?tOw4Jzg7+>Ae_*TUO4x~z5Z?qP{>v{u{8{bd5uk0n^IWVB%=NU+C+X%fb4f#bZbym4@59-Td(bEZ#aVg6 z%+Em9}Pq?_CaI_KsPRazoV&WvFF!H)EEM>jD{`{^xgU=X_?O->?&Ps=UJwe_@xhr zn>l=_#D#YCPd~$dyDKssgJoz}!Qmh9+D2bS&;-W}n_KX9V;CnC(xz%`61whW=~cR>kf zCV4x*zP08V-*!_v;zyU(Xx>F50D& zky=^9LY~t!Nb+=_f8ce5c>(iX!y_`EagT;N+(s&G>y)~su-fs;!e1x_e-OX;@4~x(FcK9+2msV!JG?$AcBpGko(8+!b(y zHP=pg>%*y!9{hkP>M`@kh&iO%V;HY>A|SXj0=Py34f<7=14}aBApL?}~W==9g}kt6yIL5$*68po^iPf{PhYt?U8H3AWjJfbvHL zznKUF3I4`_9f~{EGbb69%oSViV0f{c6Xv&-QtfZyElKI2*wu}8$o4vRJSU5sBLj}~ zdX$e+>QzFzZiUsNrw5U110)U}7M5bCEZKR)CS(y}KWT1ybgCO3!zS&aU?!sop~AO*X{lX@fXI4F2cRf zK;3Pg%Q@pjZrft_5K*j3tlWdMt;WY+Azp0yeaeQ$?}oeL`yBi=o#KLMq`4Js3eVA* z^_-!j@XF6f@Hs{~CG!W$Xp}in`{V&IvEtN`wZv2P*3ud|;d{k-f!pSpxyuI=X?wOtQ z%F(X_eg2Y{t!7|NVn={H`Y$pl)FGy068jV$vh+eRT+<|K2ISveYsM$F1lEum4wQgR zGX8eUB_61km{5d_D(oB1#!D(GgW$>oujE_cKs5N)bU7L!0v{<(Q6qiLvajhjO2@@1 zIBsf5TF4$UjJO&csW%4x(batsLf6Zzh3RF>iY)Qk6q4n|4ZaCCh(E>=7O0do%@>D1pPZKtdUnBwBtz9 zh=FL`xvzq1iZRE)$4?P}2j32aKX9f2|9;bZI*tvBIog6yt=_PzJ5WvFiIujV%h7Dj zS7yiGZH$NJTiA!I1WE69N`gz_9C5m(*%#7$HkXj+aOzfrWu*2|SS*u+ujdTIUkGhM z_s#*oD_Jk~ARhCVEHbzTWKqpWD{@uRn+YBZb>MEp_qyPU<_9C-NaJkbGB=9oeC;JL zMWB&`d-fEg#AsHcn8#D~`;|F`Q$02cwJUh%- z{|amoB?keL(};IXImp>OJVvl{J4jHy$+1?^9AX9}7li)G2(&&k>(i)YvJ*J*7oP!s z5QA;@w{JM5DsqR#jSp{$Ks30L4(`3rm=Ztn7oLnjhqd)a?;vpS_nEaS12t8Fl8V^uTDQo85l}^%!Ob$|seVyP@;JEC zbWcD|wkeeAx#PA*Hm->?O!9+qOA;pp_lRkZ^qwBJLHru%0PIMLzSvLs(jI6G?&8d1 zBZ7!-uUd=$bGRJ7OOk@PmKvg}hoRb|qvDhXtTVnNe@+m8>!Zg|9RcG9&X2!2_+_4p zQQ!vL8jIXon`?5ssg!yzANM$@)Xx4z91|A;F1_V;1I>EI`F*N?;^NEZSAu3w2q-^q zV}7715u=iZ{vW_1sqE2~ytFrim@+se9*|{Go`HXe7;`aV0IB>mSi4mi#OW}Ivb2Q~sXchlMf$nd*E!o zyk1qNKRT|%HG;Tz1;4cJbY^j-LeJ@#El{!*yFy0R%P1Ci3I{ayciAafJFP0J$pZWD zapY>ssR)nM0~}G>JCpwvjyy30I0B`k2HewN14=!d4Jt+o!Om?rIUp=LJ^PO3wSBV} zd!s?w*ws2m+I>Oz|9}^#dr!yQULSh#;5R@TkWd49J1YP{#HJ$H!YZ_mTR@yv26;jT z96FD2-y5v^=fT3UcOHCZvnfXoTlfdS&>}I7GRK?;t}F0TP0tRuPm)Lm1l9+}DS_Qc z(;A5NI>3r#i_yo4y`Qs}dl7;swmA}tv{d&pBo)t{*iKUJrc`-!Fb9+fCy1MrK9_o2 zszxT@>0>Nr8-j#%wGy{pe`Ufuf#XQT8JE$lPcfRMeGL0%g84omuw;nCCY&QJ-e(T4 znc}c{CKeHr)?4I-w!U@rsVszY@LxwCH1u1F9j_SGxyWd9%Xl{GR zP*A_q(5*>*OJwQf!%~nHQE7$uuUXo%y2QqGxWal6E(3w=eowdOyXxWKC#7%i2_|4s zv(*WsyZl~E4sQj~m7bp@ct}dP{~5W1SuF%J9{_)8xc~ceO|;1K2l0E(hbK<>;D3+9sRBk1ya|Yy(f~F&?o2Vk`i~Rl8``|m8a#kW7?(X$y|GId zoHPK!e3r8*=MGWlKW9w@{%+ZtIJg!}{~2rIE1gr_lRuoK|NC>T)j5@=0YxlkaZcrR zZluL;IW`;v;ZfT*rbkVHa`N;!UHAM#_;l7UHat@JEO(Os+U+FC4}r}j?R&F_q3^$Pmut2+8T>2j&og?B96=wp5`R+n;XdleS{H(|zTp z_gEm`g;tmr28}puH-Il&1o5U(l2nBwMtI=DF;D~y@r6$m>^*Mqa6H4X8MwIvctrt2 zl+&jlO|v|PAu{O`KJd1<0oX8ZcglVsww?~K;js+S&cpaaB*M@r0UudsYBwM=21Zv8fUjJ4gcQmm`Z#{r<*5|gLpT9TLDPf0TZsJO9|0H6 z@W3eG9fC4Z2jWam2|JH-HYPvc8Rw*0JIDpdzf;{PDhG*yl?&`@lFutU&iqHaHnzwD zY52SFy96!3Wm;kNaBqov&;ne~9%;)*y!zBdAO#{LijrgiKlXW(@GJrh@&b}Qy7~;p zY1YSqS{ozoV!;uIHC||tmf3|QTBJsRZ1F)#*#H`?@PQK%iDhn_E zJ|BcsU91nu_YQQF6d=`d7h>wryq7J5kZSene$x9PIYSTs2OfvQ-ue*}Q!8GEIMj5* zXRG|CW9Y}&vVuur7H_3OW%RMyUdMsTNQf_%Zzp*j!ch4JFcRg9UQHd!-6QNGQvpa7 z_jnA!0Fa8T{U&KNjhMk1-2ZH+c->!9_ne@oAoBU&?et%6jp|ac)(LuuL3u=lW+0Cf zcUH5cqbX%T-06|N6WIf=GNi?zXGJd`dZQvimfpQ5_3SE$14=!j-O4ziI-R=AgXJXv z((Y0~k&-bE?gKh7DX&LZXjbONON6-sj?m_ddFk?bfnJC2Ry}eZ`j6uvmz=>DvR`wW z(e#7#SoA=F%3KNEpvXQ!zq@viw)o#%Eu4E7c1_r-X<$c+gsy54!0+H8Q6|xJB%+&b zf#-^S>YHHAx5nul^?(h|s(u=84)otLZ_Y(t$ES%A;bQf){&fySXGNij}Z z=ynLxBXc7>ki*_Y1+=7FTEq#VF_xl|2uGjj5s zLX*63HuYH?#fAD`g%REE$5hDXM-cV>pu>$|zWzp^WE)(F)W*zxh{f;|xWM8*5zfPU z_|;zz{;zlVloa{lP0}iH0M~Zjg->b^d#v?G#5nwvLNyD`e}GI&Z`-f`AjZZ)W0@!X zpjF}wC^u}h0S^2tZ95wXY*E&#Q||!vJhr!D8`S-mgJR1-cMNEns9Wo#ZQJOCftn~H z8@U^dK-)eiFM{T>X;}p(+<7wqlr9`_qRt^JZ|53_c~n zbgSAXsM);b{bE9WYt|Mfl($--<^UB~WY3`^-TJ5Xx;LM(1rmFKp27634241HVauIm zr2_x-zYrA8b%u_#)37g7?vPC!(I?2F+{qW5sdnxBtqXZ7vDkup1gT-ys4iZ^JoJ^5 zxV``?pkpIR{+*iK*dUf+3n~M>T|ig4Zy<*G^}C#;o_Ru84(PYc2Fe9?y8QbvxkOBF zw~0S2U3yf7ld$0#LiB;b5r9CLZo8>zxGfqMO0ki-o%8*?>pgVcS_SR!ErAxhjhL+z z+V>bXbZ< zCiXI=d+&1v^eRC(uCPC-==zdG8*uZJp%4@f`y$Y8?*ZPB$M*!6kwuGgUl|XEirR#Q zJv2lhXQ9eja0BO|kt}Awjk7^GT^IUI?NERn3KD!3$gRV-rX3@*{R@OZk~UrlGsKX6 zxJETfPOR)tEWR{HKCtk*id!_&G)SDJ4z%Mbnpq5lxg()gbA69!MX`i>3tlszgqZ~w z6gl<1917olO>PsZ3$7D>H8yZfCvLO{tuek_T)eFt$2(|C?A3l>fZ%J2gs8Xe*rbiq zYPG&*>zJl#Qzu=x8eO(SSeTl|7f?9&f@ikCXQqHV#+MG)a!yqxj(4^lIsIvDb!o(p2NIss zLP=1%&}oC7MZwnKCScpv&PJCVb6Na=ouRI5(m)UhS68T=Xt46AtrFo;m5Ixr@1bPv z8F^^6t55C$(+8JC=S!3A3Te}@@Lyja0@DXr2bW8pIp^Ta+mMf3;Bu|QV%>IdeL}BM zbzZ%p9Q(5zG@O;XW;h5gqyC11nk>$UVwXj80p%eL6$e1eu~u0T;km-$9QJ~~9K#Kb zTF?+wU84@v!hS~qCOOcp|8G}AwH6Yf=Ssen)iAg;XP)VMcf~-|yAmkdqO94o-tz~| z8waa`)dy|p@0%d~#=4~fYC(^Jq6^}G<_#&ABhN)V(X!6(gepDD^O*zfiGI}f<2Kv! z-?{>SxJTZ%=mB{fOMgjwtSP^>{)n*r9w=U+MP`=F_~BvL$`Rm`VMW;N7B$T??z61g z6h30iJxLqW@wap=H1im6K+ibc&21gfulqewck$JvSXT>TQM-T*i1PCU5um#X#kA<; z=aARP9Zz*$e}b>uJ$Yk7i&Ym%XIKfovWHFG9_u}Q&wNAUpf3X?loBpzJo(CBv8eyv zi}|>`=rd4tUZwo|Z`W&dE#}zB7P#iBhDO$tn-!y$LRUbyvMI?Mx*+2!7wQ&9k^Bzg z^2m;dGV~b3kFQAT%K;lWpBKB;2vzQeI6i3HMh4zV+*r-4xFP*x8`a|3CDI^?IB$r7 zy5>6p!ZU^Xu)k>mjWmLUHz(q0Grsetmkw?5ze?InNq@>*J_uN3oei;p6Su&jHcGzrju}bl!+4il~HeQ{JsfM<2 z4$np3$u)Z_4^V)6@5y{HChuPys0kqQr!*@)*Co+Pf%M604o|zBIjDmp2DH`?Oz&JP zqa^ssqYPEPYJSP0!)=*SMcxAb@nYWcj=xe4;T42zg$B`s>*L3`!k>#_f$-lf;2wX5 zckTw+LYq(bJcz-;$nM!`^;(LATZ_qFt`DK|yCPMVTlReh)DA_66F+g&*%}5tu0D{_ z;jWEgK=?Wos&toY{En^InXYi8uw=Ik|^7= z4kd{umy1y2`jB6K%iW;Rl4pFi*#wW+%Pp-RoTSvhAh~*0wMJoi_QfXO*N(S`s$r!A z;Rwf<|G}yZR3Cchb%$yr(!V>1taKaSC)_H{@5SSKy~IM=Cm502zh7P)QyBr>pRf0V z4q>~ZR%kY_JqPj=qwbv--UZBDpbga65It;2h4}@QUC!7(vcG&LkBW2|5jb?oB#fRU za$-%Jg4inyyK@D_7;uxbce1FZzDwUZ!zwC)DuNyP>k}%KH7n9uc-|Z(v<4G*>cqo_ zt%h)hE8q_-MMcv!h(8^Abh}2+Am{8IGRz>?P|f7lT(l$16l5Liwip z=8=!f2X%J*O?34Nzvt#A-L{LddNmr+M55~uWWr{(70PJhhHaNe)gc70W0qSu$jr*N z!+*o%h4`6aUpIs|wyd*yOH6N3mM@-0iR%l|xYd&D$68m+mReb6(2UhB5x+AvMyjE+s=3(RH7ky9am8dVdwDI>0 zV!js0+tiHNBVA391A>;I^met-#66>EGZn>yD87RpQ?K9^S{_j_TEn7qVy8VOUN?k1 zZOm(lMJ|T8WoDK6ZHojNVtJ_C)zLruoqk-G*RJ)fnp7_FUT@vs?J2i?r=w-}puU9%H#$oAtqZ(a%46aV6Ilfi&3h zoNf~t{DM}%2>Qm>?qIr@5zW^TbM9w28)6l}W~|Kyr&cngA{WR;K zIg9hdE>Oi=7SEO;5WAXgO1}(>j76e^6!3~YSY%ojHpxsxxur@iA zeHH9j!^Piz$vXvV%!_Oh!5BqbqAuVNGl+TQH0h&5NO z8;80a4~qm~3qzLFw5`L0e-kK}QIlclL%5GX@$V; zCb`0EeLTIOhZ<1j=YCyV4g3WI?W+(m9%z(Dj4$ZxIp1y^q07(QgWYPu(jf|3v{!C7 zldJ1Gs@8Jb%`};8f)*Ep*_q&;33vXq9NBP34RmiZ7u8=TUMCT7)1@g{Bph1gN0uxU z>98FAbzWMDjmSBrDA(+Ze8gJ0&q|NEg7@=`(LY?oOxnHJrA2I)>`g0d>4Xa%18nNY3lg?&t@2(&x@(kM zUFvJ9Ns@{?!>Z$a-P?l*h50X+3HtkyZ9ATHY!y!P{g{APl9a+rx)@_vjPa5a2HA@^ z&qK2wja{rW`Qy;GGlACAKu2>HHLbu7nDq|+eWeZG0pDd8I+lVg!^H8R^s?T77AZF0 zE{gf;MdxXS7TZiwPuY(iAPXpr*%@*8Ol2Nj~ z{WbyWs7Dyi;mYmva_E=*HPcz+$*>81mCPX~osO7l*1Ggj0?eWR%HR{wU>WLdhduDGX>l&lQWb1;+tm(@uVv3gnMidB`Es!; zS4e_;7d)`laY$}CVlPZDxoND6Ne-1EqNe}7TrTM@@gOGMN0v7UWM?q!hy|Viy7)&{ zv~y>!Im6g)db*aAI`?kv2voH4aj_zZwzf=d+deoCMwEXUcU>NR`?-v@SvX^-&x_E4q*8bu7$1Ps~WeFRs@DCP4Dyx~#w_nDmbR2#4`d*Ib#C*d{ z4plink2%7~YI?c}wp9KsvOP*k4yHiqhUbOFH21X*7f6hwrEA_cI%Raz@SI{?jzGoG zYouq9u4KQQqyJ^w9h4#V1y^p(DqCCHBS@sctf!Dp(soTMwqabSAc||T>lvAb$wZgF z0$Rf)@th#73j;Dxeb8vk3Kd(|Gq+mqhme>nAK*JzI<-;ZtnVY_7B;-rGuQOK%9L94 z+ot;k{2Qew3$9Npbp}?)wu0DowODFG z+hm|K;{0ZzO@Hwe5Os?zUC)}%$ubh+HdwWD(>`f+`qhwc-p=quV*}(Tc(=G)MFh(;^+iVG!&n@hRy7}C``_vB^DAsO z$neA8b=_EX=H5yCF+MSL5*^U8DLC5vd#cUNMo~cD-p-w02g9S5VPU*l_tRAPrT(MTdX}3HIcuXp%=?_N9ue40%uV+he z9(?wy$8s%^zMQ!Z(i+{MWBmee5GpQdfbY6q3x?1%S-eG7%~@CU z*X7_)K_j6$=>J8tunT6#EL6&Y^dRgnW!1Y?4u4P{o*nQy49N*N6A;nZ-e&4?}N z>z5|bDP}~_1dH1&Wwwv_n+#QIN(C8*Q|7!B~I3S29^J;g5>nH zSA?WBEwyYKU&Q2M1XWjOd)4dG5yfRQ95Gj{wpnsd2IZ8$Bz<#^B2~|QQG69hveeOr zh&0VylN8`uS5!?kqHL&Hs}tc#1xg)ObxEOFU}847mKX;>$&Em}rvTi$e05q1%VQT3 z^>7tU|6Zy?goEFHOtv##A~1NhH{X&JaYxN$B@E?c-1}A=T<<9pZZ~z6+eq@~oY7Ov zL|8+5p?t{)jL&7(8qSD@iwTFRZ zjR_ zQuqT}B3XIP!WO=sUThfw2KQ&94?j%5XNS5)sjh)`W=kyPBl%z8LtkH<|?MmRB{BuPoBI+wJLB@mmp9#M+mWXh4{P!1X4j;C))3B4k2xbW();Dn_u#b;+uj%RBHY{%WFr#9EBy5{ zHJkjvJfP?V+%JXW+weP_;&EiHxRcof=L<*7i^=N5u#Czh=db~qBUX3x^v>x-b5=r3 zC=L%bXW#Ij^KLT?uCW%JznFMNR$16GLzm9l^>*TQF`)iGTe+Ult$F0V{S zy?!OzL?y$v))#9`?}!9~8x~YmbXk75-bR~W`Q`Y~h!WpubY5HJlox$oBFrXLJ&pK$ zE9%jW@giJjdc~A1+OI<69@_)waAkfJenUEPR4m92MsdT|pM3mz@{znQF+)c~H#C%MH~qVN zyzD+5A~HQ)Z%FWc()uS=mdEfFdKx(oil`HsdfgHBlnpcK>SiY%6O2zyOPjU*e{_9$ zJk;&?el$V}sq9-DiU^UNHi}aAean`;?AwqfDr?!2HL@>*$!;vkIx@*_FtRhoZY*Q? z-BX{%^Lu?i|JC$7#`}Js`<&}s=Q`);4b&&B;>LZ-Z^S1YD}Y$xEVt&)IwD%nd$S9F zG5O}UxfLXr>W6u(h`t=2Xg`LLH_~Sqab^D`Zj)}ovv3cqd}By&yqe3WIXW2oU}#KF zd-+PqyiCHeT;m*F74)X~g9l^a-xEX-ce=|`AvP&`Z!J$aP-jbHJD?ej(@HRT4!Srj zQsv{Qli@??dZNU3U#cQU*#ZAy9cDgsoR@lk(XHKl?6yh8%_z%;^ubH;5en+uPCAaE zG@*tyL4qKHmX}6=Y(>XfcEXO^A?8IGgvB{#nsW(Q#86#EnZ))vuZ6#}T!qT(+2c#NGj6X`q z3xlCx&7*cXSV@hVnQ3VWV`^*O@|K?2NSxod`KVB`&-{u*DxUZqY{Fhf^CX&ieSdRC z(c}vhY-W7BBDLNMvfU|trHYi;Ik%V>UxQz7)ejcx^}2Ay3(yxPIQjEfjPlfME%dfM z59*rcn04>D&%}a7`Xw4HKsJR-aWAbR{rJuw#TjK6O?}^XDxbzITr;UpRznpH(ykhzXmcOFLJ9U_ zt2uaL#SgG+wa~%1VUZNS`E7>ouXj`3p$tQDEW%q`7FHTQl5@L_8>(XQaT9a-gI0Tj zD}}sdnh4stml+BrU5<+ayxR==v5BuzM9z*O1q%0S7|LRAJkN0ZR&Pzo6a)#JlM(NJ zp78bM_@>YC@&dw{!y5y#&l?7)2c-{kBU{&NolboUdmLTg`Dmc#bK#*&V9A%*s~3!5 zED>4B_W~YD*9pK6c}}`4;wlFn;MOjfgZt;H;#p$dq^Z9yI;d_Aac)Dsxu&X%yQ%;V zkGhh}FfDp9z|3b%#n(zFzG9>`aYRl8Th5^!KipX9SKrmE;IZ%5AGovB@7-`Bxfkt$ zIF27i-WbZ)KFi5@XmcuoqW86T`5Kuj!x}#=F<<&L$xk z-4J+?3)fg7p^JGrhDb@FU}{LE1A5@OP8j3$K5*?P&c&_Pn>6^f)~w5R2|W-Xobw66 znl*=95il7yEVqrjW-`971_Pt^JIalDjyExMR#c{RePW;HF`M(=S_F5(%i1yPY)Pe3 z)m_$j#UrRYz>w)i{k<7)a~rOIWAy(9F7PKwp2ppBb~N|RHk}FYs8b3{YiyfdKTS*2 zj28q=u8x<3ss48TbzUybzsBR8&E~t zAa4>mg-c@_cfDSaup$#*QfS2u10j7y&nmSI<9Vl+4c|~~@W6x8`ZG2fy zMS43}`EzW4cI%sGQEwa$ts4kb8I(yc#%TjApMe6Lv8Z=39WiMr(_1M-{VnWe4i zYG$0>4_84fA;JkJ;yfcp*hy!m{WhNoQzP=~P2A-sgiyo2$O|zL6GR6RhUKq(Uv%T&1kU6l>okwtd4BDi zqstA4ekiTXQ8^L#8dzVFeOZ$qE{p7Hxs95V1+1l_|706X{%~oS*QGcakCAX*r zuv0pmDm$X{I9w&hy+|HxVMq0&BBv*3%c`SG#C2JfAGZpL6TpDRMt-4%V6( zEtX|Oe5?5tO38V{|GA>ygNZo^dT60?lvKf0lqT)KA>wwX9-RoxB4-(_(fWzPf-#vE zg*pY=MZu!pwNkC8Qpxu!hVVn%6R&Um+wYTN0rw#!Tu6O)&{seFKiTS$o1magA<+=8 z<#&zl!qZES;Sj93pPB%pU0V9-y|PrMtkq{X0#@n?s>ARuZ^NG&lh>IZbAVZdwwv=k zwlke^P1hcp<>it$z1?HQBNlpdc$XG>pU4|c&c_k~s^>9mTX~$=q9kbO+WB%hK|pV^ z@+6G%+zWwn0;Klh__Y@S?T4h`VMu+^t9&XUimBFWBJO9_V3{%O;rw#6J0aJ+hCTms zuJ?9?PSwEHNeFW3oAHbn!oB6bH4C95@=$_%wZ_;?8YVSet`UW`?Q_wFan^5n0_P_G zn-4RC1NHBD)l5NZYwz;@g4A?4S~5h=oz{0BOF~gB$Mks&ZUse% zF#KS*OM-Z%DsvAB4kCw*TfOSNdo&dNzpun(q4qw3pB!|;0f&0q1wkxi4*Fu9N9IRW zqD=@%O#VwuAM1XL`2CnJ&%I;B1Vip4c3u2 zImz6*@Q6)8gz zmV=x8FkQcMt zd=a|0NnNJjA>zNkrX(Yg?_}4I_yn;B2gJySvVBe(c8Q-uX(~^}&Q^j&%bmG7)~M9_ zeoqR0fJdfk>xdz;{J8e_mvHwdQQ#K19}f%(utfA1=&-qqaLVmYpRH~GFlX!sxB79- zOMd>iO(xO&wOMOP@SUwv^p}TcQPD7+HwISTv@Y=GHil0J4Tl7I)WyIPft06NExwv` z*LH?im^q4cyB%jqGOh#(QlDQ z1XKZ`JqP#XjngZ!V1%;hKrN`7Y*uwY@E=E;%3_NKnW4t2~l88(JF`8w72a1E;> zp;l3GTR7nNDr&rN843r!#m9A zDQbc!5}}Vt(8|}njUY}=r8=yOKEl^pfdZuQecq#uBcTPl@Y#!H>nLS!e2UA z6b;aV@@W@rPiAPT5hWexlD_OBZpv2S4U@Rz=<`h_IRY|4X#08-Ed<%sN6OfZ7nTC=3hE875#HT9-Qmiu`)$w?885cS z4S&X4Lj)O+@|^+ihO-gadzNddSJRUmeb^UGLtY=r!WFnHDS!*F9@Eqh{XboJH}wm@ z>vQ7Nr6zOzRyk-;gp#*&KDQF6ifjJm#0f#Q>JDPB(QMiBk?9!fR z0TtvTkzhsXSH_{Btl7{tUjS9r{K49P=k-^HI9#1IWuQl1gGR1YE5^Q?ejwix{uC>X zd*Cj=TBmV3j57sI7??Uw<>&vK1~}*%OT9585G?zQmuqg%3OuM4bDYp`HE#18ueuG* z6l_pfT~l(q8GlN2s#GJVtKQ&qpx0>WPGZMr^ir%fMu~&!z^|XY`Cdg#a5c_d5`|NE zfgZRHO>i4{xh&1zH;}7hHR?Wo%K32ZgLU{;R*_%8L+Y}{sVCpQ-(LKgQ0o6kp`x~n zu|VijROU&D)6VuOW%3R0hRaJ*&JX0bX3#E1xH2@$bTtQ+Tt;)i=gv4(Xz=$f@lN|j z_c1kxG{6M1IlOo8h@u+8J;d+N+6jtxE-d|a9%>@6A=|C5=vD6#7>osVx@jVJBAlQI zLmzwKt((@Ej2;QlFRbO&ue=A|`c%6>az$n^1xe-bQ#4?t9Hv|PO$!eevs(zoZ|?rM zg|UzAt#+|Sxt)}xA1%-k0;O049}K+@a%&m+v^8Yx8@jpcLa4n$0YTOxvU=FJI z4fVY7%i;EEL3JQ{e_-4OVq7+d_>y_B%W|fAyz1ptxFy@o=M&Y2WlS?|=eBTuU=D|O zF~ep0rSrcKK;R^URN0&as;g&TACB)E|(NJ z!NeU#E*qxa3OY4kjOOH(^ZspglmTxCq$yI^6lWAP%(ZYoow)nO9XAqE+xA*s+3NGh8)kPt+R7wET%#X_TR(9F zJF9YL(z?Vy%;PtEmxmb8F{$3ctyc}w?e zm)mK35aB_EX2+XMias()OjLB5SE#@gRwZ-T?KTk_1or^!i;A}#n_H(KE9jamH656_ z6p1YkIT(DwtDKng} z5+$n9#th6Du{vM%)BHBR)H{uJ$#8H!rs^iT{Bvp7#6eDN{KHvmv{%H6g{1`nO4w2G zm=bQwU|~O=?EkPgVTwf3h}l{!x252C=JZshaW}=>7B$QLh zrMXs)YRZnJ9E*Rqybq%mOQsolliBfpcY`PLMAv4~2aQ#CLup&3M0(3HxH6=mXuLyD z#{FE>n~g*%pcIU7{xW7<$sJ%yEhJ4KpEK?b4M9MG9=+H()&IaN^COs>K2Y8jC4cZ- zKx2eg4HAfxnx?#V%YJAAy$QyvAm_J1?P#G^z$y6bi`GK-G~%IJ7R5iXg*eH$N0hU; zkDB~{7}R%n8|4~WUA~oslcfpMFFT))SJj$;H5{mO`K|_dgGoY@q9U3FRv}7XPrd4! z?ugMS;;A>*4442#+)7Ox4cxircoRruG|k&0wG1j9PxsQqKfahAWzKoFZ7| zg498tWc`b14RX0Shz0<$MHTkLlNuxV1TLV*`C^$}_Jd!ixDLU9Q@cPJ7)ryEv2}B| znLA(tc+g(kM2-q@#98uwr-kp9bOjrILQl4Y8JTOLGn%amxjz8Wit{+1O%#0h`0mv`1-j zV?&&eKi%xX;GqHz@lR{(Ii^De5Tqd)Ngu=|knvYFLbx65{{VJ zxwi@(33(2b#QVP-YTo{z7(gGgv|%T+O&w&*#9^xWMe(X}7H2 za455ucjx;7Bbn-a8WQ;9R6oB~{uhgoRN!0lKr*TMuxba~ga^Y3=ZO?crClyA0+a9c z=%iO;aL3d$_MXg-cMNTNU_BqqM{8%S&mj1YH(}}zoqc>*KE4sURNmlU%KMN!*U( z=Soz6!bheb1d2f1uw}0qpXC>ZPn&ESc_#w7s)+hp*odqi|o_W5&c*a)G#$AQPPW*a8sfxD%|I3DO?ZHvR@%S3!|W=}t1s9^(-d^# z^hjjPWTv=7m-(-IaB-8DE$0=vw!sFu;Brp?x?OXnw|gA3vWZzkBs;3J9~Q}^Q(yUT zMWybY%Ff72!{PF^Ij|E$bf6kYJt8cxY37>NrA3l_R94C*#qb+@7vZu#V@oVGKKP}D za%NZ--^7~aL!|#Zb*iI;*L29MwHE$cpYHJ=B?bPI2eq^PiN0Ysmlj{Xye}N}dbm`# zFva1+q#J)>JWl|LP%Jj8t!V`_D2x-GPq%4!5hJD6M2 zt7k2T`0S0`xpzS6_9VwIWo>KV$coa0G(x|k+qOIk6}R%0@01G33LAGUCCU5O>2{R4 z*HWf>5x$NWHQ zzVlkC&8wRkod=Z`Bh|c960-9^?G$EVWm8+fqI3O4B48QmswZf465TnvH`Zs6EN+iE zU5qB&Qbd+Y@^nnsiLXV&y_Mk(IJdMEsn-5kdq^NhlvtQ`i}fjaP~bobn^qnI+Kz8{ zwtEkcz)4HJep-NtS{#FishPy0t@nTESlSEhS9yQ#5lW2H+s3mdRa6oUE6i<>CCKo- zYN&7ec4!-mq@ZZ)qcdzS2UqT5URw@ylIoizcBDT~gLlC*hD9*Vd+{o2Ae>8HZecGk z@;C4vJzBg06S&K_$(z)i(wK}rn>L2BG;&mJJ7cesR19ihC}zamQm-+*D})*nnquZv zJB?SW&?&d=kKJef42?NvkMQ0KFO_#+()AIZ@`4#7!e=yyhC|qLK)U9(c>#bYQ19+V zD%on>oA60|JSsQ`Qjl8%mB*V%S;_d5wirNG02xM}U9yn=*Y^I`8mf{lFW$epQMpMy zWG?7*Fc=qd6vruWlTDq{N*B|m`cFdrALIHP2D!N?Y`;G%eay)eI5hWG1A1^rfKgf@ zNVxMMCQBeTHvg4jx=w>1)V%hqOYcoC3S zKHftC6KC%3c?sqW+Q~Zt`1jj?+@_7?Pf)A%i0z4QAmW@BVM5~~Bj%Oz{d46-YqGwp zyPvT({bh+g#;~;%TSA6DN=}aN+mvvP{mFaYzWFQIY2nJvlO%e<76c;_@0Jg;(EMjD z?^@-MYZ$;u_Jy;E8pg@vhs;~o*P!br{?+j+gQp;Yl`1EwAxhQIgPkcl5|eE%6DwpQ z$0>&yw>?yJJ?9hO zBb;YCuRzCba#CU;9o1P+8g~g_#*&oyW$qp^kbpWyzTG?JxO91#^xdhWN$-*Whz#OO zQ9LMkP=Y$0FuTjnPqlQjkxvwwQ1(>a24bOT3T2PAs-Pxs${J=UG+-rz(rg?WbPHDI zu3Y+)r)HdF%~D5M&ZSu`Z5W8#F-U!hD;x(_j-wkLoL7MxvF)88)Q#9vTDzEqOo%>N zblmI^>caMO&6R`7C#_}(UAa{0s^;E$~ zz=Wn%L&fpMGP(gY;|xBL*siOC0j;X}J)8)KEU(cozq=KU@`n10G?0AFcD@PO5o(2Y zAcfp|&yvCv@F42RR>Ru*M*}MgKjN0o7U)na0G(^!hCJRvBUr^^A%~mjrD3=c@?oxs z#x3$Dv?VBl0S<3t4&@Q?8fXU`onCxU0+shTJ7TUiRXmS!i3Vnc-MRfjal8k1;D>Iu z6Q;h{a*0W>Vc*$21?ZAd#+Qpw;D?ZEBbkqXt?;J#invOXSU?>~m)S1i&iBJF-E_PJ z(&m6Q&_K|05q5*c4iLW?%5$3sw5&JzQjD?$vS=_41MFEx1qBLZ)I*d+iaxQL!2b)| zkUlGU%zYN#yN~3hT1sb|ORGM~>lOeaa&~=LdA8y6Tod~%QI@k4nvVF_M(P7KZdmoJ z`4$}2xdVO&{W>B$Y>9%~JFO2dL)n z=qXwhP{IeQGnsQh@B4foTIDjG{**XButslA1TaVCxhf_NSMJmM6#C(1sSlh-k;U)x zB#C|&;Dw*fkt!A`HwL&{?D!rl^h4tkz~AKCb_+|P;aipl7T4(QQS3fyX~qHQtK%m1 zvV;BF4UN;?TZ_!d@sw}&-)~pGEItvKg7-(P-|u(CXoo1J=!^9Ypc1P00k;8?(dzh@ zom({t!yc9)wnR}`t6(4b^Zj@|#QfFF>%WTQgyhfUKQSh5dIKMr{c?ziq~j8FE$?^o z_32OJhYhz;-uKc}%;5-V2et!^l9^>pX#`nET-Q#4QxG^P^z%l5SR=Nl2-9)=5thGp zgB4cYe*lmS(nQd^VjfPBc*YF~OVDh|(>=ekR3f%41uQSo?}O#pwIdfIyKz8%?Fto) zziu#Fhx2htgU24T;c)`dOysU-x$SIJS2(NKHCOoT50^vc9!f4>(^&YkmXitC0$9E6 zp9Jhgpk;*#%hcY18r|(Qu$#Bl=a;|Z!ug-LN?G?vttzD>P9cDt{zkp#c?JJ@@}qd? zuN?2yu?)uJ{QuShkpBIZfoX6X1vh^8cRFgW^;u~{ZNUq~v)F`jq~6Keo7E+b^FKf5 z19Qz+O_9n6p34?&ceh#C{3vW5j#Dpv))I@nLZ2+c!5^>QXzo8dLbi6Nhw9$JA4*r5 zzN3HxCQnE&MJ1rRrG*}!Vy7ZFjIk+`gPb){t-qM}ox*CH%BbiS1b*|fj=@reByCPge+xwTKA$b3=;1=Tx-^nvXZk<1(;oi|iKBfk7 zPedv}AAD*04`L4qApU5E6jI@01n_Dayl)1vP22k@H(+__f~DM2g#MTlDjk?pQ6pHh zXS39%Dz|HqNyfkzn;5i(y9w9;^F&v<3-onHq7S$wI&tPvap0I8oa|pIG2H8KdoRsRi=MaFKlNqWlWSF2y3a|t~&NzPCj{Qx9-(#(;P8HuNK$R$2NpLuxgggy$rX+Vx?Zx zoC@aEA>;EHv#20BkJ{d4om(ABlO%8~hpBM$`(u_GpY#P}-q?CbKag6wo?RexlD)5H zCB7h{LFxJ@arYv&`=EB%g`e~LF{xKvu`@g>KSDFEtOvrn@eP-Z0+Yj30*Fiz4ZGI{ z_xx^az=mHWpnL>g82ME!_{swGQ{_1OdN+pybNz+C-=S-s?Pz*EQb^+ueqnLbf@xpr zvmZl5F4z|enGXrk`(n$Fhg;eW7INCoPTxS^TvS+vrPXm>yScJyS=oA;<}8fsT*>jK zX9Dty6S41?#`(Vzch@D0w?MSPcg?rCO7``qS`bgJA2>7%iuqo7Mf~BjaePp$>TscT z?`^9`G~U9F1ypgXXglVMct{F|-O>3&a>q-HFT2>$=&~hQS0&FPfunrFb%TyhF%wuFem|9P@Mnr7QxTFF3bMVL(Q58E- zq~dK#>A?H=ljgc{1|_J6g?>mcG%nsRG0S#zmj-)`-BI~Vi7A$?rqa)`)fxDVC8kY3 zj+fuhjMSpJ+~t-@X}(=ajbLO&aT6EnK7uK+mTv~FmI zzN7{cIslwIv{(6_BXV>_V>-J^3=_g-kl(7+NEGpQgjpAE@OjxsvWjn|>% zTfgCzR{YfWMhFp?=w#bHh#n?h-^%y1ql`C<#>W{8jFT4h{WFy$mgl0F3QnG{K)t){ zQ0Ms5D`4^ca8i=E@ZHF=dJ}Hlkt(GPqX_qum(R8p+$4zvJTXBlNj9nARJWAc5ARj? zt>(~EcZ*hHr#ze}1KDuuLT0=8!Y?Am#LfznhRF;#%_(c&_QDZ-S@*_SpN~vyq-+jj znc|l017mqQBQ{68w=I$i`kRz=d`N!sPI*F_%xn$#D%{6gMC00NeV1Qb_Ir#Y&D0m_TYRif&m*TF%Gd}^qg{s&o5`wK5!Xkh3roHs>0%Y!L(_C#l ze9$E|?dKRfm(NQ7HriM^Td|?7ztVzcDR9OBP8_q|qHZF-Bw3ga_^k>Q5U)6F&gEuCuH$Nnt)Oq$tPopO zcd&=WXIw$4V0F}^+k!}xM?a9DJ?{llBAB@SQ2KP+?PRU z9NSZ<2lsr{=VP;?i*H_`JT)Ox1^gkllnzB111zBSgSivt$(`^`f=`js@E(_ z7UdUY9Dhzdz@6OpOCLQTgLXOi6mpcU(jQGU*TM2XhL0;LpNU84vVUWMzqlYo!Nw}b z>uL*kN$;_#eV2Bu);qs7(5#1CjR|wN;E4uaILqRanQ8S4l?M6;-!1~#uCek=hcYBk zBip=1{p9@A$5SK8MvgsW*0}%PC*#}Sxj$=AlPxkiBdve%H!|PCo-I{Yg!uLM=mK zwMs34?L^tW3*A`aSHV0N>>RT1p%Rx_p%9r~j_g8Jnq)`aD+Ca2lhVlbqPyfl=z|mA zSAevLT94Nb8MBRH;6jV#>$p*rk(dn+;xFJGX$A|`emr-Yqow3oO542qjnK_JK)4ol zmVzfrK0i|}A$SrLBgQM8Y7!w0mf|lEa=Xb`q(qb@qb^j^O8~AWy^=F^@cZQ;o7)md zYCj|f2E`-nBPH!JgI90CjHdN5{PY0K%qTcA#Kx6`IKCv#5RKd<93pKA?K^puG1V(E zew}nDB^(~Q3W-{w;axD_VUFy0ktMy4Gu6S+vvEQzMx)yn%|C=6-K>v^ODx*PO$B90 zi)1!mj4uBxc1u{tYWEb?gLX_7LI#NW7h`XO!a>AVC>__bzCQq@`9S{M>dc@R%N2ae zIY!SEnQ+VhffW#_q!##rE$E7}B7&sGit56HXTp?$nIm$Qqt0Qa4wnVkEVLIv8nf=- z1{1T*J$e2bv!x7S3BG4_lhay+Uf}$nnY0Fq;mn`Gwr16-axjQKS53XzmLGAW!1w^!C7`oQ34~_yTNUXmD+Fujv%q zZ{Gd}7x8h1jM_hzR?ltN{GIGBz?~bnat5w zgLx%G;sKy|XvE>W+7$BHUL{fOj@3CYPz>w?TJ5vm9ryJ?m0U-pHl(YpGie|y$NI-} z+-xzb&<5K8Ym7ybk@RZv2e-?|3Snt{^a8&dq53#S0ioaRZOa@pdI_Sfmp5%f%`CIk z63_SP@o;Rz_Is00tL$w}o}GeXqf0WzJ-lRcF*fx`q(J3eA=#YE^KxqypNsWkEN4v{ z>W5C4Sy9D{WI4F|WXUz4K8KT8$2(HLLxv;v_TG}m*kL>swek!*bo~YuYx#sXuxWLI z<_%k%KfTU*mEtfxiVSZ6 zfxz<42;eHKt)4wTmmV{bj$PUK`I#CUeJf0oUVs?&jPRfYJ&f-rrr!?ot&B)!W0!KB z$4?EuJ=@Revt$-~L6nj(CIU+H09Z#w~$0BY=N05 zd&NB3nTiqDN}YX4ZWrVB4X6?J^JS5+E?+_mlgUoJklD%xN*>eCl&B@sE%er1MBEDAI!~;@~JbaKC*vNTqFkxkubPfT|YmJlD%);@hKTRmNlyGH=`8#iit2 z5jBcRm6g^zQ%t--W0yzL)c#L-XsQgjVaBs@YF=eW1OgAIy5lvA|RLSW!X8 z00%6)u*A@@3PcAgCf@j^!~y?XU@Sj*TvX_~TF?gVC3D=d_*x=H07z#jRY0 z+~-fl&74GK=58~}Wck|ZLGslFeS&&Pg?HEz-U@MzKoeCv= z!v~E}BPcrSK-G3^Y+$aU2mj@h)O;H%(NnR;ZrP|#(_cj!afnvufZo) zxS$a=K$^OSpP%vik&1?6&DQ+d!>h34zN!c*ESX#Lc_u#U?^49*=(;XB`%qtgZ9W*N z5vo5lbpid8;lfTrY~sKyWAwsP#3i;x49a~Yjs5Yrw?LK~js{2#^>JA14qC}o;-~H{ zJ=0&bO)5~4vk5zoKtaIQzM~>u*d23ShhMnIdhx@|6^RDZ*?Y~mw-ee(uikLHPJ`5&ifB|0&e?31AD6-YB+T{aJhJD? zgFjg@r=eVk`D!4CVPK9&)h?X^nswDNZ``Y$0|k$mHqbg&P;b1O;nZ;X#mYWa5a`ty z7FzIe-ggS`dLT&T^c>I2|1F5N?vNn{XHJ?cnh2dGFptTfjUok9DUnS0#pwQjw_%)( zj{eM1cCKyqM^YQARA%$%UEA?Guf={HlL(Cbdi$j{7L_D%hsBWwW6$5OsrgrWbE520 zu4(0eM@>E8b^|qb+u<@x+wNpZ<-ktdNV&^(O#1EPTY#qKEwlz#S$rVu5GprCbLDqC zsXK}6_z4n{Ww8Xb!>(ENuhg)$ljg>5{aT9XFSHE?Hphz)KHK7pH9M1G#Qb*+oGtjZ zy)}8^kJ28+`VD>v{Ypn8-@>sM&8Ka_yrb(jhox7H`1{h@9B) ztBIw9#SMT~rw$^52>gqVnjP)dUahyg)Nbt#YNpCo67ddK=bp2P*-q;pR82*yC|{I6 z<~3v%T0Ia~(=EGg=!TNr&IOX4n{sR$VC*)mGyXbO-+kn(P3jh?MIpUx2DjmzaZ`i_ z0Ip5Iyex+`XoB_qfiU9UmP@&sfaMA6-Io-OiDydM_(ScF`ktq{ps%#(+ad?z_7U#u zsLy(*W18D`p9?Q(=5?U_DX1~BN=?T~(C+HK`Ynf%FWpjDfo72j_bo#u!E>=U?8_1z z1KUB}MDVdcaR3Ljan?-K5TCN?(J)SQ|M1ES6LxaFKcurd+nN5;wWE4>~4ebtSD9YCNpIZ{_P4$D~&pCj@6*nO>-@8^m(Z z+7|ffZ`jtc!=7ftBV!8&wMG<5Vy`s0Q|C#$L8`gjhpX4zgHJGECvKL(+V8u#i6iR~a0qvikT=^V`mc zo2g%4ZY}ncVyIFSXUbPvYA)<8Y5L?`j@y`+)eIPsU4&(K>r`NO7$tb6UDjJ8-uh)o^OuwT)Tp%{ym-B2S5FeM9hB_l>-icsBT06 zW89Pcy$kBdcTbdV){q-#e|zRfF0%2u>*8-Q?A;GIb_^{jSgI2V+d6FG_NxUKH?few zyD_DAK0#z!eNT8;o=Y(&7a{0t{}qRyx_reJrNcj)=kf%{LZ{{J8yVh!UiYhv4CSLP z;JGFW!c~{T@JjeuL)_+KSeIt?(8&v`4J$ktH#iFwqe)`<=IUMiwnJL4QsSDXmD_lk z-$UQp_QLLNALlgt5L0V|&cdE&HmLOc1WWn&;kSodJ7d&sK^lJfAegvhD0~KLI&X^; z&lA;#9brVnJ@19;oLmz*W5ZvRFTYw>xeXxi0n9Ib*g=Tx>c;g=c?iLKJMCK{EkT!s zo{m*Q{IO~iS!0;W4WF%y9OXs#kqNg$bj_{400)CB0`eRIrg;Wd;)qZH~JZQl0eCNG>^PhPHHULKT_Y{@~pn~`q?vSiK(R0DE&RFiWpv{C7|r~%hB z{A*}?7_H`S{P_;W6*wBy7NY|4qfOTXD0vPDPq>HDM0(LmRuyAlR?7#+LlS{OQkD?c zkwRA@;uP{^kAD@_E;~bY08CvAI6oukFsKibhnlEJS<6Nb*E&_tFp~5ZI=iZAI0C5S z8ICNWV;Yt90nQ0>Fcb1 zumaH-2WBq_bW3m;Pid2{kBab``pb#Rsu}UlA>@FYe_5w&EX_{GY#a6UhfX z4Of3B(;3HpW(mLiz!_?dn?-)DO{|9%*wvS3+EqQ52M8_++O z532QgUrc;6((g=7 z?7{q2PCrMpkcJU0q1Lv-?(P*)>rR0T0Ql5_BIdEoi#@P6envn@`TS5sBn#&s%NeUd5Aq1)=4Mo)@9lR{#*8Tjn|C+hQ+XOsca?W}B7F9XEa z{RW5LU%oV`q38=Mox07Z`hbS90B>KKl&_bmFH^$b^ptwY=+?YU`SOoB<&mq{2U&|0i=3~dXFXJ|eD1gNN*y4|KO%8_$N|( zZ+84tTVqW0_OM{G0{(qBfq~tBGnFkCnB{r?*r=%UEOwM!B_5+%cZl8Vd85{#>m2uf zIB-t2R_Wm}or);m?&O1ZIVF4n!pB|htP@*4z;(}*p&wX=t>r~3EKGRPuCmyzS6ZcM z*Zv_*NtL6_CD23FK9q18;Lx@D@lZo3Nl(1|nOSy&zI|^kk4WU3-@X>V!ML;He^>yz z)xKDWqrgSONX)4NNxNsXhLt@6v`X}WCj031UB<)+?e0MuP8kW#aR<;`yFVHU`Ecdf zaE+T?f33%g=gRqAs{d1^;xa86f23WqjRlMg7<4<%LbwCH+}6B-Z!aP7WUzYT=F>OVo3?^JzR)CXeB5@l9{ zNYEMp#W;fmVk=m1WfmS2L@U*996V>kSQ14i6KUp2{U2um5ZbzK7m%zuhR6I1=V0`8u{4_bHUZknL(yrklO`W>+Ml~f)MnsN67l6U?Hmc>5at362Z zFe}rn7$%7r*qu_K>pk~-Rx}IOp(#*uo-I8rP%X^K->878noXXJyfaYuHgT9cX5kHaf zM!kh)jY#Lwy6e%WrEjll)Ea2vgta^?jbwrK8wI>PsD2@s^_iE7JKBNFj*FMT>ezB2 z`Yb7XrTbktdfNJYbH)2a=oU1iYfq1cDA+33xm2`Q;kW!*dU)W_KYqzI0#tPt;Ex8y zJ1U)*rh+CVZe}Kw>I(2i0<{C(`bW0E3|IAKZaBM6zGmJu;Srec(4YM{$vN*W#V{jb z=hdZKN1ZvJK)?qfJv8mXsRED96aV<_|0C0-=MyALOtG4(*g%9mE7i>raK}g-8b<5% z|GWyJZ+~};>8s^SR4O9hW%dsNT-nHgyPo_LO_~nEx~vY|qBpqvzZjz}3a7hucYzC! zzzO(Mk}A0sVgaVD3ao7kHrrm{i1DkiwRQA8Q zKn!=detY#rM+^THG@6$(LV!H}>iTdCrZj_z9$@)KDq5`+zPw`Op@C_7& zkL78OyT=0BDXP-1hvM;})ZPEq0&Mn(U9tW{R=Nhi;mh<4dQLa$SM;*(D;V^fYw5zN z%8K8gf@j$R0rkxR*_~I2nBq2F4&yffu{HX!b$=2 z1zTFw>|jUU^t+DP#8C*`yqde0Z96j*y8qm~i-&=Vum1uMPb!jHVv*}`Cv?py8+1N% zs;sN?K!BwSaEhvl9ev#v3XMBuaRKXB8UEJ;r%OS zYozd;IzOBMvs1Ld80ar++j*c-8_WT(@657dbTwFVIdR`b z^PbX?nkXLwkPzy;-%LC@Q0X5olgh%l5nRZhI)gtYA@pxFfhCJH9M3u7PX^Sk)!CT#tdK zcFXNPAFSX90|}%6WD)~puq_D+)h%r2lkD6g2}oI5%j*OZ3OUE=Q!?mtF490jE5KOx{n_ZThSc?^QYJo(6L`)0c|^ayC<@tt_GLV1P{f&B$htUGTjPZu)&JFRTCzHe&Z?llI>(=J2FN zOWs8%D!i~I2;z6qW5D*<?{IZx9OmAJ*aG?1{&na2W{K_Qkkd$n zB9mtryAQ7ZMpWSZQO|V$nyEiEzxs)q|0Rszjp+3pTs!{8<=-X^tHZf?k*DkK5a8HOKEAKW}^zK1&P zl+OmMd8$>UF1aA?elU&$YE9DYBl|fTM{6JgMEhG#!aq1!g5e_vN(^;D3W|{MhO1}% z#4@k_bt#kNpi2^{f(t-ykr7KlHb?m4p7uV7{^Zg2(10Z>W?l%q7h-$#(|=qIV0x1ytvD0b}k}4_cj^&7}BCh&ebfY6ZH#j6IC^YWTaGyTP+6mSQ;nbg{l!wU7K^l95d)P%4%=+ zyR|2^8+VP*H3&RUURnH?vz2 z8#xp{qe^W@4Drn=a45q6i;4n2_AxmCGvDg#Lcqizg;+4OEIu1?v*pWW@QQz(xtKu{ z_&l7f^_cl9;YQ~66=72@t}m|9P0CbX1RHk~_!^?snf^LJFYd`? z8>&>ZcY|y$9rcn&i@gfQRLpZ}8xyQ7p8$2?b+M7c!E5bSx+$9tu&@_19mYatm76ZyeS!Hn2+Wh2)Z_QLapa(hYnAxE z^6y*bQv_e1P4o;SKjNUhYK@Ge?)>kkKi77-FW?mz0+NtS7*G!S z`}FO_$L5}tU%JA1B${8`s}nEQ`NW9ds@ zy}WZ{vIZ>II&vUKE~G;G3lapdsS0_05qum_1-|_JGFPPUd?Lrrg~m7xnP3GMItpAj z(yRX^d;&OoUy1C`5foP%cbV$>Fa15oR~Nv23zQnj6g_grRgmzrfyEwPWdG~Cj|KFR z!cuELpA5+*C|>~Qo`;LoEtj-w!O7UO6lV09cMt7|dxTl?Da zKaGBkou#Lj{mjI^ihKPhb^gDOM3NsoJ-eiGCd-khw|LMfapB`wRf%E z_mvRL`IXqsM?Smd9CF(+tT8*O!nW^s3#ZFOg$c8{Yhlm*JlO?#ASm5&>!`6UE81>+ zBZp7d3+pbgIDuiUSBT^T>WPjSf9z%cm@{tFP zKfum~^J%YE8Jub;qNlU-9{|bknZM@i_5*Kd0B^o7H&WMaX=sS@N8VmGuwwL=Z;#S=5MFX&Dcz}RD4aw4-OXqc$7m5lHr382@}mAFIY>UP z^nt9caQeUG&AZ589aTzvvaKe?@zmP$z?A7h`{7a%`Hzdzli7^8QV+JpG*47 zCpTE3bA9C%juy}uw^LwsZqrQ1o!5{!>TkUqowJXno^1qpx!BXCt4%DwKTZ}lLqCG% zQ={RQ$Dg z<<1pB1aTy3JfwM0G$8u)60X_bV_)2DioW$%RitDbTkuXA`yFgYDb#)$W4upAZ2mJx z*$X__ybxmZll8@)4RUu1qw{73$|@GM)_yoz?72#Cv(n>L67$05fVMGHV<#AYf0{H2 z7@gPpJ}G2vU){f zE81`KKp8C4=}wIwpnb`gsIC0tE?A5OF59531E0GfV{K#AqHYLld9*{pX?NadCqv;M zKIm!{;(^>JmLG5GK=+)t|FFi2-Vb}g#9YAQOGAu&GM&mU?%euhI!8n@^M@tGw(iF^ zFMNf4`XQ_bjxaWv9wE8{O-JcOtm;LdH%n8lTq#M5T_Yue6U#{2eg8Do58FJwYt|mI zPEy(k>0_u$o0!}9`m6XKGQl3H+J$!ISKM-?Zqzh-{Ql;fvEKxL?TsInHQUkMd-GtA z>LZB5F#gJYzyhY@O~xYIKbOns&g}h+qeZE%9P7KimcH>vM0V^uMD@@!+C?xD3<$`+ zDz%jP!{H3VXg6mrv}>m21DLq_6Nc|dBc@tzck-8vL{uI+wVC7GNPDJkkH+OoyCFhe zLx~=<^51Y)X*<-G8qlMo0x`#=2pKi7(UYQ$uH;yCvT?xtOZo|;U@W5f&eE?62O!}g3TaKA%6 z2#Tk1yeWYYhu`zdJ?hKbgL_QqId#=`J-{dK4;_Avp2vs&MsjrK*^zDW3l522Tvrpe zwb^XdtEhYEl8+qcL(XW6KWEo{K?#|Z2yPGAiO=}71?`#f>m&N9m|tp5zIoS00e6wI z<%pY}y@yA*e(X>%Y878Yf?FU4;b z+G_7@fVJXwprDg4338-}4ZQM_juWrQK1}ehO{+F~cf@Z`%?JkUWnIz~SpP^D2w}cv zDKW0klhy;qG5-|OGbE>?PYd6QL|c3@nEYNP%``>U#UQ7d4{#o3@475?0r=$*5=ue4 ztPN*nXE@IC)vah}tV#ZQ@I z_)rRhK6;10@oib?&n3erY#iEC$rX;&C(9=*KGRTW_^1r{lUN3MwH&leOyHYuTlYy$ zWS`=F@#~1>!EUmmC)iccCUK>WS&^Y1Pk2g(f+Cr7*_9_-9y#cXs8SG>h{{&=*#?Mv zFGlIGlCQ~>?udoUC+-4e!Ebhp*b5}sMXm^KB#AfTy*Kbm!WFkU+jC7X(U~Lk(cfn$ zvpWwlvsx1jtjQWXzm2x~u?`Y9mrXopEs5&*BlmgQKjT6OUm;v_`+Q;b!Jpc;4H>~v zS>ebgh@{~rQ5%HlJelhFVn6KH4T5&jEWO4zo29I_P7bY0ce$hV5I%<>b$!2S`o?Fc zAKCI#ZzNYfG=V#KtRc{4Cj69C>E@qq`)ahy2A;G1+|?KATO2vbdrxG;xa6dne}1<-EH(KZ2Yi9)%vnYi(yw`-6kzKmOWwP6w`Qv0H$;p^6~X^u>kdo-FQxLV|C} z&M%y(b~xPgi{R=H4r5^Lrnkeyp9$2{D+E3kDOYTtUXK6ip-4{NL^8S;*1k?Zk!HK} zF@s@cQHrcNp9bC>S}QvH{Z^opt(?=ktmJ-#^m)HMy@5hU)RvLa-1|-;AyiJ8;4bsgKDWw4_gx$}XdCW7ihljZ z{l@~_wTTbC+5IU0l3B?xEUVr$zYh(Gpa`!as@3K(WA z9bdwsnk`!MZ&vUtxA*;@JtZVSl`CQ6fhGUHtm@By>$(?)V=z~k|7(%`uYY^zf(zF4 zAJzNsEae~7`-=nnkAD0|_5M4p`wln%o$965m@53y3-D_=`Ue634_N*GALl!b|6E9R z&;DzHS)bOvc3OkL>IU{T*#`_N7jItuAUi7ck|gobo4K3f?S~^SKR&MHck#CXwfU!P zDx@D;eVi6o*1{(98*01whwJl~A{I)97YfoW>T7LEYV37NEb5mc8deVe96^Y6`E&N` z&ks0u3r7uyoiS$2t_#d0Hp?27Zd$Y9{x9Lk0OHa zDRfD_`hPVHIYKmAA;8!B=Mw*`H^fq)(P$e2wP*iV!${nV!K5-X9{aCW@$)7A0id6I z@wZ#~4*>mZP5lRe{sxt|fcifG^f#!y1=Rlmpnm{pi#q%*25*UXwpiAWfAtRl{R2S% zQbGQw%53{T{{YZG0Q3(4{f!R%lY;%trfl_3|D<65IyLx*1Nt|f`5zAGUjpwx0Q3(4 z{YwSe3dVmI0{#O){~rSoHi)oQ%6ISqgIKDB?_er}7>$H)%x8*wb?^8;;)k)Son~Hm zAu(SqUk0VL8b_c0?Ntxppa&E-gxPNye&9?t-%nYZ*uf&+W`L5bH_@NJUr#XXVo}E5 zchq!0-|n!TTYj8x=Kp9gz%hDho3iXfyVLSeGh{yBffJ%o`3aF^eeSgv%-@|5&nPyV!XWn2 z=k<0u;f(iEmOk&&I#ii(6fZLDGLvMySX)hVEvnJhpjfEx@AlyPmf)NOcZ*OTNDtq> zlFL!c<(Z<1u~cY`q)SNFO^26^p-rAXlzS2gY@G9$q{mHrW`b4;Hgl!WtTs!=n)!hTcOs`M`sBrRoFpbW@ z5j#()?ReRjp^ZW8pyOk=?OT_1qik6&em9}NXp|J%QzJWbEMN&uG+3#)HhA#HwZGOO z%3fnXELEMjw|v=pTQv2N9oHqC+$s0iVGqf-;IcG{U3Z&`mwE({LE8^^Tb%z5t2w*( zJd7wFflC=>itue38tv&l;up4k$!R4*PmOCmxAw3xNsE;&f4WmFI4@T?Ht;IDN}MU@ z^0vPPnhr;E@Z?H_zQ(@#1lFyacOnxzN!#joK!L1%UyT8Z&|E7q;JVI} z?Z^NE7G#iKFBw65hr)FcTlc1e_37FptI!%>K?2kS={*BqhO|4o^}fP2`SZBlG~Zr) zp_c=lS0IEz)0^C@o`$q%TH;w-BiJQUw=L)N9$3x7Xqk&0>9?J*8o%k(#ZfU*1z9hU(4MrIWpz6RM^$$MF9`gJ7Ef! z7R5E%+*$Kw5WC)Bb5?zO1ro zbMr+SmD(+STgBt2PPcSmOe~GS1&iO~z$9>*3%@=W-yn>4Fz%})0u8-Midb|rT;G|y zT++9^IY#~|ct?dCG9O5Yjwm{~O+S%;W+zFvR(yk? z+|NErVr+|d`zDN7^IF>KT}jO*qIEWb(-uu)Obef1KN|(>kwQT`vBQjGIlW&=5aISs z9snVHlDfZhR6ME*RKzP+A_tG&Ggv8Ozn&o@h}am&K)*R|Xp(*gzX|g}v#ajDI)`4B z=o7}z30t&%TI*RV*}RLTZI#z(eYE>p0IW)yP3$zqjRrcD2uHe>QDU4(=)UNkLCx<;NNj?+s0C^Q9 z+_;StA$sZS4u9pXiW&6`Q75m1N>VOZsl5(t0w*);csl3D`<}Uz(tQ+0sTk*L&lH#6 z5^Ud@cxbD6f}VlUHjf;XzJYS2*IZAeEx_Z_w2Xsbb5BopMS{z#tFMxQ73T27ja}#=hK&a z`h0PdVrRD(l{?^?hPwy7+4RoftPx|>&1IW%N9A+2SVzvyG9fEY-*bMs@BWBF$!tJJ zFU(KSI7LQK9uUmHj5%srMv%X>YhlVP8IH8L`K#whV6oHh-bYw>=)c|g3SHsd+@PM< zYz?8I0;_>(>CL=D!?NGws>n7Wc9WmnFK$yPRLz8qDkx(MDG#3i8fr4>fnx|@z((Z~ z!e!P4{r30Al58YE&RZ207Y5tiL$eD`N;|@PFt;_>H6FutQQp;1zsd|IjuWGUu`f)- zOKk#EMHaE-Hpl7sm=EHt+e;PHZDVCO7)AwgaIr6Exbx=9qlWBp8@~P(xN5E4K7gi- zY7ZtN_N?C|rL_IXsx$=x8q2~s#z4i}d8One>(1;E*OJQ$#!>|wA}W@6+4Bc| zEn$W#tvYYR`MDSvxEcES;td4z+qp%v3tICP2ov>M}*Xh=}n_mov zyf`4W1@q{zQ9*>}_ic++WvuA2nh&s(s}qH!jE7HPqjU+0m%YE4q-A&iZS!Dc^oR-svkqN!!9GHpx0$3JpnFA2fZCwfEX%!AoOgT6 z3h7QS!@^c|`LNga%m;wn%S&_%dnmr9n3N1ln&g!EW62u26W5Mx+vOP`LFg1cQOwM{LW zt1HgU@dPk-fqig%V$@} z#d@b7^2TJ=o{=b+enS*bZTR|v-TU7j#rT|`y=ojOuP!+_qc3k9W-=UMZ(IN)1Y)P| zRS7(7$UUMPmTt|?3fioH)Ps-W_Tq424O}@MHfN7t>lH2-5 z77BY^?w4SpO4L4=?8LSXgDfPXC)i*#IUZ_X`Q zNErch3#EZ@XvD;Mtut^`qiC}i_AfgNW@z+k6b9yezU^Tdq8<1u+@_J@N^kC)y(}>T z61?iqX;8=Rj2g z%{H`c0l?5)2%v$ShX@Q(AYrFe#}yasFyO^vg&>x3E4+L>0Lp$2pRWD{eZmct-6@Zd z*z#C+?};l?(a+E);<0E_r!kdYar)CKgHD~M-EdQ3aF11+T0rCRr{hT)8+V7y<6sab zx6aDOmM%c6-bxq7~5yg>caKe8Vez6lOnSeD$>`~P1ID!`iV=6;immWwt}@qO@js)Pe=9v`PNA3=0cjx*x?JM z?dOkwJ{zb=i>qoknkiDknxgNDk{Aribfq1reyXj_dbkS*PwuzeC)=6jRu)AxnA(dwYSnZSg)TV$^vJiAC9eBDk#_;c zwg7CFXw+tY#^UFI1NnOyv6^(?0!GzYVL+^-v7nBq|M3X5=_>?y{NJt!-ukj9r9ly#Jh!Oc7!gY!mOu+;x1qK$! z?$m)BtmA+Ll3JAmjicRq_O;2#=q`%Px?=ATZ01_kcxJjkp_WL2Jjzu;#VA{~htuB7 zdSyh)`FSS|u1L=HYNl;VWR(-AiggZ~TtpTB!ORcdIavaDjEk3ME3*}Q+>?+%xZ8QY z@%dBoG(0$Z-d+a_qg{QsL*&#&X~{1XM6*?dynK7y$?`?ArwBng#4=b3TuVif@LWiP zzkDV&K{=c)6fFP@2*@c_oa!H2zV(<{*jT!#gahELBi&u;n};or{V`#x=?3S`%$9m_ z*hpe`teCK(t>)#6TX&V@TPoJr)IFNu;MdfXOt#=$^ zg#DFjJ+qntvjzxhW;L z$L?~U0a_m5vY6gI7$_GiuF}e07&hMR_3%g&hTA7ZBWV}9%Iawyz0Ntd zj!MtMXC^$|ui_(=l^b+eG{EY)b$IH(k~JVuI+@$+G$O_n?jHdw8sV%u>SqjZ8_V^+ z(za1g-)2+BxOP%4+4-}>h=fMsv0(&_^wGm2BvxUdt~@I2j%c1L&(C#%@;hB&zS$zT z)4M3eG)$5Az@aKWSA}S)bE65-O_)lKI5oJ8zZqj_l2bI}Wl}qV%&CrTl+u}djyST+ zJ5`>&6^yeQ+5vLrBU-)Rl5WTK^W|__7}q{LhHFOrn?&a)y|_L*XG)s(a}{&c#(BTB znUJq7%CBbVwOu+Oc=KG6En4BxjGTg+9G8#Miw6GTFiYTsPK96Lt6$NP=;F;V+7mtQ z*=>-TuVeIZH8_10W~-$ho8p^#dEosdMZ*A9CWKm=PYK;O)R}hO^uMqr4kkd6(Mun# zeIBfeL_tgt1x?W%5YndxLhkVCzRoA?sz@P%mK(uy;F3JKVXeS#d`n{z=*tR9$E7*#Q@HmY<)FEbX)(5X(zj-)G;`i{Nh_{BgAp}KugF&@ zg?=uyG2g8H!JvGjJ&P1>W+iYM4Pf(m05B%&~-vH@5o|}9tWhL z(V|a{)-e}yx=B@?+qHwv)(Z2yGpt$ATwg8GSgBTcK1sIH+FYqMZ!<%Ap@Fk=0s+>@K*K6 zE!*l-@!TxOy-IF>U<|6Apulz2jpjh|KG@WDANTgWs|z)oO}CXo!TaMLgNt5$6OFDV z)I++!rlD6aM15Xbn#Fn+Y^4HRu{(0N z7E!E<0v+K@OqjrkDAm!DXO78*{GmznWD3~f^m1?4*_ri^8*HQ90_ozNh zZE|lUy~z)o+EO65Xcq0o zQ%#r=$X^5qHzF&+7SQPo*2yBFtkU*jz@m&`_u%N^%ml>!?;DfvB_ViAO8GpSZ@O&f zSg7cE@|}qTMcztSddfV$&XLFA)XDdN#Ud3ORW=q%r&_%uDYv)Q@|44%%gmqQow#cYw>(jwvvff+!V6}=jnpG z(zdmep=`Vn`1N676U94)J6(bNc|*FeQg2hz{934e9}MZ~eQdzKx-24r{zlPBli99e zR&m(N`iMF$S2M+uSNlug^hqdh;%-OsMrrXqzp}-sakxV#_utufhyJX4naf_pFCDwr z#EwFr1HWX0ouWei7`I8nS71upVdt9Io$A1pU$i_$;HJbHoAnqVZ8ohuqC2>ngW)sM<_D^zdD)|#hW=Y3Yv0rWE&g7rr<}Y}EVo*; zx$wd(si8%fx?V@kcx^X79Un@N7H+kEXw+cL2P0D~bVx}$^+pC~R+@rJ{8KaQ&t-=Q zYwh|3?y5j0TO_#`@;Y-PyDEVm&g0h{uSC0yYHZF1EikYN)4=S7{8_l&pfPUPEQ@Qc z2bmy}tojvh^9k$Zbu|dBdl^=@OcuF(*|;~DG&c{T2V`uJ!XrK#TF3du+h?gtgvOFH z%^_MeLLUiYlLK9g>*)8)rL;juI09Mz6$$pts)Un>ccS2X_l+O*omu()-2T{s(L54?)K0 zW|hNPB#^936JJwh5n$@uOG;}x3JLr;RPv8e7wHWtx5HF-bE9sUj6gN`yj6$4J|bRD6=;^g8sWt! zP6c`Ik~{8ztLxfMdfmkpMnAg)vC{NM%)9 z;_OBDr7^zP_zm&m+;Ct)*Qn5-vEE(`8=sup-OiVPEhw0TrKn zP5^Jb$r91~I4@cAM2g@FDqQ-4NecpE`9fz()+RfvC!2u$j7mdiY>a-KyY8KG(qk*T zgs%MUDK#s#sE{=yHfj!)KbD&&;&(G}2QGpff|iy2YEKZ#vW(-=YB_~nqP$=HnMg6; z!Nl6$f@{x9u78bKa62(_`v%L3w{Jk*@8J!W2u#Gz4vihc%%@?$W@3vY^j_ZL(6Qd*?~NeJzK+C(cnQ8r-KwJ&lI&Ag$d&F$@*8D* zIFawLxmJoVm<^4uU$9U2tDw63Q9rNH)MxY?gq*{=Cr|Uq0k@hL|VNyjS z@D*iIdk;;08lYi&MzAf{w3MXd{nnZ;dl>Zj^7o`@i}N{Npl1uDY&@!&No;mpS{Mlb zr33xLTuaG~C|CQ^vv+@|`FA08-eKWZmS<%#B<~%_6CkN=_qZ#Uwzs9Buwx)5?;E!- z(8IrxWJZ3E8-!Aw8q{t-VQj*LJV6t0@yIoO z^bK;nd*(zA6-k#k)+#6Bi+Yg|!u#m>af6V1@lNl|@)lZEsN;P0k>;tEZjSoEOjpBZ zN9FdNeNc2OzS3DxzBsB7wEA^;#VT^ zr-nFop^*vhu_KAe4hY+Y@L&7!$wX zV{WJ(7_dje)CI@O&lQ0t^qy5w$^kc|$`71!qaT=v6WRM7tw#|{qkNur+k?Lgbi9w{ zK7VB-Kozqg!JiRU%n{&C4T8Vo?v*4s4`*~(@l^Bfy%=Mbg$H*wn`>u)b^k5q%upy+Zbwt{eu53A8mFo+<>->_~-E z)L3l_Y62fo^7PV54Ga#A)sLt+lUQPWsE_A8LHUjN>ujRzN-AgR@|vsS)jt6T`kfZ7 zvNF!1B00+S!dv@EdqU>0wki`)>PcarU}jEar*jrv1;UBu&&w!X}s)OaulVgVR) zeR(6(Nz1Y4+dYMS7^fPQo~A%Mgl&o)1Q>#uh=ts0nE@On%eSe9k@$r-wSae&BYNDr zo}>t_x*r@Zo-7#SF))5>RB^;-;1OeW;BD+Qu$Kyf$zRS9l<(6wgluaEq4;FgwTBlC zxBCrsC<7KO$X2wtA=NR+wsv^)>mMXQsU1AsCvX?f0=9IY<+W(sfkPx+YgH@h$QHu~ ziG2t?r)iG3^d?>Vii4DvxLRGDoiG=_y;90#AaIUpP@?8FezRTuQ^1rZW0L8SGbT6>1XAz ziOfb$8Y9Q(9gQT*5ZCeb7g59XXPI8$cFqU2LDn_WWRccbjWDeFS|SJWfAj)uXvGca zly{q5(}s|>`1)Yec99P}QG&(Xh2ZbnY^p#I8eZcy~vn`y1_))awl>8xp7Euai zr3i=F4;_+a17|%p3J;SMt$Ym~u0^P7dCbG+N+0Pv$H;+MMZgW^nn@J_Z7@;!*c^>x zc0DO(C&i)qmW0y1vxE-hzj$Uq9Cc>^>Vqe%V%4Wc~3{@YU zC`vBafMG1gH}9~$7Yc2V~qJ)y`0yU2774--CLu<6{AC2vtXOLq@OzL-c9Lm57@ z>8&&|rUZrrN;C(gcw*;)6VbiwsAWBhWacBlyGIBig-^KLP~)7vrI|>#F(Fzszum&t z?;6i3gUN)klI04Hud_;!&519OlBibS2An{P6J~78{jVIfWlJT(qV zM>*Vp#Ahu=R)eEqM zqq;E|_IlIjDQov4(x7^>uXFuA?K++Ap&@_5tGu4!vrXOJ$Y0sZ z(E_xPF-Y}{LK+ZKmg8>npDoT4l!K$ao0@92|J`_jl;FZmH{a$g1(d7s>@%Oiju}W~ zGi5hCo-6|Is46r=e@NTIrSHt)F?eNZcIjE6I6p0x>h0iYh8f&dQ~AtC4ZKbf1l4S` zIq8A0DJevh(-RJlQZECw%6z)jrB7+^hBo?hWyY8^iRogoa;8h4BWOUuQw8hZ{y9u) z%0Y+KyC)hlAC8h=s3lcYuFYIt1-Xu&&XUS}L5jC}p@hR&Ok;p9TzP=0H zuxuwicLB8PM!F+uk-ecWgNb3w>lX`S6tinBA6E}QLV1tLd(qHJ`ra9mseT>uJszF+ z#ZE@Ft}@-U2Y8NBjhZeww@O8XyS_KCG(h8dD-=JUpd%p3>liNw*tJZR^0c2{9ZM6w z*pE>hQh1KnT}~wd^sPhC_q@>VW0umBs*kaaiRERDiL@KvMDsT~1usqSJaGQw z=^Z75g8He(ayh-0&DUb%Hwh_JPajVMw!tJ;zbYf6dquC z@I3M^v#mwhASIyt{JJW3`m`Gpk`&3&b*AnAMWR}su_aLzJy!k<;S>%-jmf&?lEQKD zbB7;CH3YAm-Bhoi$B`B(YiKyD7D_i?z2PinZS2cH#3Xj+Y-VaniVSx86r=vw+MT)7 zv?Srm@$_gy!Ybmo3-c8F>salzbkrPGqN^|`)pI}gjMotQGUVrqIdNVxjV{7>F`Udp zYBJnyK38hP!s_r-Ax6(m=&01Q*Ui?&c?@&Don>@eAJeYjKd60WhpD65BB$ruxWmjb?5sAY?ZT@U4S@5!*@vU0i)E^ zKb~P0i44rLKr@9~%BD_v(&byTqg?SRNc7@Yr3;i%eK--6KIA0g-+XyQ8_`+XO;E0} z-cMmMRClI^RUaMcytIt`WTby-+Z#`61gIezUz|kylQA3MU^4MvlM5-#N z1GQkJ`AGj2+q1mSHiqz!SX%%F?R4b2i&#`;+c|#!7}l)?49R4y@kgWEnSnqK8RSV##!2|z`N|*`cpd&iB$748C&V?BjkCsNW20YN%-6x@ z+k!>f@LG1;PW3iQW+t6(wNqlg_W|7}$=1}{VqCbmRzy26`+Fu9c%%Tmb=thNBN)VP zf9*_T5SzXF+Xnw7efI-$J8hzq?biBdh$=kyrX_u)F1&KujAsgi5;`O1EBDY_LU2sa z0PQcVan<>X;DrwZ%5GU-oH{=iJo05&sg-t_4g*i3fAVA@tLgf*Z&Awcz*T(mX>q*w z7qUdP-%;(J#<4%5gldj!2GF_?gW`aB-39LsN(`=6PB{z<@Oy!AG3E+R4sp)iEhHx> z#|NfBTJd2Z6G~D;^==SgCdW4S2~OEc8RH=*D+QN5f+Avl$}*)zyQV0yz;;3i*iDO- zI-pJT+iUYlPxAwt^|grxxUGtDsuCyAu%=)czBLMh^#!0*L{}hOwn^PYz`A&Ok8?6a z%onoT8xEQ{&4n@*v9}XfQIP-(iRV{nNSH%tmb!wGIn2ojEpL8vTT2$Y<;0}a>QD3? zvsJ>I>G~TU)B_G|5mKT@%`S7om`0aAS#lO6tY>~&%=8OXsJM`8c1IhbuUH|kkPtOW z2Fj|85}``+comL9zQOPjD4s0I$dx1zTx$m=Z=>v_m%C=~?lWtZYXuu3?YghpcHWO< z8=vz&v3BSFON)%vY_$YsJ`6Zh zEPCuPAo`xwe%p=9YuJbP`a=J^jG3QKs632Vx)hn}49sRqDU-($w}BN=W`8QK zy4EF+sw%F`QJzjgft_aKHi~}l+6%691P@tfpBNbnby7>{6dj{J<1@t`^F+xwiFKjf zjQ;)NWZTXMxhLCSbrO`9vSk_Jea{7^tlqg*s#0@sUtMjO;Nr}BIfK|&y{9E5c8hKI zE91$l6=O;o>3^5uEnJtQNxx8j^^+aA5A4$SOpg9xr6=r}Vm8pbB>SN4PJ9XYGE1$*s1CgPxL*t!rt(QyEZlDx-#Za*bHL=f;x#I(cWGVBd<=+}r3`NVOTNR&iPxqCWhoX|)Zj@V+JKH;ZJviL@sxzT3NPqL@C8Bp_5KxT(CB>~HvaG%wZ~B9 zW*w?p3kWk?P6@Nj*nkq&)d|B*3AXH;RGFLdkgRJ5b#0p1)~GZs6L@4?!J3A+TY;B6 zN%4NM?oxvQf6mKoZiIyL5!SfO@aW3tfE~Dcq5@(nVL2ksO_> zGk*2i7qjVL@5`V9{&EC*4=rlEdU`@VRpu($@U^g=a)C8OYa*IC zzaKO}`oxl2g#$b9@4)SaNWAjTNc@cz^B$x#Z2IG+14FCX!DeT5I8zGFgUWmd=b8Zp zXy_@=}2D{NAbL@{%nK8SFZdl&Kvpx+Glp7ZAO<33r6Dd zwVGM4raRTDLoF%GNs>ZY??u<qGn)|ab&DbPn#`&1wLosy=ukGP^E2-r8_f3IKR}Z%0ew<46%@@#e5io8DVYloaK`ij zODy@lvb6}DWv6Hsy*yI6s^zR2oF(oB0xE&Kx4#;5apU77A^*9ZZjL&F<=Tij=1og2nE$Tvb8f%p5;QPvqV zqgv>E%ilm+XLysJyYxNe=0SLj2iQfy%3r08r?>FBHt!yL9S$I@-Xv8#(-$yDGq$+= zNUnXhy}^km$a!7MFe`TXz=&Nqd+GXYqqUL#8q(B|q*5H#xT*9h!D(TGsec9`|0Il_ z%(v)&h< z_ZADO%*dbmVCERh_gRN2}AZy&CwC;=}BykqQ7r!{xJuotm zf5hBbU0EIo<5;;-B$b(-xf`5hpCQ!?s7zKzkeq7x4V3+F2<#ttr64?|V!nStx-FjB z=pZyn4tvOVL&9W>!vxp$XlN}~AiZkQtpYlgK)SP8tcgS!M~BdAiPRbL&z#p`@Lme? z3dF2#q~TZ7EI|WnChXT|s(3pXH=rjiOhN!?>=@3ZVLb_^p5CD1ph>qQu5aVW0IclT zB6cEum~StU;oL(_N^FfHLv)^>D(-h@5gErLH3>_6#uUNL@LRS(N!JH(0S^*`P8s;{{HTEEt=>)WbVcqK$NYn7hg+7}z3 z`*{Qz-TT^`^S*g)5%n4?(sT(;BF{U8QzJz(kBIIt=lr%Pp|L9aHskgs7DuI+UTDcQ zUwATm9U95wv{k_tN1$sdveN|W>XHMGPExT|Xth)ykh&ZJvl$&ziv*XtGG%015e90C zFk>m?#jp`o(=)bhJh)^Q)|kZLC07u%Vi_HVaM@A#O-sct{|)-rcgk3X1zRV=F&Jn7 z6+VCK`OJaFevXFLPIj2R5p2&My~{5_$nZ85Kb za6EslNr%@+=H!5L2KA$es^omBLrrR73}P)NMH0L_U8PQC=|_@NlW{TX_Hsqs%y8zU zTh8(2_L6r@dWsjNX3YAY*qkWFcKJE2t@c(5(mgBYUF;g}eUczOBk>Lzy^cX&FA zP^vCj?qn^U+4YXRXZKKj(s+)J6{V31`tiG4I2m9@uH z;)0P32O9Q*;t*1871*`&;h-R*6og}qE4w`)ti2q(euCuUPV$i{7#zW# zsdJ(OT>9QK)O+>YQmV^Xqf?OXNBvsqqgDdY)M8*&7vW*m*{CydObR>A;WXnxx}WqY zb=!qn|8)S&vm3q8|IO`ff|h98X$PnEzIJ5awB8hbYNjaKcW*pWO&7L5szlAM25di^L~PrpTnpgbi^dm|ucFgUkV^ah+NMB80LtjEGT{YWOGSO#Q= zk#LB%P|PRh56`z4A zSd{Y(z2-Hltm4K|qrGbyGQO`VNgR~Ko{J>y=NK&2ihh8=flFBoMey0Vfn(kKiR(+! zzNHXYF>;95+5;acjDX%p>h zqtCYnA*jA5VG|l#d5`0RUs)ax z!q~Cz5{N)*R97yCLq2GspJNREERE12Q0KW)`{cS-<+R}9=jfr;woY>4y{2F}x_8gd z>L)?$`xbJNuu9zlJN^`*N*_wk98V@XzFBsnIAi$+3`Q6l4DWujLz39#-yVpJ&`t%a$y{e&CEeTAYZ` zA#`F8x^{_wH0rkd0?Dj=$16rhlehM!CyXE)a&93?o`&K%U&bns6Y4cB@ruLoz6|^v zV!l#vVmWTFwy3Z1E;K&dAvV~y#F1HPn1e5pB$>i$n+s@MgCyb)^v|mS9H6`3m zqNP{^pqWpGMqO&Km^yG`lgx0*g4MfWUIJ?xMjN@>5?@KI2mygkNC4rx%JEAT=@By} z#`2GJI{Q7EfRLP@UZD~mr5LbS7(1!++bWo6535I9XLSedh0~nT3IV0TUWQ21OAv4t zUz8$8t$>Q7sAFnYR4VQcsoHO4;69S!vZm79Qz-&w>#0H4BXzmV=qruN$O>~(vM7fDs;OtKOPv?*Qd&NuJpl8qjMid3>17jkOW zIMS}r!>5M5(9p=bQ)K0E8v>dfD7hdgeTy&nEWSJNVhRe6v0O|PW5R)ejsvic6h|I! zr9_X1Ug~Li{q7?`oX*`oEUw|hOScRMf)YQa$*5(FAywoo$~-4<1iXd{;7Q#m)UUPy zG5T;MI(cRndbe!tL7HBlCk^fGtGsqJxCw-|ZH88rsFu7uS*)qdI|JAsZt{~O_J!xi zqwj6QxCCbDqpC>-k#M1}r3R$ZJTwLA+Aj&^6>qtPIj*B-?gc%;V7#5DTXv7i18+DZ zf2w$@WX-%({3w@K%bZUY=wj!J+h;Rg`Ca_DaWfjbo(&qQeP9S5kKksYTX5QdrDhf3 zwVQ^&PUc1%PFZ73vz7#*K*A?37=4Y?ei~sumQG%Ubjc~CY+L`=vqWpXYLe5d zo((8h3F%~n@51F^-m$t%QA}PllbW>DG@UHIHu-kgrRdu*=xQGXaHMAht-k6e|qHwA8BMNKVIQaQXxUd)I~`P*4pYu=AON;>2@e2{C+Y zVExTFL8M9P2)n5foQGpVPeO+fcMl#;(eUV_FICohk{0p5CFY7DjXHwob(pg64HY5j z@#5{_`+81zZ9H>CNjE$I%Co8P$L!Eimra*`lBH+rvS|ksbSlrof5fP!E~u#WZy2w? zu7=`nkVsiCk&IE)aWf41q8TwhyOBVC{ zNF|Rsip<*}eauMrXAE+(rvSgX7O$XYB`1+Hun&{kHU%`l7!-1)+Pux?wPbQJ?mnBg z-~+^w2>M|pA=0;C2|Y;Hpiyj5S(t{4y=vt~tBo*{^FqkxTWNFqIGw;|e}{VspN{P& z9Q065lTDFgUv&1;5uoikHODaPZg9SqUb@JMy=vox(`y!?AX@0%%brTPV@c z->y^$lOpWafl_aCG}^}_H{PZ`LiAFDed^Aezk#u3iD^Q)Dy8;~0953h$yYm__tkk* zb1ktwXApDvU|VoepjY;DJO#>iOimU40uR?ow94r0^Ijs0hk}HJW7Qii2mokVms1rJ zI`uf(n8)$)zQ@q$peV)feV0aL%eTMu_;0AZyFWbVRpie5B!xR*EX8W>mQF zW1b#be~&14%(wRu6f;9#g7+kT`hSGI1ymH;+CL09zyJb6gVX>99V)GKsFZ-fFd(4< zQo@kZFr-q7NUI29(b7nFr*tzk(%t_(>N)Sd=iK#uOO^{8cRcZnXPb55p+k-7BPL$} zU&vJpVY8O#n2P;3!f%?uPF4s#M77n$-h8`p49Ma1D+~*b55A9##Wz=ef{acO94_^X z{Z|kHi$n!Ldv~ic6*F-4|JJH?MagWmvh%I*f{_jPv0ca;dWcp-CB8clZ~@y?%Nr`J zh&7H}|M-FZ@dZ1tNl**!rh@RbzKjrnKW!_!S^4m!*n;Kz@DNuLNIJ~a3&7nh9xo-b znoSNyG*nll@|82ek}{8u0aCxe!%VaP{Vy#*)!Z7$Y4-0kclM~}&0L#qteMNK+Xj|a zaA;?9YdqY=060FE*Tg`^p60eC_KP-2ftYJVUG&bs=;6aHW#?*QpH=quOy))q@vb&V zXe4_RK0XqlKA4MW1w$={9a;&w;QQDZ-u_vqQui070ouH;?OFN2$U2jOMFnCq9|XIA zAXot^5M$ehkM3ib4KENi;+6*OB+W){Y`|?4JeP2A5M_%uy+U_)QHjWstqawwfMd~XD*NUSOxD*@Xti*p@!>%~Has>8I|dqS3Z@7$(Cd8_X8cZ1$~*RdF32 zoBY03@jWeuTuWvhV4pEtgTO`@%qIoxGc$!=3-YWN#`{}dxd3qhbBcPrwfGxg%rf|b zocP#Y=(cd6uw$^fNDkD(73J3nBjH? z*2o$to6@Wmj9tuy_rbpgbGRD)0={}pxjG1r0lxL|mz2v6xB6kqO6VKlU$d#qegJN{ zaWXJ#uW@hZ73Ftj#5s$4NUwsr+nuV?;PY9@4rzQND6Qz0_YPFczuw^UX1h78We9=L zDVANvCN~$7y2zI|?iUkUOlVNQGrm^sS6y;^G%b$`ef_ftBskJNpsG^CVk`3z?F5WA zU0SV#m*D$=L%U4}zMiCdtXb0rg$Wm(D{RNkhQJzA%gUEt0TPE5h>J=j8g`_dmwtTJ zSsrn^bb|bTqcNczYG5+TY=Cj{DPPxT%bVmhPt$}#R zPT)MHT8zXt;7$O&8*Aj)E?lzp0MG@t2RS#e$q=ZNC6Y8eWv|BoSAfma`{$uRyA@w( z=K@rcV;%PwLB*kiU9%CI!y(p!u4xkDqg?};bw*GRTNCu4t2b_9D%lJDaY(yVHhbncNB)`wLys>uX8nC-L^VraRC!Tw;~SDDT} zKq=RQMW|gpu>ea8A8WMlB#A(opoJiiSEXTvRvo5kuXS6}4u%IRVn&Q+6(s?H0XlZW zlj($rsx?{TJBL|B3*R1fTi~tQ`Fp>&{%?C5D0M`@(ee_Z{8;)QiwJ9iQde?D4b5=< zu``T_Y;s^I@X9a1JhA>L^QZccUMdE4h6DSpl-K@LuyX$Uq35qOq}-mK(eF!wv})Zf z3VcYT?x0VlKJrM!onToz(TN0Sh1iJ$zW?JnDY6iz%D6WRv@)HqFE)cJ%M++kE^+r) zzWw>W&1>%Tu%!)~Ip{#s*{6E)@$zlTJarv?_OY#aFOGNhcU-7phUf>tZ2=DN{p3D< z>b!Sn*&z9hVLqFRWS^eqj3)1%097dPTagyc_?{zcVt$7`X4notxJcCFDkpArJ!{nn z$k0mHkASncS-gBF^Xy&uHNQ%$j;(S~0yB=_$- z(C05uQ+Dg2(->L?qGt80`9zBOs-YVP9%B=Gj$Tslj>PBRI(C-Kk9({xZ$0&t9I^27 z?%!Ih=VdLeUvrP{ivK^8UH3N;J-Vk;1k) zEgEvm_g^2$Fi3HwZi?iCHW8v1IREvr9vETk3%Qfvd;DH|2@#_9-a#!7fnN>G1Eyc^ z1d%d+EC{FIP=b8@iiJ{`u@*JjbiHi#Kq3(@+Z4n~KZO$KZD;Wm@ z&(WE$DgQRZM%Qi2*N76~Sp;LqnmOJuGdKF#(;i%~K)erBM1};~^2e63y|qD`?7Jy9 zOY=^>HE;Eu9e;C2EP9?hl(n*EOiIa6!(dv=?jW2FZL6~$Rw|(y-sIq2j1fzWK8D|z z&J`y{+unN``Rf$H$?*0C8sb4nm2-dy z+GEI&5>gFp0)e`_9d9JR(|*@@CzUXPiIg7i%U+SKfK+eIchbG)*6G=F0dn`jZ!d~H zVm5fIx)idB*sBisQ00mE?7#LCZ0Ub~g!tp^4N&IGH>CXI>_#)=t^~82>ABO!L5?XF z*2KuX?`henFIS>$@Pxw8IPU&Lo6Kw``;+wyHv%*FT>7Evat(Iuiv$yXwI%g4>8T*Q zT++QZaLJali{P}sAOjx8B?6Q0!1T!iUm!kU;_1}c6OL8B%1ZLlIWcv{K;aB!`B9R} z$_uAlUBQ`ogjB4>C+LtwplX(O=o2Y&VES0Ik+r(Z$D1@4## z=q;fq)e=RX5s+SZJj){bB+2@vvG;*lyItQ`?2ETNh9`;Sn{3ciFbSouLvk%+mc;82 z+-}iV8Z!lE$IopA&Eyo7eYXtQJ;X^A@h-~z>*Iw6-l#E8=}ms~kbj06Pbxtl-f2nr z%_tcL3i=tbjwND0Ss^0-g44v#cGiYWDo%Xa^_k{Z1-sqZ#?s}mm~oXBrg?u2k+wDIY>uAnBS5oK3nz@*dRHR zn>|2BR-$IYs_%rm_kTLuNWd{@xj_~yG8()*`vyel=@2VwC zMdLLw3wp&Qva3D3ZoYyDiOP){X-IoyX&q^3wFxQiH+_CX>11e%+3?a!w8?9N&foWb z`m%3isDkMw#G7;T2&sgW7?mBy6A~MWx;TjJddq7b#goIGg3=2TPM@!gaYCy3m$~>@ zy-$)rar*W^m{khYq(}*2>waqBLdaX>^E$zX_7FSe2&Q=Nw<{O#$O>+{f$U@Ug8_l9 z^oG7g#m&bQzK^(hLqGs8X@ashPapPQSL4q$@hgVf`(&1hbRm%c{mXujD7w72qcT!* zuU~{Q;37l}G;?vaRBKE!&l(CS>YM_=b_iw^WBdI@5v^1u(p>ZQ3!O_IST^&td)$-{ z;YT z9^}DyVGGY&oQbJ$F-A72E59SVs2`(ehpofvu16hH)mw zIaP#byP!wO1wI1ngBM;GI{PyX=C4RTTjyxaWNP0C9+*|c-T-$I64`$pe{dmSbhu{5 zYOA6#15YSbRQ~xpE~&~?G&MgYq6^f&;#WplTs4T}_qs5hsgdhLy~&WBc4M&!I!@gZ ziq_Nse(bD%rPcC1qt2z}-cONpXFwA?aI6i>n7XwcC^Y{5e%DKouw}$42EhS0U~beu zK5{4TH(|>N>>HRnr-h>|q&j4IeWG4D`yS#pfpkd5ge#Lp6h>@>>luEy9zo`sSjSLhXdJ66 z(|jngUykbh!$#C)z5LLGt1>Yh_|^J28$!RM*ErEk?emn1plN zUfO^$AcpwaX}nNS2SygSJo9=1UZS_KeWwz`O95Vd@2`;p^Um~ZtNqnrHbXw$(`1`v zdf7(PvBusTuVX(v{kGnGgwq0fo&c(#4^B^FK+61go`%z6!`4zczj?$zfB6PcoV4J^ zc3UtuzI=FXQZOM?j7y=+7Eo;^^E+WBQfWIn+giSug2k8{J$v z10-DA`UPFs`E;(FLdyCH(4)k^lpYU>@HMLy9TVAaVx;jk4?W=BI9!^1%4K(Iu%se@PKm_UK=EBvl75%9u(x(z`1 z)Hm1eo(+lyBm#;$DfT2n?~T|=3)v1|m)5_P#2Qhn-)Ned8Kw8Ati{}0Wi+`O4||sW z_3;=|Y)n1m{c<#zXX~9_-u^!#K8o^%0Q)Ar#jt89)2Lu@J_Ow27+jOb~YGg9(>Ws_)7 zbL@kMg}DFv=BH5PH|nr;{o^{{t%2mTW=GqL$2n7mgjQ|xCX%C&=lc)st`@y{ zo_FtK6Rqy8no>X#-AeCdb{S-|j-De|w|y|tovLiTVFU!i{ZA!bSCe-2(slVZS_LW} z?SlY!?)C$_M-1~lwt=VnwJQHwh~G=&2e*Yk6X=;cRh5zsiOD|UC@=zVigN-!Qgmgk z(xUV2*VrF!Ux?9X2c14vX8y^pAh|QlI)2Z!?7f@|d~22{nWV(_AxO11emAJuJ8o@# zPK{`Zc{Kfwkilai)={ToL}pr&iR9Kl;}`Y-yb!}X7#HBG-Nzh~Uh8H1?}`lW7siSU zBO-d?E9w{O_2gb1+xdR)r!mFMpV;~DauK1yh)563Ok{zRK{Yw8sNHx*H`YSY)7f1y z2I-)NSPxQqO*tm@4wKeC%J|Y095eRst1(E>QbMZg%Jk{gK~`K{?BWL^w5Bq4?vBz3 zwjV24;?a?{4<=*2+G1YVn>+yO9U3qwF1?|#49WpjGJJJet)*!X$mbtj*47=6U4C|2 z;!2~*$eDPMnL$8J8}rWq0M13r3mFBEOAJRbW=z?80+9#N|NK4d7fmX{6zPRi+5HqK zKTnBukmHK*P3{plqO9ipg8F@0?KQrdDDq#D6@)YU9B&{E+<@Qsx{G`;S>M~vBynvI zegRHs%*805{4kUoeGUDkKX)l1{ndvu^GHRh6cr1O&kXzGwD=RKEKiY7Xm^7MlY zv)_5Figz9d@SOpb)a6pA#gy4IAVGUo)riyDr@wTE!Tl*R2;0~!n^ZZx`d3^4kzz){ z_sIIaYghisa96Gn-hUStxRg*CUxACbCfz(l_h7|!-xwb3UfQ})Gug^POJHp|lb>D- z@)oDC?0Oi(wfw@KROLvg64P>s^g^_4soT~Zp0r^8uU;d{O{0)-wu$KPkPUw&<4&q0 z1Zw6<=0E=?rxe}*&zk$3A?@6un>>_PC96KZu4v%{FIk z4x>}KH;C-LRUCpX{&$r4)#P<0J{~r*T^OXt{bwMBz^mw@aB>!2L%5-k0?LftJWf7> z^bMtosaoh5QFH>FK4qdIobl5LiMLn?D_f1)JE@yqtcji+N@4bVV))frk16+j87q?3 z{)8ydIodMM@<49>iP(3IPK2sy3rEH z-abT$gV~DPq2KI9V%dyK$cdsC-t7s(1;;FIGcTush0H+R=Sq@2npO|AVs%lMR1CMM zbPm8x`kEGcGs&j^+5Kxe)8xfImxA?Km>Z{#b*E3_hkjRM|Jjs*&qLmUzD#Z{J>H|> zJ;x)+Khnm<$yglYTgOo;(v)39=W}gB;!c{EC5S_-k;fZ$M6d0hr(K3BsbNi)NDu7z z+pl;>du#71B3Yfiu_izo71H)?>2{ z3-4@WCngJNR{Z{Hl~EF>8qgGFgMBtkm;V`BEg@(KqEWtu(GKHlcs~zmw#CDSu^&Sb&%Al#n*1f=;#|F=qD(R#otW#wQ!bG_3xqs1tz%63}2=vf~CVi!1dXA_b! zJysFv-s8o@Gr2zH{ne$6_3DfLy;kZ4s~xD{I+)tYhAg!CGPd`1f)hX2XmRju`RU;@QmUKoqxu`GtqTj|N#c%I zr@eqOE(4`-|5O?zVC3*VY%)VXFT?W6&POxVR~WL$Umb*&qiC^0%8U|}>(&^Gd|fOKR-4VN|y%1buMCO{#pm z9`TnhuxCnPT{#)31ZlAoFe~9^Z3ZY3v3)I4;@invYy)n(0bsR^5K4?}A<67xhSR5^ ze_}|>Ti=o_ZVx!*H_~x8ACjdzzSefox^hUaM%g%RNS0=`TFSKW&E;a?3waov7 z`pH@{`*d}*1W)&IUtvBNWnnq+#1tiM1#%8@DG#(P&#n5tS{{@Ez2-fE_Z?vL1{vQf zKnOy!D^DdjIy|E%@<+o;OMrU)T95h?X#t;ZlCt0I90H5DEKCO)lo-i1;ZHu_nU16wRModH{{N)hjtcLe0o_q!3eF|=SW ze($82e3hZzYqe_qyT2~CUlcp+hx>Fo1(DySi?$VQ8^Q&j{o~P-oV(KI9Z8maj%@hV zO-W{D`oOjYJ8{GJft?D52k%z!F_5W4M z-aQY{Z(4U&wUI9qGv*G65 z7W5>jRxDQt7(Fr#igtCJP4TN^)at^@W~MDpj}Iy~H8f6%5KFS4oce2tF5Z=`GHivN z|Ld}G_@(o%J)L6;S{`7h#Z#e0B2On&RT@8WL3f)CFb{&<0Qr`IL(B&?$}8aCCo-lm+EFB7j2G#_L53+CI3|nNCMI~PHudC1tx#$sGJKcv>8fKwBzwX$O=+E z1q5?`eziSN5j5X2ZdH}z=Uq{Zkh~E?=vUWi7i;AHrN0s+`-B(ctq(xZiI(siF!s66 z_^uFGU7|R9-kok=;hVq?DY-q97=ID>brleN8fP*;R4X&7#_LmAaNK>}1!Vx$j|>`$ z9W2`0FounPMBMj*D;x-Qy5c}ADiXVP!88lotN@T@!l?w?o0+%8QJ501YNCAjwl5<~ z$GH(f5ikA~_k4}<=17RLxq{3XIaft+OxG=Gm<`i;_A(izo+Zd|k)W$n?tgbdjxY#Y zMGGiULyl^qp&Fy>JKw|pq(Q%{SCTWov?Sq&YWzA2catC{H&L%=nKjH!9zAwWSsv=7TYOwSmFrktL0)XqA9NA4iKc4hw=rb&0O&rLp zg`3K3P$hPN@U`AL1K4SQkH&OhTKf!&^WhIgCHThH$o>YVz#ACDlu0~id?O%to>hVJ z3gX=+jha>vGH;_7a+ta0cd!WDFO;vYXwc?abkc%h5w=`3&)hQMF9c-Qzv`rGu}YQz z=}0}W7+-!;JVoGlR$I0=?okh5bbhJB1&&;B6qAlL;&Nf}kRS~5VLu@aopmC1Cpw~xK7tbHlb#nS-B z3h!7=kioH$0zfG}*4(Fr#_>fE+IQGs`#iQvu=VIoQsvxCGkeZ$`H!&@mjQx33aS1q zkC4wT;LAQNAbMbn3Ml_XjBfW7dE5n$4yjA`1ShIL&S`D@{?-#7pL^&@Y4FD*7zQoRbrRmBxd_Nvc%^`>_kjTWmYyv9j_f)XgaL{MhwiUBJel{43m6d`QeXmM zT`>w%2Z}?yJ|g^TKl@AlTLDB=SBHmzrXn^yuAzSBHX;?(y+_C)6(G1w)C1JU6E_(? zNcXYMqbB&98fxqXo4f=69xzJ93su|)a}C8C2h#Nf_@q2dra-h(Ym5zr?}JAdZiTPW zV>aHW*kpBirNJ=rB9}c^)lKHw;um)dK(um=B=Vtj;hPO2WNpuB4+U257Y4BL$T%GQ z>TVp;t8}mP;Pm+*9lK{vU8SA*E0)1G~~xbrzFYOy|e)DY!b zu_nWS$nwuyOj1cY>SVK`(uLP8dp?x02{y)T4kDlDN6(2dTh4@q{r5)rLdu})fpwu| z?_SEd;8F20a+p^VyOa8D)Pf4MEvk&xZrsJ29)Qj=Llik-*7`vlQopHUxZk&n$(fC< zQ8*-Ozk^f;$PXLA&t1QZM_`zcRbf_JW<%vBc~xM~u&rD=Uc}Ep6^ZVx5iC309uHb+ zsvNvq%6KSPoS>;(=?OjsB(eYd%wQRii9QEfK5ZabBxG3G2S@weKA1jG5A0;zCM(1- zIc8#RK>K(TUqR5R{x)0>5HDBAE?nnKtuQN3UBP-U@Mve=`kcCL08%algn6R;JOCn+ zAk;IB%1ebkv4GE~ciu}x886tCJHs|ie?m;S^a>^248J|PJ?Y77SS-lFQWuO`31;<% zGO_Yzwj4KMK&8MW#v+VUw|SMHDO3k$xUeB>*05y)Nw{tq_2l6!FSNs%Z&uL*>!T=K zsEoVPcZ!Xt9{BTlA=v!E@`&G2bN`--Bmu%uZ{pQbUwUlsa1A-Wv*8ypfzd1t%a0l1 z?P>auxqsf2d)S+D&pP6Op8!wOfG`NQFWZQ6+0YluJUbk!d(Vn39oOXn;31`K>dx^i zGI6@%4ZD|(n&uq;zAuW3CZ924c485Z2#T3Ii2^5OuX+Ggi$k=}2KI%WehSkm_h4QW zfn(MCF1c}w8e}q%AEu9mUV#P{zlF;CX9X~Lee8|J z9Pt&6QgX7mM?}hGp(okogC703w)7pG@oAuO-q!JD^*PqWdXscb?Ew;i|Mok8s>Yh4 zCr&`xlT77{V3n2<3<155Ssh2CAoKuTYFZm)xgiV92X%jP_v2Gm&vjY8jt4XlI(N^m zipYNoyNj_`_%ti8Rtd5Ga0 z`?Uy%vek*oN)dwdOk#op^fSYX;tiD}+QVE{JNJeaO;>+Mk-wXOJK+Fuxs%xtH}Qbo zz7mVZrNIXbm>Ojby+PaW7o%k4;ziE|?u0&NPM9qKyk7owsV2$6${$CL-1xl_a6dHF z;P*-KeU5X(p87EYL%i3)pE82lpDjiD6^3+}6gFNh60xA;{L`y0MARzOfj7f|U zoDiem0ZFeDz4&E~Hxk01c;)Zr1C#yZjcQ`r%t!M9*VgL_SnK$MFzoG;hq852E-Xi zt~4ZW95&$+GQqAtKYs=U&K0y4Ld57$Q_m)xM#c(goU>jBdeX38%jktrXLAXqa*5RP za6!5YtDH*dF=aAb?8b!QT*~^F81M5~o(a4;<6PRQ_eD$56Clhl=~S7mxjR}PCvrul zd|VDWW}j-l_4iu;{^b9WA$Yo4WB91l60SEt76o&YKhpTd2LmdyV<}R!)xQd; z$KDsbu`L`@vKcQMa-AB;y3Yd`sdOi%a|GvMp!dIJEN{;=gJGHQIV%^TO^qA{^HD0c zFmosX(BGLSLeVC|ixCZkqTXd|YLh@8(m$+MLX392uj1Ct49M38TGlS#@8BNhA7NGd zde=Q^adC;!weoFd{KW69u09YP;3nma$vz92L0$NCzFz%{xAZs#%JSX1EcDtOj8eVn-o*ni6XeU z^FWHk_oVW~1w>b4dN%+29SOoJGBY{geUA?rT%f_z!7^I;b`wTewE*4&`95sngVZM^ zz3@Rw{hj>Ghi`S_yq$;6*p5NzsdNn&gAdcOZU*8dC3<^x%pl)(M5LZvH}$T@4*0jn zB&PzX>Ok+s2aj=b1Y@92D#N}d{QR+uH8XL11;ZwkLNS1n=~$DR?z+7UkePhfKYB88Ul#ewbM(KcZ~KZ91V-XS3aqJ}qO3(5Wppq5Ys@6c(*)W8D* zg*CU+fS69?p4$rz1h@2b2nSY=!uwS(`|V*Zy~7Vp<+R~ZEXQ#`!VRqeNJ{>p+=v92 z=h(XuD4siOHq-R7pHoeC9jF^$>=N?SM@pX-F8~t#@zA%l&j8^6YHSNiey$Fn3x59; zNRoR`{ohvgaBTL0&g91j5 z4J4s64`@Vu`53x|PeS|Q#1>4)#*{1?mt)@{={23bo#d4Uu9d#a4m1m9_Ryy8*v~sO zmjxpSAQ7z-hUFA62T_%D&aDCvfSKNc1fR)RpZoRQZ`+~|T{ryrOh|el7rFt4P^IH- z9bi2LhjDmwREWg7rvt^PhbU0Ce0qy53g5h%9637Xe>n_QFV!ox5#F z0V!mU^uqO9ndEG~wWHy?YXe}?vI0nC3i~l6Pk#m6Cbe=t<`^ToK7e(C^GYmuApE&883wdZ+?!KcC zO3SB(83RT>9`nw(%om4$xZi0X0J@yaKp)V{)dAc}`viZDh5q5o%j0zG-lt%E2qAKw z&7n=vDuJF+h)iMe$39PoylqUhsYzx;OU^Ox)jt9L52h=Fi!FtG*W;aph`U}Zol?7ejbPoP=4$ zi-S*tL>B(-fE0bM;3g)x**oc=b{jm^Aw+Y2TI`_KPS{95RK>TT zXmAYt*$l-guv{kaGzZcMZuGnrz`$xM-@&ZNFCR?Dwt(x=I_R|;;}vKoJc4){eja#s z^0cH^i|Q@M{RfHhs!16|Ah$2i(&70(87sA%y^hh#W}A5fXrDcV`x>rc-njx5u?b$rh5OA#^7+ zWQ%eEi?3rm2~6XSQ9rjAd$rN#4E>!H)4~CHC7&VHFun)j!8_02-KZuH_(FAAHOGtx z!_uHBY~+cMmk7yXTi1Oz(jinC&TvhMpf^G@BP}2LI&=fmXzf<3>~wDrOcT=gh$zsY z4+fY<(O8U-@krbx3uI%zD$+Q1ZU1E?$T7T^Qe0c}+$yaHvc5!i?sNGcjN_kr8&=E- ze6TH)_AJIBlhX`&*S_gagx<>4<%)*y17m`U7jGkzg&NC}^L)n}uS%*o>r&u%<*R3A z9oRT}8%q9(SO42ZnvON;{hZK*c`zrV+U~CL>5pQb4wBqPtrknG9qkr;)A7F#_3xtT zP9(NW&F+Z9)KE3mORUp3qAn;WIfK4nxc>c>Uwwfr=nE(!`@??gbl_jGZL=0hv%_Ch z=qt70zTM+$Le~AIb2-<)1o;>6ge00+ zYLyFgjzOyTH#R{ZYC+0TTgq%|c^k>o8eAur#|AiEtGFoN!EX$y6jW<)OHV^6*c|MX3^9zr+&(L4T}ak&b4*d zxDlb*x`Z(PIwNvo+OYFHPd@8u=h(~*lm*fENBTQUA}(F8Jt_&>XGIs-km2zQOF`|Y zR8e1+8ePby!dR^fVHado?Luo;SOT|X3ACb3unCMJM zU9dQ}bQ}AYBY5+!$>uwYX*J@I+&!SnZF`}c0R@23h6KI^M9SP5nuNcpDb@`GCRBH~ zkWsKO)fI9kUNA1)0?%}@nr}0p+iXyS{aOq!bw_=L9}7$UNL>PhNN=x*HzXTMNuk9k z_(O1v=19()`Uxktx*j7u5?INj+}d2~kR+^1&2yl6nD;oXDb9!??~j}U!?x*HDz-6~ zp&bLrG#J_hnz$iEsy_!;E_?O;*;(JN>1MqLq<OPH${i_@L%||BZK=$Rd5T~l;+t4bB^)uc?Hgn^e9fC#_95T+P zQUBw=qj&5l)3EM8beqg=s;+*_rTdgvJ^Zh~ZBtn$QK0q6HZct_=^;@#d)b?!_Sejf zA?)!Jpq@ytKW7?X>|cmdvZ z8jLui+}Aw9j_5y+iw}W%^G;WDCnks{rIv9v{v67~_pS=xu2R?uy}t1&$T=^Bx(F`D z@2$-29Ifk}<7;MlEa(ZOWe)&*#bu4H8Ejg5^0?Svp7s?MfNC}xUnm5)AJ?S#PA{t^ ze0Vn{erh9)XpEfebFVH@6Z`OyvF`x9$nZI>9H=XwfiNNIl?{5|X;9~@>*srcVS3s% zcc9G%`Hx@ja%>p^c5nm8w4R!i%6Vy51+K%oux}K8kzyYaJiMTweAU}+6p%Ui#TJfO z%?^|#_j1Nfc^pXhW!{(A$*g#0R)BR5I;-|4v`|q3Pp|PXoG?6qBC4?O2iKwTNwj<( zKa4eWxIO$_FyO2Cm_|3&jk$Fx}hT|EUmJhbZJLA3t)L3fI zVv3#2#q-M@uuL#Df&;JSG9o(0R+~lAX<_p9y*ukxN4^Sq=IxNW^2gdFbo{EXmw||l z0ucB2B}ftDftM`eX(M{Rl^dj>w(%1Yl&q#rb3oYWn92LK>(0vA{(`UV@pVkF;C(ZH z$9#&!R-lle7k7F1^C~8={>}lDvgcrp6Kd!6gA1%xlRyR3u@JlvnAv9?XrI}cQ&I%g=*u6?Hbqd-cZ z?{t?Ix~UvS&xW118C{?r)(x|M3vA*2;$n$uCZ739wr8-Pe$S342^t$b%HTD2( z{TH`$ju`N;(4&I6^G}}ePi%0E;hrOSG{b6R63AkGDI;F6Aw|0Sn+E{qgwGyhhNP+} z?!lNEj{_s2pLc@9M{Oh#d4AZQBS1o<`LJaVsThG<(xwRGPM=LTD9UOp+zBZtYhM!W z=R>%fmeuaxv>U%6@>zcC34I!nO&<`?EF+%_n$v6bDI(yOa23k-qZlGxE?@wjC;^Z3-BUTY(iC~lAd#jXKsz5Z9vwd8 z(31wE529i$j+?x(3YIbd;>Ju{+tK1~E5$6kiHa!Q^KmBc_w(!x1 zSU92}<+n6j?U|DbE{C6>=XlOomkaAJ77q!5e|@&*@gMPA z_t5Kgt+F4|=9a;53N?@ zg&Fv>DzsEF=NiNuz4Cwq^drP2Ds%EX*f!p zwi=n1SSyw`M?$OM1JEAPwJ%4YkXQ9`QXnOieUpf_NEBQ@4$)#O*2Xl72UHnZHv>uo z8D}|#VO=19LdME@x3?NG0bu;cPEt3k zE_ecQu=&e^W$?D#^;#`)DV&*|Q$Qbqy1Z$FaalCPcWe~k0x=sDtZfC}QnVK_He;m) zF@^08CEJYKpTDJx?TwzFsy&Z~9D8(Qmh|ry>CY!k9Jm!PW+?bm)tUTk`uzsPBOI;I z%b5`AE?3HmIxYNSB1fV2wR&WEH~tdHTmg8{>f$T%KecMIC(+}rv=I-^HS9H%xeKs3 z?ulnTNwn+Dpht+`+@N#PrekxS^NhD67%#qoT!EqP_j1XQLzboAd|+A z_Y8b3PzdmQQKgm>Pj)fDd_zaARZW5R6E+{`lzxd}W+w!HO}M`f*X;vtF{VI82~lZFto=Ua5N@j*<{*;t@z#G`oMh6i$}1_b9(WGmCbIx%Dv11x zhabvbP2v|jI5dGIDWeZkAw_%a7In9>~ z<%(^l9Y5f|FNxRiq^@bNcK_6Zv!z~`%k28L$Z`X=0PWw+L5x#Q!gS_MOkW-DE8pZIg&hY zrhYpsMAE}2&W?q-(CLTL{a@5_KaU_FY{>_vFht`vMzCMh>c=e}DoBZl#dD_{~1UY-WX63c`UIIr? z7S9Q2uSW<$c8G*>+Bd)J7m5vV1J8>zn68GrpJLP)!E8-CiS0$<-;CJU63)ctL6X>>QaazQ=8{z3M)+>t|+i2gJ&~hjH?MX#wE4?*I+? z2B`D?=70D7eG6I6Fe075i&OADHMXJJDu^D({tTSw|Imf)<6R)du|y@S31H>)Be5(t z?1INo&z+^dp3wOXP(c0YnE(ZW=ZUY8k~?@;)oN<2P6hTN?qmmGfv>usval6`_Ul?% zVhFFgti9o}YHK!!a>Vwdk5YByCz={COV#+Rid9i@?ST}zRp=y3uGWlfK#6*luhlJp0!`;pKSm*v7lnAX|BX;`1r8MV*PX1YdJKmSWv5%p{D>6zj}N~^Ehr%31v$)RgErT zwXnXHvuo}M8^gX#frp1gc4GMUOh~)C*%n6LXevus z?%iD(X;of)Sb-7E>`#4i60&4QpvETM;2nl9GOq_?nm;zPo}gDT0(L?JimR*jCA!T; za0GJk^>Vb!%COrmBUJ<7?(-||7CpJ2Yg$XtYp^tY8On0~@r%A}H>wqt`>gOv?}<=~ zSj+o2M-FRLCzg@lv?BrsA9BrJFA%x+|BV*F2Ja8;zc?`meoPX?|uR$6KIA@jXJGN2^I z)7?i)B*OQbI3mwelk$Rig~hb5)pWkSX|Q$f?6HMx64xp!Z&dO@9h5H<_=7D9Tx{mf z)mRs(KIvao4Rr?!)m(bA5yS+^2 zV%oQQ@c=h(Ly`18b0!!?x+RwL*^a6xY{$nE_r0BYZw$c@KqNAl$st5IB%TbC0sD67 z48~H1#gMhk|32A1h#hS=j3?+9vlOoZT?@s>+NU2H4uEAj(Wqx&&K+l}0=yow?YQ*; zhMx4?#`Y&R&c4p-FpG#CSar63Uc-ezaavjWWmn#B`nqq$9nF;_L~xB@xsQ|r_(jpc zZrlxF;Lwmdc$8_kvo+S*zK2GpL z4d+|-a~=cTO;V-J%E;xmLfR&W-b`DAvX4*j_0tC%Qf-zk5ofydn)$Yg{yMg0!C$?F zSO`&b9(>bsXGP+P@WD00XRrw%k4>GWS-a~!h86DQG+DeTh|`ncu6*wJw7kA_=emd;N!uIPRbhY4+IDC`@mO5eSoI&ckAzoRb>=zhX%t=1C*50RzMgf$jV6*s{V$EEE?MNX~0{BH-!h1yMcnu2M`YI15 zfl9Tn2Yt7Gt}T+PirWlE`10GZx&10QqkVLbPJzvccU_ZA*vE*y3=pNNTStKLZ~ok) zj8M?S)F!RXb&=^*4$U>oLD5^?de1FAi@`L?e2K?DKEE_@E*TFlP%B_TJ)v4+$8+SB z07vdVrr;(Zkz!(EY0pByh)tep7v(Olr6sev8 zox#tg2~RodU&(g4^K$<)pwxLh1*hzoTSt-i z^@z934cu`qEZ(>gvERP?M&%Uv`7(3;b!-xWd?CW|^jm>lc1f#lmf#*bLuZo<+EA*+ zOl7~iLqS$_HIcOyMYWWGo&*xAQbo&hJLI*7VEto>kqayV-E{$jAX0AW32Ad3B=0`>r!Nu*P2_kOh%-e?4E^oC5d+4Bz*PcftiVqT-bMOToIM!3CxiGBG9$#iQVe~>V}&8h^& za!=I+Sw+GQ4VwINw}W~r94I~R>VjvzJi^DoSIWX!X50y2lut2a3g4e}B$2#mgs+0k z+}(q&YMe9aGq4r4NJ0g*CobO%8UC>@=E~TLSt7AASM$>VHDO=luy}@N>$hV4@-v{q z?D3u~QjTOnGA#ik3g7k0oVTm9SR_{2IF|@bA}oc~Jf@#BBy^^?1{~kldW?Bm4^wCt zxxZND!zsX}85Dz`JBhwq;R zw1GO%R%F`b_%1if-sNw+$dnt?0{TtjDO!HRIKH^G`GW{nH=Wk7E%3D*biCVs3TE3_ zZZLsoL^of$Z2xr_5t5OuAW+U|!@>#zhH0&Se4esu9tjP%>@EdrOx?9Pcia<^kZVWc zQVy`Xc)3#`E8xFnuUE-k`+RG9$c-yJ>G4X=^>1y4e_F4YdHiHZM%vwFh1=30HT zKW+aKf@eXBeP$m*KE`@dLT^@9vwt0qFug4rLc)Rf9n7^Y$j3g{i~G`~tMV5g-gr6Y zdZ0Q?j?g)$?8CReb2?(ozLpeuaES!kZGyWC;Jn*?W5CDdpQ3gUDOWcgBgjipld=J* z_BY?~z+hZSgI4y|i;+3kZHV>zuG^p|lkqGOMA3`Q7@(c%dsGKTkEb0}NACOYQtjLI ze0WA1$+a68f}E3Ou>;QxR9Rx5D`eP+!;8nhDpnhrST9c+m1);u-x@tK8V#V z6{~8hgsl%YJWjkTG15r-`*dPU*b}7)O)&zR$ITMTmAV*)tB*oFKQOoFHkq3tNlXm) znM1pb0HynN_VygPo7gO-m!U-b`asQ8UUgroCg(C=pVWwU$OTdS+omD2teVvTpE`WqN(} zA`U61ltTQXgE4Bz|6}j1qpI4v|6w_T96;gF2q*`G5D7(6goC7#1|cG)qEZqnA$34P zT2Vx4m5^3KxwbzC znR^$p$$P#woC!-XUG6D@P2Yd9^0c9^4qFJRI&f~`V0o=LiH)6#-; zTvDe=%%UXo)BY;9J+1>;gvA!$12OItEIbD^k`padA9peD*{LbWbj&W@`Av07RV=n8 zh#36S0@Rq`U{q%0 z^wmuIof3Zi+FfjVr%K}n9EpniHOUnQC3lI7M+LR7n3oL;Qa;3#sZS(4vy^6_nEt9G zU~LTTPUs@J-6x$;;xDqO7#_Sx*|a~+_cD@neYTQx^?Lnb8p}J4np%*Eo zlMtYI>(kcSJ`w3W#n7|YV>(Vp_HXWLSRzSLGkk-Jz%`3Nhl?0CQ{+iJiI$=4q|%hNvx zfa_qYA8{5fwQ$TN*gDS=1`!~91IF1f$uV{+5g?^Pl18G=ePupd7Z5~WP3*M~4VOZP zGd^|F^Jrh?c1oT|=+<$VR!dTRChPn0ql>0M+-+!IkS^Rdy9~IBClbA6F5btpg=K8U z@+SS9v(6-WYu9;8Vodz{zEt{CX!{yUysjYzot3sFH7mJ^GBNf^EzRy?#^@0KB#Y0| zQciPKy02ocRYcH8nji9|F#MUBp_I1Uq?wr6+*v&Ws@O7Z70wl?eby2uY&I%k5;Vcg zV!cJS#oMaZ9h!;C&pB7B_N7(^lLrBa2mAE|YP9PDvFHk|xN~WSP;vrZte42Ji1@Z= zhZCWSVw_3>0aQO()^0-SJcbzQEQgy`2S=SL%jNOCXusP_uSi^6wQT*2lkTfXn)~lQ zmY(@O|F(5X%;5Y8H2L}1Q|zG%$aNPzEAE?c(tdiib2dDhg0_!Mk@Ct(V+om16+_?6 zx(16!Y__74m+!rEcW!dpI`)-s<@C$~Epz=-_1=T4;Ub(cxV>W9XSe_IKkn|2ta-$f z5|y{|0iMKs`M}Fb*%veirxvzNB)0k?Cl7A1h=!2(C8;f7x367Gm_u8cQST24I%Gxp z>BhIVb5$wlnJq|MzVu!(rqQ*Zka-usJL^&!qtCn;6d)4b(J)I6aM63rt{LYhBb&Au z(PQ8UcZPf4&wpLml)>tpUJJptX0+%HtV5Ob_~}@dguR0XuE_Lb2rwqeIj;qy0!A`uQXMxslc` zv*zTmpkA<>%aG(>w8-UmG&TOCdpM!MGzl@@a7e$sWMUR*vKkv`T5UFeZ-7q%5~ROI~c}s#UnG8>9LCMMi|d zTbjwg5Z9>gM)KLar>jr11%mKwvhkJrpBJBA^(>{8!N%XK;!OD~myLpu$^On9BruLW z00EPeMcYrc%78ufn9jv@DOkt{J3EqA*Yw?=g>IngF)A;zPr9Hr(=?&48P21^mGh`d zoj3KB5Ry}a{L@{SbED7(i&t=(KyjyOG6P}pVclc5e>A*PeQ|pK1k89<<=`_;wCp+4 zl6N<@RFT|ybzpC(6myhl;2;946Zaco9(-c^Sio5Q(nJE~faJbFAyShe@zFG5ItSiF&i<%&m8aO2baSHw5AAQZ4$c?9_rBdZ-DU0f@jzMMp3Vv2R4LV3 zn!txf4&xprp1=N+lCbialN&8z<%(p?J~*TNp%o=Ae&0J6y5D5j@MV6|j)G&>gWbjP zY_&RDTbj?I==}54PT!Q=CkC83|6+DO;D%($1JlN|E)s0ywC-zPrVgaoA0LTW+Ri&& zWLC>1J&};H|6a+MUsAPS9xNBvf{2e2h~<)nu2X$4^{G^ebCc5f2r~W3 zuB>AwO^J``>Y)3p*)(IN<|U<;FKn%iP{X;O{OAZ@()O?Ejyqz_o&7|BOSL^ zmSbvJP&dwf~4hb?eC+UkRYr1-l83yr$fkt zbyq^JcoZchtBKxi4P1$@f*2XF!_i|l7PV^eO2W|--{P@cHoyx<4?ein&(%w%1np7@ zycp3t^iLKrJ1QmxO~ScA@qi|Ae|$FtWbUz^4#C>Iy}!Sp{x$$)4u6DW^-J%-(Mk78 zsJKzSG1PE^i{ehBph7C(K;xdpCB8x+C|cpCIw4ffcar^%5++gWdo@}wo8VM@Yi1_2 zX56l8D6yl}k$=xrR`-7CDKy>eJ*69qfEOe5s!V_Xbw64Ma-4Bm8Sxd2O~S0=-tQ!< z{l%axNm|e3hWAl&$_}Iy=pn7?_Mpp)qEjCL{e8`X#uaM=jd+^ABUMp_GAHNGzcg^8 z>o7j(pTOHfY7YH>ug!@KJ`eoZ;U_+Sb#!M%f=MlN!ddT^sRnU=l5n6|Wqv(f2h@~2 zK@$W`;f*=Y9D;FD`N1X1_F~2TJq+F^gY)@9`XzUKUd8p;2!w-Y2bfBZ#XWuBPA(h0{en1^_7yA7#R-p9oY92|Wq{dp1*N zdrlC^X&wm|y)ycN1zK6~mbCUqxO9P)tYlmT{Pz!MLFKxhz5Xucn(b@rv5qETC{i{9 ze6@N901(el?wpDd<VE11 z@Pqk3zOuL*7*TzmrxJ3kr_aWpJ;7BEX#V?@YOAj2nVaUo+~Wo4(EYT_KqVDUd7Ve7 z!(rwEcVXNZ6lPtPzU(#9MM3A}n#Er$ETv!!eFJOITK~AYQVZ2wgcF1+U^++Qb zhyZj9?!?W}R)HEqlRRKiV|aSv`EJy^5&Iugl#GV;YMbzxd4c|{E zX$ctXw7uhpU>3KS4XrCS3-L<}a;(R`sS^$_A{7Q?{+8L`zE2aKmyH1Y9Crll<%{o_ z?zGNcbv7w zx#%|*AYQ0#(J`M~1f4%?)SS$15(HqF_>0s-2H@`$1j;Tuzd5t`InUNg)V|=0+UTQLh*&%)SYV^d@E6TPc%1Wh&QV{}@ehlhZbPN>j#U z$b++)ltM$iJ;Tr%&M&Qkp{69JH>e1uslk=Nx(QLam;vccXpBlmK-OynK2m#nImtvi zBOP6v{@pYA0~&fhvw>`A9`}i2LvHFXP8cCbTO}#8X5L^b{lehgkcY6f2)e z^_8TOxe46YhA@b8<45OuWNUunKi)dq34Uq#9M%BL_DxUqCS z-nx3Q-AC~F3VSN6_pP0XWe5r@ze8qjr83n8*i6(Gwu+u^6kftXg|gebT@*$=6qA`-KH)8b{!yURU`YnH|M=>jUI8w`GWEPCalm zA8AgBfRJ@QWGZ8a%)5&4sB4gft{AfZ^y>0XQ;Y+br)%7fYOsCSuEgfYHR=my<`gEw&bMalzJRTNPOJJ zpn%eN+Sq8%uu|Ks|x^9^iv zc&J;RojF(Rok&;>06pj3Yf9|*u?xPMJ?mYseP3Advm{p+n~f*kSKuC4G^oJ}iAa8# zHNi&8p%q>cRzr#BinZ4p0b!(VwnEV>Cfzuq1{Wy06pI6KVA->I%?>4`X>nnQu7KD5pYV38d@ql->Qo&z*eN0W5lEIEd%M0f3ta`(%w1;2}YhEql@HEu?)!Gzv3`kB+3e z2K9qG7v4SExxDncpSUmdsI{59#N;+<#luc;G(V%O-2X`1z)nTiBa95P3WLFS` zP?U)cYZ8#XKq}Dal$-Jax#8xW!24YC0DDZIG}=vBe6IJ#&hZJfkbWVR(tN|h7J{Mr zbQ2LEFiT%HVFzYbNDQ4EIBz*~aZWu`W+xkqgADhTLp~JHpw72~bb3T1ku;(A{zEZ? zgXRF-EZ0)#C#r;kkZSIuO+TTO^L+`x2Qt*1z+$RjuszpbCTyS;H#6UbSHw)ZGRsv@ zd{7$kO4TO}M6*a^m~U`jPD}NE$xb>06+a3I)D03%cVf0`q>1a1Fi!XOr5YN)kHiOU zoA)35zDuH?-bx4Qp6%e&brtFdUSuS+s&zor1qpn@Q+EW%}+MIc4wS&bdLT7=#YXCn8f4}XN;neE2Cs;xF15b1O z=8N6K2JVVTVccOXvKts69#1=QwdSh}mFFc#ewiJqH~N}Er?c+TJSgz<{jc zb$suua!Y^S1k9xm_8$}A7Lw#c4TN+e2E+HQQSKoEh8Y3iE}wH3o_Zdrd^-Pm9Rl+3 z<$bpdq;RnjxnYq>af!XQ2u~Lz1-P-}@A|Q~+!(F`_d}KEFfg85X4GCLb%AOhZb;DG z^STJ7lF8jza-hf@=KqM)HeE;~Ehb5Fah zZcEM;gb9@l)~BA3()JZAx*wNlypvAO^9eMNy!rUT@FA!QsgOT&WCtsgbf_75PZH$A zpJ(B0jQqG6LfTf(1cpJWH}QunMatSzlZ~t-7N-J*=f6HXqyN5g0>4cluUT`qhHh#f z6T~UYygD5Kr>rCVZpugr*v`upH<=yE71Q5; z*(!eaX%qhtv4IrtDZYvW==5reOOY(MvxR4m2XlR9@C$woWe=Bj={Dv)l?a*K*JQxr zFm-Q;+rckeODR_25l{HFqF3=lPH+^_>adjI8`bAtl1<6fzq*!T)Tm7~4_k#p4rPmz_i3O8ImFirv=17bea&=_3&Hu*}^j}M}^vK6^>iTR(! zBlmrF&(8D*W61Gf0t77&pO5k%%F?#jeZ%Q_+oJJByX;cExxbWS_3Q`UN*h~#0jNtU z61{n*!uZUAsc#erO%?|eib0{_Ww}LY#wl`bpI>}wRMHS4q&|Cu?iUH;9)u_3)u&T> zk|(g@5F+$4@iCOnrheZ+Y-PIGPw|Ks_}My7AsdI)6ZJX$+Ovm5w@Wcp$FU?_ahQ@K zuZHw%^<_x=GS(pcGPM2rcxHh>GMdIJ?sgrf4A(|%94$|FoL19D&F#!=_av0P&~y9i z>^bat5}R|jzIYBC_k&nF=Pg^VA-2_a20pCm&K<|MqXm=>y@wLs3&Z=!9b?9cF5_pT zA;0tDJI;oTa^D>eFp+(-pfmHCI>l`mg`9^(C2F1yXAQ^wS+Yuxk3q3V8MK8CD<(M3 z(P$LIxO)I|7h$&PBQBv&=k)Zf0~_nXO^q{WgL8l9zE$AB-CxbV7l?8srsdd-+2g< zP>PhD#Y`7Mwz>z7uoLI=rERf6vQ9@Tt;M85Q#nY6-QwMD)?ZgOo`Cb^&3QPF`QN$E zON*-#zu7xq3`vjJb7s+pIq2Z7u>t{aYG&Yd`q2y3bfzjLRIo1_5)~CG0IE&W9AJW1)rf{zJx1i4Bxi z^!*N=W;KWPJ8oIUq|)l=-Wq-Kgz1o+{`@M4 zNUr<1?fJrTxzm7)J^I?f6YHWUO;x!-o9O_7T!O$zt5d+wAUz1x=22goW``}+%!(I2js#d;t zs8r&>fNKUuEf^JSGB^Tt)u%&Ov^fpZoJ=1!5Hcwb4czJQAj(dN|EMT$qqj zpvC2s`8~K!|1Q-Yc3$=*n@z&| zY4jq2k>(^b%W>ymI`STeGtZySYjDegEeD6pJt5CImmk(X`sRkq)q+8L6}25$A4>MI zpxM;=hvtA)Bzktr+Dk;%SL&GDEs&o>+@!c^?0f9 zflq`YJs0WXv1%39c7N&dwq~1@VwZfkwGdMnrQF6mFO?~L9cbaWvy_SkX^H!#>?2X+ z!{kB=lb%~y1_O8!^$vSt8LrJ=Q0V@$+t613#gUV*uYP#yV@t>ql`4{$Q8V$WI%1S@ z_=>$I7OAgHHQMnZhuh!rTa^E$^JBzdnw=;ZNJ$+%TAM*?Lm1`_!HIj@9Qg;Qi&;~C zY%%Tw=7id&P%;2fL+{SO4;4rk$i%tn;o=gu@ogs_6Y~wnR$HY0Cxtw)d4{GxrX!J7 z=u*0QW}9x=b0p}8PbC~@Q66gP5v~or>cInjO;_daE~{ScjnpD4LhfAahx%#x;)^%Xz6bq!yfIm4_7r_7b{7 z8jHr!?N$typ+rZxp&ZBq_@((W^NQj*6OR*Hr0Up$Sj`)qKU@RtdZlm;n1*7P#7{pi zhnmTG-g|XdtHC}prARBBWr9h%`Am%B2_g@@&()=X0B($P2$Raf&wqclWE|saoL>3N zPxK@qt!nxH5~*&4)-FND=)A2S-WDKpjQr*==gRYs!^*t{G`P&jt16!4xxhL1tZnM@ z(fmYLK2=!mpQ{k31l1Y!D)c1Yx@4?6>T6^ z^Ofgq`+&h7w1xOVAqDYIe!;F-`x$5eR{QcRq}&wGo!l{hkHmfpfx5tA;-rbXi<%)! zz$8)s=|=z0P-%40Z`xmcKF+uWhP0R*EqZGtuCEaI1B@oUNAk|UHq#PKeLvJMXxjR~ zj($AXuk=X+vrt=4#iD(s{}C*ski^KBreyO%#4&`>ntIh+!*fstyw}ejB8R{%s;g~G z`<(U$&pR26&yDdV8>Gd@k`2k7(b#aic;~Jrf362^dYY#+KBs9o{WwEj@6TvmZkzmb zUmv4#LWHH;e-NM3xI;vUv^4C+eH;y8_-UcbE{?~V+Pb<05Rbswc~0tZrNwT4gCc_! zge2lr;1H#$7yU|pRe0}#(xiRO1P(dE7@qK^(nyve)cJ=vL(IJp)Qj#?kDp$(BgDHz zZ;aE{R@H+YaS)ifDS@Q?3VPuU105G@LmM;!B)XG^p$UVEN{B><%aict_gLQEMzAN* za*r?6w2`4Ju-{y_5R{xKld$SnrUvRn)UCx+6+~jv= z75uZr%RosOomk(LeBt~N=qzzrpf=^^c~5)n^W6R?#;57hRbx}*y|Yy71dJLmn84R2 zpH3s7#qB!}?`!M__RPS0EGbMN4igFF>Wcwa(C>?heBM_eJq!rQ${+<-b)td2eirC7 z2@j4Ii*g4`Df)hw)b#%0CI~gP@6S3!)p%H70&$8rfgv>}F+7S{o(y$FQ_|ID2^zgp zaabjj8#Dk5*Igh%7giggFz6MqCEEW8n!7GNiKtD&o9Y^H6bz9A~wry?(*~ z8+fUcZ}-AZDnyd0guxnkoJln~+_MhT)5oGI=A_!Cs{I8$mPot#TlYvu1EBmQiF%v( z?2ZqdiGzSl78Ka_%=cN6BuAo_H2G0_!VJv8?CZe2jFdG$1p{;NRg{um2d-1LfR8Pn zd{n`d9~i@O=Y@xDnH?kzQ5SbsXb2PvSI$03;Fl1_&stJW5kfDV!r`VQ1qY6;qa=$= zPG2>GoAuAtryDU@>rNOjHqYu+l|q1k*9=U30{#8-d=<9LzrWZ@tnFGaZcW^36p&@Sm2nW6Sp zd*8noVm<{(E^60pJ5J7(2J;RGqAvjx`CO?C0y)P#1sV6;5-**5VbWLA} z>F6yJqa^aEER!mmnX;c-#OKX{duevw{62)rk3+i?$fPGpgs^C-P6k(Hi|`P2?&kc7 z(OP_PYzOLhh94;@|! zixE)ClM`6gDk{I#q+0vH(+{flOA6xn#Q>wf4JxE$gyi{SLJ?zVr|*%X9cb#tMNRZ! z;Nqpiy7%4|khuiejkoM)3icl%D#mDi1b79F5WyJ?ndG5eYoRtI;O2akz&`YNJ8u!O zCXhLG@5Xwt8!gZdh+Kd0;2IA2WF8QB|AO(Xs+WDLSj4Ks*sv*}C^0SP+aDA=-TLC~ zaRd2t02dwCEcsZX(l8}-r8vE^S$y54v7D8a7cO|M@@(1cn6B48alwR1Wu;Fm% zQT36F&}t>UvO2m$RKidImoZ%r9AcEVLqqe4Jz|xn_h0RZX*~7mv|jOFoKMo@kXI%u zu9ZH4J&dYq^nDD~Niqc!tAuGDMIe{P$z+&%29@)x&kwgi1n`Qgw@tRxhQBuT62Sqnu!9(4gXk|q;S#=Dl%U-Fsp7PKT z2vFA_`;`_7^x@!q`MgGYJ&YPjLjr{die~{4nC~8cI@$~I=JxV>&F7v0DzjFulg*TK zeP#am^>3`iUXLTh>1w1;$Ru{~z zDSfP}e`VWgxZu?eHrXH6{k76p5xmV(CQ3mbh47`TMR{1oq+r0WF1_Wf>$Io_q+jaZ zRsf9Ef2O2pL+V0(=HWfsJ1$*sR1fc=8duVTGFyZ9k&-#uL5>bCZb_9Wq^8K@Lk)f7`jO;aL|PH4V_~X%Y|e%lcV00|KudPb0->Ho?XeMMM z?u{toj17HSa|Vt%Iwa@Obm!5*b9;swUOaQ#h19K@Pr;t}^2>edEiYa+&mMyuRa#^Fl0>}BhA9yl0M;4bw(9(LH=8VgdzCY_~ruo(@(n9`tl*}y|+#yCO8a7WKzW2EU zhTmqx!mAd)2@Ry=*72(~jMs!(<@~hm{QSC;zny=jeQYE@0nv#o4|YrI9l<*!#J3*# z>Cz7oOj3kT_&TqvSnw9SB_S~9{Xl3kZH|res;Mxa{)P=|O(D+Arz572G$Zvr!r+r#0jfz#(I&>e-S{4VRrw(>4KD^Fym-NU`F;C%kabRQ@B3Io75*{VaA=bx2 zPN*U>&*k5a?|OJ);Q+pX2+6vRyU^!FP8{Rwc$V5a014*YF&;bdwIUxwpgeE%nTH5lgh#EP<`TgcOY@hrI2#B`3T>9bYUugd5juVBC`$ zRs_JplJgzkgHj=*Bv7D{G(O<_*>U-;ilb!~1iWA04$}R-TC*DXG5dj|P~5QNbCb%n z)^G*W^^veEZUWl7uV4N+*q0e>nxPnb#qRj3P+{PUxCs>L{T?Y3XKJdJ7xD3hUb+n< zu;SehQ|vE~IbGBqyB>K2u3|?aDLdiO^!gIzqoXt_1VeRB=hW1WJ(`tVy;n88XW^sT z!cy8*0R|}zJ3F)cc%%uzSc-kx8(icmiXRiSb2-iV$sfQc2>l?(e@?6(-*vF$$W``T z=-m&_UnEqg$pZGw60oV5k)F2W4`RhG5Aw2hKt`ejS=k%GebDNQG{s@mxRhOD?(H~) zsFG&47s~&79ZU&0m8EIn(}|{ITZR_3BWBCkw?*BZd2Bc?&X&Pr<{h%N_=TIS(|T|A z2fUG3PKgRxVQ&0QHMI+`ORAov0yKO)**c#KVKsKm0uMs)_m3gAD9m6dF6m* z)knic(Gh`jdp=UGi2AyuITtY!skdBwvdk2sFZbR?;)qGT)&@b;8-iteam9J!(E;-b zQeKlxhkRi2o#+N9m`te6TxzyLsNiLV299Sh4oi<`S?D6}{_*)b1(T53c4&@pEv~R% zBZN9WeqQfIV3Y;r%J_B@^^Bz)6YTr2s;=Z=p)74bL`D$WVaAu@-`F~wbTw*lJ!XFw zD(wF<*hmdL?T`CPgYC-n7fth6hI;VfYhr+i)E0aODTjR1fj&{x97$egd_1v+jRmz+ z`%i7P?F@&zUm_4hBhZz2IbB$FcazpwyDgCG2)sXW?OFvPTB)NUjk@}y*O z-55{8a4ogQ4058Q<6OkOMWiC;N@{A;%-zJR7pGoC4Gr$HvZ7!4)f2Yst5ZBW8gmEP zgREc|+f+=6(Bk`;r_<(6{@rMtnK||opSB&luOQKrHSqEJ;=c6-j@$yOgh28LA<7st z+ZZ38tlN##6C<7-A&O?^kRTq)jtr;%rFUCN%7$ZZsaOfEj;d=>ZEkE|&vam&!IHTM zsKhan7i41E-{x;lKG`@K>oXHzO#XZcM1HB?7;x;osvltbH3R4Bc=$wq>m?d&Ss z+GJLK?FSjZT&kT{`#rlYbbQIE!{_VF8CpKxhevtuCbhi#&-E%gYlUr`;d}9et2XfL z&lkF@+G0gd(s005V_|4GYache2+ z=v7r_loS8UxRCv@`lovo`&c~C#ddZ{=!NSSJ+v&-|MNJgqnH=N>u8-{6a-SCXRy(3lxUim)RUGfzLv2u%G zKWCRqqAvwcZyX@zt1|9bdssC4`gQBC`TKq02fQ}n2>qM=r{_=n9(5!RwgFyJVBh8& zUVs}OeYx#_ePv5{<$d&2yY~Ek4BsvSqPI5;OrLLhyZ2$vb~#5CRMxNi{e{gxWTRVn z0~DT51^!-B93FNE%GF4I^9^(1hSml<{&wPiza6}CFTAom&py$0G1e1>8xEGW%9CvT za^z8h=^NHT;p^9JxXZ@nv!qPb#XgcBWdHpk9z{g6k7!$Cz^3Vnw1yjwl`;PPQvCih z0qQLYyt20Z4bR`NTyz8Mw)(pn_ts?{?t-%hW%%vjvCZPX>6xoT?%ktTh~v5UQDuEi ziQohv-5$@nNkVXAaKnzf0-IN0(=@OC={_~Qa(2L1%klKPQ4OGBI4iYDLhv0#4fXld#{Xq0*57>}JG`j&2LSFWd24Nzonl0CWU%k3m_vAJneo5lTamMFj*v_rP^Nr`nK`J)im*7}b^T$i$S z0bUVC+#iJqLh?r;u8GATg}Cu}_)DXCq>)4|e&3R+0{aHLH`pDg?W1(DL3TYr zy&|5i5ViX}mmLCYl8r8#%&(K^Xe)7X`}<_eUvg5Gb7y!rgyeCNXlNtJWuUrkV~Pw6 z3OhQ;8*Cq$05Oo4#)gkMWWGG{_erG<`L30h(i0@6n!Cu|zCqXOk)qPd?PtllQ-pKIq z>%FA#;RCE*0WYgp#eet1H;fvI+z^^v<-&TpZ@%6YvOdJ@%~*JhEG1v3e@XJGO%L33 zkIiH8Br>_`Eo0BN`G%XOp?YS&^aq9wV(>rQ4y)?yyu*};@B?Pk^?K$6(^Fl&jF8|f z;z0HPJk=twIqv&=0sixcmvFV;_>EHu7*5UoscCF zJmn;Yuk#T`=Hh=H(x$m`#u1enPbx%{11aH zgBzCb5noBP|Nahs4$=#AvdQoi90{xm)zhonH^10lERyvHaNvsEGf^&A(VMOZu#KIa zxg~UB0PGOKqFW!R|F^`bjy2n9A?Mn>$kz0P$(x$!ee~)=oPTIU3j+X4K{CrO@G3WwY;bEo>kmD zC;hPT2AHy4U{w2IO%yzz9{R6C+H^Zyr0( z4OUO;{7N={<6AIj!}L2@msmuIF8U9g*f8vJ_p!yR({Qo+BSb4XHS6ywoBR;-BQ?0R6 zLv7k$O|AUp_~X0GZ=mKSWpv(nVLm>7DGmxz7_PkgZ~$LUXttzByHL5F($VB5raONj z>j}=7VA^77`Xz%`)N1}>Dr{>KJ@f7jF;1K)%7WmYa^2LO%?|E!uE=m@AwfG?SY#fe z>X{2h$xDf@3Gt$x-MYjPyOzT3$s0WG46l~p1UxS?@^D%RFV$bKG78&zg2&)S{3ZPC z;=?-fhi`uuwpfrq$fG+fxE|&Wq)zRM(0;RHwf66qY8Aym(TVd{N>DU!a7Ff=P616Y z7s>JQf=AJ!bFPsS%^`L59qG4p)zrpdF2eUNU;`dFyXuhJtv_ng68oauyH-&Wwma}ujs*n&P8FrL43#tzYLS&eQPwR!#ow7K zPpimjm(r~p;<)m1MJ^IynqNtNj|lmpcW-2PExWoMq)G6C5Sw#wCb_)=o&c2Zor}C44O5XxsiNf2{oaJLw49ZyX zUfP2EL$m()wUOel4dC*`8O$y}-H%d0`Od!xefL3rb#(Y$w3^*@x(7ox43R8Uw~XkJW2e+Qv}m7B@R^524o zMxv&z=|_l1VB`~RxeIen8c^iM>WE=b!-|i8+0v3u;e5AnwrWLiaA8{~=JguNy((fk zQnmTH7eg)1#SO167ETVuwXn0ArdhsXJv1MwiLW3lHjulf_m>qt4<#S3!^07|J_~Z) zF4u3xWg<;V3ELlTuts^Q~z*zZ77i_0E@ zX<2u-;IEP?|;1xEI-zkuai=NM?1l#-L9- zIH0oodKNU|R{xyRGXn!o-DeJc0^IFtgTtgUYdQUg4ZXh8pu9=`Zdl$)JlaZ;8MtRU zr%(P$U_7;cF|Achv975INvW>pVGdr^cHdAAjI8ZE4J4*t41WSygRN}esdP~MaPHit z<_p$4;Qz2)BJc;zv?Aa@V;ai7c#G#n{7`AT;;HcC|J%ZyH0DXyUMtq6;lkw0B{h?7 zOjxT1;J&!&Nq#v@vtg9TTE&9mQn^qEIbG23{Xc)av^lM&Mp0`fZd=OKp*q6Gv~@2o zQUVVolw9F~!`XdrM`Jlvu&Kc~`>sk>K98c`8E?Fe!!JE{#3*_x{;%X2T`?%pm5fu}agPm6kd96{-PNCe1UgxdkXpr#hJhu&@ zq6~kB5VQgfqAzT8994c^dq<64-E`<`*1z3!zM`B_hm|$f#PuGb;j(rGzN^WYn_}HB z2?#}I$uhs5b@MC*#5miD)?|I9g(b|PlIvQpRfL;#16Xgb_;OK=UzDYjSZ*w5d|boOv;R$;WuM&maCLlj zd5Z2AjYQN4W7_PJ`ZlcCeQFSD#boOZ^>-_p;Ufrj>`wZ8DEGoOgACnzS}2h_*b6kY zuV_6$>XV38jutcVlz%i3qYF1|*YsdO{=XbZ#N+lGmcZ|Ix$thq7Rc7?b}f!MIf)55 zJ^e>RVJtMN-?}OadM5Z!5+N4YtZA*P4JYzGc0`D^$2L^_t&IISCkQb=j~&$V;*;U{ z7?oZ&yjA}e&SAbEyBS8Q0sBxyUpQNCW43fU_r<$*LONkzJlCADvC|C@q&-X!ygc0fN1 z*6}JwVqXF{CVT)sGRk(v`t{!~Mr)E_o06VB!I zcNCJ(yt1JoKvB~JyrsQ&`DBE1^9nC1{*0a1gO(;3a|*RO10n2*b$rQuj)JfylGZQQ3xG9fMc8^0qfAP(JJgOu$eCaud7UJJ`A$wP6H=Zz1i$^L8%NBs4L0> zZst~CTJGn+HEc%JnPA(cI?wP1zHr~MiX=%?D*9RP)_lfn!x8xqIU?1MHJ@A6i@$6` zzHk8ah~4G}qh3!QtkR>S?wzffFS5KqS4;wK%veYyH#h9>tcLey8Qo?mGBTUx!-YOK z5DXNc-X8p`6+SVVc}NprfVBT`rc-F+JXV=S76|{%O!vLMEbC8#kyrbNGyQ@tWqy_I zL6&NK=|=bT1Ey8`1et_O`;ntXt?p*fnz~)v>OR0>u)9vD3Z{wSG}w^Jx!pn^3+QX8 zkOH)SroTuNZ?7>eq*MNz=QbNodfi6!85baQa^HSxA0_PBDnX7HA!H-|Wf+zXyWUFJ z0mq7F(a%SpTs|zXAURQE?|x z9T7Zv;g;**Lwq7~Sf&kS*Zy)PR+k??0mb)UJ{co0K`G>QuL&)jZr%Qj7kqv0e>l~7 z3flRrDm#qK#wlmq?%j?RCAP9*Um^ZUb^L&+!ms_iDqI!7;NgEID{;Qc*aPs!qO@#%zf`7J)EjbORSGhH|@B24a$n{7Eo+qq0 zJ=8z6LLTFGnRu?qk{;#1IuN~0)GfGSqpMT@Gd*2pMD)CKb*8Cl{*B%eDn2IUuIP+Y z+4#o%(^7h4j#ZC+$7bqg2ltjVDEV|22On5@&CqWpAWc~HeE=TJXz zV6x{P`a0hFw^B-)_s>kYjO%I^eOd@(AC+0bT)%lat;QV+`>w6sVPp1JY$iiGnU}gK zmaus<`C~hvGl%W$_eX`yNF*(>R-@mJJpsytytpA@8lPrbBZE3*TkP-{2ow7U8>Y z8B<$Rdk#NK^g0?A7V5mUIFQWt)z(|sEK+hp_K@(f8wYh*G!JdyAyEy&U6fKkC&kaW zq5yu|rtd=_${?ggfkYWjqeN3E$KKSD6CTBg$v^dNc{9@7+_bE6ktmveT_>Y&?0L@-f7JG=$GR`E;yHZ>&#AAn z1q}zSDp{{^r_Q=n98CdN~U^ai*Ol8WREjY$lh@+ZA+S08eG zF@;Q`je^)E_gFw4a3PvQ1NS=+{Tl0jvp7$VP7L@-qG+4*KCS4nnwmrR^770=_~*wz zZIHRhLFPhus=4+{l+&!G@L09R9if76>E^{Dj_l(m10oMP_m7EMa~j@k`<63j)$?Oi ztVi&yV`B6!VwV9P3GILw+~MK+Eb&%6RTVc8skY_Y{oTIT?Z13<0v^QXHcC;9*rTgd z^ldlll|JX6PwX_lx%dT0;o6hKfSL1Fdv$!B71m}6-v!;@t`71(P8_%obi{gUDus{3 zAp|XNB@(T%Vdh5SaN3$X)I*tML9%ImiVK~yh5&FRLFyDADsSjkCpT6m~c&11|>+=%m9Fe*Qc0l`X zv`(f3beSvBD4cJkty%2pK~*L5OQ_7}(T*+Am zx#IQT&`lmCIR*2}=jR84K!>}vr9s@8?1(hb4hgybBf+yUr^ULJPLDT(4q556m- z^`P!d6otdp^NGx89rd>Z12zutyXPyPt-Askd7R$);>?>95x7S;)}7B4S>Fc*LdxRO zqDUElGNEPI*p=mnU7rqZci^+h9JRmoZeK$^)Ac-y+|pdqRlm7K`vyP1z>k zsD|rp9K_t7yl2p$pB?v*Xj@pybGH_dS|lq@m}wh}!KOl6RfOMFmb}r4KvzS;akSYn zX=3E&aFZL$(zwTkV~#a-7FZkcMg`sZkESmzu{H%7MjB^&;gLx-wZ+q&i#M=Yw(=kFT`_WI#O7y)$0#LiTfR42nPY|h+e8=l z*KFOj`SF9a40}3a{WlG{;WN+n7oAx%3bz1Cza}alEKR)AvWO%f}*rbUH2f zgl!-1CaM*itd=Do1!BwY&z(y@N;^|4I_F}Y=3~bp|MzNQM0BQNwi`EYKMj=k28c9< zk3DRqotTdtm=361bK8)q<4Y~dbTJ+7aq8+9_>0DU1+m~OI|aj#U{eW7q;AF^4yq_x zL5FI;7h|r)X{OPcENtFO)n+;I7i~c+WDLy!XKt(KTZHUbzW9YWJ>ycR)zmjTZ{uPum5I6yS?@Zo-lCC(rr}~et zUy7`gvV`nwVUQ$yb_S!6eaT+7DP)bY?@LmMkag^1ZERy3GnO&@UhdEL`#kske188L z`@G(->s;rY>pDlg!u$Jo;4J8;kN3J&Xk;i$nodZ6k`T2fbj_5u42imO^drE@Z^hVH z!Wjh4NVt?|G#?|Z;oiyEGxz8l>c+q>-=U5ZX95g&R5v~6h;QEhb04PF+3%-3o@D(O z1d0I=h|N$F&^7mMscL(7P^K0G$}&0ou71M1o`|nb6^XMs?+3|xM-gAkMZgN-^TzJp zb8S&GfJQ%uOLNtzIoRrIHEh~S1o?P$tH=K(ILjnhX5Ak;m&Ha|d<9}$(fAjJMYn{> z?xn;dpZDKnL@nNw8+N>D!;B7N(R8QT28j1m@6jI+SI`&yz1Hkn&u8oqW;R+`nMhN1 zG2jfWU1N3qdN?zxeE9g@+%{7P%h6U@NzzHn%{S9o$hG_^@^b4NTmxxAt=F^}TUXL0 zC=KqA5x*rff7#7b${|OGSftPdnP|td^X2p8eu~o(USDkoO!-7=h+#KbvdC4&lRTOi8gCNA59Jvl9-$^P_whv+{}H@m)dKzHU4Vj zjhchpvUdI3K(=x@nf1|L8XUkP8+87Jr8Zf+8v_CuQ|77teZye0d&}0XpIB(0B1o+D zFe#b64HV7smGi3m3X^yS+0cLgjgr}l2)eRpzs|UM*ILbTZ>RU@?M60_jNEGVx|{`2 z;huE9MIrhxeTz73J^u}W9Ek&h;i1bXTyZ7c5n*dbd>^)MN4_iM-&a5xacNKfhC6J3 zJL8EYOSFpg%8JUYy=&)R*g3|m+pZ4#UCJ=NhMDFDeqUk=>4kT;>@z!{*h5wsrJi+bY^`DL$Eh;g68q3hrC8_d#$8Cc}q+ z0b@z${dl)FS5~rNxf;oFu*cYec8#t=-9Vgn|XkT?V{b5b|z(?`F(X5G_ zk9m*|bJxIZqH$;hTyFLE#hKb(-~E2C_vJyj*l`;|-SO0V@@x+$lVY?X} z2EO;Hjc|iz4N*Dk%|R1cCl`gAy%KS&x#q!AxM?yBIjwOOBH}3sEWM24sKQ*u%`IV7Paip7f0Czx(5zx6ScM=tG58; zJQjeQ0jsJ|brAocKUwdox&I9WhM)>=VPrS?Ch4X?qDRAb1;z3P=xWO9tEb)5 zR?(Z^vIjxw=_xYaWy_QG)nnec^mspRNa_#dCItlDD0inxiv2d?q!jPifHcymoW|YR zh&DgjB1~x{3rMtaUx>99ig%d#_O`f;QQ&EUiuSyA=MPaj0!Km6U)1b>ouIk@7Zv^M zzo=avea+a$mGFiK|LeoYpOJ9k#P9&uK;l&@@Y(EKZ=SKO2P&K$b~w1%_07D|Uhdn^ z*ROpiKKt9>eevu41=XLXjMObHBOr!vcu{%jIIBm-=!K3q!*5iCdi(7&u8v99PlSCV zHHNU&WK^o#z`JvVYu=w~vBRcj^}r}2^C4UEyJ26Qhi0uW_9Y3NEV!}CrZs�)wEBE>U`>LB;$a08W|lR5v<(CGs$9t{B|50Y7I9iDJdl z?n?m{lP@g%2S1t05bk+f2~nv+a7UY?na@$-uXUSYyR%{^iNx6tba{eDBLf|U$(C#p z!lYOq#|;5#RKTPxmG^kf@=~1QQo{U*)w!cD6LGsPaC$&v4+vc;i z44QH7{12`{>WYuNkevuOvv+g$J29qB$itCF2`+!?Z-o>%=D7^hr!u%woh8I>XSE5{ z(qCv_%iW8`tT(*lH$y&_*YqSzM?4rxEjHDjsK%Y)k|2Nk=tjLI1sg)KNxtYx`x?nC zrUx=|BSn7xu|q}d>TSIpomU=vT6O1$G_tUaOPBUE01=wOPFFtj(o~(w7ivCmiE9B# z8CeL@Dsvu+1RB}j>*i&XFyxIL(3OuIO;_(1OWfM8y-B+3( zb>>FrQb5uW-(;GkYoye-v|lI~R(}da1Fso>M>ii9aPpRh8Z;V>V4ll)fP`o3U&@(G zXGVh}Xk798l%9nUY6Y5RuveY^NAl-bwo47b*OCxALFpVuM+h~7E%sJ>jkGQ|X_650 zk^|#$s*CGGg1E8cWZ?vmrNn|`BwwIe^ebDsH|ZNpK7JPd&tq{P0ug4^QXF(lIro1a zl>dFPg9khnd)b=MK62Z!b9Pt>%F^KGz@tccxc2B1!j#$TrG9ZqADm%Qb zxJg4h%yOKd*%#BF%TV+|z?Ev>wRGv;`G<^(mzm$(WJOLRhQHil5UDZt##fwzX@^FZ zX@@ABN?MFzjIY2kIJnM~$NRp0QpH|ljBAXu(S#jtR9LMzK>DVdt!3wpV_NS+Y1Q;B zWu4y7MeJWkRngjnz;hJr6ZhBaiM*9R7>%#)Y`ekRzqQ-cW8u_E%B(K;^IVMWvG;C2 z_cPzFRFZ=r_lM?8%tXmE&#BGPq?~%v4sHD{$a86{L{F4}{08wz20Q((hnCW$kWASa z%C~V~zz!3-y?r0+{901b8(9BYn#{i2?9_V>-yGt;lKowobF2~`qHsZ@-7Hf&qQt0| zY1>F)2fA9l(vi$=6qMue6#p((;F)XTAN8)F?J9K_!QR@QKVitf`h7D9st~BlT271C*woalEhdXN#Dn0OpUDNSW#q#IWTPKTf=jC5{ zTl3BLUV78et%q*L zWN`49-9z6SX7ZDJ%!+7QzCDCKTX9!Q7<(+?jm}TzibX1JFIR>w8bjBYmjYRx8i~Wp z_-ZVPcev)o`J92X0bFAh3e>b?w9=D;^{Wg~-nZ+f6z91oO!kVOM3ovZ#M7L_9e(%X!tF{1s3qHo^%p`Ji^p zr^+p}&;$fRcEadd#ay<@=lQ9{Q3~vy!YE#(g=5Pw25yYbC1m>D|IYO(t3VZ5nXLGca!@-DFB08uF?S zwwJi?^4crc-7RNUElnED#@h6~V4?fytrr5-{syG&H{ ziK~8ZgbKr@tiw~J-P7t2Uq^qsq*WN2xCJjy7S_k^wDAc(8ijigrycY(fqbT)FKZc| z?8D004Az?t-Xms8eFpEI?A4B{njA}n`)XNFUzeubJe*I!uX4>6xtfu%4HE6;7jnOR zBtNWMT`5q@?2NuHbzkLiTw!^ze$Ta1kEB%;i zI+l+aDR*?byrl2zydFx< zFF}DaINIg4q)NH@qG^MF>Gj% zCYZP_x%WmAqTsRkyCtznF@kX!IF|<^+;6OW$!4{112-6p75DbInTA_E3^6OffU=PH$W&+!LuLX#T8p$yd0LOTbhp!eMXHe zB76ZdH}U9Y*1Z0yaTPBj(hEZ=!^e2`mIc+9T(ufkk&6J^zE=9E*G5j3kvlALP;<}77aqAKHowEm zX{hRb*3k|Gy&rtlmZR<3`7_i6Vy==3pTK9I?6Hd%2rv<`Afu(NoV|C>(9G{jq6*iO znD+NM7bmZ`g?_!u+BA)r(#ih$=&DI%fH|aS>AEeZAolX_(Px4jgN#qL&mF6BjBVh~{EbfPAr)!b4-+~|Lua|O4%>8|{JPlN`jze9V52;ndLRP5FjeaDeF10@8cB;0%$BzR(_4^)#Eofkhg z-6kyV1+r=~yJq!?Lo9Q;$nDkHk2i*g8{y<9W;|)kq zBex#KzX~w7zkGH;uqb4&WqXoza*{iqY=ylW4pZfaR4Be*n~(S7ZJAd_s~dVeH-^NM z_YwzrdcQy6A&D-(L%nE1hd9ghz>F%Hc2U7a;v>C!b}Ie7PbbNHTLe$z z-|L}o6sIYj6=YxLN8<`6h1Hth&#!m;O-N|!Q8<3#ajIk96Oc(?ipG}jCJHwMudlvq z&p>OZ8(M$lj-}yf9OQtK%;cU-cY$loiFbu9ObIRacmcbx`Pt-8CGLz!N{mH;3cC4%zUi4Rk&n(LKA}siX)HExdT#! z@)}8FU3m|`r-DY3sG8Bh{Xlk{C!nG5wu1bIw(OV7#mvCo$_HN9;68sy7_T_Gp{#Oj=HvBt+9pZ&5(_ff$F$-)_{8_O6qNtVFi3s z9&%oK@3~N4MXRG_Tck+myS<45{X&@tNzhA2RX|BMmDiq4I5hn2{S-H4n7jFZJInt8%zY4Z*&8?PYy-gOz0;)nEIOr@U_PGoxJU7-uSzJb z$nq^Lj&HMjvewl)Fl!*$VZ2IR>4#C1ulLk6I}L5{;fQ6--F>ahqwIZl5u^M~jRl!A zV{+erEA%r!*|kTI{RdyYh98)qk{@x>(sce{Jeb!pNr)=r5-sR{0FBMzGtT@mw#P}8 zo8HSvE$v;r?4QF|l)h6gVVwuMZf4?z<^q(Hobg9)D!KZ{XjkLMw;X&AW2OBFsuhph zY5jy|9~;lxV0Z#d!$R|M@f|rHQn-erQJ!lyio3O|L-|ch>AukWLo2VMbpf8M%a7L} zL7yf(`l|6EpTzK1zn2fH1_{jRyhO?nFu4Gw$=KU?nPuAFHmbWuJ6Ozm=CHM+euovW z^GAC5x1iGg4T-beZ`J9Ix#B8&w6>1Y9`N6`3V(#*%PdWZR~5F2Naosi;uXoALQ1a- zIy~JUV@hN6CG#j=3fTS-CK9@p5xQ&(0o^dhbB zFg6cUW%MNTjgwLNNc@|gO|q41d|#n^{eJrBxCAz%e$8HZB!7W)+uy4tUkzHc;(o6^ z|6u&5@k<{cB)uD4zAldAUGiQ&Vf7x_3(eSSEChWNhFIQ+rvUndE$<@=xvv6v3=bu^ zP;8chOQPoq#EoMWQ}s>Oz+Vt<2?yIAAug9vtbuC4v}Lqpn>qKv{5k>jeh0sV>IGvh z-KSg{K>l_ad0#$(A_k&*4eMX@W)w-Z?~E`OuLH5X$z~x~AaBaK{U|jiIBLQ+8C2%f z1R`Q`!ZJqoLcQVyzEUN~z8>pXx5SOkF19;vRr#K-#cRqfsp3p%IA}ol;AE6XrR|U^ z1;jjRXy4xPBa`lKbxQrxe8g`Veq#pF@$TmBuH@9NBmvz-zEs$<`&^Vn-PVE*J%6Ts z{W_6+nrFBa zrH<*BAL<_y+I%3=qon5uR=unC31&^bhO?<;5GQN^n7lhiV}7^Uf-{i&OST8Qn?GX= zvKUgKG#cy4DBrEH6-$LBzT=;ddNX^d`*5X8W%?rB4lf#fe==bvGfbP{cK~M&!6}$ z1qGhW@|>tD6(wN}roN&4ha}LhnGd@DP_*_M=CEm`Zh@K{9&|G|d2iR*Z_bJvV|KbR z&!q`jI60o}ZS_LT%?CQt=vUj9sL$Xv8)+$k$Bs>MVs>%@YBtC5`6~dkqocA9L9~02_ zReWwgE+oEm$lVT_n6|{89vJN4Ht-XB8g(RoS zE6o#yhG_9Nk+9%vFOD0`As~F^fFyHPBH%{6l@=22AYfsy)&a=5VA2inmhF72kPF z=*dw3TK`+&o}wg&=1lSMPDyMzV37=DwV4LCdZmb{exS4l9Z7iQFHyP@&Fw8=l{ zl?~8@j>TNS9M_5j#y2|G)>FNG|9UpgMDjI-#@>S|CbKMfBNM;kiO~n-Ji$Z;+22JYuq}ODr%*wstY2L9e0Zoj)27@=hvL4Zsu-B zNQ4Iqlc33B^4paYXGb3EMn0V2^`mkxyUb$Q_Z#Tv(!^)-JlR_WjzFec9iIV`hK?7Krt zbEY7b^NjBi>;T$8kLG8`jDQkrmykcel1-x%Oy3bl{Fe=SIW@mPGd5 z3Edd+F%Bv-v_~>71<*7^Ywpv<%G4zuY>g5-&W4A#$hmg8(MqWYnH*&2_)r|Q41-6w zd=n5%ZJY3Y8>`gTurB8{n%IM8^|6oLKR6giM?R==?4>*S12Ks?^`--tyYI@|Za+ig zb@pXzsC(exaAo0ME7Us8S?QgnADbi;cpH+q>x$WYH9Rc zOHGk`3rez$2;x>zo7(TXXFtwiw@DYJdGRF{t*e|r3Af1Yj`y`hO6HB5d}~`Y4rT^4 zVU-d5(mS&fz|vJlmZ!^(BE?(@-n4+cU2Yox@?Wo zPl|dh8W*2x0c9<Jo_x;- zXaE~(<__ZF9ZG*No*s9j@Ir!wYUdeD5rmIHT3x>tW zNk%DEKeJ}SgJ~&y?G@Jg)ywzLQ_*hiOeD!E^P5oXW*PW{$&mG?DTzkYp48q{$aGMc z!tKg|Q7WUbPF|>^bUJoV8C~oD{hKDe%s~M%m?FJCBJ)aCgTmIZC6smHLrf5)Qfgrr z@4(u9&55Nh3TfqIYDS*A-paa^%O%%m$<-`Clk~E11(v~<7ghC9KZpc(*s2#lth!lT zwSSfy|EQ8F&DkWcF8gBD*YY_>2idMrReJuuJYwmWr$fBUMNF)l_VH}3ZWssoSB-U* zL&0|=PGW9S`7}nk9DJ{tDL&99#wY+uraLlxaVW#hBzoQZokj9NXka?-U?Aph|Dyyi zY4rjEomsl=Jd+3VFufqn7h8@yBbh?bvfrc+bwk?5z&R-~I|4E7 z$tR9)^7RM6uLE@(ZD(`pvF73}#Tayg8}@VXC}{hIv&_!WUSI5Fbw8@PMnC&)tkUkH z&-|!a+4C@`vsD1T>7vb=rzHFeSgI#nBD6gLG#R9W9lYaJ+nNI8dM1cxwwxzMMAyIU zgL0&Qk>IRze6Rk!>llD^#&%4?jkV-Az$Iyy;5i${gSe8sm7+k8XhwDL90{v3Q?XJ2#$*cd%yFDP6JIJwI zH={A;Dg6PZtoHP!B_4?DINqhlL4IQm|CF5LzIBh>)2N#Lz&8vtGdT&=FE2%p6{=_Px0EG*REI>2BAMV12s$ z@i%>wzH?5$ScVPCfEmBl_ZnZ9wT$}gnse15*5hXk%?Mt_6FHE`bZxQn#5A&=+SSN-rY(QSB9K#0v+ck zjyGeKLZ)?t`XoT!Jm*pKK@O-(FfX{R40nrZ-aa1?BfWM{GnFE!ifA-jn2c&voP>E$ zEP9R!omSRTe76L4Ti_cbb(c^6V+jby_&R%gBy)UK%^6m&uP@6(6`S{$`Fee`lw-vE z#cc;W#7yfVwk*RD&DdA17c-s&&;&Fp)E&pITYKjVHUYDTQfjszL$?tYRQel+*EW0Y z9cvk>)r=jQr2%QBo5CL8(AexTYL%R@RLh+9y2pLM*`E8^)qiR=Z|(v7q3bMsmF2%X z(kJZZ=v+z9h-?e0OTK@xeLXX~auVwhe${^W{)VRhBj(`O3S;jjoHF7TuQBXp1E1At z&lo!Y1cgsEfB|dOoBJRRfCn1hIJlIH%1HEQaNryg_p6g0%VcUT!6-D`5HCQcok@)u>c$<~=KhzK zT7WdVWGyH2^kVHi|Ii9ZWgQuI3E?i7F(B##plo_%f71?-bB1cxXBcY)2%#QJTr_fo zpp0O=skHkAlaK+Ps^1t*`Ud0rVI|Y{8-42C=~9B*&28f!`l>`BsZtKrJEQc}=%)u? z>d0;W1x>lvi=^* zy5Rvo+2qo!vtzdbq?TVqW=J7}3a<-^*yshATfCycdOa&uR^vOI8Cr~}NwWjZMZU7H zn(x_LIh_yq5wcB|kG8tdPtL=BXp9ogTt($_N8K5N;t^|~`ab!|w;4_5D2+QhjBuJf zwa1P;65E)FH?`^CEFbmW^Q;ry^227ZEl%7cr5Q3KPi93jbK!Eun`_WaVx>nBLQPug zDevcMTJ@*O)7<)1Z2PlS0F2iE6yd*odxy>^^e;!C|9?8X$SnHZ%kkiQ+-H6ox%CFZ zgUxlIuDASBqrdKcG;%sra}soj1y0zepKKrO#;b~K$13t|e}9zUx`En75qhIDdF8Gt z(O);va;PTG$7_mvorYZXT$>o};D{}zRH+Hpet$F$NE)r)P{QNmL~$j_en+%GD7(@3 zt{$W5)djzoBY2P=?wUvdAmZ8&8OruR@tu|7BC-C29nN#|C8i+<_ZI-X_De+qix{&9 z7QmAxn_5Wp>$&nVx$~$;TGao#ptWvMNB+?JbSK>7fAsu+;EZ!=uNyP|$TVe2>}NE! zpV>I!%l?rrh-~t9@B;%_eUY_49Y{9_{@moq4z0qZ+pK+Zf9YJ}e%w)!^1LaJx@8?m zT(x7&+^$upT7WazAWJDqheh0;X5d19&drZxk#^>YGrQy~8|%q<%c^M}ELFB1QSGu$ zBZW-yi}?*L(p%_~HKw2V@D9(0BJsLA$I-OLsto=S7Fs-)fGR13^++t$23;9Niq zsK$LT=$d-_c$0t6Pi1DS-LnDJPG#w_g8V|w+tu(%m|Lm?OB!K|CIE|=febCM`EdXE zgmk#*A{%*(Zv)RORXb|+PQ&*1)gHRq4K?Iz2Pd2BQ1{8N{^E>cO1*WeWtIoH2=t-1 z9t|NOM{1YHV;`Qm74~Iy*RZZpfQIpnbDa#yZ_k3N(czdwxy8|W_(8_@eIH|^>4IcZ z$FHi%Dt|TDs7-(R_-ey}v?=pmlT$BUXX}TCUrt>sCvB2+CrCF->_U<|C3qc`K^U6(Bwsta~REkI&Xf zSFoh(AFt!$Z|H_oX7&EwVX3UkC|yR8>tkFQE;b#18Hg0M>b#r<0~&k|mL!`b9+79d zerE5c8X72)NZtO^JPvQqUD=ga6w+dbyVlr}sg4c;{>c9ex?0dA2;_*X@3+o#3H<8} z9#eko#nh|BJ2+E?_^MXYv-So-b`(fn!!PugAMQPN?!#(S}$OA8~Z+hf)NAO?{ zfnPqe_q736g^uZ9emwttsB7IV4e%<6>Wz&&<7Lr&)8JhD9DqF6BLZu+w{m=>uCg z8Snv%WuxY|te!(twh8%-#+!6>3Kuyw0z(KtGbC zk~*+Zx_;EyDyYN^F1^pLzhX#Y3)6|~pLy2YDFR?d2eg)lul;M1-<cze+ zWfn`5cP@cBdw?r4Awp@UA~{3Z?=2t34*!hV4cicT3CmSw;(oC4`ou}`)}I?MlTCj~ z+7#q^7HcXA&yLTL*XHbx;EOuz-`<{Y3|I5U1D@ek zqS%XHS2=pqJ*RB4^MP*Y3}fNZrV03*{xF30u6^vwUU=$_PxXdqIQ(Z#(#;bwIL>0M zySc(UKgmGdI!{@EY>4JhCFQIQZS1O}#3?}Oaiej2E`le>S(O|PFc1I_sW zzErGr-Jm0hiwf9!xYuXO4+HFGx%!Hm$3$QQdtbtfbulLk2@P;u%%L!cD#@uO}itqs+mrQ2S2H} zZ15gCFtP%N(@mNH#fCyyVea*T)*;7nTJk}`q4l-DucHDp%%fb4amJi*rcphf1iJKT z9P2eavq%+ao^5CGn7nE;Up+s<)OD`d&-nc&GjYrh&PaBz-`=@3ofRvudiV^BpAX)( zm>+sWkg^(irYqDk4{)gP@@-A*m^UipPXEv!Uz&g$tbB}*)s)U-?RKg%{!CJMItK#%MSCxJxWYl=-jKE^VdleXCm_T&U;dE$1YyI zJ;dXHtfvdiKpR*0=<@_jcRvE?ENcyg%kb%OUF)y3Gra3Ot3U+HM+%*q_S(euD-07x zg#)HbAW0JO6TZ(0p!g-lv2j#LK)!;RjNcm+?JT9ypOFM$h3k35wk`Q6*>PvmQ)1a! z1AODRXwyS*g4ZrXyoCC`<6YXKZ`jROpK7_nXK-iDdXAGkqX}%w( z8e|ZTxER88yKKv;TSv(WZ{tL{*x42x%Dcst*sAR?f&;Uc1EwSUVoTGgW!gj?7H5Qm zsh2q!!cZ~?->$BAIv>?4KudF5hZqlrt5b;o>jh8{xOYz140Q={?SjGvBe(y%3P4Ko zOj;;ijXS)&x#G#zaJ?hv!DZ_40Ee*qEJ3vye;Nj&MfOKD=_df%Q>wEQl9g~XMKspl zqvfMHBoGuktJH$32iBVJzH`t%7qBu^jp)%bHFIFww*48$WeXfC1wK1#1ptG!ycb0?{SxV3T_ci7KWao1Agss297yCIXLPZR0wb^Pxvij}UXaS`U ze;=&QhxegWD@d)3mzQV)x&|)I3(%dI4B0ypuAvs~LdTGgnoNG?k)DdJDU&URBXUsZj`fx>jzO2s&A| z2Y5~w8S^ec9xV5^e0A0AsS~>A(CNlzKre&a6bV*;hOIF^eWq%q@N>E8p6ivHH9tLG zxK%v<9_^7}jTRmDm%&;Mh{Ze6{o=I8UI}L(ajaILW7M{tl&Un5Irv^s#eOe-5mR;F zw9UNH0la6&MbG}&&7$P9U6qKdc{1k^RVQju?H-5#W%JN9LtH5qlfib6aGF%gMZa{Q zcf=ypZePo_0iODTrGeZ+FkJTgYJHF&5ML8$j_LscDx#`IEl@r77wt3s6KAmIZ@0 z!_psg(%o7l(Owm1PtDOu(m9P)|6(aE()#Lu9ka)8asu>(Prq5X__Is@taSf*`^SOA zW1V_y;cxVGzxeDtRBGcXAGE|FaC0XP{YsRl!~;L}OUzhu;o(DyB_Dv7Eg$SjA*MRR zK#>%?UBDmXt7lie4$LP4^{ACVUku8Qtoqq^TzR!6gkS{eP~5J>H3og9)dz>g!Cf?WAQCDvw2l| zd*$fH>Bu>%YF#h?y zR6XTV`S709I2aRNLI^Sn!B;0pljH0BiuY5xj@ve95T?NDu;UjIW5!nZq};mRKXNgU zPENSR zSnaqb^$V)YePNODDmlhPfBVyk%R@u^#Fg@A+a0kSQOJDYhi_Ye()3)t!Q7?t)l%lX zFlTJG!r2SNjWd>M=bilxps~9?QW}7e&FcRbTc8Dx~Ys-(-0Gu16wXuB5TdBoIxV_VtX5#teU#-I@qv{U!f1>GF>sF*V znk$Ahg-6TDNTsoX7?{jure<+3Qz19`l8U`K3`)n?zVvO&e4yds!n0@RfpHR@+>OM@ z`3&5kZ0;$qxg|pMk3#R)YT#3XCxI<**)|3xYf&5#voxnxpZ+wc00%((-L2fMbzywC zRFN#~kpyZQsd6dQ7g+!cbos?7@CF#~hpx7RWnErbC!n_yI$97g^^`k5AH{cHqHamG zId0KLVO3~1{Fu9|<;m+|^!hs-l06~pMk#fG6k>6xU8`H^OvGyl`k2Te)*fdH3N(t2#lt&A$R5Vi%n`*;l)|FoZ1%PqIKDWmb<|@Dq_;1^ds_i=aHF=*Wc!A29LaT}O%QPv}lntz@JMdM@l-NL zngWONSNFZr?mxtmfN2go5!f#n==7+@3BbRkH=s0Lv%8>5FXN_VmQ_4fX&V$i><64e zkq5J_$bji%zkdHP+E`j|eqPw`S|$4~M$_y(SBj_o=qDSFz%UHmxe>r(@xzp+6Jj0L zxyIlCRPp&IP%M>|U_c5iCS{lNbx@3hP3$+WoFGZ8cb_%EfEp`)e6rZ_KMk+>Ag6z^ zjI>AJhyTglnpiyQtepsVCjnq1SwW$b*?8T8Rh#$jxEXTQCi>oN=x-u*_iIq*^4SB- zRc`1XUH6`k4Q4xLuToi3|2zsx2jeMsx4K+WLVy$;BRc1r)_YhnjyxFOoNG^>RCC_| zoe;BSp&z%xW^Kv2&DkC{13KxRV^~T{i8jw>=AK@#A@XWTG}9<9e>bef-404m@C5 z82Yr4zu7XZjL%P?$q@J+Y}*2}WX5Nc&5E7IOWw3-W;jbX0;M$R8Mxvzi*IfvX`GmkXaaG!U1;JWSf{4DVxdEf6iEx%KdZeCIK&%do6K z`JcHhW@ht0U|*Wb`vXeKzdg;*8)NL;DMU35j0`4!tCW>P2DZJjI~N=dYn=bYGX~_dS3%{Nz5X^L;w3qv4`#-Ds5fEnsV0-hIu-iRR$6~O<7qjLjSH41@ z8T@X+st<8_!MLepa3I((;DZU41$Lr5G@caIC0PHfW95}Mz7n&VZG~G{ zFf@4A-txC%He6&^u>@2mL*T)HW3pMkTpnjf9em#G+${d!Qk za%ZTOR{F6@_S)G?+<9PTX+k-{07sydmBv|5SwP8Qmv|5_*rYwa z#I8B{lT+jN1MNAKB89ia?S_9P7RdxmbE~J+be?yy!1{IXoYRygCiI``Pvq6t0VJ-& zyUa(I;$E-0rbb&zh_ssj3rvchu!Ily)^%r`GL^F`*fy*|eMN@7p_7QsolTc4+ROp+9RsqUGc1T16s7=g?JRg8PIx;$P z0Z7#%Y!#yqo$PzMF8SeqJO(K8iSb6f(2VwPL}O5>yh1LNY7jP`WZkXy_3B&p-QHfN z{N?W`;GtE zt~XRrU&;c?Rv*U9R`}gE@ZQThnCjqwE<1Egi_J5=`7)4UznU8@0W(J%RECcMFME@F zsQIe_?CW`W=301%l&LW*n~!UM^~zxJ62o(ttWCDlAs~Q%gscqbTUAtpNf@0m9**|^&a=t0uUX@uWa+KNq@Wf&D0`LGOA!cX+J9Re@W zHTTuw;>x&3E%IG(nSsc$ThId{TQ8_H4Aht}+OqT#kj`+Uht|&c&$znfS7YD+h92FS z=)6w;uCXV7B3A(T`$Wd0MUQ&a97QS?~6RqrleVLbJ$n_Im|~wR?Y3qnaS4_V4lrL94ub z)NQshsI6b1C(`K!W~PXaccNWy(x2hd@JH8 z7!rU5KSk;Ac!`TdiW3l`Dn_Fx_@0fkLx%zV&#k!Lv&-+Z*QX58^Kk%*h3-(Hp@cpC z<`)G`jmjd^dIJYA;G)z7#!tr*xd89AtVakb25eBy_l%O%P?S5FOR7xHQ;sxZ*~+N0 z|C-uu4Lk~WMOuyi^(aW4uq@SIZhOY|-;aXY@uP5-^T*#p$NiqOp^HBc>l4>Zg1+Lc zKUpcso@my+Im%51=5|8H0Bdw1xIdXe`vEk(;c$P&7W`9hd;e5^dTi%sFnyRQFw!La zyyIQM-oT^+eOfgAj;rEV(gJ^^;bm=K>R_+kH+E^|{l8Q=8PYrL3Iuk4CU4w&+$dYW zj(g?`L@vW)+nnx~yDNS5CbK{Mq}P@|hy(Fv1YuOI5qy!jJZyjxM2wZI$HA!)(Rtd? zC5<}Eyx3-7ZE1oyW?iO^_-klOcc@ZVnFu80j4BnB>Cn-yG8yP!!-QN0>WF)NF>r{w=ldwl76~xQo!Vl@YY?2iYWB&r$Id)cb-|K6-1Zpa7yhM5W5#$w;~^H zue(|K?Jf_NIe)eA1Q1JxFdAT<+cPYXlD|MeZU5pRcHMifyi%-RUbl~}7ux?5R^XrQ z2Yu~n?@40V-07-*u~((JrE>X|@pnPkx#@OaU^JImiQR1FiwTWeV0IaMe(czWFI@R{ z*9WOJwRd_iBJTdwpWL4E`Bm3STD~Ed5IQ!vIP2Mm5R>rN0_hugFdwCZf!iIvdVBCO z8cT-`%NtnYuoi;&Hv>UA;bpFR>YwoMDXRB*zR6>-xRyZO;hPe3{4|W@tVK46hqT}N z>X{2yr^h9>9A9lrx1{3GV3Hx-W9;XxhtM-*2cSRugSjsy<7@}8Ua8u-d)<4(uG|C$ zB*aM3prOyn@B$=-Xo$7{whX3Dge(^}8o{z5KSB_&Vw3fyJJAYF6kwh6?P4n3k;J9V zl__S1=Z+~wyP+Xqf744M==Qx|7?(bKI|iKDQ2>4r!05q(Dw`5L`0a&Qtj-NE!M$4a zU(}svxLIc)KxmImJB+1(Y0dsCEtCsq7tEDR| z<0W(1qJinFe>a-v67P>Je#Kg;(5!9SJ6ubwEyUIo__}igbOgfup!{F zd#)D^nqHlY*Y9bigK=!tOy!Z-o7)XMC|{ScMTVtmWiA>~@7 z+(ZJ-S9ZWf#Gl&D>`$OLV7!Lp?6)hE%WhJ8(2NJ59?;+XY!^t=Tm@9TyG<(8?P|R+ z{V-vj%va%$jDng;V%)RhkYVqkONs1Wq=b4?JVVP=$ETAC3SW+iPlVIj+;X3Y1UJX1 z6f_igUkcv#YN(#O;ZU#eoWJj(A^-cNU+W`GpV^I;S1T}%g5y==FZkTMzq%%bKF6YV zg7$a5gbd0`m=*(6SH_Q*RUX><<2{^ z-e8dK*B`5znZ4}Z;rx!Ko3{6(4}^A1JD*FmBJ^~7bdAoW==|(+pY5%NOdLtd>nQsM z1H==6(>%b@<`&nl%5Vi3wbMd=s%={s&l^{&THW;?6y^%(<|=0s_np#UF`(xssa&?q zz1RcK)bDcL9vj#xq=WAn#!*V-{h~UGp<{9-1h~?aTY!o&wGdH-Q*cHMs0%9CxF$w6 z7FWU*)%T0Bb)1bfIGn}}>sP<`x}3@B#?1IQIhlp`tjlXGNBNw*?#*I8g;sKNA*M;# z+GK%#@lwUM*FctkT%~IdiKPJch;u#c)#MDn&t|SBquhc`3@~cRy<=m2=gYvg^Xn3V zH|&|fujgMNrF9C+Bt(Xi$xv@O?WCMgs!JbC2glqPBYZDZz2DKhNl}=;w?6W%7#nL* zu-TB1BOi07NeZ*Z6AuIYtYaT|$hR#3pJSx}Ji>e;K&PABd zqEp|G%n)L-jO>9iwUZ9Mevl}Mx%j35*jaGLb`}VI>?eV;%h3R7K5nx70LJE1WPPd- z3yFqtWU%~5n7On9Y|Sa&Bm!ws^T{3&vi(44{+KEz#ELfP`z%LR;^`w zbn$l7wYxgNUFY737^`-2npZpYlUumVHQNEiw?g0v$+zlCVzvVP;+{qAR#U_#gC+df z$2gu%+g#KTFg(@h!{To0HS-p!&xKa*gTY~kJQu(?*Jp#Gr=JaqO+IW_t`yg6I5bm8 zR`~VNa%-JzM=?O#6fm$+cIRT^VdwH#UgloBWMe4AGvs_M3y-~wQQYbgjaLt%&Pj&$13M2LScW^9vzbFw^U87)7_K6?uGh6u+tzRvdwo; zTR9)N#_IaPlDVu5;_-FnV}sfMf*{WCN_eaqxr4@qvt6(^{7VEd3%gfp8>v!T?>V2U zngGq?U2)JnzWwK1^PIZj}TH_@!j|nO$*51;kZdAW>!r*>z0U(Z4;V9OAzmpe2n8wYb5O1w2UE10{X~MFjZrF?9fp11yS*b=||n#*7d5 zF~v2Dk)j5)<@WgW&>D}UdpPL!@Crj|MW{?VS)P=>Gxh(m_m*K*tz8?a;8MV%R8YFX zLPRP(s|A zde(n{Qk3sepssApyCFgYR^mb4U`_n|X7e#){9x`O*0%jv*{x>>ri=G7^BE-=@aSEb zBx^V%vF}Uqe8c;)dC{kp4vohyZHV&F?webRq6lKi*Y-%4JVw`)B)eYavWrt9e>6vP zM(e|)CA-~x9jX4IBQ5e$)=$!)B|ueZeeN2l|kkyoMW zctec5bO>Zobs-?j&*qr#PRYs3`asM1v2*o+A>->oOd86XhPC_+cA;4j{4q zK5!lHlog%s5XQ=*$@^j7G>gQ6puC2)z?qnkX?{v{=)A! zSW+$UKT^xIrvT+DIkh5&tMEkn^Q z*WtB+0XIw|SdS8`a@KE{sa)`uE+f9|;T(fZKGHpzRUFH|?VFZcVFNzFA-KqHLtN9ls(% z-J%Z>+q*0ILQnQ>wz2_WDXyq_Nk&)X@gplb3j0p*zJ!s?@foGGX5E;A?uK(cvAbQ{ zt-)=Jf%=WC&!&253rYsLsmIxLZ-fu95MD?;e>DPQ0=kmfwa`8fWsnNKqv*eWWBKN2 zf^3Xjcoyxq%r)hfR8R^D3Q0n2cfJ;+uZP>K-*xuycq$lr+7vZ9@S0NR>Us3aicbNL za}~a1P@db#>04)ooFyr%ovH zuOFrwhw70V(76L?2;ys{#qivgZr?>DTn)!bVji`d>zK^eh{W8B&qQL_;^kNtP3;h9 zfXvq(x=t3b_mNjG+2Lh;d%Y2o&oN_+kKdTq0>|^NTlwB?qsV1fX@j%e(JSk=@~6`b zVrd_|y@=nIb%AdV8c)#fi89EY6s2U5gS<*v`$mP0f{J0OQFNQsX>WY@KAPS@w&;_t z=gpgqoZmArw0gU{3`I69P%|Rn4(S09{h;s46>2r|jv30i{ux}qCK3}z^;~NNdQ|bg ziqieAizS;b6&I;4@A!&3F&oax>jEzGO}##SkgT?0YNIz#XJO5K#iB{IEG(BxxXt)` z-|#2lL!$dmUvfXm3uRib@25*W^+jTPY!l^1cCSM%>InOrqd!)ka6Q@#XYs|11uL&^ z*8=4G=6Pd(rgoWglR8DMmL%*LOMU1l)obkYbOg!RaR~qfiFl$U;eb5@lZ7vLFBe|B z<#?8{cbw1V`6d^J`LM=!&;(najbY< zI&s+dr9N}fb^K?hW3@@6nWmv+$FQK_S*-10-xJ-YnCrqz&uX*RdzN$?!}Fr=j~o@7 zFH&oClTo1l9)M|Oc zskJP?e=OfJnTw{J$FrowUKT~`zW6MrhOgEFp&_w&>S5DwI?2_yHwMR^-ziKX&lPvw zCBG~Z%34N#%vei#40;h9hm+59b3DviT0R%G!lpXkB_~OQGEK29DW%+NA*(ZwB73bG z!r#ug0xb*9mL}Wi%(IV=upfp4TLOs#xWWGC?Q*K6$Ciw~nj9I*!C8gF9kM-TUh)K$ zDG=N!gFQ2km?3)H^!W|QI5y6sAafO<3_ zC9$L_ND+^p22{^PzY=yn zKJ?lJ@6-`hlRDYb4x?i}v;+^+*v*Mf)Htoo4*48@@!3-PmTcyOzTO!oerxDg`|kbq zs1x}3SZ(J36)a8f-o>1^7y%_aGSe@;^PZWeOeespkMg9~YWX(9FLgr8&D;$~7r{~U zvG0Z+I;yF6zhACPP*ZbNXg$VIGJlL!`yD7fZbhpFD89V*6=E~qR=3@~r^HGxB*{|~ zs~LSfl4sJyp`Sg*UMxKi^M-hE1{CSlt8uSbusa#;Odz>XVQ4--BD}(K?60*DI8bQw zQicY1D+h2XT%Y=R4@aMMeYBQ6SfcfEwux>aSSu%tb8WF$^Oh-n>{GsK{jmy0duqlr zkAn8SUxRZLUdL5M$0AQZ;Yn+mad_8HSL zO8X{-r3;>!Ao&5-bydHrsPhWYE2}r?F(ApDFFZ=+cGS8N%T& zBzE=zVZ*i*y#YvH1LVn~DB90PP&WCwo|Wxh{SBy(yH3THMBAcKjXTY*6rq8JW+)j@ zpN}dA(Qk0QcNF?-IXvBEunDdvjQt1|7^yHV9(I~QE>NBPKJrez@@&M=XrcGXE{YF* zMq1Tsbp+P;$KK|Jg^AK;^~W#)d}&09e@K6L(SRi1>^fU}{416Yi^2GjWcp_%^83o< z`7Q2e)l{E58o$0^Jj-UUZbj+FFVoIa4Ho)ds8H^60>*%)_qqI^zfgNz`LQ^Dl+z(H z-B=xHr!nE<{iTT(c#t}T?kf7B^Jm7Gr9vkMQm-OsP<9mSz@Opgu>rez*p%!;2=PW# zy>!EC?b4-ov*qdwKhe9)pl!PFc6!qA#DoSsmQq7mRlH zFT-kV53FcKx@@*%DE#W7oE@%b;u4*(NWGZbLme~;BckehA! zs`2)In`A2L2=~Q(HRI4ZN;B^R^p1M>k(EO9zoK;ud;bvxA_aa(-^SVXZUqrNx)u*!d{Z^2kk58w>MZD&4 zRWi*gTA><_Fx#*4lS>egEq5uJSKu65SF)b@%22pMD<7+Bxoq<~?9Ik}N0h_zL`#a* z%2=^{RJ2@W(D9|{8}DPGFV#$*`GdOkYs^F!4A;Y+Yb>x>+Nf8Nb2>nvn%MSacjlE6 z-A$onq{W1EP#pJQxPyDXbn3kZIW_A!St_=a$QF%!)=x`%j{DHK*-jLPcz?X;y|?Gk zWEz2Uf>Q+GGUr%}eAy%;B{ybi#~1JQti3&OCQB4&@`BRC-CS&$IF0sU8boJn)>qv+ z>DyRp16a8Oq9<|=mZ9VN!SK%xY13e7n7QAw9iiOF=Dipp@{q`otd8Nx5`c#!z4U>)?HSZtvkQO+zoN`^7e zW}j9)q~%zIrmF1j;553$-?$H2#@7cb!5-WSpN{Fv9hy`eqsIc%!Pu*mTSW!7e*07u*N75C z_0`-{Qxo^j;)1z+_IREuh_$Ns4)JRR>-xtsy~4 zsf~A$I`vki#>EIO0@wbcsEwOzPRQ8{*~;T}-{+HN7WAY1T4Er~7a3;USPj*P95#L3 zicD$eAX{a*x9|vdukYh24!WW@$7FxlKyTD4su0@bAg4g=uaRSOj);NJS&sc=XJyka z%o>8Ts@Rv6*i!#$I-mN1>5LfTKE730iBAB5=KiiABBUSX72mCQyU6+Bs%+~f!xEmV zX)ijOyEfHCJqHaK-)){$8n2hTFPk49t(@r%Vi%#CA#0r~9^@BYjl);hd$qWB*=v9X zukw}P`G)Gx3t#%9UDMTGOAXekjOAz=1L8j|3#syGI4~NG#2s@N?nJ>!EHS=?uXj?X z+&G3tNEg`bJB!FkjMsRzUt2-Ti-jeEc@e1sMIyQdx~u~wU^5UCsg4P_Q5G7F${sm! zLk1CHm^K)69O|)d=31Cwq-T8yDqZ>hX+ZM^_71az2r@H@Chp~DH2L1V;-fg2;Hi1C z)0-OHZV($pMjYDS#{zdn(1M1pIoMmObRm(UdGCmswKV%4rBy!#K!xB$yAnk9_eWLUdZWQ&d# za-2Jl4{uEXE#Le)3i-xUTkI)N${$a6Mr;fUY@VN+ggOgYhRcc-&I%0!%sQf0{PGQy z?xvEufikl_zGUUTt?RdRGZV6kNVeyZ_j((w{;~MqQ!4eWXS-clvzf! zc$QsoU@Hm^?z3OK=xaxO5Ki#H*`{3-jQSLb16bq7Q1X<|u4BT;xV777kN)t1h44Gq z?n(`)9!4wc%^?JK?ayU9kE|5kc*>AMx{*jkpytZvdwgO>mhmn@R`dX@k#Y|P|D7)r zo#YG6_hI;HeD_hq8rxZlAA7=X1(vJCI?r+KIU#Jx(>a>-AG9{2g`r~qSH|dBtU1UI zVwXwv7se?0d&bcB3-$eRK$7t$W{yDRP^%l7hJ9v=2{ZI^(w%-o!w6xXI)LnU4>H`u z*<{xxIz%ruGwa;pggr4t_9WlIvh`m29s%r(r%DBvHfn5taA?yc#!oqd`D%O8b>Cdr zA~moVY)S77%ZZ)p5ip87k^S>}iQB(#$S%8XI%r;Kw&Llx6_I<0a?kf)T3db6Oa+Y% zss9Nvm`Fhj(`n~!YCo5iaK*+Ks= zA^f>S*4m?*4OX{6wiWZtve$a?maKkq!fl*!$f)*D6nFrlT3-Fl_vVjP>=B1mJg+W$ zhqqHGpKn^0o2)PXU|A5Stb2^-=9X;N;3H~l)Su=20Z?1qNTQ~dpNn8oA*9H%v+Cz;%*S z0D2xs{_kbPd*l*h-;W)6>i%Dll2geOx9^+*wN>zsOiAb5Ny#5#*oz3OG510Q+KGVP zkjF6kbRzB*#0 z9bGneT!>OVSKvh^CVEAmj1Xen=(LF5{^X6HTKxgi6z0s(HTF%_>$}fRde%#dAC89$ zEgo`WhwCp%bwW@tZJ?Xt#piHWvX2)E{!Wn?Rp{Qije~!-Ui4C4@9UpU$h7PpuiLT) zd5Yf|c3?tdQs7)XQnXLDun>wGq6c{N1e+>XumUG1-u7X#VOP;9t5P9^O077j6cP(U z-KxEo6x^2Z3E_-x6CVE6y&C7YU?GN8c!o7#p^LnHueh;+Mi~jmk|?&d`t6E?cqmpy zH0wWvpUANGMu+O?U$uO)G!SV15+eZe^r=3)y7i_AeWe9A@{gek>9{tE8Gl(iq?wy4c4_dQ{vTRs zhh?+}zmv@O@X+Q*lvSwsdI9bsD2uDHz32dHKyV$0)MD_}yz=U2PTUWTA>Dp@_sJ4#DUtd1i(NQQP0IIJ9g`7&4eSeM4@=Tui(7`Z;8=nAA{~5?0o>q2B zdqE3}yHO&}AGnR51^uuGH#i(9GiV2FkpST~N8>?MZhv7wN`ckSkG7$NpbQ*2aPX!k z+uXsDkOHD*X9hwBsfup{rw)V1Tk^aBdi>q1F3xvfp>$iT`Fnm65Pnq(`%*7vqCF~Bbh-bXbKZ(sP6Y?LcVO<@?*);Utay9C5Bwr1Zl zj5Oz<`Ah(G!rqHOx?OfimnAkh%^K?5p%N&}Aa~>(Y~`QP-4kB_SNGwO3JiM`RG%Yw zY*Qf+FobX9AF%KA4&J!6V;vw=;1p_BVb1&jKR=hY3-bc_L5Hq9eYp7%o+%~|oQd{W zE@Pk(@jNvpeIJPleA;7&Pjk7^cru^B_2QQd+~h`z|IB1@zHW2Gw|^*bN*QHfGN1nw zlZh9&5GaG^oBD9*TlcbsQ$5_;VZLHq7|JkBQi| zlC%UPv$!&8P1+=>P?cuCc-HAM@Wc~Ib?8A5eZgVx{OU^CMQSR|{Ui_z-FC2lSMn}a z_CimL7}R6^_gOv>8QE3=F7}VtH&`xWd#>ET2mAF?2(CN_jhcA)UCCm@MI2_rI7S0UxNcYH_N~72CTC%Z4@crX zfAqS45-;$*sK4!bl5LJVMUc25@b)l+U?W;@O3qDnb_|vFS9K-?V4e)~sMwD;3BqpG zwROCfuCId3X1P7ZO7s-4$CW1qFi6tZ9e+LpPTT8i+;}3$j|6P~=w?iF$-f#`097mb zCYiqE&^9&BF?3EzvHAJXx}%*ed5=JRzv$A}@d$$QQ(@dBm6-|D&E z`w>DPjp)>4L#}8WxlnEMo0deux@|y)ly~AbWjD9^%@stcL|@h*`m0j;f+&?^j32km zrXF@JJUqeD${lIu1>v*fZ{Q?Dl)JzKDjLwmIjH(Lr6?rl1{wd;mhof3`F^6bx@FoQ zO1|3D{T)LxHo6`-cv2R#Dv&9Yxm}iOD{zD;Dr zTNZ)IAPYUl^@FRq?Oe$zB7N7a`C!yztuNE{T5me>S}3UYi!)GX!~*i-VU9E;$U{-U zwT<L1YFt z*>){J4x(yMB&dB)ciA&spG4uBZ3YIASe`xw`uD8Xk)bD4N6!WN#x zFZ0=$N^fU4LU0r+`WzcE3eZlpZ0?ibUPKOdd7Sz|!(FIhC^PAS3~z}fW>+6z>wAtx z7rj1WUHOKUcZHUKLf@jELC<1-1VzjsifNZaAULVDFSHW_cNbP%lzTR&l$vEy~;6^Gq0Uh%vT*#9ue__e+1#dk5*^ zPoG^BXM=b-cT!@D_9!ZV%-D3_wx9KPH`rE%=(j~aRfMofg<_%TPYtwvD?CVm|@Cwp=z#gefx<56}`p3H1S*=narOPWYa zS3i`NZ)mAbseULgA2J!55L5l~y+O=fZY%<1!1T_E$v+39{_&5q3K&FZapfx3e+^JY zt_zPUv$%N}eQNc8yy;hVxL3Nz%}Z$a`g#eo{=3TgfGnYZvM#~!?|YOBT8C&Nt?PJkfmdpWRIyx!arFF-qunyM{3`(^U#hdt^fI6c*I<=G_T;?Ko~9l>+42W+6C9@-=RBjXB&AHh7MuKy(Z96Hrn;AYv@ zj&ojUum7LkS`Z5-<8h|LUg7I#SB9U3J$Q2L#6h~9um2y{CS!%{f$f1g^!IFLR_AN8 zF=qQ`;?5WctR~Jg%Z<*t!g#O+n4!XGZ;$>wv{(7@6>%`!4Qt@G!H((6a2*~{?IXs2 zd@*z?+$S`|Fm8D#i!RnGwD6Xf9NwQq6AkoV{^2Wb72u5!exYXcQN|&Ra5vZ25t4uS z$)Dcu2SaAvfV-)1CuUtjBgyF_Ani;EMgNd!?~cNYraBFvuOXZTq`fqF6#WtC*PuOp z>#KsZ*cp$_iSdqHK>P9yD55iM&qmJvqfM}T4tp^3sVU|q8oNI|3AwP=r0);VclkeU z!V_deyPPB((C8Ds8x!Mf7byEZua`z!1hEuQt*iFN(SP)w z7?>tt43z!Lg3#$pDGxBf|Knw}NBn1{bd#zRvtRDr2_LjK%2ELx*&?E_@tO4#p-}%d{1r|3+cUmsAZ_%Fo^N0V! zj(=gt|G+Z;!j6Ao$KSHYzp&$9*zxyf@L$;RFYMTfPSEhjzp&$9*zvb^1%>_p7wiyh z*ss;#pt>-7R-JNh$zx)?-5Qi0cJX0&LzI73bnfng^F-4$-}j}W#}e!`aG+B7Ud{)< zogz?7_e=%XB7|OWs*~!+?bS21$v#v4gyZOc9J3o`?qW5t{4Gp_-HWXtJrLfw)7`ft zz(!UsZbi6TL-2qL1`FlhWEL5FrsrqS7qSTw3S{1U`MQMN@eX}D4Z-?}7&`$qG2GdT9kC=Ds zBfD?=XJ@5d&J_BJ5}`T1Km8bWT9mhdg4e~}wZD;MA4Dfq3NC!t+PUrn4uZ+#r>yrL z-nI29wXxC2JUi*bls^P@7Te*eKEJg8PD)q?T`6W|Cu6` z@{~&sCgbGnzdu(Ih#l+Fu=Bo*&cEIF-vw{&=f4#GAz{z{<>8-{`2S4kJlFMKZr1|* z)O7!9jGv_VSH*1^qyLvIA$Sk9J|nQfx)e(WZ4l$$i@vwUbS8Zus*wkMqvvu5$|v{f zWpp{Y&eguZ?woGV{$d^~yXe+j#FC&(o5A(55Lpk$&Z89>hkrA<+jcJ#OlH-yB*shc}jXV-NUO!L^4^Vg&;_f&C@#A*d=Ml`&; z`nm|lP1LkI`DU==6pm3?;S^HErqB}up*ohm!l`B%rc^sKGUFsu^*Py z?j~kA1*`6u7SC_%{JZxxyqMy3gS;IMGoQWv*>}>zz=}o!CL1(fWN%b=&z<_62VV|~r;q2%ROOwEA;><_QtCxP0Zq%;PR%h!<~?@oT;})4;c2WEkr;Q! z3C!J4HSc?IIeIACy4l3J6FTT;R&!ZEo$<&MlTi=<_ORU{H2%sD%JYmzVa)N(MjIWH z(6v0`VXfk+ok(Rz;vn2lu!Fg|W2x_9+?w9+8CdQ83eweSlkPiN&YPLz}Nh5ij&Y_@|=U{3A;l5ZxCng@v7bDkDs( zh?{oi{*`hM?9t4DQ0pERQk+8Q+@V3tsx6`R((P2T=;DyHZSw**{ayp;|K@SNl3)1n zGd$jl1$aesKg5)uCVW2#HshC^kQ|ja&KbR-O-|G%U@aV_uQfOl3p5 zb?v*WT}fr+B=7FFQ$)b-Q(-#cIjzjF%pNtd!6C3$;<*eRPKJ5>OO0b4JI_gm&A!;V zH$NAMauTOpy1im}B$^Z*X@Bj5{E7;HLDtUfquufCB_=SO)hu;CTSjU;>rrM%i%Li; zJ#O9iQ7bhjJ}dg0qnGulX8C+Eu0W3J_Z*G`m<0CDPK{5i%f8;c;r^NqmHsHWUe$7} zSNQ~0MyW)xHu|G~io1*mtj#iHEoU2nZ?j{?(ZtZu`(4L&O8#fsXR%mHLELrC-+Dp} zm@_)<6QQ$<6U>GXIF(v^?biCz0IqQrmyUvA;hy4sCu8xTQBw9~rGX7=D>R3ZfH!?_v#Gl5oLEPYQ)zg3gzSRLJ#i=>uJcazQ_ygo><==KYtQTT7WZB#^&n|jP@R~nTwfhg+qgNj0gok- zyLtD`(=}iq6{BV?AIYK%SY(ICVXUgQ8*bbgTh6ldEFWPpY|oyfKAHKmZ+G_~oPYx5`?E7)8#xne+M&EK>-rXq$9#dx8-8$)&&&0@7vH=>v21GA zs+_xl$v~hawx`%QOH!7f=A#wZu%l3%oHiVNkKfDGDW0Fd)YPgZvOU01c}>+y^<+6K zxiM^%oVQj=S*_(7uy5jJ0oHrin#Bb@PdUbgEqVN~>% zIt!I~o?>;o=_KJXO-m0cyZ=R|3W zS$Zinz2zDbmLj-bxzH2B&=c|y%YqjM65e|4!5*zBmCKFTv_Ml@eOc(_@}-}5ro!jL zLKV-1MAoqhcBQs)vw?bTimCYADXG-DKDKGzc8pm+CH-TG&2s)7(Nl5bjp{(05RD$P zt0YDhNSbQp`1+cV z(0*pwcB#*wV>Jw?WIfER+x10!nHkdTlb~8PEGH~!9L~Gs&<8noHl63PxgAI{baJQO z`^B;!u2QbJt+UI;o!Ch~JW3e_Fg8VpLY#Jnfz(Aol^Z@fA;S_1l4vBhqKWzaL`*CJ zf`OdP%33<0e7vh($>3mvs^xu7FhasPG`c8bWvCL?r6JWZxTr=IDx< ztVXdtpul2kSz+w^iR`f1ecz?L%p50@#308g;N0yioFlO*MbHPG z$dhlrF%ep;Gnia{Z6@;7VlEBD!_y$O4cWf7H!+%w{9fgK&SZ}iGGO#eQP{@nfMFS# zsUs+f4-a(umj=QFngl!tV6?SDo1;xN(wV(CpxlSSc~s{_JCoV_H-6ErES$_#ob}J| z4}iUu&*YhhrnLC+nf-y2K^?2~%FvFhi>G5rO2Hs^Zh0)f`{_w1=u(!ew&JwBM64$? zdD~y5eqt4`nuubhv8)K1N?*^+9tGX1#Fel*C?c>AY|s7typoHn(2p`oO)Z+EWadI@ z6AUjR_5)q{IZdGhj-3!oaSug)ZY*UFu^4{;Vq=lga{TG-5+2qD%ZD05hG`o$C+V-3 zt-DhQR-kk0A0nev=OaLwXult9~pYAZASzKw38{C6em&qc_O zb(?=^=H~Y*tF<`bi%04;!bef|Nasu5+I-7OyVpwHivIgLC#j~;v6g4r#}EBIxJk}8 zOh}1I|HXovPKKQ+xB^cwcQWZ`CNR!CbolR|Kgt2~LlvZObi!f<*sG3jRoZs>y4tjg zLD6?;4|;PZ02)^_usn73W9dp$<+EKZrZ`a^l-pMp#-ca|El%SVr6nH6wA;ebl9)_` zTn-Jgld*|H*W@Iesw{IBawjC`SDG90{L+=$?o(_mmie61h-jCUSCO3wFk|={aQ0?f z!=39RHN(>_Ywmk2R*J`OOu{cIn49NeZ%|z0r#io|1 z=&-(Ex*@im8}(}|KPXeK>|gMce}{>#O}_3yfZFpoV|Dk8ggc?l<_3W(Fx0jmhrT)PrH=+z83M4^7Jx29Y1%6 zzKbOx7D&qdp0&Me4n$U`J-*9XVD(nAK@Opw#I)Wl{={nFTqd|MSiGw+^l03)Rg$Bv zb|M3Gch%JW^HiMeOdLT0S-`{%l7bUYf><;!2LP_o$cFaG3wdo5IyphQbBnnE)8cbH zO*7;DC)<_2GTSbF>0MNi%ONqP@iI#vAI{SJrkyLo8s=3(+p9*=H_ z%v-1u*jVjtY)oiuzv*QrKRujRHZZk1H~U?>fjiQ`(ttp3VhUjKdmg!v0KDLa4Org? zeF78Sbe)aY4yq1jMAH^tO8S{^!c2M7d--Tl)pA2~am!65hl{EHj7$X8)d8AJWAPV} z|8~LSxevr!a5#>zF()c&pf)r#RLRo9Vtis~$o%ba#PFzTVgn!F0pi1Kd%JabY)TD= zhK9J3qM~$C>OboVz3u=vluyG#Ltj;PjoW-3^PB{V9< z9|KC|^WjF|dh435?CKL{D=IF2`U~|I=Y1vvrz8jI`r2p*?hKY%RGRYTkdB z@#=?$GeN<}CrXd|xX+MJRn^pK;)O9M7GMH`RQ=SF+mW{aOa^7ng!RP!n7Fi?E~Ye| zuAy_|_9`j`a6v#V*@V>!Sea}K|6X(0Ke+j8X?8Ia@Z!XWDF#1UjKulR>cAMLcyrOT z_(9c?L+MRI$s71Wyz>BCtHHvT&K4rHdORdcya* zR5_o7(4?N9YD{!kG53-Tv7H5`E!S&?#j+o%9!SZ&BicRJPtd+2Xc2CPX`NqSJK+EA zl&l-tjtj%1Vys(5^T>Q!TS2bnnd2?}z<$yK- z6|lev6!NY}AE_&c?!$hOBl`uD3%`_{Z^wUh){CRVDn;$Vy*Qrh19YeXI&F@dwy(QB1_CzGus~ew!JF2o;nv%j0DP9|EQTFg zdCgkicECKUO7la^{yoEV8)niE0+4Ls=6>L5hVPFO%=(p{3$Mj2XPy#2{b~kXn!=3$ zA(h6BZpE&KaZa^=|86V<=MzS_h-7r~4RZakPwxFpxI1BPcGfB(DvBYLh8O!`px}cu zfg$^9m#X!F$0En3vKK@ImTMB(R>81Iehvd4pa{mv^SqnZwC}wpe)@&4ah+$~pPcf+fH~1!Il(*S=)8XF?w504PF+tSOKr~pFAq$ktuEa#xC0B|G~N8zuU}pI>4?1Y^K7+N z1xLqD7)_R_y%N*mvKGsq|8W4?a+=PaVGGllU{{Ti!YNF_0X@QQUK2Wg^w}U?jrh-; zBr)UOEKBxC(_bY1%iW_xtw_KDFZZZ>J7rE&-lRB*c)mV9io~Vthn$w|?-vYtJdx6Ps3En^<_TKkq=ZE0^Z&&iv z1XjCnox@gp8D3N?K^?Si2QfKCl zT_50)q;zeFux2!Xp!Hdc*}+KM+_3B;atc%>kqK(6-9%jo><-VKf01BC$HYNj*>2Y3 z;jo?#j7ZyOwfsG->b^KDj#u3tl?UZ?VtjD+cAqrw)J0@-D8L~pPh#mZ48NESQyD3_ zv_nkl-z(a%8hprFedJ|8gHs5z(iJt1YjU+;wMaBFEx{L|?W?__T}_WFGotuRV?z}B z;4@R#ezirR%_xawJIwOFRpgim6YQM>P)chCHJ6Aan~7Jrui+FnZ777xB@YU+L$?Eo z28%mWSB*hysYKr$AWiJ-DF35xF|#S zPgmi?Rr!_!q}_T~)FbzJ6QAyOo(27ayPrA7@SE4@z#00o`1E#*E`kafz5RW5((-_hUXhhngHaW#tsq3@1gD(?ugxkj zpvU41zCu99S^pghkru|N0uL^tE6&W;L*kNcu7>k{4G@q0dK!~CXHqEO{M~Dh^4eCG zogRd8&t(;(EP9frQ{IK;f-lZH3OeT&C|Rjxp9Ma$^tg=fr-+r@XOJ^>x$=zd>}!hq z?_zJ7)HdfeX$SSybNM=U!jzLlwR8OtPxMuij`L{B4k|-cTX-RHQrBvAf@dQyT2@qJ zz8EYlvU}rM!O#Wzx2YQMUXG<`R}Q}!TX`vot>1s98mx=gGMx{{_dK%-Q94u^Po-Qs zS367g%QE^PJ#XI>un4_JX{gMSO2mW=^#j}&ONXmVfG72qBe>dtCl{Y%)8p@`9;w33 zGCvb(utQTbK3nYyci*)vu_NLIycq~*YxFTIH&LpLg=FCy?qE9W{l=YS9ji=h0!j~$bi(6-dgb7nTM3B2AE5DBA`i3 zZsrTCZo)9)$;F&=Sj}=LhaLb90}!Du-n?9}8@IQ)#G}cv4W^A zXwO19&yR8>9s$OhT2c954CX6DxwKoH$s*S07d;VoN_`LY%IhrKW zO-QKfJoA%w8@&tyViKCkV-VNo3yu|2gm5!5z^?ep$vEE+rU1urz)ih-O(c#e#1}88 z;@lV7HO|$^;(Kh_0b9^yibt3o)ri5H-0noCzBC-q`W_oA=_h zIv`k=*`FtDu33DLLt^+P;J(W4Jg95e>vce-?Rv-#T#c}3F#|*lt^BS~BTnczQ9$GO@2oM)m_q@gv(UuW zb8t_~2?oJ%VoWdIX;HeR#AVXyDz4j2;{w*hx15nUu7;I&;JrR@apW^CC$k}v99caz zld;r)FKSG7yA~j5;pA+%!=WqlN~UclD`Tv|BoKw=9|$(~exzN+ENo!_-VQEIIJ3~_ z$e(_ZKzq9^`!w#r>unUV9=5R*R&w664@}7UAGG!?pKns&fd*1O(<8ZN{V#Qv$po&M zVyoUyt@BQk2t5B@_4~a%4zO5}!3j2VF_|mcgc@`xwU80tHn5@`^m(8gMI@@?JsS{+ zu<&(};?#`^qA+PtxTYQX5CK}7AA8GotNxYnz}djMH<(S16k_V$1zW5O*w}7#HC#OE z!j8jW;U6G9nc;s_sO%Rv0E=5<6OFm{5w6&#LCBG(pCpgXS} z0wSnFd7`W7K=cRv)<;3~QQis_ZcX|v^Q9yPj-ze2dIqKdr-@}9_aTW9h;k6)7vHBl zc?tA965jh(6%ar&Vc1-e53utr)5&=V>Q+~e6}mEn28@za-vd4Pxh?&r$4@K_mpu#U z|9G3#FV*wd6`{$7y!q6~I0RY+a2adIMK9mahxoitkEWUkq>&*MDB7G{C#N)bZ$gkn zgZggHYvVbtp8SoKd}CZ6yc~t@-b00%x6XBw#Aq&s4A8JiUp2tllZ+$aT|jH+iWKo} zlCEj#0#1}@)-UB49AOG*6&c<1TS%%1$vx8w4v z#{GkEI@xS9{r~6?dG+a-M+;0hCb(}@_mq|-JG-iR?31} zj;7w+PiBPdcY1Nre&*neP>8eDohn|o0%g1D3qI0^n3{ubON|Ic2q{I6P9%Z77x(bH z$kQyDT%I4*$!!6%d7m4e6A?;u>?|y)7ab$fV7ly~GHPpimPhM*$BCe(WNa>QW3sYxVU92s9D$Bcow=cpM-STRhD2n=x! zyO!n?z5d8ikihxUssfUOp=u8?P6VXdNHeqo9Z|fgHNH(^?mzWxbY^YBR-j3TQ|&zL za5eu5?U)jh`-2I2=OVQ~I(82)Nm;G?=dZp|dzp~8tQ(*cYVK|A#nm5R16Tx)FfnFC z5rB!0ijs;=c3Jv!$4+bn715pH8PCw{J{QdF9_Ou#B&^`)XAq-uaZ@RdR43Bp%=&Y!{ZHTJpSG~rUzJ!jOA{P%L8mJLK|8; zG0b0}K6wUapFf@T{>fH?=1{tr>>Jf$aRuErJHhc%K3aY(L|Y2FqSjTdZ_NT~W4P$yvz>03}+3}uM#)}$f?uxDVA zJrFP0!vW&!CpoCHDdg&$AO`^^pPLkFWxB?*C*my_thoV5ajMp_5R|3Vloeu81e3NX zN#&e;7$;JHJG@%t)W9?0Lt?{CkYjk@76#ErVgVbgWP?@Q-N&sB6cE69DOGOk;Ald zRYr*Ym!Y>i7=6Ymo|fWcF9t4f{P~l3KKoKk8%BqQ6cZ#E8`f1+_2`E4+zHFx?5R&y0?67J|=ZDB;!fJp|9*>DpF|) zSJIW|vD7RH;+ur~!(YcV z1;tR1gJ2d*H$g9-#y%hhp#@Q^&D@2ZH#Vt~_0?G9rjA;VE)iNMNIp`4zH@6rM)-ueWsm=tvqD7UJ^yrb?YZK#Ur?jCz#509PmUzxBi+pgI&XRv+VE>| zL6XDMwAIrzBYyn4L`A&+VN$|*O#w(uzaS-=;8&fXqRQYQfSl(m&2BT3iW1@pKM|As zcJp>FR-)5G7Jq_fU*`y^$$qsakU3}9>pw;}l0E**{{l_4%T617t)Lgiq?_RevCigU zw}@&;$m(a-D+yrZ5nr%Fya67fjj(ee3UjG6C~soYLa*ZRm^_G03Fo-!&n*~Rk^6`v zHt5Q=KB(iMuz`kQPHOAZ{!}*Y^AMNDn~(_Pqo-G|wX!B>};Hll*iq~cMnF<)Jr>Vn8Y++7|}X$pg& zgIg0kc*Z_lcMloi+Q$z*?55Ku~8#zBG5epWg!FOBplisnoeeiHY#-Z3A@3VfCuXY^Rfk?IL7w9 zxfMhHbCW@rV{VsyFH;6h(%?uC{EE^(3!(7U)`)!l%WJwq{cNqzN-Qhxx3le#vj$J9 z+jz4hfbYf5DqyJ;v3(&{Ea_?Bxo2WRbmQKmGd4IJQ|Op%fHQXjDsFu z&Q=7s-&~^oscYJ9K8q;1@C<&C|ADBdz+}4{`w4o{DRkk%#ul5 zE{MguLO-cBcd162e@P2JVWb{PwYViZA%$FC^^t<9DO1)|L=|-Bp%s_&wZQ@#OVw2L zt#Y=~9McH=Ig}5@1SHWk-n-Sp(ZhrRL<;J5k)cSGhRqEDy+s4?9K4oBmklUzA_|3i ziNLE)c2As}0$(#6U!Vc4ZTWsc)!4NZ2X zR*=o#$6}*uJy(}EUjfm94l+5*FXiIc`n@wX@{1cQ73@Bc8_%D}TPXqsdsaQnqUE>% zg9xe7MKdVZh>1y9QWl!jaJ~P00&f-ON;@B9Z=@WOHc*~j_r>F#CL}w}82ZPsLHhv_ zw;dFJ2hs6MmbuosJ1gxFrMYU0F>?3$R+@G1QM1 z{OPl^vpKwzL!Zb|PO`8Umo?J~7u-xwdYIlrN)3)9Gi(wEBix)I&K%_(o`qO%S3(B4 z@d8U2n(ZvGKIJ88N=1J&)OLO87AT*0w5*;a9A_#ZG4~=1DQCO#pb?@pWH6)N`wGF7 z`bi5&3kmVs6glGD0$p=!v@z*L_JlrEEOvbr#ytpF#_F8*6zK!#_SXKg59p zt!otoTgEu0UkIf*lAMzTyH8FX(WGfV#*j}#a zlDsJogWhq0uLG}_!y%4h`NbtH29h}RNDTAVlOuA2ZhdCX?RUs0YWa{V7r;HU#5fHckXKQyUfP2qf9{0;Mw*sB*`M-MJ){)o92LSuw zpr6e|vpVtrxW0KL(34@^c8aX~XA&i445x{BmbLxIs0=?HMd= zjg{f(xBmO)*`2|6H{+D-$-lB3KE{i~XZZ&>DtXy#>7spV(&y6<^4oU(D+rkUiX9Xp z+5WA|vW*hV`8mF^dOB>W+<<<+p+}Dk#SH8!Ei`9()SdKyISGFO zBHTi|PUig^Rw@h1(|fC5tp#!GP_70R+75kwvZHw^#2tS19+z$Jre}N5F1f{0JJ1pRE%MI|b`ULDCO`e98v*|% zk9Bo++$I>*gY=|-Jg|cJn}2p8{dczalR_&v%iMZ@KJ4rPH+%5u;dl}HUwT+br`uEw zaL*V2a?eeklD|g_O0xd9+;iHCl8OotneG0JMHEg;4^l3O)+6Jx@meROe53^*!D9#qSA} z^Z%{*yPv3p0N|&8GZBb`OSyXb!gvkS7fwptP9+T_%QpX|c(k^f-v|JH|B6e0#9ug? zyomRAJlg+nxvM3^FR)i2<&%~CA}gY@u-Zksd8F|+?iJ(|YVj8UhPBv}WM`8K;$Y6& z6C+kXb@TLj0ST8s`p>46-X`4Q1v-z96R#+A?o1jJ6ydIf|F{OEI~9i3;K5uaLK^K9C0PIbpwAumsxBAk9tp7|<#KgvkG?V^L z4bS481Gyowof!^KCb@CbKM?3W9S;0XDsCmO#_7aubSLP!>3@*|l2${O!g|W|Xj&10 zx?kTFq{-fpOk`|?u@@2mg{@biXVHB1S3v#?% zmGHpd3+xXeNXmdL9J;<&cI!EOF6ET+gPB1H9rH`@estvtrh|K7#6<8GK@b&`#b!#;Vc%}(aNj|N(sW|{I$h)spi6jf9kcsKsd2;Fe@&L-_T(+}ANe>g z+hznUtCYrX%in+%T)3756n9J2?)M(uT4|jDSapH$4oIcSR*06bqLsVl3fS7g> zr}*8&sksMh#_I=`YzwO`aJPF~X#Uh5#1mdz5S>fRA8D9QIc^pD2bymM2YXY^lD+Y( z!gLYz@(s!e5;o_`-41ocs-O$7(et; zUX!PwvI+gC7U1`8maBk-oF;DIodKlv^h~U=fHSdN&QzNTx9r!KnAr8EC2VdBfw`(2 zSWG9iZCHZ;-KbO+5qwP0myG^%V2q?3AyfEtludH`-)G&w4`l1>6D0$uF=p=s&#=3i zzIqpn+yxA~F8pj>WkXj#Mn7yajlUk~X^bbToI|Y@mBqHdj=8ginl^x?5V%6mAQVIl z-3$zMzON5Jj4yyx#b)c_1c#e|F0M38R=8Jf<^eQpsceG}KV(=^_gUtF>UP>u`82Qr zx7tBCU(hIGiTTJ3qqwnky6A#Gk>!! z#3$b$oc~zF-{*&(djdRV3um4v?q#c2O|!z3%$AKUKaoi{>dc9#Vtx#Lu`NaZ8G%*~Ymc%Hc1z-wPbg(;kTd5g9s$Rl*1EIZ{z?MhU_SX^& zq5IsBwNY-s&IIjc1h!Ud97c=cy7fsK2dRC{mNe9Ilu;tT09i`}nhkZeAY9?+^?=?EdmPy!Po8*%=pHuF=G61S@N%ksm2wg{bVYv5bTNagpyvCwF*xWn(4C#Z zI2S+fmFU=tc5y)+&54aSx?DxS%!6TqMEM0(dRi~uy!x^{;HqviE0$kyLwx^@eM>oc z)TRED4Rjz|<$%E9YJgfCX6fB@+-_st2rII}6v!@LQF954(Ny*4v?Qb!(k19y>G%Xpe~(R4&>)(akp89c-8@I$n8VjO7%}Z8bVP(pZy2 zW5-H=B2({4lzs1W8`fgxsGm2vzWa)ThI*=Ycy%`4aDr2GFIWNF6^-@VdG8y0(D-X# zKW=wt_45=2p+3k~Qoa8O`TBYSH66tbk!&)<4IPWz;&s0QDh$Fj(W$MRE@*_VzS^PM zQQX<~dz62>9c;I**1>bg-tL#@;abKoSYXRNx~T`PLa3v)j!}KH+4JlO$nm#?*|(+* zROvNyiC2ai4@-f%tY$x~>>w(2f0Q%6zqv!a%Dm0tcz+QVF~Y0BMJk}RBo^;+uv5gf zjA$HyKHm`3n^V)bnA#D7YNolHglv(UK8W%Y^=sSNZY7*+$)+yQUr~wZubZQur07@T z$@c2+-I}1A6Jd$*+j7ky@T*$uc(P9xfZ+3gM)Ze!>Lp?dZ(j^|X8Pkba8~cc1E47P zwXP*dU7l+BdnBgZJg1MZjy~RaEzBdd-@wtTK0!PF)gyR(RV20tsN-%a1ec{|C>!@=wE&Ib z-KcWmP}rg;$>}RYa1f=Tk8_jGRf)sRk9D|qWS1Vm9o)bX_4D<6lPnA#lFvj)mbF05 zl)d<3^2N81K9%ryB!?3x26QZ_<1Lc7+pgkrM-^@O9UTshyidlvSOU#~xRB9yVhNVx zKs=pv_)7l!grr;B{G_3wkItl59`b0(xA7`=y~0)6e0P|ZT;K2T=r-VgSnx2nDE->; zyQU7fL{U}pUyRXMz@M3H6RNT7(vEohz%qDdH*K*S15Yzd0=D_w4R!Bgzw-@FtF{HL z>$p94j3(^PIGI|A(TVF3 zJhp0CDd`Y1dy-hs=U;2$b8_;;+j_eE>GLqg_)N3#Qh4U$3J%h+uI*khWF)@SPnDrm zA(Juw`JE>TcCywCOxK=tADtL3jfhTHZzKy_E{eKhc0KFUM|zU06OmriBNMI}u8TW* zNANifLxTV#1c3Hb?Q?D2Y`kSYbV_ zt6@+{zo^he8S2HQ072g^;!J*x91wRK!euMTF=wwUE>M_ELq!dnrSV zS1WkCwN2}+1{h%x8G`#91Oj~A-GM%~!v$M`oKKTklv1orwKHW1(LhOm!6xvFylEBd zqI6QJ6=OGnlbh17=FSo@u$ z5mv8DWr`0sL**)?66)VuvKpdvF(FnPS;;Ei7*n2@h?dx)(LBl*-s&0Y&R7zWHI#h2 z#>z=!mc#dB|9ABfBMqA+cDv(YO{Iv=4r^a8xFv0oVUhCluLtv02)GyH;jh(>2MsTV z=dCUn<-_O^w{>r2%EW-y(NTM?fEnYF-9aJzttX}3Q2vuoRpL+V5Qwy+Lupl>oOsev zs4`{}zgYsx%ja~M4lxm7=3yKwMEO2$pYb?kt}P=7N1+eb!4^Ex8+3xxOs*9XmZFHs zK7~V3{$q$7O%-})$I?+wxE4O=w$^mumUZ*13U?tFJ{ZaK)(Y>hTV@F2U+#Zk`_XO< z?rsMAL;uJ9JuzAMd!lJs=fZVy-*JhN{KmnL@t&xC^LTzwio2vTet_7~veX$-VXqd? zt~snFpRK(!RPXH$>j4@HBZ^S0xZ(L`;Pz@`3%W5En}aNQ4S-}fWH|cQeiwTYQ&#>v zhe2@-ZwwKSx+=c{p_5^Zm=)8%^4&RFJEkQr*aF7~K` z>lmLar3$#cb^P|;A8@pdqLH-x^8GQaww%`8P`Wt9W`3I=Ar_Y(k*tNrl9PP(z{4O@ z(AEis_lO)J)cL*rnXuy2)taoLqA>%YqtNTb~5Km=Z&PJp3r0{%~m4Mz36}w?! z!NGdqh~9bQYt3IyW?&D(~8+w-*rVe&muDKym`TKilF`c zcrdeQ97jzszy18@k%CTtRS5&HH3xJb5ivVya@b4M_o>ODDf4cju8!_&hnpvOZ4NI=Dr~7WbfJ~3bkoBFiDvP%VlUpu+BL+MXcwwgv%FFYm!_&s*j??X zNxisH_izZN#y9@x4Wn$Psn}wLzs+jvfX#v0uB<7tN163n4^hHNDf*|yhDh?9>4qF; z^7vt(nMESUAn!5R#qDT3rh81`KFQxd-G}^a)U&jxUG(nEc37gvGPXAC4%=qBhV^g~ zWsBdcA4X~Ci?|7mJ99D++&h#CrTFt;o$+@fOrrDnVxKnr*UP83JXJq=**{nk8IO7^NSG*n!KgrWck@2bgq9F3Nte6h@!n}o1>CZ7|*U>Q$AkjS(c?& zaBiQC0H+A%hq(BP0(pPQQ)Zua>_(&eFE`Ms$UI@tpz$KP#l`Koy=WA_s&N6y^m3Zy z4wHYi>(YbL6}aulJ&X3~G!gf_57NOGYNDfW@;zdoE;5u*uXLDPE+JPIdgu!z2J*bu zyA>*cOv;@>Eb9S2eat<)0u@uP@$F?ho!>`nAmykg_bGJa^UJ<#uG$;2RqO%s-n67s z+Dj;1H4+ZSxo6(128a#Oe#PWQKYo?5^Try6j4b7qj?;d>(y94VKlag%=oiXZS#w!V z8`kf+4Sha7fn6*Rmx-WZ56lVSg_V}VDjhk8KB^uq^N_weF84{W^!r&>U$_>2qt7AE z*KZ*+S6(Is^C0%Db`+vp8ylO3evtZ7tF;=I%5<-L((_&Z`%Hz+g;qFA8cHFIRNwBCzW> zXv(5OCc$U9-kgaxz<-Yse+3`4sC+21s^MwNZeJ7n?o&E}HLRdD_MvXjiiX%&JDDQ1 zc5~?S=LrLY)_DVG=A%x2XXm0q9lB?Jec{no&{1D9P!ST3Rk{`@a`rUz5MiK9>}7QR zd52l&b`G|~+>>k9e6>uBNIe>{U4CLWL+lv~;Uku*~A+^*C|iDD>V!bNJ+8N`4k>59w6BuYL_b=K-_E(+xXJ@ zj2D@L3>4Lgo@M(p7;Fc;#C%}p5^aC-?{}-cl$<5p^sL#uZ2kNCvS)IVr9bRSB${Gp zj_V#Xx#*oKgJaEWZuRtGpwU7<2_ol!>~CW=Hsra@NFgkqRsvdQt6dZbtQIE{7b7yh9zRI}e z^(xRl?+$rQH~7M9ww;bZR-uOkiWg;e?-~D#kEY#`!%C=ecsKm&MclRLOic&(gEf*~ zxiWJi)zmiQ6rELX*eh5(-${9+_;G7I!LGzYth32_nD2bEMp|lN!&lYef?A8t7wV;E zgs_ZSht&=3{%fB@U-sJ#qU!ImT%)!W<(n!iH0v%uEOwNAXB{Tmdn{ATev=1Gyg&4-Qo9-tjM-HH4&jeNjzOkt?^NDl^zsiyG;otCF+2XLq>AmRx|k z{OQ<`r#1F_cF2oKUMdBV68yMq5AD*Eb~4v-lpyk!%hPizC(oD(5-xW^AdFUU1dZ)< z1eU0ObxlW;*8zcz@g=>5t$rlKZ8u!sb-T87)P`4ic<=GBty%%cSd%+Ucde_b&v_@& zHES#%1w}V5bM$)!3yNr&eye&|pLF8UysE$pLtu+Brfrq#f`b){2k)H}Xl(wzdM^1< z)8S^UHO83uPxCr;gY@LUkRFiBolpJ!UkZN&ELc-&^x*mhkdChT6o}MoaOqYkn%*(p z1*42Ssodrwy)05d+Ub$tCi12zVCMJ;&B3wlltxexhkgL&+rXW#GYA$L;p;7yXzkD~ zxul-itu#s`{=^Woi=V)uojDo2kiHFO{2VNnI?p{)uX$k&iv;&OR}F)#1q*liu37D} z@FQC(Rj=EX1YG`X0DPRQck|6}wQq}5l$uqt31bz#`&J75Sk`~cTB$rttS>a1j8}wX zkoHY&mLjV)gaOP%s6IH|gRXHzB}SIRc4Ka>kX9f0#G5gbd|(U;-wn0kj!GODT9vN2 z$Uk9-T$0e#UmlNs>qd?r?zA7wJSc`7#qzd=W1koO)OMWK;lE#d@NTlLte~ElG&aTU zRaPSX=!VBQws=Fqmv3-eOptifJik6o3mZxhz}&K2Vz2Y4Lz6d2BlkIjMZ1;vNv!ek zEpNt{DCTcsbLAKv&s=uKXWpp>*x2Nesl+u2;dO|in}jEJ>@)XJ!3J~E+k(+;{nYwH zc9n?jp~O)xXM+MQRak@O;`(#KfZm?A7RTi!1YKv-#O}o4P{@hihjdS;ssoQ(II#NLMYWW*^JS>+aSGbi>K^aw`hfNvLC}q*`r~H&Y$dzrh|T4owpoIC5(Gu zQ7#r@o?H=E`FPV5e2exVwzt)yl97QgkvGHswxXNLO@}javx_FT{>Pl{kDLr!V-h*o+cl+m9M`(|lJnxfBiR&1tvER)~Y|*AjzC z$r9+-%z1J&_xP8w5W_1->64Z!RV5y>+zd+41If4 zF<9c9eaw>sYHut(EK)1kREY&T#mYz^fN-0$ODLK0JDTcFk@&JvOKh-X_LGGG!(Pr` zMBa&Czkt|J_th5A(IwqZ-4*9*p2x-Kc(L~m_9J^`;}8TyY()!prKqPkmki$!GPRN- z#<=NLR?FQnf!`dSt+Y8AO<>f^g9}no2e~vE7?h5+fTy_}<|oU|epxfeUF1T?hV$O9 zZ(mQW%+30+_H8tB!bQ-YYT1LGFvlVR-r1^Zaf0H64|o3B@|g4Z<;3FJMqDiaep%@m zd|v-E8998$*NT5frU0@V7JgbRtw+_jPLrw0X!o3{12FwX4Fw29sum!iZ0Dcfn~NS< zeFsK{I3u;rZ>y6`EclfrdS9`;JN+>k#m+hu7Y96J2=eJU2CTi2gO zua!KTzJ{+*F$6G*9rLWaR@Xn&rz#nA+^XHR2!Iup7D=hZdzK2pryKedV#S24gAkAaDpiRhwI+cnlkpJCRiKHAMk-7y{JncmR!rh{GKdg!#P_RG(Tl4-7FD93D?Q$6qF@N__K^u>xX zoBoMx9g@2J?&=gSUS-Bb0aWQ!YQW5*618Und{qmP6>U|BX1-YobA?vqPi5o{QR>#? z$1$40J2FB-kA4|*nI7|#buZrDpgC*ruydC_$2hFXO1yKIweTCQK7rXeGHm5sCUa>7Dfd);k+)e zR@)J%L2Ea&{I!ws%`ivrdPRib$i=h6Jl9_R1zeQA#O10)Yi%-rn#ZZ7NV1S{OQ`IK zZ~Ng=D^)8U>(E z6@e5K)qp%z9J^M=ZvbwON4K#LNKqPid>GC!yFPzC;>>PhU45g~h%(jBmss6mh4}9z zUxn}_j()|N-tq+Pj^_~77QIw*BA~ChCW}^$L=UFJFL(1Q_+-@&>8~KkIz)r6cve4( zD*Q)sv4*+4<{d>*`w%|@12I8?Rm+YHB=n+dunn=uGJIGZLO%UYRC&^;w=EC(q=Rh> z)_jc3qZ-Ql%ofikbgal=`}EOL;;OyAD+5h_ZZ<>T#-GU8*^D_jw2F)mk5dr#oU;p#f}+Y54sOJPlO zhu=-zMS%6kWy_OrTz;)T-ESPX$C{kS99TlI#+-e!4}G)YTr%1<4E)XIv3~4WqVQMo zM@L)_6l`zD&+)nawCbfOK}P0uoR2!6Y>E;GfPntald2y@nsV%X%cWCMyjy$8YZE_3 z45(Mc0TjwRdzQ%VZ$#_M?f1T$ghkpq|NHvt`TJ*gcJ6PG;*+0iJ;Nh;ndF?a3BBO0 z9py+$A_@+t)1CS_P z1$N4}iJJSWm3p+J7K0a&zQ*{?-BVtVX#IZ7sycs8gh8V&l7a}H?$>OE&Wqw|KnCkhmZ0qKiuodtGnnsuKikt;xI$=XO!QLdAZNPPE0z(`{%2_^E>X-jhhQ;y0l|@&us_mFVLQ`#d^U7{F~$1 z_~9{t%iiprH=8eBT=iJ_{z=ETI%*0`pRKZ=&!^v8uT9gwi!h%u2obvK&%spev1Nj~#o_u5AS-mEaR3Mz8R!E8 zALgw(uHg$hPEDx3J_mN(f#mBe{wv~U8&rsY?B&Uziha?fw2F9xy%F&4m<2ty^UbLZ z9;_*ZLJ>$-a{T6;bf>oh;!7_igg1dcDUS#)P>0`a0U6`IAx|9|!cuR-ruuNxPj2#K z*md?i=f^)J1PAiXH*V&vjKrDERP?nW67K5Dm#NrAX?BSEnRQE-3xK28ZK*QQ#njad zn-bv?T`LwI0t83tCY&|%r=uYCWK`%kcYuKj+X?Qc1Q-c6SkUg&kF_VKDStaqTG$I& zo`{sY(E%wudb-mcv4Kk?(gcO8>k}gYpGY>lG3>w=4I*-riuBXJZ!rIAg*P6Y5K(b$ z?sTjEx==k?y6I4~*Bih2AIGh=>BPjyi;2wI+|TF{#&iGnCTQ9G9Lucm`j!e1&M51h zE3DV>FI1)M7hIV|Brs)~RWYwjJB~OrSa13C6XGc(a15+B^AZCP(z-IM4ZJPTh(ZZ)ZV#iJ`_Xb<&?p>eysp9~m0JC2UVVjoz^`1kt&LM-HFD zx(&&v9x$Viq{y#;{qoym9#L((wD2~>WE#5uka~@yY#*G{<7=;Q9FbSL;hKLi zkFp#p%IMdK)gE7S1Qj{0VgNzFMMG#|mQoop(igzxPmxjhn_u zl#U-r)&X$JU|q7=F|u>N5uj0NmAZB*b-la1QLpSc3w8D^}CTyuoLC#Q262b5UDr%I`K=D2>C89`;xm=X)C{!SKuIcFqDGvNu~G zXi^ROgGq~R1C?e?L~}!*Rd2&kAj`gaLbAo;$4-N=uxJsR)E+cn=1yor5yzF7piCz%Wl z-NeMRKHA^rj1QRUif6MrT&N-JDs~R^(xG<9>~>R_{?YZ-ZF`;l%A>#X8f(pc) zu@*y*U-#U`Jaa@$zBE_})r~c;Zm1LKc_szSd)F7vQNsL5d7B$4tjFma%M)e5M~Pe{VXvZ~fe`Y=pCc9L}YV?m<6X`$S~P@COrg z#@`NvPODCVxf06%MHBt&=X}VkCXbs`L$HoiQbyhMDD2WZ-)#|@4iFt-t0N(D-EZ$^!Nsh;(Mza{bqC!gNKj@n%}7IoCN&rs zU`E`3OfKdO#=YAfg^=t6WvXI%bsfx-E?*2gT-PEXfg_I)V`n-TNFthmo)eBOo{+}% zz8OW{`2;jBB61>*4g1+ywD`?enP^^0_K_L+reuVFyJ3*?!q?^!^cnMg`Hva4_r&CC zg9Y*o1&bfE8#IChw$j!&X;I+p`Me6B~j>QpUffw z83OAJk&A#9`lVHDC;x)_If*ECKlpw|Yopvo^+2Ve1ZT#==Zu2O&Di0*59s)i(Se@r zwc+;R_zmkLf;dpI?^%$&SmTu?u^ZcU~eDLkr4@daMsR7xN0 z4)~BYuVIEZuoz_EN?iE?FGVLAermF5QB`rUqsXh>*XDg2B%t!)w|zczNR=TeVA5#% zE;qoa`#3VA;gb&Su*{q)+(i~{J85#!PmN>({n3=xyZ|y;5$mhT`y5fUG9aC{^E|J8 z3At-9Y)4uP$hvAt@#_5*NP(Mcn)A2)h25e>VLNn~W92d5LQ=JONC{;2+Fz+p%q#pJ z;(OZ5cr1SdV}E&CNg6z96!FP57e5OoGGSh2KNlU~SuHaTuMU(rOx9TUtPaESA*k_q zCt}b*{%t&tCt1Y3(9#=ZJuaf(#`86~`nRDfxVhL@MKp>GP?a^d)y3zVe|m#7ieH2s z6h+Xz*^48`;nDjcjMWOD4w~vGIP+4H8xIWYeg|ok zn2X>G;D7(N27vu=fv$M=r5X!q5}F&F*Xd*6_*xl@>n40>`=2$4^PiVUW|VO$Go7_n zvD$rF4H5UmYEK6g`!yJTl-aaAdh$rUEaN#rfM&hK&}_${CY|f3$+$&5= zssGt?`m=c6a*S_!F~LS;6B!F?1a`@veNW!O0o?g@(+xQ++*%cCR#2A8Zt~L$y=pz@ z1XQAka3KuHc#7h=GzyY*;5PAD@21ZIMTfIl8_=EJKGN9bpsb+RdQbyqH1kg{JRlwT z7DX!}irV!4xsaHq&8<`EfMUC~jj#|;bWLt4@C>$xlFl3_^pl@$kfwi#C;fU^in8;@ z;YQ=h1)E+yt~8*5EJTyy*P6`Iui!;FTX79#}07HXM0v_EFQI z>w~f##+(xSQr2p@xGIcq5wj7jLrRaME&EoWrH+2b`aAyPMHum`P;jt`X(u$1`BMA! z=gg7o1N$Jr1F1gG~vxD%ZVUF0;xOczzOx1#7SC4nTG z<0PWV=JwREQhB|@N-7T7q~qiBT8iorS_@rD%-GqT5S5%`$6GU$$UxN=JxoLouXcnv zN?<ltRC*6@J=g+#S$+biuFX+6Cm58Jr+Iz4BaVS!s?Oa2ZWxLh0SLr~ZvLYlOmD$Q zvLXZf)Q+OspFWYb*Xd%_5gfMl5_9*DG7hdZ9P0I#YS7vu6V9qfX)gitE`8pcv-^=P zl9_;lG*A0@YoKy(wY$`G`0d5#-O|L*Kx9$fF@Qb~eL4QXavG3Bfgx5Xdry=?g8oh0 z(0Y@$u)GzO$t9a`OSRe%ZJq7P?1oNj+Q2NSk@7YpEEU3 z`=au*vvjN zy$TrrMsY740Nj6d2e^YG`wSi!(_aoLD$=bi951(4o1ieeG6=WTggLZ@T^BoXCJ30R zdVKec|2qaF-9#N%nd5@4%^!?075_3q2PqkeOf}N8@(FTS^dgIq;wyTO4r02`rRMUs z6?>g84ng7bJhg>5au|{0bsYxX$&M6lvjGWW_YKJE`=Yo!jl$1RU7n6X0o#d5UYjnh zHZuHZkeIYfcB!P^XK^t6zEtQIK7=c%SHmTTOIagO3el4=xMB8-yKwI#vVL(HZmVdO z&Kh<`q(_D5$=9z|cA5oG`xw4Lfy}7?;1wyr#5D7?49a#}vvfOtsT`7QHC%6j7@A8Y z7?oo0cG&uc-hrZjj)?h|@sZC~nw_iMWgV%mkAQP&8=)4=3`@epA9u0Pz#@e>iX1zZk{ZzsXroN}l`BZgOwE}=J+@EC@touUr|B{E2;0fvy!|+G@q5xqh)szE57@vw4Yx5gT15a5~W>bDJ zqWPN_?<@8zRQE&fc3tOjjAuJ&(Kb1kU7?mrG`j=5DezQpjU%%)aiE8-C_Kb6Xx>(lDDCX2+gu)FDKru(&;E@6aW=pf= zI8dzHPUN|8oH;vdb@+WZS|SZU zXbY#@>2XR0XdJ=QUSXJTt%eOi1oVC5cxqQx!!NCdoEbHcNTAnh_3urg`5aH_JU@T& zbv4GkEh$7?iKoDfD!$;oMlyGWtAUS9nbM&bvihPJmZT(e(tV6>beE=oJ9YsBB(K*A zCh6*z9?1=xb<(UYgm=4at3TjZLf7iI-1Na*2G5+3>LU1p>+d z&nA6j;Cop=smqYD{$9z2a3QO$)%Uk_(BF<}L z|EzLj5crqGo7VQ};}BCnY5$L|(EpHupmoI7Z9YTP#pAGoc4l#x-Zb}^Te z(4Zwf=LaYP2Yu!j9LWJjJXT<0N@1o&H(e*A518VY3ucvTq(Ki>@=QCT@?^s)3Z-oF zqs$g>0D?*C_}LRyBObUt43~Y8%p7MMlGOpCi;SMzZj`&DMz-{*OG3aCsB4F|7rKW) zFJvZ|NS^!p^36=lq`RTqKBxuS)^0uo*O|Nnfts`!rU0vEl+ZBuuqJ(s#0hTA0toJ= zUtv7VGZ@;Z4KQ=6tC;qb4|)^(N=@bq;~{?$4{2p+aUU!LP=A(6o=wJy1eiy}w4a$w z7ivB^=JhX$7p41J$=r{FF+bx_&8+e|L5He-$XZDZiD33#79=tV9j-i7_(ZRDU^jBW z9qb6lB?$MAl0?E_2urn%SmHLVL-^z&?=~QhYbyQ zN14c)1si4)C(_6UL9{da#~xycdFh2(Ec4J*@EW%Bo88v0+Uv9LljC)GrNgZ@-_!mBa+)_Hgh?So(IeU-pCB@QDj)sQJ%P1 z*6xkY$M>LyzE8N+bB0fjOH9E)yU_NCdIR3Y8zLuWYpKX{wgX=%{w`pyfC46eV)GK$ z|4RWg^9U==&VyMB;=r%?YCA2l^kZ;};lU1=;`QLxy|)~7#tkxhb<hqQ-1oPL<4(IHb5Jb+J z>x|@N&#>Oi%rq;%8!+W-kH?XS{E8OWFOjPL{C>DQ8`%CQKS5Pp4hb3Vy)Rkrvghp> zkIRXqdc7E5!+jLtKt!B&fi{&q+5uMKTghEaujO;?15$h_zbdM-vki6RS6Ea0GQN$Y z02WU=0y7k5k#h7lWK5uVlcVWbIVVRqpm((2TRQ-mkV)2{wH}$$G(O+_J%Ior`_TbC zYw5kiPbr5YU?WI4mRaT+@y~$vfLjp~pA{)rX_^`>8Kc7Yh6-#OD4TQD#Rp(c+=wgN z2FE4MI5NOG_%6XMZ|wWe#iGj|Y3_@;swLHQ5^6l+Cc$PO*4>+v33u{!b1Zr|IunXq zGDy!l#W)KC5kcnI_yQfxC~^{tGEX-(M<-hAy84os(ze|FE40%S5n9pdlzxLMzWx`| z^fxUB41)D+r}9qz(TD4aM`J)xSZ&?`wj*1>Zj{7?_+;emU5~p4 zbyWvoIO0#tZIhosxsiwKK7iD;#?AQv_~Hj>iKeQImbvs%io|XVjX^ld@tsN4esaid zHC0#b1%7b|RIvq%qpu~KUin&)Q(iF_1yB@&o-|HWa2Wm4?3_5@fN79761|nm73;mw zKY|F!k4GdU#PFMWW}GhJ2|sEw@B6wZd;P-eNA#%EXl@%lVTIY+#4miIl=o=OuYwsqpi~M93Ns(Z2LET$-vB8WreXD0LY0C(nv8++b-$8Z_ zur@1lypjr!%m)p2>h~VZ{45&+^3H2}^fbMfD>drP2m;!s#`+~bGKo|UMUQBd4$4=U zgqt%480E5$eUg=2ABsjelUm@kKj(dQ1*+_Ebga#!C}uawm>}SjV<-Lu(D+F|d$4BF=+*<6+C^hw)|=U;M|@|)GYEp2^LL}@#5db|R|UuBOwqS>_b(Dgu8yF4 zi=OAku6Buw4bd6)@1Ww$szHtC=v?ZkA~t&m-Mv(nWv@_Sj;*G?s5f7$QX9Q80f_w% zFdr*|zkLY7DW6nK@LSsT7oYS$Ajtb-{MVy&T0EF(g=de91}y*zP2)W!a?Kr}$8_qS z!qU%vI;~ag1xg(zA9S3n0R05_!`pls0fY!79^6CKu9i4%LH&c&d1kytGG_VD0Hu;^ zyAPP!Y$`sB2%QoW*`A6^-n{Vu@f!wHcD0pK?mq!@bj|aCpezp*&Urrj+p2}&LSj|W ziSQJ#N>6dkh*W|O?{EN%dc6Ht{0L#CMJj`RX@HM?9U<=pJvj265|VHH&hUC{8V%LB z*}_4^llT3Tg51eGbh^}BVW`p1kKca$J{lk?2ajIUj|#F~lA=cv7K`_0w0#cGu{O*| z3CMU67EOl2B3>2cc{|oWaudZoR&O+*WlrW}4##o1LvJ{VLoX>O)}tf1cr*as)pFh?TlocmG0Wi$t?XF&M98|Ti%&Bd0^WZ7{Mh3TwD>QUlGBkT^bbI zlPFgE;;Dj#sQQd!9v?meiP~Y#sP?SZfF9#7MF3sO8VTbrc$O=5 zKcRo^h184mIFD_cZYYpNb<|5TC8OZK_jBgqTVJ;J<2=|k`=FQAqm0{vj}Us*f9iXY`-FD>#`XEP1Y z8w`R5l-2E>{-;3qr)cZl>R0$}vGkZS?NeGMHYOJf>NE2zEewBq>+n-=JxZ(?{D1b= z{wKGeJ|GLVgLu;KPvR8bml&+4B`lA~r-T4bV0QUz;y&jqHER7&Z-6E$qWTgK{y$H# z2#BWEdJNf>$OtW*xhh^~F&>fAW@S+@>nW`MMT5dN5qUwnh#JX_<56x`ZO0!|+mc?h ztW`-iYXroX<&}OWkrHOtB?u4+Ofi$!|BZbclYbL`8$2n5I_+rt&!1nii*Uk7G(uDY z5RDlw?2M!+tR=SP`x@>q-MM_$)G^VE_McjSsJQCanz(#gBZ(-u=ARCRDe_dZ6;b1n zOp0^+fkN!AZQA?X0uGA`IOCTE|%=c7(-SxsCBXAW7|7S&#FYUHBN3agej^T+=ihU2E~SfO-jz*99Mq;dcy)q$QYXZep*R3f%k=DRL&yVq^gDw4L2F{P)&7>BDH2C z#UAM$&bBiOPnWt@MAwgg$A9mrqJ%R$F9cbl01IGtJ%KJf9th0=0C5~BOENs8CkYmc38qB|Qof56UY>#h-dOezm) z(R}&IhI8JY+pL!kB|J#sf98|n-4FHY@zjE$<2*(xb&i)f_*4axlp%cEy5^^2)pjXp zGq>-I%fJ_vW1UnQqiaG6e6u(|G|AV~cxMCtz(V3O4wOy(dlNs|kwzL1Jjufi5(~(M zM5qkA*4_K8)`z#g1xF!(J(v*u@Y`3NdyuXW<2GmV@mElbYk@(s6sLmCWjb|j`m7&E z6~aLrMje?Gt@z9FmdaMQB&~JtPr&^w{_e{?zVn575%-1eiL6zz^)22LZn)~3#sGHm z98_mdG}#*6G`>m|r!8qM#Lv2Rh)zSkz=~DO`V?sjbv>@%ZtT+1P$HdkXF;bu@*?xz znYbmUS9K7Q$~k&^XTXj?fk$M13b;yobvn*S8=b7-s)Yb;6C(=Sc-`pP zx$zuM=c&IQM#LGGt; zQ}0lNuux;RVZF*SRKA+d9l;3!>Uo{KQt5A$cVhmw4e{>t4}2H=U>nt(rNm3xS)Zn% zx$ISY6lKC%q-~y_`7IKeq|01`Ge-~g!kQy%E*6pX}LExE7^|FS(kYC z^Xej5PDdU&q#Wp6zP_0GtTXPb%Li)`kTe3@ONrOuNF^MTXP3cRkBsTFvI*}hbimh$ z7)iT`3hy-2NKdI^=>jKvHT!&-#;>YvgcD=ZOIJVak0CG&ycZ9h77NYpO-`QD``SQ0 zE4-`pLVT?0+8j;EW?hx}Wuos4CqSfXKar+4WO5lV#3hPFRP>EA$_FXB#ZY%5d-s`) zr5*Rw?I(@+JHl=LY?xhyZKoy!eRoiMr;O9I<0DtZ=C=bYdob{h2k&z6QY^ODEO6}U z53u!Y20e@@1)51baFJIQ6|NrE-Q$2V(aLu6n$y_$`g$6iG7k)--q7o4_}9Yl?=KLd zB5rg@tryugCEuZMc3xWpL=ZhW8TqMF6<(u(Pm?2F|3WgM2&qNs=)`#Yed*&zOV(PJ z&pmXxM5DULp$tXTgrm+5d;dxTntY8CMe5^f_~#$*5NRO_d|km?aZUU4{%~t{?x97P zFS06q{2(yj1x&m%cPF(UJ?Mi4RCw-=`o4e%G@#e^%H8A9Ob6L13GBr@Q|UK%?Ar<8 z9m9copZ!esCOh-Z1AFhN?=W&ZmbVK#Ky+8>&7)K&r{JAhrkIZ*|8zJOV( z{=4Cyhy1Q|am~s1bgsbf_#&dBhdr9UQy#_@`69IU=D;)DsoTbnMQ^G`2%P=&C*t4r zb^<3tS>T{=Gbr^Ncr-ch((*4X<-XlyIwi;H^ZkkG!QiV+DKvfzsE8fF#gMbun?oj8 z>Gz%X-U##MzF8_I{Z#;jXo#B}QgP5BCj6uU&2dZ!{C2MEas`1o47~`vFP_0(clCM9}9;`Pl5=a zrbybpKL}s?LpcAlejbQ7g69RIpO{BF@;t4lzbr504(_)f`X57l$e{pcTRXPhf_ORU z3MCaQtPbA`PSwhtas}Q+2JQ>`XSE2y9q>T%)?W*e|AG2WPJ{^gdFI2pjNm8aLc2;I z_>qUuRv!nK0&5flhDm+ZKAOZp|7t~>CJR1H2p$p;5gF24{4RMkIO)8I>=i6xkNuj3 zfW9DFL;#dxHJElN#hosWCJP2cHm=y*I;?=S643(#xaw?eu=uPiSV$ecMfi;a@glxn zRgMTLgp?SWgXLjtBh85Aio*cqVJN|no13EdmA`s=6GZ$kO)3k)kBX|<4Y_F%Wgq64-Z`|R*G-@w~N)k7vaD!tynWVSk2ks1VVu6 zdR4(c5r6;)ptD>R%LCdUY7h{Y`)tEl!qJ|77nQ7*?t)UUZt7&YJR>n_j7}L|KbVoU_o*5i^H)0C(3j8aK3%} zogMhe&4qk5Gh1-)BBQ1467s$X-34EnP}7niWYTp*nQ4&!*Nxuw0|7Muoa-*OV^zP% z2z>OXM>sHa8;|P{@NegNP(e?%&GRymt6xwxCa;-q$v&>0XeCF8NiBYvdllpR;k_>f z$NLNe`lya9!?02J9;{#{g`jGBog_n~`s{L7QlGE%gDbp znp?BUv=E2SSbH54&*fOtDz31}T}(>&CudY5AyMkAacPj$q0sMs1lhm*h}AcoWpcm1 zas&%w8h6spgp7K}3U@Axh7R#W7d{G`Y=EN|AO(cHJZf@ojvhpLHQ4&6#M(Ij}Nd_*`^%l#&Y(@4{@Q!R_tUNP~RXE{N@Zev#5hBaKB(9n&;O& z2+`DG*HT~oV6eaU`^^g-PYU^>I`kY*+CY9AgZgzWH^NRQFhV7!%p{HzcLp3Yqc_qd z#9+dSxc>f;A{~oyA0NlPPmQ0Vq6m_paIHq;gW|`r+xcYSviBUeQsOw16(BMpmdNP-g1APT9B+#dy zp`+#c^0rjTxBKnBa@`*_{z4X2h|*o#O^7r-{lX3u7}H|ArU{JE?d>Pudy?GJay+>P z6PxyK-Q?gvzDtG;)kb%=vK9@8nh$Us^+&-TeNZ0__me=Gu~=z`6d=SV$EodcN#c-! zUhd~*1JJ3#Wwf1pOQ<}ptaZ(6kx<7Mh7q~U5j()N;`e07TcPSPbsD-l{PcrAreyX) zG`Qzn?oAq~?1u)h1LZ-fTQCDBE;-uQ>z_MPq0Z4L{gbx7$%dbsZ0x`vy=sjGfW8+a~{B~C9WNCnbxFI+m_ zPzJTW*{b!zsBkhJeTOVVGxa7{l1|~@p0uybKG}bnSNsEZuZzbd?i4Sc{1F!UdBVTa z!{fq$O!wQyi9vVjt5el_dI&*MiE?1ib^Te&-W)`x`!O%kL{~&J@paazVd}Rhw^s6B z7f!8Jb5IVzSb?Ey-r88nO8HrB*_lNFj2SSF=0VixeEOBxJuWb2_LLzXAWRWTVVBO4 zAIvI;{@!b-U_2L+m^*cKS%$W+Oo zRm=`n54|vO2=)~Z3-;u{E&0{Pa$?4X-+j2+-R58WbS;&h5Kos?cdwL%Sx5>pB zYvgz`5886{#_A(H`IWxy=<;hQG)#cxNl3Bb5p~IP21osA5!cXk6xSIrd@mkezPZPR zsf+=7g6qP#+Nb<8+tRA25};GS@SsM%yAT`_Aco)0ThW_(SnQi+MO{Sfs>=f`-W{tIx{7Kn>S)0CGua7&^{e*@ zP2&$rY}Q?yNa(MKPmO5ep!!nw-BdL>R6U*#FeKS2$o9)M!|X7wj4@glHl2@m#?;^?&}%|f=k z1!fYqTsjf)f`VNaRdIGelgM<}){WH# z4US>%69iKZjLHSK7&25#G0lUt~VSDFy??ToEx*yvkAAc_DAXvK4==5cp`n(Q+qDRIvI3alYRosxV_##ZP>Y7yt$-c4xN}{DH7u< zL&*U1fK=2p>0cP-7EC$j%YA-93kD#`XNDQ&UE(#SmdLgz$5Kwi&oQYXQC9)#keB>+=4)07}p8v_N&XP*{j1(VO8)3#e}-5T=~ zSkqkurP~!Yo5?)%5o(E7sYr;Vl9db3X?Is2!bYl;kRqhWv^%V6#uqg60S-_qznKoN zFUK?{4+cjcNmI}6?SaO-OdCjhB2Q=GsS7=O!bZM)Nh$B%T*d6{TS7U2uyifF-M)F{ z0JiNav-&(TA~<>b#&(0?Hsh>ZvI^07W!PIyhbNBVsF?>e+*HqI8^YS9DcVoni*U#O z-DP&(#Pfd5uQLDc4(2E!5zjPZ{h#dVWqe9XPf?3*YF{dTn|mu#D$TUuU@u_9EK{Qe zuB3=Z;xB|R>#(15E!ie&RA(JyE;`SB^0xB@#ycvw*qz25sn5PvBFLxS8^4k5NH&nr z4+A-GfG8Lz+iS+t-107j33HTN2&Qwg!!2CP&pqS^b#TeC5)w5}*#o?HV(gF+9Yd-D zy+#6mN|NS~{r2WEf43Ci&ZWP-?54@wt$u`*XbeojjGpB=>{42TJ{Z46GOq=|!8f1+ zCMtn>$u;0XcfBUmj5X=MzSA7rWok>FZSP5v&(hZCo*4xlX4NJOo?sK6LWfyc~SSa4YtL#Xv!>k7js`JmY9f z#i4YlXtztRyj*?*=^6=e+&>TF6kmZ7yLdL?Y8a;^QlFWr+fszDUP=`wQ zv@`okD4YB$w0>AURGvP9%(jk)=3#lI!A3v~(v=;>C!v1@6{zyPFeG#$M8ntg34=;e z0kPW4Zid?~1JH9Qd#QM7j@XgTjm}8fanqc`^0Ok{^GSDV2kxgBa`!Wq=IJDYZU!7_ zo7SrEC{HN#oni)k=tWnZs_zKuy6(D8XS&uBZPym~Y)|kK>KsHj&J@*#aWUISinomc zEP=3+)!>8V+xMxV3N=Y-K{DH@_lCU=h|c5H&?e#1KG z^Vo^!B6+q=X>>UKZ+&ERfmyKN|5IRABKpR0;?=iXPG113A*L-^Y0~cD(_@HUAi$)x zNs!NsU$t$EdL%A7dPo^1j*G!W<>UWxnhKNl?wkJg3w+~&!maxy?>`6Bmd1(taGqx6 z7pf|v1@2TfuViIKBa}ZTJ*55g#5>z!-EIF7y$FlmhvE$Y=H@e}Tn!a5{juWL*ph4t zW3Plh?_@55X?n-Bwc8da+j-agS64vV<|gQEHfql{w5)-}I)8K5XPNQLc4f1TW?UlQ z{K5b_yw9x(!P*%fwik{cndE@!y{~4QsYq#weHMvLUltZj!3}0PE&dgaiz?AeK+98} z6j4{gex0Tap217D3o`*sJVAy5y=|Yp=x`3PCVDs(D#NhAK&Va0lFbHFm;Br=!3VT% z*p}r~2kV41I2}(k-&xptzUm3L1^fbent>wd^$FB`Vqpt&XJshPsxh;ET6}l{FRT6R zS>GB#!hwU~PMbCz8Bx9*d+bL~{Wi2G6?`e@S5MeEoKAI1*FVE|i0s#J$G`4;FMLYK zN3lKt;JfOTN5ZpWsjs0TYlH%Wh!z20*l%g(a{L{cYPjv zNNpBXdXvYr1`@;?F=vEp)&^cFfxE!Vjv`JXqI3_ALgi3^{+x^M#qH$EsCg(D&?(J^ z(Oq*H=Oe^OtaBAi6h-R-JX@5r9k;i3kJTONFE{=4qZXiAK%bdmJwvB~(~GCitE4OO z1o?|PIX3K4XfllxdBLOk4wa$bzKrxMYiE1#zvNGm1E-xfnUhBVCf6#D>Q>1mD~_YI zy{@%PnpcwRaIX;$7Dvqm)#k=V1k`m;27Xh~XEX4|H41y!%=hlC{&08_kn$W~L-mn< zk5T?KXTxbc7yhQ>)Az}n8AE9NFaP#-@>(&hk#q-%0aLY$5T|;^m+D{C{`DG8BZcqH zMja63KH6JOb;Yza6OYn7XA3=6YYna0J)v=CCyjLWV=$e`7=3;@?HRyPr&Zor znH?-*LJ4aD_+G0A(Xke&tB(ic@y>_=Esonpe8_6K|hI?m;pIR;G*9C!)9w?(wDqkXxM!x$7n_=UaB`-%%-^ zVwy7HUoGPZIYgyg`4)~?{wXSDj=l6yly;_z%HP*Pkg0P+lrI(R`Uro7Bse%iZKxH% z5r2MOsG3c;p7fEprp0mMN4fV&u|HfA@~TVB&ADOlO7l>r%3IpmeG43pTXs;0E|LBa z*V@yn!D#rXJLS-Aev;j#Mx9o4B8jVd{Y8bNadMSf8Ig+)fNT{HdzL@U3?T02d8!O$ z*NF~yhh7b3dpTfNaD>PQJbGF4&po#n$D74`s0I73(~-NVW{?n_fTw$Od|rS;Nxp;= z(x{DY#<}Ly5;5H!z7Y@dmB24+SX8&AA+KSL#;Q#p3Wsg6=hpQba zh5YN|iV2ODkwm|XQ@+diNc8#F8#@i0m>}m!!CP*;9p22Z0rloifpypg(PeZ!RgEs5!NNo-Ko%kb?bPh7Bj4 z%Y}idF*@?bx=9O|IN}f=zrD3wEZ=*}o)&NE0ej2&(VQ*g&Jrq!js7mqBfjDVIJOwkPC%BLi>kKSom^C}Ek(G#D{QMuGJfA>Tx7%n&=R-ZsT=?jX0 z2#T|O8N(OC2}=6;mNR`AdfO`3tFaa0Z=Onu*uD2qPS#`3Z$4Ot(va!=NcGcA*-*|w!1?jyZvz{YN;rduepT=DL69&I?z>T9 z`g>BN#5tUuK~V(PxHgY2w-xw_s_t^N^KpjDjVQDvq257Cb1{VP&h@2iKB$8A2{dmA zzEY4RpLqiY7I{5|zVJ10+%S1)Nv>7kBkYQbZM%ZEb51codEsb5&2L z%a*~LX`YHYXC5C@3sc64LYe_(BQaAN?*2*C)@Mxygp#g+M}9jroDrS{g_qn(B*93bPYL&&n9OFViftc) zOVS$QJPbC;c;k?+gyK^z+13A9!R%S4Qh`-kO5Qx-D`;EJlYk8efkbhsP=zL%!RZXPb0=_*^>Z(*@ zeWaEHaGPTLgUPvI@_T4XJWxjMvcgd_#j}QUF8sNYyGkFQv2wxX`;n-}&>JtcPO!STuTlarFs<*&v&^H!!@(F80F>7$H&?q)=+)d1`f+w6G zuOBimFc~~=4&0;Pqu#sVcW&Y&hyB`@5GvXDo7I-KX=`i^m)g{` zFdeSsc^@KhV$A{Kj`AvS)5>dW2PYsgf^b+8`upJ4^C(_1H(lHDx#9;pJOOYqIM$`k zjla0>51m;)^1Kk~w=~2Ro+YO^fnA!c79fYKH0pgtsY+FDKe5o4kpujt*z~`$MhQFx;wU$do=Bu?eHxkfuf%NbL-3?+dbZ1XrkKv@T4^ zHc2+=Dd&E*q=Pv7DL-|o0C`}X45g1SBswUw5aS{rn#z5N7sS%NE$S5B=f-EQ76RT} z)qv`zkX(>%zQZk$;c5BYn}5WJUBB&$MmPxEow$hD&ZaaCG4~{g z{RHG}qWU_(F{VjwG-Sf5`l=&y!ojPpRRJ!vC_MLFE+>>`u?eldXEsq-^<;QDt-=gD zNFx-BYILZrJ`j_N^{0^Xk3_c+4%iTtI*n=RXNvuA?mV^`d_dZw6|58sfy-#tOs{wZ zi)0Z3qr7WulRbcW?#re|^^P4dQ^x{plPqM7$gNLEMJ5JzLO-kGg(S7qiRL)JwqQ-0 z{p*1Q!m}`>Ai9(33Z2AfXa%tgjXDLeJv5Ogw=uAAboq`i^(y1J08T;01p(@ehAP{o zvnKeimv(GtXBf|aFCr3mOOM+9Pz%4adS4&n5Bhc{VU^KgPqSq;mEB}gHsW>NvAb}S zuBt8=@4@s?g0L%2=!Nt4QFmMhUQ5U6ZSD1%8?NHDixjZWi|K(-?D$F2%CEun$r=f9 z`H-TrLolPMT?L6jKkbEh@*Yif2sUS~jlW0rKzy~%7hKwzf z@ba<~&@MhP-6{2f?Y{P(oYH=%N*W#ECD_ zJRok7j`I@zFpCP{%jncSec8!qhg>uI=_M2)87HfMOvz;cam6xXL_LY|=Zu?UecG-< zXRneq4IT`GpdhohYjlw6%AnRbRl2iD>0c)$G=v-_v9a6JKb-duE`=~wB(hH`{iuM^ zHMp$Fz-$5bdO$~MTssWyA{Ir^UfH#p+OHWvV}*DcGqik@&}WuV1CEI-B#v9&Lzc2B z(?E^z3^c({icPJJJeIQKT8BvJD~ML54a|UUyW6r)0ku(1BBjge<S}*v`Y5ud{uU{yMKsN1A9pPe|578(gOo;?{xK^nQ^TBOn^5(sDK)%%-yWo)t zK3&q45Mw|$Vl4Y~_v8CJMH2KKaJTr--1}Hc;5I`)WLO*0AMkudq=4I?o;?Kj$}Arf z@_+G{%?4<9-#j?)nfw`nqz1?{@T_^84?teMZ6Zz@RiIUKh%QZ)l&;UbT`8^BGW_vm zt+L9}g)dV}=VA99OlRg-L#(HBn2&NJMI!$?=6~e(Bp=2CZbVtO_}>3_2M!fdUm3f= zE{avdEpNbOZwuV1o+B-4u~Jc=Wm*=j>Yj3N)Ek9fg)CfRAP>X^_`A(`)8GpC$_I(K z+I$R@Yk{czXIVxYq>oCw(<%iLVfss+x27Nt=_gmWumQ&&4;Lb8u`sSas~DXlJgi#p z4=>&3vcf2X zf$%KkW@b_?2g@F4XZtSGzDkA^-<#x9AE;nJQcQvQ0O%|8FDE*aH3|WWuXn|divOJK z!tSw=JO&uepxyuO(XqYtVZ3-QW@0Ei7{qaB_{{AJ>)j`uXt+h>3`2f@OQONW*HxJs zi+0S}8FoicLm?VQ#IBUmiR7wiz)dwCM1~>`g5L?$4l75Kp%Z8^Fd#A3LQMu1s5t4_ zn0Y%xTmCi?p;RPaXJ&!lK45*D{rTa{HTVTRv0IGw-w)@Q;66umNj4=6!G^rUXG3dx+lUN@a zg5^*&40Z+7I1>+}VJ)luw0J=RNDF=EG1`7B@+4BmTLU@Tbf0_fuLPNmaDxLHFFRpiq?}Eg?P9B3W_npClYWj4mVlJFh1vQo*;m&}Gh)Y!5ofs2kEST3vnY)H z&QRw^q_Aa`4ble<=@9czkd+-$V0*Q&<~Y@hUtn)mD7a-vb!_2)ik&ChiJLcR*~vZx zqb}UVe zL!W+BVS__t)$n>pvwYNGZlCRKzl?(VIDY4i9E-{4BD~)wS$-ch`Oi#m8d7nGv?#|< z96JZv!Mx<1U#&%ne@@9FC8dZ=YT%tIC_jbsaulK_sdb#)_jA<8!H+rwx{4|p63!-& zUUdg$oV#_KVDylP3?z(ItUf(+e_B>?Z2H;xF96k9s)xX1!;a~>$#61vucmJ>39ihIS-I=ZhjII?E0cY z5K`I76AVa>M4Jbz4zF*m_irmt8P$%#Aj)nJ&KMkOc+%2^SCIF7`0MePfUh{kcY1_5X4dZdTvdXP49I~caM;@*^j>reyEiBh3|6)ptt$)_-PM^K$rQ-w6SCN z4HeeLd`NR<^~xzGEyKLiJ6&Q2od+DZ7NU+OXZ0BLY0WTaw%k~}W=N?^kT~YtH6+05 zue`B3L|V+Pt->1KyK;vMMY(JXvxVM5ok!JF9Cv-?!UIxe?jE?U`Fsu&xO$H!hqZ4` z;9}H<&MmA`h!GojRN1rFNOJYEkIkPWIXM@`PAWiu{$FzNeTeHOo&WZY;^K=s?0+WK zCu--BExjPzc{UOc28@)viFnW3mvm3B^0_g9#qFMj{GxUeha543(l(=Gkv)r>u{!MW#~l%4AxB=H#%&PDx5xjDlYuP zz3!D#%i{Ik>%|F}r7`oZg0+77+lpCa_~>=d6;9_7`V!5s@YR1N=l(}8A+v$K5Qa=U zc0S7rG!K-T^q__=7qDK*g=oARnTgL}FPW^O=A#P}&jvvyoC$~F*@I1D)JM3wkYUFr zaA$B|E}XGnfC%6Hfh8JC+{aY&)1$_DI&JL2?Ar}<`yC^D_Uz=wEu zZw+qq+>b$f7i!N+*)BVBlLEX=sb#^<6Rh+GO)vSF5u z=@)N??MkOnMYFntqj0u1n-$TsD%)%AL}u$%f?GsLx#HRqtI3h=3Yp~LG>-)CZP1h9 zX$@Agc#&ylc#B!}+{4~$mb5sf!^=z#%R>)SQ|zbp--1YztKWJPvCF|gg~sacZkJ)! z!tvO!vNi={CBc*m3Qq=$ls6wPFLv?F6f8W{`e^OxBxFLG@`n8adVz}BbDS$ttoMWa zpXG_n2$82t^zRhDeXqnH9}k;wx#C&p&iU})IVw6BvwGj8vPB~EZZAFU;(O8u)25^0Q&A-Jdn$~&5 z&HRGBZqQDf{%^5*EKHMIEFXYBf9Ts2STr#)OCJvsH&CK|E(;k#+)}di>u8Dea}TQL z(Jl9Ua`nB-Kfm+K2j^!8fC_{!oi3q0(x2aq=0L*=*%m}FVD%@Ve*N%CktSEI*V;@T z-HHBus#D2}gW&1xzui}T4~F@|sX7y5I1gO1?bT8L^=UsJ@`)EAZof~x6IvquWQ#^Y zG`#RRYA?sJe@(dm_LdS&QlNs=QuR~ne;?;RYekOp9O9V$d%63Q6Q|G;7X#A}9|Wzt ztGN>GZhmfy>>&@WO7K>JY82TN$wSx%wXDFyUrQnG@G#;|c^ zozt{F(M;E2X) z5mLr_Yx`1j6#XWzy>?O&mwTUJ`e%)X{=|PJKm@pHmZLhx|J&yT?!m+UyPn_h01*5y zeSYP-|1$Mo`uwHOADssD#^5I-{pFv({PUN8eu~4-4}b0ZpXK5&eg4wtf1@}4^3PxX z`O7~)&CSmbfBmsP%f(;%{H4$TMsNJ(pTGR`mw$emo1Y*4KljJ%Pt9h@Ct27e$>wLu zCiJQ#v~DRTw9cD3w_j-~8E6;UFshnaVak-BZjnz~YAfP9Mt%To02xPofUE!2?rpMf z;aw!u9n)H}OR0J_r}^<&FnW}-o|t&0;svkd7Q-`)2mG{Go?i@b8NS; zy8zzPsF^~lje}0SJZ=rGdYL5pneu#MD`+#LyPOa0#xBGz{1F#_<(#G$T~V_q>^IpU z=d9iHEZ4jD0Ti=y(ZP;v*#v$DJVv}koR*T49H<5&>hbQ35NEVMj&8uN+_P&{QT)pH zXt@)`r;HlXx4&7}rQ?ua^4uT$8g&vcoa6E?7K6gYw!!CKXZAoLsLsmfj3YJ7GRqxs z-{o9=3{~8WU}NMA`|_4ST@qPVmtMj~@$%|q%E5Z-NVG{-Cm|ANzLA5GImcG2e#Gxf zOxlGU>>Eee%DR6t=gtq&8qR#E7E@OW8X?GtDJvzkI$S@5qYTabZ=ooMI1)--s~_92 zLs^*oAuA|`nH+O^a7g~-wz1>zqEDtgQ>4fS`uIMwn%QH!ID0Tys`}^TzVd+cEv(f= z;m0+2#^{q_yPSP@Qyh)1)Tr902dOmtgCWX?aQdJJ{cS(A2?n{kavm2_o!_$oHDG(8 z_}+53czt!)oWusFnFlTVt|`(G0;&|g%j>V%420d`{ZT6QWK?Lsk4KOyM1@T;@S5zL z^D|OzEq5L z5mKn}!Y$jwkm#?nx4eBWeCRhxBsPTb*!0-HB!}8@J3qPxqg^OeNa*%n5HqU1W>Lhhj?PF_OG_{Xmv(LRNNCq7Y}vD zAbN)-cwY6_G?Ih;pOR@$GrseV^R`$WphJJ$s83IYsJ6!C-%`*DMW4V- z0EH9mb+icT7S*k8cxzvF5^BfZ&okn`@suV~L3X-2^vVgeG$cczBRSUH+ZrKgzfZ&B zglWB^vnvh?5!~blyw%C9(kc$^h1yQR{6nY~6td;nFU?Z!4@lR0wiSQW0w{AApW!xq z)sRXrg_iLDC%fPHxqC-Abf|Nj8ob2(^b`iB5-Ioeo96jRmnz%4^v&pt@Nh)Y(7V)0 zv5kx#J;9;4fog-iB`+zvtXb3k61`ZH}mNf2BR3gBR zGOOna+>Om~#i?W#FWkKCHtaC)|JDvS;>qxe7V3H3Po(L_V&mPUH-V)6 zn@94>pW~CzTnh!4=;N625p*^d%6-rX0nQh;s#LU#5>f@oQK7+I-tADL6mrVn&XGX^ z2RW=~Pu?*?2?p*x-rxUBg7GQTGXz4C zU(R8x4K4R!okn9WRfU+%2*S`V3L8fV2)4h(YTu(>&Y_sq%h~Cg(QcqX&Otd|=n44- zv_9$IWBGe5J59!4Y56NHzj}~A+?Kye?5}P4|Eq1$=@3y>;awUSacIrcFFHez@431c zCmy-sb|pAx7hCs^6w|4!)K=ksE~Z;uEOk;ICFA_T*E@|Vfs@d@#3BY+%262KD^0Vy zB^yN0V$!fX(q`iIY(~^3qar{O4!(GNbr0aK7_5|$7NM>}Cy5E5a=Pb#&SOCO&iJW= z_q&Thhry_4+gY@coddh)OBzz$i?Cg~_ZIH6Eet8PxsIh5orr_&;w48B`MXd+6SxtB zpTgFj>~fY*$}*xp1+K)P=jkl2X6lUrTu*6&bM??_G?>+Gq@VIEAc+v}X)mS$3o~6a zp{*|uCK{eMm|0A5v=7k=x*cF4Q5LEO{mp~`5@X8GvH@N1S#6i9Wj9AM+T`_pcxKqV zEc(I(>}@<g-so5w^=r?pWmPXUk$TAQpL4y(eu(w+VM zNYc9QhRaJVVn!vqrUyEd*?`=!pWjd9RVYBj!+sl}xuBJU}(;GA>MT^ei-!weXTs!066Mm|{ zJRciR6LT)5QBa0BWYV04dv(kA$lT$2ri*(EDm8LCwZnW4Yx6k|AfTjEsc-jJr|GwR zxOmv`fKkC*Wl$wackarN7t&HG(S2@pZVaZ<)Z*VwLI4DDMbEQ3FR6% zPx2Hm4m^q7ik>5QWhBU`c?b0)2^w%Mmjs(0ffkUD>4wz3XqG zsXog1X~9?3GSYbElUIOQ_pLF}D6~2{niP}7!SNyu_r3yr>^Q1TvNwmHu<|d4jjILS z)($l-{(5Hm)2(u$rnT5ExWgff!#u(?Ii$hY*3c)7oU3Vp3qu(nvk_wQ6LS|FXAgFa z8=52|=zHP9N@p*rYm@57+klmVK)$XZ?TG+;8n6Ogn?{BW&!IUQ*epOmW0TT)E0V2v z=&HcPV>K_Ieo9$+wa(O%gwee~L$O=xX&1^A+7uWl-z>YA^|mWh%H#WdbRO8(mui#V ze=J*xNMOC1e`5Mf-fY5Kzz{h!8fDyvdK=koFt=nfitqlwQQ)3*x)j4^rD0^wWIT+- zG|I5PHEhoCpkoW#F>goJ40)ZQY_r>ZKX{DS=*XFkF4neX9Dp>&gm4O}yPYOR4mg!wZ$<~f75Iwz*Lrq)%YDk;W#^i)jq-Hi(i1cI5k zZ1rzxO*~1RJ-^otdd3Tt_a-EUb1& zYSq;k-{F^4Mthr?`FSaG+UwOG`?T$?Ia4TFSTs!i$;X^ZlFM;Dtc)mXMK@>0P2!>< zL)2TupCPYN65MR_-gKN#N^!F^o)5CwhZy?B>4#Bch869_IUC_?-0ipR15-zayjprm z6;-!pD>Id;1qvJ7-_97VZFw&ZFNsmVk^8W{McvD~T9D{BWShPDX~V{_Xj;-3kKyWV z`U1VJ)rrN$r!Rx?jBjbQrp|~7ppv<_M`kyUart$9_HxYOAg{VrWsuaW%&TWx!J4(k z=dfICGgUf>rC@wWJ%Y1nJd=&`f7) z+0n1>#x_;KHh);l^k{_6=e0R`o9c?PwaG-;lsMbu?RxKNg$Oaze4`^#>S0<9!*lCR z58~Wz38uvk&-sm|SSc&3)Ql1gky-&C+?jto!F_H#d){fX}E6E ztkr*|ixiKlebGMxZP-IdReX0q7=?(QY8Q4T18RHErnE-y2&0{YMlfQiEz3ym+n;md zo6Q@Gv~3eZ&|>Hv=D3v{Hx~`-o<|7Hf>T9Iv5h4ZL*E7{7qcHEm@`|)bPo&8m6NCy zt&U2JW`bGw>k=zoDYwSQ_OrNWyM8<7;$FXDeyJ|>jeEU^LK@f4x>Dk8&Df^wvz^IP z@)&$qHscs3;D=EqX1uLN-1Yvgsx=Ka&h24N=53Iek+`Kq_tDA;1~+%n$LC zI!)cOz3fS&EYG4g-Z~1tqzXU7OI6qB6_kW?kxS7ysXUJ;gl}+mGhq3!J;z>bv30}# zP2Ugp6zi2$WYOM(8>9}7`kNt@yL9Fj8m5YEC92kzsJCscs@#mPEHPz07W6CaFph9A zXwEvphT6zpPfl=LR^WH9$gS|7rJ}Y|v0BUKVvmqctR_=rk}q#Gu-k59Xh^};@`?)N z_gi+>Xk4Tw+_GzNc(_O%Wx2jGGEJ)DI95A6>4^Q@U_)!BV!@i=G-)^4q&0!Qap7t= zaZP&GuK3WZZ%!L3nwZ$sV5NYKob)aQBE@|EV(+J8$$Kc}92r+PXI{-zv~n7+4q8jP-nOP$i7-|wE}BlJ?zr1x zv0z%>*mp!uspCzQo3NrOcd}miO#j5BpW_IY#u8E0bpz()4vO{dwO~R*#66q8ZJM7x z))dFOr0vJ5x>{su*dv=S9qcH{|88w2jw)h`)HSMZ?M{K?SSx9(+^#c+XKu|D-s$By zPoT-wHSr})!Fiy;(PpMxEz$abpkG2wpX2aLjrvn<7N*7e+r!>AA!oN;OMDF9W0pFu zH6(N;_b(Tj#h~<$CtLLD@(NTQbgi2AOW>_iH8m}kjjC$2Cs-P@zj70VLQ*Are$Vhz ziSUK@3}?8GiAOb@D)Q}LcwR@R6LpOctLk8$*NopHU-FgSiH9RHlu_xq6@eMUbCmj1 zT2X+wF#yvkUb&__Y}qt$n2)7fJS|-AdM!P{;BWlYz8KrZ)=}-H7+SlCBBONP2;Oo% zd-oV!BQ@sq*1@$Q%g;JccW~s$m6#6M1}sr1=hMncZ0~?6^u$UFoP}KbNX` zCe4B(ii2u<*;4Ruld)oE?qIK#_h;58TRtRycyjjZ`h#vW5lVuxbKFV!qmvg6sIl4_ z1n(|*WO*%kmiAm+pJSy8W8!o$n^#WsA!G5)48V0!vEB$iiWBc;SUy(6l%dJra~P}A zQpMIZ#9_R1Fe9obrthjow}@boLWf#d-D7({-g{Bks}2|I`)nTeLp&(^%$}U|FDc1I zCwt5`Ez6{e&1_bBoVO1J-PW5U>aL<-q+pNa@)b*ryV&hhl`~{Gys)w|QrI4p)ufxy zT4h-{%yew+VZ!^!dm|@A6zjN>J1C3e=6J~s`%)|8Uv_g%G7ECXQ9Fu<%s+iOVOTDR zjq+Qp7PDtlwCKAu_{O{Nu`;WIm7VY)SE87m?@u{A}vx06Zb zlKSpuWc#k1!N<1T%)8`@HuFWp;)y-4@=ogc>(D)ra<@BEoYp!zIfvu=c*eMa#1-qS z3;_yzz@sRrzwjKUG^-{0T)5n)8K%uF4+uUo?g%*Mi>MaM{$_Ex(`MP+N=}4JuTh5PS5Ji*R>~-^+_k0l%1kO=gYTx30IPeNkyJH7OhXj zZdUM+F8efSkR@}+4lUps7crLmYnw&^rjcE7j?%ETV#MOWc_(f+Gq3f^Ms;$e`b9<2`E>g?SX2g|We5Y7N!2xpO!|UiKF!xwD4I)Wr+a?1x#i zZXdeqyIw(Ks39|y<6=P&%LP6~%x-$>l?uZ1Md^kFkGT>OI#f2U+TDvY3=mKkY$7ZLyk>12?#96;6Q@bI(FBkrwzOFo;3IG3pilkEbl%t$| z`jjH1Lb;|CMd(DXl~r<%l6zb0F30MlDA$xwxsvYxfAr`NZEx?_{d~RN&sXi&vGN$lch@Lj?4-_X^DpL~Ks+z5ELIYidhosSKT~l? zx0$97u$(Besx=P3QDy5yi}Vnh1o#BEiy%ODSmV_97w;&2$p8oGu+2pG8%~vMJ7||@ zVq-l2EiYbWktSf9X{7)rs?Dz9Gj**C%hee=d(i#&K7NG6Cf0Tz(CvCER40w4pFd{r z3+d1J>~~7PJ6a=k1ka4pcoN+n=&Y$n(ax!Q!2ldY3T#DW)zr44rbRASJ68gbZMnC$ zthvu11>lWRWJSV55-#U5_gqw@+T!Nh)7gafy$Z~oCIr7L%Cn8^2y}1BA6NYGB_BL+ zF4XxIVXqeh+@_iO`mWspYywi}rsG8FOn3o^5xoU@F5!_c>q>t2OKtk9OjXaSL%=@m zy?4lhoYC7d+wZ1 zIpLO4cwppfGVKPQyus<&l!ASamNIt9NDSk|ivC#Thhq>EvT_uO@e1}g!Ux}xLL3g} zi1B7s;M%%74NO28KHr`h!R&@FD#cGNf&vLEpHd9)=710KKvfS%o16K){*@JY|4Ow2u5sBV_UG_@RAw z+g|Sw_U)=)ZlIGX*m@BNSN7OvBD30u@~mfHC-AX)>jPvKqcW!m&padW+I{>~!|2Z9 z-BOD7FA?-SvbndDH-5(G-sK3yL`l;~8oO@6?Sa<4=2)jI^~-AsuW#J`F3YbxJt*p{`v4ST|@$uz!7>oJSeugO&D^$Z=4F_Xd#NRCJETGZd5( zR^4(kPOdX~)I#O4EE}K(Zv0q+qqlnjjk-pZC}U3HjocU~>gQZ2`*e6+beUT~9>1i< zJ8!|wG_>I6RKcR}U*0NP5?5pM^8%qi=S3c3S2$y{xndwGU z_3~#6HipJ7KcZr8fbpFC?QDIg(sFxrfB5hqOtPzdnDtTS`C`v7cc8>RN+BDYrMVH^g{T` z+^JUe>N>_yi&tT{d8$N4$>c{hadv=cwx}!h3xxTi<+_w8_(O&P|mDOR0QEq*(TUD`lPf~@wtT+x}4^C5RVi%aO z01#8;^HAEDmK_S&aglGk#y&Om3_haiT!JQ&7ICaJ>FWm6b@z9WKVI*npb*>#lkxL0 zSSL3W5c+uq?lcn2?On7tH`pN*jzk~Ve#~)0wzhPLt~skQ%^GZauVsSm`%^wK9Od+B zY5nkyY%y0XDEs!@82k1ypu4~$HNJ3*xCwv_Vgg}4oB>IceBq>xNd@3Dw3rK;EF{JL z5cnEV{Xci`@`gC)CcDmz3wKI*Q(H#M5E_dV->R!%CXqjkXK=@jNd=0no*lk3T%%EW zHoF1EEf_YLJvpw>;ZQh?h@i@kvv4XbQ#Wa|=B9;R>&9FIx@if%*kWb_*7@ z=6;dGr-tk)S?c=RqQzXP)48Q1@gMj1y%DUpiEqw|F`cGjAbkbBHjokk3t2Q$0STU# zPmxOa7LkqOzQ;~*U_8j~NdGCOj<7bF=#JAV83GG#IkNh(`8XtJ)QN*&9L{x3$$s2% z)koi?L8RJByVSu6k%;7Mt(UiVy6ox1)+gw6P*;RaJe_0q1^Ip}zT>km7uUr>k9mNZfU=l%PvBtIe55MdM`-$P#4f5!aXOVCYjyTO!5W2f z<@vY9wHt$6blsd;2b@BZR^QS`j4%5XD&SRg{&ZD@Ij=v!D7Polro6Om2)`3$_zz4? zlJi_uP@TBrhK$|*A?yT_bBEbb%&clj5t@=W5TKoi{ z%ZnSUOW2r9>ii}@M_=qOLuJb+ejEL0Agn+&9;|=iF`W7SR3HlHyKd@kS z@pwXBj-VoG)hnMF0eguduke6du(W`Voc55|Eh%dIV(<0|FgNYO3IhEFy|S6kTc+4# zw)wY0|7AwOe+K?QaFwR0Rb6*%ux53e`2ZK#YX{%!>nME5f>@M2Z%`}p# zSbjITDzwFD;Qgh@Y_VIg12aUqq%F})A1!M2oGOezmSz{!e7N|qPIgVi?t=aYsF25n z0^U>xu59=w8E$D;zI&Z014r$s@6qqNS{ci}su*K5N(R1tVJ!1cgb%*muy)R>#g|R- zigo?N!`CxofLMDmb)K{#FWK#C=-0bY<5xRoFI+K-E7&L= zeUGIWU+L=qdGAA~^Ct_sa8Zk}6nrpFW8Dc}3s?V7^2bR*9bANArcss#9|V4`d0n|y z)Z(@PCz6IeVn%43Bg#a=s!TfOn3$fPS$~gC0ueY6uQy8}8ZFd=Z-OHi$cX!|qg<7- z4b6tTHd`r@Fj_{1la3E)or8&j()p6j*UMwGxyOqR0${_!dtWTn*WQi-E7bXlrIA+0 zuu;1E425TU&yNYry$(7QHib$#DRTRqh~_2Ey=yUnBDpB;IN0wLvHPz?1xdj6dAi(A zq*@MYG^@Qwu-_uhCy?57#^&Jm%_xo*1?(+KvtGPy3j+XdF!1_O7^4M;Di-Q}Ge0_x znkGc#|GWSDwEX?p6}Co55kC$RXs{QCHCY!*MPKT{$kf zSI8(<{^|nbk?;*sq$JQ`U#1t=80v+?j1{}Rv$88F0Hey4EL4^kG>|v)&p=Qo$-Wx7 zCC;tp=P&FPd*$?k7F@I|pMF{OKu0|&JNGq$-b8A%&OJU=y+}=oRWD_4=lhN1fDwS# zk;HB_z7g-@tyh!2hThK#zBW*=^X#K738xk9L3Q}KkyXK5jwbG+T*)Gpx&WWtPB?-} zhN_$x;)|#MgbnF=&&p>#qN77%w-8~AklpW-ojZ)1*KIfvGzpyX$7bWjo}nIj_-;TN zJh^S8$5V9)w8yNvBPf-?F}NQI>kZu|_B?{ZIKUIQxdN8JUQei&Y}J{;)Gg11U*i_n z%mf&<|39nzM?~LD-F3mJ<_?3K`yKfVRLhQf?kxcn<8!~j+zW#2XfU0oOqJ*0e)rS& zEKylm&FBiK9a;+aBL@{C!Uc);afPOp)vU1(y?Y{kBGvYHWu+4o#ChK#*A^3}!99Jf zXLnr{s7VWbbL>s_{l4LP9n=bDV^XAcbVwFrwuMqKwdJ_NWpsUct`f`Q5z*@jBdB+~ zd$j!ZT#@RpLvnH0Gm^ zQ#6=I21##BQ5nna_IkZz%TE4vG6{MVkn>jmNP%=9_~1#r$A9i#s8rC7T;2)gCHm#g zH@!H}Y`+30r%XQXa6l}8Km*D_N%(nq_7Kk^tKMFF>7A5W9x0qQCuL9J(9HDjmiU-V zi7a&P>M91Z(y4IbxK8e!G~Px?YT1TDEUhS4^Vz>nRJ-WY;rhTjq+v*(%}za)FrFZb zRdEUSq(90_@GfvYusGCmmtQeL9;gT19RJJo3Otx0LEJfRi0-#Vc*jZmj3D;Aw&;=) zk3%U&^n6VQ`RX>wgxFO(807iwS>3iI$k@MMkPAjvi#}K82 zfo1p%`7A8o03v+C-}W5$lfp%SLpW{>zL9MgmL8n?uAv1bnE7y!x4d@7dvMzw?!j9# zVy-AQnR2gm#1ig`q+3BPcZ3Lf=EQ!%>lhPloC9LMJ;ul0(Iah;=n}>Qz20c~MKB}K zUBE@oJQUd^?i>0%ly|7UG}CWvMmX?+*#4#MJMck5rv@&wKSevKE$(pZ&raexbrpe9 zk7;vo?+YuAai9dA$0d=9_h%p_L}}>Bl9fIhBXvF|3j-bxt@2H$Ej4y0cn8fL3M=fj z&!ea(3moH&WbwUlSDj!szq@?nfzo#d(EjaCH-9^>Dy6q#>%@a;DMe{Nn0SPg>7lx3 z5=SnJ$-GLv={mJhe6z6}to#p_VkN{;n!MOCavNJyf6a>BS{BG;c}uv7@9aLGjTIq}9(HcWssso)ZbmThlXW*f@M=;0&wqyj00(MZlRX z#>46rbiV>L=|Ck6V_bBp0kUw)t4^_dnbllF$(6~owFY&ViJito*3-VAlV zJx=UsVU>;~WauTb8K@9152JaQ(^HyPZmHwj+^?P4dvDa8R%jXvJ4NWkz?k!g+GVW> zX8(Jr>)+VVN!iglIF^4gLe=lyy-?})wCbF zzw|mSw)>&NbQpMkBDnWUnb}3^^ZPtnU(W#v6nf*-O>|7r{jqJ|7UAFc87X)Z?Hog8 zq5k0Hb~Nq>*d)F=stD5-%|1d;uKvqP>xpalU|)_{%`#v~S270kc{8o0iPsvpDkTw{ z;eAB`;W8_$rQ&$=kGgoj@9R#}bG-YAQb~(!WxE9pe(gAy8$G^XD!j9r z9oM{TWxjSJzI>8dMvG@!5sA)o>Qade#jr1{7d^rf2e{ubxnA;KnN>rcZRxRn?BP=r z<~>u2_PSEek$inf#A}_P$ zTGH82M2V@NqF^D!(>|3O*T7Pe8`iV8)@fb6%Ku^}sZ_*OX8}%a!*dAkl^8FF+Et&{ z39b9z+%%vDyjeyDEHXqKop#Xm$}TIxb(n)->p z8AmOs7>15aM$MCw#BMQ_VksYbJCu^z{P{~y{yM${gvDuoVfbv>Q`a_oq~9q61#}>? z@Z5!Kn54j+m5U;5T=up&JJ{8Q&~}k(osp0rmoC5DMT#%i_4aYlQt3q|Bwf!WDPzN| z!5;L{`*MiVmr=+jThXU#wvM>{=}cTeKy9#NlC4^=w^FCteh>K5sBj^f@KIR=u&q|`^z@`B1gHFVQXnkt zYnubI(K|@*2g|5Wgu?mfq~&A2M>PsM)n++D)f)#Jp23>DnM~<;f#nC#akb0iIqiPl zKvL3f%_v`PgP|5&-by1OH~Hj-K69sY;-Zvrde?f|4gL*^C%XbSTWYJTNKwDq?XBOl zItTxL66e?z$egzksScasq_?sd#iV8*Y>SEtUM;&2Gy$opS^!Bg32mM@4UMsL$Vu%j zTkJv*TW54S?9lz%ivE7|N)785-@Z22CpCKD!JY?5sJq2W)}XU%VaJy3F<0>55ufON zf6m@pucDqPC)_Qgrhof`Q~9!1)lcWvX{?LYN?hZXG4p=i8hl&2 zwMIxwysm~|$9fvce68r}Nia@v-eAYr6|kL>{=`Cgb0Nn}()g)hKIdMbE$F{Ule7N9 zm`*=vYX`$4rO7fRC5&)`dQ|niM*y$GWQ;tEDM6PFV+hUf1)eE8r9%teRTRK@*=3W; z6&HmBGR~#>e{6Zr;8wGIl4^5DTx0%_dcp5u!-Ild8mOp+RL1@ae(8O<7mF9JrCc%D zdXI|r{XLqE!t^|ebqzgCue4CUX6nTKIMoD@fei-<2aDE<66N*dU2$=9eZ`D!J7^t? zy8wk-=Jo}LE>E*5$$}hW4vQ~IOQl8xIvRsS-af~~r*nbnay-@5sW1u8tH0d`y{0|3 zEwH_r;uOwZ=Ol(>)HW)UK0d-2!ovY(y&v~Q3uBg)JZYQ^gb#1y7 zqe8laqmoK)uAYx)y|xLJ#RizKAk(&V%bvr9*fWnjLv zndb-d&p2z_8qC7zYWl7{bDb&_zf<-4WBZWOW`>h|UR<$WrFro?MqsyM=Hk%!?RUFl zBX0{etnZRc+5LVe9>K$!Zx+=uKUtR7QT)39=8bPrRbGj+#rWPOGL6>w;!OPQz?Idu z5N<%*w6AEicInVx(E(5}Z2i(d8!TV|^0e-#TG_1L2M(@AvPzYzgyl&!D=i zlx?r%6(&e36_2S8hwXCmExOq7-VqOKj{9&ndD4oed!w$N9>iZrjfH89RCYzj>)6+> zx@BuPwJ{Ah$hA*GeSUyA3g)V3adXkdm4yM}qL(6O0;n^sx!9AQsIJSgHrm`!-v*OE z_BcSXdE>r!vMjbVY=?3=Cw**_3&PD**=$-;&+O9CHKG>lZC_Lz_NXxQ#W%gD$cG7Db`n{07!{*Z6o6Gn|9)S@$}WPuun!t-(4 zi(e(*%VazOYQdn5-&O}|A#BwD?|e4pRR6v@>$e+};aTmTWL>@X8I80A7&l_=20Pnc z(5gG%@?0nN67Jh+t7kZ0H7UhO&V)O}3XIBLqj$bSx-OQH(g0GR23omiG+)wMuvpwe zVQ!jcQRgcU1$c0+LhG$n>l~G#{3t;TAhk4hnrM&ZP32M7Jr((P4)>pe`HLA^ryLTq z8c9$O{&pN6HUXR__YRdevyEP-Hs!OWqil+tp?^oNxOZ9CnnK2y`X!G08v5EB+y_;I zC8m$bO@}>Nv@p#T*Cp7L(Gc{}))_0U(jyH@zU*E84S z)*QXmnRSIM!eB5 zsAiOA^Y}eRc-mzZX}c`QVleX41lJJ<2`n|{q~^4teyw%@bbP|j1#3c8 z=KR*b_V`7pI<+=nnM{L^ot7$*pQ=%~8pCc ze0jQ7GK1ch5jXN4mmQ1)BZ28Y#l3n>i3j%y#0Y*Zn{Zm%1goUDZNOI0@y|cen{*R@? z&);MerjCEy5RF~>#6B&$4JOwtzQ$r&pTF7v4*3rUQWh4u>Q*j(De|8G(F=^BRLSFc zu;Ca<=L95@xt&gSSB4bC_(-32_I$g&t=Ar_zbT-xMdL6bFKkqsQ4&77G{{*7`e#y1 zPM?vh%E66&roSn$zxzB**ID(z@}uhw zw_o{lI-I=YZ9p{GRnsrMrIPy@{u+*Cbp})+!_qsq7veC%ea#!1?z)#_q!k;3(xQ`I zZri`qzHx(<8geAnjQSRy+cj0X&%MHb)X2@Ehd5QK-W$pywYo!C1DnvDgGPV+sZuUU z+e*0{oBX&LGXH!Nx=D~Ton^AZ48aT$t4@nhC;y1pnQdTV5rpI?&cTb3@J~DtrK}9g z&9Abv$?!7ABDc{2I+~mm9EJD4-hIYHg8{aww>D$_v@Hnz~vmis;em|5SjAQK> zk0Z!jUjmUlzWD%8<;;X7Vmd1*eYKM_WVXl=(L3Sn=IyWLzrJL)BIZ6}Gwt`S>@(2^ zFO7ytJ8LIWb;jsV%5%L#f$R^As3K=f73Io@nnOv-y8`nzzQFiSNVnaQ5}OP?`EWd^ltjgd`h2Ya&BI?IvvzZ zFNZ^p_T!eeOUx6^pL10fC_$r?=bcZCn%S_`6^7ZR%LR8~p)Gyo6746r{*@(!Z|udv z5S+=Is?d5Vp}y^hliQ1~9fw=4XL2lDHmsDZbqJ2xy}Xc7YN{`i`?YqBTH?uTx!6UU zmDOMECI-X63Pb%K=UjMxFD*vRR=N9pN$KHn`^=%3)wjsTi#8PfpsAh?RouQmzkDnx znF{{%KYsLI|EO|U7fJu#B8fP8O1nGKl%X-c(!mMa!AKZ-y9 z#;1h&psGKpg;#U(re+Ox9{q(=B3>&?>tvYvO$2n)dnQV_dUTcrW8#36B2E4f>74!f zxAbtDRuhgl2MPCkdG2CIHW6sp6)wR`dM<~dQPV0t>pjoAk_+dTX|{oSfBd9j)8Q9& zI$wPe(1Cg$Y!KFlX=zTPy(XFsglvH*@f629{&opp_p`HrS&bD=}vL zh$f9}!ZhKdt2}0SUrp|r_4%qniQ0N4pwcN+v``l3wdUR5u&Ti@DR;3FMtb=^#E{m7 zVLkN!sP#>SRb^;CS-cRRxxU=$nt#p=b;v{VBT6^CacD=yt#}5)<{C! zL_{fLKd8i)zyh!n`B$1O8+NyKp&T9{Ne-~60I*y<13c7AznYUu6hz6O{Wpve*H5+G zz_?TfdkAM)NZlmQ{9Y@0qF)aXm;jeC;r5ohZ@8;Ij^vT&k}bkfG<|r&A6W*@30yF= zx8Z3%r97x%rUQFs;%tb8?BR-~MyivtVJy0TI?Bb0QZQ+!NwiONnh4%fZh+szpL!Yc z&?PB?QAa&yC@Ob-bGiBb%edQ~2qzY^GieFbpCO&0JG)gTVG|uj&MA8&MJ*tCA^{U` z5;6LGgXZ~E)MC!ueTylF;0*)M8GcTRqzF^L$VGxx^NBpeps%)>#LgtWKn<UJ?7O;bP`mI9Ydhgk zLDGUNch8r0Ek%&Pi0*`uA|*m8{XYBh%A+W0#b}pG{#<5Q_ce{>$$8Eu?nfBs)}8ev zr*a>BT3qsD9+Hn}%a`nJT{u{$MQRF+*G?Q$2||o3w6;O;{%R{4BTAk`lJ0M&XKeB6!mG|2zk3T0<`cjq9%rm=sH;sE3_}x@s1orFhoC5DM)618m z^`xAqd0>v=m^~D6BOc&?@j5W`(DqE%XM(3mu?}tz_g}2JvmeYq2ws zHCV9Su-0PUL6CEwvc71$;d73MfA)-UN~d#DKa|6LcdbS0BzwRx_ZZY@jOvl0&$D)f zC+VJ2Ss%Vkf*YOx6q%?#aS8M&xP(*Xc3K8Z~z@s8hf@$Du<=u|n8l3ohojMOkE7dKST zQ_B}>+FG-MCZFiJ^3QpE9+J7YvRqms>Sphg`-+d1%NO6>rAAVtllPSe;Qa(h2m;LB zUujVRFvs#|n#r?;9+tJ)p$2j4J@<(XSnsG_J3pp80%k-f_)}l+2 zTk)5|4u>0Wv|u@ItB1uu7Ih~bIE?dGmcA6_=O?;(Tgqm`trlOF^RXPi+b%lk{3TYD z*-Ijr=vqC%?IwBez2sD(rd*z9=J(Y#Qa?~F`5-mQqqmSG-#vVQP~Khe*6iiflJoG^ zMtvMkQ64h<94~4Yp=S{q+3z9xNr3dMgDlp$tL2E4PnNhW_gq9_1?6nC=gwu9J&c8b z#>6g6YL=oQee-OOeTvNv$(z;_U*89Z4JD2ZNqwmU5#Jbu9$nC zEG2l@_?H`6V{gwn&F6v%f)aCC3Z{Rl*oN=@NUzrOMVgvKyXCj;acDW~vDcmDh(*ju zUK~i*k~=k*%HY`KKW-{8H)8V#!w2IxlG=lsdv+xu1_uOj?c!P5Cc_Us#+r_zMAK8K`z4f|DVs?$WR!dA_-IalGZ_yA}Y$%E($1{uNgKuVb8+ zLth3E-#+V=*NZ_{OMhPaEkMH6-kL^%*Wy~M;+-kW!5(cgLUHu?wPyzfF!o!|J@qA1 zDkXcmu8vGlS5MiOL6^`7ik?<;*nYd)$VS-&ABXsH@lBG;2hVwMLR3qTq-pi2Hivg% zKEOt;?f1G0jetLnD!&nJd--B185}Z!c;U~q1RQm5;ppo%Qlk$|1EV6mq98&c4|y-N z<#))V=6w5l_o(}&50en%sC1QbWb}QeGKMB!Ufj_#e~yNA%i;62x_aM%H#(;k&USP%4ccPum1B|}fS(qCj9x2_7oJXX3|VT{uw*JO z`X-m~SC2TVI;;=K6O)~fkIR+J>itEk@^0&NJ>ZeF00;A0b?;2sjG@+<2%C7o`vx`| z+V`)8iwnE4Z|lyE2!wh5+iy>(nH$R#BT7qV{@T};D2dmf%xl}=kxCzb-5b>Xa`Gmn zDK6Qi%w8Ts#s-m|`KUl-X@<#cBihimwnHjCYLg(>@W|G+vxXiR>@T8?je=zJy3(QP z8Sk!$>&0f%OE}q})b!c;L)_Bc)@#> z`gK8Z5U}mY>!=xpBkby zdIB!Yt_&nCZPodGFYFTcz8&B)`mW!*IeG>LiQ9%qHhIq=ZyE8exs%q)UhLBR?(DkP z*;)zUIs>3kXBz3CG4pkr7fdg zZ{@KNwrJx7&+~8$N!#Ti5cX*+%@^s}6{kVv+}6fpbZ<*Sjp=w)SCCg736qzaoOd67 zu^MheOTKnCl+>8i3i@pc=_g#bYUX_$1n5JojaOEYWoR$Id$-cwF#OzYcv7tE^1So) zUTUeVc+Ns$9tlhIEx>}2_xGY-{}ige-xa><<~niF#Xr}+1%4a6Ugtnp*9uz)?e8t3+=N>j{DtP@O7X`GtOAzIV<+pnHDn z18+8PUO)s)BY13XWX0(4~>15rE*A zZvNnyLe15G=1j!O#efTj%5FChPG$T33*>jMKwl`e7RVhCpPb~&%I_9-nFs+B-b&}& zO8t9LBep+?a?4JM0Nuh^ZFCXJtNX)!N<0A6cebw{Z`p1N$Yo4n@O5UPkjQXX|}RjJ*@$8Vb20`Y2~xca8TKAv#wXV)*!@ zY0}>*?D*=c;C4hy#0;x0^BS=~?k6BsAl+55yYKxX_dBTrlqUJeR$a@RKn!&`3-^Te z>rF2M3P)T0!$-QM%>Q9|-qWf37&IpH{dA;+o#;n$g8mHhjRqe;E4vYV&u3@adSPoS z(T~;)p;cDoRB!Nm0byqR7#!?<1B81rZ#ZH=_)CQEw|o}pOo`g5V<1xnyeDXlimk$a z_~dcmk=ml9p6K2A`p+DyM4-U7EVbMu9tn}x-x_}5#J_F#xhwgGu$XUp7Z4v|ej{C2 zUDAkU{kR{r?>8XaH`AvHUw)CM5sv-q_(taTH+qFdfRiCVJN{?ws}hfYe*6>$(9LTJ ze`g>J(siK(Dqtrjh%Yz2-itVov~Yg-HdB31Rj7)@rw@cZztGL)ogfs)?0jv$MoLP2 ziu%miUYKW-c={91Q*Em0EAcDS(*F1HwMl+S!h|cJ*!{`z`+p}2^@V?@j-k8%ef*hr zC#KNjXZ`H>RayZOKjZlXCj}AXU$^g0@>wq|!tUw+>G7AY5vPA~`=P4uQ%nkqFI3-3 z78L>ZTebB21Fz%U!Zbi_PP#oFw?pXv1)S^u#Ie->9mhmUKj~ckg()YmH9D=*9X9vX zf@tsg6)b@MvJoA^909L(?uUhLZ#y6?Du{~x)UU2^{3#i|K+L9C(W!Tmq7*PVX}o4N z2yW<^?S4e1Ai$tRW(Qce2~SAXwSN*NPO?@-tq^8hfBVKcm;Oh~rqiIUu8TVz(HtwN zloG-8CLk6FL*UEk!mUh3;MIi&y;lwLwZhW^;tOjAr#PXA1F&m1e{e>LZ}U9>0*%<3l|(5VExO;nB2QE!lsysH9F z^B>1LdcHN1;*423&q&-7>Puv#e)e0gw30OwR)_ulTfRxD${jbW1_Q{x_O<9OfL1+x zjern2M1JY*TGvI1heE#&w&N!<+;e4}jFQls`SE>c9s4uq(fxo^dLMTNgHnX9F?YAR zX=*Q;jN-BO`*ar=NrjuI<=zw%x`-NWvhF8A=nHN5;nXj@xY&^kF@WdoG-Brxpqrbr zJaBT`cY$uSIj~hy1n-d9o-X;R@QZLy`bF+%&K7?#@yO4X2nastw&osz zhjGGNO~1>`iBAU4`;M*^Hvsg)Gh6qdcpL!;Y9zs7J7&w0WKqJeEk#f_3TpKA7x({2 zb-^nH7eTVO$>-pobk0405-S|`{vt({l0V-6+Gvvzczqv0OA3ls-#MzfQq;9?WpU3nt4Cf( zkiBo(J+TUOH!54`$>no@X1LTFNkbJv{qzsN)Gg>V(kt`eco5LHkiY060; zE_hVmTIIpxu;_pW%~sAO;MAj*@EI0-W@%n8N25=uNum7(fkRjVU0nj*vqFgZ{gYFV zI`lsV#!r(Sz(1)$bRp@)j#_?OiRVO9Zm2P&TB`D_hzePKF7CJg_;|Q~{sel=58SsAC1gKXJUhIy_yLL~!^roV)tS!OkJF4&`&q63? zKA#tbM=q%8SMCiKK7lCO{kv4K`s(E1>F+z;!6UOT4kA99>J|SDF(9GfDa?FCr60ZW SN6~NK&+(%+M{*8dxb;8FjnHHO literal 333205 zcmb?@c_7ql-**^ADoUuVC1eRDAro4VUCF*iB5TOLjL~Ve71@_jD%rE|h6-7Sgsdam zSh9^}3}fcKess?JKF_(|`^j^kzjDg?UDx&9zn|~&R9jPd|K4MJckSA>U*+1>8@qNf z!glSV4W!!*{$`emxdZ$`<#t2)@~)gVj;UR{cy_5=y>!!y>gOQ+fU{1OG?_Dw&*b6r zvwUxZZ@6>?-?$l8I(WlWQ1ON8sII9{=*hUIb{3~&@6WZr`6AMEx1H~}gy5B=1Mc^} zQz*D8?_{jmMg_WaDG7}w1XQ)n5aoOge6tB=zS-`{J?nn@(Y2F#ny_?|j0^`BH^vuAEPJe%La+ z*7$Jnh#u0lYNeuBeft#XuqJm4gN8GB#sBd||MfJa41HF#b?*zq=+pV@nHCn{;-|hL z5w{Ij<3yTYhk~QdBVB94v9!o^n(4p`DF@!uOe>Tf*w??N81V1t_FqrgCbGBGjT5>!lK`Pf!q3(>o zQ|dsN0x$ASbr>cg{p9w+H72w|WJJHM$d4ocgRK1R&5z71#zmS%(_=-Fa?7VPhzFH9 zUWl2L-pg_OV5%HgL&qRu@WCQuzkzj>ZiGeiWnY(D(bgT0zSHe9;z>{CCG|C4*gmnH z5BV|H{Z69ztt^y<F+D^q{pO^svBj09nFb+M!|X5d^^svQ%3Al7=D94ITfX6Bq&c9 zaI27@F&2W+g+$ea2P~(;`<}Q~ys+-2>`U2nRijo!zA+2y3QiOMMe{_MP<>Wi-UG}I zna_0OD6%9*;94%4yiQ!{F_%wk>=r$tU~v|fQ!!UgYSapFJ>(}d7=1Otl2`l`@{Oiu zegFHH+lK(g<0+ndB(J%c@ARqnPb`dyG_$gSgY%n&h@nzL-)-fJtiX3;50(CS#E!R> zc;@)!enP&c!2U>k`ujZ3zbWSm{Sv2?b9$k9L81SXCHjAP3Mo0Sz&$$`*X0{(r=!e$ zrrzEO0fLcYjSLp6mJTmY{T>Ze`0We({nlP4u!!>Su8JNfw$BqUrhe;^5jgB}bVYE_ zuPgkX(LmB4@=}eqW@Hmk=Jpy!TFKIz)Y36cCe={w;dl?zbLgWSxJ26(hQU1M0{&_zIc^KIs z@reINdVzhmKE?fqc*GA-qc#R`5eh9L%}(>mS0=b%s?;hMIUake9o;sC$TrwB$~+5` z$uSvX)Xw;ce8uMF;c{ac-zy#H?26U)do=b&v(Yk+0Efbz)(plg_j} z3Kk304crL7t>Xys#Y&ny?WV{#2M&<4pVMp~XwgnxN7>j*H#b+KX17CIuxvIQQ>W6g zgu`$zb2t(N6fE|^L@R#gpFAP~ytywnv5W?J6;RS@!AOvLn{4f`6c#Df)IpIhk>)$} zZbzt)#^80%RV&>G(hMpR0sXxLKJAw}SsQB@Jt$5+`${A%M&ZVus+eETK#oxSX<^|# zHClIfc9eQh%>(c*M!B^V!x8YYNdt=?A0KYX2ZO+?OS<*14*hGMy{~sXyHlPqP*cBC z3NWgmW;&utMa6cyutsz0Z6MiEI$?L&i7h3gVHTI09dB3b+bMgD6l%WJyi2V(gIr`~ zy4Nu?VZ5#ZTXr5D{CtXYiygMcHEV^9la04_XpSF&FW>C%{9>vQs31&DE&8Z@7WGHV z6xPW5deZj$`LETi-9Pjwu<6>4MA*WQ7N)Mz4)apvYu5tQ80~inxz@Psyy^F2FnCMh zLIML9r=En2+>ZP${o9s0Kt`l06_pOJxQi((eaP#;z~H9yJ#A$ANvu-dkLNa9&u_m% zHQGtu|9Rl)4!=CdKo>jx;}16#=Gfcd&V$Y$-hPh;9E@P+u@>0kAPaSUnq%nOMD-mJ zBe3Q?tQUD(WN#y3!;0-2wRgRKyHPGJ0E|jtGN0H?lJco%!pbzw-mqBP}cLWtS7OVM={=d7$e=mixtl-Osbvmts zYS!rKO4~8}3=}Bm16rRQItYbT$S_!l)*ko;H{TtK+y!vsu8xE?=41Z6Y%ZS@`u4cd70D_ZR$IaJNqrsL3CikMtd=tALuEDSb4Ulm^tKDxmSL z))vE*)N9thoqDlDvA7OV!ZPx^bxh5Bh{oeNw?yzc2==J@%W_*pRX_n+G+2hDG41Te z{CYt9Q2eNh{YVvNaN)eorVocrDCh5nhT#uw5t$#z+o!YYk&HVe^27-qi;TuME|2M% zViSOpl$~qLnR*RG*(o&O@aCyTgxWiAci}G05IiytxA3@gcr7NBE^__c^ z4!-;|S^)2s%KSD-EDB*T_5FkA+>f3R=K{7!DO2Ler-5l~eX8K~ zz1xZ{36$gv$D-h&-_eb~eg_0&K;(+1#t)rPNIAtbY#HPe@k1nooV|8={g)!2w0ba= zH+?V6a_rg8goBEjg}U*Lt=nfH2<@k-sA^eG=a_CDZb!S%SVte&y224=aO;2rbpzXW z@3*xOglKfJ$08eNpIx%}4uhH8uPBQ)OQ2paxn+NN?D5t$_Za}Q-`erAbBDTpLg)8dI!7Je6=Ub$?|zau7!%K;}iAsshh4Wl~; z>7X2E-IM66lO=`e~hNlKA4whCF#O{4=~>8@=9@t8`*M zHCkn~lPbJzAbE$k2!lm5;!@AQG7g|;I${Q#1ZPpJ=$r|#jFqid^xgP*N;4A=@jhpu zn?vw1F%8JOjdr%}F}U$JTlH_HK>RK>hT}DLxPQ$zG6=$gRW%WVRilvQ`UQyybeT`>wbH6+;08$TV+69 z75^W?O{Q~LpDxN?x||yBAEu1*qoD;7Gl`U*E*<{MMhp1Hoc+^IEBmm~Bc z<$6%k?$3JaIa<@*EsILtwjMu|ediiuOg(y=?jzPaQRgcve=M3sA)<8k8X2XB14-nK zd1o(*3tW1sg+cytN@L_hE`~{L{i1c-Qo5Mw+N834JYww=cU!ph$dhQ*-dwW2!acQc ztJ|9EwTuDUy_nq6k!M6Kd9~z)V8bb!n+o?llZS{nlzi76rHWpW(h|FYp`Y<{W3Koc zf+1=)eeqn3p(nT9&2I;*HSZZjVyt^jJ0oB0;XDGDIOsEtlh&l42k-yxF2Um!D%t&o z_nLc-v986X)IuK?CgbG$*i($HVVnVLKUDlrzpLtZs*v1zc#OQBY+_+e*vL{G89wb; zLXrZ$Rnp6_|mqQo2OrHR&rZ2R$m zvC`2n_OB-4`o%DqC(gSXAC;S!-7J9ebM3rp)Au0`70f2)F6iv{mcO|jaIeCe9N=acsB6%?ch&94n zpVC^S5Dv#*tL{)@Z|&}}jyB{s_h0Fx^O3}v%=7xwYMVdaa{*NJs( z=J2$Juc3j%R$(%CGzoKcinv5K%^UijeRtFRu>J&%RZgGDS8mnrS@n7W+&Ck0#eB7_ z{Q6|-Qp3eL7s2%jG40^3npFPOBbf=>^bP(GZyEN-^fp-VT8Az zpDLw=p+{J9ubG_qFappxjn!;`TX|=lgvVqjP}NEh!dZf?BtPMO1DXWWS`yE8%QuhD zUGbe@{luGsU@s_<)sshgr-3B0_Y-Ht2znv zObhrp=es_YCa|KXa1ZxxQ1#Y3F<}x%az|w1zqQ(bca-AasDw4D3&j*o9 z^B~gK!~XS(_*)58s@laC-ZksDQF^M$&9!^D2hLAP)55SW4V=VO?#)TV$hR?O7tn+u z-!#2Gf6^$oe1$wI03V4ebYx*$KEWgXwTiqxvt%7(dcJYA*=#jmW*i7|hHd|&@=MWW zIeS4uH2cu;Io6ijs%|~b(@5bSjmYB(k%draKda&}Mbm!Q=F@3k%kfRZk(gIZDyTTClv>IfviG_LTPKqT9`LJ2ToFk@Bn0@* z1IZ^9c4{_TS$ER8ngA2AL}zE>+Q^qyy~`4aZ?orsO9Q-`^aH$jB@s)sZP2{9^39Jh z=!rp*m(#QcZPMRHH|d+Yclo7;o^LY8N5qVwHhXjPhA{oW)T|tQNFQ?MNs0; zZFEuOa55Mby!+>a%HPKLJQDp^dmFvQ{HN3+mri_HexDlFJ%vkZQYfv|4JH5J;l8TXK4HY18%ov~I}$AUTGZh~?QWv5 z+2XVG@`W_{&GhRx8uK19u<-{#9^57z0ASLT0i0Y+LxER|6_}8cF3zldeX(X44dK6tu1w%I7lX}P z=Ft?g%wSH>l=3@KGzp(xP9)*v<-?0ll2Ye#zy*n{#ttv$ORxbt)+U9v*PE>;&+$lC z5AYAYP4egyL^SCnpVggzefnAP{9P?yBXWFCCBOXmOC3C5OvN~Szleic-8(Pi{2O1+Gl|Yj8As~9{l?(^h>jqN#!59^o;qe z*NGTJ^4R!DuviE-;|+}L|ODlK_~%lGFC1Wp#)$n8D$Vl4g=<;J4OBd=3@ z_P?FMY+J#72?|-S*J7SMZEPHy`MAhX!Eq#Uz^0wK(AR|mT%6(%FHgoo);ntM_^9+m zG@Yi`+KjIcRIR?`Be2bqB@_j>_0j^baQU2L)u}&5FdRxv?ubp5reX?iepO)SY{c4n4i9 zJZ!UQ;O8U&gkt$k>0Wo37~6xW=1p6evq!lkRgKEjyr!(PQ(B+x&)KdANm{B!zGMRt|QX@5k zts)G`vV1<~UK)#1LXB2kSp3Y)KHhP-h}kydrShvk*U@uy1$zP9I}_5^z;kO%rZo`2hERwaw15$5NYO0eJ* z-tCN~eL5z$nHVyd>l;PmWTjha<~T@4SG`!zo|ey+c~wb4Jae9v}PH=m!1qd$2(ai)apSU#CxhN zRta{DwS?|~=pJXKK!QmLBZ!zAH=hxlmWl2l!n(QZe!<4-g-rv~5|YTV@d_^yJ-5)| zMWucd>L45jCBLF5UFTc0F4Omc?yF;QR5Ltgoo)1|0bfN|WfaD@zkf(iDq-^g@cXUJ z!uBys{gVWP^fLH6QMMe8pOmV3f9Gk#DE(Qd`zYyEKpB~E-H^w(GQZ4BhUSdL?l6Hv z?k%i%X6bThgVr$GvFFlU@ZJ5NIA(Kjx4uya1!rC+_aHX)@qU)>`6JJ~LqF8>@pv_G zdaCa`Vf((4)BW4^Mwx^67ryX@ztpl{^A)2Bl3&dW=OYFy{Gk}kD%paO<~V$><5DwR zE=JRVvYM{tpD|Gd*~19L!9@U|G zyVCan*k&>8?MRIX`;qmvh(GAQhWJ80Oo#Av*GG`#yyahTACJ;+%dMDu?~SYdvlpN| z-uUYC@7$npn~unfxP8VvuY9Z}FAk-PGy}0dZ){O4nm0`P^*eYTZxAXNr>I~Ii)w=% z%_;nF}tF=*3XyG48dRJ$SE2iot7@;5nF+`UKow z;jHH-p135>iR)Uyck9?ZKYQ`%bvarGFRFU$j;@`3jxV0cso*C()y=`>L-CH**Qb>Y zo1?wTDFl6B@zc8kdG8h5bxlI{e7|%5%(B*nsW_@W+u2{30`i17%4!KZ z$!DTtD66R3ND>FRsr}9EP6`WA`etzrF-H#1T=ENOR5Ob}`QaON9NVF+sEfaD<7n;L zxSJH#Z|PladQvyqwmLqWW+vN4M=OM@(8t_(M^_>j(g{c8*!*qn-dlNG(aQ2cVI zzuvXoB}+uE)2xjo5~iEE?VzUR($>B{b?s++mv`ts96f0q07$Fe^_ZJ9yoczE-57#b z!(RX7x>OrlJSp|8=Z_93hU@hQJKU?uwca!hGNjS!Zd^&^W@>{5dQ#%IF*MJ_7uy>iR^?QqF zvI;a^2RE=3a(Qc=@en?GY+x(RIsTaA>w+Acxu1)M_V?m`r~U=C!_})rxqJjekP*yG zq(^{#!KA*COX|Qp=uCAMh!e1_`@I1?@7FMc`Y=?tcX6kM$ zUHTZ_?|GGVO>gR!PMnfmpYtfDi$0xuj+CKal`%J6_#&XIsTs(#*|?)`QUGi|=7Hs? z8dVO+N}5QY+m0|+PiZ)-{``1``tywAEDWan+|iHz(qiw`i^PubfSY2(^i5z`1{}o6 zEk$|xuBq9b>z<&1dXgBjp~Q3VjChG3CBdm&FkH+nw$X}Y;?^peX3~sfMTnU*BRfKi zGhBRA35!q+8Iks-#~8cb4Ii5IG0yr3cOI&YpE>cRWJvG8XB7SJFi*Llz!}FyTIF$z zq0pUAcj8PB}|a2Q^dW9@M@bFwq($azacONgJB1B1U7$K3LL`M{_`$M{uJ6#MI?! z^MJ{XWd|p}wRLCWDImakZ}>t&FEQbdY!l~x+nB@)X4K3*Xw!SOv?{)Z^~dbTAmm}H zC_H7Dt|ieMal*F9E{1j_!{jMt&oTh$cC5e5lxLgrhjDJ?f?pS!8 zE3>m+wb^a3iE8kAa>nVQSFV9SI+VFh-R%bb50cD8oJnRZekSTX^*Zd%l`gJ>!Dh>^ zM+6H{zDeXZ+4;mVUie)3Oiu5H)Vg-H2Z(jEeSKu9YN3Q85`G%M5jw(DJsOqwh8I3D zYUPBMAI`*e_g~0HoCy<=qZn*fM9t#lDc-K8Zx%mslRx};TeXiatgG=;hCwu)gR^z; zy2*jzuys>sUw{z47!a5{n%RqTYm-?KjTA6!e70##A z+4rZ`TwQTaOZKtD4=LB&mFe6z+$k@C4C5cY#n#@8)c95btvw=vtNI=sKCO6 z6k4WCPVZ87NvNB`y)02g^XZar!an(w;RlSGEhpM5hPpAhC4l6KV|`|_m-e6kZed4@ zg&e6_vE3?^E2_jLgI+MDx0LKtS~m{iA^%;n_0Gc+gIwGM*=EX5&=KA&NuBH68fx1ImN!K+Ya0)i+v?0 z_D;Z9HmdQ1hc~lqE(#+?m{G9}dpq+o+%x-iQ0w2`B!=oa zho5U6pPtxT`kI3NT;2>)jpA;83R@_%{AtVNcd(P1FOg>)cFlxSk%i0 z&X6QvxSUsC0j%Z)#-Qi}spTU`r&sNwqw-|TuFD@gr+6T=4C4Oyu08|Bq6A~z=ek*+ zzqbJ+7NUF6s;e<0+awv_)g{w~@%|v9X%=qb0(ifq_ft+?VHgF6AlrB?f@OD%8A zpAEN6`ZgJ(QCdW@uD1|MV#(L9Ln$viOrcT9Sca$Idez;RZ7q4O7VE&rOSrwq<3Rq4 z%1Yt%Mz4(o3u8{tliDB4y?iN2ecpJ`vTnRp3JVV(CWEZ~ba>zwx?Q49RhkqCqlloa zbQ|a9lUbH-l1ca&G+bqL)*0bTe3_0l-cMHz0`kb^5$^%7(a@;7-Tg=B?eh+tH!3Ub zU&&4Kd`lXK`~J*Rt~#MHJ8!LU?_1q#LwJuz@mj>w{BbC(YC4$#%&0pW|8XkG*db3b zq9@#Mj5kzszB%vp;4IKol-0^-st6=DS+HvA%? zyfhC&G(JO)&)KNYm3+b?-EIRo_2+LmGb z^JibKE-sq5uenDUJwND4k4wMkE2pZ5~%Iy$6OMHk;>& zxOKG|XcSMfprAmnE3t1LrxS@h?*YsL_FB_&Yy0xhh0+S>&k@^amLXIqYzgr*uYv!rL)mzA)LT1A zp0(#!4yb(X2jRF-r+wklbY`yR*C(qEpot_Z=6(TLcPOQ{?FfzqOYvTskd&_Q6oxgd zRabs>gRPcSQ~}gny@}asC?lJLi9`5uNdc%viK)%$h%J;Ros+#-vc{1n&q$$DJ+RX} z(+Fvn_1YluiRpoTqFgig16H)n%ny`?KAo-V^Et}IQENQT(@Qt@o^9bm6ICq$vUG2V zS>*?0UG8zH7>_o_8|39lcTo1ouU#r=eix=s3uEh?T6W7C(qobCzA>S+{AO>#D@QNu zEHP^4PPC$L6-ZeH9IwO5>e$##093+>?oj4*zZtP=WS=dWcCMK!WJOPx8y7e{>1;HZ zvHlKp4`xo_1LRTh`wH_$`>|w?8!>tYw;n#ykD)mWfd!IqbVn`7DV7?mc#o7tiM2lA znX{zigRE#GFUYwdJCWd}IXK{xM9#>}iGR6)Amb2yZDat4#=kk}0g@AKjSJbkVe`PN zs`$)im0on~v=!s!uCp<6?!x7}2&_0ykh94m;fuWOMIGIlEJ29X0u-O#57v#o!6soN zC}Yc3e+^iI{5Bl4z4ojS>kNlvy|0oDQ6>(Oz~2S%*{gw;O7F zvmGG~z^lb5Yu|)f4FMd?5xp_*hm(!GpBf6EuUzUQmvm~%@=bkXm|zDC0*$@}))Zh` zJfG^rF`%&#Fv*q5l5bSYe_DrVZ@$q7ua-VZ&5T<3LtyNnx*?hEQmMqs*??kpCXP#0 zZiD9s?{|(t$9Sr#)UDkCX{ct-#gQkx$IL1$YJ57=Cz35tZX_FqLAA8Rfq$H>@hwN(6`p@bP77O!>7r#8Jfe<0a& zRB$lW`+g#I&?r5}{q{>LoKQRTlEKlEN_SqKwOFe#L4p1yEQFfE^#p}AYvjkCUoonl zhoH5wKE4=}vuI#@;?1zLfgmW6lcs=3u6?l>=y8C^B8?5eQfJG7J>?{;h!l)(q{T1>D@ zT;@F^sPROl9TbafO;hfCbqE)@T5i6FDm}T?LSVmCeEY?WhWgVyULCI$C8^{=%`(#) zo(gcn%#SSnNV>_Y(J)!NCVgjRn9s`x@DtJ{y?QK619l3_094j-!+@kKulIBV*=tc| z9sa#I332`d;WRa^Rn!W8dTu4TaeXEi#qGb`K?JNakir0KX8%>QTP<^N69Zl(G!M!X zD3NW_!$}LDAoQd+>Ouzq7)sx~t#UsVgwVjiGV6h#x%53&HW;HW^^ z#rQH0ZICknw-`x+I$U*cY7jO-kG>{A7)${;B-ukxcRnB?eQAHd|3cE=$NlWHIGgH5 zyQHbgxn>q^Z5)k#7;iXi^}%WY$oz}X86M*{Y{E3GCD(y;MV)Q7o>?Yl*E+nM;R{B3 zG=xMzQ~axexv8{c>A(xUn%xb9LSkLrcR#8DuY|*S>h-2?%i<~lYLM-V%?KP+6D@l) zN1WxFbYJgaEwt)rE7QGH1Q;kk=Mp}nQauDblCE43Fg~)t_~1&0d}iWF^+Iz{HEIb( z8WZr&`s@eVsc|k&-u(#5W~BWd79eW^Y$#{H-p?k*0LYV75%^j;5pQo7afr!5L@&$P zU9M!!MkZ~mQSNsQ4%;a$564Yan?sZ6nkFz~k|ohwY!ZXRZx9MZeDz)#s2r0lsA;fh zklqbzu=4)IKJ*-3A=zUhL76e9T-f+*$@jzcV*Eve#aEqy-=CfAA6i*LQ7ZW{<7Zn| z2zM^=CPhkHXb=f^C3d!QQU_7edqI*TkJ9=U{x;f3D4kKu zZ-iM`e?2RM`2iiBXzslWI#}7wqnGLrdYKp1sSb`W^X@7%HqPyYOrjkgYpXb>+1zEP zu&|rm;rZAMu#a=g-TQOrPx7pdMQUl{kF5ZY=<#J9KyHr+i89h6RJG=7AKC1huCx4< zkDT|BM+58D^=7F-o}4$aOixdjTyxw|Sy8knDeREjPI@U*RBQgI6JptTq&qz9T5~xj zfO1KY$?F}dapSrKgWo=n5PN_)Rb>_T*)=Zp+o1gKpuPhG5z7(m^UZeV98dA}zHF|3 zFePG-A9%Ztg2rTSoiD#mhWbXlvziQAmY`bKBLXMxf#TySjKpjhDpD{7k-7A-;aPf~ z&jQq=Q^>tI1P5&lxne|tId@jtvSOE{T3pqC~=z^uC9H2iT8hP=4n6Uz7EQp<{D%uKXS50 z^Cv-eekIF>kLUyHF{Y7vQl9q@F`1CRM!$ayW)_kc>~5!Z-^R;3$L@nh!{6@#nPrIm@Vz=tcsFl*a2GSeKmZW> zkH(EN5-NU)0bzj9@KmUP+PLKVEtM)0sPVpBWF+*u0a+6v_r@ zCI^zU9};A$zr3m}cc_%rH}kf3U7;69d|oJV@MKRjWP;p50yl?S>b1+vjwt`I)FxY^ z%W^!(^RAoR8RqesaW1}@ArDFgObNJ*N#W)9gZyHw~ z?A@x`MEG5e6D^;7?dp+0CLRrUfPk?i;XwLSN zEicBB;ohnFZK{dz&bA0w$=@_U5F(Uf1eCyz&G)g^@Fy1Lm(43BU0B3R>s~kGQD1hkQ*K56>hA2D2KCF3KrV zx<`V^?N=DbXR=GozCPjriE?8X)ZP|3x)?AB^65sIL6Rb1ljJs=1PM|Q%+&9*Eavxv zA+r42OyDrUc=*b&AWKM)2Y%Xdyvz#^m90)zd9eXtt`frN%$HxY@!^!r`g-R;a!LwE zkVb!^C+CBKeG0djw?wZ4fU4SSBPYN~l1DnoF4+4SuD96{Fb!%Li||uQ7OPzN7+r9T zsxI8S#VX?5Zr~ZLNKj`|WAm8?j!sv@JDLM`(~=_2O-Cs!EO;@tO&FBFnQJ+-KV~Ps z;n-fFFV7olj~_HR)0~e!EYO8nTMY^kg*(pBpyiH@+1*pPfyCI1MMlSOF8;-G~mp+XT7k*-tubkZ|^g#v= zBUFoyF%4jF1)!-!zfNGmD6kY>JOE=lLr~v+My-B}1A`!%@&6zUF_kMzYpyy++ zjM0V1nEb$l`QCN(fD$9xxc9w^4PXrjx^wOE-k>R~`;ECXgov5D`B&}gi#umoG(93c z3EWDu%uS-i`m+(@A`z69bjQoaqiU^IMm&n&6UN2%XAng9(j{k683(^T-P6S?=5}l+ z8stvJ%xYZXIx!5ByO|6dnwXb&k^tuIP2)yK+im=H8P5UG;3fl{Bc7j$|=|K)bmCbY1vG)z2{v9 z4Mix+xHyjnOyi;0_vBen;cp}W<%ClgN1F!_Nsu4u&t0=OTZ(_P`QB)A5d!L5+dzzq z)w^ePTc|HxziL{S_*5V{77H4J+?NcYD(qe3-t}L7Eh1r{E3)b5Ccs)W+JZgqLdXYB zZ`J|mL(Xi^(o+`0V8_{4kGYJZR^t5+7FGg0OrS^Uf|^*>{noNNPPhGELe9yNelQ9U ze3w(Xldz!UrEUzjEJJ-Xc=z>3P}82|-MR`xxR{)Bij8nT1l_yM?w1;P4k4?V)ET3L zjyAFzKMR(iRtDl8xdkMNw1mM}74>Fh1AAIpOnN8^FkD~V2zSCDG^F`1!Rf+Eo#5g_ zAp}6FW|C!l*4c#L$DsV-oqEN#?9GJGLQBO-2nJjOuER35Gp!o_I&#J)T#$z9f4Eo-X3%x=+e-}E3(i}&6pt-Cuk$ZUB8>gSj z$64_#sGo@>q)Hq5naB}9<*oAnf^JO)ZRRkMq6$TYhR)>G!m*)##}d=(I#%P88^_-E z&jx;1A_#E@2NqgdT*>;VFLv#%pJM@5s`qx}$=R6d<+lKksvsRaRXE_<%tsiqO%0tW zG_tjRq-fa1TwrGQbQwwsThn!g&8l%1 z=hJ0!hr&|B0IK&pHFOQr zd)bgB>`tY(T>ZOZ_J4i|ifr7VLa!3P$k7JEocIm>*(WT?lu>yyZ&~$q*)u>8s20Xq zTt=Jk$2%^Hwq(^C2k4&%1>Z+85Gb$J#3Brr>gzK+E{$gqHes6~0WUFdqrwk3`H69{ zLr*;34Ds`Lx$bswe0eV2*U)Ky#WZ-Wv>( z9@d(gbjvzyc+LRy@dVpPUH`KeK5jL$PZrxQ3fRvNCdS6!IL&_G0Ri~>Rj_ch# zO<;p&I;Tw|loecw{s7QNm=H*DGysf$e1=DQ-}<880U!tQHcLtKel`;azmcHY|I(Ue zh*xq4AsJ*9l08spnOo*`r@@5gtkrmrE9d$TMuc>vLxa3I86P7s1! zO=P61wZ{Ppn9*_tW)`jgGt89)+O;#_=$@&D7>1WLms0(qhMwzjsJNs>Yl-n)T@c(v z+$3P--Bj@fNrA&4Ugi-)&wy4!hpiEJl>(C5w>sAkcVQkq#w=1fDErM|dn?6dOHLE_ zF5M-(5T*`JhJ<~8iWwMC#7An$f%4K2N-6UwbSteks9#=aW~}96KRsQTeFk-2YO7(P zZHIbi!Gga#^*0V_^jC7X3V;+x)|AL-Fx zobc*A zlBJNAgw@2q1P*`E)?K*n^3~V+U7DvJ?Ps~sqnODr=}l{0xdHAGp|0%?u=JvW_&X5> zbz*rZ%wX>hb3*W2yhLV`x$}5seDKWACp>Xb@KELntANTJS#EV+v!d|~rLlKi1*UPI zSDg=<9Lb!F#v-#zhAvRPD9c4aS%VHTmd)heCGrDq5|2E2ZFEVhdNGvPB%EvFrjck2 zYW3B4p-C4E-Ey!P_Y>U<5YR=kk>4;3s6T2mwrI^T9(8<_#0G|7_tSKpxR=YJz>(>w zWMMFNQO{}+fQEMYpjY41fF@{T(eHJ*@SZ11@=J4`Xy55FsM1FS#iAJH=gwJsNuVZh zr+BMXUI*h))TNg&$hL9|Buf|ss2Ho$s+ob}dZSyCy~3R=6B9q~*If0}9|rqg`_(Ov zy1``i9rtkF*KRF4IB--rD*(W9jp*gKV&hQp{$`RH*hgU3=HF~QbR+8L&uX(Y^8@Ok z`SmeLpJQh}GixR89S-01gKkWI^}AJC6H7y|-1Q-lN;sd#j57jr)lhWso=MJQ7c}TR zI~$&|LYEQ-H@)AXs8iixc6eq)eJDP=5At8$aNq%%AC%%oxd^53p$Edbm0OS^p0a_a zG(+u>n%PEhW@#?-9A-z`moEG$33=Wx(m^$#!q%5Q6C4IDG_Y$6XL<99H(9N)L%kOD!q_IfH|OTgBDi4(a=KFkEaK3c5DV4TyR zZH9yYudE)O-@Q9GydzQav#!7eUI#AFm4EHYyvUxDk}jI?=_KFj^fbMUeHVD7^@M`E zPR@*1obBwC&7`)RdE41YraO_)d*aA@j>O{4)qV`eTpxx)!cf%JKTd+sL-lK}5F!m2 z&IcJ$k|p0QgX1>@;*Lg|3r#nwSB&Cr)2ZL5u-2A>y0FRD)ti;f?%~S2oM3(D`%f5n zf-a|w1kD0pr37ElLoZpOL5_&2eDmYt39p>Wl}rj}ci`~CWW$mS=w3Z0mymH`0W?Ls zt-4f!7&F(`9|mVFDTCcsQgD??fm5?ql+}5ip#BkT?LRJTZb)D~$YBmI>B8jt&)U!A zd^fE$%V9_nIZ5$IABqL*H>yF8LrbG1o{cKMwYcmX z+A`kR>l1rllQ~Qiif2%&C#dgPNlv`BUUY-4vz7q6mNi!<(NkwPD`8v#XfTKcjV|#~ z;Wl5LRwaTyTSfi2lK{e(BOi(kn_LH-mR!?zvJ@j8O4J9w9DQ)`Nf-0H)7e`ai6YI( zJ)eH^%_|qE{7ChxG^bLzB{2zX%oUjEw@jVTWOH2whpPJ*dd>IIkwKkUKe8vTCRoYa zkzkPZ(Xh?UMYs4`ZUzZ-LWUK30+PpXaJzmvKFew~)+Uxf_`n&tyZ~l--|4r81ol7k zeD$Nc6_jYFn_))&Q@qcAg5vm1v!eLBRlZO`8D(@dzf0H1inax>nqOB)3+q7`ZFFjiZ%CJtW(j1I-0sp z>&x&+i)I<|m3rlZUmWFHq?J1OojsG2trK)rLS4^z2C+(ULE|cO7>p6S%bw2lW{&-p z=X{1caTglEUAXwZ9@R-^JQthge?43eCOQMSSJgP2T8a1y;9Wz-U0S+>cFP<<*)qRQ z-ZwwPQ<{jO(+;)>HFJOpL(Gw!9^a3bY3LFwKzd810<4d#D+S6l!+Ek?hJ>b7%QhD` z*1*KUUNHiIbfdVzAPN!eNr-m_;~U;EHl>9-unwibiAaE^rn7kQ(#->-uK1&ARZi64 z0}lmce)02VxMU(U>XXhg8e`@&mF}zf;XBkJ1VvwMyxM1iZuSp4fl@{Kj1^xuU9kz2 zAwm!|;s=AdL0P#CdL4Vq?0Bi|zzog}l%8>r&8`N?h!(B0vi6;<8=RT(Q1nF1Yv4*y z=E^9B9+45CRAUYAH<*$P(%{{dUs}Zeyv(-ab){b`s72pU&$mZG_3U)djPHc2DSoM^ z>p7s(*%H8h1j5(L0p2^Y*mgB=87jav2z?Sr_OgW5Zb+%Vo69pxisw%7@bMJ(U0hDPw^%)=3D{(aiec=U0Rp(^pW6&gPa(79!Bm~gONy-IRKGZM7 zK%E7UAN^)Zzb=a7(iZ`h#*1}(U9fBUv7kHE z_Pn{9;c>6k5jX}+h{Zwxqs}Y>X4oJL*NI6D_a-l)P+QHcVpYpuN31pE8R)pMNTWS` zYGkd>OBY1>{yqlt|NWb9EaJEFL_=w44jYI_90@MPLW>o?0JrdEj8-1Ofr|}4kgC&|fSZ|Lq^NN7M^hJwv#EnZ0=_)%YWASJo zxAJOYpGuU2qg&#~N2cF&-cFIPu=M%I&w)0FR zMF2XK=gfa{sF!)PHJgp$>PO_n2uez8D4Zgt+XuA<-G>gPGg>3tT%vUM+K<|8JNJ~w zVD6lg@jxV+`+j2lj^-a&K%S$Q@?BCJ*}BJvusi``(@$kR5nw^fM=-(mO=L z2ZD*q7Ghj;iXM!i!%t|C1KM5ec2c3GyGa-O!2oH=hP;a$+dT5NaR9FxSaT0-SNOH6 zU_j%Kf$dcV)eO)X7u4$YIn(%e0OkZLJPf1{W;x{ndRVRvg;!&~cwC`|)q|=1hXGsT z$9ayXheNjdCtEZiS?n-8TRkl;xf3iLCInMA$Wq7)t|?T&2eddE6+!d)+QK};m*pia zs5Xsf?eA`Hs)@A)bL3&lHjQf;qu);cf0gQA;PCI6fSys;iBfk`1C+g^;1f&oE@TcE z-ruHFcbAlr~Ml=7H8bznhaB{w3QfpC<@h?iH%!!L&Ko_%s+>-9({Xt%+C&TuEq;%HVX>d4c7 zGNb>t)FsvJ*_zSx;x1+ZhzHIi7sK#=@-eOrm zDM7FrVp)QQwH>XYYL%L}^^6q7e?&DpM&Nc((KaPLFpy!hC6IR6Sp$1RU|Xgd4}s-9 zUiYIzaxZ9VY@5m7^8m=b01_6~{&_ks_a#n47!$!!qwfg*@TB}I!p=ZEaG5ud_1)B{N*_NzZ{|vo8 zoij8xqhmVa_?IbBs-Sy1GK_@1qn#7hd{#YQ zy|I3drQZ>7-3Do^_RLW&+M1!L9JVg<{9CO{0QTjtRf)D5Dd*(C=EUraNFc~VZ`*dV z)uoUh#IE+5ZSm?z`NIN=STHW1-TKA@I7ZkpIupd^%6K)QywSlj$|sOoh0{UXlyiIA z8I1pG${GSYg`wfd2pP+cT~=i;KmU;O6j%q1 zK#pWvq%)g^vv}`*m^2UR3_B-s$kEg8C@1+ITp_Lcr{FW793*_kO1qhV_$6EY#Y{N#V z&V^scvTX0i!`$@(&S~OhQ1I`*6tdPDApCTo9$UD|;9!<`xa#9x;jIxHYtbS%@EL8v zg&G>hF{qqZHa~d(uj7S2I(q9r$a54_ETX^y*u!7}EGQ8Y zLB*gCKV~NYY-Jg>)Zl%c>OQ;7sEvNKwIQoxaA*w=EMi@{%sDOMmugD@%Fi1e_xg{- zjb5Fh@-_UD547LGxpJ{Sj@TIha?cbcp1vob`21m@r+&V|&Xj(iHcxt_BumeMZB4Tn zfi+REoWs)AH=UD0a+Qjh@Y{jgZwdRp5-94}^c!<3g&h#qihybdcu?!RJ;EO>EKWt; zO4}w+A^o}SSKx8x-N*#`!`G&*m->G0`*nc=*rEGMnzg1 z7V@2^egN)shoP%a@R#z(GQ6aqWWOMro(#zzH4n8tx|6kDM_fT*{Fp@5IMhy`m1y1j zmL>A-5}4AJf!0(n8^zSK>Zs>lbpZtgMGsCp$UhT>6dkR z(sP*?nuLBW6mGwoVky$!Q`>lC0CD8w<-Vdyw_-nEH$^~(CtC;Iw)XJPfFDH-hVEy5d zGvG+&pUB3!c6#{5=KNqQVeF5C+M3%HfQ0`3F_ZxW8s{UFsK?*_ETU4b+9 zZ6DX8Iq@MEt+pSD)SRjL5N7pA(%gFfR%@Ey4*V{_^gfQz$-@n~Rgt=&)7CoL zT0mnD9R;khm#05m?2~mtJlcJ@O{6&|E}%y%F@T`Y)fBDrj_wWh_#z5R8~R^%y}wD_ zgO+3-?ot2ZvaPVclOd*9fj7(YZ?DJO$_W09QEFfeYa4wqc|XPN#hAb2<2Db8=e_KW z`Lh?`R-XCSxxa6+6%V5(SDz2l(vABq(*@lM>@bb}Abp$h>MvmO&r3qgRZ^|N_9#ue zGy=!{JC_8%b3_B;^io;l-}@75?$Lo~--GWd`yI8|{vE5+fQ<(7W)J_qbaFB;5S_bn z!~p-BHv=D3h>rX4p7p=*Vq1n|E5Nr}2iu}{@U38|^Mh{u+`pg<3*dqtfG~fXYGCU# zAX~+Zpyc1ahHN~vKqzYT8B$gI9jV*;o!ub(8d3N@_;=Z}P=}HH9o4zsSpEwt{A;!# zZ?S@SJr)&K`FHi(2hnZ+26Ke`-|qeYd%O5tDUz<<325=jpPq-JvP_m_XD zhXLmsxs(<4_ot?804{X<>j>@uedYsPP~!>s7sZbDN8qJJ$nhOC2U$3Qm$tRG>i+k4 z0@7RtiuLW+hVS2DYYGm0Yc=uv{{KcY@TqzO@U8l_A40$1&v=9tyz}w6%9p=yzppv9 z7x3VeoTT^f=aRf2lN@<+QM~u>bORen5$5a}4aX(^1rh%K7U*v*;I!%n9GL$@+k3}T z-T(jNIUORDR7z5kku5~_Y1@=dM&Z~I+1V`(vK>1a*_&)y*0Hnam6cug_Itd#uHIMP zZ`bvCU*FH?_fI!*&TBlM&&R$$?vK$VrT_fO#sQFp&GSX1e|5V4BYh6p^@CK*tKZrF zV2c0c1DMCi0XY?2``^0}?jx`b`~p@)f82jyOK(PQAU$NM(kE&Wj+#^=XLB44y?S#J zr*A||m{c{VCcXL>jjSTyD!;ENLJ`xs{qc_r>VDY>^Ltw~1!fn)fB%m}*slHT@h|*5 zcKX_01-F^@z2Bl+4F3BIB6rW?DBu08lPW=Mhp)NcryN+zy)P6xPxucW6SK?x_~8Nf zkH(E^%DAkcxdOrW>iTJO6dYJ+H z&m?n|Xon{yK;MQ#MfFfp3QtfX8EQ|iMTni=;d`;t zAgaxbl7c^o!nuEqhBIB z_0mVo`PxqB_%DA)Ck?M3!f2FqVTX@YNh3>I`(7$xCpGrhzpLUPIH8759lT(=(`TLr z!|NYTAG~6EV8`Y8@gUJp2*tz*JJi}0dfyAa68g3bl$}=wxZE55b?-kO#l85%?pd6x z3Ik;UKcyF6bx{$G&;v}*g?*pW#`MVcMn0^@?{ zW*1s{$DIWC=i{;L?HO_$=wH7gHSavpmf8wDBI#GXk0%1JAngJWOeT`k@Smaj^?A>T zp=PPI#cIm{$=KAe=t)F=1KOox7fzJFz4p?H2tF$zS1wZN$M*2%j{ABj9yy64cN5xo z{PXYIu1h?5!0R#-&HmL&7hfLB0n9m@aiv_~sQ7a5H;nYJN0{!GyKESLB8y`D8z5Ar zw-whdkhf>1^itxTX0d;^3-z54Kga5_@5aBJi*0vxJ6*nH>Wxm{_RF99|NB=IGEk2% z)BDbF>|aUFt{0L{Rm-IRjSj{0>jg32kGynp=WP&axnEx6u%*R7>FY!SD?!XP5H4PC zx*Q&Rc?U@cK^%2DH+uNMugm-I(it6%F6>6RBdie%&=g6vMNH)QbMt;YH47;q^!7+i zA23_m2Z9^!QRo?yO&rUl8+k1;@aml%ue}%1uzM%$TQqn4^Y048k|f9bGJQAx@#@;b zM1t*9SD;nnF2ZfEy-8dpdNEzQ1phd7sH8{n_*7wo?qLG-Iw9V=N}SPYCq+boDL*u@ zc24oZ(%-E)1!@fxkqwsn8`4T6et>iy{Zl}Y1#0HB1o(5<{+rcK1^FEbbknh48BmEJ zd-5i6zBIpn^5-MCze8NLcS3#hf9I;u`%1Ke;wzvgyWg&57bmLbhT3-4w$PB$-#7P) z&7q6|j@XDd_-`n9S!V9D!oPm-&&|dhgqMBcDeyNh`*H@w2oisY_vl-@nZA`HaTuSU zPmR0@ogNBsosla8fyGgvUWXz*!G)PbjX3DZe^l9d`!YcCLuDVD|J_aVQ5$u-18u3A z$+W_@`s@mB9>2Z--4;5}ygS}oY}IJ)H#UcUVT+mguSZddq#>g+lo{BOF^{q} z)GmS|H;2*=#Y{L}zpl>Dl{N$K4y$-;Cq?*EoQLAdA5QD)sz(W0V?TMK-~9aQkIT)f z>UQNAkL*^P-Sj9fejTGo9LuR2$(0x^L9*j29`Z)CSbb)E!j6CbAti@$FzVK}1Dslg zLl#OX(O-RC_Y{&GlST$d^jfJ zgmOHFd$gfBsSSmGL;UM9&8iLz`iS$NeCM~s%w%mESSB@}LP5wr>gJH9=9fY8>qq}w z+xzHcm%2TV>i+uu=w9lePWKX2Kr^}RDY0j=QNKPO-6a(8pe3!)wLQ_llgRT~x>sIN%l`cKG zOkYP?l3IglIYa4Ae=y^@>)i27hFb@B7KmjC^g{QOh5dT9UvB(E`d!gPMJH>vfbBqC zfBz-Lv%g+xC>>MjO3;d(HS%8V;K7nq zRx%bx^)slT?-r4#gBZ*%{@Zf>@!yl+LeIJ1;{A28el=X65{7)r>FqGz-aRBG9qu$; z_4=tLkdLV!g2{N1E8K0xmo1XBI&LOiq#OLdx#j+8w*jEp5gXhus<^j6Fb^VV-cRuSs z+=iFTC{2)A&HOvEEwAeiZTAh=88dFZCxYE2_v%yJP(Ef_K>sqayjLbLjO|YIzS?Dh zh6B=+{C}aNd_W_vlxI-?x_5u7li#)MHO$&W2~N@DvYNmCg{}9{%1WH? z$&zZNfjjXvb&NK(1MSld9BZ8qe%+ow-)<906j{7Kv7<@&{SH+J38s$F7tCAong1GX zxvx`JUB*}@$VJ2~@eS7m)^erXZU$hz!)0iTx|`|BYgj*TzLKJzeS0a&uFoOCLa5VM zqQISS_?uj<-QKfN`lu0(;mjSk!TloQYFrfRn*R%11rO$qI^5`T%I|%HR14p)4}WF^ zHMWnqufRGXNh8-}KJt;2>`?N?gCu7u$ES){f%rNt6eN(9Xx7P7Rzp z59bbWe*avlfBVUSE_&l4!@{*t7)tc({WC~og@5o8Wv)@9Jf=npauz--%D6+dWFB(0% zsg|giAUA1$fI4+#6$jW zi=@6iE)T-new7!@T`CD6Qh?sjnBMnlHP5G_gltTnPk`({GY=LyqHTZ6tUrK7@iTP& zr<;6!^GYh<%qx?&6zXn6O{6Qd707y$9p}Hk3Kg(OgPy$o%6Vq$%BA-ml=JUswHDf# zBGlSRg4QD)Sx$KyFyu$0dlj7bIN!yE$xcP2fivm$$EQg$I3AM*(Iq8d_Q*LVbnlHu ziDPb%SYH^UbkG}ww6|-Ni2T?aR^_BOH{zrcr2<)59QwiZ*+2{08Ob9S1&C(KgEsSt zOm^sbe3r-cRZUW-M_Qp^`rgPY%;QbE`r=qzz0d@^4Yc{bfs=ftWGLjRPX3+V&zJU# z#;T-h7+`Zt5sJlJvF9`boI!UW_8cEeh*HrivQ=J~Xji2S;M9xOE^!)m7qy?x>lCSoc+4&t5{82t_wiZQ(cJ9xDRuUOooMR zs*m~>GVJQ;9C10Um-$^&pRAxo8nfISC;dA6Vp0B{)S29NZIh|4+(=e-Pn~3_#Q&8C z$ORtYCjaD)qW=4$x{DkD4f4g|B98o5wdIBhMYCV-FsKRe ziVNP=3~cb6i<`g)as!Fq##@tv{d8|xQ;Ry@V^5vGgmPoVEQ3U=f*2)t<(dX}71|`P z!mOe|^owa|^3rg`v79&ZRd=C{s*ey(CfH4MxnDI&Ns|18h+18k0GEajzOcxsiQWcC z7Fg^~RCgySv-Pvq14W$Lil2&yXO#UHk_F&>J%iIy4YHYNW5KN~0vG;uAV16x+QjoV z^gvs5XdhzcaTrlP*t)47yR3d&rLsv2^n+=N7X6 zugtfab#d`eEWi&_9?2Zgxh(-g94lE)n^WK<`l_2Xo7#&A9n7U8X1mprrX|dn-6mB& zm7HE`LX}z)tcwH<0zs->2H(hi6N+@v|NQu zSY>kv8yKS2nqXVWk`a2|g+k9)VSL6h3~uL)d_@p`!Ib+XZb5Du)+97F4PrCct$~20y)!<7t?H&h$6K z{<}=AGs#>yeEtu_`aTA?-9}>y(F`w}mxCM413SGh@AhC^Zco&~9tv8xJNOCr(Xp>q zCR6EaHD_NEdV;z-<1e>80a$!eRr}?})Dq9TfE)*6PkP&&_*5E8OO9 zvN}JeaSS)ikN<-AX1kCF!~M!axo>$eYhK^;gULdp9|;!ZY0PO5doXO;6!VZn{T>#( zlo`ALnlA}@>feX=UiBalK=fWTy_$|ZBM*ljuGO^Yc9_u z;^Si}DcH?{4(k%0K6Qq1*}6Vl&}4o2yUG05rg1>#=EU;~$l-Xd6!i;%2UN$9xrD`7 zHbjc*t$C>2Dci73^?r5fv7=wvVwb5#XvT%?8;u~~f%un``G*WJ-+=%B)q*s3qqo>0 zTSqZ>3f4^VoN3$VSuTwn3F*@o0LTKHeD|~-9ljatDn~jRTXdv$xxHEQf9cwHab51& z&z$YO%`=Hrq-#fcAXH!XY#S8YMx$KQdM$Dx{owzpQL7vsMdz=5B}GA7prYo6VAh>7t}hP4_?NwW&|}w@tt0w z{v1HvGRZWKzXj&Xo}$+iJf?S2HF9(AA?`(UsZwwZ8S!*Wf=^oloLTW#(^WFn(`P%& zTwUc|c&p-C%UHA!91)T=a+FQXHC*%XPB5Nf(srslKmFVckoCsI`HO%% zrvw)8*`gjYG`#NE%>aUm%H!70+Y*2zvbM{v>;>>Ega(yedb}?(7S8u*eT1m-IzQPl zJ_)uhXlQQn`&1;JKWV7=ovQJZ=UTBrM7i!CWuJe&?(bEg-~UTZz5C-@H-pCC)-Bc0 zIeTv8CipvScTZxkm(MDM4O4w|_3sQ&!V=3dd~Hiyf|*B3JZ$C=pyjTekuFPFdryRJ zPf>449QAPTb|@e#9fvXp5j|r9`s2*>9Tz4POo3|ncW`yg}&0I za#@eyNm{YYOQ+!h0jIE@R_=c zEPwU3hdv!W)0qD1EC1hln%QoP&(iGo^JQ@?ydnFHb_)rtpBjee!J@@K4{@o)Au-sJwXg z_PAHVA9I(SSZof@o4XbdUV^G*hD9+WFbDUV>tthJIBu?tD)*NoUT77>!g!ld zVQI4xI9_28iRIdW1CeR_P~ErFCt|ZYnL{_sO?M`k*i2FbLt`NseDUh9f#=^u$p4Bl zce#5UhLtCuYveQD=HPaSjgvl-dXvTJ-2;-y7+C3LAZu*tLIPjMt|K|W z0Y`cBtle}^r+<&gql74zLgp9!kKni&4~xS zrEVC8-+h$Lwx|J047>Jd|H%`ksv&`(`?V&b=0Dy9uGZNZ_Sr;&F8kU9@1`UFe8DG) z;mJbxi_e|d{$#;!!sl&~+>|I*IP2`CZ_l_&-}LfE0E+^a_kO?KM4N1_W)I3k;7-pQ zIRA$y-V^LOJ}_o_9SC|?hWs=0s_lhCXdh1wtv(pDGd>rlJBz4ZLWv2#}Zm5A6aLrF#vjK=fabg(EU5N>AX5vEEMK0VC# zX;w;*O*L&^{}f%v8Y4>6kLt;beEm(ji_N)y{|x+sEH0e|Vgz;+L&yS8w5OjeiekAQ z^8m@W>q@i1S(XMdtSir{mm`U_$zOx{W%q1XO7HX)t8W0QW8ilK8V>7%C zGMg;SPj#y%>#fWVOPPg>-2~E-uFYrxNx|`Iww$g!7Y~R{*oDC)=kJ%mr{ugI{7wV%l z#)+)?Jy#ssz{Dig1aZ)q`V0kI znUVfHp-)~E=%=|>T**GNO)UN!B^FJAY_s`(Og8zp?@By&6Sfz?xt-4@2ZyY6+7RKT zHRApXIfBpOg4Un$INn_LYNFmqkTDHW2ws&fN>{LESHHlgS#Vye*pgKEiO>A?)fb;F z$~NNnfraOo0T$VKhLQq??mTXS3dMMtrY^cgpwjX1qth~8f@)?=T_+^S=1a^h`b$fK zuB|S>*sPE`m0P>*pe-UjkQwmDy6Xt!fva@+;)|2wV&lU~6nQr#U8@;`jSPZ0wKNc> z@^N6!(ZOqAeS!wGB{h?jSU5Jy-FHWrh^C{_N8Yv5t53YslEOJCucvnYX&cJsg`O@2QrA-Vf*Yz?1QpHk5yEy!;0mg?zPbM1#C$OsycLrVPYz)1L}o~c z<-Q(byqn=B$nUB6|8VMe5nMu~eQutYX1nF)BMG^H`&1&?lb?r8(J9l`0@}7Dh`^<= zo`K~WxZHf{V9s&G?apGLxi@iW7HnH0@cb&$0vC=HmH_I=_i{>M_811q<-!5g2DhqK z@`Td{LBuaR^>9-#wKL>Uc2qv#37TQd( z;>Oglje+IEAY<2T#y?9UQ>3N3Xe}fe=+tULg=~_>K{ehB(*N#HH-XTrB>^~LJXpuY zOF7u6K<*PrWgH3i5W2KfQ!ayZ*wf;N{*5qa zM(3U3>79^?|C4ZRF-MEOJhsfhw;f{PehAHTfFk^&b=6ah?_RaifW{w{BBf%&^QC_U zg57r3{{5UrS0TRPvw349)?eX#?!{Debm!Ceb45ril+T*G*}C5O5eb%m=jf~S`THnu zn`!>zJ+E-W>x2%>)iV5g7XtJ}QVNRWp-&$W(&?`7V}8b61Itu1gV!duC29ZmE&j+@ z(jNiuk;Ba}ZH)fc5akf`PC=`we6AqN|JhyYsuN<35B++Vp@(o6hr36|E<=K}pU7xw z6jJuAeW>I8{}beHyW;y}`4omwUAq&F9n)~Pw+R#h^kr3?pyWT4;Wpg8YihFxa=afk z-3B#_eNLusU)=5A+tD|CdK08Jmm=z;cCJZasE9)rV*EdU`|W)z)I?*_Phay^f=XCq{4##^<6!;xdyT-2jtjHc4V5s!?f|d zH{)C5TCkbwIw#Xs&Ij?+;{0juOW_feLrzUsjwFHxbF5k5HEE8OiQl#mMFZfK~t4`SusgLa9m60%i zmaDaMQ2Q}9c$%JL2l)q$LjAsw_Qx@WVoWWIO0$za1&ZfPK35HPrR$U_J$(_T>ahmy z^=mnyF$U$t8;tTBBL$~t;v%f-k$&VmD_#uCKn)$^`s51?RKEen%ey;>l2Pgnu#bzZ z?m0H(qrs51zSwPXw>E!4w8`AXJgb%KLI+OGtUdVh+5xVOyOp$~-SbKl!I=u#SlL!6 zl^~JaIsGb%1(;`)2=35I8?MG10znpPO>9)<3z{Q^YR2g}am5+KhR7-7;5w1MhEwvV z(#TEQQoJI=kjft`I7x3xX#qZH@@=4kHPF#~)a!iB$uvnD-1)mPZ9dUw!%ehYRyg$N zUum8$v+DH5+&z>*<}!6W_eVJ+|12YZS?e=_#bBk6 zYF+5LmQ^znDdHZk3mJsLg&b59l)jczhMM>@$bn%_;ys7lPlxo?zjM|t04xgM%$m~f*=uMAc z>FLxy<<(h!ZG1JInY zITQzOkRIVAOJbcCBU$y|H8?w5%iJ3Terpmb=Ua@V!rhRMT#b!wl}dRlxgS-;VXVvp z@3M6QZ|11`JX7u!04j{gr3C^1E*u^?wE`*V(H5i>Jmh1<;B-R5GIzZx7~(Jc@Gs^W z5zNir5O^hlgUheISiXTq@0raw=$=BVR=S@%T^PVGte-%m-oF3MNa$DPyQ2!-9!nld z!#o6-W9{@V&zOB=Z6_q^<_|VrIsA>u{jg!ALwsAi{%(=*`;-}P?Z1C{P=((VHfT-N zRF$Oh*SbMY-1qkGYavigE#r#d{o25M1E$Z6nwD=kq66Fp%GAuU^>3vXm9dXppc1{A z#4r?^%8@rX%2^*&X}kn&*~4<7-y9*x6W^Fu?6;1E60a0WR#6>4ap@HrT}xI{e^x-} zBse@u5~2>ODQd60p|;e&ieDXs`b`g{KPwgGL&#ea zzyItjajfi7$2iPw&verrJ)dLRE|;pAU+*LIY6<`^%DJZPi=qNz@bC)5!*E=HvXD9g z*LhcNK^aRGB!28v_N&KQW}{v$`*0jWfsln&ny-3>StVrG@d|0b4ak?ndY~}RirMpR z_geo8g{i6ga!z+^x_$p?Ux`Y3x~3BnvRkL?9lfp`__hdDz_t3lH?#C5Z8~l}PMkgN@dYAj;Ss^4+Kc4?uIS3GvkBmh|Xp9SDmz7Cz$ zK}M_&d@5S(^0;J95C=uF2#66izq%?XDK&NFgCToR&*nZf!gK2#I#pzB4yIk;^(9MA z@|%UIzjk zWm+arM2?14=}k2F@gs7PjmU98AjS@o134`!4$gxw1Sn0Sa2>^Bhc05iL4`Tc>3C>7 zhei%J&d;R`YM%Y-?u;4vU}VOpi)K`Sb~!8btlri6@SrF{y-IIoRUPNtE=Y*x4o-{xSL>acRUwie>Bjzb|^nKI-&L=9hUR8dc^0pcBu?;y=v7Wc=^o6#Ss zjLx_Y(EFO2gyguGXS7Dux#eJsx zw1cDiA&6Qsztlks(R<4{cf%E2wGh5J+pwXr6w)ls;{m2FYIc%KUV^?7}ktgE!D zAl;ZSlhiD!@5@R09v_`Ti5K|Ih<+e@FFF-NV&dyr;}bwA;M` zTrQjgekJ`zHtn}XIFm`RhbGR43`x*I(SgIY!CS3w-ExrvMK9PU1g#XARTIpWF1Gsh zwOfzt6liU+O-i>}@P#%5&%5X9@AeQd>!2WiVw?Z|`&iTK$E%QYyqJH{qjeqI7f_zZ zEuG{p;$pMDG2`0qtqGy#y5FO&$O(c99#5-~VL(DWA*w(I>6BiW0g+bWk$cBpeOz4g z#FG8w=S0Pjq*UW(Y6^A&JMcB0zIY8M{0y&~+@?K-^_he7nFnqIr!GDEAT#{7AA-Jd zV1)Uc=e+*CGBM-oTurVEKw&=D1g)C+Q22gkrkvY&rr?Wym zbYe7%b7~F7KE8(IO_d)GrIuuXxJp&yKVtgEkeH2TJr6{bD zp4CBi>f4h8r*jt1oBNj!gH~pmCo8k6^Aj)rZOE=nO5t0YR?!#R7Td_TwZ0Qqva&B7 zq&OZ7>`eN~<+FiL95yl-ZYiFn0uw#xd9CFiM-LU#kJnx-;Cv-wFHt>#pon*4-a2o0 zpWON1(5bGs*?EiW!UcH~(>9@a($;y8k$Vtoir$*>MO!>`$>>LKeVoAY{0ur|Fi4LH z;52GjH=A~@3Cj6(kk?S<2aa49IHBgW5WoVHaFf%&1o=wQ$t(N@7H(|4UyS5QF^t{G z*~M*WcJFKBg{h9r(|1n6Ui12>iCH!L!~)=}CL_JGg zpheHy>($SL>TOA8Z)V7BW+8>YKK zkVJQ$bSR(j7^Dcfo!^j+EXaP6N+PJHG-ItOsDJCPT7Zq`30w7Jl+KwAFYkf8qe?et z_CUOKb)1_nZmNB~^K{;9rJmo)O(r==W@QCA0K)2n0bfH4%&zF-Rm{P&M&SMS6I7_b z6_44AetH8_v`A%e>5cGdu>8+6Zk+jthM(>wt$Pi$Ql$#Nd7l+IR;~-~mp+P=vf97S zEg#bT8WUk1Qr|iu%Ew9giyAW$D|qDN^%yUl{!W#>MY*n$YoeT*qG?fbPWx=+Mm5;$ zNmuMi1~mOi7zWw*x=1w1<9`@fGWaI65Q?a*Fq77!oh%bO46_)gK%nft`+1?Y>3J4H+ zO*!B`kKMg5j)z1Aoc8R59)$Y3Eic6V(U%LDj6l}m7qDw7isZyWS8>_?(gn8+-{jfU zkl}%O-t=|#376$t<~Jo3OoWbPYco>_1`3&td>6Y`mC|D+OL1+f%rvclDKP%>oLmU^ zh3b^vX{%wMJs(W{9U}AY^lBhE8ny%|PmaTr$-jMpMjMVY`Djo`T)+soE1r3rQovIF zy{>NXV)B0xpKkkzdm~Dq&=ZYnW8{A8{Po6r=Fi|zoKK>wAnV*~@4u_labeup*}qfR zKVqeAawPPesS9q0@alI^lHtKfk5Uv)mJFjg5hPZBJvKb*F=V$%YgtZU0<{!(1DtT3X%m=1L#FCwr-Y5P_HTBa zv6tz#2yc%rPg^r=Io(tf9a^Sp`yQXaQ%dM>e)sY*ibwjJMcSS(b$c$?EuD-NZyl4wSRQ2*t$TC*wTNCUB>Noc2eo)A8}Kb< zu3JWldDJNh@=D4R3d>CNDOLTTn|6X(k$Cn=m)5!{aUB4~$dFU>T;_nf2bcQ2 zBK!%nJOhZM-5n@9SHMhP-lBN_2V!(Mtd)!}fd2r+WNl#czPVMVwlQLmS;_KzClTOx zza^R5THF>k8mjKIwi>MTFioa_f`Z+BgR*KSFGb?af6nfJJKmt6O-JBpI)abLfASSMVUnE%=V1epdpzjyD=DNB1dS8+2BF5u? z%2xizUMi3gK6<%Es!q8N+Fw8?PB*BOhY8NM)A9 zE9Z>zu4Qk*oGJ4h8Qcqb)R&%07f238uCDVlz;v=?RjyRdL@3b~xO_A;FXFI=qQ8~< zCV%!lba*xX3FX(XC;WLz86~PMGIJUGzVpsib=(Vr&P2szSIE*T^0d9@MAi+bTG#1U z*J%LGvsG#Y#LMRLumT7Wta`A~ zS(b!g@y&sKZb2@&0Jj;o@@FZB&B>#n2!F1>E`li3mb=bDp+$BxX)nx~b@^P9=MOzT z;rK?S9yDP(qdg2a%h_m6R#kbYnC zqO3(^0<@t%kE1<%`+-W(y4fb^7rnK?RJh%vBIc(Ux@=UJU}R^~nG$03`O+(Ha)JM` z3)=(W|A>(>g@lw5j2#;kW6z#DL z6+6OAaDq}~Fh68Nr|_OJ`xuOBNeE=j_AWHUKWEHIfqlAJWNV(vi7VhdLZ$glso1TV zdy0Q|e(!~ZTeD%tOfn(SE7f;>1ccwHKk8qDT%NIkG`C6PZC+{B^3IM-z1%zrad7(w zyN_#XexViTZ4ev{Kgg!zaRvbs=Kl7H#^U*uPrjeG+W?T^ODC7XsJTd!BODsBalYjZ z;F~)&f9%$U{X9pfmZmzAQo}P?SWso7`6+ykt7&c#!d|aoo0_lf=~3#kDt$A17!bMiV;gOprvdfJ9}jVO)dLz)!}{Z?WF+i?;vNIqNQdBJkF`8U zZ;QP6l$_tZBPSZI19?A<{-LAQ=R|vJAy29VsLm+j+w`8uZc#^RnG|NMl$D`v^Iz4f_v4_Fnay^8C^S;+m_^^_rED)$(48Z|G1_}lpLzLVZ3)sK-RRI5(U;># zL|&#%brRbb0c18;%%~~qWc%jECNl`3Bwvp7Z&~6SC)`OW7ui&#}Rz>rb1$>!vJeS5N@T__#vFe z3D@!Ozhsyf+rp%1mJ9@~qQUQ&(YWx;J-LzfBh>dfo^Mhs%I2X{-r8%bZO#`tCMq zBt6|*qum~LZXCG4W(!HgOEkNXVHH`0FQ1+mgb-)E{dvct(r%9;n~C^VmeKhBS-@jD zc}!@#tQeFHwM~sIRA6t_sXgZhTm*(UP!H~YqyIz?R4M@;KP5a#pDkNdiH8B^)cmFZ zrksqN&I^a3D#q!j&D^okuX3Kb4P-ca#qp+F+%{h;h>}QzjQ91~N|K(z#5=u(Qdn|1 z{j=hvpVM`8rg{om@`>m6^Hw!HQaUm>Dh;J_MUESt_zkgZ>(GK1`Z}Z!h!a`zE7IMd zy~cjr393UW)pc{9sVIt#TbLTy7jLC;K=0D`2nMa%BLs6AzFZqIC%2f(zZ)?8hq?Km zoCpU71yR{-bkRwk2q56_CgHY9$R%QowbtWD^)VcMM|(yQqQ!f*6^d<8E>3P`=AB;Q zz;2nlUx2KtzaM|mnk5+6)x*@ikrJ2;YF*|92?ZHWb}#fSL$fvs{XM6}@m4n9$;cc8 zBU|I2#n^b3wic>fIayFp>2e!@(b-o_edcXIb+@H4A?nTLLdMA3RF%|F1pA*lWyv2; zNl|Rl3Tj4)C3Oaz1M8=GrGSA`lt%i5OohrIsH$jq$K`srqYq%UbzejDyh+UR)-yez z=wal5$WysUeLcT`SJ6O)>?l22sWK7Y{nKB*VP*Z zX`kizK-$;WeA=38&zD4b?>3zZkXsXI-DvIysJ_`%P(L%j`hFT>!By* z+;(nPkG1#Dks#T38xKOBh0qsn`H<5waW?6BdpExDAjc9Ir`Ba)&|NG zLD2`QgAkOvwOmGdq!-UhrJ9lC)ee!>s1QfJ$QxiO!)@GunsJATuA_$1yNe-wGIn7226;_zr8%PTmKuj@KfR#IwXIrVAeg?A z3m(MCO2oJm%vKl50w2PxL3l>Q=Hp@22de@AKwxwoidE0XMwZ);o@eA$L}&n#Uq}|H zaA@XDra#hb(?717c;iYf^M!Yb?0|$7aoxP1Dt=oCiw{vMJQQLF_77ZPR3=Cs7o8gG zBxDj*((pO#m9-Y9=+0l8UN#~^ZGt;E74=;7qY|V-W%eJh`Q}#Y_r^v*Kk4VLk$K_12_#IUiYv({ls`amGlv%~4iRgl-Uj%^ zrj>OL{&;ZN(S#M?6|}YleIKk8ZgtZ3hvbCYCgArqlPB`J@5}{QbknudEIC;A+O&82 zspsR`AJdVV5(t*w1qe&%3-l2p!c@Ut-%k17crbMP&m|W?YP9`xjG7sEB$nDr&!~;Q z=E+tH!5C;-^|{rceL4wbE0<0|N^T=L3*838M`fnMO#tuurU&L9x(CgGRV5B=;JVI9 zg!Z8ks826ovCt`VDH&m|w1UcEn^oN$-x<1PNCK)r<>s-+t8<2uwSQf)$Lpq*5X!vaoeVE;*C?m6t>s!hcRxvP|ihY0VqR2fmSX_3W#Xx&cM9syFXGwCQ1@q38iqmAVeFDz(~t zbI2H;3`9>BbT7Rl*$mZV?@;$*fYsq@@ycru5s&K3%eIZyV9i?;N+& zp`la{#%01Ny(_t(O!dPK*4aTTtf}60kEvna%N=o`9yKj8qR7#GjgcYtm<8Clt%uYjdnS`IvE-+ zZez%inEu^K78Oy9e(`h{dLITKI~9@ngA}5phy(dFVzt zjQDg(Nw40zf6npNY4OP4mGE5lHg!A?0lUAyvn11I>WubrQQEQ zsIS2}ff1V4O8H$FXOQCdq};gjX2>M~R_9nTc8K{711P9v77W@)yP!q;VJaI;2D(WF z+BhfVp_yzD@jLRqb34rHn>vg*90P;4*SA3$LG!PkuB-)2`v`%-Qp44@XCLh)Hp7Ih zMq=D-BkDgAH8cGYd{q^?t*p2$rS+@cZMeZct$sB7x%!Wum6t1LUoPxFqx9sjTup_e zsQcAXD_kpQKb`N@8%UL4uzI_Kc}UIoa(W4?pu~jg`{Z+SCi56CR;I9slEVTDno?Lg zTj9mAmdbq2?5$fU&v^N$v_LMKlJ(hI4O%ZeRNqcdFV?KSJas8&ws~O$yoI*$8kjE$ z%|_A_!AI+%Yn8)nqxFc$^HXyeuo@Zb)OrfC3J-Z3pZl z+I9}VCIcK7DLzZ>iP1iUFA2TuiZ2gqK497?VLm~nOY8%JT@yTE^4&8&a ztLcVs0|oTQHjdNLg*;B|)r(xXefGrOLCufv#^P)vIK%I>DE_fs#1!1(C%;AZ6Y~5? zp{MKpKgt|I=}Wmj?{MM}R4WigJt7ke-vBZ^3)%$-v0i<~P|BabFF z&+$V}0;>O7b@J?xDGsH|f$^ORY?|ISjeaKO>I$7aV!eZx+dQ#va&j3J!IRK6CBpRq zB2B~YM|iqHdFF7Agl>t$osbRr#f?@~9a<%udr=O~Rl!g_=d3Oy9QGfCj&2Q|cF5^} zR-A!qz*v}=zc3_VUF0>9p^-8wW14x8+4zJ;uUW3x(4~XZHNzDn3o$)gKkV`u*wpUxwJX2y=AQ9@kwKLQ`by?J-$l^l|WJoZF;5 zP0^8flZ~yV>{u;if6)nVX~Bqv`*t3!>s&*a9#jCCR%^5@_+J<;Muu>1Cc zS$CdnH?#A84ahl7OP1+Z`$e-$PSv)%4M2~!{W^k^kA04p0eDh#O;9JPXOPnFdXJi* z0m&r?hKXlKxEAYfn@Y!{JmL<3EGD;=BDf;(3@f|r-jfR$tql^QYtQnng{3W7ZAwL} zG$N_sQ*>&mBZyu;+YVFE8-kU_(-afDRqP-i5{RFStiR&HzXc!_LMoQEx=e;q$HF58 z-nGy17r?hXGeu8#UV?qaInVTVN7R~JDqtt)pVM{*eVqjc3RWDh>-gg_M{(E9^~+%a z2f|oPPiB~a${*RNXk9}5Ov>D--hR>T?Uuh} ztE$ccPfS}u+xad}%vs8+50m8wol)+zR8#A9^A>GchrjXPU$#uunSI8Kdv!MA8Cna+ z8({mj@l?j%>@6=e(F0>iN3R94`KB6%dP1oB@T{J6p3)!r-QgM6ts-GB!``+a86vbrZ=o_R za4~7n2-{5`Hw~udKF&q=7U0(!>O8ey0FDy!xeTWKO0h}TXTs>@vdp|r6+lyoq0#b@ zBAtVc;B&^x46Egsb>3i;_rBg}_5I@!)3M?6BH%7uP^au`hq8{*w_a+)@K;nE8be`a zNN|?Ne)DakfOCxS&}tL3hkQLZ6l$7w9my`_5`$wZLrk1^Bd)l~R#s+cw3JU5DXu9e zt8{fFLO1;?H_%;;^fxw*5eOEXalP7HTB@f2oZ)ClZCDN8is z8J?1BG<2;Wx;~tfxf_tkHcp{{vtS}gGe6Cb#{hR$?@^u);JJdHsQw5gt|6gB&3+k$ zpICr@3oBMmM>~ssE4i+}=MSgz&~vx7qTb$#mAUH2k$)MW4+Q`-$V9ja^@|J9_9Q)K zD}+7{E)Si>Stz}ZQ^%}nIN&yAHS$n>E*lG~%E0lFYQe)h1V*Q&?IZYnro*+FG~zDz zbyu)k2g%9CJ2GFZB%qC?C_>n=bjAvo7|P!O)L%m#_Wdc57kXIwo=zzd`q`ytR2+O| z2nOH0zf|-(J;w%8_y}at8wdPuQ*($#^8rh25X%hL+X0lkW+ae0Xf}87Yija9M0Xge ztw!P~5U{7Y|H@+m4@g>Yw-j%BpAZ#l%hy-I)0Ns^P=!by*n;E*hY!^uu;Hd%mHHx# z4IjJ?=FSdC3x)2&G(At z4L>aVuwgV_%7hb1uR*d?kwtXIy#2#v*J){KeHF(Q>Z#{64x(eR{uc#qY}$LE3kv6! zCOdiWxoE!o(ME`Loos-sofli$Z3Q~!m>tBh#?A+rS6=TM(+J|!O428C%HM(sLdVpK z9U_^IQLsmO)I{KfafJ45ZxF2mCy#i`^XULwr5~8>hG>)zuIHQ0dC58lQx$Nk^KA!Q{@x{$xmp$Vi(1m%A*1AqfwpW zGJV$y9Q$kg!>A_@&Zr?ByBdNw;?cQ~=;7CHYg~gSja#YS_7|A{s4pBl?cQ=H+dg~x z5z8C|`Ykm9vj$Y7`bS9in)MYIsKg&PHM}ZbW@V1`@@C7Pgo!tDrjO^RUj;bW$GjI{2LXDiR()xT_@uGV2L!O+)=wo5^?SCLX}wRRLzX>90l zfQPu4`yD{>OGD(L5&SZ*U>?m2Dl#r-8bK@lkd#cm0>~^nE|@U3-(Mk0S<+)URArjCDP zn1PC*gPp_}#qYX+g>6j6!jNp0y;DH8kJ@2!#&m~ri&&e%U!ps6v_AKlb7TM zYp%t{+fv3>iv??L&jcugr;nzQQ0zNVg zna`wPXOPzjiT97ZgK+^I?hLm8aaD~bsy4I6x|tT)PJITIn6$tv;{HuVWyyxas$waO93o4H=(D@y)KJT{v+uba(2rlxfV8BUbJ)*!sU_>1sK#H`1O_) zqhlm;!HXf47}QNqkK+-0&9K$a*+}?lxOLqUXq(eOR|~chmUeYf&Op(|kK7{=gKhZ+ zv2-c-RL%fZe9-jm(`u;!O{yMJeGF$s==ulD`NhuK!5H@kv7jOoD&-lLQoadbL&wOS+qpt5?x*L5wkCde5B^Rp&)h<~X6x|e1n1=qBOVUq8Z)8;Km@+2(_JusYIUsV zJajWFOTR@~%LP;CHDN4S+04kCfWn+#AiUvE?YiOR*l%vt$vlMgURD}g&yC^ZvqS)^ zC)z_tlCLZiX-x+eiwdU)QhP?t50^sgp{?88mCw*S#O1D7t_q2*dGP)5ymwBZ^UGk9 z_-?`pDelY&g4ZO9S*I5Rrhjzv3J;h<+y-9p_uww*FWwUG8+Qr^-X)xK5%Vrg251-XLG?&P2x%`bLG5TDAU+Z9^o&B>Y4B!5;p#&;l`XIEUKvJFN+q7 zarsL0r&EHtK?E_SIT`!uIQq%MO0otn`^Lq37cmaVHG=;BW;|xF7HS0CaA05w-2DE+ zG4$;1%TdtTl1ACTOS14xEZsj{9Vc&2E)yB;#sg4oohPLN8RwMz`?3(0ou*yWF4-=2XGIG zQt4@;qyf-!mHO~j$?akx!oG`k18W*?bGfgeSXSB`++5}#v}sEIfjo>0MScxLXCld> zZueLgbO5hE1-7cTO9NFq+Olg^ zu&Pg@vdyY_hCdS#q{1!h4V$j#7=_J^j-fk2?l>HyxB-O%TK}B{eX|t2oPS_QPg_U z9Q`OtFRF(uenZA)?Hx3V41d{=J7jnpLOW!48uvl$aIvz2aF`nZKNE;=i6VeRNWl{Pxwetm==+0^+A1eq?0kh}qh5y)Zbw zD9Ae@3?^6*5uKuHUe|Pw=Ux(v30rLpn=5I_t}!vUR%@8Dv~$(uG5Z4G@ld5H+IBTbO#j&!qtf2a&&^pQut9>o>c67DH59m8AWKX#30 zw@6n)^{iI{1N7GfhGQ`vs}Z(o2BH^!cLv#$sWZrerGOKO^d00z-u1<6ne0$Wa@5Z|fD}}bMwa5lt$7Cto zRI;))4RRT$Br_w>?*wP_PciWq_&#>6^gC$FM`77j1A`wrxqLT~^l#aqqYpY4RCNGp z4zv=FYvBb=Ql75*un==hfCHG!$F#f40FFsP%6~OOQ8#TFj{(GxKwJNT`32+FIQjjH z8|{)ki;x{TQoMGxAULsBCl+PSbiREyAbmle6*deaYLK6+-_QFDQ0V3vQDJ>2g#b2*I(f8 z7uT7oJ=gGlptkQO5A3@L!dYxtrNygSW8$X@wK!?=bh~QluXGd&ai;W5>&TOWyQXK%!rYwtP}2JI&k^JjHK{uEuq`H)rdGQvYxQDNqWuFSj)-PQne`+J)x5N{EU@ z8in;1?c3h$r90OO_Iu3=AzIMKv5P=NM&|@kNPRGa;>ljAJf^>~QFI=sHFY1n9TRBD zrgwMS7?U*Su>_WbEq?_hCSSJUf>H~a>I6GDq5i+p%h-%=9{9}I-f=RxKFe(F>6 zW}x7+Rr-+Ha|O-jpxIIEv67v}K?}@ithVUK;v*AGmZpQCB*L&kh-qrL$ONrS{dH}q zHxM%_dwb95ri}}20Ly7KTUsnJGYC9YR@Hlkd4L)(57*+1dy=wm<77wlORb%pdGsbG zf*$?GQBQZb;(iqG(J)uE8j*a9=Z~A6h7X&aZNd8N3WJ8HsfNYZ&$zZo_H;tCf=W)V z`N-K4gWJT8IOs041BP+5DihKQC3tpA0z1U@`3ixO!i2&w6)mOZHp}Z)``*?DE>X3J z0qz~)!N3rr{_5KaAsgVO(e6vl+YT62Nbo0cd44aAr8uW>i+t#e5;(9bLBr4S?RUty zshgvn~mx*U;A~=>R!aN?Z%Ge~o=AfM$&TsgizlCeVyD zL3*-Yt1~<^hWxyR^F!;hQ;c>dP{9iUFw&0DEiwp9GB0R~5Uy$+Q83u$n{E>dkA>R&R-t zjaoM?;OTojlAp^?ly+#%pW+65kaX~9^}Xtmh28?pMKHht$lwa_#C34j(7etlTUJ|w zbEcP9k&qIRCVei|QF`C27j>J)^ul^E{h(o2gr1$^+(6k;w!5JPmQEqiHxb%+>jM18 zWq7wO4VxpAXAN5&ctmHmR4zZCG;ptX|LOm%1{gCz^?}(MJ*TJes_ZwIhqS!X^#_A( z5(FAHRkH7Wc<&q_O(mIfO=gef2eH=d!riBamC0i%fu3R@4qvWMK;rXX_7uj{Z z*}v_WOr_$<9z|pH8*-G2`#w6o%Sn4@qoQfP#j&ogm-mbOu?+;gIyYp!5%f-m{>f#C zIXz2Gqoy+W-talZKYZT#y`Dcwj2695Xc1KB({6TT$nM7#BpY~dw zb;=X-9-rVOzs*1%d#ViGRN8DsaY=~8^}QX1TV|+gK7Wm;-@z_?7Cyo1vY!*hQFudH zXs`3`fE9$d;eH+KT{<=UtFx)y0|)B=K9$;;N~;Ecsc33-9aYI7Qyhn-An!CGJJ@? zY&s-3cmLw8TGYCm+A$l_ae{bbl*(tb5zN(?@pC10|e?PvzmS?RWp4KMAbD zv!y=2>Oawk1IRyGs7R(5C=hrW5zo-SG%?0ma$4NGO|UmA9ZTHj{*m$}n|KPj1m5hL z$P1VeEmN_nbpar3|Lm zJ&HfV@!4;u_Ak~-`aCC1?7Sd~2!1V1&}aCa+0*j79_N^9NSqiNO}Q3+(JtO1ztnd^ zS?{-f-n)iFcVN9|c@IUL^1xg`=WP_8w|sirbo<)96vC!FJ~Idk&(f5)6FYy? zsEe+5vxwt_vP3(|(}?f|PU?b*1jk!g`FDX#^gAbh_;hR&X_4MP!;J_DpSN7~!|wUM zzkQ_JRLH8A<+PLHp)cT>Z;erIL$jDtG&I>0XeTr`{TbTlCK|(za$(fAX?0{N9t}=X zB?4a#p(HqUnj4-(p0;mFbl2^Qzpyjm#M2i)Z&f^rN?Y&m-9^M_t(;4wZpp0u?KNPFb9BIcRl%nQSNQ$VGc(uNViHw@DjN`}H$ zlB4Vbu>L0~#}r`6ri#ET1#qZQ}CcnY-QktnA!AATzX$9I9qKg%>Ur$erq$OfGae;3RX( zd#(1lhfX}WaEO@?BB}`2TKqwf4i6dJzF9Sw7$%n?_4`fTbIymfF(qMN#HiI7Juqmv zVf<74l}Yr!MUxC9ns~BdQpog?Xi`rRZ($5K+c-O5_b96%@5$S;)~Aw9Kr2kS=6n1l z(pcvMzyFUX?1nrKm~5D7Q)xrT-R<7`CjV5^s;lX z*gg+*eIM+#vc>$sr*W?}(0+(6bGz$|9%k2>qgu9!>{atM&&74PabDZsoga!*iVjgRwH97aJt#7h@{A zgSs&54g~$hJF;m7bsfZ2pj}dboa=}P+wiB2{HSondAg$+CEwJneKleHK~+I-T9H%v z$Hc>>e>z4$UJ~&Pr0*%*5TMm+9)*Ds-IO1fwHN4n>+WPcWY(Urn+HjHTPk}p z3JyHYqXxSXvl;pf{10E>Y2c%49Y*CxoCgtY8BztTbL42Kb?&vc>~lBO9QvK9pWp)bL7dW zjHie&5FY};G{>ahd6XCU=)O(?G&#@^Qp0vco4lZv@!0vt*8m@^e>^J&lf_ED?)n)g z`TfK(En<{cZm%I2y+5)Sfvo>|8&l68M{f9=%9gxHTEgdZ0z;G8XiSG(lP)$EM@cvWEzmhh3s`JT8P2DxpaAM~8Ht=U6#+3~8b z+Z+_#gC_hI>c}v$3dpCHFErSXCVLe4=T99kBR)kgj@)3crPtD7aD&5E15WJZ0|H1s zaIajc(VPKeef#mOq6Zl@+yoch?pC%DR)76@lFrJ z0SW6!Ixl~eEVAFt1W+)0_W!Sz*~caQEZg7>u$e~erBeXgL`pxz%hv=f?r#C}<`(p& z6cNXuH_*`PcqQ?))glGWf;c@)!5{$zax1p6U@mPf&|9m6?m#OAs*fp-4QG9 z{r)F5dvd*8?@G;60IE~Fa}86Gc?bY%vb5Hh8_s#d4^fb$wNrSNA%kVVA7|?xHo3{| z_+2O6wd}!?HCOFOn-2+93L>MRbs7ywf#MLkXhbC4p$Ml9ypF?;PXmiMO!9CYJ>pi7 z8btFtl9U@6ZJ~e^T{u4%t{N)VT!1?tbAJb5KsYGQB`VcpXuA=%aDpv9e+%UL@-S~8 zH&EBdvEg&Tea@O5kWNU&o8V4bmIerH$_y%`t0~sqH!SS8zXR5Rx3|{1D%xSv#2vM| zP@pe=>^U`}RqeUq@0y)AlDFtQ&(;1gm$p~yj2y$y|8X_;{HN!6bR+%XyV@WTh^PFh zo=x>6{^}(Dy${`0Z4WV{h9(KR_+x1v_O4o4>9NCFs2`c32V-_(z^zgw9IYwa*6~44 z@#!0A#wbFkFTbEj17|!aQ+dxHBT94(`oVE?)?i4Q3eGIAp=%MKF=-y7cjEikux$A$ z;5K*l2R z;8p*$FqRIS?sGwwRGj1+ys8Cyg4&<5iVhPFIXQ*s?`}Y-iSBIXV!G84ruF>pg1uDt*shxj!x0GTy~nEs*u^OU;~_U`geRc3G%XJE@VeDpC;|az>xIzm*R9>A6B* zW4%QduPctjBRf^hc)tMUr61A+#4(el4Uneg8PuEPHa}>nPoES8&u-P^&ajx6t{l`? z#L&(pySrIT9d4(}M?k??m6Wb7jTl+n0T^NloO=bHI=FJMWec^{pL>_{!~||kUdya` zDay<8%_K|L?5u4v0<9aiRIbae_}OmzeFf&t#idj%3RAb_NShmz3Vsu4tD71JdP2tB zmRaQuwwm%*y4wc{?M=6UjyQo6JLUT?hto+-b!xSNPadXDv*`)JG&iU31 zm4D+DW-Foc3)@a{^h5!vi=CH3Hu@|8qD$YjF6%0Fvatig3#;n9Ju+|t41P?;8^fkx zjpcI~lhgX9OF8?D6QhFBe?7Rwq|##E(Tt2N$>zxpo(D!gQ$1qLCiLa6qrqwSCfRjs zXdP@dFDWQZZB%UGD&ALsT*TDa9w?lFb2H{lKbu-cwtHppoXE-NkczF}>b*9#4zvSi zbLE}`wms&740$lnoEP=hw9cbrq8sjc4f4+h+ zg|06(*lrP?AQJ%_wzv^*8ZN|QZ|VCx(lbh-nvhfu7g@t-ixeRDjlSfZ0<#=g)|93$So9UWcX!dDD`6s44HN7*{RD9o{~+U) z9DfNi(wk}f)(5vXm9O`H_yWJCt5i=|^@tk;s3~9G=Ci9e3W6|SU=qef?&XK1^ckZ9 zQ+e2~!0PGSaLMCx{c7YbdFPOUI-}0roE^myHn%{= z>4A}gOMNorq-Oj6UpXF%itObFTSJ>(1#KzBQ@dj!P{*jS1|+Vr<_=AKT}9^Dh1`mbSxYrK@+5wM z?^-V8kSC#ig?i6j)bcZ%h)LZ%L{4V*96uW|Jtt3Hc_0Y7lC3+?RE!-zmpTU~I<0Jv z-;6vL&YQ)p%w_8JU3UVK(j91LpQX;_$$*wZ<`^?Bwydl_hG!YerJZ4JSRPQR%=C2|*rP$h&JmF2WU4a%mln?ww?UxrA4s2FbQeYpOB!*j04ig~T2 zJw+v3`Ar!osA5vED`WE%ApX4Q_1@-`=2#gdWNQ7)j+S5mS{}|IUe&DVa+2R-Cj5qy z4qxUe{djdTQlbQQXeMB_lsJ|j#2x+q72CB#F=Q)6UPg<n@rY!)$r*Za&@UDZ6Q_&j z%yFvaomC8xE=OE@^7C3blQX-nC^0(}XlgagPec4(k(OU5rbU}3WHR68udOpG}=-*+m*KEe&qg7zoZiXOXlxMNcci* zR5Dgt0lMuj#74NeWp%mI-?cAqDXi8{MYz%qFXs3(k)0*p-jt`WK1sAom1xgSFq%Bj zig=KuuR6ls5N@g3X^7R|7_#Qf!Tn{}@OGc~W!n8YmJOnt1^TMG>~2u#~+;cGj7@lks~ z`XL2s$x&KL5g{G7qHGvd z`@3EAgts)7GY36}kQtXY$tu~eGBLM%n-AUy=}=*={XBb$O;Q+#(SjeXxdFrli- z7eSY@?MMjK>N(YCDyU0$(!FLIhaR7a{#cI_5r!vssuwCyr!1zy##E`@4;Fq{|EVxpWu#BJbt$z5iAuldgIr= zL$m6R{NIZ%@;y(=5HFsBvcbwJczD=|lA#O-1GbFhm<<*bM-N4TAA6HpWe`A~6d4pOK8EBPw!met}n&lakx(E;WROiYZ@BaCkhwCq0e}U@zde zzTxAW%q2R?!j!LBofRVq9{72Ah=-{u56Y`BSHN$!S4+~4?n>Fcv;OCPKAa;wtb6eM zFJ%j+8gnoab79YjRL@tGAKl(_nGl`u!+at7!+itTlX%W6;KYOi00S+?b;qzI(DK05 z3#()867^Nxiy|#$-3N{mHXJ`2&7D=1lh(`85U7hLMFX-*`}A$uTD^q@XfQ#kAP6tt zT-i$sAy5!=Y#~-s^zQ52w>HTcR1PuwC6t8-0Y5#WcbSloPQWVGa3e}vN;s;9-)RFn!b1G>F6J2* zzbQiH+e;)jog}A~bh8wn@CW0^r+Y3(Yc;0S@Jim{f0GE$;iKm*_Z^Gb$8jyz3O{ed z0hi9A^?QTl3-R{@=046}q?&9PV>M$Y;;s_c#qZmQ(43WFZ%~`Fj^^%n(iRbq{lVvI z{v1#6+K;AhFCXW6CPStrPb4HuiALZijLSMHBqa&S9UH8sAO zeShTI1WR-#^VgoRwN@xp#ky2mh@oD2#jk~iCQLw9p%OSo67h%+7E#G6*J1-QqtwOFdlM(DC4Ops(4T_0|M?NDewnca1^Fapk*3R=)31C*|(Mqnx9K7$=^dMS9PwR248i8a`77Jt(g!>fXqsa-Z| zBdl&31Uqk*y{XCipeF5_mBv}YjJOowOG+z!ZH|jxB__-O`Hhk#QPPcxyBXEaRrpjz z2D&iQ2+aL5dYxR4L!1M}T^+LWu(1Mbu4H60$|g8_PMmf51Y5B7Rg^&`DW1*;+I`oy z+O~GD2ZL^9B>k~Z?T-@nNtI(dy!bW=O2>+T`qAop|F8PTc@LT;p9jab?n_9N0S% z1*6>u32zvNOu$*^XMG_OwRSz+1qjK~;P%__q{+`ZA_5{ZDdoz8KTnbQV$S~)X3i5du8O}|JlMK7hGQ;3d;h?vG{$^LWJ!^p z9gdds+;3gjY^1d)l2QNjxMu})^lfh4I|D1(8&4WO5e&Y$Nf3Vd3MOuy0C;4Qr11s! zl{)UXA{HuGJME%}EY?>TvOF$ww$YD$l3IlqD-|#YHliEp;EmdOF?8c*-IF8)5=~!c zO^lQ`c~B@KgKK2_$`j;)Oq4Z<&wvAFmmfgd;o<+Z<#CNQfSq{ZrA1cyvF zL3n0QH9FuV8zZV&H`P1-0%QcK51?&?pwGcGK~Uq!*4ram&&dS}s7lTX_gaB5NWPo^20m7o6C4S}MircQ78*2bBJGiN?8MOA5-9ul zJ}0fIdGRrtoI|@@q;ultiHG}8UkF{6I+Py|U76t4>*bCY7kGHqS{ymDVuXfqlDwfn zbYM{;9RMzE-o=JZ#QcXvaSbdy+6zp<$6E*0dzp-0g!eX zY;I2)!**cztTl*I#d$-@5x2h=X=++wFk~sKOt2F%_#2CvY68s7KUh?o4Gm2!`BWLu zH{4O|Un~LHl*y_F43o;}4adtyqbo+I^xVLV+^k8NWWD{g_FU7#?i z3q}su_AhU3&TR!2JZs~7IZ5VdFOEXI36>hi@9pHHRm%VFM)J3SJE$L3!fmWvd*-eSwZoa%0C`eRqvg$LvlQ zA`9DZiQ--@dA=^?*P(I&cXqW)%;%Mr1mq?LVQf}@Y1{^Ac8W|%kl7jLY&H4NZz-{e zXnwd;?3`h61hQs$a&M7rO)HxmWV~G(HqVs0H0`@3%=?Nyr6$F-Aj7-jLkq^C1&how zoN9$OQrsGL*%KXD|D?HDw;Fs-=)3gL=(#w-?8{lx=j(6}o3l%Qi>rjb4F501RfB=} zCXR-lVUf^-Coi%WOvoZ(wfpFCP)az-Vs&MnHj>^M^}y)hnX?;Mwo9^20OppAIIWxW zd#@nQ|Fh15TZT4EH2{Qz!DFyO4PqN}dIkZcoan&zG-DO%X7$()pI(~B`G-8z_mRWJ zq#d9BHy*%xq`(Nc+cvIn+9TOtmN$b@8?Yl=r@8@Y#n_chCPd`@;BkXM>Vn9@?E;1j zCZ96+K~j0M;k2SNAtCrB)PAn-D&YD1nY-ti<4hO^&HujLlg+$Ra0&lCe4maD9hfv) zCdt2C=?4dIe7c%)Y|qQ@fmz4*6*CAjJwivwkfjL+Z*Y@4^ByB+%U~d2>wdH(lgiM_ zpu68zT@WP@E54#2&A$yF`l4ThgQ43C#sg>+%sM^)qbl0_AYyx{XV)C-SMG{4F{cNs zP^=I75Q1m)jsu)qSRe;tS|Y-4;CiW4fxL4NAN3VDh|bzKJB%(tH!VDP0u&sGh#=n_ zgfd}yQC$bfJ!aVxp?%kr@asUT?0YV{X4Di9$#S^N3rmQuqJYQeJ&1N&n=DUdNwo!+ z`&%+xx~Cw01=A3z{Jl}Gg25Enup3r6T; zVGfg9f-R@P@9ojn zB}z!^)$|<<)Q;qN7Q;0rCLB^A9mSfq*p4>d{r0#6L>c?4bk@3iMXlnVAi%zNrPANwo5YrmcIFN8bj z?tGE#7hN!NuN>f-nRs>e(f!x6Zuv2~eeG!%W-$|jSH1k096b=-I;1IRittoZHEahb zo8);OiAwd#Xey@YHrkfr8!JuxgGNgkAhuU4FbkVAsXg}wj9^o-HSn%sgWX^RV9!M! zs^b@oZnfHL(fdMPE2CX#p~;;3`puL9Ef74;!_TF%uxI~^m+48vG<_6Bx zE`Xw`U+JzJyrKECafjbMB<0E{h7$7)%nI_wDlPEP!#xN^P$)-8*ASjS__MgBlaDx4 zXTm42AD&W0whSUaGN|4UR%*bE@v>%xvCJd*1eUI zq~AQr-b+C_PGX;3-6?Sf3Og#z>5)O5HU3=D@()gj1);yCYil3J3cJMR35})jn(-rH zv?)^0kT`yD+*DgCu@5wvYN^h!NQx;G*JgRZ*(1Ht^(M-$Z1c4r(x+#W9N(YAn62)S zrujE|W5Bje?z(tp4o^|n6;xo9%^@cQgmpI0SO$rRIS!(|qs7S|B!!r6sPx+TB7nfI zmHMz!{p2`1mrF<$14xlA|W1>MGLV?J?vChHCX6$pyaA@bXlTELcGz^?yCl76Z@gC+z@< zh#=d+$zN~u%e!H_EqnFmf1x9)q0P3@SLnbS<7?Dt5|Dw9MOOZtA8FEEB>8tYC|hsj z>D7@lr+yV`X<1P7lCdoM^7qwSV?g?E2cpDFEfCr;<9ZPbC_R07-e+i?2bc6Z+JLUX z9B&M;#0eg~N8zC9VKlm>gmwjR{iygO1D%(_4lqYCUSnQaDdK{1Q%H!PzQny`T*c-R zmmTEIXHr-_TMSOVjgH8(9Moca4Vs#atK@Me83pWirZCrx(Mk=)0^xd(71yzFputngo5tGu#E1C9@axmqP`*KySYB zbHp#Y0LeQOpze`P(S_DPFxu4}+|5m3`t9QlORxl#MlH{lhcZ|aC0qhlql{?K9E=N1 zW4RIeLS+^Q{oAf7TD`5TqXZ!0xsbzX2Y)YL=z8S@$Q!~1qNT`wfPyzo&&O1i;&YQm zPcf)AONcXCRu2+pC}&0oiq?p`d$JbgBNPtZ}CVPqvCD_{A{6#YwEXNzYoWM)NM^^ zGGbQIR~i|7-iiv#JENgOt6X1Qgwy2Jcvvy+8d5|MEar2?sb`=^q{&_`($J3Pqb;w; z0wICunk|Xj5B1I?k~A;D;#yga8{t5)f=>7Gg1-l^VK=z~n`io6Q5b(BntqV=rdL)! z9r?#zsNmveqwH**IjXwJr8Ij^!`{Dg_lA&2+^~ULAvH4*mbtYCD*QXG2GD;W5%=nx z<=GISx2`=Utuzu+1L)3Zn9>3tz1s?@uqJRVuAiw&w%GdQ5mSIvY9^4%*w06|7+_|g zQlBeM@1@GI&dwEuTJC-?`+Qh?U9tJ`%zh;ju1=33#0@ZhP5QgrDN&7T={=akp4hq@ zPyYjRXr%9bttx|5$`+{UNdA!Z_1jlZ4G6q${x=nbV5yB)+-ardtb%3kVg&w>PKigc zpV`*m%J<1)-Fc@!%tcQ4LkY@RafVM?a-XNlb}2WWy_)*(`jgzR0oIvcFuG5urOi#N z(75dyq7*KVU}uvYfHw!BS(P^ghS(rBjQRQvl-gs+ENl}{X)QNugFT94J|fAwh)A+B z*S*b{x>~?rv8%p#CZ|Cp7no)A?Eph2#yxji_k%QV36}A}xS?ABkcav!#6b|YjPQa} zpe;}?`$4n%?=-hJ22Ce~Nm?dk_j@tx5`D!g8p=#BLej!YEe5loxRP5y7#pOdlD~ML zgm5|6JyRx=VO zpCPf$pI5g1f1GFT-xY(m&{69$3eEnX)wOKcZ^@z-uvlj2O=#1_83s_=J^UX=S7GMy z54(54&-VVgeVz;`AVc%I3#(Ah$#AGWglEi#o+uKJh>-&_@y<)`Lhco7aD==gy*^U{ zSZzh&KXhs$`$JCJAdj#@zzNSvRL^l++9dpimuX7pfKmkT8R7?&0`O(Zy$??w@9O|} zvJ`OYV^SJI_NxP0U=jAIOdl73;Gqndha8$0xi^US`Rz`C^8yJEmkfE4059-TJX7t3 zuOl#kN-3}$L~JQ8s|$#7?{S9%;u`(;LF!kCE$&hn%@wdOI+k}_yBATbsi{KufH$^{ zBM6!1+z*QiormZ0h&^dw$J2OPavIl<;s>?~g&bgY#F3oY0*u0fHU54N9r1t;FT@I$ z;4saLosXd(!6!8T)GOi{tzj8uzvWhjfUf zv99+J!W}5cicUZcqE_xwY+A-tsfl`_?_+H2H&ckXkiCJ%(aoX27q%PE$+~eH)n1{CP88+Ja%Lub-#wdJTq(HDYzD9_GRm;1U? z5 z6Q#))px77b>wG1(7b196QVDdCroqGGf7{)@B1-uFYGt3~y;k<{Y&nn3CbP3fZui9u zTSXykMtLk2&YNfQ3ai1%&_P8GS{IhwA>Szq@lRE*U-+!|B>f%5e_|J8-)6k~_MT0K zK}7QFqWt&55e$QWC2w^CbS;n@AH4yt9I-+-P3)l<1j>KwYREY!eL3m z`-l{W&bQOah2y=KLDa!J&E3THZ9=vO%I4yuR+|^gXYC9m+2l`?$$BiRf3tUx-XSE! zGN50?5Jbpk+Z7?Wy0{M7llxbv)q`87ne=UxtN$;fqn)p#4w|2+x%yk8C_*%O(MP8{ zld;~1&;7^B4SDQ8eBNDHfa_xj$;s1X?r`}ZyFY!J>H`$=jr3KDPHO)isJ?^oBP*T( zKe^j8yxo|{%I)a_p4Xcl?AiYS-gu&MQ?k^t!2bqU!K+vAH=pbyM-VAc+zka_Ijs}T zd@D^>NRXw@hhj~nujhZ9yi^Yj-P-)W7kfai7qy|8lSP4&I1Otk(e|Cu`0Pf6s-&sg z{Y%=doN)NcJh;U|bPtgN%cgRbW2NL0^G+E?W(=ROIP%GDEbD)!5tWf*-+##ox6dCj zvV5AKqxG#91r;oB!(LURuQWuRR<)T#w1>EZ|<4Bo12-{?9~oI z^A-Ehx~5C-bmMa+$R%Fvn&ycjcV@_l`ZYRumK6HNh@1sZPuq?iNO1JkG=@@~W zv7GJ7D)c*4hAzU#19tNGmrhEF-^xx6e3+DaYtg|wV!w7i^uK;r=?=1<9$$(1uC1?9M%fD_5?u{sC4|)QL zuzS4;GvKh`Ui=nIc_&+zJz~?tEEBj{lvI$Kgpg-o&h0_w=`V2+)B_u;ptUBpG!L&C5`c z`U`-x#tr684$ch9){3yD!tu~=PLC0png^@SCQEep%O~y70vlR4_!hhy#9-VxM3m^8 z0Ss6F`=vN_<5KN!O=?C4M2LlPO+tZo?acWaC+}qFHB5DByK^k4TU?;u8;@I$`~-!z z0vO@Kht#?;C-0*`c+AJ6xZ;?^>!(Qpu)R^~tMN8kjECT17-AV(zqI#m@E6hswd_0t zXYauVSFzkNqy0nQ#>$X>^tbGO6$#4|B|O1?`%uOtG&%!1LNK(e1MmaY_l14G56eYU z_?tcg&(w$tidtN!v39yY+4dcg-FrvAIz666Dhw{X#g*^7x#+$L{>-SLmYu@mto;AZ zA)F*xZ!4{{1%q$O$=QqHze&s{32XWOa?-r3+FAR9>yFf8%xw^2%H6*3=Fy4kkePLd zYYR=Vv?4LV0>x?5`A=~9e{2D%NlGmSjF5cg>Cb|ba(mxDyb2WHL;UWi{Z}&eTtY4r z5Wd&0>~k0%93D0~1yR}E)XlBsx*3882easG9{%?bD)ro`U)gzdkA>}9Y^z*kCI9Q} zf5v5o_sIuTe`|1py6$A>kt9+@0CF19ChFKFu|V%Vjr?_9G-9-xU8LM^={h6m+&J6WIIgt zjr#_`2xIZsHQwJ!><|x)leK(az4_kys)>Kw7+>bxzTET_doQ;T*F3_4A-h_se>kH1 z6B2-q4y{w_J=9mW8N$}$Pt1Dpz%WsB@W|~?ADmd3V5k)9kh0v>|}S~rf;5+H={29??mUj zA;aizA7S+v5{+^h5v)=5h>@9UClx1u3^}eGO#l-|mQ3b{KX8}LUd!E^^kUGIoEk}g z1G^jw9sSM2LoQp%`l{B4svueNA`)0R?bLJ{6g7~YC9mFBLRi6X$*oqKgmYh0Bp)GU zf#*9dD$HefV;{o>(+OfNIK0gu_+P8}qFhqz-%=VE5_ljNHL2^N22Uew&tf-CXgGA% ze9IDuLnkg6`G=ps>-7LMFC73y#z9d;71V2aVGmi|bC^t}?19}qPBEZ|^SQ16d{0vW z)W@E_!I7RJ=7yXU{jn#1$sT!B0oDJ9iVq(;F2iHG*}48?#7veAvV1CtWIg{xvOR&Qe?WAeQ!Kz~OoAvLdZTMHO zP|{Hn%pBNm{4+e`W|&Y>Wxmy1Z2gT^SGCgzt3P{U`Fiv^XaRN5jZXSi3XxAB`C#yb zdMv7ZHoUiQ&Z%XIc~6IC`v=83)_ANdIflayHC4hov>rY0_i}RVa!L}oMT9N+jw@r_ z8{`z>n+>BlSL*()ix}N}V;}6+9%}!8u7Yp3ByU3w0Yp0>6RT^oRQ8Y>xZKP-`Ok;3 z<{=o3T*vCGD#O>6JbuPy0pg?Ak@FLS_;>D~13OG(qTt?TdYcVDL8TkxD&ySPl@BM4 zt_-%V?4dziH9wg4d6^!+o)1L|$+T=`Uj=W&v-aEDh02j8t}b_fIVZT%+IXRZh5vq$ zVQ0se`a54Fj(Kmk^W+lYOh!az>-hBSvU&28{=b%w9`O@M4Gg?f_;1`z^!&F@<+mN%|GW!0e8k+3vaXcGQt@9L#uON&E zV4NCqp69bq-)+e0Jiqni{d$84-C}g?sXa6qU?6yA)l^QIckQ$0z%W={3sqpchB{O{t+>AFA`5u!!imilcjEM%|Z-RhzNVCZfv8Il$@uSa7fccq-MeRk) z0h+4tnnY>N3gdrsz7G>tmt}S?9ihbD?L6lEkqWP>%4^_>Yw1U~Y7*G9p^F5Bgqx-r zIez-8Z5k|ZdPsF$TIlI{f0c9$fx0>=`l{(~H&$Wb5C&+?t|KKSM72F)b>eofaKq{#xS=o0W_YQIK zxJ)b=ZpGK-ZgFtxs?UOQr{1dqXrzW;Fn-ltKj#SJU&O10Ad72VNQVep?bJhUJKZVQ zP~yDuZCRPQ1+?g)1#%bNV{F+f;utx(z=4UvZop|G84MlPQgp!vvIChV3CK?zSQ&l| zJWa39IK*>ND&!g%V{fd#ltur|ke;OYk~Z7~njw5Nxm=WB`ri1iD>k+xF-CA4!xm2p1tHgmvTf|GcJSP_T>rJ5sZ(aL3Hs#gyY1a z$D%=Q>PwSmYqPkwUkf#!k&2Ch4U3g|Lyo~4S&O4$e`|tgtn}tYBM4aEoABJ!-T7^2 z6+D4{o{C7iGy!hvdB!%PvH410l}~pi_uwHYiEJt)0Ug@?Xxq#B>mTbR-*MsYsh9h5 z$Z&-aebfv4N9r7Ovc{E@RzAH_nuG3`Nk%iy36bDj>tJSZ6dnX*upQW8!^X3=E4T-s zR#OCr`T;G%%vMS(Zm#z>2kj2C-0IFr3+Y`G9fUdb*{5bbWiRjk_D9c<=j>?73p3iV zRaU&J2eBaNd-E`+lD}a7qWZ#G5ObINGy6;#9b->4_S+kq*+4h-a-9v6@w&IO zVS*FrG>AhVr%&~l6s`dQR+rZ)@zl=7zrT%X?qIdBaMxAEMov3{7|R7M&FNCu^kt-t zN9{jHzhaj0;e6n#SJ_|Q!YOYCDI4~80lv-FHM;gC?Fx-$>R7295J1y=?mncI)(G(0#`$25I`<0Wg^}0-uMkfu9%r8Uk$$QUybwceIRa8^hAs*K)0KS zV4W}>aQ?mfn{{B^rh@wS&LtT3^EkvK-U4Z?ro^;o0~m@(3ZwNGeZ=raj-Tlid2&T3 z>(dH2>HMs^vFgj^Oq&oL!;{vu$7k4u z?N?eCKE)yX_y) z;D!5%rMkCy$+}rgfVd**)&Y2YRVw>xc$@wI+nwbsBc7Y~QwKvT>#gSVTW;^>wNT!f zjpAL#Zu8}-*o{u`pS})ydS%{_q4qED3NsZLU0ooRPtc@Bd4&j#ztFv)%iRw`)AmR~ zn^tQ?R?rR-KmXtfP@<-|fetHgfhjX$$ySbb9v_5_VpCMX9H3v}D|!cD-(i94aF7WSKSm|o`840+@sh% zG3F@iKfieIAv!C%y&5sF8lBnfrm3qAG}Sn>0|aL$%)Neb0ZiSvi}bNwEHDsDV$lp{ zo4pc+u+u4;34C!iNLSVDIF_N+efRTcNpkVeKvR`#XuFXI!;KMJg1A!s4|nM%iC%0R zo4a!)ofn+~rAKbVajS2--G>j_V?zcQSbiyt-b+{NTilbq>v&T4e_0c$B~^&dil8<4 zb*u7?`%CxUszV=Od==oFHya<%m>2d_ral&Wwp)IF#z%Sta{h%;II#kD8Mlu^kQV!} z>3r+;=_NM-d!7Gyy}lvQX=S{aJ^LeWMSsy!P-H+x=X)i4rHR`Iw@i+B$sdbp>5l*olv%l4m zqI8>lraKjPcPhF!<93C+pt8(JqDJ>P&WD$L^5(2va8Ke`wDbZpc=8oT$u|x4+1`|} zDd(yAsZS->k`8H?jg|O@ZI!8)5C|spR;l%L#FS-J_u1;d&2;P6JgN^fpl)}h=jIBP z-VwHY7faHyCF*!xW~5NAVO&n}^h1rb!;@JRCMxcQR|gbR6+pUamezb}$#H3|?P#9M zpyRk!dPb{3g?^pAc9T2jC+x^`k*j=zuLDvvQxibwp>dCWrr(9su7{|<VFKUxf8)if!~*Hx~sh0>i&ePBBqeB65hhs}GpS{4>s>ONh3 zfPAU1!pb z;&{YEx^^W#a|Lb1OeH?*-b zmTO~LSE+1AtcPX1QDe9b4sGLUvdYL*9@65B^tptsW=~nPHSICbWv6AD{byL^i<1mp zNt|4=M`S_+jWv0h|GdPk`a5F*6SvL(5A5&n>n!1kDnZ3}YS=1&U5pK|HTUxu-4o&& zPjoIxdSh9L^YeCPKd~&>JIp}^?r1C2I8<{NELt+oVn7Wr3r7kx`D6}a5ntJtoOWkK zmrt@hz#5cXVW0i%8@1C{$bCR}W?lx?oZcVH9bSP#ZGbV34ygx)klLOt_G_n*vM@hD zKS+x&wkOAuy%>jC&EN|0Xs|P%Vl#moC?z{LVVb52R)L33Hs5w8fa>lCs>%kcaLJnY;LY~q17UUuOoc&aAM?uKDB{|yS!{KN5uyxP&Ies?| z%*H~bYqz9j(`3CD$96@EF{~1s^}&(}q^z4?OAY=V6ut%zKNMAzF}NTrSr=8}7den) zO1dhfDIR6T@NM8{dwlJMhg1!OpiizZX`-`iAEc3aSv;KkbyknCz)@&$X!{oZ(aE*g z6h{zlBB7^e75&FDjaYKx&x=H?quE@BZ-{){)m4HL_ZhQ#_ecyJYAU9W6*#Ui!>Ok{#jUi*(PFA}ge5MfxO&)WHMW$t2HT%}N>NK? z^nT-ecynpunW4n!J$!cctEd0?_t-A{v}D764-F;cyJCS8?qNCAmkM3wqdiSvEM_|K zXzb)MOM>8}d7a~!_YIASA{dO`psS~l5Ikm28}KqPeE53wECu{JkOYY_$DWl;j!vQL zWykR=qm^BE@v~Gdf*Txvt*dFVn8g|hoA4pab|u7u#%m<~YnIl`LE@H|IG3l;=f+FZ z+x^?tRIX;`u7~BS_?MdlFTW_Oa z*lv$kQyJhS#C~c7Teg*t!SaQCGII0xu=+*WCXgVLQ*4l;9YR0x+;X{R&@D-V!4y?> zmPfu96Gr=;r#nj3$M{&f({pjNvH*5=a)<}TG)Y8jmZr4VH$;flM;^vC>d@d!y4iGm zPhB3zEL$ikFt^OPbM9_7JChYpcWk@D&JL41Lq^o9UEnPxBV6i9XzF%!2MF|`ErUT8 z#;(hzUJcTV(}X?+c#$>A^2|PIy36Bfjp7b(3^DYDi)jb2DiPAM60j8Y>;VG|$m~Z) zuRc1Nr1y>!12gVFM)-(QfB|$N4?Q{Ouu(3dJ^0(*AZOcw9WBc z4VSA=Pt7^L$^jds^$OAqj0X280xO$s(jVYl)6+#-{C>h0hAsl0?y4jwT~vV`LRqGwar7jJs4 z1HnI)Z-VExVEk`q3ZUPAx1PNBt|&f&jv>joeU6=XP0&;~arztE!UzyKdJT@qD2H*D z=Aj+XRx(Eb6rgh|a|GG`;6Ela`CP&`m~tZJ`()ytaJ7ioGoWYn{(G**>iSkbpfCu& z{ahh|;ak+QGKHKe0RkwP+fFOQn;xG!=S>lw~$;h{u?ZiSUVApleQy9;gU$W?@C9jop)RnY1cRV^{x?+cs^@AC+6?U3JWyckU#U~XXI^P}4q3s;F4TNPKzn@xmnRvDMKEh8Z-lV?5UN3W2r z!scmR<57PYk+TEM<n6i9v8{4KD%4=6VAC%lU$v9}`NiUbhwtihqu*-;RhV%F?>U zSoy7xX7jc6>QIx}@H*oX^9r|VDQe^HSlOdvDgo{EY_TJo;}&{nrjF6sh)p$n?Ggm{ zfUb3aS^0!`zx`4r!s{0;dwCDr@X!tKy(RJ6QFe6sKh^WJWy@nudOS^5EE*DikEGl? zc!yqU)3`$uViZcLwW3%rURo@yUMRNn^Lg}1Ry76$$!7qd1i~{M0ph>-(>}czz`7>x zv1A#?=4H#ZXy7FM>k9OhYwZgB$CUruHT8LnDqikZpvw^?TzmY!yom7L9lnb@ddb`P zTs2upAz4t_A=djd3LGujN`%OyAS;MdF1VoEe)%m51JF-XD!%Fh zhdPy_Q!D?@IK2qT@oB=>|~rz4vMx z5faLGs(S^VB_BkoqTwtVd%g<>)aiz15zVNu3y$K)LU~2x7m34KPbjB!|1baUG@;I)5A%(3Ff{8#N2Am_vVtGG7 z>JW(TatO!dF5@2~n%Nri)5(rew2nZRNAuw09sBr?1Tq%Iavba*Aw z%R|1|ubvPn>^v#T6q#V|7cNXt3(WMg>UJrl>gShjDlW%`Zhy43PU^A{;u7rnteSWQ z$?XP$E<1X_Po7&+pUz z_Z-H2g+k&bt1863zkLAPb1ftF=djCvaD~uUbHAP+-@)lA(_kD=W!(>#Fu?gh${C>Q zXdd>zHrg|&MtfH$>i6xoEHC3Y{c_HActX>h7X*K-n+4`(W>8rLDE40$K^MLKwGxsy z0=U}*hQB801lMgdwg3fx*@y66GK!L|0-{Z*8MQuii+{W_o|T9{m&6@LUV@qha4 zUC?rp)Z_B&F$Nqv;b^2s8&p?QGSdSN~pK&qRY6(?S# zS85nwG5N@-;{##`2sDNunUigOQI>HQ55%PY@M$5kO|*f0c~@c<4mscze{##Sj9i=O za+z7nocZlv*WY6(@}-dDTjtc995}?lo(y{)?%V;b`|Wo^pzLh|fA@_E z&D|u`dbdyiS>B?2k$EWQg5_# zHjaZ%M*{tn!XS>?xhWdPs3d6~w47PkSP_<;7{_fN3Y`u=SR}^jjE#OtyjRI!5BQm* zY<$4HOdS!lO!mmQn`rj;Ibigv0!+421fW&xU#|h6I0TC+L)AzqChOSt89rzi)SHYO zl!*u*Jy>UpIz*M%gq7Y5ja8aS&mAvoBqsNt&XQh z)B>ZXxr3_RhPlKJ&3JNnH9#kz*%q&hBh-o;a;O0_z8n{a;mL65cXf%9+3Sz-^X{DM zeR1(OPqujV9359;HXNUV|Gj0+fC|BQuCB&2ou}3p%l=ZhCxO@`#YhP~Qw3u!)!kCv z%1xGCGP7T#Ubm+k-e0zK+-hWf6z4R^9?6WZ(su;hT*}yBm!m6F*NIp!&)DQQxEJBt zHB=Qxy6n!YY@pGpIbCVK@~Dzl({I@8jT!k#N1ET+Fm@XDZe#S&zg*!ghD&oQ)rNg4vh(U!Mc1y6!qCQwo!LgMkH1_Vp2>qrT}A73tB`uLF*&IMy%?fXYqfcj z2$^;?Z%o^Oj-<<>t9H(~tG;zg zB%vnGc@_7}5l2ta_bU#c%axh|c76LcRZ=qqzt!7W$IA(5ohWj{^GkftSa%7CXgkiM zvhO??n#Kxe5>fs`A~utL4LzU#&?t`-OTChMbFO`&G}gae`4n0hv9-*^o+=+zU#_Dx zdsCdrf3-SFH_30`dvP2y77aUO>lA^>Ky?=p?2#<)*8O-}tP?lM-auK#++d(3?{62U zOhz8Ck7m{KUUSs>drcs9UU;tFQ zE;km~R_HbR@w!ktxL6$u!L;y1#jlwk^}snCz)Vm2P`)f|m102Bc5o;e40y7#O9fcK z1`E&>ROCac+q{a7TLlt#Z`qYj+CgDyoK;Y5vSAO*DuWLV2C=7>c$t6>*<)DZ_I_nOSI^B1&+Ro^W7!$SvB<@R1djv*%t{zQ zGj}WcU1LwqqZ`h>6qzLZbtTPN6Thgo2KK)@#R^LFjG4#c5Gq47bN%uq?+ciZmp)K`%&>&EVCOBchZ#qg;_RU1kIQEPIe*4V-Q_aN?vI0?6^r%(^4+3nWojSXTRv!b_d`$9Po5Qp?J zU0^olRTk8!EciP&rL&AJjy*4cTYTjmGk5Edn7}Px;IWqnD{$#_CMVF}E%*-iv~RJJ zU3d5`UiQQFH(Olg)0*Eoj}vA(Y4VooZbJMLv%S(9%@9A?_E-4xX1q>TRNlFk9zK}O zJLp0>uUtx)a9ljadI2_+Zr$u^1c+PZVEh$Vo=X*dbWue9$46M|Kns$c(xq@ST9LE>AjWEUO zyu%=Yo~Pu!INVDeJ{c=EvY*Fw+GUOQrr>gZP<@B{MHtZm!%%1(45~y5NnlqQQlY-_ zJmqTdD9=~lCz`FGpYfc#D;np{Wi>JWh(=g)Po1V=hfH^X!oYY(F!1y(o`B`AyK>dT zN}M)0-#Z5flsNTX%C^elPn{7Q`#I@~P$xlKF04~UHXfWTm+S6XmM5k*;A!E*k(-RS zg+~b6rfPLoYPhhA926ZpOH3#oyau6;vG6%N1bh_?Fn)6|idi}mC_MYgRwW)BGQC6> zG$_vG?HW|2A%q*zN&va3Faf3vx?H4fMf6xmLh)j^S;GYDoFoSw{HcYEz|^4^H{LSZ zu=_LK$MDu4X#=GFZ!LXvPJ_LzmEea#K{FYd!$X1cprwiBS!3THirak-ckgDciG7?r zSw+b`5plea*1`UK8Pg6dCT3oY5&Y*R^F;zo-s8}e7zoG>`I_f9v;039OA*LO zqBl5EU$h;GS<-~6%X&j({^hlWy>@6J5_zfqnz@*L&aUIpghPu_$q>yO+fXsBS7HEY zC-wxZPmaa|055;>`QeM$YOpTsKrEnw(F_zeU%SMyD7O$7OWo1|EE_q`J+_~H6lm8) z@27S{hfK>#uSrw($O^_63y*mp<3vd~5u5@Q{J86|)h@8sIzN#K#+L7fpul2|bA8Qs zE}BvPUCSOi_(E6wpB?)l%TOsTUh@LWa3#lPr81o8_imWSb#Khdbs^#QPfH^lCHI7$ zz;Rre#h$(`9W10JTWG7{jwD4+k4k^E9De)FQdOy#MJ|DZE0mPe@@zPuKo_IA(Nk=; zvT56b!Y0AVcWy@XDT}eqOtsIZNbl3ZfCfe1xyjYH>IWO1n)0PfeX^-HY_aTxnK8lR zBNaNc7j)Ry`@_!d{y{rLS4BGy9|#n1{z|3&%B5Toob_t0ML}es9^1G1HMid|bXjhh z*xKota!&P%Blh|7ETwSs63wi8uD|4I(9X_oP3o-s^&|PGPKHAzkY;_Jjs7G~{&e@f zw|DV6@W;Qux;bo>8#^{EYu6=(e81a;oTgkPXBZpwo>6Bp^VbwF&yG+92go5i5;;Y( z7arI1w!xA$OJVNKa>Z@AF9;iWHvtp1cuI=SMMT0&r`fSiESKi9uebx-@_t8TMdd`` zGXCfF)CVZzu={1pFz`-Wzlcp6`$*xUh`z4SG|;dZ6+aV1<-5;|6ZOZxyu9zCd3b(W zC4!XS6|C_2nA(G^vjkpbRTbZXUdp&5KUfb{Ul_|(ZdIL9AcoAkEPlFOOetg^yx198 zXBaQ@ErLpz?M#_+DJ28$^r@4a(dG5IV%bPNlB5^Ncc4$am;*Z9l_JuBXSz0#42&(` z4JAG@3S^|x!Pf@EaCtIaa0g`Y(7SlK(y0=K_(w6sCpaZSV$+euLY-gNiS4cbFByI^`E*|5F-W%gzWg zhB?g%OTGP*T3RynMVH-I&ia3I0ql-0PI-KKPion@REDt2J+noH-ju$8v9ovX^%f*( z+05oLiz>h!{*Q;;7{VPQ#s2WKSKzSGTK}7W9-Ma*9D10s=u2qi59Pm;;a)Fwzz`)1 zao-j>30e0T7b7Z;{i9o16lRz>C?R^L*zzsmoo-fx48uwr&V!E>MbkBM#huvTC z@{;F+(U;9JMEOF*u8vfe1;_?|1Ckn)t82bBh;v;8NI=DZ{3waSpE(R%d>}HkqS&^{ z@yUx73VEbDdok1KnHp!#W@FlCcdZax=mQT6HP#n(zxd8g>v8gmpj`}(MoZ#P6}1P* zU1?9$6t14vT~Z#972-RN&@lg3cXR_ zZ<}@EpVaaDg{)6Vtr#yl{EgA<Vz}ay|sWQxPRN_)NXrCDUD@$2!Z^L zy!U!%GkL3jeoza>dH>pJJrMeehGq_9b=5u{=uD?k)7!=S{vEz)>Cp4li`6hiKFhqX zoDO9XFJ^qtLjPGJlwhxXS1>aRX%M6jSNQ90|8vRz`$qq{M4H~B5Jt1*t+?uiqjn*{|(Uz5%8i3KIhHcBW|BtFfgP_Y2fEJ zXuC;XR+?P+YE^Eis$pM>7u%O^CJwRlTL+=JHQJM&HY;3G6&)BuTm61NLrzd=wt&*@ ze)|S&b2S9pcU6JLX7dpYx`=7mP1xFgj;DLSj-P{QkE3w43e*cEOuCR}KbzXg=XoNDE1QDPt$eOlS784aH0g#i$Sh zc6aTh%Es}tL`u^BaeY6s6e3l4&bJX7Q5bjGQjq2)?yjzHWiVSs!?x_JZjxA~gBXEs zuI6?YWT)qlpVWwnHC^;k*{8#7W>f#?;Sj&v^W&X6yTPCqALj@@IDYdike2{Q26D19 zonN8l9wMqKpeG#ZVR-w_1ub0e-_OaMg!iGvJ$)A;R-CudV{Q=JODzV1b;daDb(*fH zcxjeSpQuIO&9A77O1_5!q2DjZdTBI976u=30FU z>JQUA39VBfU#SO#fm5-uP8?^8#H$%}(6w)nqy%Y#X5ysuR}aSgHX^38noSD?8N(NM z*e?fd;JgLO$B#j*A6!1Ebco|wW0s%w?03+$w(3!oEU~1A2Q`YVE87_rbH(%1MUrof zJ(a(#H?HBt)4>-pv=v9#+Bclrr8tb7jZ+kDWoF(txq^!r#14^wH1Xcfz0m@O1^nZn8!EulG)cs$e>TGrlX!n~%<|CD&z_s1K(8hPi0_A@wt z2~nyCKElUoqm_^>8G3OnRxq`M^DpTfqyPy8^kluTkRXAW@TQ;xS3H_XN4gSC%Pg<9 zFR;}@LP!LSI2RxVky4y#C>a7^_>pELg@9rn-%>pgs`_F#HRYcxsMp{wH;F=ulX4>r zE{P!Ygf3e#nxrhRCAJV%1CMT`Y_uKvp2&&eKfD1ns}QDy(*32{r*@WN&ea17=tx8b zPF69ai&qg7gnymQ%+yl)eX}er2F})0jmmnX3qKrXx-NeJ0+!ZLqOfxjBh_tRP8pCM zhT^^ZG+HSIY||1UNieA7z&Uxq9>Xw9<6&Hma@WrLEKwf6{cNZKw2R>qaR6)N=o zUNX>cq9d4uOYQ6CXps}!CEIJEPJQ?e+4HVe?$$GzvkBba--M7iJ z6j)|62a(lWK%;A*stvFExox|BRvet*zVL=_>h_Re2{bVp?@Mp$iN6Jt?k1Neq`7u_ zj~Z9meDGlahe&eUk6K#6`@3Vc5>x~F6EL35RaCNwy&8BWPwe&{QD(25_e_(qSZX|u zO<6&clJ2&Si+w41l!Qg+r zF;-kWf(Ae8m;?^a9*iP0XbtBZ`K1}vwN(I8m#@`44&AJxbpZmLBot{b3pnb_4iwn@ ztt#c0)|J2;*7`eNvXq30%Yug2^`3|WHe}wzD%B5vJoCqqQJ&dB6iDe^ICG2a0k`wQ z_M|^OSe`JidxQXD6rAg?@hv4=?l45bAcA5~f@G(pAAbJTnNvH*jQd$R0~${AM2cK~ zwL4CQ@@kz>55vF!+joAD4=AF^X{M41{ZtW}0H z+c!hD1jNX#k(W4FyKNz`{BH|TVhA3UZT%Z2Y!kez>TbsxF;APX1T>EKV`(*zl!%+! zouX~XZrYgUDt-zi##lb#b@%aG^qJu4QM`JN3rC-H`Nw$2R)^HaOut1H%7+}+F#uNTw1 zK3#bpR;aj*;JSHVlMSx6oXYKZ7`+2Y_}}Tj=?R*LJN{8cgheaaFK2Y{+lF{H*8}vZ zA%{lIch7PftlO^X0nON!?n!zBohvApW>hquDqUkT=uRqRY|9aLn+_smuMeXd$ns;2w?)VxUuEdqM z$ug&8@=R18-MvGogO6*|=w$3v3v)bnlcUc44&_TN%e=34CGkx=(^j%QJ8$u&#+Dsh zWWweLql3fcxLq!vRt7Z;OI;!!hlBDe~CH!oqe~las1i}4@sbAQUPwbdpqKn;Up$d_T zK)?qELBDyZ!v#|Ggq$myQe}?&0iw#LD%g&2UxV4t`^za1?5UHB;u=`~k>Z z6}qtGLye!gC#@!)P0fpyV-p2SJ#@30^vmMz#NnIG0)ZtzGY!Wh!kEG5<3pa0xojVO zI_JRtuNzy2n6CL?Mu3(3ZC|U>y@xoNjA%)vfkM`E;JduCY*65KZG>Qrp>$ z>d@ci9{18avm5Q3$0=2|-F=Rad%t{U7Z8dOhGB$BrZg&@^fK(^kY@Rr?>cW^Cg`j#w~Y>L0@NX8@&`?7O__t%*s>7(*vQWOjF-ey6315> zcPD2_wfZ%h(oAig-sqcBTp1E^JIA_wXhK`k5KUih7T2ZTU-{O=)Dfr{*RTiQ7V4Pv6xba{9+!z#nd7fdNH_ zwO1Yav8SbzRTOSz?BSq>j8b6Lco)&F$?_MFM2n^bIog-}0HLbC#`{&8{ zdfoRU$5f8~W%z3s$>2H=LpVrDG7M|3m4udw_CcdBlr3x#|GVcd1Rivc%07JYQg4ZK&a>wY@QfQD8HRhmKI_|^x1SguHpm^UVM`~*wjGrhMzBd;_$ zxj;lS))UW_zW1DFtQCA&(Co|@fnua-s6 z#wc7Kev8EOO>NzOPkHM?ZVptDkr5cI*e7^aK#2FdHY@hMbDWl=e?>i;)X@iP>Iof| z8<_grWSX$hHTUnq5#Octr?s=ZP6hH)Jz1$lUEjuX7ju2x8p(^{#y|WaC$ z%=Oq@2?m@pB*H0$hRW9No1sLyQilxn2USnJOs;1sI-&`UG z1vwjj^;$+)tfw~E1u6v#jn&ykxWhp7l+hZ1v6SMJ&m?WNGjS!*&7ONNsyKX!9lWrl zK-Iom1k^QsV~W9RFF)SCPYW06zUotKA`7HF{RxYFaqSKz)|zs8I)mH}%22-g`V!8Y z70SN9nXEFcTtE^}OXfJ<5cgD(4FH>f8c_P(%A_6v9g)&$CxAqP%FDoeuRKTez5w?U z)bb)HL+gS>&K>*xE4Rz>#3|Ft zMtdQy()qMwAe5HOs`|s{XQB0++~#EE?kres7bX<(J)w&lzFqwZk5vwQS*|;kW*s?_ zdU0E9Ty7;CJ{M1D{nELI&K}hI2(Fxjyc%y5y!K>_1h6gX9?=&6w$f@tZd(xcP1A~T z{3(EVeK8K|7BJJdP#d004mVL0oX{`)L8{^(#Ixjo42Z=N(h%`jg;WN0T2A*|l7HIxo@)@v2rq$xhLmM@)jhCeRfYyg3i<&_zc86SbEI>z zl;_y)<#-e9XQzDmsi}EzpfP%zePjY)c<$^4T-teH8AU;vs}0^BmLFEGuhJFG*zSiX z#sagRHn*UV;zjwwkO51UpK0QaSqgyWK#0o6pEi#TUxSDO2sXH3!4H-@Ta4UANU0;{ zUyWPe@&oN#ND#HF%ugEsxQltP)MG*#HztA~1x*z^ng86*0BSD}{_UoNslgVGaH)r% zJXms~BZIPgz5#Ga_L)9#<%yp?zr$560h+?r!4|-rl|R}>sIT9+bSQj%-1X=lMsvgm z7eB~Qgg5_6Q@O9!%Ke|PKZihE^Pdykg)3m5!Iq$Q3i~eZVaPt}dJ~t!xzK*+!ARL% zia=U2=25^~!!? zGbOQgDqU6ud0lw@!7kLJNLhNsy_`3N>`0IH7$@AWCDa_PDRnVsPyN%K#Rcj^y3{b=1cx)n*uVn3}A1z$c@3WE+KFP62V4_BKgLTLlrgEV|hX2`{lPewaIaffBF? z)S!+xIBH?yk9qYxf>9xei!G(S12>uh1Kjo*1MYnBOed|iUr9e#8W?+lDx+i^qj_fh zz8^$H&00@b-BRP=tIKj?5Uvs|TV_92#XdxJSMiB|gli2gZy@s5tDaf@g`{P$Nf$0c zAy8n&s#U|w*uICjxE=hy@qEv*bmeM&VHR(ev0t>@{ITV1{!l4s{?eXk9<$Eq|SMxCwhUhdBktUgWOa5Ws;UNMjOR9fjGKE-5bIR|(c)TrC0MIShc6YJ zc1WP^1)B+Fk|;*Ar1;w}V*eTd7!)Pam=#1AI~dSzaC)l}9Yzrx{Z}ODNsP(|L#y4; zYdv%zFOXtvM+e_KuaVRa$7}E2P6v_6uKW}%(7yn>7O^h&53D2UTu#mh5iT7Q^%nc! z23#t8x@(VF2^j_CD}N6JhSJ7x!~F(%bpC?A)qBW9$vNsIe*H0Z(hCk0jtZ@@gyFtK zXNdBL?9D?H1_h^%Ie(e2cW1z@Hj8^rx?_BP9>5v*5^B!8*xVBaHkdDzF#UJ`= zJb0*-v*$F%{j@mZ6m$XfRKm*HE|y;_X|BK~UWNd}?*^pt%v;v^8qVqmT8;i>;Vpx@l`4g1E4$oo}`S zOQtM5jyFd8@ssLUP05aL3C{(buUOPE_7=YhD0@`T0CseCaUo5*8_NZJY!ow-`#!gX zX0D!Fe=K0BsjKIA!VlsoKniyha5SYkxq9n5Kk8+tZ^qkkd z7r6*BdZ{`NFLlSs&)q8D=MN5{ zt2jPD(>$z~{{He)8vuU@xx@T-g6OdM@3vz30MB2meL2H;zR?DdcnpEh`oho8^d|OG z7ZOc@Q13`yrj+-PIS;FZR}@icS$F6^|9pWq$+^1xJj{du6sHrif6RE#|3TaD!037d zkSIcwu(UBRMspDl7>i_Lpe32gct5|7`X*%_sIgJ>t0(Ya> zdWX6Q6H@G8RiiBOY+5pEmJ6NfcEcRAVt7za_wrY4yA?h>p^iR9NuJXdi}iNW5r>Ka z4hoUfmi$8i5|AIG7x%A-ZY@Hw`8Nr4zc;@@eq+nYqG=W0hm$L{TjH6VhwRK33dMhW zO$wo>aq$k6Hl8MxFJAbY3!r;NXtU9pl!qKJcoX^WV-c{mKWp10(`UIHamN< z+}vr?UE}16&X&7kw5IH@mJPwAvX+Ywu8n|x6%gvWaN^`5YP8Y#ka^dp=b#>x&D&3v zYQiU=1)${gd~-XF8poYv8S52z&pD+D654IJE0UJ;HF$etDLc0V=7;zo~@CkFtbyGm%akT^16k&kGpcTFGJ3oP-QNP(YuzqjKeXa?O{t_svF#;zodZ66= zA(1Hb_}IP5cTP#{OsW*kQMugY)#8JO%*X@*eC%B?F8iQ_Z;srV)(W|0f|4=Ha$mt1 z`P6&-S(^Hh4f(~liF^6mby@X+tH(H1Eo{>kgZdIDE zehT)0EUgF5c(~Hh{;h%G1PNFqsvva=jU?#1s3YDD?hKk`dM6;NhnoF)uPV6Q=Ty!3 zBG@=n6FB#A+LyejO#{$$`VKt#Z;S`Q*k=Ji>$rFwUzk}mXdAtAx-4q-*k)V}D(3GG z<8trPu~<%(z*wTh(|)F05TOkuBshOyR2y((eK%7g3h6oN^MJzFroa0MmQSu{0F)z8 zpS0yQ_EzBCTFJ}3uC3gZU;!`yUcSk?SD3_tT&~!Ts4DVQy1baLlgfdSQaqCnw)+H4 zfJ3Fu%Cc}jA5dKt-=}GK(p5R8Qs)lWz5q-#40u55yN2*VE@kz-Z@7{LG0uj;?#lPD zHR*SU|dby*3Y)nuhXI-RQ&^%~ZkPUEO1rWPOWiKh!T|FB>Ep5j#L zD;4FMH_+CeM_Zg)wf=M)FB^wme0fEY=ey7R@>;#bJe%AGZ=Myh)JGu@eBxHVJ11mo z*3+>tpI#MQEbcn2Lh-Bti=Uei#eOtZFE%W}@+t{>O_pj_Rh+UZ^eX3o5)d^8sRv2+ zaBnrX1l%U`z`zXyth|b4>uoKv0ig=!oQkDQK!O^OITZ6>98U9;pnX-+oy1%$nn!@W9@q0SYE(jR2gB9f zU&)OB9j?m%*$_J$P5uTXCSz^;&BCfsz+6kJiW6f&6Mwq}(zG+27BY!Sxd* zdD8avmvk~P2V$}N@ivcucy=T4XKGL>&mZW9!SZy~j+1)}k}#Z3eBn(B|Dw~3I&u;x ziGl|f&ne+>p2a5W;GpBad|F_YAs&$(QUMqaX36S6vdeP3L{dptNctN8ZW6!2qb{Ib z5X*Dk1w;!-?nb(3`1=Mtc1qHc zw;uC1eEJV9?5{Tx-ypFyO%e`<3k-9q5`!Q%Xs6DK*+Ux#_ z{TD+lQ*AUo^&k1f(nbjogltvj-DG{1Sz5rCZ<+;iv+?tP;jXlOsEhcF@+(iiB|{X^ zpWt~x3&Uh3({kJUkdX;1kK(u2dbKA9C*;aIQW{yV$tddO#slAlx7;ec69CXQE}rjt z&uk?-V_FArHy7FU3NtY=)BS%C3vK*gomi4eB~1)Exj4mziiY~-*n2Fv26<-O{^h5x z)o|d{L+eU24`!B(C%d!USf!$Y`qjW%L2e4j#7zVSFzXLvZW#=Nl?`L zyazaD`6Ey)6@MRTErFzU908?Nkp-~pfe(BiiWtADOY(?N^(_0383(6t`}ewo z6guO#USrI!goMm!NXSa};o%K8dLX__)Wupuz}xenX-c7DRO2M^5K>`Enfhdk*RM(E z-Lw}`h}2i(=YwY#@iLvplz-EMjezMvz~Zna**9aAc-co{zcIv#Oc{#>*$Fo=Q$3bV zAHqFNp4IS`hVRX=jU8{9DU}r6%*w;`tbBa+Z#2$Tne*Z!z=yAa`tU{gO$Yz`;S>D% z;TJU(cwU{e8bt$_@0v0g_*@5F_WUnERmrvwY~qsL!d%`a#7a`#_-_);B>{9o%=N3SAUNZ=y|G~bUTih zSx)fok80V3gb*@^60@tZAX5~9U=(%MCAgPWcfS%#?k#o2SPhSGZ%`M|jlvKtU=k40 z{O^+h+Slma$?v}jJ+dRP1wO_1;M@cuQ#)MmXwze_4Fsh7El@c$3fre-Rtf9C|9yro zPSeHYE;FD9GZ2{VJVB#rJw$STj_48mJJ)sqw!*PpX53R*#y-?gG4rc_$VqnO+V*M0 z?~G?PL)|y>AhtCL_%I;k4l3eyflkN>pC^{rJH8;tSCTvk??@}!`~eXUcW=7*A-iE0 z%l?din&fJRKVjw=A5Gu`SIf&Z0ont0iz@4BHlSL_f`1LF;&{P5Y>ou5s@n+jx2xR) z#vp8VAoE&Lyd{MUBnb@gCwtlf6GOT4TUhr-{DJ}5lGOkO-~l482~NUK3~>m`qgs~1 zV$3cTx6Br{5T8pc2&e`{A}{GtwsmYUloAtc`5S5=i23gWK_3YmmP2o!m9{q7 zCMqA~^(+OCf7A0R47|s&L*kaqUC_^{8$duy+c+RR>_BmD65&jT5Tp@%pH z^SfH;SMkb!9XQ$)99#FV5c-O}S2AD!#EpM=2k*y7e@vuuEZwU#ZJSFfBB6RGaR14V zR39)!yo35mo*qgXL%PF{h{O0L|@{B^i!@;;g#*O3ji=MCtp#X`!A2}o3~)LA^Ejcrq;=XGD6FfS3ATXWTZU8!fm}6E z^bP}!TQkAvWg)!nvQlv19mvR(j2y)h|=fuwEU*C$rP<#mECd;0D1 zC^dSnFaK{JKJ|`o0D;^(4J>8}E`yry9Q3GOJuKJ+@qxJXm zCyO0MT0IRgC*xI^oJSnDmfY6GNo%zu49r0@P?UNIAG*|T;x^rL$P9@k5Wt;~7hn*n?^>>?d zdyN3UI9{TRRuF9H#a}3r&dF*h)+wcl!6ef>&&?Pq7n0o%x-vjeG6W1I6qJbrz1#nT zw%U5S7Isowa|$j>Xw{6XJZdDjhZ+Im*-aQHgrN4a&QP%M8>dE$W*}2%XH;|_6WVk9 z1c(JAs)-<2S8e*||NOB3^9?==nlUxcujDU+IGNOFSzhCc(T5LF_z;7HgeR8sg5Ys# zRE1z1&K{D}$Fqm!uYVrZ4`Row<#e45MA02jme8`$jGt|ygxJsIiP$qP2mU|K-a4%6 zb?X8ZTnMPZA_VC!K|&OeMnO^#gKngxC8S#rNogbn6@%^$DQN+vr9-;A?p$u&=X~Ej zp8MVVtn-J@evZic{oZ%ZF~=Np%+s%a%sX*jKP$51URl4&k|BC-G)btD8+W1JEfLZ1 zsKJAYZ7XQsZ17#uuHn%^$kukdl+|<4E5vS=1B$#DT|6bcC1(($0FhL7V_}m z>(lH;{?mg`mj+9Pv>++SjI$kI_+O2nxOe-mqUr`=G;kn2|h{7i&Sk!P;HR*t*83w zAHJiVNMsESl+0En;z@RrJ`ccVJd1Q`i?_^+Thd z7jyU2s5TZE)>b5bim9e4eI3D9mlla*;?xm;7 zLoAdbp|Y#AjM01?5Z(wznU7@X*u`_=)?mV{9#o2KkNUDGd(61zb5*jnCm_5U-8W1| zoi?v60LgEyeJxNeQ1DK8r&{5v_J!uC3XxxU^qkfo5=fzu!VpN z%i28{#|x2w&2m(C<$Wh=mW?5d289X)MQ0qDZ=!B;ZB?tu@0*+jH@W?bl3qBG2Fc-_ z^IM|aL~0L%8#FkBh@l;ret2TAQ4u)8sa=rcIF;lPU@#>5M*1qv3lpTpKFkF?!(1s- zBVrE|RgcM?C*65;U-)+0OM&Pu3SHrQ$b`aK6{H*Ex9+bXj3{DB6w<<+VJG=bK6|>L z@9)z5a0-Fu+oj1Duxp@%kN4JR5aSBA&heUdOUM|2XfK)qBt@-f4uM@k_nwD(RQ63g22b%FXjU9F; zS9IBvoW%ZFNz@&b_VnD-zBkz9LC1~2-j(vKw!+@jxb=%R^|E97>tK1%YKi6@m!6tR|o0f#npmAV$L*Vn_QbqjqgmAe?4mHgL7o!I@ZlSpP zgAw!%UhS3(;pF<9oJlC>O9XpG1!u zBx{Qk(WV&9eQ8f=tp!hZxU(_kAdPwsRShz?d40%LoUOgy3Y__0gvwY55WLTLPQs># zfQr4}NROHVH#SMQ1Nuj$?o3ceCS2?tGETIQ4nI>dFt6co*4thK@)s>&gOB||`>rtM zwv_@WcNL6biClnOos&I(-lqw6O4q;f*H!s`TW{vlng4ciW8vZ&g^wj6GT`RwIjzy8>;{f+)rP{D8a2UmPx_Br=MBtAFJ*{=RGzdv`&aelyeRpEaX zm30!Fqxt*z()?7J9yUU2C2|c5Q3S5yieL6mBvE{HxTP05#_^M$hOS(LCJC4riMp!$ zv5GN*roUhbShl;1%fJdbv6bP;A%z}KNjF4``<#)qc=p74GMMj@&CdXJ!6-|g3;FxV z{_ z&~(*Wy@{ss=v;}aM}}w-+Fu{hL3ndD)=vr5N!L5E17&`_QOm!AFrTgp#D^&EW=M8g zaphnqy7rkqRN`dpg6hbn`|na-m%AT1?>V$h!tP7?01enRJha-(f+YgOE`YeDz8*tD z(=dnc>$=g-C$%It^pf8uwSl<&9LU%RpvirA;x2OW1K*`K%?4eXUoYmLF@^>$0tj?@ zg5e0yC`fIKGuuwVKk+dwa{It^VKP|dN&*CBg1M5Qo4cx8%j+_ z_g0*nZ0OXlkJzJPc#WRpXPFDScc}@8fBrNS;HLeFUq?NI0S?`3WPl0JP_`a_aBZ%S zhx|j34e+Vu2%r8I%Z@?fd1?{O01%Jp42_AO^*(_O^SO3&ceyQx`E$V~b?7jW0~YnZ zS2_TW&`vIAkpQ6>&)cpa`2Fc@k_*S9>H(&oFWlZTiw?N`F8NBqyeo>X_ncu&Obp^|P1GPdM=$k4 zsDF3b;&BEd~F>}0=x1y4B$lQnuHwZ*Mm3&6K1H!?guM?zeEa_k}> zxC2ZUT>KK^mykw-8>6_o=K=I(Mlb3ioO8ttvS;k!IE1=TyIzFqrn{k7 zfxmNt8tQ0mVq;c!-qwh}X7)Bnj*QQ8k!3^}hP-}2SRkO9b3Fj0&MLmKQs!Zn{c6%aDRUwxU72&zbgX zZcCk>lM-eNda|4;5KV1aej(37Hj$V8_FqPqk?|%ar}{BuNhTR{66D zwjnT4%ZCt}dpQJ>7eqxB>~H=az76I9;Lhh3<~;_A83`=n#Z<#Jw?7=eP)H|vUxT^sF%-pDT9nM7LJq7Mh4)b4|b2K>QIufooe0q8=ZLQ7cAps&=E&moPo9{64 zp$B*uoaqEk5hxQ@0^RDn>v&w$Ot*h$)&JG35JR7nhF~zK`jI_C2bJYIx@>4N&Ne^nV$rBq7Q<@=Fi`^rF$R9mVK`mN_Ty#?8V%U{1ujyVO&%Q0CC zG?InTttQ@@pPw-)a^UkWidx@bYd^-;v-wTCe1!g-m&o|oPO0Sz3U6bOXr=@ynVVl( zzRAB2owqre{v>)$=$L7~2|Pqetza>Setfhmw~08{y7#P(qnyKp?vo=p$Hd@t8Fssn zBFz;!J=oB6tr}7L*%4aS=v3~B>sPXMoTj6cxVa`O;oKG3Jf7{KysUTy+gpza@ulqZ z0Q+bF2rb-2rDLgn2l0OZhg}$M4c%mZ@b(7!oH%5XE*WPkRE7~F#x_~$TFn^0g|0_{ zy0!;gX}`E|u`+x>4sEY4ZggY+@TL}(kdXJ$zxo?D6nTBMJiWhrY7$ey`6NQkJ*!V}pQL#?JV$w%I(8@f99n1LXUAV5NP_j~B;&B(P%yF~wgp3T4i z%Np$8yevZR_gNDP0~UF*S$xxjA?p6@S?rkxli%^({Pg?pXEwp5gD2t3 z*`rZ}(NCHU{$}%EBYJ4z!&glxv3KQYejF1yoZ!3?YWuqf{*RRXi6Nyz6pzPXMiQM> z3=Z;f$KB1v;NMz+B%W*V6y=#}b~IR5&xMUJt?yippcZ2n{PkV?QDC?d)1z5i;Ll*# z(T`A__q3Dtuc{Y*+)q?^s`+6ryUPqd*8iuGF|o7AJNr^I?W_6q@Quas#||=yb}^)_ z2=@+%@6Q^Q{d$05sVIVLrB){|MuFsTmzGYSj3_M^C+FAawZqQ{)Cmzt@?;=o;P+!E z`dN)2r0-1YmNA3{A-tCr^>#*)Ep_a_V$?sLpEQj;ddtBE7mtxPLl`>5#}`4is|ApA zX|7?f9x0zaM1NfzaOfu2E`^!N^jF#MRf7fe@`z9ML(W8w-B+G$g&3L{qP^6=z_cf| z1!M|cp*rl$nqx}cPrtv>%fHkMH1A~slq1CS|9|~%{p{BbP&mXh>eQ&!n;K3r=lIW~ zd}hT{7k(wT&nA%E-tLTX4#=hds^XsiqlybMhAOV>Brj)`Ah^eOX#j z##_LNM2r}b#SS7i-3c}k(vNylw;0BP|F8Finebotq@q292b^3^VFNz;*K3{`7IyMS zpfg(cX+2>*%7)>dkUcHO@u#vVwK>1v?HO`RJgWOGUZXXjGiS_iW;GiEF*{K&pl*eM zyo4tsPO@q+^%;|AD089i`o9jzpD=xr(y@$mlo#(3gBK09`B2eq-7C85Q_T|)@rWR1 zr8sVONj1P)Zbog_HOaLuDe3@JJ4u=_*1;2=O%k>D7{Ks=hCq@)kUKnwHQAadg+mYw zwWGXVE7lsx^}%v`Vs*R@JLb9fm~R)izW1+Z=WTR_4Er^MSIWV?{v$r$b*^)Ntm&{K zJlBtf+JfRpuwS1782NgNK{yx=oU|;uYjqTQ^{F`vI*-xt^=7fOD_*BCYEQJPZ;M-V zWhQ!$>6RGDe)vDWb=H%_oP>~{quIdP(r1;3veO>vw^Tp#I8Hr0QHHf z6{tJHk6B+(oLT-}u42l@+sQEv68=&NXrR=?Mph1}8`x3%!@2c7A-t{`4%>ObK?~b>tUlZCbx6@(kQ++BYEA{rOod*phLbSgfTR(W3IIsLk(Dc{tg7|-FTbs<1>fP*|Lz(d0z{^R%b+r zRw)AVU2tG0?|O9;)23U7nQ_?iISD5RmD3cy&D3Xn6(SZaho=Evt_&$V5h>{cu2&Of zUWj!Q{@=pqj}?zkZShVo#PSIFX*$JSj<6ngD~|PuL3B5#^)wDRG!KxVJBT>alRki{ ziS9G`Z|J#t%xPDloqDT}qHGOD+L0N;Ly->3z)7r)`QV|{dxmlY5sW={_y`xZYUkB4 z@i&)K5=%@yn(rFB_lt|?Jb6Bw_#~;@5-uAF&kHaC=iYZcZDl!v-7i$vV|l6`oskpm zSGVU*P~$IbSi>7O_%r@7q#Z_#xqWWE$PjjffUf!lizbw6%gl#KF^L`gQ%Hk9?qFhx zKqrd@DrkB@%S@}^M1+G}L$ddlU@pY|_^N<~=rIFzz_Mf{7mor}d{!FA0UH*?cR4CGa5_M-OlUrS{6 zS+RJNT~y<-^x*3IPtGKVpwWb2sBCcdVj6RR^RtPY*Jv!aLHL<~zO9c&PB3GcCKd6P zUGE|RXv{m*z-Val<7O(u;aYT$Z^?*P5(HEgVOgzc6(Sn~YML%_r#suHe& z8wQ%!41_>)nKS^S6JK84e0-IPnG`KQtG$w3e06QIN%G|Q=<=4uTO}AK>&n&<^~yei zrC2H%P_03uj2V5&9L9H2A$-$;isArvE)5C0r zDyNf>Aywb|ds3+N2?crS`nQ@dVJX-hJ-XEErNisbh_&51a$kNH7Hoxx*s@?LWSnWA z%`e!wQlzU&@R{Jh9QGW1%FW4Ga_rY+UZ6&lF|D(N8Og?7)zCVci1TnT`udgXnQnsPQ` z1djae1b%MP^l?){sCk~_JMPb=Z;g)dRfr^9OhV*Ii<$bc_C7VS^hUVv&oRFlfzp1G zbjHXBQ3iobE(Z9*4uoGk4DyDkW_}mEzcAXr70vG@plE)7U!&lfIeOje zCsL?`j#l|zKM($|aS~(UavWVAF8+Q;)&}mRitxDNzMfnu&DeL&Nx`VSV)o338KN9) z^mtt$9F*SzSHt~y&-gljs3KBYS=^d#L4~LC?o#gx%B(Riq@j3y1q@4^itZp2E~@W& zj1o4Hit5sNu0o6BPjx0eq2X9^e@;xUG|d6l*DNiKpJ#5Lp$+y%zj%X=S_+nnc7$4- zrzRWm!iOFnmOi%kcwsTnVbS~TA4q<{9-lz?4OP3fN*}+msAa_}YWNh0M)2i8#_=9$ z8z5j9cHLhI#FM##{YTXD`65`rw8nlg5+|g&BjxTN35VSVROY8fRk=;!zS=Qc|M)^{ z)54nmqq=gIY1LJqhyYfwzrlIyQf;tzEH_p(WO;91SYA9w4HGUXF$7kn#TwO*AP|}W zuE~gN`QINH%<2|lw7tA0=ahwdQdU2olp3iS7Y8;>`Tm)x&}2D%QtwweqF;HiTrQim zu3|u2RSxK&0W|~#P|(0PVnuM;4w5vtaR-GBO1lS^yQDV+>p4MV%nu6*B>@06xb1vr zh91p$r0>TC5XxLA9)29i50tnhussq$X-STMdMXL}iw01%vP841rM~tNGHgWo+5s<% z%xxLBKHr&dSq$j1fnYS4t5;t1ygMc?1rl!2haa%J5j7M%{(uiGap*uo)7ZCsNhOON zg|n8cPu!v8cka2`N>wzUp`Y0I;X!NoEf{H!y6OzlKkUirPbkMlXd={ujE92;_joEo zu^zO;hVk_vv5l+%U3{kR0Yo8$P-hY#Xg}lyi}O0CGn6x5dSVXD^`r;F_>5G*s9)r=G0#7n;Rbxbl&#HAuMTt^rEoTEt|VQp$TM<0VrAlt#d1jUpDAxh2ME znq4r{zB_-;rrdtv?dzBy*hwULm!Ta=jKbv>k3r(;&`j=Ik1R{8^g-LdAoRfJ;98$1 zJy&zY4+-unf$KIC5|C6wf8^s8O}v4j=QlyKqYy8w3fML=iiZyOHlo&x&H5Aq_5rnD zTuKLZ_fKlgX`(cQQxD*NgZ|X#7y7UjNS30QdH1rIN5gApXsieE`WQPw$0K-@rt)aA zl%el}yIF;~BU8-?AYLq?g|o!$CXtw_s}Rr0s@d|5J3H=MzU%r<@#TXUi0)9<&!Koc-N70VI`Z$c9g;?u6j06FP6wCC%r7t|i z#Z3JJie}{l{kJ552#PE@TyG7w*Hx7ZC=^yLegFu5lB`$ob}W~8jm?eJ_~eC7JMs71 zhf0HJ%X*2472}$r8=F0ft>Qw|C(wgv+*cOGPzI8j zeai_sZ-&kZDjM#GpOI@Y%pPBBu)J01l-qlDVT;eGEjHG)l@Eq5bu(Ja7xP-r$9LVz zM~?eXkYA={=vCJw`ff zROhT;>JB(IU7{RTt4AF?RxLO9idNi@FfXy`mq34o4|(YiEX^6F7E!cZ|Kj7}2GRD% zRj?N93W49d3lmyAOimhL@u>mb^W}VjSKhv`>hsmtb4*Ni zgCouhml>^|rR9qE3+UFILKPLPJ4^hpDmm2)K1VdiN;|`fP|dzNR10L)Fh_#vA#L|! zPkJb=Y+=4m^%q9C9!T4IewoH!hA; z4n-v9qTl>H{6>xhHS?WoH7e4S0{8ERvH9*Zbf%q$7JOi0Q4sa;YKk;<6pK<6iT_=G&Ar zN1kfk8->j$HXAoi$p`V8^~wjZrKeFRI}DoM(y)$ltnsoNx)I;3dkgZcJMv4ip!@6Q ztA8eM?t$Fm^1Vkdr{yDS^4DD$Tu=46rW3C&urWbu4>LmKgkVf?@1b}|CWd`$eIbI+ z=xA>!->Ru>RPw9xJ>8N}4Slnv(`1_=TsH1UuAdd$jf10q6vx35Z0vCn2GI^c;#=S- z=buBk!13K&Jp1ITg{LDaF57UgFh#^6=&z0JhTOh*>+&1dI*&NoUmo@UOuR6dP?V9S zbNfEB!gf}nZVpl3msgn^0+jX-=fw9Nrm!F33_8DyO}PVE2S4bfW_&rEg~3`*VcI{I zBE&)8rct>51Ue{bh7u=FrTMfyYB%ty6`mD?G&?lxWXED&=-f@5Ta0K{KczLA?=O$( zALSnZZqy%|plIl{bJNrpPWdBG{Pan$qiM^|cod<28EVuoz@O7{_0Yr#HsGb`FeL}U}{EX{aQ~zaTCdu zzLRL*)sD3i&u@;J`a5WL{+|W7MkBN(%bcdAtd?^-LzYWu#r38(w zPGx(8Od>ms;^uQj)N%y%T;nHuUI=F@P=Ra5eEzu)69HDRC&%vEO^N!eEVq7>BD&<#OFvuV zTuR4tSVpQDZ_B`(gi+Bk6LtEd%y#|BPNZvX-$l?|9Fem>z{gA?Ct+9Bb-j)gaTE5I z7p)oQK{tzad_3UWT(ZM}zGLRs4X=0RAhGmQy>MdAsZsQE7XJqB(EEGLUZU5R-zlX{ zy-sWTdG@?ASTx2IT-sJP{$A^39-c=4ugV^$7pWDV>T<}(Q^2x#TK>1h@ z5U-8B=&1;;q#~Kq^}gA0x=F9{wJX&2Q5E2f{?K*2wICf9zfJ(?B!oTHB(Yy_l4EeX zZgrkFSf+gzJiE44<8>N6)qp3Y6nc_x$4g1=b8IGWrBTu7O2mJwB&w5JM)gKiyq37< z>nsUybPnPL>_5ElAJBo+!c24O+7kB;AXt3BVR^SlE1qTJd?L&wZ5oE(t>Ko)Dn$@y z{y3XGvLm%UPH!xeOxv*Cb}^BO67b(6MvB21=%+q>i9e5Wajv|P@hCbCl&9#OB+p{k z+FYQQ8jMHqqf^+I`l`tt`Jviscm!Pq?Lssne$2CwK6-W^(^OPW)|~|d?!wF+$0Tps zt9(6;R1yBWWvQ&Gm+!v|qpg<|0I#__1o2B-YZCoIiM$ zJOL0p0l|j^I==X;Rhl3_Hlc!VUF^whJfQ426jFE_N(=1Jl3f9Mru{pj$!^|8?2jE5xI6e`hw5h@@CLr* zLTiw-hSwbY#KNn(M*j>X0@ItP7D~-U&=pr|utlRuxdRcAYdV8=1*gt-7g=aLz0ez> zTS?r@-5$pyRa1Mq_gFU(ueVoMIHKwpF>YWXo+aw@#K2bT)$;vQ3)t;0GgJ$~Q#e#U zTk9n@`ZVd|cIOq#$|3?mMIng6m*t;(Oh~GCTNyTrvKuy$abz&o39x3^yY7zrM{VUZ zv1Oq73VfjMfKe-Cs{=> zEAsXl&ASm(M004Nh7$K!2s5-KMa7*}`JQckTpiBfsS{{a#g%}n8H6j;Zhl%QZ_Rz6 zNt`y51{_ZIW~s|Rj9&}z)Rt1CFyj*Vf32!KOxel%X?^cJu0pbH&wpzz@yotBo?Hot zPHMwHMQPNiBjNpPug$V2D^we;cR^5*b4ZWTMNbrAfW`vv?u-KiwuRz_TOKRow?jFfg zx@F2I!?dfRHeuxToq6rCNbZKr)f@9)i&pVU5~UWYgq`cJs+>5}Fcnd`ZFa?Oo#GtX zk7?&3{iyi3h4iMx*%!H*yz(E!Pf?oH`Mw;`X)6J?_t^zWF&0z5Ydff+X9J3Y2HKl` z7j0-%dpB$e5OuZ%aU$EGS;{h?5+D77Q48sZ$GkOyIh6a=e57do$c0Py@3eSr6Pw+@ zjPQ6|Y7->$UUe%}##GHQm>*eefZk*3b4sNHb0iQnV&;=%OoRq*_+K*=uZu9XCh%g# zOy}?~e|hCIX>~?~;R_6t(c@OwEa(W-H{mAm%Ci`B`6N)g&+=N0ED|-0eN9)SX2hMi z`87!^-uxuMK#`E(JUBXsWdf@tQ$$wR_UBaAfJ$Wzmx5-D&UvMRLv-??$a^3S2DWXc z7oC$EUEyyM(0guStV@+C3dtRVjgMoIHNDp&O-j%Sf!V+u^*IHBsZsZ5%-{J9yzUTD zcg0K!WHO(#J&LR9z@BJy)Clv|oyrVE#l(X zRJDa)Bv(}VNX;xRR}8freI+{WgDp{`FoXipHhyT#Vz~*Q7}8**$^+~Iai~-~vG4{Q z$P+?;m?@2)YSrX(2U`2AV`S0L@m976YelU{uX?Scx9)X3w{|WOs+x8|v{KOo{*Dmt zvm0%9{)?uGOJ*?**1p?T-)1L{MMA?KXmXdY8&J?1%7-)|Fuc*#Kpw*E{Uu&nb|%?8vmOjorLcgEZ5ra*vyA>WT*p(~^Hz~# zQtpW*uiFH*6By!ka?e8;G0i<^^QCb*^hQ6UXFwi!_pq+5VMwLpj0Csm8F)038rQo; z8?0ZTTAX&A$?eIf*t=+bUc}*V@{Val|B%dq@M!1UKL@BZ3;98yP6W8QWj6Yk#SVhCq+iW&l^@TV7=N=uAE-Ks-=jvsjpJXfFD$vV3K`=Wef3r|8 zvDO>@;9sL2iiy{~PYk2<3&(aZW`Hu^%CP7JtIEv&V7suSp6Ji}4>-X?_M?4Br_e@F z#Pt??{%qi#vk63d_odRe0xajrlWgq;4Kfw~LS?jzPw79X#wVs*=6J@8sFL@-iVyLX zcc7OFu?xB(o7C{lfl_H9zi3#;;_oK*NP^{(SJm>71 z(~0!qGbtvYScu4o)yyA4wO|{Vu$l~@wF9 zRNA8G(d8M6+izh){dmA8$YIJzquRZawxV|ue#lz6*D<@l$H7wZ_lJhQ;saaQrdXNz z1`(~+6Z~6N~|4~#zkV|*iyH}!&yr$JSEIpdT1Nk9U} zY&+Hpj%}d_A?q~ueGi;8izM}mMRHLZRlTi1RgcWT(8OM5I?E4O-c7)vkbHY=sY0Bg zbOhuEyWZA06-}F`cSTnlQNzQF5=$Et~ z<-ELRcFZZ3kcNu%yn=4r9jv6!CZTc~t_x>ZJk_$>`T zyF1u<-QOKIt8upqkbn1?SM2av_M=rIt~=KGRkKV(KTJd8Q>og<8{CjZ@G ze5m`Xfm`3 zc(h|};C!gR0n>fU6t&|a9G5C!?HW6+Rn?vm91E@1R-;+HuW;a^Y53*cS0BAE&Iat) zaqd%z9%0;_TsfjovaStZI$Sce&+Ji9`OF=Hs3p=J9Ab(&|apdfFegv)1_MeCUKf_cB@fB;Mn03T+3Az_iyerX&k@QKelJ72~i;gD^LU6`DG3Ee! zxCZP%;Ekte=c+Sj_MS^K+~uE6_GT9oKynSe&c!QEf309yW*Z6A0QNJSqrp#_9%tes zl#u4d(eqI%+Db_O(qmhgw2&RGaqR4fd#0b#6v2h4rMgXk>M`71hAy@M(+kMAFie>7 z;A>MqGTHe%hz#Dmo@Ds?t&bU6+TZRem+?)iE)d=mN1pe}kH=ZKu;ok!OVQ)sp)b4# zudj9RE52}7=XA5Z?F2t%qY(Se=O|goA825|Yb~NgRUv+q1o`nLIS1i!TAQ7sCz`n= z+a55h;~;LJ?SiTh?O+k4DfTF8>QNr-z}WTlwLEuJT^VJK78&Ty$ssA2M4!o+eSP;T zlA2EOnOZg2_No5R9F==`gHd?`wI&YLsmBmn237U_T&*mr@=0iCo)yf^NJ>tmafAt0 z=bTvZH%l@{#Nn zB0qqdOk?&@RKuY48L-nw6ZABot3 z()YnyuBFOMph0nn@t5l95@ed71rb8<1@>~8CLeQ1ge(8ejqZT|5}Ov&4sYTQf7$h5 zHI_sGEzaJc-H(Sq16$67j%w+1H5~+VA3|3-OBMOF_b{cRWl@a{BEZId8%UEKxYwY zXUEOR6m35Obdqul<;v7ae>q{v!dqvXF@Jg1jmYbF!emXu&*HpIz2bXi<>cgvbEiw^pmFj>!iJD>zf1DUv1?Li z-1dlB=8CpUa$#S-yYY9sp4*fMEN8JoTxWas*JG-MdX}ZOovP}V+O6C-#7viRo2X=* z_HnR6%3Og0eQ47j)KQZzdNik|*{47APh|t;=C6>D2bl+lna)=vHP|$?#M%@Ps`& zToTEprX2UH`@X2Zb%@Vb(BwO%#AZtx#G4Wm!aP0AItC%L_7m9%rZ#9 zYzz4cr;R&n%{VhCikoIvN_1bz-^x8T(I(_1Xe}?(fFhLJ(!9TwAKlwPzK<2=9wnWM zV4;qA#BJVYpym_J-$W_TUpye59H-iPC&f6ObYE=M{a`6(DorKFBzuw|!nlCC={Dc@ z0_&~A-Fj({FvGC5fCpGuB4eJX_c`3lt%OdFcdAGGiq?E&mWH+k8qvKE=qTr9mzs=@ zH?97>VoLzuyWFu+k;poB0j(U8@E`N*XSZY0_>zPHk^qtx}WqpQwW8b!~EJ4f*d6FKnsyq zxeq%yXsI-bJV*Bq6i`*vQ3UmsE&rE6+RsJcSg0BQ_Y+be3ll@Z|vc@ulk7R3(ao% z$9Wvc4yg+{%BSFdtvGjo?Vra8>-+cFxidjP`YBxKFqpiLj z#w)0E)D{Wn2s$*1^ZFNc9yc>)vhz_lT|efbmL}tA$8{k!6k7%M?WH8?I-%y~hjPi} z=_als@;0NxN7X!t71+8iAVhdX=<-0GPJr&Q|X+t=YRBd^1QAKQ(|7g&{{p4WO7!(~=Mg97Lj8sd! zOPvM|Gm7r(5d-j&zEs7B%;wMCnd@(6AALsZYcTWma`A9pj=XV#&8_jI4YXPqmvS6; zt{iDwp9yC_wpqJO|;s{O}4zfjpUOAN`OadcDTa(U7-r* z&qK8ADzx0TzDbrps^V+*98-P^LfaRMVK;H-SmY=UQW>e+$Z>r*ph^*!a^}`}bg&*C zQ}Nm$k#16aG*GPTFt1ydEtny*xN^xt<}UtWe5aKXmsOt9a>MBHc5&5CZp)>Q3=56y zz3^7QjT3tjlsLP(`yBJ#&iN!u@a#g$A z5&h966CQ}ym#%sqJQ4XZ1y>+(pVi^78 zE*IWsD?dl|GX@}0M)I7Wn{twZ=xBCfTKm%ZGa+#{2EFsp5f>^4m3Ut4d%i~ZnV58u zt@q6~vG?Ijm79r%I`r%LyDA?zyL}PIWIS*ho}^MK`Cih{|<2eS}-)qfQb_^H3N8+VX zuw~@j2=8@)=ETvy?9t4XIOeI<{dVny&MkP=<`v9F~$(sx7se=^P9`Ox%6Y zsB{^0VA|om_)-+y;jf=(QH~zY@L|d>D0=MQ3-7aDB)(q(Z5yTqk$I)i7P@zC1g#|k z!y-GSos5RK$-DNoU{F<=tslcp!+&BH+C*V1uVZMcV+zq%QS*7$v<>b|XRDRlg2qz$ z`>z|WYL~u|)8!+urn03Z{==a_{?HLSQ9n`cW%va#zKYYBo;-MDEfsL(Ag20|Q4ln0 z`Fs`QIBM?fY6ll1+j)oB1F0TVKPuD?F2^K1STIVjZfH}bhd?=@v)MR9vBHKoek7)u1APQ>9Y`h#qbqXp@_N~njKO{b07mYBOP zsAzHzNGT!J7LBveYWuWZEW#B^>P0qM`H$93J2wT;uNiEQF$>ShP#QXI=O=5GIK`oR zcV3@O2ysRE+EVUupz^xH_gtmrVAm#XiWP`XJZcM+D~?j($;LvHq|LK+uK1LN8&;0- zp;jITL;j@)7zdXG6wf4H-y*5rl??Cu{G=GLgU)@S`FCl=Q^u-_6DpX%ejO*3ldJf{ z;wkfpU7>MoMV3Y1mFNM~br`5R&x6P=op~vfRHo%$9>qG+d2-gYO9Xtyk{A--X@H@F za`yM={rqiP@Ny%&=0@~XYzbq%FKv)S6%G3z01@lFlGw>0l6&d-ueg5)&Fl4%%6u)w zg%(ZuQv`%L^$%(GxLG6#^MlL|)dF+O(Q1v8oQ(W?m__%Rl^sZgLTnFbtB)6|nVjZ{ zrORk+^Bu1&dXAyuk_PmgBV18g`t&rrs7?KABPK~GvWGsoh-^#a_CY?}kwSeWznjg9455Y>dtddmv%v8@YoBgfCz2WCT zc8NtNe=i!cNiq|&rbrVvo^3aLQrk*5WaTeM@17scN%*_+M1 ziCOMn_9ax1?hPQ#mMWA;S95VcBdoIDu432U(AK(Sdcodxdr(Ko_%6KCc&n=G8V_Gc zhHolE*k(5>rs^fAJ?z3RZ6q^$$Zcy;>=v3rBsZdR>CJbU92j z@RAlm9P{6o;O{?hxuYGKP4dOi{VEG|!_j39tm^By-&*dVX4RpMS5eQ;q~-+F0b!sG z+*C$&xT%K>xPcsHCd3AP>vCNe87hIQxdv&Gc0he12z4 zWrE9csmwr(no(Sq%v3A2ef}t;Xh+s)9v0TJisO}q>CgoR@=M)Je}9!b3}M5oL1_a* z5RtJ)G~otD2ze~qCX>q)0sk?|kO-nz#}vDDz6cxJFPEQXu#B+_SnX?xz!_n73N8Q~ z-89!{H4@nC0vvZf47c*J_SiI0_T|o}pw)UDPEyA=jWuw(+Z1&OEL`3302buQ;uBu0 z!&QG#`E~N9F^KruOrtpqkqOObq(`e$)=gE7g5!;mp>3vl6Oo5W06@XvKjSJ zeG5-6J@{D`%20wzPDY!4^gI0BCQhejIe}h}R*jJ>cV2#14#Dk)^(DLmCvZ~xyT&Pp zW(5;)g;r}U%P+fn05*~CcIt^A`I)-$D>^7Jj|kECPuof%70l zaJfGd>*-4J;}%w#xKD3}3SD8i?RIbQ%8L&iOS7AYvyv8AEBG{b6uhR??{~1bT=@4o z@vngI)qVDd4%^bJ7u>%}$Qo%x__of2Ca1{jqwv$Tni!C%@+6!+)b>z~LG!KW*hRru z>huj%A-rZ zxKa)3c+3ip$`pl8UU~01CdX0wnx6CM%*&z{qDjJy$;|R7V~R;ajXeV7As#kbZ6=vg zN7JFb6T@YsAmiVsf(z4Y>a7h$`+O-N{^NC?JIi^k9Q4iG{vw;N>Y0p~jsUm~KT*fG zj;W^oK`h|_N99QdIp5|H#~w|Abg{(0C*pMo?f*#I z_=q!Y-*x^QK8^5mL+JD>v>ZpK3mK+7Oj-*vW*BO+nZJOfNQ~W6vo(m%c3Uz#{YIl; zU2tSAB&5Pl@YduH>%hF3g;i9(O3fgtdUCkd^u%1p&vUE}SCG9~<*<8{rdnBzh-hR< z{n!i7l?MLx8B`s3uCnFWsEVWQRifTKbVMU31ck=r3ZnlI^zW-fE`NiU+(!6|FgQaj zJ?LRb-N`+7*uY;Sj?S*JXK{O^i!3xe`L%AsWG9`XAvRV>&5y&2)v?&y;3I3=WiJHQ z$j0)xxxgPX&o(JZQGR=oY-v@G;L4n&3{`ZUAQV)lbP!u@g0sNT{!LjUlfGTsY7x>@ z^Y)7sOSFRAWbvl#MqV4-!t(kJ=uv#2*WiB3KY!z(4AxJCF?Qsm!Z<>hi@9Qt>-a*9wlq(BZ}5o+vgb*6;)bPOp>*FJ9{`ei zv_kEqS<(G&fvhqS1qqtf5j(zP*=DyKbJ5R8!R}tV#2xA+pXZK<-OjI<|0IbP2v@af ze5Y0C_)4JX4`Y#yxB-~Ah?5+fOlj42S&DL`ux;a}EN7X&6QHKxav47*wps~=fLtuD zOd3Po-ser~uW>K}bkVtDsQyDvHN4|FVn?Mb!Sxf-lMT_Q@m1qER?@w}ViUX5mEzH> z&U11)FB8EUZ2*UF_=|lHTz63!vz5x7Vq`+R|twkukWk|m;8v0G5 z&pJDPC1&Mxf8W->|8U0z@=~E_{n_6M9u;avznszjY9a;Q4a*{s8}K$cG^n;i_t9mn zJF{&5Lx63UeEKAr2XR~{fabP5p36`NO5OFlc<EE&3PeI}JVRZECk3|mfNe-G zlpUYsZ}cc4=)nA(1;9_MskpGnRCpO|^<@T9ai@O~nG}xkZ6e z;JZniz{^F_A%;O|OGQ&nICuhjO2tPCLkCNHWV9%!vI4{+@cYw_H_thE|;mEJALC|@oE3P8>tVu4Pe^6in zlx5WMk;Gm;mC;zsZB~7W%!UCWQBWLYsVIeaqOhSkG~E@p*B~G9s4;8T z2eoIe7g0_2p}Sn>wp{{;o&W4dfogP(vMp~kQr|M^gX0JCN({XCS-{CY5Tzqj8r#wa_$!A`R;aW|6f3T%Y_7fsfYJ{|{?# z9TsKR^$iOS3KpO!7=%hl2}nwg0jMBg(5aNtDBXjXqLNBCf(R%f-KEkX0s_)VcQfR` zw@xYV=i+<5`*`2)4>)FqVV`@iz1G?*e|w2Hs$m>CP*d!EQXegKOgbDQ6&T&B1@Mn2 zw@4nBl%O!oXwji;E5&jWpt`_pY-tF?rg<1fQRUBuPFA0z$?NJbJ#AdAw)lnIVvN}V z-QB96G@cW@YD(S5S1PseOVg9KhVWM{8^hesP9`OpCK&iKS2nFRk1D}2mCGH}x z`OKkyEJMncYCt61%vN+6MK}jaReZUtI%p@vy5lPiQOob&dUub(Yt=Emjqmki2a(do z^h|HfGqNadY_1*bjdX_k!&h`E6x0Fg;Qq4IcR&opTX3FpcH}d@^Z5wQ(!C|una2~S zR~2h*n%wX*dnwji_<2N+ahw4&BEd6PxRjP~sk=3j=*$aBk~6(~Wzw1;Ij%?^T_+XB5)fuehcBqdObqM!R9DE2EkNmpd0Mb+^pD>cdLuQFjC zTd+<$+RIkD*4Gl-L`@dKm9Bf!lnVirFh%#1mdc<9#g=T%E5&|HLNK?$Ln>R^e&n8N z!)uSyfZrLuVuE6W<8d)zt>(dtG~c7`bnmXd?UR*PZ8XnyTpM(hs(+QXHr}bfkG z_AUEpvx@@TckgIFC8ib!FphrdqO!#)jo8#jt;c2|rfz&9^pWV5Rnn<5oa18R5~B*4 z8SZ6-U-IDubxkSg&d;m601S}4dZ-lw9Cp~?u2r2Y!ZXqjU(Czx(O-4Cx+Z^u95ixb zs!;8GZbX+;cllGZ>WtvBS;B#fIf>tv>o8r*zLk7sz57qKW=@*3dQywLoXxSv#R^Po zlI8nNm9M8hNJwuQ8MXPTUzm!E7h0bU_b<3|{uzpph2%!!m4lu0|NJ}rw+G{ZnoF9G z(xTi{Uub(oRU4Ek{VY{ z&6U!EMyWMC&wC46Ir*ExK{Co=bS2^kbnJZEaXDe0c9XATP!z2%oiaLW>b7n`R{+|} zqK~)qgvDt~bGYup+^x?2rtxb(Fe1yc%C!Aec`A%03G4LZwG=W+k4=D=spycW?N&3M z0pZ~h8oc5+Mh;J2Q?Lm%xHUl${^PRCr{@zdkQB;hAVGvV6l(pNJ%kuJ{L;-;UzNpn zaol;O&5p77x>P&bFmvbVma4`m5z-!BFAmC0RklsMqLFZ4eW_BO-r94YCF(&wHa*F3 zU!DWlu#fi*g+Bd$S#i}_xjkU;^bo*)+E_sJCc~m-nj%y(K_e4u*xOumE{n|pcTwkx z(C~ZjAkI9oZaw|{06ISEtY6G8S)3=%k))*CkD9g_X4dq`=bsC>T+cuK?N};w{aF@E zhLM_`EcOP7P>YmtFb=xzgkgEb#x0@BhJ5X{s@cRDFm`G*&7dnu2O{B_DSToaQ4^ok zaU&i_0!>~@`5RTy2OGTg5x`G|{-a42XZiCH0y>@UMa5V;XP&6p585G)ZYQ5<^0X)n zI_*7Der|}z`4L~hIxP+d>j-S7fA+KR0OvC4Vxb0bSlpyumluPQOZyviFx}I-9 zloPDEx*9G4Llm#L?gLvYu-#6HWk*Vho+2f)g}OVfx(dG}iR85-0%Po&F}fjbOX%`n zJm2##+%v<9%4mfILr9Q3Xi)DHXM&I;XU(k@m^u@O_X|vDDB7 z?==XGeFvCpj~UUTrz+1L($5bCtif>?WUu~@lRq;>BBhLLM?PfwP;|(|s`rz18Trm2er{<2pfKn(<8`fI^^dx)M6$mM`uCjp)bWJf9WKg`FneCeli(&duQ)>t{Z66lvXF?%~Vn@sY8S* zNRtW4M-A|`5`s71n+2w{E-8gt+93fNzIwi)h-dsWr!+5V9#U{qcSU2FlkzSJV1H?* z@;M~*k{lEMMv+P((PWb}PqE^btj*yt0iKTjT_50|Bd17K!C&BjkVzx|44FCom~wAt z4@W6S+2z3S(95OR5{f#tDkPFi1#Wn+_`Y+KsW?~k#Of0;ap;XW96q-uRnU8VqSng_BH=8PfmBoF@|+>^%(7DtU}-mcekTkSyM?Dbo~^y z_+EQN&;?7`+(eyplr?Q521(~AFwZ$zNzG2+6+L@Dn-(L)>ROZmR`}%>qYuHckta25 zqfg^$C7e_^PmyBZ5m?D{q>zw@HHb7_C_Fz*yzCp|jE1=kJ)>ULxH}Pv6Wycd@G7F) z)2{FQb4;}8%Ftl`P*IiTVqZheev~-Fwbi>S!rdkx=FWLxT|`zNI4nF*ii-M}Kdbk_ zeo(}-s7bBxNORbuK1O`s*_EM%c}Y&H%zA$CJ_PVDz?Id`&onFcFNw?86jp)e@GoKc zx%7P`u>Rt*paXkEm%4eiC7-+Ai*Az(BP2KMevPzL2WR*w z6V64`$`E5#(_^Tj?;hBNk$VwFrqYeu^4u!Vd8Mt>bBIMTJuc-7a-OEOFC@pjL(Vw2 z63Vj0R0!KWEVUDN(qFktMj}Y=`HP4C*{cepoSKZbFz9ASZ2NjQr%q_deJYlkCoY*t z>Md!eEJjMwZiw$|*V(FGb{$PRby@-yKe$(~t=au1O{@O~o1J-FqIE5wKKXI2`q~my z*oE7#v~?NPKKVUs>LJYnVckL7AI-nL)jx34EJEZ~`9xX1{{uIdw7C-(rkEviMTNHv zJrp4q!CNuM$$@bb;ZQK@@`Vqfiee{y;g05L)-tcYXAXA-2tl7g4O%Td^QY>sU zE~4{w6+FxOc0qi`w&qYqQ2oOXEh-(H4{J7kC(JTrCH<#8Os=r-61QGqxp?P0q416{ zaqAxPy}C;0&`$xGK)N!lOBV!Jzi`^sn8Ve?jBg-wbkH0{fy6!(&5mMI`}R7Y|IF(* zH1tZHakMe;XQgzt-l^29#3|p_qSlak*!y!jv`qF=uUlcKz7i9^z5kTHqZx8F_Km%A zfnhT~Fq5Z=*i8ORlAr zT2riJv9S!W=*=Ry%36M7i}n(0nXb0Zc8pu2!CcbqHHvb)tq5lb65+i5m0d5jEr7@hNq1BqC=H+uFSE*mFrg5*RHMrlFBKn) z3$4XJ^6SQ?xLu;*qbIcn4hZW2R9yRDGiB4Cy&}rPrIP6!r=Pev>RXOr1xw3IepRbg zAtqYB$m(z6=c&iZ`^{Y_Ey|4mfr&Pl9ae1AB!WYWjV%z28h9ujuXuug?{4A{`8pTgg&BipO6(=Sb&AZEpYQ3pBWfx|p1Sv^rAz}#e>HzmLmFYTaRBTVrC$;&H2G0)jJX&+UYi4wv<}r%1V8T49>LLiV zR#&a{_oqj@AlIRMy6m=9_0=56MH_qXcTtWTTbC zb=bCBlVDFS`#K#$% zWS#YJnp|{M)Qh_KjisI!>T4u(%g+&B!uKME@?#c$-kyL`VXBp1WjwPKoRs2DW3UMS z@vL4C#p)l+;9GJaAPTzemMaIAz}|LTIhq<)%92g$M8$be+{EfaYzGe?V|aY#j~#**B2aXBPF#JTMMPZ-%Y;qfB+wL>%5mr>Md{PlUt_8mgWZa zCvzAgIE{Q#Pi}6eXej*9^=r&kS?-qx&(r(AoL1u~Wp!rMT)pkK?mB&!V;@6lUWr07 zSWP7@;=(g;#w-h0I^tb9N5C|BPy~)Z$C+ctHE(NHE4p!aKp-G>m6kR&@GM{H{^z&d z7+pz|Usfe+MYzX(Q;unZld<&9!NrqI-d{~YN#?mX#RoxQYI6Nn<$^@3f#@JDo4M-28lE59mH_yyItiI?d)>F?^fbGQ?+KXe=ZlfQNroz>L{t}*wv zNR0IC6)oI8R4wD3)BZ{{)Ffv(tCa{zE@Yw|_F*3nku<#H{;1=RJ4)e-t}mdLcztxY z&7g+On7{0I>+0ra42gq{=xd8|Z71C@Z+c1C9a6&SeayE{E_%j@Yx@6K?!$K$f2mxj zdXO-22;)5-cjBe`3j???Z8SbrZ?aCUbE%f0MeYp`9{w{T+UEFTo^*J*y@t&fm^gAc z+2>{VZ0cu7*4Q`jr!p` zkJ@PYeoDkg60tKvCn<#>oujGhnj4|QpT_hn(pwvUox!Wn2-n3Bwz;PNmxw&Qrk=f5QkB@&?I=ZY#U zq6vgoT55HW^jqqn(4=*Xl751(efM7KpVHtDft<-$ZXRPdLZOX*m*J^IT?o`y2AwTExmK@S;FhTi5-W6 zQq|XH{9BHNFMiX?rSnrbm%B6&oNIJ1hS=%w)zabvov5E^DyhDf(Sljr;g z?Yei|nWer7M3M?Lj<_Hb3tH)a6ENZ~5Rl0{OUrMI;dLQx&db_+)yI3|lc9?mt9>DD z@)p|>Z}x|Hlu8|KvrpHqqo+cM^fUM36{iclKX9KEg8;6zKn5?sZt%ESs~K(;>K_ts z+;s7-!4D?o6(0-RgE@PkFG>4ad%Ef_tRI^XoZm|QkYKAegBG!X_@XY3J>Qs2Y>Lyg z_f6%Bo!vZoVCcuG-;^#+-K0HoX3hA{%r@OxxhL@9)RnTUR?Cs$pYu^!35#Z z9=nVL+Z0`Ai0{6{_dd$=K zXr#lJGQQ+&>>FALkw?=i>AJ0*<|akt(U$Z-@bwTJ;VW@v1yjCD7*J8uhRw0g2whl5eqKG7!#mITOQ-rI{L5LVv) z_g-rF!CvYR>2hvrHMA%J2t#2nQ@r@bmw(EG?s}auqP4Y3c2SUp5nGW+tv@T#kb}1$ zV(DUI&B<=GE|{}KT-s%mDBi&)k@mE5Zz;fkkWG?%#$s@N^D(#JF-J3g0ckhCLId=W z{iICtd_&D_liuY2()f7z$4Pz^%3+?- zZV554DD8ORS>nRa0vq236%R*VaWr0kxt!+dn&;OAxZ-j^?^r3>s6llECCdu4Bvvr%VmBYi`?^`J+{gW~o- zEkCpQpcC*Q@wUYj%k2kc9|UDum4LbahyBpzK)0HFj5aZf{sIt=A%OViR-S#EKM6@< zBS9Z9QE^*u6}VKZ0awfFYPoC~0#QfV9iCthGb?Wy283?nU>U?t>>Km{!@T$J!&|FU z5AL32KZoeINUpK1^XM-U!nV#OHO`kak#8Iuicg+tiB3+RQu32c*~smYefM%Ag2v>bH1S)q7@*9l#;n{P;b@d zRo?~;_t@Yl6X(`Uls1ft%nhX&8|ri>Hc!_6&Z|8ykWDEC&AHD4hx*+`HTV|GB z7y&j_JvjHB(AGjf(s~)MTX#HS*Z9*{fRv5DH;=ewc-nfq79{{5^S)SZa*95BLr_u6 zq$DJQ1gvP$_*8gO($g!x?*Cp;5h17p_dSglx5S<9M0w_Vp48q5t0^d0-l$u?)$a9% zdwY9^$!?q)#-WH5T{eb`&2)0=9yTCjGB*T6&ff4=G|i^4{k^c#^AV1Qg5U3MsaPLT zny$53rS9OZs@I4keWPf_R@RvvlQDwPi%VgYvh%&!#(-!Me0=BhqeSwg(O`CKbVTHk? z^7{_s%OXdBY-Lv7Zi8cB@S|r?ivRoI3drF3UxR%%59=XuG}^>8sv;M~geYa^x4Hm4 zzjK0ZPD^ZMh3TW;bo-U;K3iBz@t54-j+o7A>Py_Ph)kPdaD+Iwl-y# zqa}g`_^9#;ZQm|O^%nKP%shhWqYnC?!r*~@%S(9wCh{Q0-kDqfUVQ`#2ES!OqP1xi z?X2&wMeM;mLgH|vY?%iC-jzR}ye5Fbn*{Q14sTEl^3PDR&l{8{5pfQ& zN6%UN-QHz(+K^n3^E-c*`rowp>k~6V+Vvk}3^&R*?IJYv0--F^{PV6v+(HJwb<$sc zm%-@}W7qi^&B4Eh+R+qSdrx){29LM2@~+=>0B}f4iV>H!KUx$~%%U?a!MhAlc@A7& z7V)cpB^CZXHpvi4R*cXP)J9DVGe~Vu|29D+>yJ*JM_i}ss$iS+O9z$ZC`DqU1_Pa$sJ%$0XDd3z54CpBkPBW5%w?QGs{C-h~4nL(4w zPZ@WN`<<0lGQxsF%0v_Y#qvAfAtZr0`)BS)0T^vR?%RRwvn;MC+Fvb*ddw{D#4$X4 z-=pQ>Uwtd{s&~<$0iQvK5>fBjFeG6XLi z2KgM`^LAIA&_u|Bh*B>|{5{9boxQ~j3rcelEB#*=v}k6FM&Rx{rQ^Le!)%zK181I; zpIs`J3a?i=hlaSp($lQFf&PlS@Yt~v5JUUDm&SURzwOK^=V0DDAsVYH*39_FR^AV{ z8O;F7sNgY4!<}wZ;1AG|0o~}TBUyHFMK2@(-Rh}MZTb^CWB(J}Fvx_iVC1jxYr7>s!J|iHvmo zGX*S-tg7t)YE?8S;a^lFc@X`cKgPMOzI5u0CgMPkD3`Y?LR>Cbr;gm zUjQr0dGYO**}jXUg43geF>KrG+`9yr_bRC*3?-Ykfen!gQ!otL0U z`LJ%#4alM0rE$C{pF(nJw-CrxI1K4gY`byg&ZC#ff5i#W@P(C0Voq$ZXv7*m(r@D6 zbT7}rXuXC||0s>jIn3&kN@RS+fq%;*rXCa!Gw$r$EB`BpU+oqczfuh0XDJIvqBM&f zxJC5G^eZAe*bbSD7AQXsr0zDud>{q&aJ)Rc)|d6A+b$kffD@t~A|!TmBDN=oDJJ02 zCnoe5ghC{9BxfmU8sHPT;h8QU_-45Z7r)Fr3+|aOea3s<;EEIaCh&&Y%@n%RJA~QZ z3Z}E5CXTw?q~FC<-Qg2L4DrA-XQT*cS?ns~#%={X#4LK$I!^MQa*yJA1>RvAdMz)} z?15I;-~6!g$f5vn=-f}LJlSOi+fyN|zTN%S&g91f7fPOz-*;bcM8!t{4E>$Uz<%zM z(e+T}V_%w3gg$5*MZKE9$k|-3^J!%gjKHvaV%3(r_ z-OuJ-U*0|UXOkgT21P`UC%T50CYQvbrdO5>_avOfM}1`V5-I$odMbOjo)tB)Fnj0y zPHjJ8w-?t)ti+<~tZ1lN(je)k?Fj9&F&7MO-T6a%s8Q!t0TsUKpe4SkTSitdqIjehy(pCWSbr&W<_=mz(*r>m7&uF73A;Qa;d9p2=RLc0>m z{$JM`(U{a^6Tf>_{co;w7wesdpVr8TZYwtYXT$ws!wO6`c{*#Bd8J_4&cg{lInNYYzfI>9fy#U#o?;J>sGgc!7OJOGrXdh+Ye!c0BTas|qrEIDaj8~pz!S6M&d+_^EBm;)T-OlQ?t*osu6*sg@wcM1CX6Dt z-HE03^@x@vklnFxF6Yke7U^3*F~P8$(bMi?b}q`Gj55({r5`$@WjCFm|FGM?9tW#M zMcOu44I>M!;VuO0ay{!Wmqx>y_thOvJ#yX4MCD*lkj7b=TNt%s5#eKJJ|M6R8(sHz z_TOrG`6iD4;Gx;D>Vo#(Pg{SOkKg-L?;vX{^d5teAq+jp6Guq~s4s7$I>e0>h0Yd6 z_2w$kOoapq^3cmLVpiRiqc5>R3+umjik=0|>@WM#Grr^s(5!5i2TLAYe-XW0_+YJd zz+7lQ#&;=eEg$~!9`=d*%hibc`1tuKo1K6~k)(OVeRuM}zJ+R|%Ybc>+ zczGJ`8ujlINnk$&Gx#c#=J}Y6uRxw=3Y>tTP_W5bh#eQdjzL?uJr;fmrGn={jp2)N zT*&RxM!NPb;Jytlq=b8Ig=-xyip-N?dI}!H6}1*td7U+iZ4PKq-9Iz_>`BJMzK^B& z6}Wr$6K8xkYmfsH(8cTOdhKL)xpvHj1_m!PLMioW-+;e0)W((m0Q_FD*gfG#!EkEB4QvTcT@ih;Nj`Z)oV03{A^Yh?HPRXJv6s5yePedGRiRU;C? z55d!DpxiUCD6qE8r7*=;JaV+c?)V9|9|km^8z0o(jB!%Dg-L3BNOpf;y~B5U%rMEO z44(sH{~;-VzM#PcN=2+!FKPaGR+a|MEeq&v)&f+q6|WaLzYgQ!%br+-(y+JVh3jie zlg&+|t|PYA_ftL+_U&~*ITNAoZ3P5>LMkGHY5deuygPc-A#O>bf8~nx=2`mUyv&qi zKr5FW*{H78PoXCjvM3m7#0DBon> zY)Y0`UlJ&UUXhqprH_lpPL%IoCB#35`b(OZu*LrbGrtWN#`G1$$??88uo+gWz7-K6 zZN98@SH(TrA=|dxih&trNcIt{D2~bO+aG~6K$j!lr{ZCqWU%=f z&YFy;H|rn<;#w|`S{ZlARgH7V#$C~HF52OLnl9mh8|OtM8(6&BId7MBMBd$WA@fl) z>z;uFFW#o?7>%(}==!q?W%x|sa{kX5VMw7Z^7Pq6)n+k`P*ArrD|>v9Mv|3rW5+iA zyw|lb@gHQ1&|2eN!X1S>b!j~)MaMAl?SZ?D7`q}*8ulw1TYAfh-^-Z#{zudEspcd% zCj8rPZF#j%?Bo9U@7o3zbg{p`_F1g|F4@24gNNS>(FmR++K=z6cKcw98IVq03&34F z{RSwGDImC*KUdF^NIBm87H0eWqxzZt!k}I06RX24p2!UJVV<{-(%y{MMr7b;JN$ga ztgyWwa00+Jac32xo-poa)te#}4lXHNA6cgQ;DIJ9-QL%ZTz;SN%z(^o52lVNZ&Y=% z(s8gfT^q-wPScUH$7v{NxFi&)% zee;!W;_uE9XCEQIr5)>s7VZ`&37}!$I$F?_<(b4E z8*|>Yog$=NxM`lXaBttnf;Eir$JhO#JmgtZ*twnKuAGRL(mA^}Zx=<5j>rV#qElEn z)Cg14wm*~wD*aln5eso;-eJk0M{9f}m;eoF08P)ejtfTo9sWwu)S0_ZsI)`)P3O;p zv3DHzvh(~Whh(31Jt9Q)VTkbmQ}rn&oX$?bpr3eh4F+En*c_9I z?Z;Z-NxWk2N8^k;(NRnY!YnJ*61y@BxTK@wy$!=B_zLZRR3Pm`mBf*E_TZ!F*-W7G zcCgU4Hf%y7q25!OhI;Bep(IJbj(yeFw!haX{D$!e!CTw+6DEHk1<$qhY7=$ zGtR+C8;i%BIsm)F%@TfYH`6Z~cIVDWt7RjB!%yL%J}CSC{l2W|M))4gDMA&~lH)*+ zNm<-O#`VUdyJ_Al=}Np$l=ou#sN(iz+HYl0tM6>=ivEw*d#J5>;Nf2e)xy3IxRsFo z52l@ikV8{jSxf_~iRMa#H(;cjdR$X50QV8Yf^@TcuTS7=%+&RK9olzQDHN6~*KO`W z>)82h<1IE!TQ?R%PyNh1jJGzEJ^!gqDbem3RZR77Q0~oU)>Wg{h=`wV+@HTDC$d_?kwrQ zUhE-L7FWppviIZfOS`?`U-e!hoOqEGMNcTXWy{JSR@==?`S&8`_{-`aR;d)HH{5PD z^!o76^!>-T%`=Tkgv5-@xjnnkIN%d-efELYg75ehOK+&XdXPM@4zmVYIkb?!Qaxk0 z)6=I=^t=oAu^;P~+JYt8{)iF;S^v)$`_oLt9ipi0c>m?j9?N3$rTrr^7gC+p8shYc znb@}^sK^IV!1v@VO15*t+lK@VyF8fEPmibBhZ4MOT+bpyC_$U`tjq#(xFak{&Cr-UsK%vFQLEZjyGYNKC1tKB3Y;K4oLyo{8%aM&UwCX#I+koR(+%W=+JIq_ zYWo4Y|6Jz=q4Pm?%wwmA%|Lp}?z?B)QNTxuF=?RN%p9{NbLMt65|P&4dkhil+V3qR zEH>g~AK|UpNb9o$+ZHQQ(dyFe2>llJvt)(zg(<# zzO^sg9~!ft1y#YVKhC(B4@3-||L*L%@!gZi-4-z_xXIWf408%q=v9|@lOD;O{ByWC zke<6=SJXr|O7otQ{&3_sAHPDd?STedf)m1|vNADihsU<{$N&=@+=S5Zw%+0E(B+Md^GZ8Bun^r8zZCTsCx1|;=^6?*Ivl-QSTF#zMR8udkSb`4 z2ZsUyCMxLQkRxNU{l|^U z1k5EO&`{Q+($m{y1k-YuB*fDjWcEJ{xICOxAEu2GsIH8 zU%lKw>lH$Mjk@lk3uuZ2eX1QR#pRFLh^ELFkTdx+s0>TQdfGsONXcdq z3?WH?4Z=<%+p=>V4gqJinb`;WB&6*o zy%&^ML>=_lKzgUzZYgh^eM$#`*!C;ZJ9t+gR1ji6IasnATg3ufT`7qdxeaV}XS9y{ zfVfkU0>Pn2!5@;|&iHcgs+aYP%kR_>%oV!Ld)$BcX9pvo>P1?=bNQa&7HOd<9y#aL z_HJ7?J1;QB5UV&mpgj)Nf8RZ4h~K=q1~Kt-|J_ofnRrvdl|e=;r3GSR$3?bFe@OzM zx(#HPl`MScX&V9u3OEAs^pB^maS?%f3@FXM@nR1EdVomF&s45Nz3Cb@Y=X?n6A)Mns21yHzJ`xx>7No^=4A3xY zqy)y(#`cRWUaZB}n2vE`s(`@&K2~fP3@QSrRzWG|~y4G+YV@NA-o3V=aAcx|fHpN}aRQ6!R zuB`_t$?#xqOZdF&Tcud@@*8gJ1y4LU)U5ty3ry38wP3O5m2vT&@PWaDYhP96)s0du5Ze0xk2YJLuHSWBmnU7%Z*!XG*-0n*V=}I zJLf*Ur@CI)gS7L#8!t?cI&GA7*3~|E#=tQ^8{_PhLM?geJOvpxMUs&>-a<5uj@50hukbB}FX)-3k`ql&8 z4aqK64pxev4YRXIbA>?9%kwD#s#$I4XsojEDv*|03&`>5I0Dj0?i*Xj6Ziz?g(!bP zMF2^9T+oF=#avOvcfLn_#qsH^Ro?)$mUzL_!m-bL)x+(_US{eF4h~$tSm-U{U^N?1 zVw&3<Rs63|l!yBKQOo@^@joH)(m7f;2t(-Cb;IncHwYHwqe=f1i(n0DSlWF*d+V!{mvB zkMRvj?k8l$xd@8Zv8q*#Fwql=w90@Pms%z?VcK%3ilu?$tC$0hJg=Len?Xl|G*Qz1duQ#buLv7$cybrvrXhd_%|Bh=i2-j{!wn zcUb~IIoi)={m1>)P1+q+@>9=bzCM$AN!1mF(w~sMAHg-=kg*auFmE*_z@q%~js_57 zt#EQsSjUP|9&NG;G58CaYY0vc|BQT&WSc>1jdRYiX8%Tc_54B4gGZEpxllXsDMJR! zn+xtI;T$XnyuhZ1)*8Etnh1Ki2f7|l8Di~`M`0L71VKlm*SJ&zkcsrb89OBDa0 z(XRpCW!I+ZT?(J^@JoR4UaRH_C}J$r56`^hw;5hvx9vow_=He5p1OE1ti52RV^Zo& z@2`t_Q(szK)#f6{5ZuQUK%~gfl}w zYF0ngRMnVn07?Bx{k9vuZk*qT%D>7Nwx0CLMd~r~YaM1BkOtBBZ8lLCaGxD&^wk<> zCyystiDm#8hz{xEO02lh$FFoDa;oNyV{mJoF&&_o;xF0oVn%~$8P3bR-jMDXM7kyM zEM%*zUWrrZbPE75EcZy0xqoF0xR`4UIUz75nLP8Uz70W*tMAw4;cA4-;H|#B>~X` z9?p2wy+;m7efJzWk-9M2{)@6+E+@JxvGETh3dF-QKxcp@HsPm*0UU6frvif2l z=|K<0RMtl?G&pH%AHLASE56r~_(|fOM4fO=7xnG0LhmkNPXL}rftQ2GLY+Kk;z?)Q z!S)z!k}T-QN@Wg%|d_-m_u*9s|#AZH`e8B0)h3q4h> zrmcLwOE^}dSK{)HO+m8g0(Ws{EV(;g+&)eJdNIcaPOl@gzK48w1kf^Jc^L`ZOKX-( zG3O6xw(R?M|E$PTaRBL0fwq%6aEZn$i?dVPXbC_Cu3qK<{K=XHNN_XSR^AJH8{o2z zw8k!U{)pi`kk;J0R9j|p)BE~O6#W_wn$`~kGC_#Vebzmh21^~?uSQuGJIP2?+;h^` z3m&6gPC9=wZLhSLI7oQ$CbI;O4m0~S_VL=@t$;$+#upUtJI%r; zhwrS5WokPG=@*03{2AL;H!xiY!gPlME)3$mW!|z%w@nPpU8EXk{&(O=wNM5iIA?48 z5VsAbG}kb(Rnk69eDBq28gb5R&86k$LIw0lxI4AMjMP%kix42Nxs{ef#rI6xT@=fQYAe@2 zcLUBK_aLn>^xrd>b0(?-@X39p<7^A$%E8=$;^Z;fI4- zwWF}JM1ZQFf<|PQu{j}O!CJ1a4zx3`UL}Ej#O(4X`0@vwOz}t`8ET+?@kx`tFHPUOUW$!-QQx-R$bMkV(6=b zbNCrW)o6F9fik1xl0cujy0@x*#jwzVFWc7-!K+pI0!ZA8t4>JA7K?vTb`MGgpVd;&O6}j&uk6N+$1wH*UFpUGej}!um_g zytB!C-Q2eH;pEYEYXBl<`Xtpz*tSYnYcw(6CgZ0jbwj+metgC)tXoWcc>b^~Tg`X= zrKlGB!u-5J2kN}vuW6|{DN|#N=H7>`=+|l%*7mlq_pNjV=9@K-r^d!4JQW$4cv5w- z!){Vt?XxO24gfrIhg}BeeAjxLRahCD`*lOpG;&wq5}*O=smRbw{Z`hcA-bS4{q(W~ zAH%gd_n`S<-7Z1H;$@s)lzsjK%5bdx2_etk1^0WxZ$xpg_$kXo64gyr)pQdYQw@0> zl~M)oh`44Yx##+KTHAGLpme#3Z+8)V}{`aNhQyD z?{tnScf&Oyl^1h{B3X1;?Y}<_^G--EJ=Jnog4I{lwgv z|LB#ZW(22A0E?U~UGs^Sbk-fvzt2BYZ_^8Ikxt44R3+e=#A^^d5-vFNa4ENWT4L87HDRlL47$@%RtT6i7JLrcwz-vu0cA1rL3g??f?F~M$z9tFFiW)c6SD`L zQ?3VsgOOkW4d9QOo&&m9PIDr^u&Yg@8gU{ZQxc3KV8(xZnuM&L*DcOi{kFm6hws}8 zaG)av^lRn5!0lepqsUjLqjZja-shfF1r`bb4SL;qzso6V`x?MaaW#HW3O#mH+U9QR z8EU|UPDLyZ&T*zCyNdu~)LFJf&BF^lvvht zr|vZqPm#4nKy~EE|NY|ha@#MZ=lJ7;C98ua@>eFCWD%7qdxUVUp_Z*0+qF1 zyi=CWgn!0y0hh#ZMR`f%Gt}jwQcC%WyXJ6+Pt$cMD3~#UuoE}n?>QMLWt)?^-V@y7 zu(B$lzG4(jiAiLjvVWxh_&SY-ey)|u%?9CBS%a zbNc$MbLL|~B^h3&<7&lHjs1G9Zo|opa}l}9r^YA6i)Qq(tqGGkB*jsG94h0~L!Cy_ zxws|vz0QSeOP<_&V_ZGNGZ((3bUD=}3<`0_ktaA+5T9A~>%++@jpKbC*FLh+VQFLZ znTU{?R%lJqs^74>(iPC#z%1wArX|x;q2Ex6F%6s-`wyYMtOP6s|@M3+HfnQ z!2BY(-7{2Z`jxa~;!W$W)louW_wjv-J>soR%51oaipfmed}`Qy{1}3+-Ap@jiX?>i z25x}2u!U<8xpHG1Sdd0 zpIJz4K8&FIIFGv`_fzoIznYB~V#~+Jxz04&OscQXt9#=Rp!)<*!S7ciZ~@hho#|(L z|8Bkb$l%qEmStOcvYlkuiN``E5>#YYvP}!4jxbUzzDdelYUa?KnqB_2Ao+=QCA1{K zH?E6T$LEoV14nFvq$@~|M=4yf%W&`cy#w%tOW2d!|dUEDTL)l|bDNye%XWc1<{^XQ zJTc)@7#((#>K`3zYm&8^IwKCcwA3Zjj7-YaA(UlLKje|yQ_T+^3>S=yq9Tia+E%-k zIjoWvZZs)0Or+1NOS2x+z69=`!{JOu#=38<`P$X&L78I<=4qsGv*OT6 zJWZZo>t&sxMO`x3b!rh``>v}^MiNXCaX(dgj}zUwNjLs3^7d6FS|1+Y$hX(i-nB=H z8oj@8wS6K|^!)|1*#>&0`zq_}gY5(QiTXO<1212OE$Whu*yQF1 zLR7+bRuRI#RxYG21DM*N+?}umxTCgl#EU(tI%UjyRj-{W~WpKZ%EVcdI8|CCyeH{&cH5vt-V84?XT*gE&PaZ1@b~V#H55K+48clY}bgHtd z@V<5_=hYs3LK>$(zt9eZ0qQcdQO$El@lYh_J^$kurVqJF{IZA7TYgML>d#+gbGdJB zyf;4^q{CLVQc2c1O~wa^A6(b61N7kj!muhA+&+wkV~-K%$9T2;)~-sHex@PrEIC!7a);&0d|iu4O|3$9N_3-q zmDx`yRmSAt`6Oz?=8j@H~Qfdo1Dx2Pj^4N$*RxNyQ_?T zcGkV*I#GA~)a53DkJAt893-hluI39F#=rH7L;XrDc<;(|FULo7$%>P}ajuEXFqGb< zS^kp#=i~8Y#6-HcE+>hsynJgT-d@Kr@_4=^hfOgu>!{-=Vz|#i#WGtiJf8XNw^3V_ z2(2b%BEL$OXwME#8A@w~d}nR#(pH9v{OIoNc+2GqhHvru^KER|LFEQNys0QpB@8w^ zZ}=H0&k!pu!r&(rGn*)8&xgIv!O*&O= zIpmf^(VmW0pMyC2P1C1*P3sKl+J=AWi1YdRJIzm?_T#I}SP*y4mRowl*7gAx$Do%~ z@yp98+3h$dNuFiZ0XmGH?a7%eshW{nU-FN#t8qJiRARRe$w}>!t$Px$ZJhfqccdvh zG-Dz^Q z4PRCL7e3au^Jq@w$~Gp<7g7(t(Rgk!D*j^rUXs+QI2|DoCjN}?BC~1EIOj&k?1d+( z&7qa!nn~hRxj6K*>gtQBl2urLQyLL6n%=8AZ`fp0{?TE;`PT+2CN8Py+{+Xw*Ccu< zBG~s~NLUoh>Z%?}f{Sm{O%R@)lk9F_{7gZ>Ps8cnH@wp$@(>6wl6Vs(Sw2o^#KCaOil?^=k(r2D7kMGeB z8gAoG!Fect|K!Uo|M4WJPAr7#MF5?3M$Tzfb+60J0ty__g5R8Cml*JpKal2 z2A8q@3bwJydo8Aio-?|&ja;Ap&TQVVx#0%c7^%<$O~!SRqGtOP1MB2<+I$Vq8);Yh zu_}~))Gu2Zjq+$xdxLrv zOY_?dn-f(NIj4{dD)}`NtGQOezz`Mjt`%O1e`|U!{BYIX32nI!wt~ek35(9n&ikBK z7ABJ#&(4=CczYGv>Bz?`yhE<&9&+ejTbZ;xoLE)eUAQ_UapiP7)eUwmT;ON~p3| z(^+r#VUwpn6~XycrRgcr#I1<>0uR(={KEKx4voUqQaWsc?QFWg^>?48hQWirLL@qk zbPulDE@8`hsm{DlzuA;++s%E;*$>-4=E-}}@f!C>b$Mm!FXhQPQ$8{u8mY2H(ku=) zX5GOJ=^s7Nk)xNWYhSOsk~5?5#RSXKLY<^O^YN|M2YbpuJVmukHeDgV7RCLo_}`9x zPfucgC#tVFtM(sHQdv_+d_QEbjV4Kqd7Tga$))>!(?MC{ex<& z(Y5LM6z3lw`el-gZqsqzEK`zqE^eA>!o}w9|E41TWuhtN2^&UqG#iB;H-DX;R@1qU zC{DRbdExE{<#NR)Z<+*d=H%)K)?zb#p={6N0joW@z&fyht%3HY^TJL1LM(q@az}B2!2_x)hhjC)YP~^*2qqCT4Tplf(%iA!F>{3n8vhSp z?;Y1v)_o5Pf`XtRsE9~WDN0p3QWcdhDxJ`j-jUt{QtU_(Y0{J`C3F&6C?X&b2uKfA zks1P05+ot;J8_=EeBWo@{~Y{`mviqvd#}CL+UL;wH_6XB>K=AXjdaFgHT}QG(~1R^ zunrSWdTn~~;Z_0-A?U{fSeG4i)8Kj!hclGrIqur$$^GEKNO;5Gr3>IRBD0mHU*ASa z$KWxjJMJ=3QjH7}i4ST^0)k^{JMK$flcIK%Q>qRP`FRa7Lk(_P9VDoVK;ZhIow7!S z{|q97Bg_k70ut{7C-d$O#ay$6Xe6VL4c5XCw%uoZfXmU@N8R6xM8LVdRc6DlZ_2l09;c1u{@@O8Tu; zS*^L+n{#tR>5Ev(9m(+MNPU=iNz+~+>~8tvRG3lwhsdWe{7(zJffIp2;0n%a@t^)~ zv+Zw6+O}3FArQmQjo@CU&tKQS{@V-i1XF1rgWcHp@uTf^_V>Ub`MFJY?5<<1O4;t& zC+yb~$zOmNqBzbgAiT_5|pY7KO|zs%I8{K1+yv0vfw8xw9U(TQbc$hFf#hTfCU z+ZbrZyJeJF#oeqY>-^SAs&CkBobaR^30j4>Z9>63s0r7~*B(1Xhg?2=a8rJ}_yPJ- zQ;Xr#se?cLHxdb3IX$y$N^q+WcB(}^s2rH1X7<``4{E&1@-pq*p}Rt*9!aG?*Dx^C z>Tl;^xKWT<7K_h<3vG2cP5>OT1#VJmgdevhWE!*a5{0Cik}8yr!bykf`OoxR2&>wK zN*q=$U}WRVc1d9$BAC2XN=#9oO%SPUdynm8Oq&n1;~6zwh;CHm?0%08K|V?pv}i~+ zL?8CsS~o*8e$se?79POWvh%-_-gDlt&cJrLq!=o%Y_s%As%F?hSw<7sui>zrsJwa4 z;mt-P^BfVO7PQow&bHZ3gh=Z#ms()S{BPF>P-_$qye}kgQ#=}QBcBU z{J1UI@=+vTt~UKrU5|tC+?Qk8@4wrokYx;$2c|;2CiB!Jf2~*=15kBi%uOK7Feuep zQMv=V?PgzFA|&B9j*abL(O=(Wk83WgT|LfKDWnC_nbmjYPQhasg}Pm4f~3X#q{`&? zYV2-!6P$vYh+8Z3wNsDPI1AX%PtEitD>qmT@kzkOv1MEx=cb42QheRHxPSJopE0NB zk4>D_!&X{PE^H&(W{^qDIjBIVolbIoX2^2Uhje+r!gEqi4%oV<=WY3orPPjM6Scx-fKa3>!K%DNQV87(E?s475S8e_Am`RAY`c$5A(ZL7 zNT>|O@&1xpuLVr%?9M1-Nv6kV`i$-_4!aM;verF6g>&BXhLvfTqGd1IA>G`$z>PDe zO?(qL-+16#q>p5r8P_vh90ftdat&#emAiQ&RlTVQvL+gC* z9V#>!7*5*koj4|7J(A1CAzlSzbX9>L{3E`uKi@wnH_$^Av(X= zT$Jre^6bc(S5u1>tl_hH@4L1+fVDW9cp5x$Aw%pd1Uu$ zz~qh?C)=ei_zy!_s!fTR+J)IS!OV2zwN&=somDDt$1+~md-v@A1${gWw{sWeu!RH3!4|Tv>6<^ zC31tEv>}lZ@YTrtTL}BY?N{e>U~5udeqeKW&Ho5;Lk|0e+8mj;NXjT$MdGeY1)vm{ zmAx#z%|}F-gU5C_&69k_d*>Uq?JoMIA{9_L>t0O}Qn|bG7WdE0M<|R)e@hU@tRcQWY^bsBdFPkU|G8Cm<;NV+?nq)TRua_yPB$H zTroMg4jbt~9t6l>7RS%a-h0C?aR&)bdn~E+>=Gy7cw3MZ1mq{Bm#5u7oHVA)_hs3) z8?RD^y12Z+uf(U7I5?3JxO`>Apmjn?ymB4f8J)$eFI1`6jcN-)&mutxn1*I`ls4`D zzz78Ni`)~rF#17;UU0indqA^dN-A>=?r7G{iB9Rz$g7 z3Z8>5@m|r`KF>n~IfQfcZA4kg*7v1+Joo!JZkFGC?b2|f$Tk>P%N_2u>v=ym9j$cN zmd98y_OUBsgA@P-_cv7G1q}*MdEIeW>+o+eXl@iCC=wL>zaKvs@?VvxaIf_VQkiEi z{nf1=+$D58v4&K=rMU^2U5DxP)xQb15Uw>{W_ei^)qjLkQNot{D@!?yJLLC`luA^c zS)bmF2%AoNznwVdf4F3uh`V8K%30P({v&3^Zp$b z97_I^ewjIqpsg%TIO#lZJn#j*d5gNmuGX!0UVM17`n5$r@luGTNKntf7ZK(a83*T( zyEgob>6Q%(CP_nguomIF@TP$N4vVnP`lA-vA`pP?M%L{UKnkoSUomC3kZ65&nr;<3 zR%;r>JA)lw{oF8rhR$MxcxxK3erR~&PNuN`Sb0eDc)m{e8Pn7TJ2ir5JUg1t#(ix> zh?UEGYpIjuK9Cp(onp#F&Kma?ad}N�R_qDx&yzpUvMq9WhOd7A|3ZF}k=+y#SO* z@)O7tX?5cfT~}AkqO$NeWRRb7(P`mLunX=)WD{I*Qkw;kP-&OZd-oDYA{wD2Cz2O^ zVcrkQg&lc!$fA>8oYM2w$9O&)xP` zaMrf%8IxZVJ?`yM?6hknD37aTXz|srXA|#zg02k1AR|&gv1fiHres7+pnjD{=IyWT z@1d*dn!;v6$V5k6(q@Txwrgx^lvjONln!DXr~<_zBlUjnh&D6JR0;cNr~a&`%Y7ds zD7T>{R6z)w1W4iG7AEE0vf({rWeY3!5pdg0F3b;1b&pQZKMn`*2(k8f<`${3*e(K#tW+bd#-~Hurcwolb zb<{oVH65mHWC@aUoy&51mb&NW&0Y&^4Xux5@S~cA4LdoZy%3;vz(Xg z&XjgFov9G3QBlrFFnKxYR(l>~SEpDAparUMn5NLsj^&5$;Q9>ehB7G07pA;1W?Ac* zYflgQNV~kLYUiYdjq)jfVDPD~(*i6+2yrRjxaih230!7l@buW}Dj%d>hdJCO1)df> z9XsX|F~Qql1~Zj{olmJ9$IZ(y2Y=H5H}`_U)Z1=tZNWNr%!sujzy!@FQyH~q)nJme zY%EU}T_`v~qxHMap+C!%+s1Ik7y;6xs>WB$)SB_^bwiVee1=h-ZN(GbS6e^-n_Q$s zYU~&_hOGeQCJ0kK5ZC{SaGqHj*`~zDsgXz8nAO{ar3mOJ?2PcHe9JeVD{s<&MTuTg zi`Ey9cxi@O@O&JDbry#tnKAxe%FjGg7~(t^Oi$DOv{_v5ZgJ>{Whk-^%(v+S)`XLd zXgZ!BusOdB5(oTujacLpTc`S%a_lTjfte0Z!8sa!hprfs#j{IsURi>Mm)S1ooGx;~ zDoQY$WfNP%md|=+DybUJ-oYP+xmRDBf=(BSeiOc4?Yi_QMFTz$E+0IQ*-fII6fnjB$m`z2orO~AJf*1 z9a7rk)n3UzK@y*jq5tZeH1-JB{dE>pvD7_s-rME|q$P_lr}T#;BB50-+BXHawK>5^ zlR3QnTV<|mLG|VjK%uxa+f6=n%{17|cXEyM?Tn#I#=YF$Z5%Hh>2k#W@a%fo;ne-r zp3kC|u+7(CR-DXre*N4u0WXd#2R-r84omNAaFtIT`2=W;!u%OC6}#_}oP5Hvz+l=e z5%#{i)U>+mK7q|L_@U^T?H!=}!fRHx}adbz{HXz;Gtz3nFH|am+i=g|e&B4GXsxMyu3>EyK*3-6Ua_%!X zU*)|hPI+l{sgiC=U7e_{tOM5{yxq{X<9O+lDmNfEo|XErZ-lpj)7voK7>C;44kuPB zgr>$z9?1%wMm6i^(Y{^5EsbCw;oNV=9?C|h8OMN}72g^`8`z=bQ9pdA3GnLzy&;dQ z&IJ!76nc^L-fh8Jrk#qMjv5&z2qpUMN<cMk*KxW0qb0Iu63s3Exq3#0} zPuH#&yFNMsMN+q@$vEZ=4dIL7PAyxH!}f;?Kce9Y>Z5~B^#PetD!FA z%WP=lcXmRQ0KJY;fqu(1ew0<-ial#kF(RB+l~9BKCltKKKJRQT3Y^4 zV(>?JlyK;p>j>>s??6Y4$Gh1x{Ktiug^#ql*ADmdFJ+?63rL*RYPM+K0zCKcDbYmO zL~587yDDLutdIzeg>vAR#&m=(p>UhaIdP_t9CP=^tJi-S$3lydx>8I9g?J6KWo}a~ zNM7ig*7@!)n-aK*cE1MkZ{)^+U@O1bYaLlv&L2(-)%cb)3)q}bm})$^rh4+HLN_>7 zs+eEreU7x-#Mzp5BTJvXvgb52XM~NJ7pG@hBC5$SBV+NT!!5uarNguDHd*Ir=N2|o zhKL!XV%O7ESdUyDDl*zqn?EPxR=hk|kX@)>z@pe8FpDPI_ht!NORDq8I()#mVEK~F zvI2hjdo?&zqNY4Vy!ryJ3Ev+WIcltgc zz=`3Q`@LXz^yBGGa7BY$;#j%$bGY`y%*c~;(%4w;PZL#+@%95^O}n13=@^BL7Yh{) zC$*c;Rl-SI`!Rwd2ZJ~)hu*<5@2#OA?S=mdueqt`ccd~{pV>0{M}=7>6_t5sQ3HC` zAQMVR2?RAJTSEMuQ2ui@7q&wM^sM~6raIn8kczlNcOQSmu-nYp91V9KD$Kp}=3Fje zWsEh4U6@0ySt&X|yZPeEHLD{b-#ArX88o48I&I7CtaZ?waBLH_oRT=)(jhH>@g64# z(|Q?EgYAhxSIHU2HAr6v_=$XzKiaQp_ei*yEXmuIq+TPFf!Ns_O7iaS`gM$k+qC`} z-0YrM=^S@mrTdI@Dzq$vjh}hpGgTyJc>&K8HZzs9!xUu*d!VriJYw_B zZpX1h{aqdm+L}BVU1e62_8xweN?BC=$HReF=udrdYKq*qJu@DsO1hF_GIq{#eYFQP zvQe`z>qaqUZ7X*O;7=TFBWs}AF?>~!%Iy{;H2H(mXN@M3S$P{so)fhUtgxcWM1k)Xz-t)u}V@;AIMSg~d_>_2Bh6<&cKAR)srq!X_0tn1%qa&r-~E!(#ek28Hk5vIm-0IeY}S z1l{5L{sY+9BpzBCZk@T>A&$nEzff~h1SzxbuzLBjGQyg}b$a?EUL#D^w7e^6`!gd= z=>F1pf69~iYwZ#jm?ze&LLJ5zeu#2XyJwEO^@+XT2106OH-GEBE_GhXC8<1?<21_T zKF&h*xCqJaTcm|Efz_BG3jy*buY?C=t*xG-NDV7FdNufF1nuXX3XlgZR(w`8sEVPH`(8zk6A2T*p#^c?Iau)=DznviqokszA`S zvt0MvRBv|Xc(w-jC@7U}Kkq0|lx`ha!jg4f z`Td~Z1@>*Hudx^U*-gk%uve#r1nCRhrW+?Kf!w0zOp;ZeBbv{HG~zj^#pAF1GE>E4 zbX?6;K>3G2i(1pT+_2{jJG#}8(&>;i8g41qLhktX_tgP2&0(h8pn3U~T2G0R3XY{X!__tFEzk4KG!4(?Fdt^f)R?ZXwca?Le`g-_FAO<-2z zY?zhfLf=Q#>c+1wXg3+JXRE#G^7SI^&h*D>g73cF$jmwwez3bqx$ptH-WA2)f9xPD z@ShY`afcE%n+nJ4>&(pJ(AEzPd08AEzUTFyJXXY~VYSekUI-Mo=*I!zNJm~X)kd1| z*0hhZ-`~X93%w_?Wyq@@O3wMhOWf{Z+>KcSW^4t6zFD>7@LsEu!|oB6b|=9s+2|g;WCG`(AY%>#2C}&4kt9o z$=07XoT4Cnc8P`4Z|sU5tZXYw51;J^OJ)SUIs)KZXn5u=35@|oma@9&bZjL$9*ugMYq zH{MlpoMBeo){{Tj`^P@VxKEAxFec-af$FIVudQwja3@Bq^9(wzX4m<+m#GiaV!{m8dEenoT2pZ8&*o6`Luzeee8+bTC1TpffQ-7Gv?%b8Tw|!B10VxQuduU z;%oyMemIN)M5!PBwAKRLXImXuECBG`59dULO(#nc-SoD2YK=*+o~~jp%>79C>oX#S z$jm5#hqS;FMs)6wwXAZ8%Vq%fq>u9#sUEs@vR>^l8{RDyI)1RZrm_UBiJ+x(8S_EJ z_b+3_pEy*JKBoWT)@I2JWsGKsohm@wtH(>Z2r?^dRfbo+Mfp3%{g{Kwfu)1b+AzbqVsvm&5$m|{8> zD@2)>*9)MQ0x`9GMpkQ6NT<231Pbp~XkPDIXw&%?qtv~j3{0tmRgMGa6PkeE60^|{ z-Izi~&%MP{hs}`Rf{*>sEfb`4Jqnf0!PNGeE#?_|8-XF+=cfq|-P^G@$kS$rF~#%i zcuEEW0Usm2Q5#3-r~?Bm2AJ!hAVydFf1KWArL#b|r4RG(G&F$`!Z7R}I7RmSoOb$k z1EB>l6yzm*$(la}0Z_{~yUpiUg7C|^KDX^`#LVlwZ)5`3xfS0HPY^w2drD)g`0Ude z2Z54`A;YQQkCehTl>Tx3e-<`MEM-vpjfw7EMIUFI-*LG_=OU#dB=IMD9@5y{u_DP{ zM!B%kgfmp~86&O&5(u^LZc;zd(8%D5w5Xz@s0#?Y`4J4v&$Z29XRT zkfUxLfCZepY!ASxshqfc$)o{S_kvss;_Bg+`GDE31R>`z%N;7(pimOnBB+uFi4Wed zDLF@f`?okrAu)KK)1V^u&M%)czwy854a(0(1!7-~IquD!q=ENUZ=%hf#@951{*%>m z%veuUvdYqhFUEF$=9b(1Q}YMIKwM(EQfS3l`)Sx^8Wd8qUm=CuIrV$`+hRstG953f z2fizb(cauA*&PY_Ovlb=+OhbZNIP`<^_lwsDex48m0bmzV)nv~qntTpsK1SIlL~ne z*m7LS+H^Ep4!w=a@*8D=VMN~9A7wz-`Q++$9lhMowOV4eVca4BXJ?lHv zZ|CVFF^Yub;V0G3BTj2-+nq&5&fUD5^dODA|0|6Eo4Pp%gZQQ8)yev88QI=!V6Ab) zb{lJ|@%(OOQueM=Jr5fPaftnGCT!U_5jeg%rC@)B>YM)5E={=YvtOQbTihw^z|=Qm z*OQLjy_N+mG1@}*K*l>U0!CqtAbDlF08w_kG>Nz4NNPcJL~xzb&{X`MmsZJ>$&hJl ztnt&JgAfK>sfp7vII;Cy^kB6)2z}^eX`j`Z9eR|(O&|r|aj2R{pma0JFa5jCLRe@2ms^Q`~e|*|d!CeU{&qd!12*c8U*a!kf&N z)2=KbQ)W3`uZ`O&CaHia&s?e3AfRHPDoix*1Wi6meR9CJHcW4=$y6(K67a`pw4PuZ z*WR%!_H2A3D>#7Ac~}cHf-s`wZlbdk>$-*kPYq_V-f z3U7G|q31hiy=lU83k1?U!iN(nm$rX6nynTyJVm*enPKWRenxqJCkCFeRa&O3aJEPZ zbX_L(J)3QmKUT~my8ZG^iQ zruTGj))FAeVO9lxzz=2`Dhhfd2QR?%3K#&87{2{Lk)vvoCzETu<6C2gTZc%)vxCuO zB6#mt?yJLl!js{W9RJ~7|DLd3h}`36dAYmjN%bNiM0RSkRw<&{(79@3W9d=qX9E6> z%v9fs&3K9gir4hH9O)*2X)Gd|C+Y4cN1tZ6GE<>kNsymdNK!G~qeum1ht+N@$MY1+ zSOca33$vtRtU7N&t*Y%13r%0}bgbMKs%nepVS+%A; z#Rb}F@;QK1qw&b_Jh#g4C26FrwYmnE_?^H$m0xn4TMV0GtKVAuLic_LrWEQ`*0qWm zgw23%-O(ojc&_?fCe6`KMKCezQ6c8tW=?38t&ov0x5NBTo^eUQySiH!vEi6um zHNW?gjt}|{OE}1f?EVhlex&#t7>*NYY;kj4OdNU3cJNIwA>;|`N*gn=W0a17mk41j z-jTzRmXxB3nU! zJCqvt?XQRB(=)eFz>ZeP2_XhQ{D6mf zHUJt3;HIHRiSE6cg0n+KE}QtU5%Urg<5^X^A?c**jLZ>@rWc{jQb~cL&M@oA`kp6( zr6y|~bxG^qz{Dtr!2%tMxv+LOGR}`!*zMFYQK0+DI+gRI+uDGtNU&|%+e6j(4Dyr+ z^LgG|&SKrza#V%TxM{mZ+{L2>Cg>PX*ViM&4dR8NLWhtIc9|qU1{x+{)wP!MQpE1m za^lzfSH3r+><0JX*XsRWoOuh1XWba)KvWd^nmv}nK-ik^eX z5DB=V>T=Jyu3?Av$O#8S9dPW zc2eN>s(D$-yZcQcWQQk%P{(Z}d7tGRo4i#(Tz+zI+-Zki$bC1hQpWC-;M>VW^&1JZ zY_jOIpAwHFy<`=rE7=1%+p(K+JhtZYwim~>N0D&A{`znho#tmYtM_$P3kb20UE(D- zdE0J+z1OTXPf&z&R{UZ(L!@AvW?h#eW;w6`w#y zBcR>!>glPn7;907O5fT5zfAZazk+$or6znG?MZUvT|OFzrdWuQvl~@A*hrxvmD&lS z1`kLa^Y(eOoX%{8tU#VJF9jAI46!Fwa)YtxDTr2A|M?{%<2?gGgL}%sglPNmV%(~9 zcAiVNao9|MtNSpc&CWeoh(jkiKjDs z)U7P(AI|Za{>-w8J711gL;O`GCu}lUO?DtovyBu+@4rH z$zIuO-OUk##3Es;>50BTkfj--J@L{!F zG49fAKBk4(s7t&8>O(c(FcOvQ+AH2fbhS@5?Ye6JFmZu}@W!CA!4De4ASu&*b@+F* zkzL)CObpY;>er|fuT?N$&!D4yEWegQ0uaRMJ%Ws@B`^bs(TXpQmS@BFVlSwk$Aab< z0-Vk|kh`B>Y(#j3xQR2ktp6Y~byDUhe1^bK|J@?B_BLQ`GfS#&N=5^*0geX5YpE*- zeK#>Bfe3B~-@89?Z|ELoD0fV|jjC$0+8(Lcd;k?%z9)m0=ckm9}3^D1&7(1G+dU`=g)pzVP-& zb_~lW-+J6=xoU!_xhXax(%zQv(-?sRGG3uUkrQ?j90?z707RdB-I35mfJh%`5?QzS zzuO1x+xps&$~SiwGP$eN6Su(x{`7Y8CF#G_lnYe2Zo?D!*Cqdmg>PMqFc;muie^Yf zFQ{FNOVnr{=)wo2AA5~s{XH9_Jor)|;}d%q{2e==&7C*^em^M&5x#7_eO+Z(Vpd?| zdpyOpd_>T|THkONQOKag8U>YOiw9~s3Zvn;Y z`j95zx5$u~cm`hop~6~SXP~MPANNp?GF7&BdTYPnTCtrypam#s1%US^&Tb6}f+o-WDeXW?3Wa4&o zaQN#)Z&e-SZ(K&;+oG}Y=GOM7D+Wj%CqOED##G}A>~@!DXI8*7?P z!0!YNFc1zWnvYas>Pqa7gu||L43!oQiw3s&a28k+ROekL=eiON_qW#}8Q92bXbzO+ z34-W0*&Wq19U|LN39ZOLQM)}Gol~P~K&eeCHdk|vh1S3>eYDwOG;tL_ZvDm`u_69l z3ZN*`37ErU7MgFq!A{V`Vv;_Tse8zi8)V&Za@<+XnFrJ^>*4Mcgj|OeB|jJXdDN#N z#9!xT`ml5bm`0ffo;YcK9N;R?OO&@C>(lV)Ti*`o`;hGOHFXDgD)ye2LwQGCU4yWV zmQ5iU<9B+GpExJ!u)mJ2dA$6qm1(3aHYEb-28<4XU|ImWqALZ~6W)(3v=sGh5T!=U zvJ);C%1j4W5^;!W1tZp?@2$_-j7=IT%HP6uz}$L<45iH(*)>iAY-PX0LIC$k7jZ)4 zOxmm`??iits3`!cdI<37Gj$k%fd;{u3%Ns=DrMX$Oh$05$}e!FM)0UfM92q4Po}Yl9nKsZqR%d9=cYdQX4Ig&5T3$AGmj;!+H}Wj|L#CX5^G z?~#WnJ|!ChotGUQsV>RPQ)6O`@5lG&pcXU&!W>j8Gy%n(eBqv ztYtB_e-$2|%;7(UhxMlVI)0UTcj#{Qx!x>FqKox{g&oDwqB7lB$okX&>iXx(fV4_XAB zL>3l8W{_YO_JIR#Ol{gpU)h*4xAZo4C7&U`AQT;N<4x_F;n3ELBedNXP>rNT>B?;( zuo0KvHm2OTZ_?D(|7J+lk6^%ZB&lzaGOe}1U9V;Cvo5D;rvZGaF=SMqO8^m>H1k1D zs2as6^06iV&O`~<`C#iRMZ(5}9U3>W2c|}C?o1r#ZYY^bU$3g83~*4F8!Geiid8bD zUYLH%_o~QV?YJJxsF~dMZC6xk_mSf?TKhI1sWGizSK&* zJsm$&Hz&L;p3!JVEOZV9`lrj`o$pj8x^|tofbV0PcI9Uz#zxeQ&F#SKsKOf{M>%s6 z_G2G;w+DM@KTcf3)fBU)`r?W>uuIsgW>;7sW^ zIjN3aFCcGTim9b#jg9@tUU8}eP$0L^ zI3<&giw~4g3>^@Jn|a?IFH7D9Vb)rW*kN3-L;7`}L2w8|o<%6x2M-YUr(CV1Lg22w z-I@HBJ*bB`UhT{#G0F|R(d5|Xa+Bw2sR`(4Fpvc^&9!-EJ(lPh4F~j4^c-4lA+3gY z<8W+#n&&HP^8zfew(EnV0ct4jzpTn@eoNnOpB6D4EMEcRS!P&z7P`dEZ_#V^xms%5 zp}LCrcY(lTmQ4~Jc@@P5sPZ|7Y~wD*-i_H~6Avy~MH`(M`x`Tgph1b5)(*)BMjXsj z2cYiH(q^8d*Ged_&l|hxyhp=C9>Yoo&4%BSa>3`+GY7ZVz0XDCmg}O;E?<5)>Mt?* zI}W%+%#y*_%XopFz=$Xdov&?Y4VyW%=k99{`D?8@{(8_e(FPR=eOW z-yrHGlk*W@CTw}6WsgtK0*h>QqVAT(d6Z{_LK3&Me-OqP?VB7n1AM;R#}kiES|p`U zUpptgJ%GLnkEv3%``Ac$waH2-f?#8lD|sQ%geD1=LnkUgUN5%rhWqY>9VP|(O-_t^ zK}_(r7$mT9aX+`&`oEu`+5=XHOzd&~uNw+wsU6%I`J`e80V!*cmo+6^^DfUYbe1doy>12Ml4R z1(~6Ha+-2riW2QAG>35qEMmS+>iig2>Agba8;cmesO2*m(Q`JTrC{4>+U33RVK@ig z6w0Ip=hGe}tlV1zj3&l9g8sU_M>Bmfju~(ZpH3!J4edHCJOXgC=@PxNm+UyQrqRWp zttYyfIBTlqh8ah$y_yxtq!yirtFm!j{ExkW=ZOlOA=$F30;ycZeXs#L7_Kv+l>@;G zp8e0sX}@;WdA|uhH73*rTjYIyWI-*y`4n~WyEIlc4R?O>M1r8f17y&)VXCz2M&ZR@ zSeo#|@#Qz)(wMaeAM>+4mHv=goMdYHmt&TJx6KJXY~VGNz~&SEOwe3O4KwW;(4>lu ze-~+Boxo0UaDG_vS*nfpt;658D>QS7WX@L#C|#&qVx)OpiZTsc*60X?qnEQ${(_a) z*QRPD>&$Ho?Xh5tPDZt?TEuqPps<^(rIwR~MJnT$a8&~4C&9fzAWqzw6ftH6ULnO3&;*MwKvJRe5z8n{{6Bc;~ zpI*6O0=>GX_3m;>$=c&EOu6sJHKk7B5jTmRRNL;&=zOxO>%L7$l}n22SR?8KM-Z`O zV5-AgNjio}eC7Ac`5Z$Y9MA;Nz>k=i+zh}Kb2?6ZF(AolsIcJiZ2Ogzp@B7>oA2J7 zlln%0&ihs=i`~zPd^_gqw=(*@=omdecWCfR(>_f&@`@f3YGXGJ#*n^D?%jTM>b}gB ze>M@AXc^84g+1^(;^17IbBTEus4|~`%}bu>39=#SMAI4XUVolSKQMJmE(BeF^ae~R zbsO|_27n^nzz1l9w5;=P>H^xg$j{;`ulNSkRuD?r|D>;ipz8bxM8dl~WI{zwYfTh(3;liNrV zL#?WA4{&#P>I*|1MEE4^yM(h0iu50ZD#INmJ&3@E)%e*M6jIpUp8e|UWgsRQ#J6IF zQd*2fZ;C?ls@|sXi>+ZakmBE47Ne4fHwZ!WrzmjFAkX^>;JL5yNmyEV5SE;|hU;vFOsdJspGMd!pw?6RbYbtgNp1C18HFU}>FD2v#;_|Cm@@#h5fM`%~(+*221vZpkX~kV0Z)k@eYTk z9Rp0SGSJ(s3;ve<9Un7RO1?ZYIG3BnCc&eOhMn)j6^RR4eZKeyjt+fYC~eOg19`0S+CFMaBtuBPzIzb7D>oMTMhPU8>cz`W$8Knv_BBIp%KZHLL604`Z}q4EpYx~EMZn}lN2|-W+1#E`fGZB&*%-e zvPGv$24$e#w>OtEiOrLb8Vv-K5}!ctCGmYzM4SVbR=PCZ6e`(3G0891a?Pl$_M zOTK2EB~hj+YYf*df7F&Wz6i)Z10d`nFl7%TranQ@HUu;J7hqIfp4b|;ap?&-4KMB7 zb?;B`;Ilw{e(E>z_&LGPjG!UT>RsXHDXMSBu?oCalKO%Rifx7d>p%L@`B6)N7c|w$ zR5I6iF}fzwuTu6-O!?5SVTgMH)!`$zl=Uh^eohqc7J8$L%Z&$sQlKHGjJOWi z9<{@5Y-S!|*TIRj`oKz&5ZMMJM{Yp@E_DLvc33cjBJ4lt1HyQAV@1qca{S8C+$Qme zbpRUYO_Fxnfyi0>CZ6@KY>Qdsg2tJvF-&IB5B=#6*1`&771G;;Hu8t10|@Q!jLbgk zW%if1LcD8dW+#CU#_5GRW@mxd5`FVAu=#gTi;@t`ey;incfz86Q>c4!spMPrd+9z8 zD{jHZbc`&EIo-`4x1_ZMevlm}z0<(S0CS2-t3*M16`$8O4q*Os zF-f1Un}tQmDoHhQ&#fEXu8XFi$k>n6fZG{ttXCp$4X|UrO*ke71T(K*V5$C_Goz5U zO3b97Bx>Ve#{8Sy^+434=y7>R5al$JE@vOZ59y)3=~|A9^we}Ykmk{j&cw;l@X- zH7xGtJpte2$2As%zkLrnV6=iUFK7R6A0LIA7^G*6x^?mOrMRz-1x26zIzeRFSfFm2 zfK^OWoAu2HDW_>M*!@|B-squ|So^z+;+*4;_PTWosYc8Sd)@pht~a!Nq)gqBPW%>0 zR=O)c{1!S(5`NZO#8 z90HaN@q(9f<7YO1H*dapCUX!~@(9r$YjnWL|3-J+?Q{4?X6BR1CZlIxukyl5f|NHS z70peynQ%BGX5jhAyQn`h*xQpAv!Zs7XDI>;DrWr~)zR}G644=|Zljw3P!&)lBUlhf z+CNGua=*x&{p?D(K(DTZq5U|{sI>h$UNk2unPnoL@k8CpAZ1<8a z*Oj8h}KLKHSnyvaCKQ-OY{6lP2a|_%F+Dp~!zb~Ac zW4!(F$Mh}gk3eMTi%#LaT=&Bg9dtw~)U1-{dUjc@SlT*DH3M6wv+EwOZ-U&%NML*u zaeiQMrEot)vcsz$x;N!LRA#~Hiev$Vi^%>?(!%uur_holEgo5NW}FMRHApad=MjC; z4JZ5d41X>lZUz1sz>d|R28%>q2f3xXNf&4h@;}iWbQFfd+om zDse5E9a{V@QEq<{$=GziKD<&SRT+~b4M3EMSK1+3B`Ws~_o zc_MEfSiTC6BK3Sy$yQak>A{~K2m~q`PaUxS^HaH^gOP`*YelWh_8ptHTR9lg*SCvjr zBLH7}l-V>5yw6`}RN3Drrcz_36V3LO)c61FJaOF*KvKj^U&P8s`6&DUnn5{xMyfoKN9Gf3RRs)$_UPn*MQfcbd}pX0#g|vccK5((_4Di^7b)XVRZ|`&IZ6b zGwTKxH2MAb2?KESQK#?S@4i4otRWi-DhZ7l<{kVwFV`R2#J6%8&bT%=XtdllHhpB`w14^hiq25Y+8DkY{5T>5f?|N1C1 zqVGg)3&BU}gg3L`dRF?zxh=)?+!eMzEra&7kiw3(BnTCP^Fj(hlT%0;DAI{>_z-C3 z4-fPmyjtx{zDS*Qh4Domv2tVfJ+0G^OR9rU)5i-gF%{*50lWNHr{vTV1Wj&IveNbM z$^3;t%NR-(i!uyC6k9>^{XxCyU4dE`D#vtQo(7+GaP}-Fp^|!dJ8Kad9dbMe@@GBl z!hLx<9F*uZ$WcFO&=?%xv(>LwbR*(OfljKltw)hpy?9(XbleWyatQoH!IeR#Ys$Io5h6)H3 zA0rqIZ}L2*>TQbLdHSyIublstnyNRGKg6o-{eS;yI-7_mzBjLOoYUs`$0)0~Nl6p5 zBVYS&(J+5y0ad&ERTGumxH`ZdPlW0Zo4F{%xvigEYd&km$ZO4*+;LPci04*^xWSW6 zF_R7RM7zHd5Od<81zibz*&E*j#W(gmB_KRs<(&Gb>O)0y5mehUQSXmj;OS8C^jR_O z>$G5YLj2~fcQ?+y`SV=L^2Zd90AS2Yi`BSqN<-1oK_4avy zH!lm`{3Zss5qS2WSN~a-|KkZ77wWXo&Kh@^B;B8dg>8Y=5BlbOIq22#q&z-3f}E{& zAQt}~|4S!9)aP$+usNw63NvE?QNOh^Sbz@&j~8ISaIuRgsvQK}pSTZO;W`WeYKIP8 zq;T_2k{R){mgQeBQav23T~+B^_Voktb@NQ$UAkvxGD8Of@ozbZ?q>-F0nm?>-J_v= z`P1Ox6Xe#ogul>vdYlm{HmGk^3=nqkwT=|gBjOyb0 z|ABkjrzq*>$8D)C(1Lxt1Wrgysp&>%N~eTzQ=5%(&O9QOlmGP#@UT-J|26Z{rNH+W zz-QM$8|gXyHN?PUO$%0kLCsO}@PFew>=Y&F_4JRn9SFt$^XfAxuim;e>f=Lzu6+Qy zP7DpbCtlF;PoMn;KWBYkVgobSa>LM~+?Kxu zH~RaZcxov-e$Zm-Cg?L`btw;@NSDf`Wxe`O-<^47F+BI=<*GvqmK#e9*PwqbzWF(L z^$gJ9+f)ZWtW6aq)n-F9XAf@jziqk-4Y1`_X3w2IL-A_|(^Gal`N~%${QW=e_*y@j zTQTBh;LA5QYE=AdRAlE;^UeUHa$t7AfybYE09J4OwZixxSAU4=&yH74!u08Z;o)ik zd`;?2RtGMCX-GN`TfZl-aUFzzm6|Y{C`zH>?6^FbGD7+C_@sMXf8`RMZc5ybbUgFs z`hV=bc|4VC_XnKacG_`-WC%r6GGr+8xKmLgBJ)_=kdS#Ewym57AsI`iLS~s|)vlTl@cf>h=l6S__mB7Ue$GGV<2c8CU-!D!@Lk`vu50}%T~6^?Hq}Y5L z!2tu#)}&e=h7kX$_gFa$;%uLu6-52Hq-}zSR(X0fINRaE@4n*HSXL2IusZsUGse~| zA1WwGGRF4UWUYVpf(W~5b@v5~4zd_e2JJcCpbA0u+n}bQ+Yev=3I!3q>6!TBEte*F zD?^lvZE)0rd}b@OnqFt6z_7d6C^YMDI_pKjq${4%_|DFfC&9tE8fH zP=a{K0X9F}{c^~C{HK9#X5HoP#%*5kw%wc8HoOL z`lFhkd^zB7ZKLq@r@?UgX5fvlpaX1C6F2MX-qo@rd+&~Y7&yS`Su6P`){*;1tTP*6 zbnQ|A`L*7lrd5CcjvwaEN`t;X``j+A;&-k1A@~24B$k@IKE8*u7ooe`DjR=+&}T=0 z`$!^*1@mX!oE<+!TmL)&&WtbJ*+_)Oxqy%X!{uwzKg4kORK*7V)yVK+pIlaeFU;5>W z;14Wf^sDhAf<|PeCF8`=xs&IXH==?ze%w;z-4sB9LEFFBVu;v@-4VOiU$&iggGA_` z>&SyWghvb5sn1!smwR@BG>_$0KyTBHjowz7=B%5~>epz0>LMSM%PY)DDxo@@<7M%~ zPj~##%y(`itHe4g%*AGE#+EJN;DIax3CTv|eojcN?JaEf`gk7NF>^N97{wug4AYCk zg=`;)okddRPU&;P-9JSMr-}kKlVm0lsSFca<;Z^sp0yjbK#V*@^~4$c7Q>%r`oHp9 zSo_tp9I!ze(E6iUlzB7G3zX(6p}W{Q6_Sxh#DW&VC;E(etWz?e#Xo_}%p!-Vvb`4$ zaQcbcxjp9mxrF{8AIdle`kl|N{NYE7U@;~b^iZ9^p#y&% zRD8#dY}dj0$c!y}xILuD8}xCm`f}u5Z&8KIG;VvDkToDuXF(xX`=n^3KVBy4D93w= z$WdUv|J=6bp6!Z0^uUf}-2Gu-rY6rHM{&h?jfnXDs7g*5x@V{@PEVE|0eJ=zv_DtBO|*yRV85`-NnNzkf?_^-af%o1}q?ww(yuyfs|(0fAdr^xHwhi42r zp|3%=6E1tOJX8Ebw|POg-&0}gzdXYh{gvuHC_r`Wt}IcH?ccJQTm8WfRPx?N)7`xK zMY%e8*VUc$rA}KwG)hOoY5B|0Iw(j~_G>4o<+UYtMf_Y+R}U&q9YwvTZ!F_Zn6G6D z{bBeJ1i{)iNa&Aj5ebk=uq4In3|2oqA@*)J;U388_BtvA3X7>oCi})$0Ewh0bd8{i z1Sts)63y0`@18O4eMLcN{At9#*+{99#NSJrJ9**JIz?dX5B!Z~0NV?^@>`#W%;k9E zU!r*lQ~=e7w|km6w(RRRM@h&fe`03fZTI=g?PR!|;+E|=xg%iaFtT^jPoc4UkZAIL zme;&D^`m#mzwl25yA&KG^iAJsU$?&?B;W)gL|~sTpZbwq zZQs7%7k}p92|n3mt*obR(5w*b@`(KGA#ZF3hDWbZ<-PQ)F6%RFL93r**dAQ`c~pz4 z=K2&Bj_O!U)LXuIPUa6UWlIunpW^EJ;LP(aYkH@Sm|%v}L$9AEH1Ya<73U7mWVjxx zLC)U6Xan(isN8UPIg(qjd1LD_mc3>Aa8~#N(nCH-yz+i_Iq2M(g(F>5=OPg*tRl3V zgg2k1Gw?^Y{ZIhOwQ~<7so0j0UF(gq8>~Ha;D-hgZjpW<-hSV9^YF?R41~=7OORIm@I=&*YM!0CChKh@2Z1xj+UE?6lO{)aw+zmv)0h zeeH(cz%y(EC$B2YvCruI+(t)l9ube(LozC%HYe>~PTOSnhkFh4t|eB+_cI`n?=LvW zdKTH?eJ!W5{!+z%{OL34(IUMEsy1aSa9~DN?fFG@#6qFd-!VIb5XTG-n2G>+CfT1! zBn6qsczx#Edj;v)tcBfRNhO}UUg6M9oIi)vf9`(ruge|sC;!-ee-!VK&g=~9-HTgp z9DI<9ELU&*@cI_=@UO4gj0U0vFL-ZYtuN=Gt3|Xt8-vkC38VMFxH{3_e}px*93|I=C^!9$GqY0MUxeDn2QHaW&8uCyiF z+GeQWD`aEOAKt62cr2oV4<6Nb;uktOHtKeHo71e%&=|>K0*B<(k93}-%G>@|<4=|3 z{_l5@%&y2puTsii@umH-fN!-7?{4GRR<`1o9vBl~Jd@b(@K3MlMf8mohZdJ(3rgT6 zU}u?y8(w1l1Rkv7unVNw%6-3K<;bYq?0$>pue|jqo3z64?%hoW#?V@nhjRV;~s3{+e{Xf=awtOSSO*K4CA^BdwZ)UZQF$ta1@{Cz0+n*!y^bp1cL*>%6Q`x1j@(-GWWQbu(^nRZSTJ?yL z0kPU%7WX3`L72A)9IJZup^z>2jPF31Q}ubvP<%(2)GeF!&pg)u>UZ9TB&bTS1g(F1 zZTZiPdYcTk=>$O#iAOud)whJB?ZDxGwW>eAtxwY%`@)bjY|FO%{N?|CxvUf@v`@45 z#nAsZLYS{y`6-6rGNAS073b;2mH^?0C{Mjdeom{o$`i zd7qxUr4V;GRN!>D;(jhRHMe1*%<|shG5a>7lXVCzC54Jq1JygdC{ed zv(dd?e~vnKV`XJ6-1R->FxGp=pR;@agCA5hVKA;f=kT8o{tthc!@_eY8`aPMcgw-X zW_Ww|6{$8+!yL)~=EJ@d;5i3lQy=~}4?$*G>XVREIwr(#nV^`zKc@EmvV42AzO0Q Ku1zEx-Il!z<(=eN;De1xI;g5 z%cxLfmgxWau_I(KN}Bt~f&b%Y{Nrm02Qe@^nxu$p_kXmCzpUsJEftlXrh@o?D`zPx zDypuX4(faV6QTUI9I7O4a2y#S4*&SU|5tha?STHZ1pjtG|Jrc=c0m8yx&7^c{*CMZ z+X4OUfc~4H`nLo6+X4MoSn6*F^tS{0+X4L(9r!y1`zJ#AI|cjKLfPVq|K@=HO=SL? z1Nzr&#orF-U)$Q>9MHevCjS3ULK6;>TRv13mrig{R~XI@X}ZaoFr(EcMAKH$XSmbW zx>{;uG^9y@Gr`|oav>>tdm{dcmLD&)G`n{&?8$5KHt*%sqGwMX){m+Tt%OyHerL3y zDEvilX9h`|w?&0e-(UY)!K%M=U6}Y(YMW{{o{3#E$vJptGi5R*8x^sPi<@_)V? zSqgt>Cc$);b%AC}pz+4W><%e^vY}M7uc;O_5DgsR?RaL;#V|b`Og9NYHQoLcvT0MMU068^Wz5s z`)i2uU-B%TdQe1^Gd6tZQhrWa)0W&;#ruyt@Yf=KS!et{=W%al8@Fxr5M5)49*}ibt8+jBh-b`F2_$1?nE#(oyFptU-<>>IQag*po?+TIHU_o-;LL;Yk zlkoYEf)5kn5BX3q+R&B`cgD5r9OwGtJ_brh!nUWcsDV_<6@R_9i$Frfk8g?D`BH;o z_r5{(U42eXXZ}$t*i*4zt*aDQxB1cvZ_K`p*KXL3v`1*neY(%ZlBZ7Ms_u_LODUJ) zSC>=XI|wBeQO-S&N(Y59Iq`IN+5{3mZxgC_g)vz~c@3U(@yU)&fgH7G&}cnOwr}vV zh5m=V|D!OtaxQjlF)>)w`suMPE98DVDDX!w0EX)O3+xw}Gzq=%ue+(f->=20LxQ@=3WE!Fg~-sn`J8RXv5VhioA<291tk%}(Cq9uXS4&XNXc*U{;6T( zE4+?7Zm=l*kIM8u^bFo!e9c2;&?Gl_tKKymAQEXd*tvsHNwehUb=7qGEqwz_08f7P z#-AQ`Ac=kI4UMv~A8*mMW&6suU#zu0UEQ+Ru)il^Hyq0%E}ZtRhyWW}v2=*(spI_c zEWmYIVXLuiI;QU@32VJkWEk-7`fkd9*-%B_ZbWyd9%sHqCze*k%+j3Xh<3Reqr|i+ zi^EfSnV#uuFZ(vkWol5{q)fOAD$5xEp2X@%;}E?6sQBSpne!-L*H6;rR)T@Z$F3+E z!HqY*i$P1o4W=7~aSb}jV(4Ek^!09x_mVBPbix(Ol_M29@>{ipy*ZSEL77zcz9V)g zd-t7xETH=9R*zbASS5mLTs11?5Z1^J-P)jB^8v0FYKL3(4Ik%EBNgv?(rB2jFlNH% zuDzU7DIR>%nA3Nw#L?oh_a>pbO z@tZ@Xn8QEY=~PvA$K}0He~h&zox!_vu@=g3#OB`H`rJA+IO%Slpmk8XgbMoE;1e*t z#IyI}L30LBCiWL~!kr;9Ow6s}?6Gp&RJwu{0|I=)Npk!MKR*cYmn%y#Ggdqw;`V%~ zdlrWnA%9}UV~Y%JhJNC_A<^-JHhPc*P4kKMNH4dSCECkM9-n%sSTt(YUQj|AR?k7vLTs?5T=aCPR?@3;BN*f!L_`C)?sc@X#~`X!|s zCyo|xtc>ou%66U|Oxl`|no*Rp*4{U=^7>)OHdls?Wi{GJDSu9q8&H7-<>k7cV=yNd z%YR$^fyhHSSiKP=h8d3Iu=mfe!nIa9QWJ7m8^Ob<@fl(?+%K#%9-Kr(N5e#VOR!az zm#s7S*VGNxrSq*D7IXV7gS`9RizQ#+$$IlH&!a(V@xJyoFJ`}?s%(MxhY<&7xI09q zV9xa3+4OCT;y*|Tx?A#v&$*xT^g$HbjeV+mE&c-wajClOF@F;S3jK>(-$d~wFYHIL z$mu6K+dQrj8KOcThDp+oHnxEZB~}!_?sJagzunO$a=!|+&4`g4MlAEP_dAx8qLurb zPYe`oq+5Ghd=vL8?_CY`&`ql- z-S>_-o?Ontvi6=!YKspra@)P{=xm~9+k99>1-WEoOo%HW0e3N(_#1$j?o@nubh0*v z!gSBtwd9@KzPXVbK}W`ASP{%zFj%4i#qdZS#9Wot;f+Q*L{XPy2m@idH;hZ@sMhej z(MlN=a!gi&c2RG8t@U8)b^BOOgLJla&{?|orge{nUWRg6g+TAirNdT}qT{*Eav7b4 zVWj8+rDHq6hx~Gpm00lnb%VVcOZ2u*0;~)0*j}=T zsRKei9T2&<_@I6ofCmM=8$$Ohj35><_QvwG#qV~(GmRZOGrF59;ujR9)SSwdG&(9t zii>WPMN8$x)pFla9*tcAR{j1Wykmjb3%X{|I-=a=4En*NR{%cdMhY6fcdpobIq!TV zhbq;U_o0h;RU$r&x{Y%k#u~Aqd{+y4IUeK&LcpNr{~{3-r){vsq%lJQ&Fr2~)wcN$K_Yb#J^J$Ua`s zbwXmU@pKN1*0q&X|8>9>{723vE;k9+&u%MQ$U8m%0d4?qf9l8kIKA-ez4r38+Hzz0 zgRaI-a39=#ZFw=)7hh*(udGQ=mdwh9z8rjPLD#f4TD~!wBuLXOV9}Z;d*EX|61TEH zBlhT2P(zVBnn7d&CYG z!_W(I*A7>KM?=rmOKnS|?CZtaZ%fa`jZs*;ynZ(?3{zzG=#$s-m3z<)v1Rybt-qXb zf{T6W)_SG`obMZZ0;bMZ#;-KDbET%8Fs2(ig!ednC79#mU?KfXn|8m!5_s7sXFF%B zuL^y6|M_Y6^Jus0`OOz4Ouz+R&;NYYkD`Tk@dKkpT9D_`YnFO1_=hQ9$<(XDlu?Ie zP(i(gn=EUrop8f(wqvU{hpy=(li${00{h08P^PO={zo|`69gD7)EaJNr!Rz05|N#; z8Yo|#D84p}7dll3RS{K?xYWXX>UK3s%( z0u8VunI@U|_0b$sIxVAP`Ws8nn_&A9P6I+a?XeA*D0fjg_AIXXTtLC zkuZj$UyvLu&Q_@Ev4-vwzcnH8)>#IYSzQU7wzOgYGO{soWhJBflZ-`_&(^P$O}!#F zJ8AmiUC&&ih)K+9*HAWhM&Z+-gx3CFm@HMkw}D2ey>lK2)iiYn@jg)RdOcl6=UC<1 z>)58Bvvle%qzhROs>wme71as%vdSBt<9-J-e+D5&l<)Z$RTl$6$!}r5Y(%BdD6gFL z#x9a7F70{a?k%^~#~4u|nHJHalySErIXJzWQ*`_Zo!{53bnXj^pEq(NJ45wFvuq}m z2i45gV;wosX_-@(4H;;e{Pb4mTI`3 zVpR72XypAlqD1fV#r$_{e)|G6=f!+TVO+%bAP>iAhp%gwTbSB9spXjk_IYTxETni+ zFD<=S_Bz4D{aIk7_}jw^WYX52qq?^rQ&VSlbIZ z@9gbPuMJqnp6*EM!U(>C_SsNP1F_ZR2E0LW^u=%%in}cP@AOTWTJcWyy7c?!z|Dz8 z8Z0%7_-^k$Oa!rSmyGDXeL5NCBaZ0FgHE5Xv_o`V6zHTqRlaC3D%lP?wwWz$CQy9fywCubwWqFtbx+X?xhKX(#- z;15OD(CDirTd&9(rI7EN=;ag}jaLJYe1=uzV<&@I;)+WO9tmEJ5`M%!6d(vZL?uj83sil^IH*;uc7`x(JKWnr!0ho;*W&Im zvl#cIl^#v|#&AkIi)_qgbxA&@XdByG1TH5o;&!f5MbzKf{69#9iM{=^%NpW&T zPAH!?@b0qhS#Gvot38WlnxY2@C5}GlW=#a6<;%2=OZ0||H}o^!Z85Iy5ZCuYSIF^O zLFHVaz|X|hDupEU(xrcarU&Sjp4PH z^Wt8Deb)F@-GrzpkYNNDiniZKWJu%F*}ozM#9bPyW6DlSvB$Il)MX=f#zmvFa>^S! z33le>DyWHcJ0=!jpQD^5)F zuxJV|yUfu0b=@f;RHH_E@nwSvxSAUaeuiso#Um-H*@#2YMu*Gso1w1_^oA3MV>USb zyqiorgO#Npr5BB)_(}%h{e@Z?$R7HM-vICz=XOzQ{*z_#cs>*D5+flLJm63gmudZz zM{jE~r>)!cosWOYf;|jiwupCyfnM^VSxBUrIqN-VY@L;D)x#6rYx9~SwB^i{y|fiN z_iak0KkI8G&UJb&cHh<@DTVoV*^^$2#qHtcYXg=yDTI%G^E)vJu6B$MzkI<&%0DVf zQpR7LF%TG+p(J5&Cz&4>;Bx)3`zPz)dCdgJ7-wY6g9XXi zh6aM7SRHB*A5A;yU^SpL1YwN_RfijBD4c*;I=`U9U}Gknenx7k@22+s;N@&O@Bwk^*|@ipGjs!) zfLeU#f<&rPw30>ZtwITX7QA_avGwa6<$;`~*l@T-4qOf7ER+QX&f4Hw za`#&~gjCE?-|2gc$*n7|o&ZGLPR>`-xc898i{qIKOOF~n63wHDi^L7XxB$$Y1RN69 zZKX*q3ERmn((Ta9gW4ZyHQ>g^npNLwO;QQJQmY(o$@Fr}@3@{yG48jc0K;pU?>V9t z!}ZPIo{2j+zoX_xl(f*5)FjUwXGa@Pg!syGWbazy18JX+ zy^Cdw@QfB2Tu+eAMX6uA5W+&JP1i6e1vr%hmwT5#;PWwM@ml&)BmJfx zd>#8cVXs@Py_1*>WG-=J7|X7!c>{9%UhI=YFv>B^^=X$}hs*tG-h=Gl#Waf7M-7SM z56eeZ{QBBFHe3!8D$=XUA;vj>uV$WE4%4}w%!6`?w4!EsqRi5OGx@5aD?w8Eu?Ldv zG!=QRXpfoq=_&87rfI>j1M+3I2gT~0`MqANvMX}@HWBhvHaX*LD zKUKKspsXw4$xYN!7@p}W_t#OejBpQJQS@`LO^ULsK2~$(cXcsBAxr{}3(LLx*C*JC z;#0UMk1AA-a1-)L8QZ!W`zyM!km2kgkP#q3AM(wzdVeI`lF>%1{@|%f>WFq1d_ZhV z%5jYyR`KSNUekVtX$s=k4bvFJ+Vt#cXR1@)*5%t7jmG|huC7U@NL}j(i#5O)r`x%J z=gFqk(29G2huQ7$N4c4iLqp9m8xC>$S@%Ys1xk11TKVs!=4U3vx%%zgBN}V#@(Cvv zE1of`MJnh+s7;LusOd7UhUr$qxgB<86kxBE+-matIB9*!K;f3|t1Y85DG7i^8zb7E z^@Nv>nfMl!Px3G@#E7fBw8sc&YWiVURKX^Q;(yBU0qC)7Iey`q4M|^ zBu`i4ul^Kwq))t4vwWpRwnyuLxQ{vP^!=#vUo`Y=-^Qt1;}Rytb;bCLZm77XO+;pj zL=(Tu%UstndA`%995|Q2>kVz?8}o_d?^y~*Gm7Q9?FFhtI@z%0U5i?E8!#!%D$K+f zpQdP7&y;$$6G0d1q%}B$&K&j=+X!Q91Aq=~DT_Pzc2ix`jkO_OY`M#^&W4R$MIH6% zJQ!#K`eH+Bs>~@RAUUxcGeMkPO73$1q(xG>-ph3ScapLBH1O7o<*lhfKuNyy6uEZ) zWHat^ORX36H9hCkfz4kNo6kdlEU6fN9%I1J$<~(}HQslVvi_@K+5*EVO?47H%TmQI zGRHJnnWQ`7UWhY3d3kW^BCUk0xkXWl!zYmd}iqmMTFjc{j?tJfaM zsR~QD+M8Kt`J{$Q_l@H5$3hmLHl!B2avGnDlzgFh)+Fd8NS?F-IJ4$x&bNJS zIdI5!y{-K!?RU6LTUZz9jN3lXh9FwTsr!z8^A}7_%T|b+&`2$C7H2KYQm}sg6(~-t z+SSCaY8arD*%7EqbQE zdurC}k@Lqr+dMtP=~(`|LUKB{!KC>RRzdyf<2g8(*FzpLHJ({%U;$1)seX^;!|9c@&B0c!JHWW%tm36T@R-oR&1FJ?tc!KROVsd-(P~_1? zYF7SnbUlRaSD)!pwJr{7&>GWn3*_f?1CsC+u1bl<&H9k@ z9*cO(^@zGrtEb4*t7cv^FZoI0^a{|-;K4P5tn$@K(VC=H!nKBZ<;=f|x85tIJ{&_F zVx zooY2@24}BXi^b-**Yr8=^vQ%2TsHD+SC@T*6fXZrOf2(0WZ2daC4F>wXYchcE@R7? zr%~=EuvNTskc>H7sa_Y(t+Cw@Pwzj0B;(6L996?Jbg9?n%V!5}Uy;ytT?@><>XF)! zg7TRx><>tZ4_$3VaIY?<*tZ8Y4o;AW8F690RS$j{dYMeAyp1`FjUgoq)>`jUv0}#> zg&^>fELd>`XgWOR5ALVp6Yb}dB7>Xuw`MfqvH3%S?C4~>6Wxrjl>1#Ap`DxXUrn4^2cE4>-E$n%q{n~+y=6c}j$2IK<>vJD-`>p%u2(be1;HG&Zmq1vE6Ojfyn zZR-ZgxjFao#SAKDZo8pQU_ar$qC_imCsvJj_2JDtDh15&Ut|k%LN!nJz+-NO@}hSMMrn20cR4;!Oq%OLP%u-@28} zZOY>u*x0*RbZ17%OpWjKai6XpkdztJ4eW#U=ABvWKM43{heN1dd1TL70Cb707;&0~ z7$mWRSAK4XodSw!27ll{zjpj_{0+CIFSq3fMi!R$w|EOXJpq*OD}A=nJSUxtbqUyF zubgkViQX%>50E)llNCDVQ+j?s?dt&v)J8=6*D~&y;>a6C<{vy9X&j2yu35ZXhrc)L z9`ui2{Yqc1bH>J0FQl#hUZ?-c)siOws>ufQTn9q^U;9?uVQtbr zb)}EPo!%~S{?y+)EJuy8Q{iQE39=GMK2Q@{6PcHuRbKLRUIHkjs<>A;F;>xuPN)1C z&x3>(sAD6f#*Dk82*>}(wrGwi7Ad72d-+GUwT0FAk!^L;E$O@!)m+jGl_+z~uq7W_ zkYAy(tL}NMx?-y^oE6gK$C)5+SDg~g8=~4FlrWbb(xe2xQB!D$4>3&$*?6M50-YC0 zAx)#HCp5<*Ge6}AE0{m^e4Y?8agI|eRMky5VNOM1xF)12j&I)Nz3NJqK?XD@SQa)c z!e57}x=AO@87pua7|y7=OUJ0*bHG{2hj*0e^S-{CfUB!l8w)J^R-iF3*c=+e2WzrX z7?$8n=u}mpq;!8PMo~U%DBiFd9}>oCW;x@Qs>;$6d_lxn!Mq@($(J)hrflCg=2OGA z6lumgW zq*v#gfj~^fVyI@P zl?ZELl=p~-#OqQIyvL|+Zw-g}${GSrl4c|(QdX-gD37~}HwZkTI_*yrJy z24H|MjR(?}c9u@!&JM{D`?J~ucYmV57+9p|kqw-kGAp*aH&@G(qZs#uxG_o0_{O&j zjUe*S;gK;91mdx5Ox@OwIKw|SYOq+uqfzc3+FZMMzJzzz@kK6H7od@kX{AE~;aDWW zRR>iIgJWh=>isc5= zbd-)#_Nb+GCLYImpdpc$usGlBOQ}B~A1Wk%a-4 z*P@n>t!ya8K zDlfD0vBn~^y*?B6)^{zd$u_lbqVV~QXJCr~hdogL)y(#aaqG)vigU|QK$p4q^agf{ z&5x%Ew7_Gk@>$0|2?+et&&bCu5hl4&p@K%pZ>^LJ({nvFoovwBy|c695W{&U8QCCb zt*dvB$OR0cP@<9a&-0&X{zK*@Q8lr zuI@)x|1OlpoLzM3G~c|doC2pto4-|1h-#Y0>T*cadcvF;<#SG%PZVALMU3ly)eRx! zT%{RMl=L(D>d{V(_Apj3PyaI8bWD7Okz_zQw8^mJoXT{e7pGNWuVBe!Sx8g$Z#!?% zD{_|Fi5@HFvRRwDmp%S_8`MqK2l&8r;@iu}QS|$VwknIiZJ@ZKcf}_v7f4yNA>TOE zX;*tZ2L?75@Gq#B(3^3m=c+nEl6~39>-GUBhLd>pN4RnK?ok6x?HKPq{0ngB;4#Gd zym!j!Qvz}{%ZF6e6d^gC09u$)7p?*V_ZKe*oNaK(x|pOg-N!~=UAUwl$qzn>wK{4q zE}iFy`jl1^$GYkvW?v_y*__)irm_bUJvIZgCzk>ue9x<^I0Lu;mfo<0eSGB`hm5u> zBd83$fy)(>qLe7=J7r&fV+y!#opx~@XsDw|p<%Ok&V3~LIhST2Z)Q?ws&`+K2>!Tr z)>}ID?gRF{W-_bovSJr_UmBYnB&iJLLC|}wDyxh%rOf1D*S(_cxDkcm#@!+8+$5-O zdccjLIl`N8pBWP9Vwu>~pdEzh-MLIulH4M48-fY@Qd{LJ#wDu1pF*$p1lKaf^e-^6 zH<0m>{vva!X7)Ea*O^l(lzVnD%U2A~9G|f?;F9T}oewL}N)}=H)wAsaNe*>I$8|r+ zwtyfImLaSsIc!ZC9#Vq%|%wvV2}) zc)+hxPzK56PdAQHoRm4#Zhbm*2{9gm-HQ6yf9@(#XEOhJ^Ut6 z+eOgMF*QNpsR~tx+h}@t9Rv;EtQXTg%&FErw$%roor6*$C2dpra-H?TP}3967|h0P zQ`nXp(J_V6Y)iSeb#HKKW$u9JTZ_?n)X$P=36y48?yuncO91b#I4e zRF!BW-~+fZR(2Kl!37e$>T4}aln@>a5Ta{b94f8VhUWfHXm(?y2SU`yto$ulHQJC0 z<@HZbOxE{Otwk@EJZ}s{YRGvVh8J@iq*wRV++~SN>OiA4lRpFNMYvA5*C23HLhaeW z){qckitMF%t8@1e{_jYY+pVJtsch%+8NG6D>^+zpvx6Xv?x4T~^z~Mmz0kTO8eRTe z&NHjYlHE{JIz(5!Kz(72>`l<*3%a|rR(`ozHRBz}n?&}kr+vy_6yEdgV6UD6O=?$b zJ7a3U+=KCPK2nUeeo%57No6_DycO}Du*Ud`4QDTf`rY3&P3vP;UA(Ln%n3(_nTm(- zoYy=|lLHc%c1dj(^#~+;kCjm76Dib@jQ=uuh%|S#7LL79iDc5cr692s;59qpHj9_b zwfR0;O}#AsqgC#6M$F}3S7C>mHt8ci_C>>^XdFC(7mFrk_fB$CPtwX6Dq7B)yd!FnR zyhQt2HB^^Xiz%0HW%;;lMC-tfy|cIFqscJ`hjf7ADvkLz1=%8|VCCKl5%-a22(`LitI;T{ODdEUWjEr7Id=CY_M0q%gdbGvR>6 zpu2^+;)a2r2SAQyo%lMIl>*fRw+AWr$n=(lB;IJWG&Veuu#fw&NT=I=suH_o!>o}> z$vQ@z4jD~_;ULuwAqDfV14Rjfw%u=pRLqLwLqt$HR=>mbMo7+E)_8gMlc2_TZ{4Hu z?rc>WR(@a7XwQZAw2~sr5@jes)cG197}+=Lq|Z0;m%G7;Zv1XU6vCflZH^k@ zWLpp6fd~XY)j&70S?$M2ADAphoS;gNy!1>^%|cqNAdCi3^?9 zEG-)|h5XS@BDKf{Ap}S6Xw;;KSq>YA2@y~%`;>El*x<3;`FHGrmZ?gRKA0TBXQF({ zp^~$&LjdY*W&qtibUp9B8OXvx^FkWWX{^l=Kcsw?w2!~MwJ!OvZUpP* zHvQfQx{>}QFAM2E?5E=Y()s11?ld5-;EFRleHKS;%rrRt-^*BEG8AKVsiiZYy?xcU z9~2DJc--3hSi*A4g;d%GgNuUoZKc0rHm)Tb_TI>$Gz*)VycARp>5B)1O=5aZ)MYMw zvG}9--`hPrk3Jwi5eTqO%7$z|Rws5&TkH=!oLVL{4$%KG88TVD9YUKX0~4ezne>8Q zvyr{~0;=6z(@Hv$m9SGX#-qQWooCm0ipR2jExx>Xy~kqogiEb%kLtVL_uhSw86VXJ z^g%XX3KW+`YU#k6UCcJvxDx0!kV(}M6G0tCSU=egAfJo$^qSlF%9gIuagz-Z&+fqE z00mtlz9Q$-yGG=E{-i0%tBD2PCa+?(QTzr0(8_MQGo%4flUgh%dd5Y49E2_cHbaNn zA!?P93KaRin(yk^sey1qgKP401JD*>Rl5*QSv9Xy79Ak^^^RS3TpP-VTYC(+T5#|i zQno)qM9M{5DxBLkY2c%tBW#kY(Nmye$J*bIwgloOe(9% zSwa_mdT6$K)^zbHWS+(epngT)<$S+T$kwP zNScHA^PUFGrY=qoa+x_TWJkyYa@J=PLh{dXdU7Sq8FD6^R8{Cz=G4Eu;;e11n88G~ z=D;+5FZ9-I40rj*!;{qt!)y)YoCz^|7IAg98H`=E-hGB4D{~7+J+1TIS5-GIaPJM< z>BEDY zfjP_uhs7FcUACO940SszXB))R-1i56(Uo+f=2Q{V7K8N2UK-XJzvG<`zZO`n5-AH> z|3Zns_BdBhvs+ys>O6I_GHfp_vkNeVy!fz}0OYt*@2U&dnzI*XOlXL(iq>#PI*zQp zxtF#q?Fo!xMoSb%rw2#}a@S{1FoKr(N}nc`tliY&%G5RW^R(5i#`!Ys){5FnGfv>e zl1}=>u{Rdf(`C30rG(l@=zEF9y48yfefav=(oEvpgVWiVTLCRb)IKj=X^^JG_0{BtqtMp^O^W`1>s!l5|YX+AGeLQx3ft5iMiDB zP66StQUA4cR1NOPu$^a?f^BL#6nm@2J(juCUdYm=ZnQ$yZB-z(aImp#G{HcD4)*VMOF?r$&gJbNaS2iJMNKhVOIiq7P~*0 zg(T3f0Z%ui66UT3=bv3=xxg6}sk(AbVK`K1B;YXOX04L>GBeu;<+7D7EN7ZCzmo#( zD36p7ZdD_x#O)S?LydiQ~3<##*R5G-PG%uKT4cmrT|2NeFGB#{_(!m5bQP6U%11B zFZvpmNxw;tA&F-zHg!U6_qljiXcuuCIg?=bVP|a|QpdmCW;y7nd=N=Evw;*v-1#Og zevQb~yHwR7gSHvZYcu6@Z?7d=2Av+fw0`HnI2ygl+Mam52-!*!PeI8^AC=zu3}@Pz zf|W1cc19CWlGozRo^gEAKl76KioQ(ck#PCRdh@ly({srlP=1ySTnm((ITxoKB%`5r zBQFn1gTSNvbCpkUP1{;S_X4x;n&C=Q_+w!utc@DuE(EYEuoCy;g3yd|ReyumLQeh)o2?Y#o_+H=^+kUO@!tawg<@aIi?Rw1X)@%l`dqWvestLF z02TAP=LLn~j-%tXi$^plHz3`p!?DhvU|lLxl`)Wz)2+ST#ywD8`lK&`HU?@tv7a|v zY!1+CJ?|I#l*vk5j_nC=BDtU*O}sXLyMkuC!?=#c3Y<5Mm4e3n?ecUoPiU$nZ<8Ii z{}g|~qUAU7>XgAsgoWZkQ60@z$|Yv){R|C$A#YO*kU9Zf+bcK;B;|1MXj8_idR<$J z7M4fx%$ETj-}Gp{E&&If_^3#7mKWQ!Jg1RfmWc6yP=SJW(@3b5f3nJ-!KEcV%H)Wy zzV~K&IlGgv^_R?k96$NHu1iwKxwCqh_$x*H!P~hB&=TX?Rzm? zwR|_!pth|706_2Dr!%ooySEYwF+)z8@RrUsU0TLZ-DJ58CnY4ji@13vp<%+;ZSav< zG;(w)HSKwKl&whFl1iDrr5q2m$YQo+Og$)4jAw5~pq_Qw zo#;s-(v#W^?LA7J4BW@6Yl?%+UJiuSUKAS$k=-c7KTbDgCV4jy+qsic@`bs+Z7jI0 zCZyEjyKu&nBgVt7Rvam5AZ_S;-*h2C%UL>f&s2ArIdAqg&85MM662SXtTRg&u4{y@ zgZ?nM5Y|>dOwFE(I@xq%GphWkz$i)(UL9`D9WC8M!(fSoyQ!0kQe)T_JX%B1g|?*H zy@UzshtPS%p>%TNbnaShj(-_BCR%W?j62CTz&`M%l+JbJ+}mSv#lyfytGk%R15wYU z*>C^0_qJwrw`4-DqJlXvrIrbaWkn&+Sx`PqN_yN0b1a+*OjTM!qAPAX3g*#rRZTd+ zEtAKWGYqbGYVo!44G{Iu{z6hod&~(zwb*LX1!d0lnFPG`xQh}_Qzb%qxR|dZxG{Ey zg_=?pYvb|TU74Ebcbh6(6L}45Ic%@_rKpAlG&U>XtoOM!YL~K-s@W9Ui7GBWe2Ln6 zpv(gqAV{*IVV29VJJ+R0RODrKmi%GPU-XgIn!;kohdT%cySo6MwnKs-GLqBy8`F)5 z19tBYosMB)r<#S%64!;-EF1h1UvAN4Q+o96YzHtY$)%jy@Ob*ANsGGXfzTnO3t<8H z57TR*^$?T9S0PkIMM0C+=@`ea@|Wx;mrpk!Wv4Kij=hz)1|+G!dBD^L6F7hKwGr1s z7Cg|fnCUUVo#R~6e}HDi85)!5FIu#i4V#kqsuKhCMPh}x)}d}7QgcWn&??`tf9=iC z1n7QwV+JOr3#xCo>sOI(wy}DN$q#JrL^MbPj3%mHTBaQi@KrvCU26uK zR+xr+T-IO3d03SLoMz&5J`p_z_U9}8hWK7H-GQ0Asccxunk(L4T7H%7&JxrRYcI;I z&y7LK!c10pKepjF&Hibq(_40YgN{(zNq8a|q*3$<+UZ9RIu_qouTg- zT{Tkezws8QUXkzJC;qSrSr8olc|++hDY+)yGFs8M=00HLDVEXRVOLQRi$?Rk{Ps{A zogCnty7IbL!^Dw`HGj@EO`WDnQX_9hiJ^GoR)dYqraM=6B4%xlvpRQ&x)IOUlmeIx) zuCZzwiNmbKoLz;p%BgvGpe?Htq8QWwZ8oI9*N8Oqe#K`i$~d4+RP-y@ZRoxWqO(zqz3Yj&|2yoKi>p2n5*VE6Q&>H{jf{bH@;Utye;T?rm zXIFK`JK{o!U+=vcuwUv%(#Qh_T=;O)-QygaQG^z?E2Kw0Ly^p2M9`>^*C)Qg zA;!f^X|i*G3=-6-j|ZyH%lH^wJ)0>`yegEv*~?=RsxGJDc|A9MngM@JI%=?nalKy3 z$xTwt3y*QZTZnato&%ckF8Q0GyO_ed(&|>XvQ`}n6Pfj4WoR#zR<0r|MGjA=&peZY zb6RJd0H>N|JvEOShvJ&~N;_u_*tlL6(-4Qo^?-(MoW2G5@!ZD7k+|j7s*%J2Vvcpl z$^9giK&Rh;uC^3Mj(ic|UVYuZN~q?H1CH2VWJafFQz;uQS6&+kdCN@WNPb-n_v9pS z4Tk8HjNB%LybhN2yDYN3kgaiPUgRynLu13GDhTuZbKRmE$-GR$?xoNaV+IwRz#63_ z52=qpbU-6&l4o7V!`|{&WZcFB74t}m&b%B5cV(G%hkQ_A5hWH!B|%ov2UkOI7Xnv|gd28jR*4EP+s# zbe^HS%F(4w3ddfDT$fyXfAwILg&jFh_gxM<6{*laV%_ombXrj)o_HX{yHAdunEGkM zo^h95Amlu}1(RwoomyO1tP?iQ8rDR5_hsK{Lu{t;I6>>|^mLQEx<|%$CnKAU9K|oi zLzi6z-a*F4sJ>tr+n|1)s-2979H*n_i=|;4vNBo^r$uI}4iMY4< zNS#d=teM;@U{wlcuX|dEThjLH7F21@&uKvDcPOl!huT3IRUsTd%U)W`ftD~c>RWdcQyTDCrGU{~tH484{Sig6SCU3wcT)2rz*$S}X( zGEMMizO2o`gyx~4jn&D9J<>~kn{9Vu@>vRwY1bKt#-Wqdt=Xs%GJeT8`XIS zD(5pj$1QG8gu{8`V}2}Bj1AC+*S}f=U_lDRH6i`Ow-FzAf%#GYh zFdL8$)>ml$H8Pp@qZDpOV~`cpu2HwbrJduF+@JjB9Sje9##=#^46 z0m%2nCP%Oo8G(5hfVZ`NtHqouNgP(jUl%mLrpOzJuhWoVc^~4w*W|6#!9nU{J%wTY z>qos_aF>O%IDWcx8ej0RR(KG}q4%B#??s>{%!u}MaKrl{NuCu=2zGfn|PUK)6)Fra;BtN@9Yb| z5|BYi)Bwg~mys&^Qww0WOi{I!`sNaBjQyq>XK2*^<^uow1Tc0Ua#iIpXKal-_-WdA z29V%Y4p#?6{$4ELm|R*g0(kf|S3v6S-)z+=Wb*c$BB3tBy;I;*v4Pr=Up+}%uRu8g65pHDarflnjGcgO zI6itd9yCkFhrwG#3iJ41aWNYePq>d)1IoMVuYsB&t|mbE(s>0;i+$*i!hn7^x*yOU zJ%vwa5{rgJtKJ%(&$O|r`z6A6wz5qh5lwC^Z7)wL}niD5}PXUqbTPYF@z~+5Q zK)Gl?WjZb9lU#fWI>n)y(jdeZn-MXooQ@rNx9XCuErB`rAbgMZ5NDp$$a$LNRW^r3 z=Hk>&xL5wcUccU8vw-sb#m2{#?6WVqHbXyIKN`cNxKut$n-%0p!J2PR@Aqt|@yv$h zCv?tLBr(~6p2(&}rN3Ha)Z~+*u^@+)Ac-rHJRcjj2&7Ap#$Wa2_qWwm zQ4@KaYkCI@lr-fUM4D0AMuULy_9lVSW5xoY(D?HdMDro#{Ehb%r zJJfOMY-r0t%ST-iJOs0{Q&#!Q^*z_}bC|3lr0UkQ=30^bYErfzOSlJ5k;HrMPtJWF zda1~*x4lpuC;%GDFRw*8qU1CVbR644JXhSR9pclAzLBOmRXX2ajMa8!@`zL^Ackf= z&iUo7P|5+5{JP<^3Pu8kKP@@Ck;k@IPsz}q-AF0!xI?Z9l!AUopd>ZM4P25gnD#2& zv`$}8VL|MJ3b6~L^I{m?P_pp;mZ2TUVen8u(Piv z^H-n#g!i6+&dAqnyc*n?`HO}N>eN|5MHMU7)(IF;_cFx+UF6-?SCX(0Yanr;8@@<| z22^S)eGJ*(`uf_)%UdXZIcs|a&9Abiijr@Nhe*}y;|Z&%fGk2JmjIl zp}cLGW1pL18h>N>y`%9Z`(m@Jr72y;RECeZ^7kz40u2_ab&%}T|}mS z=DlQHR}VR0kYvf{VePiy$ZzQ}ylxznDo{wmQ5KoQVhnr5$aLWAb{owN8@cW&UjDKyDIR5MoCSQMJ zPpiqUkfuxRR%mY;r$KKk_ojdGK;$co$?1)bI0k9n9{Ii7mi?_+t*`}Jx~4^Teha!2 zl9!ClI;OTadcAm&qE#EUl8_GNlKOK&HTvi9a$~P#F+72E->}}1m&V@rUI4!a_&i{O z^#vx0E_AHNG@V4=4M{K7!|2%SS)r$VNiVW0*n=Zwv6I)vT^6ub^;6e88=NV4)Y$W{{}&0zt$WH77Yqgx80R_Qv6aK2nr049L+pbQ zc_r1BL}~B*LO$c>aH%JbfOKN112gcQhQLeV)p`@?1Z+wOK{%k~J_Vn}9O{aS*@))f zL*x-KJY>H6d}kq|%vgSyw2Y9M5UOfvsxYg@IayF%g&=0 z@1tv?Ud_KdvrzQ-`#LA{|5)B|sqc{DD$Jfcm+7y~{KuC5v8zpTi66!F$#x(zwuIV665y9DeFlHA|Y_gJ+OBOyaFKv5S%1se>BCf(N;UOPA zKWYvryr}QYrkbGql5XMqnG&_S#?_Nc1lNS5u^dkB;9TU3%ACyVie4m=UI#NCpQ0+j zm7rM-tKG@|^Lu?N%8omhuHo0E*T+g6Dq*eT?!UwvkQ?jktO~Jn{R9uXTp6Q5sfm(SPkx zx*Atz79ly^_j@HA|CUH-Uar;IkKsNwnm>5rSr-VhlKU@kPIboJ>?&vt)PaqCxJ{H&B<+xT|O zwy`;Qxus_~3ENO{!gmTN>z@bSh6THn0-C-+XcJKQ&T4vLSHuN=0x~0IJ^`(N?rsK8 z@CNw`I`p5*f!nKBAod1wkH(dGeQTETkd+EeaxgN|;#B!U>(Rn2^q?Ue0?d{cG|TEG znt_E#Z($d>M?P?KuFcXw56r>jPfyjbLJNOXnb{FJPh@J{+yD~hqgDlNF^&CtqexSZ z8!XiaT-@*C=KgU||2(t-J|JV>822+2{`c?P3@jUoSP!}=9RO5OkkTYpJ38l6Gk7ah zMUY}xZHuyn6-ITy;AMz~1;S|69&g-nf^gDSwiMPpCD#x(u0~Z0{r4lh@LaiuDIe0+pJc70z}7G@2tgxzkrRmk z-4C|R&O5<02EO!u2pYI`-4L4$9nfTd7ECCN1Dc3fwMI~}G|hLoWP=NrHIY!elVWXR zG|q>J&w0~WQX}9ULuj3OlR;)?gt}SzeN$A>cw!Cy>;Hu%%pk>j)FY_ZWBzS*$^o%g z{~1W6zMK!|VcJBd(IKCmU%x$NAEpF@dK1ZUl3`AS?D}32P={Zl zI>24k`MUzo#)_#uhDp%4kv-t=pUHZ&^4`_G3LvdF8}jkJ?n z-R?ZZyI$$$_{V~pv?u8#$VNdO8uXOM@hpRBzDU(XzWE#QL;TblZ>^R0zASyis?<}v z3S?r208N_L`Ex-l!R$=KOhZs_D(zE>vFMpfRmK7@;XOf2$bWVvZezZOkeJ)BusUyS z(HbBAk4SGOsY}dq=Z*~i1}m1SWBzs|+`HhEw#)icEoT%*uJ45it8t+E{LsGuW@0fy z_qT{X3FWMuJl}eWnGTv zzar!B_{bc-d=ha!SaPB&-gNO_k%T1BbGI%E-Fk`tHt@umx}QLM;Sm(KCS~-W@VOuI z5u-i!r-^Xp7p$WsC~UFys8Gl%nt(K-tGjX>(n$@m95QsDc8KpCIajytA7yp+e}CMk zjhPXCpfxADL4K(zda;-o{pc>RT~lkl^%GP^$xrlhNYEg?zI!Z`_l~gQ*%0=_KFC`F z67zCG0Nn_pj`t(ofNp)(^ahI~eg6CJ2@b0A)``aRMG==DB9Z@&10Za$OXD-HM1B0B zg|RL71s=8Y|4O2oG@Xfque-jR6^^>y?j3x8xr(KjEvks= z;u{1_IOt@lW@d_kIn2vtUT29cx;`l6 z&$BbzMw#%}|4^701QFDalWd@;*-YKv>ju+9P$PX&`D9_8;;_)!VqfP%jQYwkx;^2# z#Jr8cA5-pR~bUR zOj-(rXZPXs>eA~={poVxpcNc0j~3bFk`!5wri$M#+q54hF|3%`J^BI49EBDKO^TVic@{(LsSYQNvVHB1z5 zHQS`(Rq9GVm=0t9cdqd|1KF23e+FI=A$7?sQ4QUXf~Pj<3r>8!=|=P6mX{$FIIjne*z0GbpdLY{KM<&S@ALAt}k*gw?*@0iz`cD<9!$d z3S^g$;62&eCApYMFj*pf49r;CzOUu?KIokp0kf<1paj?1qEb5`BB%SD5+ok~eBhN1 z|C4VN#U3pF8dvC>rjOOWox~2a{h3Yw{%Z%k2bnc@LY;rlA}=(Y@?QmMxThYz8{>vT z;HkV68*gF>o!jD%htd<2dSN7OqLmS0bdT>}3Jebd1`=Pv#QzN*1qHxe%vMy?5`3h|%W0(OP4 z;PWy9S~-StnOFSD>EE)uy%TlJKhoWy#UKW*pUZx#6erZb8R(v6H4e;#k{dL@{;fyF zaZT{H{RE90^Ti~+y_L~Hj8(>(Mk7B6YDi6pa8*O;r##z#hl*b(spMBUx!K+BK9a#~ z{GV_#6%E44aYT~jd3lyIjM>BfH!A#io%E#)uo$&0Ary_xH7`SINHX)oLv4qYQuf*M`Y2ptk$HHKn|$iidv%5#7OTB5HgE zI?ebES8q7eDq6p980@;Ner8Cmp8HOeS?z7 zndq8l+HwEY9%z;2H&VVhz@=eJ^V!>;p!0%Fr5}vL@F|7f62rjpI&JJ$zHwgsC$Rbh zib*{nw)NmzRuZrd6Ivdk!Tb03KoHdzBhFyIM?uK&vFGXhOfD2K5K_ytb8y}$+TtgZu!;U=k}J@H_bGw)%>Fw zoj=2gq?c6&+o_(PjJ}42b!G5u`g0B_8U#<)_7iL<{jEU24G+CM@#6|O*Mlj2xt29Y zg$a3-%B#IK-%(I}>*cCdh|rHs9QTs+IOV?P2o9X=uX+5mRFVw6SpuTRaD;?CD#&QT zH1@AY@%I-@jJVXY*Pnkf{QplaSXl8yE}!9Ux?&b1StV;ogFe@U{0pxbd9>%j*=7m% zLt~}+!0TCGmmGivg#zuT18=~0o%Hdyrz*wC?kx2eJU2e70QyU@x*5R5m{T@1dRtv= z?Y?om0sp<`kz#lbI!`vGpucjSe4;+_*yr-e*sbW%9oo>@e2NdUn#VcLc4{Pst6lK` zp||$hDkl#~+P7`|7|tWe_?l*I4ouW~vc_v?P(vWRx=CvMYZ zG{kPvBUr<)KFmPtQ%}tV@eGWFSd{_dN;lW-85@A@%l+wWrH;$+!%5(Vzk)HD=nD4) z>%~{ygVz0x5fY7|G0SNY9Kxjce$oSPgloEDmRstPXRw7eaXe?j}-yY?%|zk z?KT+M?=42n|w_GFx$5()BYMxFi1~q-+fbO<^bFphdPAz<`WlCBq!GJYqk!Sc+*t#lwDIF!E)9s%4G*S3 z;2UWC1O#0r?18|s`Q%>P9-uI_sSiw9?@6(&109ySWfPLBEAFQ9PQ;GL(ftAFB@nNq zf}uD#(c3rx|<&XgpA0WeEDz;&P zN0u5kNi55m!6pNgH~y0#*A=SW7^ejruvTY%#|aT+5}z`>Egk179qZT(sKBG(Mdn)# zKeoJ8=XY+)Hvp}#7h^d6inbCJ{b>8{AKP&Tk}vq=Ri6IFADe;X&6y0gtitlyFAhWC zJU?$X*zM0Z+~~A|Cq+VP*pEKmdy_BvWHh?vPDLTHVL#U3T{?OSptFzPE*wydcEs>8 zv%CX>ngecyzV5uxf zO}cva1GgWbyL*Ka!2Gac&?A7HQfvVine$*eKX@Nla@GUZs$KWgy!{;37X*0twJ)GV-=0oH~s&IGsw zM4xT^E-I&8ROZg#!S1iuDB>8NtL5BQeC*5qI}Sy&!h)@$#RFIDE6>(LA|Qai!u3j7 zN69O%ecvMj#SL4W)DPw2>E)M~C8;wW>rqY$e>{yuTVk@@^2wG1OEq9S z7$;!t^2&%#@3VpuELhY>kXmbWGfgiJF#x|?xTh+OjqMV3Try^1+PJ0%GOhqCKqo!r zqpb`Wgj0XolO%8!H4iUbSEI&dY>a=g4ss+=M z5yRa~t86yW&^-TcuL5C*(xbX&a0u=PdYUNm`!VQ7{7D1ZRvOd(0p;0k@uL9M-*Q8* zW8eMf-goF$=Sh0R$RmA&dk9f{%m!EOhmd=7uca~;ZbCiwhK$0#jcI@^_B!MdSBYkx_aRQNVGtCsQ+t?+VR(S%+V68Rcg`1>83b)LrM|CCX%dYs3t#LJf{*3CWs^$AB?0s&)Sbm=!an(<^#5 zp1;5Dl9=qcP}5MQNHaFc&vPl?-Jlv^;xV$6EUEw9DiPi&)u<<47U;*H1m z3N1NqitU^ES?h{zHZzZ-*HO(7b|^WKS$N6kNP?O~cO30{atcZ!(og5L4ReC|oX0jf zT0a&XUTZzi+xssdE2jY9yPTF|yOS5p?7MI$52k}M&&I_5Bz;y``Q)@HK|!NHSZCMT zDGryu@u{%E=G=8Kn>W8f-#x0Y1G6kjXx~2yDt1}?!Aol|`01M#WBh|HwoIljsuKQs zE*J3|Y5a5ivIL;@E-0L%Q-L!T{u$Bp0qAP5D(|gaVJSpl7lu$>xTY%aceCj!bPW(@ ztiU<>We#XVn!&RbtBNPU{;dzZa2;*zg<@t6&qO$VYkrN7L0Ru4w1@|E<2n-g)SF!P zigD5|0l`ws1DOT8gGq8h!M#~}Rh96IBetW3*8G7s;Onc6$16nQuDgn_NRxDTlrNBd za)QhBeNkbHZNkA{A)b*6x7{eW5Q@uZbRkT(;5MDBql3(0V&~bd;>DikVeDtIj>~E} z01dGoq#2#><1RyKNVf?Vi~b4;25TbhECyx}AhNvAeeWSuq$q zMiC$WP1kwu!bS}dLx70GJTyOVy3U^z`5+USlO*UiUg`)c4!3Dy&IG2rUBMd$-yr%N z>V>zQwM(CyPr0=xNJ_F?srR>A0gWUwItI?n*5l?`pctSOz9M+0e)9%59qAKT{Mv@J zN#mA2d#ix`pmj5hty$o4E{bHCYGG7LR`dHJ` z$V`DA=5X87>HO2>r&RtZTrE&df%k0xkj{7U4|X=OkJxN^y)jyI5{bNyN6foVE#u|b_5e%Cl1LCrJc`)l9{S0(hon}RP<(bQuN>K@O$ zHlp!ylOD%4*!K|-%?cOCuVw;20Z@y9Km9<0-V&EE`|30uSDkCpmcRR?6+NXm@OV+G z$YxS^_LfO2wGsje%7sXZ?2kcjy1c0p5yHa!{IaYLuP@!@(A`@d*P=apxVsWZMP|Q} zM3+3d!m&zS;Bsv>iFfZ`v8mw>h)oS@M(s9?luok4WPC@D!HR(_>=*DyfN>Q`hyCxgEG30M;--zg7TIkFf@q6aGv6sN3~y!UCT!*MN(8N{6~Tt$&$CvUQapN<+5%=@ z5h>&4;BTm%F}(tOKTOgkCpgdHgDK+o1259lv$+A*oG)9a6|#bXZjQ>0P*83MbiTXA zmdz+kzG)W*Jb9&QgSzhm9X9#of!!8xw<2QQ@)0Igf@!nQdecfy?6KN{aAL8N4iHXk zR!aHzT>!LJi4htag}kYv@p*c?|7@vHDS zzXyy>L{@!G4*t#`fY&5JfG;9Rmxzg*VdRw_hVmUfDqYSDoee(KAsa)q%~&k@R7}_H zgYUc_?P=oHW?yV*`+MyJSn#aHue6=defawfg^T01`uI(2Ogz}?R`_F8ttd}ZG7U-7|(DA9Q5n-V?hM)GX(R3iu)=FY~q*MVEkgB@sI>+ zgd~$T4Ds?SXcfrE&;W5uVj!)|1?^+oWS+i(=_Ca3078KYZUA|Go$}ipU-ASu%j9@ z8)tLUJDcHLIZ~=`GeC|`xi{%ib;cWL=XtvCJ|u#jNz$#xch&}>Fx)H?RWl84cA*6K zaC{sB!eF@qi~jSNT7-|U;G=Dvz?CC?6On*bMS&7H2q%V6%|P;P`15@OHl>RBC63Dj zEL#^Jtq3YZGX*V0fHK^q82?28Pt+n?fgl1!>%OVd&8Op zO6FIn0vzBF29R-Xrj9~V@sPp=Um>hneK1RhY9qNSNk=V9Tca;sU6~HtQGjorXhTT( zn*6eWywNSIAzm)apo=_k*bPP$GF$E~SX3qC+aCj&aWsM!k(QFZOu5?a@5OI*>lyT; z0Ps~_uSHIzD$(N9m8tC)iY8prG3t>w14zqwaE%~M)K_lM1zNqO@creIum~t3fD{Y1 zG66vBw_BA!2q{AvRJ_oYkZ}HrQOaBH&V`P+=jL#$>+O()WA`>Z3UK?X3ah> zGH_Ry+%gU*q~*7N4D*)=)sGOOk3da!b-*81ZLoUhXm1&?Y^ifpX!m{t-8$_F(CLvq zc+EO5nbA-Kbyx$~vkx)iOk>HxB{OFT;OZ;Kpw`{lFv$n|)h-u|N)E{!6luuu-81xf zFACXAh>6%t>6}^K1|tdbVA}Qi`<1%u3?-oqvy%X6Qk{GRTjAA z@VC@q(U}P09|xq)O?Q?0ggixbL~R?z$kO}SC6B*!rAThk%xkiYmOw293fz!-5IZNL z`eO7BtFS(24N^1DRH?hzZnoYDH@*-A93%)|3FW+hytM<8yyY|~@#(uknwIsbDI;n` zetfk@P@Yf)t{d?ha1Nkzc>R{O@lNnr15v@#+^q~Dh5Ni%wYw}x6g>8y%pD>ObcQ1C z?kkp>5m$?1hhHA+hLK1^Icv<#{Yr-GigEEN&eJ3q*Mj;hqkF(Wq2Mt#{}=4_l#z<# zQ8==WO97<=^bG(&k*_hI4iK=BW5OD*k@p*Q#*&@K28V#mc@HJDi$9(&x||)2pqU}@ zX`;yN=Y6&?*A{&d>+_vOxF8A-O#zh{pLw!&dy3fdmF@ncf++a_3Q)LdI{+3WRz{Vx#>BAnUv3C-&)=jPX6+MIJh6DDit}L zZ-@R$GV>WhUYiJRWkhVuqO{`Y#RD=Cu(5Jyhj8QbC`R7zLpjN65BO0#mt`hiQLzy| zSOEW~0`zTvvDE^MUn-b@sQcp*5!1Ds{<+Kx5qcoHgBp30QnsNjErG1NZSZ*AH zVfe;q=y#$|@%Dk3thYqYnZPG_^HOMY0z-6qUuP6 zom(?sKBRF+yMQyqsatP4oLe?V*SzH^40CXy=|Sub7Dh9S!3iCs?rq^XQUw@UH`9O< zGJC&;>R2j9^u-UPR^j7S1G*=(4gP{3y}w_^x7jIKq1ze_pky}YU7=~zydU(iga%Me zn4500cO5-Ww-O2#kVnR|SX3z>svgf<(o&6iBd##)Z!Fu>OKxrel)xst{mfZt?dA8c zj2j!5Bu#iH%c>{C+WL=u^E-C^DK1t^vy*J(Y3TAu+j0+FJ2(%-$R~TR!scRTGg@v} zJR8hL1}M5%Z898>!33NKFwFf6e3@;vSxdCI1gL6x53720EJ4@^$ z14WcFQGq3h_FMm~+@v-@;dXDM|B^$z2YxJ)=*qP4gOl*QtQ|eQGU07m9EB$VwXM7P zt@~~FA1(3vD9^$xVU~=4HQbsbJcaZQomf&X;?nuL94OK>LOaRcb9p_SF9Ly@IKZ-h z_ZYAY`%7oB0$=>R3$6#m>6<^U;OQEN)a-9;;#`@}G1ryS8<^kIysi*!9^h)A)5XO- z>K^b20T;oQ+qRF_O;cmRBc?t^eDst0+SuGBZhKcti8QzSkv}yecI2@X6 z3*-1=ep`wlJq?SWI-&fMoH8PAs)ds%qfSORmixh|!!}>ONfr6Pf#R}9p_BCUv!ibgM2 z>Z69LO}PfS!f3XPoxl3=5?T*orKt?+X3`k^u`wzpZo)}CquLUXnv$jKz5){R16b-% zKBY|3ss&igA?3Zdv-lY`0P_v*`D+-XfYX3Lto0x>Cyl~S=`ffm1%reb%POEnk$D94 z3Vp|V;3`&*gBv!$HGxQTn6cK|dkAi#GOO_NG|c0;E?7b?JeHe$RP!23PcAK%FtgF$ zMRgq5gMSilqKRy2x(j2gC7`TsbMs>4#HKoc&~K@{H7k81Y%vsRIbFxTs10}@?Jhl< z=>E-`Lq6?jZk_z2p0GHCu)1ZG8x+lG)z~Cp9P3TD@nDtpRDIOH<>DG8a<<57_{PIh znDy-Vcy=8!14G1+OWga#F8bZmGQGzZ(*=hd1+{tQf5qNEUL4>G*yGKoOAU9=40w4I zSoy`c6A#7#ln-+%qPw7?z~A0+rBMzr{UZ=gBkfQ>zB>xPbpvurfMK}kcrV8JH{5Kd z$DzxWB5MpzRIP|Zm*dqPG47O56BI3g6L1P2O4K+oT*~yN=hgT0WRWSbsea502^JoK z)W8ylIJ>8b8ey^0+eP{{_!~ewL45rA1a}oopeLB!l!R~SM=5pCc0SULGy*Q(_>xn1 zT=bI;<=*bA)Rk(;25Q3SE>r;~;L&wSWOc3pible5NtMra_lJ*QHx7RpEDlq@mj7un zI#TLrS&OErcc+j%#=ru@AbZ;(3H0DmkWPoSH55|0<0?)?2bM+w{rD7fChnp79LYj0z))I4ft!YSUVvSW%g&PKIO59o)A}P&X0c^#Cb`Qz zBuKZPCt|9;Fc4G`uW=F90^|UkvD}A*vbES%vhG#@nK=+vXgTv?p}8CYOmy$DK(Y%d zLC#s?d3Zi!Q~)wMaJkJE>64Rf*d0PIut( zpsAtyA!_93MmOH*zIh{sL1`=Df*G?=^aEHhulRAKq zeZzYwx_Jz|+-iM@Umd80?!cm6EcJ2t@*G;1hLy!IFzzp6;-I&Hwzg# zWgI$7bx?CIxSO4Srsguq;sg+X*XGy162_`kH(9G*1X(OZ`F-+(J~yLt`l;uF%I5Dv z9{NkuFA;9VzrE6#qgz|n@Vz^kYKw5bk-t;8&Z6Ve*qC%0T&W`J6-X@C&Tz*&vJlG-Aj15j#=K1%Y&D zZ^Q;6RMpzllkc31wO*#QbdKw{$i81{U;Hv{wy7lf|Ynr-QJy79;z zsdK#my>X$O${Hdb-mql7r11~reVbEs?(Nxm6$^%|(6(6Ttpa8lnYsK2)P1uw;=Lh?6{liE+zl|`(8;` z6EmBFav^`oyuZB%xodZ=~3_Xi+hlg>#^DH}>)(pPb_U2RgsM&!5^To?Cxozm;sX?50saauy;&IV2B4%=EEdsEL|-`?8xmp0Gzj) zpxQ&6d5u1|)inNc%+6mhe#O5>+Q)ytyEIn0esMl&if9`1mJRCK^9mlW7x1&4q2#u# zrGv8gP9%nKI$d+xYyQ!#O6~ZOS+(~eI!TCMJs-2}4P&4LezFr>A z`(&wx*!Pmx%_Is47;|b3Kx{@@BmL;boUm?I;xaJ?fjNkgpP=oTd1^;BQw>0+R2xGN zKY_Ld1dFi35HHHaugxRwL=32QNG!5I)iOUb=>dAKO6$Bxl}#YstrtIHrU>mgeFUG8 zGcg5N7>mz9H?YzCTxQ;sKKFFV9ZgB15MmqlF!L`5qVq9E=NY`J#REQkowp`udZK|6 z6yvlg6$x%j(~G~|{DalW_va5j3Ml7bV!@gvjcKdVg^;>&mWYcxj_?qJ%#pcfa z&ai*!(wZ6ZD#O3QxRXQay`B$v-4qRVcnOiwCstdolD_%;djhUD8w2=KojgzMH}B@j z2FRe*#Wxhc#RG}YiOsfBMqSz0a6GisLy)eojlW8fx__nhm~gqmLd$RNPE{wh7j8`c zRWag<_Ylv!JPqdOR3mTgq^-#8qTlYdykU!*h!{*OkoEBjuU5jwl3n#N-FTwZrX&kb zK?q+%VN1VY=$VMXKNE6W-_Rj7rWSD3cHb~^(>=%Wju$y>;&SBHt6b&a84(aT4*2= zUs#T^7jY0W2$($_5tx!LSPj~Sg+*gqSPNx}pU*gaB=}GgtL#Qy+fn24srAg(gVG#2 zLvbXRYF&#%Q4ZZ=+=__0JD&LpnAy@i1>&JqKZNrnwWf^f)psHiJ1e8=687R(z<9pq zm2$|!0T_+wtX;kCDi@ihqIQV0azPa3 zwq8rUkpS*2%5uol+9Y4cxwHDmZBB%j| zqe*Jfp9et?H&(7t*NDp))mLMgN#a#G^2|1rLZ||$S_by}!ir`qqIr zGiEZ;{N&39=H12SLWOSQ+v#yhErR@iX-WR*%)>~5p7NEPU@nZ3GRABeBF%u7n{owG z75YaK#y2#7DwTQProds>sW+Y`8UK?_5bvBK{!C3`oQzkawa9{Yu2&(Cde?T%bftHi?;bZhO4UhDamR$D=L`6G66-0a*w?Kgh1^e&?6A$?E&rz4q zI#0BHPUq$jZ}}y2r~8#RS)k-)zcPTRV3Ysp$&u?5tyX@O{ZPK@j#%>#l8SEyS~|*J zcmQ6Q!@XMw&ZSkTxJ9(#0V4{U!oD~Gw}u1)daYE`Q*fd9Ia+_43(C5YLj%3htqznW z)3+>BecN%Qg(WPVZ8tv^U}V# zVMEHp`{5_1-m}6UVA4?epe2HN>$R|p^~CzGoeW{rzqGa~(9WmvJ0q~0;o2*S4z2Bf z3hPgyW?LrVFI5hIX=8bCRoG;8XCxIQ_x+@z!kzwf^*xJCjxH-E-YOZn(XiJiNTMhF ze1Mh=!OKWJU9Y1^i>?=uRkHBl0$OXEpicqS`IuM5W3tANh|$U4h)ADYlZ3j}y%-Ke zB36O9pVs60&lZ*aTOefyg0>Shz-a1YYH@Z_vKgshGQz1>VRJ<2 z;xV{LT2VszrTtF7x}`b2`*!yL!c-K7m1$lYbX@F_Qy`ji_+w{FW*mMgx07()wHi!{ zJ>Bqv_8N#io;?PIk`hmgrGvPqEg0Fe-YjvB0AvaGFFveLv|5xcfWOHlU<$NNo`%%Y z1tEfWZo!8+uPY}=h_lego#6>U-e8f5rj;hBDKtX|zs3zu4ivfUty%}&0JT{RuCUNK ziK75!_$*vpeP6V6^K=wi@|E5%a_)wL(z1=&Cm1DHf$J&22imTswI_(p+`a(j$u3~u zjsX=_z5j*w9Z)Vv0$7)ST<7uv=70Rw-EQ++%K-Z^2|78x%4!8jT?^sO_Pv?bTIH&D%5`!#hS4P~EwNB4A7Y>e+u@_=0)-~N4M6T1B>KVTbvXS3@eI(^UE^fF)7D8V!|-xU9zE9T?fOL9S4bpFW7CA*#tX34T#Q zL|O~mmvRI1{*W4JPBNx)pXnyI-LFbpBSbrOG~4q#Y1+6>Jv2lFRL| z41#mzKlh_xSiPKL&5f*dD@pg*s=<*XDFhz^J7O8wJfE~8$eBzEI;O^~Im6O;nva1* zMQJLT&f>IO)(IFIhs^JROAs-SSi-OYS&jZ8lN}%E(@?z~ZvfU=Nqevgew~G|DN>#N+TBU`qsh)!G zeD$^Hq*rV3vsz1lwkfN|8r=dqIJNy%2l_w`s;Mb|5p5MmYQ(hzOzpy%D!^>&@}YwFw;~qV%Ev3%I%t(V5!A zW2CuiEhz|^<@=6`)g^;>g~wX0P@GLlpDjtyaRTNu@RXfO^9~vY(~V^-OQ(Eq-uRaA zQE@Ngm=#`I2-zP1;%{GLan)$*H=3+SsKE8nNzbOvAPU`89OZ==4)m{LpNXR%CJ)>eT*XshN^PU)T*|KMy@ucBR zh*b~``g+jSP4oKwTGlsl&GU}9W$}QKzIEZ3AciiHT9_(%DaQ#}_ce`(WVp5E7Hd@e z{PspU0yR|xhN3j-mgGQ5Bv^%gzdE9%OOT@2}(R)>bsYIR-4F?#`3!A=fs9t z)07^%psy6(!c|7EIlkT15}OHNKF?svyHJK$Oh+ZdAviC>%SHjqWARG7#M6a(PpO=L z0#(ewltD&Hr|>LUrWMw6xk>sVchgn69L)WNc0Q8ndC+v^j#*m(WUKR&w%{$$M?UCG z*meRvZL6YVDVWDo zTbp;mI}r-tKN69!ht0JRMgP(2n?H2d2p5bX-hl zFn{*j++bhl+dQ*BZ9l+;$t<9sm@|T;Mr)sMb^$$n)dKpuh-a|q5a^HA>)Cxh6ToE; zB8!&(2?i*V8jPqE-pa5+KX{8GbsuY#{N98V8DOweDDyaiz{d=G#uZrVuq=VQez~N( zS&#i04ebO%6`QXD9TiLCx&+^GU4q2PW=b30y4)S({nxF`}2LCKc4H?b=}u}={U~W@4eSvd+oJeuh+V5V>Y+9 z66clTmg)WYzb^s@^}Q@qbEyZNq$zxG1W#Od8MTG!9rQc>f&kgi>5UP8G5Jk9tfG7J4Z7pMl* zv8jV?b$RTQvia_%hMOdZy_ImOefk8SqeA-O`wvR!RS+k5`b5Bac9`k3?`Shs4}Ny? zpt{fDqicX@Ax0@G?z~*@e5@@ni1Cyiw>4!(lHMn~VlQ1g&YMqX7bBDUpoOenpjs><(hTW*u9a8S5V`zYfvXLaaAdA zGsZ;|8ucm$Mn(*ob634YB{Tsb+{EIX#n3c;f(NQiH_r(WtvTkGCk&6EvsN7A31<{VI!v z>)S(|;bV)nFEtFqYn=c~n2K6Oc|DGW5OQB>TRiuz>@(c>C4;AOT63)!siaGbP2A|s zsH2bKmq>T@fRskxV}8?pjC}e&T+x_`=Qd$6Lmrh+U)#oiR*n&D=Fkv=xo9AjI>uGwlT@k(R@ZsTXDb@!YLZe-n| zKzOwsOa5jJx&k7h;E`J`nb!h=31-T9k$Z57;uQT|^n8-dmk)5xq&Rsl;)U%*R0quR zSe0W_ot0ywy>x}7P5C_s-Ui{W0><)a?K6{xPgfs~WVdtyu*HhYBXKIFrxVa8X^P+( z8b5kz2qd`xwmVC>eQ^Uy)KQZC#9o1}d2A;g8C@qap06*Y1uE7NOQX$i4;WMg5nc&4 zlFY3oI5&@;d83t_Y^6*F z^JZw|^I9zq$fdbX3K~VKZJOM8&8DT%LRQp^Oo1Z1lAToQ_!b@&=3gpP?fW2$E&wy~ zIixF4t60~^gsRX4HjA8Q+X!4^Z;6bHNbGvdpQ@G?HMv_d1Q2X9aql&;92em5WPGYp zy>BpY{4t3;p8w4NX;%xt0t;7tGLV_I=Y%VtfnMf9!Ofy-#~7f%uN z++{)BuFTm-UhO{Y-HImT&pc<|r~X5<;q4tbBlR_&bDn>Xu3xt5-oO7lR2-ygBAtBj zw@l&PZSXR6+(-Pj`2v_PyXyxP!kbk(kryyn1XkGQ^jL!^Y;JYeRBG#OL}p%U4NHYb z@RG<0fZN6lJ$-EA=UV0&B}sox3stCj+%PVelqN5wU8FLpo+n5f=LlKb!Hpi9V8 zRu-gy_wb2#K}l5l=r<@xaB&IorSGi}yXk+KD_5O9QMH4~;6bEiPIDqHxB7ts@Mo9H zu^EB{4NZ_3;sD@QWX8I2<_B|4IxakE-cgOT8EBNW>jjzX6RF@b!LU;;G&MMgoV(__ zZr;W0h=Ba_l|GO=ch)>FkVXa-;qwZ%EA!(CNbN5QPM1%sU$}b@pyXPJ3|&1{RkAIN zj%0{_%_z%qbe{iel2S^gXZfPyz|kql%J?H}poef&7je!sC7qLb?G_EExPDtiHhbbjw#&H0M^;8x1M^y|?h z$IuR(_Q~L(Cne{%jLqjP_Tf<(WlsdKirfLDNFZl&s4E}I%P?_5#^hEB$+`BE5KtZE z!XsGYvl8^`MmmjFOS)@3SQOPqMygGdx;_*s4xoS-k}n%>z-# zOcHF)SH2gtXhmtDvhq%#@v2?z$6Hl7WI+DuEfk)a7!QZQk!P4q$Z>xs=V5eJa*#Ed zjnAlJA_A&g7S6JJVm4?9S+Ymv>2gkdCWZ+iMfeIP(TVAb&{d zyg3=uxH9M%%0ZzWC*hXG@6E?qC%t2|a!&%&mn?@M2dYm3K=A3)-#mjkdXE6c+1Q)v3R z)dv81gN!qrI!I{ML_IlmSFs%wFkX~OpZyiy?c2@jB z5(J8Of5)c9UnQLMeR4G=7C&U?&a{nui}pzgWa04+VM)7aYtWoHTV_Como?`|MaciX z+`@JOpvrW!YoY6iWnhCLbh%|M=dT_Hp^G9#4dAN!n%dJAl+ML9hpgA4?u5181UX~f zMg`+$kX5}I7G^^CS@}f9$E3k#)&nwPz&oYk(tPsN`xwQuk%azhi80^yHhDAWzW^}L znM>_&zxWlOL*P(dZGOGJbX;6G;m+?cR9e8gbBW64_TF?rtwPy0LFRy?crNia=@-nJI zlu}>q!Rd&h#d=I_A;1vXO-^Ldg;m?HUPx3t{eA;*_w;J>7kZ~QJxG-t7>eeha4+4U zX4AM5$Jl_ejyJi~%22#ZZRkfFhhs0~gfj<^4l6y-YjG-Yu(H+Jo3_?3A(Hq@qF^gj z^?=mXdqz%2Ih=Ai$X5MUNXz|_h ?{>Y?^m`Ut3_Ud*XH@^NqD`~SmlJiT|a3hma zw5XIWKiq=y0?2OKQ&PP%FX-JB)52yz6^=BND)mrukBueeUFP%AOpYTTpB6O&c6j0Z zM{tdg`-hIt_*H_eqIQ-=n;HkX&u2k}3^1Z|r}QovA{dTrvByQv&c>LAo<&77X=L|D z?#9~UCS1(6P=$<7d3cMmcTQI*O5DkHC%l zrJulA|GH9J^b89*>E2^#+I=0pw@>(hS3j1PYHX0fIoA9rMD6+clYx)XcqP!+@lMz? zkWpLWI$zoafQ0NxZ3Cx^ZY64-n}zEkx@!;b&N_TNeb}UqSNo~mpvF_pAm2SQ_9Xe> zS{hG=J2GrpO~!m`6Ta+Az(SN$IrR1s3euEoTvceED1-wpG4$k~%9JTQ3OuXMf=k%l zIaSM$BUXK^;NspJaM-jbPzx;vsQxrDgcpg9Gg`jp?$`q~?;QRZNspp1?$N8@IMs?H z+iUDsbLRBxvlZ{yE>YmI6tNAZn?u}^j)W^n>x8VF0?_;pK-hNjbF8aTVK?5~n6M0H z>GJAkRf;km*bn$afjDWa{cSPjJVp@i14`4sTy}wyr#gbGQ#-i`dj8Ga=P6 za51|&>K}O^DSB%ba4}vCE0H3b342T_Gawy^4_~e!+;llR2&t$5Gu!u5?HT@S=3i^>dI`nQHGC_iB(rF}z!J!W@SUoVX}J_`v`gDZMRf#yUpgesbj z{g81qr+m0XVgBBS(Ruh$XqNevg#N=bVeh99g$>Z2YpluwY0}W7t-I%gBt$_#>nnhq z0u~{+Js#?KG;a!;SD7xIbgPRzdic1R5Ug)N(?(qt`yn z#&Do+rKqMPmY=HuGD$XQklj{eu&%3szE<{{uHdcr2v+As9RK{1(4J5KEvoDEV-KnR z=j)J{=c1Eno?>y+c%in^4!pp7ijrR`i{ZNZi`m6WxaBvI)w8aCc=jqLzA$S1y~X$g zD`{(3q3r1*(3XEidujjYqKgjNw_Lcz+6rO|90S%IbRAgXpM%i!5 zu!t9nM=nr3B(vN01u{#3u*Q$MVDw$EZu%4;tRJW=$0D(hlp4gz4~j7{?1zy$Xa^w2 zH0jecvxz<(eg%84t4RE$3ZLuZq}0gDoEVS=(jKCdUT7D#T3I&~dw6h(Ef+=mo5MAS z-F=G1ruf4uh2)mwIy^(RGom&>-SwM8sF#+AQLB#-IDE(=??H=H3EPlV+j4WFlc##= z58yN+srHk{;4EwUm=Es0_Nq^<=`q>rJnIay=8y(!W|M)XOn5k{I2& ziar4;_tX{yb`zGqSHKkS74{mXTYm7sxjFpH(tIHiCpv&)aR!T%r?#JjB;kHU$Z0%r8hzq^P>Xe{WlglDD z=u&vbVp{%{N-NF4Z-8fua!ncns@b^@I&geE)N}jATSW98&$)zA9qVhs_udB}DieC7HSW8J%Nb7AqCtm+* zH9Uv+hr*3VWatSM{G{n+X)|br0O0-d`p9`RmFUGXr3hWQ9X*ds@1C2srM%nXa~mMH zHW>%aZ_(e4g);6UV6Dd9W$bAL%|*n=jld z3$G;lZ2-9@m|irIrc*3oVxv*f0(ed{N6=ZqIhjQ#NhTQ^Zt{+W)4P?P)A@`Ob7<&y zEP$l&{OITE!P>b_VDas?{{kTg=2#Py?&jXOE=`9D`WNkaEB$Gg5u|2zqsvm7mOnXy zMo8iVLi=xn>ZCVkK+;`{n3#10uLN}in(ICF@t)*wbnsrcB)Wbl9G6U(DgA($2HV9p z;+WaeV&Z-R6vnFOv z_Na%4m1E6`O$%>;c((Brb81TnsD)l5HG318#zd>8*_fAvpR&ZjsJs6a9KV|4CASK6 zZj$>R171II*P9zw&E0u}#5;L8%VVue32~Zkw`H01frBM@d@7`=3YX#`zyx$>X@st2 zsz?F{UudG$E%m69zD z(P1XD>xtNWm?@kSI+EYuqWkev&?pF~7rb+Rm*w;QJ?KHMAK zN^-anAV{Z5>asrEKuCj}GR_Z9x*4q-7wDJYLYP8OYhMERPzqlP@EbLaGVT%g`1kv; z$Ub^!$4Z714K02(1Icaj11c@NbQc%QMw(XnBxR%FB+W7E$Qlg3&NRHx$Al-oHrtqO zn-`Fb?t-Sj2}{0@xp;~+Xu6u77t8-s*Rq;Z8-c$rR;71apkEtbHE7n)lI24}RPho(G4)o$_(&Xn6 zmVjxoYGwQ{@x zlYsM+Zayza{D#)0)EdDXWQj_z87LWxS__QfhQ*C`TVB)N=D;x{6=o2Lxi`Gy8S zCAD;c;P&8$m}reR$!l+GTa$I9d1++@w(b8aKMg(wUYmrbmrYBEOc$>t(LlBYUl+4i zfh3D0l8|3M3)t_qt4Dh(S5>@~{3nj{mpyJJulgV^B(uot>#3H`uI%LfPvf_hhaf=2 zr#k60Qza;Mn|*DbyobDppA~{m`jE~bz~Lh)4Q}MZa)qeecC+9K$NoDcCErJ*x@&WH zfY^Ha35GN}Eft(cHCBm9JHuYA=9{0?l_#K9s4cnoon>Aw1euoesTvZKSlkzv zatV(xA1n(gvmh%~TovByv=X{iuFz_ z11=C9gv}ew1u|*qs#H>sQSc?Mevrzz@b(cxh#o!Uv<}Q06W4R=pvok^)IN@9ankTm z9ROU}v>ki!cVg5<30`u%l|mBS0b|gi?|SwJLn1HWl^=l`U8ujoaQ&kfJxpZ9ppSat zV?GE!Xk`+W5T<^pn(jf_%mFu`XYVfZ`XZ%<9jVQ=AWtmN4qwEjLM_0h!R~EbUM)?f zf9n;52K|}@N&6c2vZl_p;=SP4LiIht)_lDW8BhNqI0W{vg=k7Rk#U5fA4*5)QBKKR z2^PcNOG-7Pqdw&yg}`4TwZ`~}C>Sc_FB~If-Y5IelB_ok(AkGxOF5d}=Aw;mzmj8z z0R#DX^Ny~2ota?nJ?FfVk}?x>^fQ%I>xqqE7G{AlE5`dHtpIc^0$84 z3A#b5XyZu6cT$q`w&x~&dDV0H==rRI86`VKi;|sAdI%1kPAx~0*`F^@)7xc7orRR4 zc%!GG>gNsaH(w7FNciKXq)i*p3d1de+voC_pngpv8Uyf+`eCZH~B0?xRT2%Q4U9M_m?EgDo2YmhJ`C-DA*up z{B~6Awl}w-za|rbOVf8?OMwPMOTjx-L%S#V@~Q9|N}uVQclLQeoDy*sB$u+UPA&oQB{1w14+Wj$~<36Qq+ClLh+$WUKajFZrEh3rm%Ly&0h zB`-f-$ryW0e{RJ`+|$H*j31qVC%ikM1N1Zkp#1`8i2{+>XWONhKE^3_{W_O{B4+N5&r@89EwKaO&9he$8LZq|m~(c7AK{45vE$C)ve^o-#o zKcPD2r1CF#HX;%XJD8uFl&g^9HpDV=6rA&)#Ol?@OS2EiMEm&D>mTu7mR#({odR4T zYnpa~7+T@6WK`erSmv`Dp+0jbK9}Z?2qk4NLc4(eG+?H)8_KvHU`)d8r&#L-Hg^N3 zP{P;gKH^v33My=^v$7km%;H~e>wsFq`6~7q(wA3NnvuY3QFmO_AJ7zX1;#G?6T8pe2&IlZz4(17=)rlgl%zvGT<}FJL<2Jxo+86I6(<(6=m!!m;xl zr5PHoM3=ebu`MRVfEv@WLmuciTEJHCg%ac*Xb3?Gx{LDkd^hwuZw@zcQVv=OT_d_o zkptK6fIJF2szLYE!Y49OMynvs;i&I=8F0>CQ=9ai`cN;28gY$~R@pmfx;}&5v^o^p zqR~38=H=-yX0lgdrOOSg)^CAh+9!0mXtl?H^vJcEM>*MK5;+(row-1}e)0qQLE}ir z5`8Yu1?o%>EYE0F?SQEJ6Jm~UM(Zz)%3AlVQQPfqt%T-)2be;0=PtV*8~}#G4GupP z%*w%YH99Rh6Ku^#ba!9pCOU%hV=IK?oZVt)AB99aQ!|@zZw%#_>C75IUr_TYCY9T+ zfc6nEOMHN^247eR4&!E$8x|>@f5n`g&whyr(T&*3+iz#@wNaD42YJ3kvJv{6(0!TD z-ZwW;6CW);s|>8Qe7qVSo#VGN*+MA-zw25^t)eE~MBVMHc5jyhlp*Qz^i4VT-hHVL zu*Z+AmPGOGVvR2(H){RDoO5v_jv(PuG52MP2t@*%T^i{ZXDIps2rkK(>YG$bg?*wh z1c(PJwB>amUsdafQbd}xaBGR8BTk#8C!)RrRV6ejwUTXd6ZXE;_@L62Od%94;v`~H z-blic&iwABh`-lF-Vg(Zv0kCLg@Ku04L>C3x{@@n?5zw5BOhj;$ySLk z9!+z87O3O)&CvIYBFO=#=wZ3wy72-~NazLiZK20m+A^qN>X5cIK7$IBMw42cj0(kD z3(zpYo_WrGMZIs<^)2vW(5?g>@KBihO8!Xt#G1_C;k)DJo&sN?+v>ZX|S{7rh8 zI)zRiN%r`xe?7-e8ZFH`y^Bw$e*HEd$%n6TBNetj0m(cE`IA<0OP*9+5%++sB~{$| zS-#37o1~#6ZziM$0CxmirOSi3ULv1Qepdf*z5uVX*0D+5gdy zBLdDIxhVJM^NX)wAz%lmYRY6; zRzHq&8D<%2T7g`I?!B=kj<)&z1Dg0^ULQ`vEAqI-k+aL)chp@xv!{V1pJ?{Mi4t#P zNOI$}Ngpu{w_>zTF$1SLj@6w|#~qpOXXpt6!N7h^BBKuhDMR*jw8>qm*La<(LWYwk z6-AMY^}Dbg>t(0+U#72&-1Duz{0kD4A#s@?UX936L41Sny&afj5w!07$(SC&bB1T6To@Hio=8|py=CPBO{+^9u`_+I_F$fyNL|6x15cctW&2*N9fr48$SL7hv=6IM)QKP!jP39~7XLDKJ z%8$r$nM%~F>vGkFERrUS0Xv@6OD4l&P!DMKrk{#FFt@%jQLt zl(4(!(Ij-Ui}`#YJ54MDTL4toV7k{|R(rLfhtj+LeO3j`P;uaCUVZN>a|M^<$;U{q z%=?wGu1;k2%{O*&O`A03BppCLBFI$g0y_ZEK-o=i;(2<@0TU2P#cjpn>0 zD=zWwx{Z%8V_5W|xa+5Cq|rqy*%JE(G_oAVTYa8>if4?(5}F5GE`E^X6fyki72ITbf{AxkwdO|Z9)G9RB;imRNu()^&=cpcuM$q?L zhrYb$L?d77Me2YpWOqqX!qF9Jcw9H% zndvO|HRmY+1Kxr#PPzM3MTQ39qd|!1IGG;$#sj62dv~40iuno0kv-vUM^R|K2b3nq z%$gLXcz4+_LN~Uv2i8IE&a4DlL>LF>>QK70631Nzjds^Fxeq81b=+h9I5$`MNtE%>evCXk-v_8#^_Bk8Ba29T_3?5XuU_I!4xazWGj~-5m^E7Hx6AB z@+OlKdVSMS@>0z#o~#y7DP%A(6+4zdA3y&_LveSeOlHs@|l-jVzy{&v;aZa5t+@tEtx#a7Tj^3g3H_wGW+ zltyVorgXOfZ>w} z8Z;(=sStY5&J48g!kABV7K#s<2Bm3aGEZncE3GmE9kOh4)~j&3m@?CXG>j%uUxdgD z-P^UkE}+MA;iGM|-PL8|>b}Yl<&3wYS}z{)T0N3@dG@Vq%t$LMqyoOVBJu7RVUU$Z zV?xYhr7Hf};RY6F2l7{8?=GS_^9J?Tt8(0`3r@aNyK90U8OXl}uR4o29ZIH0UaH+x zxsqd8;L_{1gVF6ZSdOck@ac*GgCe|=oBJIin&N87xsse}`rGNly{tk)T~TT7XJU8l z{4EsPK`4vV1@875=^sQN!9;&jqFcSWZ&Pdks=^MPJL;9xl{UM4MQ!=`x7~q1`A)kJ zLCWtnc5lCc3W1x=E4Opk9KlIY!5$~Fx?`kBhwSVNdrds|p;?nxUZSs>Lv28cWNN|m z);k~?^eHD^S1=~>0?9EJXft7slgLEvrN4RhefK&ya2ADq^L0GQGg7bQeH544rTl5J z`oqyqHueTj&HWG9aH%)RzS~D5aylv_f-;9E6~pjOFj?QpXZPOtT0uj;*{g%;0uBIi zm0ahvkVCaa(r4<{x$hS}dO`^9Zf95VZwGfu5Zpx;JvmAb3<3mvSjvz{r{f2=Hfb}1 zIVVar9Xi4*U{x!hfK_oS`5=3m=@<^j zr{G9X0k~N-RfdB1ow_N@P?PV#_jO_1Y1bK~LwM=?3n)Yl@XR$c%%MY= zhm??q7sfqm@IK0OULwMxOsEau0cquMFA1~AdP%4(ZEc>+pXH^3rr&!;P8R1bS|iK& zuAo)#0x1;C0uNfSp7n^|x!iXpvsV0W$V3l4MQ%_#Iz)o`mgc<-+MHgx_fhGmnHKOq zh>meu#3qA+74&IvYxRK~?GeCvCHn41$g9?~zYO{5nQj19BhXmo7jdRdsqBd4*u!oW z54$tc)}wJN&c72LE4;P}@DwvuSD9S+O6_~$ld(Vl;%g*b;-Fu#gF#yOkv!lWzr;RIK z`F6b78e(rM;7Ns0zd(}a<+t{{&|Ca5XxKlISP%w338n|zadE28&dk_Lo7INN(0fwUP7Y>ny`qfG^3e{u}KxcytR&7#LJ zar-MvzMR-n-G*uI2Jo07`<21=oIALKt~dj09Ll<5*X>a1bu@q=i54A6@X4zY=-k3;vC1R%xqZnV6i(XCFN zmcm|U@M2P$Ilr?cUKYD}hW0H1AvK+V&(2+^&uh@d1Zd)2-*u{7cNZIl0IT%lfDnp3 zw|2893CrH|kEh(lk5k0tcm7t5zh{VX(7CH;e=ugBfeuT4m_7rE7~PqeIb>8PLU zSg>j8TiJM1x4fVo=mI&MaAo)D`%l+{7ig|nOFO++&_0j!#j7nUUYGFr(Q!4A_@T?U zyx_S;2+f7p_8njT+8brrJHgQDH8OW+@6_m=Jn8KnKYHb2uHz8hyUr}|=q}MiVH*RZ zo}uOU%I>y#5C$I4Uwcf4gU3(wso8&iBhsZYyWi)owt`ah=3ko!dpbLtWx4WfepJ$t zg>?STE4+tsN^rjEIIRpnmwL?bb-J?qXxx%w-;U2fP0$$iE;U&1lbVcpEa~=*3{UyS z)Fqq-9N>w0I5h-ne{v)@pE#%Stq%B!=Z=M|icZnS+QiKd z*Q#36p5^K}A5WcceVvOd!23(P@M%Ie`RVdcK@}X<+AFNJK%5xdU|@8VYR|9LYw{AF?WexdkC~&CX_p?TZ`Xbym#by zId5V|62Y7Gp2hl`5}%AW0F}p$;EtO+ND{>fya*_h1@#&M_oIpV;s#FF(uW&WP?~v@<(}NEncHrwAY2zJ z(9ZjAxO3T**T6mF5zl32JaNpd|pIeFA9Kys^nGBymqb>it|ci)Na(Xf1m_&5T=j{~$i8%y=VfaY6JFrS^yrLOH{*aA9tp9Ed+eYe2)PyzN6*qF=AU0#dnF7mB#{9)gyej1fK{UI;uZY$`z zsj3Q{&AW5~gyD2L*S_5dhcxO9B}>{7pB)%?LSQP05A2_CJaq}saw~-%Q+@lAlUwbt zgeztq+O)2tgq%e;x!1)n7-&QPcbH+hgWwj6E$L`UF`XzdfrJ}gJ<9ek$*wHE5t5YM zbz<{PKSzSrc!UiVPb@1o$jmuv+|H=k_F_)%=XzT&QC1iREp_5ErgYH8-9K818GfrBJjZgN@>0(3tSqY*2{Li7l!#%>e zFn=$2r1LC|okct2Xo9rGukX-(3Vz_hnI#FFGD=4aRaJ7OJe$V#yagLoK3(1>`Y$S~ zs%~kMH@BAUi!)|^S#Rv}B+=H!1FHVQ)mF13jMV`SWI%T+ObEdl7n^%&7EXT$*H((` z-A)lEf_~2*|KOdaAMO*6kO+Cce?lVU^Ox^4T74YX^*a^-9#Eb&p6N8TN+WaqZbws9 z)#l?=U$N=%As1}B^ASV#`EJOgc%K?m>}HN^j;5a4dZS7%Z$7`O(pI03puN~shtI8@ z22)Nympk_0#~6Ma(49jB%eGyHY<A9r2;KOLp-^)SsI1ww*7g1+R51u|;#n^!v1=tS%gE9Xrez2*n3js!qyf?n&#s zv6&ZUf0z{*5mv=6eqzC3S+L0A;fkO{AM?*8WP0i8b40(6CMR>ZUzb|+ zP*t7NBJf?C*AThGPq6+xIoadOZ0358lH|(Rvnw>Nx3-o{BL>{Hy`}caO`FI8JAXiG zH*OymGBfD2qJBC5z_POr{*~})?eMp1<^w;M>iab5ri#=zukgCikaaFfxQ-|V-8 zFzMNw%ul<2afJW*Y48f|EzdO^nSfB6-9Nrto(&9%_Tq(K2JN{6W4&|ky6{V~@5cAX z4}*`8n!x)?Gpr>~;{RjVSVugngM9(nkw3ozdE*V7(UEVQ*|NV4`wt)McR;rot8&2b z;m_agCITzl^*Qvn!7yEs65oF|75C@N{QQGo-&lWq=L)_v&2HSE&&SKK6aT%VzD441 ze^C!ckbhi(i{i)3{P_pWBh(ij-cWhE!#^e);{*P|M_S;}Z-YV6s3_m09Q%KIVASkc ztUIRD_pRs8VF#U(lID-qh-Uxs703_Q568!T`*2?2w_*P@wI5#u{&Jp}AF?C+ng7y%H~&CI6U}M;c5GOQtB{|+G&pcUgpUP z%*DIFkN;bKn+eSwA4_()Y3DEBD~&VmTv3_Q_4WPjm_JvO;9LIq2o(AM>Jc>mKYWDI zNG6Tnruet?&-Qf}Bfpb;mBl_=>9=2Ag2K)v7BlUicj9T{q-)caUr7F=i2B-~UF zVB=|y?~;@S#!hEtS$cT63dt6|BYupYws&u3#4lNUM_PU1pJd3}+AC@*K+8 zyEy@x%6N_v@rHS#L&4h%V`-Hr^T zL)O4!#x>)-rNQWGPBI~K2mV?YtKBbECjcd<0sUx)E*yZG8%ZOKWPm$)+16mW# z>Ukjjq5h__d<@7t8Cda!_DpNiFCZ?|YBpXTvT+Sr(6@0d_|!@?8?lAu6xsC>lYKkB zye9VyC|<1IoIbFy@wpQJFuBB5a!k4XT4@(9H!*3<*41}dUbpIKgnO!Hkk`+2(x)ntG`a#8x!Wvyc}p4dD12n{tH zl=HF+JGECAqaqX4JmJPKBgm&VZbyI3w;BJ< zU+lm<0W#JTi~tw%RuqMBd~!1B{e3FHlg+h-)_B~xI_1q^${9@7NcWTFC_X3Bmg`C_ zJpH!>Zp*dB_C?sA$~0$Ov_aJ{^Zuw+#}`Tr8@D{7!{OLtoI3H~-nQvrnhHNTr*)J6 z2nTlJ1R&N$SzCSam)#7WOX>+&*Ln3ev<-xXcThgJ%oGWE7Zg#2uX`&|8#f*4)k%=nz4YNA96`gz}%KG-W$qfG| zDI5&rAhJ1)wG)4_GsMOZfMdOz-^z-to+1tbY_|IT!TXsXL^;M;_ffJ)F`exWI{Lvl zy=2U+x+Ic2!b~_kXJD^``09&R0(W{GJCx!NdZ%$ZxnFTFpEri^SQ8LOBg3|i7GRSp zO5AUmoxpHek!-rmZ67j#Oj7uYoDR#@uz$=|81Ok2sMe)7w@BC?$Bq7q`_PCyrTs>i zn@r1510c@L%6G@Qd}9ZNLl>9*>z#(_Qbmi_I2M&RS0v)%4j>)^9U-Ip!|6)7xbYei z_FRC+1xsgmVB@zv4K=5Ar}KhvOYTvL5X9ay$MvUxf-1)aLa^ka`yIYKDx{V?){3+mH5_ErSjK~38h4?4+b^flO^t;WqlH-Dd(SA`W z7I~{0+a$sL=(9+}pvyMMd}U&x!$_NUVBDKhvwK!6ky34w*L0@Rxrnm<;Frv8qUHt6$VOXNji%W4lQYy2u7V(GAWY+L^aCYv=Q21--i3>`zsM{gvw0n&hHpXV zWi~gzM)w4)Si9>??Mx@`V-Fykpj^M%#hJla;ub~s3S{T#U6f>Rv-pDxlFvi&KbIhe zJw{k1abf$3ji@$9VjUN5Q}L66u4|7Iyw5AetTg4v-rD>DI}AJQF>xLtV)ED{cts+4 zBmL1`tAjz8H3}ZWTs>{KsoX!Fy|_Q+wM6jRA&at?F6N(C|76EGrZzp%gf-l-PAU7g zHvCSU`*lY2s93j`Pk({axKSdGx~)5Cn?(M7sb()qiFY(&X{nJpnmyB9@?PmMxx`|; zmN2p*E_H)wl|_2_#Q5h2R>Gb17W-IS>tMj z(PFVDAN^$O2Ax8VGOO_u(jGmEhTQhIdiNI(Z0+y({38hJ!sxEshok9(z%D zG*|G|u0Odxxg0V6jwNJS3fbF9e71};BHDB1*^Ev+-A@D&Mjlf^TJr98)(?Z(@_xI4 z-%N?$xOrkQDaKE^i{!@eh_XsC#US6Ule@2ZDDv{YOSt2>l4KYWykBDIW&)PW43Xbf z5!ZGdKb~;gQC#NgULRSdF_!!3U75}!rumBH7gvWY14b4OOWBfRdywfsQ5qNMSkB$v z!-LpH8R|>D;Eeqn8@JfJ?7ISgbgZui?v8xWiGNw-5y4;eY}@Hm5We;h-N29fzE$9p z{i(nLg1*Xc9)G_K>Mk6L=XjNTktr+1+dC1?(rRXqjEBM_-u`ZzppV$^Sb+b@ILNsx zk120?3=%2qTH_K=ebBZ8foGC>0?u9c>Z#2$4>7v!%^U!GBEZY!2=W4&wcfFq9?L){ zb5Kf`2}dxi*0sa(O58O|i>su6@>W6SPFM41Xux?AoNuCI-TG8C+kd|RyS`a89NUS* zLYeW%VsOl%Z&}RFjKwS-LQ7`eo7mq%%d6EajWNYi25yqCrt7b7Pd_`(x3~`;7$dwN zkB1z6LU=64KMMZx%6eQNA?hWyU}jzjqB^g z$5^)ijo1-8L|wEkcXPgb#_bt80Ec&iZWIwRW*j-6ur<7YV{4~Wc1Io9+Cdrk|BE>%Ub)~J z30A{F{Vx{0xVN-QX!|x~g5NF~vw>5K`tHB*P_jf2D#|%LvG}>~5PQ2LFC`ws7Lm9a z^6KFPFH~n8H&YDSff1njH{U&oA4Rt9T{{04D_+<}VIYNvB2oJnE54>nERMUa2qjAS z-|w>HZSND9Au{ICm1(PK9Rs5W#N!@FG%<_MvSVvP<6jDXxz1z1 z&O!al7MF@YikVL+&h!)bN0w+eF&yXw&7Y9nkMc4#Wq{v;&DDG#gy`I;+RzXc&F_+ zhJ)t6UvTvz)$$v#VRW7Tjc=<~zfiO-J`*JU-#<8g8S6efh#xHQ%#EX$@;hEj)U~(1 z+iT3YNVmeAu~0Ba8tf`MJ90DhWpqTbHwL+^V$!NHEOBxfQ@=>38J(=igQs@b8v5fNo1OzHRvj%F?UTB4m?7~Ar{F7M69qFy<}WvRibs=E z_S$tq)^A19nB_|LpAJPi49)-GU{Wu%D<^(NgeaP|L-u39E{_ zr>j$p8#Yc|E1l}li{jOEIgk5GM0x9i&cuB@KhA&dw7M_kZX)Oc`ltc`rrh)LEjY9V*sVdO`T-(WM(;M;U*rN z-*=JW9Y+_i1_)N3W%Vc$Tyx$$i1YpkcU101v$Yz~gaxSrC zJ0slC#qShA>!>hz&zp8=TStEC+e`{N;@-+kUKMF>^L(~G>gbZJs_F*RHjWO8YY=!v z-^`~+Svm{P3Po2|c&zG+ERa466)IfspMD`!{9^K9tzFtGxATGsF<(lb!-7Tgt+w2o z6uH?|ArEHZ3SOWtw5$VqXgn!N0|i&d@woGc6Q&b|3Qc;7kt9*zewd4s3FlnP!i!f2 z=GVM@S2VSh*B{z_Xi1HWw#+CXI5n7lss?pB)x+w<1s=u+5m|bNN<8m3v%rL%mn<&g;1m&3-BCi6*UGS^PT} zbaIM9XKo2lIo233%w#SM?OF9}&K5;q*&uHm#jOh5SQ|bisVTEZD^0c=0zx2L?Tk+QSD`P|^T+=`7tQSXK z=HyV>n1B0zA$bf$(VDA^4h#m~H=u2@jARI&hb>`H_VV_)V4L{`?bTkIa0TwXC$4iT zIvwU0IuR{R-?C?*fxA)-T{VkZ#>NECiVTE4&s=>hx%}7`G+EP!i=8vIIhw18wI{vy z6y|*E1Mk;mPQtjcI7na{B08G1CpYijOX&C<89n!AF~DT4xhdVToFi;);wg`ti3oI5 zKjSue19HwCHBTK{L7cF9+M+bF<}2 zO!uJPS=bK@ZlbzEZ(q7D#$4mkilav{$XRx{_w7;OOG$4a!y{+0bbBKqj4nu2po_8R z=w7cTv5yI_AZ&+Lp|uM`4Es^HqqD=_>|TWBYJC^y9K6u%vDU05pz{J+r`NU?Lo3JQ zW*$#TgQuh>&sb0wPr$lNo=>GmX^<6om2;mU1))zb43ms~7kb**b-O^tN=RW&z9 zi2Lm0eN&EaSs2bqfCQwa>hW=_^)HnYP0&$2@3?x#`>c)+{gsVm{q9TEI^kn#Pr?4l^LRMpHn|up%|EkhW%ENQgYo!y*B;zegdyt#kuM5Vpn!GGCZr66sxYD^^wpA(aJxQx$*}yE@oJ0t{#qx z+PnsD-D5W$G%wr|Y190WpgW!g(-rrs$6#u0?5L{hn(3)E&gL3@4`Po63z-^pMPp~s zCB{*$ajS^6PtPP&M`f`0ouqWtY1W%mPX&wTfX}^Pt807q5rH?%6N7^t z)9aCjTp0(My>%VAT5XGQ;gEa`YIh#IKps`FPEFtiM^=&6K6=z`9jOuKi(p`eDMC6A zZ(>0xw`Oo9vkNU2!b_50x9qOA;=#F?lUrypD1!9&4Q@|0TWPa=V=?HU-sp*2Qk~M_ zw$KqwZ_VWBlr90iatbr+@$Xjrl4sDkjB&se<`j$0e$AdZVUX;>GI^B*nt88A`nfhL2|b`ZEBxr8+kDFavT-5A zP_I(8a^vJ@-FUUZLhEC( zg^X*VjmmB&c>`A5TpS|2O%iC=MIQ0&sr+T@?v`}7ffH}wBr7t{?Z_EuI6jdz*`^cX z(QtR5c)e#Le5J_2txtesBzHa5%41~Iw>j?mDsgoqnMlT`@rjHw7Mj872=N;{${tm9 z;awsluWhGXK5#8`*_7Q{S^V^L!lJ)1ePeWHZ~9t~WZ9Bh8%%To1|&@C>R$K*5B6CIoCYFM+nxpfUs#v^=+?+kf$^WgKz zjp9G1xqJU9opZ zepuqw*~z{hg01m>gn4VpbYiN&Fu7{0W7%)FszXDLNr!-2C^@%(oC?T)Xq4Ev{=+i1 zjJ(CuUN}tJFSV~&c=5X*Nx+pXIr%O2$MQCi^OVR1OuhpyjLyYmmZEaZghM`g?;WPz z#54)BH}Ix?mbt9epIEfaY(yRuOnKtBrY*p8L_EMewZV|d_fyGr=kxoGou14t_aDR^ zjxC_;t=R4(=dc*9l)bmU9sFSvo@^LqOpjTIfFyoub7^wFa8s9&q~JN#eJ$30H+yo= z(2U98Jyy_fx~-$~zUcR8avd3aR94ma`EbZd;D%cYKY3-irVe-Db}m(XBQCw&dy?Qi zXK)|sEK529Wlw0{Z5ClvyXu zY-#2iVo`z%gU;Vmt`x;jx*ZnP@2M#zOS`EKZ=lhL9k=~gq+LEaiRJinTe({Q5!R9%Ck*d%XvKozc3+daB^& zWM}Y%f4dA^m>+Xs{1YhW>K{aAf}Dr+ETgYERGS9lhwbe_jOXTZ&&%(E!nQ7jevj5c zvU~4e%OIB&i^&KfZ|D82nWJ zU(JP86San#iN1y1`EAw6MJ0s(K}vp6ZQh^e3S`FeDlHGA(8H5Ycg6P)xTQ8w`2@q2 zJ&^V0P_B0rV!x>7dwU0DMDri59+i6Vuj?u=AF;R!j7LU2oO?nYD8j@>mqr&MUIT|P zP@z65vAtKk8Eq>Pt|TU_rFdWLmvP#S3z(owHRhzF9;vP>JzEPx3N{w&-Q%}5oIgA^ zg!e>S4i((%S|BF5#em?L=;Q18Zy_4%^Ni{$N5Sz)?|vM-X9MCDa^LqAS;8POMB`N? zD&ue$b7X`E2OY{ABxJtN1JMa6_Y`pW*&Oa|D5k+IH^Il3oFL+qwlvXDXVaS|o7The ztZYP}5!oxtm}}jib^2;>#$>Xue){9{h1MXoI?sJPe#jQ_Jv37(ws!MJLu|KWlmF?W z(#!mYajF`>G}^!2y|~4m_x1!O>xq+)2PY_KU!9C{^KN*g-ZKQ{hy2T!3{<7^ow%Ej%WU}>*m{eSt0QR3heEM={Lr;VGP+k`*=eY5 zHGO!Hb0LW-$F9x+TKnOem)R#VIK*lpvJi3ue~`-TYx(fS@A}mWf#zSPRRo?6%Y|Ls z`>FMV2}uep2gRIYOt*X#Y3!@lTRx~Oad28fz<=(X>Kfe$BV593`Ce=eqVJNU__F(| zCCDW1W8dX`+iy&o_E3F#h9QKU-X)cQ81V<)&-PF^&Q0|6SJlJ--{IL&&-s$Ab{)zn zSoaYrH~=NZa58(#>xifO;=pilwq)8UY4!vkx{S#M@wP-Qq`s?a1ti^Jj@Bz$8U*}# z%f|g$VRVh_A@qX>=4HP25oG9eUKtIvt9?H}lbh>pX}7I05tae{y!@TPC30wX`!u%4 z{U~luJS^2~{X+}O>vbEZT%s~7b0U%w82Jll9*eb%|v~TFqdd6H`*7Ps@Qm2dY|3C zD`ByR8C{BZ0U7t&ARK735LV=GqWSUQU>VK*mk+q3JYRWUCzGC`~(7vs{6W~wLyO3n6|D_W^@@i ze6X=2Su$U++y;bmP8Vbo|FJb#PrMeQwmO$1)WLe~pIhe7E1w1+#VPz1%&o@9JL#K} z$*a~tmU)*>iI|`!e3?n9j>FZ-f+(NMs2kHO()&4uAN?TyZ+5;13pD2Jq;KcKZRca9 z{@xkq9_c7Bm>xX8bM+`MkR{GNzLoCIUV?Jyz0=YfK_R6Yf$-BYzr##x6w13!3#hC! zfF$%Og8fD149VRA`iFy@X$@7`((?vkT@PRvl(c4x-A5J$)|_nG#WJqDdtnt@baIbA z*Ey==?8-vjyW+cT5ql%{U>khdY%vRiXgl;9UFCdR5JrQM?ci=!!+5Q1DOpIQ1f5tJ zoX}bzHy%wWQexfp;vLF3AgL!^lZ7mvgX{B8_dl^t;$3Kx(mhN$e?G}`J{ z26c6L*cx(W+_#S~tLaI$OSvK_!geMGGTyzFOW?fg_A}^L&2JU~9EWq|wq;(Ww-Mu! z=Qi2E&~Hk+=cwVx#=lHg)NjGvag+o4`tZgq`5|r6qFunDC+rI`c02av>2OV0$U&%X zZg&Th6G#WXiT`L-OxG){?P)wb7xrE9;CFh8TZ=ZWPc!vF!o#=2bbQ)rEnasv#krxe zNRY>?=H4Ayv&3R~ok0F1^X4ITs$3=Qzz>8TxN9`xKnqXtmzGEC~u(LUQ*TLu&sn>326~2SI$;a)H=f|7ZO^;D^MW8!#M@iT~H*<2PPcLro;FS22HMK3=;UoV3D< zp<7q(x0V*TU-{$|Gk0WuR@a9*>E#US>ZAQQo9X6&#>Mo;SF9p`IiZ7YfsjYz;?9gs zjxSX9S3)|EI`TsKuEfTqQZzrNb|2-1z9DAdR-Rp=43@XezP>Dag@bTW>XRF6X?f4v z@kyBEi~QQzgATgh7hT>32L$cGg>#7YOK(9eJ&MM2_!Uq4l1;g$@8Ir?AiaMnBNvVK zlVNSfv@>X+NIBSj_c_Mt>-Fd$Z&{Oi*LjY6 zwwr&snWdhipBu48*Bwd>HYic?t>K4_63QE#(b#>weZbi{`d(+w(ru)LM9~D2baSU& zlYLOdSK!I{Yb#TV0#d)9o2=nTY~<&$_Kuu0g}z3WlfJk6%V_EfKH1Z4t^KE zbxd|{)-a#-x5wC#szsN(&5uNu!+p`xKUu@EobBb?n7!ABpHFO@L%|T4&YYpiBLche zdPSbRy#vWi&k=7&cE?<`pDBlzm``lY((Tp?+U!uvRk@8TLHzrZGd~LSP`*5xsqy0Z z5V^I`9>`7i+FdP7c{xLU&zrE)LW~1}#JSY;Tsh2=UN=w&i%h%E>&w|k4)pBL z!Z2T;wbJ4=H~+PP^x=JaNzYVg4$@-9Y^+(tZOS@#?P z|3q-Zz8~p3H1eE_)|V=gW|T%nE!iPT<ne~;gbJ#mv))S&lTsXuq~})En&EbK9N{(R(QuO{ZEK=uI=TZG zD0lHV-TX&OPy~HAW~|JyVJGGQfNQ$hFMu*wylEKwV+u6zE_&DM-Qj4z5ps)dt~+S^xkWSAlt# zRwPFg_A$y~W#udAC{=w)JHy=^D}fwSziP~-do(%o0{?NqouDjLcwhiGFEeTP|JUO` z*fkDd*S|dYvt*93E8FWt2`TdJRP(kE{S0Sp&EFjw2mDgJDbQqJVKYd_BGTS!x=;43 zaGYz8zH+ZaNrH!^hAz7)>Ihh&##&t?|;o$r&0| zw)XUQEb{6x$dY2^a%-27LWM`1;Te&045r1&6B8HeDiD1VF!!o{fN+BeC6EWnZf9++ z6U)xSo>cYY3~u%-{o>t+%iGFv#z014%2iu!!to}X{r9tP2$mKGwUG`Lmm8EuF_J`O+dYzexs*GoJZv$-`02{6vXS?Y}S@NA{O$G4h^nXBb2(hri+D9)kMU_ z^SymalCWn-b7h{5Oep{)my*M+wpHJ?9g5Q<+Rcq!{62o&zbMNnd~yPFY4L2iS?h;U z5m(R|=dt+hvE|+?Es~xIVlVfh>m69TZyh1ksvOcbUdtJ3NF3Bf)i2qSch|lvQKY;FpgAs&pr0g_h0l{KKNmB4&-1n!q#bM zwPUk*lrKlKNf{#W{Iz*Y)fu0K?&Jyy*prHm>Xp)tapj zY-L8XZPjS!>v&#v+4#n2Yc0DX{&L-{8Oi01y!x1y7fJKw z()A9J5{s^@lfnvb=Rn%1O{F}MA9LtDDd9W~^urf(;f;}-^?tAqmrIKK3HlW_o*zte zDVw@CySyJB3S)uh+uc9P8eaePkiTL32_Gh;MTg?A~Bqt~pW5KrU!+Y}{Z)EilN)E-YGhr7WbS~)S&0=HBuR|$b=@?t2qN5yE zK^CbE6W-4bTWSuw^}W=*WAhA^%!}LG*-6gthXUzH+*m49lOi8pi{Lvo^6sw$`K2if zqD9HW@Ec8)=i}{U|MJmRhh$B0$IhhLMe&7esHoDRgtW1Ad_$ewP?0X5EY^{3m#@(a zb$tn*n3uMBc~49Hb$X_*c@gIYPuswz1Ut6HgulJ*`;L@$!Z;eEVytn~WA8=!FL@^H zpiFdO&&0MAo@)vw`})iUWP^Xf-u}k5NZ)?kKK#{E!Pf~jE=bJpEO#;Ndn*mtNt`(s zPVthCr7=|R{a-?QDaFIe)6ZyS*2`N1ZSfJp-El%N^*S-;or`>HGDzEKAq40ntrtBe zVM2_;GIr7OL#pp0jutqcDcsbA*BV1ZGn1bCD`?j9_97!uqRIICTdNJaf(T+79ihKVYj_z}x%f zK3Z?3?MvH6V3;Lmnyxs0$=ADMzA{i@>Do(=F1bZy!br$v@UfK(N6 zmI;3*=yr{hnXli?@L-Z3T}{7U*a~Al>mCROcE`ec7C`FuK|I3U7}lD=1elAb?&CG| z=10nj!d-(!R|G9Y5@+ii&kkP{`^`F8?%Z@q3xuQ|&8M5PS0&6Hi!}<%JGFa2MOP^^ zXc;$_Mt!s=;I4a&O-B#7IRFl&$f^c}3>WYu`@%w4Ut&mv{?WmDPnR7~nMY+g#|bM~ z%?_UB+tO?$AvZ1FE}uMghJz2me;l5e_e_=)<~0tKuOgosfNpQ#R>V;Wpb>qxaImv% zyFb?;i0OpHk)U;YjAxFk&VRx9rxt3f;2b*3*ZcqT=)d26{fY9a8WpFk*dI3L#wCiX zmp&(+N%i3{XhXRdIK_ne@S&mMn~8|)NA3@4O-gjvDsRku5Fgm+s@hULkn53D zU0z8X(hGzrbk#Tas?jo)ODDUD>~dnRSnn5|)TOk^FH3q(T!i>@HvgWcT1)+nK$+-g z>x5=N)020U-s)wqwFU0CQPy&^ATwf&H{S;h=w(ed!sp$FIEkQbWK=|HeQ@*!F zq~_whRS7XqT1@rcTYccBK>XIz5sg#rSYxaa2c6cHn!QR}@6(lXu-m&5%N%Y*x7a-H z#}ip(!C9xCdSm~oGPT9u@k9BkT_wt}aBo?Guu^1a&cNLdz9iKbY)6rg2OLl{JTS9< zzmm2^$5LtXM55thr;jsl2;m+qS;lMmR+;eT4;O=d(8*$O9czEVo1%GHpvvfCT75Y-AjUd{~yP;@qdC z&IcPQmWJ|*lXMBPhgY_D0Ucbusg^7@C`jC2NJVD?X4v->^#Zw|9ZeeMdh-4%uF(MsAnbSJ??vPf-*m7aCN#8>_A?JfY=f2ttVK zoo+xNe0Q|@5ctuG$j966SH4rLQFJ$slp++j?$`zV1D8Em0bEM%h(Yk{|GN!VXiX%O zuYZW5_(MzfLUZCXZ!~pVP8oKTUQl`FFIc!BcQc9Ru?d(%YY(}*ydk4@#c|(i=`Fpg z`lEL=8h<)c#Xfn4XjYNS)^9zl4C_^21+$LQ5we=;P1@@@@ zC*$r8MZ3?XF`mM4?2LOTAqqpDhnuNz$$aRCQYOxMISKcVw06u(R~M)L=y-zA_O^7L9ojzD?80#SdN9qk zXx6=%GPS-@b_xXA-O{;RiB{t1+s5l<=*a@C980IyXtZ=YS#M^>rQe9^#99p|2#upmmxh&;19^H**cCiaTI6TCmLmrAac3(W4hb9S7Q`94=tBZJ| zo*Pq)-hMXD>dxeuK@OA!Yq6dc+ujGxR2J APdZTxzG3TNUabD}XTm&N=wuN;F|U z(UH(eXMPlS9&+nUj1P!q?N6zhxtNM1*XTXRmc+8|0Vf}S)D zyq=X=w>J~q5aF4UDCJvg)1MV82BudB^(>P!Gsf?_iy&(*Q%(X_QJ)w|+Muwkd(dgAFVt0%ZRdRg66*cXa=xs-5Jc$VAqvS1~a4+@gmpWzY6SGFjwcBQB;}aeWppLg8cfG zTlreQD7i`LFT1mTXJy|08a@Lpi?<`Mk#tW5mmjvfrQ8qr@MN-Tt%0ukg66682IMJ?nw*uut>F5~ zLUKU03LO=V(atqgXxIXFAp1?TxTX4=kRqe}ccb+dPE%rVlQp~a6=^|>VjiRxiCtqb zU#B-6=2gMX5UVN9Qi$b5wlsD2FOO-K3(;{-C`YdBMc(JK-494kMRN0SPY!qP%ao`U zSs}jzHi6D2Aa=3^=3by*ktci^73Z)u-=$|A2chcPJa*^&G*9))lS+-wX)(r#ob#8B zx;pOxmbfixw8{~oOUNO%4!)x09s<7`mc6GF@Ckb{Cg3l=yYoHtnr}aM-HTx(4{JAF zkhe?%p3AmUj-q1)CC{QOLEjkjyBY)_5A?NpJxW`Cx8FuG1o_W}OsFyZ&beC`I}UWk3*2nNt79k$sHOMJUSyw5ElEWB#KT{R7OOO#ootf0g+v z)t_TqiqaXH`F&qmD4?m^_F(u1lR5kWtd8con3e)1{eE1}>@0JS3tgd-)R{wo5e4%m zyA5yoo9xr>wez5r57vMZrU`&drP%h*M@B3MqogvR1?Hyu9khLK6+T5Ftl2tbIWk)g zqUuA|6?BBMU7(yJZSwSI68%$s&V7s+6oC3(-$mtVmwDX?*C{Q<+h(!81pH$_p4qSK z!#4JIHFEvx`*`<^QDe{PMSaQED(QhgCvsp}>V}Hr5TAAO7-*!kEo!e3e`|bnw;%f% z{T;Z|?mJYc>%^wARxdl@%Uw-j%s4m2?QzBEZO_*Fh1LLvGNY85P<`6NudQW5TzzV= zd10J6OQQc2NgqF*IMi+Ch+{5K)rp0VRiaO0{VJzC`7q^!YPWAb)X6?V#fivY?-rV8 zq5tR?YgN)MRLT;~`f>*+zys|R$J3Q8cagmE(3A12HnG@l*48Z6y_`y_ceiv`FG5k` zxEsB%x@yyxQZog)t?k3z+gPBtagj@VAC?9B+pX7{=GNcr4)^_Nh{!WsaDxiy=6pIQ z2TtgC^iM+9zD#dtnw3=%WSz|UX2)2nRPmDP!e9JE*kzx&Xk8FBeHHT&!JtID|cMg5?X99m`95r4|#SNXdC}?%A7PX+O$eE3@p;p)+~}OC8A7l$%}Mm=24$ zaS03&n#9>i^grf=toCIFi|vlNlx?b|g>n#8;%7co{{D7*MHK277-|zykeunq$BXO} z)a{A5SP&WXA2{Ak*k1H}M^J{ao4CeA+D%@ftQr+e`m_s}8C!drTae36GoVMzKdEc< zsg}v5nhuwMuPw_%pg-hk=D%A`z4`n+4}@&781jXpDoirX$cx&)N4l`gf*2lHNo^Q7 z&YkshSdF&cF<-L0w${xCZK1+Ue}G6&-nKGW3{t^YCgSWM{F|g-NElb)QU6B2`#?(yxk9TeYW%DZ9L>!pKc&5EMmY!yzeG?bycFIWiwNEBi(>-92G|6DlMS|o z9aiGqGor+t-Tm>3yJ;(_3*0n=qcFVJe#!J_UzzVuvsC~I{Rzuqn6TO>uhb7D0VC@t z8-iHReUH4mo4(^oEFv`}J%&PoQb6b7<@OK&0*iEdr6rBwb9C%AjKai)L z|8RKkaBEe1g^i*bkiG#2_f5W>u&>{tSNg6;>jPqt-_A@nczcA#$Fhnnk?)+RO}%>O z+1n+MK|d4LSz(8La?fGx>0qJ3{f!T5hdpG=#~KVQ=h-0_cyfesUi0ymHWF_jAs~A` ze=b~p*bf8D35rU%de1HO-5_7J*4#r8ipn0b%5Qrr zXYBti*ZV-Mf^Vh@CH?#9pR@V_w@Fd9=wr&ji&LlePDs7Fn6du)MQZ*>F(V2jX(twl zUtt4}E=ooP{ZMbHQmn&0l#d3$qQF)iGJ1u}rSf!B=+%2q!05MT;(f;p z{WN`9tW(=&1n5&Z{uH2DCMhzW?PSWj*~qo>Ax zi))P=?LX~>?Tf<%p_CX<=kvy;FUSWyB8^`C<@1-!`Zr4|#*kI@s><)ky-)d%Tx=T+ z%nE4)nld11Z${!(uL=ljob~^vc80K=3s?VGK!TBDZ&W^_B52U*VF_q015H|9idiks z&gIQO>Lhz{v^RHQ$PJ?9OmSjGr3fy%tr2b^j29*u9JDD%E{!~2n48RP|FP=^ctdK- z&AXVc0jejw+0`qLrT~YaG2rVp#Z}nG?jPQRzcoRT1pOddbNxb!*7F&rRZ zmrTaqqRC?_&LvZAVdD1I4;J<9gVRt-Z|rTCdFA8czx96gu!UaD%Cpm|{h3_lBzMBI z@vHZ2tn6PfD<=pkEQfKaB!~zQSCtZF2Ub_8_8-L zYp`Sx<30uX7j(U0Lt!4A%NI#b6Mpyo|5AG}*zr13WutI8v}7+Z2{>ME4^RgW5+(~j z@;#ye8bKMLEehyN^Y$f*KtHQrW}z~Aj}+rIH;d$qaFYNBT)c7qRXgE8=tQ_Sq%M!%_mh`QsCjVZ&?O zs4w;irHaBQH4#Hn)-HJx^E;R|OqI^NSQF<(Wl}oHRrKYYH$I-q$o>O>Q_2%Q)6;MF zaQUIe3-I6KJH4hwm5DwoGR2Gt!7xv|7^ik>IqRLrSZSEp?o4>73$n;K18aV;3phsG zVHH*5R=Qpsw$gRaJNnw3sEglJc_3-5yK8EBei;)nqj-w~bGR7{a@rH=pn7libPDw= zqJp%Bi;R{Hwt=Qnafe^NMyCG|wDUz?P)bKxP&b*}j^vkrh3%o%?^sE5D=~6CJZ^d_ zn-yFf*BW+2txI#dh7DapEoQ;B7V+f(itb3eM|G~=9_COi85Rg)eYr97E#dr=HUHD+ z>fbAQt?o`DJ)#9|25#{6kaj20nYmiI5$=-Ls5Bt{naQW9E)3X(TlE-A3qJISQ+tC>o^+AyazeewNst8@5MLPoRN&%* z+!*tUJFP#2Fa~S}F%U2rBy-)R^A7*f;ezy0y!-h~805pn$Ysr{4JX*mU{s=_WZAcXg|9ojkF0I!Z_5vZvSkELetJ3M@kL(Lv7;zBU;V zzZ0dA!fFcoW#hWWFKc6}Xepau6K)gvmdRtigAV-{w)Wof^niAmo^m)}Q%Px|;C>|O zcG}Z2{JfKx|5Pl?wbd(k2tOX-ayE7+GA4l5yfaQE7!8jRUM5b@>hW`#QZ|wJMLV>! z^a6biOP-xBEOL6}2s$hNua^?NsJWz*NFh3ET)wvRzNXFUx`|tCkV;S9)LlcE{@!b1 z#rF2eG7>k_xQ;?9ZojLr%|rfbnvP4z(nRJP9YhpKaPxz$%lx_J*sh_Kh@4K<3FAiV zP2sRi7D2wRyn;(+e=n(|&JLl}o2K9Ek!`*DPt$ay07hBr6ztIg`k%_8Bi-~S)-rX+ zt_u)Sn)7PIfx~FTS{}X3x(LI%MgMDysV|EY>y5xgPmBf2~_Zw?i ze1-Ubef)Gn(Rn$gE#GTrNs;{5=Y9H_@)HJTOof?JoN_KXJf!Tj6Itn5SL)?IvZDb<)}(@xNYxbau0M zloH?XwEq0+Kuu>gGfhAGG?<*EheX zGV3e|eyuDcSiSG+bloZJm@cWm#MQl8WCNd-Qqv z>}Vyhk|o(tw{MrieNmHEq8Opp#orwu@#cP7$!}wj*+^< zb+i-9V^pci3Yk#63#wi_c^?!_tz&W04s#Nn4PKx#95(hT*`4% zHrv12A}fTPC*=VJ^M`&>1L|4?XV0EK5K%x=TOr&=A}{5m-xYZSj31hH^Xk$svht9`~N;;JZ7m*xiD)P^BYexQ) zolJ#!AB)_z66$}I!eeUxqdi4Ic9}}l<{y;BdX}O}all5u$2HAEv0`o ztUN0B`7p$6iMxw+?8|wrqbs)Jo?~FZ^R)vbXl-`Mvuppgq@#&JDd0^a+WgU9wj6+y zPbL1Y>~*&RjnNTKm+*vpwzr^UQKV+Js#_+#hItV%$W=w02M2p8(xN+QaWmkK*>^kp z7w;P!8~49QOD{p1`ruG^vEj>LOf4vXu9exlASO#LjJZf?9+i)7)bH2=vQL+C#NaHe z|CA$!q+=U70!)Nzfex(;smRq^mZRm?`l58#hugFXbAH|P0*W%l`xDiw$zlmpy5v{> z{S#8Y2haPp+Mg)S)&;n=sdnCG`saV$iNi$oVAhIV_@Cm=-;`dd%BvmMO4JkPzZt!R z2mERMhd4Qi9WG5$VE-()F9pztRiw+pHKl}H{p>i2bfO~3sr#m}Q5DW}?XK@{b+EGx zCg8n+x1*zI!HauxXJNFlI?C}NNb+|vp8`cq(1rS;E6|Y)8?Z)buVfmuuFD)y4bFAM zY64IZr7iOmG!3ZVHRJ9$>z+Vw$5s0F55S$1HYY#{dXD*|S-s$Kk8|dcd*4=760OYl zQ18{GH~!*FhI6Y9qn)D#3Rw4mCsrsCewzqj`fI$th+A3=;sB=WZzAZtlDXh^ZcKHW zv?JbcWWPhNES!VTRRYR#Z_pcp)917Pcmk3*!IRh3$ajy~&30HTahTVA~sxC zhq!$5Ls84_i=F$YS~+FGLF1(N@=USWShbTPj4alA1cqP{9W{2?yLhi>%6@B-d@8~h zX(=5uuK)~Weq;#xngjuP_y8z3_O@>{SNII8)jI?lqb|y<1MYd&Ch$c$5*%6;%Z*R# zUzYe{J!~7xE}gXIM}opc$5!vLXi$jmA6+)JnxVzs37|!?mN7%=~Fi-xEtp;+)8A3v?q9cXeBtTte~;s*3Ue z2{{U!^g1ETVy-zu0>@sVIzv#e{!^pMPCTMhc&0ezb`kmWdkyWdEW}6VmMV|{)!)h+ z<6mwC1RC)Iywdi?zZi7oy0E>nBL%p2S;`H{rc}Nca*AGN?N4z?*yDERuPp?eDXIu?5P&Nw9a_7`Po;ov@Y(L_ zv0;>cI+91`#V-H#^4i0LHuObi?6v+Vty1rvcdcmcNx8l7 ztu<*@30VE!`>-}9{#0Qe*v10O=zBG2*s_0ab-BlK)}{bA3gS^Q0`mt?4}XH?7$ z894Hlne44kk5&L=j9JkyO+JRE!1N{1FD(&Q(8%g<(uQn-%30yX_J2i2GAw)I0qE{+ z9|8LD;CxqNMLCkZpB=GV-YvxpU{VYh_Vr%r*iknU*6v15yF{tf03cNV3h4e_=(_fS zQlkCsJwr#)oY>X!NST{>abN2WzXEQPzy79P|5nsqKVes|%z4&~urUg2_U%y~zzhNfm6~td3U3ylARsuK`V~rfuki5l4>}%CS z(UWRcOAO~d+Co}S4bQa-CoX(F>#ruEb9DPCq^R{w<-)GO<-G6bJzO_B0Ap%`NzpgD zm#2GAc6TIyq-Q}}}?N+L{>@RUy_TQ&LNFul+z z|Ea49o!Lc;AmUCzF7|3 ze|Ff4=imhY5y+g)SWEs z>;+sOY&{`Rz{3pN~xH@Ig2R#8!Vi5=t=+f1FNB zi8kC$8@jMKEGwW!^ZaY9qlz{xNXU2k_ty)XT}R|)wVFOaGo7E@wm|qCet)h@u3(<2 zPL)o~zNI~Sl|f-=k?;o3)07 zT%~SNJ;~km@ugNZi@UtMhwu99Ov%F6gwVrIjGY$qs!co%h0@dzpgP~AMB8F63Y9fr?Q7+P)1sMN-NNZV1{6KCw4yi`Kp_ z=Bf@Xu$oj%FCP599C9W7D4Y@f`*S3hO5gW(0A+Fk&==7%xcHL$ojHyu`T(VBHt{zE$~{E-GImT-O0IE!Z8aH48R`WOUr#=V)+`X`V3vsCCQo~#W_Sb|^fC1-eTYv{G?#=}jeHMnB#CosS=a0?$H zO-Z{A#<0$E?$&p~D`#87b~~lKwypTafhLikL1x9UJ$h&5nJ8pE(;kCjeF?62b&qEJ z)xs9|dyOFlN%ow(B(IyJF5?RjoXmTeiadpCDy|gaOfN|DPfGSd60ib&0Sc}C|9d>2 zc+E=(JP@*RmrnoTNJKe5D!3--_FtmFow4re_&Av#<+BOK2GnM`S@7~4AHM}NW`BF! z@?~>6X6q3vG}vdoiOM>fJD!#@JM=@y6}lG(cUa1?j~v?U1yL6cedB_@aOwSbGc~*o zl7VN#C|v!1@a-nVzPfYv?`BgwUu!7ER0eh(jSx1t?(<+7-gw<3Cw*=bJ;>bntO9WQ zeSzFeg>tX*4C=D&=pUC-Q(`LBIh zR@*A>Yq&PEor@#+T16S;gC)L6G5GE3xho$>6bFo;df7G|{poAUd+uFVadnhf0p-7z z5~b;7iuYa=CJa^(DjmH|o)B9uK-X|mE9KgRNNTP+=3&)*CHMvy6Z>VG7#R=2a9*u0 zlLE6N)+@d!ie+VPB2b1KQ$q3VUmbgwMydvx6=A2T_`ElSByG}z*6$a^Ew_VF6@Y98 zAB@3o@H{)u9c)n4IHDamJ`c>9huMCTzANeg-##kKRH5F#7uBGv}}FJ>EKh3lbxo2%JuK*WfJ&!w4iNe2u^) zSGg(2BCC$yF~ImW90N^@H$j%1Ue2YH;2a;kAinZxt`6KLY^2u=@#j_>I{K*{eM>uP zgr2}XW0_5&yN(t0keZ9qY`&~;@QN~NtZF5;Uwyt!ugb6_QO&>O1~qLhZ|V-wltXnoM~_2 zm*S<7jibQK_r!QJd?wS*^)hj8MvKSj&zf^tP|)xmgC;ODre% z(;14K_`ZokDR$cjwEo^7ab93#uJfA>P_J^Obp^lECnWL0%>AM}k7nRIS!AUa<}P;N#Q6+EZ)CLf@Nx^If!jIvvA+YGf#W`KT}5 z6lH{#xYt*80m>t0A4`&w>{(Y4&~P9koc!W{`gR(Tj5H!Sor_cXxZd0bo_}TQM67Xc z&zjUFmg02RV0A+nL2QegUb!gls6J1p;(d%?Y_i9b=FT1|QGv!uo1QHFMu4KW8T5mH zVnZJDhC~iR2?_9pB3-#KDem1M_>rpi5VxZ;|1~N*_i?d`-A+r;?uqSMjl%g7i3OI- zxrpyjsDE98KxZ6ti zcs)N{Z)ZPldI@`M^lOa?_Jqu(~ z?|nw^lj+8aFv2ld8HAtsxrTt2Nm=@8A~*#5thiw{fRh z*@stNcl{|dDvBXCp}U;P5lZ~M?X)@oJyie(A<|LU^q$qvPj_{MC!y?*_vWeDAu+r8 z7EuV4&#@zXKSto$S}=d@5A$F+gBszQ*g(T$iN%b_fm*j^i84M!qahw#SEMgV*RT)f zGn_InvP1lU^RMD=z# z_2dL)J#}2L@S0ZAKb>~RcnlPgFAA@A$|KJZ|7g;QCQGfhW30g3Mmh{u2Kho&fEJaw#S=4e6sSG(HZdk{hC;7 zhqG?=TFPoYx~pu*_ZL0)H_2796AVa;zyS7Q zaQwb;E}Vuxt+%EpOfzf(8C(nK(P+4W+YlR31}21)c;g@|V)ZyP=EqOiRVK+_UT$Du zjSlY=v%nx()o~|~d*x$LH4kG$&b-9#$J(6)r6|ZVdvQ32KyRQ*xZ|86!(fZ)eIBSC zfBZ)E{FcRNvA;=)TH0SY`{F9PLjBeB`-qoMeT5bf)P(!H%ek`d47~&m`-=mcS#-(? zu$Q@NFemC%pdTpj#Q-2Uk|U1RY;L)dtJD|#!f)u;ovT#bNUY;{TFnsu;@2|O)ttv; zWHnBWT<_FLBi|K4zc};#>)u$HJ-xwmnwNgfKjGrvE<>@C-Y%&v_n<|%By%3}Hr9VZ z5`PDnE2uUDsW?*MZIVaj-HK^X&k0_!g%|LL*EXzXgSk0E!B^|lSQRjonY&fLnk;nT zS!B7vsw0%9gT!w(eQa0&Q_-p+RH_c8lf_LJmcZcgMuigPE`i1L#XQ3u;+&+aii8;l ztY*X)nCJ5!i`$1rc+M-da{7Fa7hp6CiA3@Plgb|k@$NB$h?z6}elPgP&r5pkaRUW< zWi8?{D0=QZUUk0Y7t^8X~Qt!zd2eZg#lY{L=a0h_4 z4bW1l5q01yt-<5_7>3B*$>QAbC9cT!Xda%8UIrc=4)Tpp{SO4~0IG$!VTu; z7H!gtqafXztqgl}?_MpUIR$yXs{gY&jDnnW`K%4IFys3B82XRt@%ThyWe1eGV6&XX zpZ9};9w5WQq&h9*m@p~kpkqwY(RGlrMIm#q3EQay;^V{jyCxW~`S6RUWoZ&`^{LR7 z0z-lzP%75|AF^f*^EXlBJ?+t#j=(zw+FR4cO;4XPHZ#@<_`7dBr=h{$eo1Dn`@%_` z2k-KL=tu9bj}eyTgv1;)!0p?>hc+c>c7~hM4n}r8`>@Lg_O8M{1jxGKs$U5z#7e3> zl~l|X@U`&!pKh(!mtKwwzV0^i*!MIqu(QC9jzXQf$R%O2zwrf1Eq$=fax@jTQqoF# zr+-rv~_@XYud+kR)0ANmsGZ=!`Rp4K9+c)d@?F}pK z^!mhp&3t5g^kj%_#%!VI5+$*Mtyg5@kTEr3J*V@ zLJM;Tzevsy;XlnW)l~nS%i^!I|InFVKVdcDFIQ}`u>1GL7soa7xgua+vnbmx{&~NK zi?!Ffacl4Q*L|8qYdswtlW>ck?w1}d`FXhqFogUiYIM%Un+Kx37b|Rsb-=DH(Qojo zKrnpn0bZcc5E?z$)by4pQ~QnDFAz%5bv2ml#m?o8|2=onHoDc-cjfn-2U z>-~Ot-G2YPUZ``P*Ynzs>v6xXYY;l$c%)sDD+->=<^^7I^rK0$NZ%I?^*(fE#D(zZ znf0|KH`OI;v1})q9P(`1;XcnN<*&vvMOiELo~G5+bRQbzwd?}LDEnL38Pcr(^2t67FYFD0k* zz!V_bE3L2r=dbHY8^LUZkL}RIf0`!zb8>|ZU%fe}Zd%R0-3qC_LEk>I<7N^nhVn75 zLTcQz60P$n4L>6VW76T~edcqmShVt28ZxKa^Ll&woHM`5aG$Dq&C)DLJ=L19G%X2F zzIUVV@!`;u(-r6+^M@t)PZg}pUN*s5UoFTTX3b-1tzVZN@`FD*n*Dq7t zhx%K3#)m3L5g3rEd^m60LVFA}(^^!AiYPsEAz8ZVcNr>ib>(sc5*LTH;?<8Izw&u% zsF^hW;Pv;UETM~Yfw&e{v*d-N?4O5Wy#?<=k$&#wL4UqvH9%k}>zFF4Ssd}oTH<8& z?nF?tKXZBl1oZ|R6Lx4X>Yjg+wx>Q1FgYio9Zx`OE~}>hDoi9)1Dq7a75NvC8*(Wf z=q#9Nm$nV#_&5PK=#)dJS(S`#Ej1=+QK^R0 zvbU$BZaHk$9MaN1{3-b3ULCn*IyP%Shp1Ns?A8DzbCBCP?t7k`b90-4iooBr8SJ2$cuGv7QHoL?aw6S-nv=@xs> zxIMJ~8d)f*_!T-D;!C?cwNxCC*C0PX^Oug+ifT@f+QnOFB*gmD^YPqt zbG8_WZq!@x$f$0Q-Gi3?EdFz>YjE+CR6@byk$8*7#0cyUe_?g>Rq^RuwIuz?vpUk8 z9mO89msV7*kf|tn!~CBuS8ip$h`;BkpKwxU+V6VZ>9U+RXP%XcS*0F2_}mS;IbvID z1ITtwH6+0Og67SV{=en|0A})dMjafUPRzzk1|3#oP)Iboa+Z3|e>eL%db?E2PQ@tR zdv_Hty2BiqoR-#0^TXF3k<~{xu+0!g<%}a4$g-|7wVvN|Fx4O;L+cr>qh!BrrrrbJ zn>-aC+exN|xDJ24Z1jk|x|FJEYtKykqI^lb!TIyLoS?h~vef^U1(gM)VXxA>GABsHu_spC5A2GZ>A@3@dqVr_*=-Aes zrPqy+Hsu+A;lwiuN8W^}N_NGTNpLUsY6VXKem+>_W1--iu?m(PjpL8r#9xl_Co`fp zlAiTyB1>i;%>MN9RSk6Of8JB?{Zf9;i-st95@xGp$?ofam(vC#21Mbu8A`Vx9hyE)IQ=O5CJj>>AF}gv-pr_ofk5l-A zL3<1K`g44R!I?&)SAS@8*2@4G$@6EpGLq39JbAOl1*T*qgg^=O=ZpZ&9nJRU$)BIa z+1f9`9bxy^0L*>GEv@kye2oRJGuK;Yp~aq3MfF*9yW2!fyjfMS68i19>h&;ox?rBS zmQ9KEl^h3CeGm1$_B`AxeYyADVYDVSsq%_?tQuSW(WATUuD?byImq3nj$D$w|1Fmt z+u=MAPU|V5wv6e7u~|_h+jqsr1hOAYRd*_-6u($&r}Ijg!5TcQ~{&FJ~tecNje9QjJJFe0bMnNHR{lGDLpMD8Luu!EJF4^M0pr7Ux?5+}=Y* zX=G-Bq1)Koj0()>fRUmVIW``-sfII+hOR$j24SYbVSejC+OrFAPHcoLO|uJQ$hE(+ z0-y|)MuS9@%DH!vzBRmQ>;{SCT$7n$4zv#*keB=xb*-9X*M&!36$`JtALHv8f6d_V zxc$(;%lGQpJIY_;=-MB7c0vlL{31bw4!Ht2MH34M8Y&i6x9T+hAwP`3$A}P}>J%wdl*l-x!9v!M&Oam+xV%!Io|y2=B7}FASKWl>r%T?qvUA@jTM@iNP4)-b zsq6PsrFUz-jkwUE=|ZPKO}8UY#is#KK|gLY86NxjT);;|Fke4D(tr^T<)A%_vG9}H!thQCVXUz3B-t zlV@i)OKJgK$)Iy$_7znK&94Qv)oeQpnoBFPEJd~uGXmW!?)rgfvUl)U7j+L4NF0Yj}0#tL$x|U*S_T#(RvwKaYQ58UaS!EaT&{hZ7P^8iT;IVynl1 z>wAQ4JMouf?V-QGm(Q!g9Nydf`NYA!*Vd~Qt5-_B&}^dFn|X%q|2aBDNkCap@PkKm zBf=;pLa}JDSqVo}1Hu7)qB8p$6aB6Y%cUduu;c17E~X;@*U)V^M$dUXA@z;0=aNBx`oYusMG)EDmyx4TKfrQ7LVR+EVy2I)H!h?qX6ls14s(H64Xm8)DwiIUFrmo|?NSYEgyt2vb7OL8-0K9RmnGQSl zz=&&ri8s~50IGM4w%KMn`?y9ov;}d2N4)APo;pr_iOe5^6gUQzPfI$&TOLqAV`1_EV{08(8hPj9hzgD%~g3dEeiMhO&rF2 z{?${d`J*$oYVo3q&tuA-;0>zMeRYDT5-Ly~`74rwyHD}Bs~FjUt7WN5KX>py_)6gk2l;TJlGrBeJj8*yn4?gI4k?Rtz><>ej9cn~|>YJ2*z$%f9Ada68b| zx$1(0Q76{E0-r`(7ZFnLK6p?CRP76yQ~r$L^w|CB9n^@L;FNY8F4-f?B0g1cEKJ<_ zwtZnUa)fIe{m$%n_!fQ@U(hIWbk~p1A#w9d033c9Y2Q!_^N5)97$>qXg9<1f$b1?% zhKrKb>n>y|lUsc#j||FTu%SLevA^wnu@{j~^S99KcR#K=5CHoQ;?JG<;cJb_cwMfXM+W?BTfK#8jn z#v;Fvau`&oMf5&q%w@#3D{S_G;a z2ZT;SJ2chV*rc;O+ULr zkflB~*l-$Zd}{Q2A8JhvHJ*Z^^NA^mq*sq6ew@#=d#jIrCQ0YlKW{h(7;%fm0`a&{ zudk>J*YO51sR=RKABy;jlMXPC%qu=39L4C`(*#SO#(<4{2m9j3L#U8tE`fGAxi16JrQt z%a<2;%gZMA3)JHw4be{@W8R$sNmxH#f({FXv%_0@tylnw(|?vGYXf9;uU9eT;34S69yz#{1&*s0y9M+Y zDQ2uEg=$Xdi~%z;p;D3EDD1m^M1hXFKH{j4&su1Nx5{I3{Pl_zSL!`iJEuB{TStlP zJ+Pl|VtwiN!n~k!&NatZ^F_#a&vF+pd^#AORWJA}q33RRO&=7NRy<7(ahMcUP_xwy z@Cc1?fc0N0K>vg>IG2xg!uSRaSj&(gx#OpQb!Y35VT1aL)b&&HHYU%2D!jKm0!zt_` zrDG6DARZNGh{&DJQhyLhD6e^qvHXY1)l3K*-L=***Gc^LCowpw^qXY#3Z0&CA#s{X z*(7nDE;Lv1!kHI0H=GFKsr|$eZsx1JmBN(WFJ=igyL45sopc)`)~R0gAR+}Zf@MlU z(-YcvE$J8dkDi33(W^9pvdsOcJ{h+@2LtQ31AMW0ib5-*y6+x(O@z+|FFDFw>3k-m|MQZm&Wy-6F1YuQkz*rK2nB z5F^1lkJ0X{I{enTBc1qx zX9a-F7zA^<{e6fG$?%`yM&V919?br+{k5h2%<+FErUFD0k9O)E`b$fRK;%2$wgpQ8 z`#<73-NXZM64y>WPBi~pD}OHf9!HD*2<|83qc*uI=lTl^1EnwI)7ZJ!{=Vkz{2|FY zn99g>f*G9hK9r-xj-PP-Lz&;gy?S<#M?uTtz5$Z#;5$-35KTs2u#>}BZhv@l3o^0` zF&wafjDeUA-G>v%kKfSP7BU~jR`21qfS5>1q-95u^G$x9YR$FdnB|N=P(6!?R5N-{ z3)bDD$oYL;LL!L2ydTMmT7S%{P4=TRc6f_q(@)^A;;8*kU?mN!heUr0k1!Qjm3J|W zmafSyX~?0BXj%6W?`VL3k7Ca9lB{bw->M=y{H2K2poobP%!($r*AFpbcXU~{!QZj3TblMwItn>Y zr`}TfxbC&jp7fe|xmC(CTIW~K1MC3L6I}Tm3OYC@R6_WzX{a+-EYff7hp2K23vJM~ zK;c0BHuHwHjwmdT6smv!t8d$)O4cdFU@q2H@ib*3-Fgp6hz9cP&?VHj`_-TRtp;9v zK)M}w*A*$r+=&s^T=x+u5V-j;w{Zg^*$p8R+-M+j_rGFmfZEb^uF*XEdH@a-ksAJZ zfCWx_u@WF%3$?#S`Sd9FzV%OmbDpc_r%XtrS(kADoD?SYZe3=9zvH!09~^t24UMw; z`G+Te8)2$1?0UF`paxQ=xq9lj%X%oR21xjU27UjsUwH@&X`?84W+_YQi#MmO8}0}# ziYx|yggc1Jhsyj7il$W&;EhpjZZfulH0!UcbPK4uZELQq0Yo8R9G}6$<#Qe&(f?;O ziK^=t%HW{$Km_+fll;6NOu`g#`}58{(Q+U%}`d}s^G1fi(z#)?yR?cex2h5QSL zw6(nc4;E!?xnOl*QwNj|2c+E9XLAv>VsC`k)s^zaB{cF9)HIzw#>1qx7KrEALV!e| zzb7pfvuFJj+sX~vzem6AG(9N4Ju1Jba@kAeW(gToo2>l&c!))q)?(QfIkhi{=kTuO zKSoAK#DeRnZY~a8_re(HJ$tG1$n+HESKme+jQBQVz2l|uFd`^rp23nFE-Kbtjw&F3Q_5qPAM!9&G5#wbxEGKg0^Ge9ssz1rPwB9^_ zmlDZSPkm5{r9k!1^Zc0iUlj!Ma%F*DlJdso=>NzK`A5(R1S-jl>P{8x;{kA)|_7GjVLl@o0`eH+e?s5_JEX7sR z|CL*=*`x?Ni1GG4gHROQl16j>FITd+Ie+ z)`7KzXKcb9x#jw)#tMbOuN%N3%KVC9B13iV?3ZUd>CG?lWByL%&We05@jJ^Nm2~fH z#$qYmh8ce3=v*w?i7t72ASpWOS9gIqf&_nlia1br6x;7i+`6yw)3(*`K+MrCzm8dX zVciy-*@fTcmLtGj1534&h@>#eoiK}2c%XZw@)P6HOirc0OHCARo_ruI4RKiXbc-m% zMnuK>u@Vie)Zj25Iymk;UJtXYq~3+7NKvA%aWEHr(@D(58Jk7JqG;6}} zGBcmB^V(4D&f~`N15B@=z=|YXSCS5`+BJ@c0Nr0I8nJ36Pi~F;ltkIlpd^t37uJ?O z+w0bH^ve3Em-H?qwLkg^>+j>mikQt6_w{j%V3^&?#dDtfG2Tlr)K=s5n$-Xg#}KV# zNZFaO3&nXHpXb@LV1cRvvSZ1>C38gbGOpd6bdg=07#nSUzwT+^^2A88`4OPY16>{| zyTkX~#>l{c_kNkhq5C^kL^6#3Rx8QRcON{Y1T)1>`q$H7&#bEu_Sgfji4`*}I;8R; zR{9r-E8RqR`EXl>CZ@~_-1CdvVeZu(20MrhG3A|P1hO@GLu0-i%YPd4c}}CE!-uM2 z!fYJebbrlc=tCo3TpbO7spo^uDK;NUkJ5c_Iri#S=-(PRd&FSfWH(1t(u31UNjYoQ z32(YcCb42fqF`%xa`d9;uVTNC9Ob!`--*JZwsTcAjZPUuHj1SOQW?HDsa{)s*(hOz zmv5}tlhzMQbZ7ztRQLMyEn!I7fp|{ADbNTJcHwjHu=d-RUz+LEke_`XP0gtYMs)7b z;ln%q>eod+O6Z=3W4zkw2YYS{piynQyhp0=C)Ry09;br(u<}3wtB?64+O{F^)nN7m z5&HS;i%L*szI+0t{z-r40VQ~FuUlJ$(DpJeXP_JbpD6S35@QX#b*g1u?C+?F1e9z6 z7S{MNM%iHK)T*tI?nyoOo<;+X*Y?{_Ug_LL*+v)k_vuUTE3)K+xFK{#=KYS>{;P>M z@}!5`i3(S$=G|_gevv&+O$|vHwl?l#f+YDlJGi8niFlMUWc>QH5S`<@LWb5H7y%99 z-%h(`Ra?;aX`rm$i&WEWc0Z->EmNfV&Lo zJ~uNvdnNw1@5X2uy6n}{JU5TJ_8>ZA>h!i?Lg)qy@xI{VSznnIH4G@XtO0J;snA9= zpuBS5Z31Ws_$J>W&vYad^X!2rIV+D(U5}Cnkti8+n0zBjh84f>cd>`HBU*e~$^3eO z>ByO&m;+~e81M`=x!JoM@66o2>ELtXZ`~+ct=UCAezJ>}T=oWUMK-iD=4kQaN~rb+ zFJbbvgkkL!IFVDH_M2V8yHRhC;UoHQDQwII$n#Vl3EIj4H0L6L{j3{D9hBDL4c-wW zf%C?E+r3oYB{PgaQUCCfCm4U?hi{Fyd8}M~HZk z(~_51mX))lwlFa(hJvN8hpTAa>6=Ek9PMS?BaKPT_XbC7o$EKzu)Ve8BwvMnzxA z)*;|MRFnvJn8jggfo2>G(a@6}E2C8!o;zpiZKh*->uN@HSK6Mxjcr$HaohGn^5L?# zJ>hubUpHhJsB|Xz$VEPdIE1*jHNJb{F-WR_ojV2?y530OJc&;414Lc$SR_?g*`i9Z z`nyp)81To>E{fb)uY=LC5agiJHLZQ)aji~(Kr`zM)L@m~k}hZPE0;su*x#tn`ja)#CkUkUyg>CIEM0z`0|W9v>3fXYMpx&j$7ow-Vf;U%&XCc?ab=~z@VPl zLu?m8VX|qfky3zHE+e1h7RGIayXa}EM{*(WGZ(UXG;UBIaH)LA%fvkwdj*EoBa5FZ zbEctwsmbTsSxhhwnS;%?dwEk7Z!uWFz>oUMsd;P`0-%G%y~i-VMbNaCF(kkt2f$@j zrMv>|>yqLCxyjH8I(>xdMeeRD9_BSCtCk3Nams0J3VG|X%;!i{mYL31{wk&-MO=P$ zdZLYNQ+)rc(4OwOQNO}xDORkr<>`s4Szm^Fvc4>cQe0AdCW{p&!#RE2sygaLx^a-~ zgjl~^ECLa`*w8f1tl-Xuj5~=vF&zew{GjWGA}sU{TzWG-N{cJNgH%8KI^ zq63ED<&P&amTL-?B)H+*UOQM$Rj_(q=dBD9WA^TZn-L=zl4z%E*&^_#ZOA<^@+`~|FOMa%w)@+U)@exXlE+ftZ#pD{t}2e(s@+%6d>+apP}hp}+@IS+j+IL><>vSlIW;Sk;< z9?Lji<_RMQ3Om&dLOzwT$nC7bC=0B+q;7WO53T+QQyH6P8T`Vj|NTdvy+EP9`d39$ zitELhzS`CiQ!6cbv^iD%Z>Sb4j1L@P{H&dRN1#uLlk4NbR*#Ek*^^2a4?CUOsmK#! zb?RWc;-2)w>Cbs+IP=n;|Jbjt%TK#s-js1-X{D&vb9n!ZYlMB|fLyKp%tB#GNVCBQ z$&Nnv!kI54X9o6n@GscXwgtO+4n5v()$?Y7BELMyA<}L9J==_RETI!->-s`VoUEj0 zpQ!~v#!LWnOaYTfD4}J~AZI8!?+uJ?V}aJw$F|e07jCG!51uiJ3DVpv<8e=sfeg|k z{YG~S&PX?$Q=^6!CCmU}_kR(&Fo z7BANlH;sxB(V6~|&zJmob*U?Uh`e{eB(Z=*B z{bkq58~jyr4PI9{r<&wwT6S{w6Q|gjwFC0)Kw2JjEZ%5neTw#0mFT+ud{`pjtSgMK zon*`Gf(iZ<54cr_&-8oCq~1MPna=MPE!(#?XOrlER99H#V%tfaJgH^g z_KU)sS9kwUCjZ>iNzy+psioVdi&8d&n5%Fx8Cp0;jBT9_C@ILZ^c3fchqQ|38*SgQ z-Qc*&mz;CfX?bpd^lN4bi8rfr?>%9_2tFTXBqParXHT=puZl9%BX52yi{piut& zV8R?=*Ac3pJbC=0kT)kQvx#2Ya#j3zOHA*8QBwWhr2k3gW_^j;gK+rXOO2OI9Jc2a zE()%M`;V9kJB3MQ@Wv&?eJ^21mSJ_01z_KsAFZ!SA6q6rn*9mfyf*ySn79O%`J)m0`ysy$sip3kbbmTy-BWKkIDMyrCS*zNQhMDS8JC zFLki({!@A#5PDw^9I4VZ!X?wlyuwL@tQZEhcj)#Q+s1u~7r(aRtLPQx^@&!0XT zEsuxXG?ED{TKGCb(s-)`?fp_UlI6&4#(NEO9~=w!SHsjvHHYc!3Fw|+ zma^!8y_gSuMOt$+c5geWnxjOH=ia$Pk)?VG$cFgs!i+>WZr`D#Y{Ss~7fy~$6AZU; zVclRC6NkfFJA2sENvZxeDx1}|n8QgJ%{W((W*r_rnW z`%Qwdn4i!i6?^Cp>CFfLdi4hMFCKR#-*z>qbA05BfKKow+1u73A&sNO#(C52*=DA1hxJHJy$!a}+To$(8P^J`2x8XImxh(7nl)2wPdo3JU zv;6k5?ptm#HC#@&xy39Aq0>bF(QYM#hhI7FMmjp2>6i-or!H;H{}D(iatOI4o$*7* z2q`H>0Zl|R_> zSl}J0A@|8Ap$D$OSUZy{f$S6fJqxpQ_&^Kd5;$_Gp7z+qhiogyzol|sK(^FAFTA(s zs4w(f7o_HEj`E70z~yk%FAjJQwc-R-u5zxbu)&_Y)w!=`|3e=Uk5v|OT1WFR_by^vDMw#@M>JCx)wylx*i5$EiSj8&&sL&Rp{FPF2)XQ|S~HTSBr)nGl`xk4AsI zs-6Cv0BjY}e?p}#H(E@*6fFDX4gj02Bj<-cWR7sUM__CXvYWKZVKU;{cwElb^A{hln)pxL-AMb)Lt&Zs)(qmGhFO9b z{kx9hAMRnk3KVbjKA44sSCI^C{ruu}35lU;#RnL-+qV)R~ZJw%pY9^p26jrBw!MVM9kaVO|K zd~i~e8RG$Uru*sLxnXcTIjt$sahp|MF3twBboyI1TO&{RpuLr8YCJy}8NK$%La*5` z9R>LJZUeVJ^pmUam+`nbT_?C^FXm(4HPj(@PlI5y5y7D=r%z7oxt`SO{glLz)qS!) zwTwoYqr3xhk^3iEJZ8JzPXlIGs?~7$eDobLrD+4luMSn>%|E7~iT~rvuP_iNUfTmw z6B2T?mW&EzhnnqfzPw4N<7?#dV~_Pas{he>U_E$FV`tAR_zAMoFjg)Y^?4U_-g%zr z%T4n6`5U0qbf$2w#)hk0SuppU(_q|77grA$LB{cUfdZ}iXdh>*ctB8?_3OCoMBM_3 zmBopL27BPNCV!!Z+gakR-h2@+d~JAgf`gK!BUW?2Ed(%h=YM19tH#5t7T8GeG+@K% zqmH34l&agZj{B67iLGfwOP<~8ZA2Eu!py+8O&h|YQZ^~2i60vxz93Zt3_QrFk8Jfogy@7;@(POrh zl`E2p4zt{t;t}+Nwc-T-5KLg&o%L<<`=`>6%0l4}Sv#oIuky`d&{VFB4T)afLptAI z_dHsoO`GR#bpeCN5Bfi*6pO3#M;QrWYWqrwmI~l5@>((Hwdd83IfsF#qlccpMIA{`XW~s9pr}g zCY92=^I33{hV~8^FAZDm`8UjzAw-jV+s_%}mzVB9R-|!_i@Q%uaBqvDXye{dCf9CfE#u%+}wyA~}bpic&NrQL$rFitS_Jy#fA z@E8;W#H%A@^Sa0Sn04PD#pNtkADD44mkE|_?z|s^S=G=wJJejRc7=o5jX(EPcy7$L zs}7xE7IbLAR!*Yp{pF;3+0(ithLJ9VajCucmAQt^2=CP{;Up}OEi=s> zT~>K;R-D+@K7b~7Q*Pc}yGBp(LBirL>n?_rKWFh4LNL}Zfmq%M`z7co)`h{A zw(-}O?c{8fQJLHG3zz4IOnUB!pZuZRW1LFpJk7i^-(2Jii->QWiatUgthcx5n{#HP zCI!rQv}38 zz9{b@z2*5H*)^NHYxdr47v|sCpDrpooj*(m8=A*il};s=8h3olQ^7dA4-Kv^2!&Lm z4BONdS7UnH5!|D|Y?TDjhkx$huiPv)$xZ!|1Q!1FdLcK__2d%*g9nIE4%F`qdb%^q zudRLMH@>^o6${qWWdG((_z5{uqxKYUE_=R9w+cHi%E8)_puAV@DH?Mn2ERQ2v25r` z{946_j{<|v9&fD|`_nLm{boTBx}Y;%ffW8wY>|P5AIe$VH}Qc-3x%eWI8Oy`YB(*3*?lB=cC}57}K zh1Vj-pv8YkC9@-(y=X%?C)eI?Q19}`dZLbwwy2)ZX-@M`|(s$mP3qM*XSQ&tLWkNFTvHl)|X4lgALV2z>lTS0Z-7Fhk+$!+Z&U+aR@ z8aU}=)llfyr{T<+;Hh^d0(rl9sI2xhvY!9r$^>GDg#H*Ab2Jx3`MwRSdta@sRe2tni*qLFKchH)j{xi+J5`d?{f2(YGc9IsSwgU{} z!`#z4T7Iu%o;waaK|aKU_;_Z$%(g$Hb5+?1SE+w< zVS@6+ZL3F46$X%)iuJ9*f8)X!=r`M$b$vqNdBnxy6UY#UYx!jQ-xymG+g&vF^}fv5 zPiRboBIuW>;JEJU)sBD=FhQ>{lj+#Ma5e`Nf8#B0^OYb(zwiqPwbPb`41ZY2SQYRc z>~FmFQ_hh>gcL=Lga^{eqdWeM$fPiv!$WhIf6_5TzrGzt!o$to4Qn3l&y>t~_P6kG z!;_$iLd@!l4-y{yS%x_Ng^>wg{4G2v7zOTLrR*y&NG$IGKIPx&7vVRLKy_sN1%Rt+=44#;V9Gc{<;oPe8L8R(dduAHH4A+=Ui9eLzmOXd z${iiSPxVt4Msa)%(rwT~a)wc8Q|>KQ37pBDpIuj6Kh#{uiM{{o1>{hkd#TvIz`S?| zGEyYh8K#--VO4H^2Kav}swbOuu zBS0sjEUWeF{QtimpzDk=d2^lYuQzCc*HK=x zqm?~}*5WUYyw_7Y?%%j}^j>m~1au$>Mh32Dz6PB`48)hy7SpS#)lFUwHXCc} zUV{x_)EVBbcxbkNVpx02KVu_4*o?M{xMXY!CReb&P>pQgee*~G2j2J?YK$qZ-DRk+ z^u*Xwa&qFDN)&s6{nrsur4s)ewd;KD#^VHyj$Hu0WInA{rvUCdt9S%vB4Jag=Z201 zn^ojKSxjmvbB;ps z%LiJ>#cwl;u(O`^AF-)U=QmWAS@W9&!q)Mk7-Civs(;DPs`EP2FWq<~3XQI|nw8EJ ztt<%xKrH^?wX5v-s8?u1m+vvQFq!fOY^9K5HQZZJBv6%Zrhk0h7UH)m6+Mj^h^NZ< zHw894j{J!c9l4-;R+V7hb*P(je1S!>T`<9LII$tR9gD-BuZ`FZC z5x4IPMqP9IAt%>f*tiaa+^n#pbIZSBKygSqziaftSs_-#QMoEc;cw+4!a`N)PD!Kd zZi__dZlv_KLiEv127;F+?_FV;Y+ord-o{8=?j?f!Z%(8xz<$@I|8kbPm|lEDCwS=; zk9JElqc911c`;mM-)hFJ%g*>B%6gRPaai=PA+c^4HCIGhumiQ9v~v8> z0D>preBODF%m*^K&4gU)8hY?z?JDys?YoXGP1Zk~4L1po@iBgRL}A3IY~ziIOmXrg zzG79jbpORoH1=lmhZfTkjW< znni7VR1=dt@k4p+zsTU%A2IskFBAX22fB<9{P;{1W`mKC_!n^5>ni^vKa6)I;}G|9 z)M}mzUQ6KC-q%3j?xHLYYU6~5#S9PTKK<}twDXs@tm{TtD$uT3vkCJ?Xd~nBr1Hma zl#n#K8 zF>FJD_WbsJ!;hV#0@g#q-+avmpX+>)_rBEPp|Z(e5T5@2-Z#YJE^i2HXTM73-$=!gG`VCLd|L%9pDD zzTyv>>Gbl7lKiG;8{@%@6sURDT>%uTye7D%|0$W~2tQRUef&4sa#TI)eaAI+wGF}u zokvtF8aAuN#?LmnAVl(n!L9e1ixcFlBR2g?UH|XjDHi$FT<)Lg=59na+v{Z;B{w~e zXUDN+7COSlT?qyqq8gOHNi+Wb>+zO|Rc32`%JBWwD$#>HzllA$r&@Wlv;R9q!eAL+ zta^{C%MzO&oDulD_i*RBtozUI{qZxa-ot2SYSSgG!S7Z%+~)i=;2(Mql2t3JGgR5^ zklQf7X{Y7>_ox5q;bRc7BEvxPhwE^Gbqy5Y{f(X0?I{6p^%brh`V$>ytrD|de9 zrDZ?iA7ah$%;bp7O%_DgFOAndl`q#ik$87>`$GE+S4ZZ9lTvYV^t_o`ovEeUm8)Sg zbX{J}tu}H5*O7*73bD{rxTX{aXPu9MjQ-(bmvpaL*d$q?z5mej6tyN%JH)SFmaLQW zSO~~z(Y519Vylyc3hN#D5ctpj9T@8;4$&4g80%%U3dJTT@b@lG?Kt9yKAx1@RPrMP z(1PVysn;Eoy+e<{DjrPix@NfN$ZZU4OgLf6{PArj8Cra~mjZobG{7-`&)hJAz82&@ zh|3X7R1r|e<@EHsN*(_D$Npj>cv4Vc(yMAkS9~@Z+B{;sRu=Qe`b+?Q*cECTKz5YX z{fY#_TdwrE{xI%=T)N45xcxJHB}LazJ!l}$61QW33L?NTk5)fzZ$lRx@}!vBy3Hy^z=S1q;Q z?%nVyt7=Smf%xq#OWU|JZA;J~GZPUg+N}SI>+9>0!UdNqeu}G8Zdm|f_i>)+Z+y<; zGbsdDF-5APdZY_WeqA3J>-d+%VGO-R{P$RQrp$w*unoW^JbDHefVO1?#EhMGVfn_C z`%#H+%Fq-5#O+y2AH-!=T&re zC0|2|gR0Ef;mfl0nBkV(`vL#dc4N@@!XgiJ1w z!;W19c!v*+oSg}lgmVjWWXYIu-$pV5Q>z;f)X0^>jTsAK?;%NpQ(~JO?tck?4-vAISl6LA>tqoE5M@lXxuW!)m<$2>6bwW&5Re&H z1=;zG%i#yiPlw97US$-uP#+mU%mmKqjIrifRA=xwr%*4p>$;xuz8%k+gcNW&g##C1 zq1H%2aJgk7-nOFl(UrUZQLz6?C1f05@|$P`KCVF-HZ=6&b?|t`?$KwIMpTXas~?#_ zJI8lf)=UiACZqmHLEqcdHUM)pf4UAE+63knVS(_E6!WY`Jdoz(H#O_AEk*ICT?XFP zz4jAVnALrK<*nY#B9~5){#RQ5k{24oA)eCpOG<~_fKjh;E50zMBFILlVDh7|^LTG+ z>-jLBG}8)S&Jg{5{I9<~GXbR5b{GgjA^juu5OV9ibGT?_nN6IFgjNU^K#hJ^^^__r zzLa&J>LJAUFKQQXUJRJGhobGCo7I5&#!T_+Mp|LZisz zhnd~}e5+983lsEO`uD8#%z`vrvV#Ix2PYn=%C&x4fo>SNL>N&fI}KoyA9ih*s{~4) z-e6&3aq1*IWndjN@DQlAapt}OAd~?C-&`uW+0Inhb>*9#-zU(eV&if~+afOJ4eZa@ zjo7wr!>OY_(7ckAUrA(yAk%h|zI<|7X+*?xuFB}m1^I>6RA{1@xjiBwSd~39tUY}e zW_oq?huLh0)xXDDV6U`Gz@3hQkB+u?M4K=G3^7pEgDnJI>3eP&ZJ$}NYcaXOxfCXB za?nnZUJi*T62mz?Z;&bq?CmT-&;%^EW({11^g5WJeuZ5ZFj}VT?1pf3v;!ea+A$7de*ry1M{r4H88*EQ2uaY{&=Mc;6%40Xu>zJ zU;Rsp#uo{|wmfIG`%+=2=2A9t*0cHBV%E2gC`aGA!m_ded|d8<>xyts2R!tyxjybQ?k*Z z5WVjX+fLSoibM~_gHp(TuyG#nWx@oo%`he=_lB-4x{tUT zG3rAFBDVU40)@$RFKvhlQ^-$ zMoj;vKIXG(nTxYdl(z!4M?SYtXPwiV^XN-4)s_xuC9othU;=(7HLT21(U)y;c9x$= ziFS}l=?esOmq=NvqesW$0%JT2&jBH9zM9yG*0nib_D%l&zr={BBdEEsehc-)vztB< z^%jW`JB|?AdNlNt?7GWt9%m&#c!EB=B8a<3={2z|>tUsDCXxK?HS{QPMTShr0T{3;yHF#? z^Lx&6gqF66kAKNx7qFHF1G^Bb7Tg@?Ej{P5BqDnDW)jPGJG@-X$$32ouuOv~c`-F9 zF~bECmyENxoY)mugyqn<5{mz^68AEq?bDQmA)?1z5uB0F2DE3u&l}uR!8x(15R7iA zUN{i=4;}W`J$H-jl3iVrU;e7<->i|shR>;}X(xxpu?p^=fkZDT#aeJ~OG8Ffc5gq+ zL+e5pcsY#t7u!P;u=zG*zvqf~%cvFoz*P~xlmrtRaw*^}0MKWR&C8fB0^ zi06qaVy(|>O{io>@#(5o6K7Oq8!r?Qbd{Oj*ADLb<*7-!G538G^g&Q~5T5Y@AjKc(l(<>7D1xZlx0F-ubB`lEZ`DHS{jq zz9IIMY=UVdY&PqHDm4`pR7Xl7$D%zcGggLp<>^+>aEB(cl)`z7$Z5)%1(6o~sD_q7 z$W#vJoEk3$T+iu2PrM)L!i&aOh6FM zB)03l|BiHPv_OvzZFA22uzjtp*7v)k1tac4t)AeBsqDVIotK+@O63Dc|5uLH<#tn* zd?_4eZ%2&HS3b_&Hno8@Rqs9K#6=kO+lnR^K`-Tt^v30EPS?zs3KKdRWdaF9r(L@z z;8R~{Csmp5yV73!FgLbKEAdW3h?dL4Hz_f%ueO;(I}_0RRrpd{hSH5G^tl}dSL&bN zfoIykUFz}G+=d=lVAbLdWU#wk`&cv~RbDYcZ3H?JWh?INlH9lWI!2*_%034NcwtLX^k0JCS{V(1oEW@`#g0q ztO&ABa4r+>gPF<^yI8dZk|!CJI@4kkjQ~P04}#X%?5fd_Q+L07J11%Ai;6&j!aP_iFc1u?ws);xT_YMEd^+C*d?D@&Sc4v zg`h{xp_Mu3vBlh+9wctA?G+ly(6byuK92yncd=IaC)jCC_$4@mH19qXwj}F2zQlL} zH>+$kfBIv@?AL;o<%I>y(<4~`{+5swo94^P{I%)Hzqv{$xDI* zSY=(V6b;1F6PGA1bwH=^JmskhOV?#qDW08W8t)cdkqc+{{GQC1Z)^}1V|w+bzr6Ug ztLC3pf(GEwcY7$GWsrJREEgk+7hds8@2N_chHDOvs&vnwuj=6|l+(yn$Hit5Y|-a2 zX%E+6vzKrQRM>BDwc&)Z8tT2HwFzD9lo7Ii@c62ar;4vPT4-xNxConeK2V61>C$;U zLApaKAPYa8V-({LQ(!uJXBoW{*X2Y;%f;c~(M=o4)0Q;wYGrw*$X!#s00JG~aAe0Q zoObrbSw=M~DOXf9p6{`U?X!QD^V)tHu{LLq1n7h7<(5CLAFO@$X1w<^&OA2>(d2Tb zL*DG%x2ksy&>(A%1q?*(^C z{BhFBZVR3(GoF2U94R-(mtw`RyWGdw8i}c7gyTG;#GxU>{A1*$?5|nfY;&)lxyI02 zPx$n%uw8fhfwW(G^@S#Sij{_u`PPp#hPKUV)e3S?fzt*nYi?krNpMP`6dGafDAWgvK^b<$(3^Q z+XK0^)B1Vx#QSEg$KMoD*t{0XyC)+*GFr(0q&Tjp{KPi03QL82E+_0o4MML}zA$;i ze9AacNzQ9?0ag(X35$l;BDQ6m9l0Pk@#x%&#kEER1MFwgIR5%9YrMM~oLRO*0&UiU1Q=M5yZa>I!h7pn zLOQ-p=v~4&!OV%{Cwlx-uQ}%f-r4<4Qjq2gL2~qtt*;W2irR#2`A1;`Mz^L*K_^;aj$EAci%kaow?_pnR~wHiB@mBYim736b?e=&^%PNIKRG%(DK3A z0?>n8p@o?|mNSzFTE5RU!T=l*l~V_(M{TPpuyz5G*l4Fu$M}nroTnk(O39e*9m2%1 zpEVa=?e$FlhuQi&LOu3Y$z5kSC8AJ#?}57_xz}T?F`zxACzvZ^t-56N;FlBBBjU6( zR)$`by!MIlYbiZ6ZydjWIe&Md8hFHtH^q&ZQIB?+&o+muCnIFvta2J!y!A!sMFPEPk_G#rjqAw?s{5ZR)*N8f&KhE6k3VsdD*X!UMnI$EYe|=8N zF>p!G^+jN1Xo1jDY2eqNPsl}wBhSI1#La+?^s1<7E1s~Tl{=n{G@_?ljY|fn zZu(y}R_avi1cv4B?WP4OM|rLvvj67Z|HF4sADnW@;M%13|0}HWg;N&@`=^gJ%x&Yc zH%8d0JaZBkwvRpUdtSB1$%13JV#t5|^TCfw$Q{9FPz<5B3$w* zP!SZBuWt-35{NDX_W#WE*J!seUS$Tkm{@lGXW`cxR?EJLHFE2q)$02wjpOda`smf@ zP-2YaSB}7zg%jd7>h?MsNeia1j~y-&z#BUYONFBl47Rhik)TpOE#VGAf%8DHIWRf_ zZl1o1z>B1X=b^kYf!_7yz%Kv;Q%PwHfxf`e5uanK>yH`>UpSX@!h~|QI{+|C9T9{T zgMk0+x(UF@92?LOrDZVANI#DRqA3IU9nw2lZ|5x$4)exN&#gQ#DAHmaO))RcRYxnG zS0CP7A31&L?!Iqc0%Ci~V9M40`Kj#nZV~4{q5boRZ##zy4c6N3*&L;6DqD`>OCv-g z;dNxdX_JTFZ^|Q*!w2~CX79{R!scY8Rzx_w4j$}fPWTZE zA^{NJK!k(NbAga{?@&PZiJ(}xrA*Fw`F=NVKxdqp)@3Z11%)A%EVFDu2ZKOc;}c5B zgcInm7{|H<`5Rbn!J*E&7tY;q&++8lv58Gz>|EB_!D&>>Mh)qiK!fZylC zgR=GDzVO7v3?$;fssL(vQNA{a>F@kCe2JHOYwMc6R?J=r@4rQ@{{xC2aaF$Dvpbip z;MN7gKvJRP%2&PBi7X4yhG*oXU!)I;P{Nf=?u(gGPZXv6Jn`Ck0Q4=?J3gm_+Z;S? zS;$kJMhOrNK%^1{o2vE}MSO16Hq*Rt3kVdIQ@|yba zuENJaRG8ulg0TcZ_w@TMAeBu%_)BA*ApAbjdJxq?9_k)t-zoh`((tT;zJa;|YXA_( zIJ%@iSEqT9hSC<3)7>+*23p3iLWqD7g*c4E4q&EjI`q3SH>tM35CQ{lx|)QbSNNPx>f$C%o8PZxsvxknai70Qk=u*d6)q^CV;$Ax(rm5K%wUmH~gMLy*N}Cr!=a(#xqA?J3p~PB8DaB%;rlWwe zL49FvL-PgIQOqS}^g@AoIkV4$HiWxcRZ7rXMdW40|`KNTC;P8S@K-@FDI#=6d_E4;Vnjn(A(J%@(Miq7?oNKkU-bsP;9c28|Q)aG<5G@YV4Kxg6ZS zGCfnb#TzLws-{w>DwmEiqhCPdI;5ces?b;0`HXuX-=H}HcCMSSt%KHZk!&jf6#14n zQ!mpIvbBG@OT)*MnPt*MprFH7T5j_{F2VXIX{8rd={xtXsu>4encye{uf3k|sajCL0y|zt!4o^GgLT z{}H(LfwYjYmnqJ3FR#gDHkPt|=!aW+?YShM)OzR1UT!KHBh@kB)>%MA>jhil!8AIC zf-jcgv}JxYTD%V00@6QU06BP!S#f)r!aj4*a!%s5-icXWH@Pph(+?c;;dnTtwT(}) ze?$2YO(SfE`q`Fm^IZ(!Z_^)0;Q=!HdXCo2aqC~(CJJb4pfLcQ?MOCP>rKlZrwIlV z>eh3Y$`{UJO&`2C^Ceo}?0xsWISru$!TP42J!yO@yuMcHHXFn(pp204mJ(faEG6%t zDcAfdQIFsXdPh~|!O%b7bkjQ7(Uk}*3>X6q8TOXuY5-AWw@34Z&$_}Qm>?k<{WOR9 zXTg|on>L;9A<)KL6Uq9H_1~|esr1bs)_=N+FO=N7%<}8G_MYJv&GiDMlg%!#BCe%^ zd6-h`&!Ewu(2$o(OMYEfYcqHIME+P@z90F)q&%FKQbbYQC}nSl3;>m5eh?Nju=FT} zM%*M3vqM&R%Io*@LlcYwC<%)?Ei8cGL<7?0jn_<$Xx(5ja1>7{^X7Bo&9^5wqw*&m zT8aX?E4FVXV;rbzDHIlamyd`!aNkDxXRQyNW96>HZ{>Lbsj73+8yhnqNYziCj0f4V zXI#$j3au&RENYIU1ew=xLRH3mt686MqmAytf#4w1pKo`T0kN(b@X@j;@>shFA8Oa( ze^}u&IFAuUCjo0Zj;63;#Kj@iAodxa6IagNI|S;D0>)J6)#?8iwq0GL?mGLY?HmyS zY6{39`CrMqAmP_J*ZW&--*@$0K$1$=C#sZE-+K4-GT>3fzB;OG6@hp$`Iq;2Ubqs^ zfj4;uS8Qal1z^U@#VP%ea7-h>TbJe>n51HYwCLCs)EKi?+wM}=8aw6P{Ly}_HC!lx zdAb^W+@~)H;dek7FS1w*_{z9NE|eoB?jQC(&)56+j#B1_KQOu?67s-s?j5+NK>G=G z7HaBN&rvsA<{_llGrI<$*C`nVe32o1jDjKTTS5TCqJZW3`S{rBaG|TQ=His5Ysyy* ztfAG@u`l<3{9xANbrj{YMk=nSN4 z3ilc53zXlBzx56}y|NzQnwC=G^X$H-QEj+u4;A5c%(B9Ybdh~AC6GXg{8Nh7yRuQ8givHY!x{kY#fJSP@XAtG-X2g12kH0=Ym_+l zzAsQJG|o5w^#YrTXVd465ORtkhY2;rDE`X>gO1A(5Rgf_k$?`5NxODeUmXKY(2RJp z>R?%$lW87{;FsM|9F+m$8;$%_us1w{vEz3H6ARjMNDetG4J+ygwwzb zU^)+(4sK(1Nah7g-yx#=si4Bkl*A|ncqy{%Tno?93l+F@3~t3;JlQu-$%?pnw%009 z%vc((k=sLE`v%jYYM`c|iQfVWS@GZ_l~QJ)!2$J6RbmXNNxcM;(Dx;TXhU0OWmncI zw2*=|dbL^T{);m)xABzG>cmC;xyQ$9L{PR>>%D4TfVJOqC#PzdWfxzSE`lcE7it$V zOy^j)zemEZ*w3C*+-k~-KdL`x2CyR7Is-efb>IvB*%eb7ykfz-Lb#`pq!NBY&#m4H zZUG;weTlTe8Y?7mR`RwEe?fx+>)+k6OW94&9{(xz{qPa6a}WO2z@k(|LpFq2{sMXd zBiY1)9#B$GM-Mn!#cv&TJNHmwvF;4NPQ7|r=e6Y^zxwUeIEcoWC?A~xP(Y#N1h4-5 z6a;ve+XUXa*T7r4RsboSC#CsV3tmb;cR!d!_9YTD{4ayP16{c*K)eM+;zCPYQk8(5 zxu2OHbB6%bvgm&Kt4nZADtaA$TtDrRBpNuU_B4c2g4+ah%qg>}XSG5<0&WuI)H(IKevoIeoK>(Kpjma2&38y)OP&6AqHu{Wi5R51g) zsBHfqgv-ALOM_bcW%hZbI8^=aQz-&e@v$RJBkT&H<6!704Ly?{|1-ulgrkjNvAuGR zouEMOT~JHvnlV}Sy^#_)sa60i%#-9Z@gggpP5-+o(1Lh#83uUfbr~`kv7v>3;Q_y( z^XbIdEDL@y)vZ9zo#;feW-n~^}_?&N?JZ6d`}7dm#>ZgF^74n6R9TFOMuc5Fqd_JU|^5;aVom@ ztF+mfTryot$Jg40ujB(NLzK{Ju(b7Z%adbg`F^^A6zh5dkzz+G=QLdIG?#+3uMn?7 zKTbtBV^GO;SSn&@wTzq^CUSzJ>lBK;fML~V2D8x6Xb|DHc&nO$L%7Ai3BVW5W0bBU z|KVi-r!-*dq6v~dH&e*Jb^GhduQT@g4t}3VRdNK3fQ2Kr*MVo(8rwzGxJ^slq~sbd zdbJeKfL_B0s*1&YHJAuY-9yC90s8=M#Z=t2VF%`Z-yTE*(Tb;J$gzv-*yW?Ge67kgDF&NFS-A z;GacB*!E^9k=aZ6-d+5cgQCL1GpG2rZvTkrU+UkulLVB*0*?W*z`Yekmf=nZ#~fpe-OCJkVGJTWkcvjBh3<<|j$= zG{Lf`z!T3RYFAdp*c*L5%QX{=#ymN-q90a$|Lx|7Cnab6DI-YfD3n4K8BG?3?0y`D z&ub2W%}@3o^-Xj~mB7H}-+)uFy&~t1b(qQ8m5=^3Z^Zh)qUur*pa395+2m%)_J#~P zV*H0oz$BOahh~ts5gP{O3gbY~QSUjXgra^>dfA@*?pRIsujhy)G#2Wz;L&=*F`JD7 zeO-Z?+^;9Jlc6b!J6j$8*Pm}$+|PCaNwEd*dQ9n{6|85tbk)t|wRAB_7PF;E!Nq=Y z#~*iWDRlce=L6h)#*-5AKfNKA7H1BXDTabDbBRH-v1aN3r%5OK;fUF@m?cU;BL{5f zQ|m?+3eVGyv!JTY!vK`4&xc5lG0L)K`np00QQQ_72BDq2CGiQnCjHhLMx?oZX?0tI!f4}SVLygYs%BzEL6)s_)5XTR3K=7t+zc{6osf^xHsf>J0* z3*HBOtUMwR1Hx+63c5AYc^>I^O0IHeb8c5r7!+tIyhDCtxM0@ruySV*c`aGlWc+Fl zqlpzSQ3lXV+U$(U@yF@S0ClGxI{N{M0!vbMBM3Eabg~;EPxDTSb#S&4mgkyYSt`IYCrk(~1$BTRv zAv$f9Y|&@AVZ36U6_iSrf$GZena4z zfj%rG4{o8?25hnV7=Yc)9rei$k!qU6ReLWO2wJ46hNOXbQfy>&T&tL{JLfMgiJm}nZ8=i^6zeX>fX zW|mILTBR${VY;*n+2&=yPz|A@E2ton&^B&|?D8C%-4F!K^KMCI{pu=($gAqW0b$g1 z@(xHu9;Ao_>V5hy9}!+km{Sw2(iKddSaYSW%^N%RGXl}h{IH!9U>w%Q4vM_jP!f<2 z#v9%*($%~NiYIX@F5^2GZ?E(4F`sRUjA<^YZ(-^GtZjV7ld<#fT7b!osf>>ijDSTG zM4=}f;bYV6LtbVAn?3sGhbUrFKazixo|gyytn;O+{)w}{Lvo$DFJ6TH=`;#6l*kQ5 zN1>l~yR-L!Qp-w6d8VvFH4s$ca9J&(xV;|6ugiD0ih!Jnp+?n@%u22UZ^R6+{m^>S zghRSpQ3FWmN>l=ycyPCf3`FUER9P*;1?mRiTKPl9D3GrX*K?Y4Qy_EF zrAZ2y08N(zI(>jp?Pq5u0-}vGr*tATiFL(7C{E1s*7HUbh(GUB3e?mt7U_1(SMU)! zL%sl7hFA0IT-sDZz2i493t6$>A!~346c+_(>zjNpk?ShGC{?xPA z@Z8s)FiXV;(gb;&ua-0rJ*ortB$OFBU*H#Oj#`uLR&u@Z0&##sH;lhhW}Z84?&kD0 zI`5++QwF8ZZyfZ|`bY!cSO;7*E{l6o6BGb8x=*|V?6|le+FXpATe)dPHV?r05Ej_- zT)FEGfR592ha^}{1W&Apk>L9eW7P zXY2`B+*~joxj+>gVMe2Wp4k0_kA*(kvhV9)iD&%n73^;Ma~*9V2qvg~4i>7g z?_N|TAx7{<<+98{F<_C;A7(AJt5<{R7d7FGzjJo&B?D5z4zy}jIEeJSC${|tINOym zyrli(B6BIPe7pep3$Jm)r#AA#aEJOlsc0O8`CY#Q6$G9k&1x43vZm0kAS8WZ1z2Qb zJ8>}8@^{P-R4nuRZWI3RoC<|3_dIgjc^}GBK6EcE#|ppNHY+9`8XeSnq_jX!Z&J9X zrL0mof-_z)VJ>{Khh(0BSE{tG3>LHh_LZ{V|17N}0TL+tQ1{-4?)7>nf--xv;;*KI zC$2qGQUR}gIM{J>XuT0{RiRjzr873 z0F0tYd<{9d6U6@PJs}(fDd~`-t(|vVy(Se$H-N* z+wT_1qbTs>+Mg&Q>fJZyqT2S{xAB2Dn3iGE573*gWbuuPigSce@Z&NGPn4W;K~e9< zv`V&&?~;pK<&Z*LZ+=6tbVf&=PW)5t!ril!RttPt?Cu*M0XZ&kdBk0ay+TwpaRU6V zdCS)q^mJ&p(GrtksJ({I&M#CmpEce`Wj=%}DJ-9&IZI>nzgjT2;4l8vbq9Cm1m}qJ zVj}G|5pd9eB_2h48+QR>TO4dEqrNGh)SVifalEPcmDs&=GzRB*uj|tKk>5J$BW(f! zdm1&r_YD-q6|S0!%t^vtu7VacW1005X`QA4dnpfg^>OLpp(0)?7^ZyI{o`KwU5eoT zwJtyPvbToF->val(HbN1Pv7KEU0`^YHL+>1-KQw}%hj=ZBR8QGH49y^uVSr;g1Qi) zu?=J>F4J_+R!A|tOJ?@=o8BD%Jqu);Gj8yw+mpyo>1<-)`9Zh))LlBtS;jll_UQw4 z1|fdedm%!_C+SXsccRVR()TWGG5aM&o>tvvbkWh@M(yj{%D#J7WA`ZjPsli^LFow@ zIf1I$yRz4)nsC-bBj1s=ps6w&SlGuo6Iq$3!8@%{%qRAaDeja7%*cLlYVFo<*LmfE zW-9Za)`=9Rth4!0&z?dTh={;CWlF3O(fi<aLGlO4yddE!4fP%PW zeX{fR?}*#Sx7szj|8AcAoy|)DIzn7E#(D6;y*?EqCH}1{?uM!!X3!0ybQ0KDD*eqR z=U`096xZCLJ)2?y8ytzMv)NGiO+q7OV2xw_PYqUf#T1)f!1WQfyAhqKU|Z9Tzf$;N zA@GqLt(y1ND%eK%%(rBN)CRadodV#a91&-8s!t+UFODz_t55Ijth^31KV^I*U+Bhb z$vg4L8}|3uZrXp)5M+Sjb$$q8x?(cdsKDsOw0OC(9G;G#=~?r;k~#= zhr7*;ry?(=u~puqy-2RZv%L&0gCkz1R(w)J4;Q07M*VVs!#+#UdJX1ON{4*Vpyz+I zkLsWQNYhsG-zOK%p~JcN(DBnLBccUUGA`xteN_8d`CVUM^A28g65J@+XF_L3wfE4q z!xpf(#3;1-T=elx0h(L%FU4w(SukDNeY*$j)rGYagD?K{R{lpy`80)eHBovD(Y#jJm>Ol7RRomG_2p8_ET{lhk1Y7p7983SyZD(s_ffO!>YtTPSvU<9uyqgB!B65 z3%=}|qddf>wEOHo{c-!rBm6#}lZRoBA?^Xc{;GQ3!`eWjGW#Ki9XZ#Vj&$4SET z|FY4i_ha`j-{xB7`Rl#HlmjNrxm*p|M|FX+-a79Xi-(Cs<2xNbg35dQyb1RCv6yO0 z59A%3@4Cg4ntxp@P`ouuS9Vn^74y$`YIi3Ls0OLWdP6Grj`z`{v*5Llcj%=qf^Al3 z<9GdF>bP}gooX0!dHTUM*}X%%{d(V8SGU%;jFliNo3V3!$`(;7BN=Ud#*&U1?jujg z>`Yd>`<@pLXCEr;UOKZe?C04qqSm@qyJN##x%cD$>EM<4r4AGZ(X?t%`GxOpnUd~) zEbM*iY;GnkJndir5nJK_`qbw08hLdr8(!W6nQf+O1rS*{0NL+(AhV+HzpJ(-vsy{n(8<-ifnU(x2+Vi>A-aQ{ zBD#S@ydD_awchg#4F5wcjZ`2$C&P@eqg6wY!!GOsW0xhV9?pHdpn7OXbCN-&+NZrc0x%BGZGe?4ext$%04$g?k8KWki>fM7U9D9sVR>G$jBxINSxj1V#`u$c#gT(-^6 zRE8PX)XRCJ2xVO!OD=B7VvB!&`AtWGIhKvmHrApRS3JX-O*cYMv%m`rc5#}7;+uYO zu91iCB2VZs#Ms=!DfHa z#%(|`G;=DKQ`fqnw?54e79mhOiEa(YjWFpuZShhYMW}AE2Vd#65J=+^zZ}K@(9e?@ zbI~{p)K}h=2l22&ZSVnyk#bLmfqd(Ekez2h(Fj9@?xjBY82F>%vUPI?Nc;KswsDea zUOFZitVMAFqq3cN(&_16hVcSrd$^+R#hTGRfZgFYVDSJqS3dYiZp+tVIfW&B9R`ikKNhfNf=`=jdlT46r5KR75;h=ipJ{yHcY*AFl#JRS!E@q?f6kuKPXpX7sij>wCv0zSVb< z(6~4LX9*zTR%t5b)Su$Fv4jLZI+Kx8ggfa}e|5*uD=B*ZS8TvnQOkL#Yjpj% zs@V2SY59}4ZRU!%8A?+&Gd#=RKtu1-Lsh-B+xPXR$3nB9h*Ld>s6`-r!hV`t3@_iq z$1IJme8)$*j$!-Ec|}UJpSow={Scg`+jRKOmn2gy*?Ssg-WdePE=DMy;(D_r1{EY! zxwB;|oAv3?g5ZT}yYDB*(YiUh*CZTuwM@NWoa^0F72P>)LVfsbJYZEdr z=5wp#Fe3H+k~b%gBAJP{2uuPSZ~Qs#q3b+mh;l*GEGwUYo(#y%BD+B)Q%^%J3I7J4 z^$vZ+$(V}S_>DrZ8?rVkk_smu_~IoAfugfy>W|L4@)ZeLRtZM4=$9j_)6Gv57hn+o z^|7Dv-MyY3fj#CGHWEm4gpF3qkjq9N?peoUk9H@%VxfDL2Ae*5vQrj4<-U{4J_Ng! zHQym3HYBj(1`nVAduQDAX4O{r=`)im4Tao6Ww0jCtz2aU!V4M6xS`VUd58>CjB<>6 zd0}BtxDR$5bC{pc$DXC=LGPr|7EQ2@I6M`EH-GT6`)RZxTI2?~7@*?aH->nlA6 zuUr1~&3IBi4c+4+qV+AgdY;Z(&5T8O4pl}D!8BkYWBLZgEF0{4HR2`Ph$1mkHg@Sw z1NnK2yl%!GPlvlSWiL+PzoUoIffc>B#~bs%xKt{Fkp^iWE3ZAKtv60sfT60%_V&KX_V32Mq+}s2J;Q^};NF3^ZycM2JRPFA2b4D!-Bnb>b z*4yQt<8eu+caTxgOI$}3Hq5`lAp}t;YA!)(f|bi_OD4zH-y0APz2xnizYR4pfH(Pv9QvV9GQY}56Gj@aO;{|C zEJ9V@d8GYiYscAFG(i1Kjr|U}*O9P!wbyY*AyZRf$qs7nFEiuM(4er^dA=jR>p1=B zO4HD|2L>mhPB<$t-Xi+*6O0&;X`5`N4(4(@3w$u#+OCoj|8mWc=Qb4mdlDDQ4k( z(h{rq$pW*KWQ>Z)9JRyVsowz8<%4v1@VoKFKVL`wwcUtmd#RI}av9;mM@!qtW1$@z z`45&aFkJe+6blb@m!&@81%~7}#+a5r{BCq{+``dXX5kphsOZj6Lx*S?H@&33MGW0m zvD3gr$i+|46H?CEJS``0hGu|a?(&~5_Z!$hqiYDD5-~jT`aVEzrN@9fK-1uH7(O$$ z{y5osf?&`i>xEt<+t4M4?(^6rPXMK!;)p$2bBI7gPte={ttpnC#;E3MBouXAvM9BT zf%W##b~n>@+DWUo&#zkPSs0SOdyQ`Ti6WqAV#C7@iv~A$&Udl8LPdUCOv6IerU4Y(s7KZ% zU0Ofpe+hOFDmAeu#`zbbqHfs{RhPREybEidYst*0eNNFFEem-U;{_S4jIF0PB<{h- zUP~S7wXlMShX;bs*bU~6-gjHSNie}JE3XCrvPquumg&Gs zifUF#anr_dlw*@s{6&Ryh^DXQjyEPJCnlUi@p=)R~>CyNVRnOlVyR+~dmw^P_U-EeId%uDMn1`Wh&ts1H1Bm{g6q{Z}_vRd$T zwO_@LD@Mw#K8HkhZ-KdAXFq0Ti*&)VnJXhuA7c5u#0?;rI;3FiAQxrm(sqOG1?S&-~Adf5npIZv@EE|3bO*NUQHRod*t2e>C7^k?!v=_!wa_B5l^h9gCd8ebQi*2@+`**jYf(I1`sgHFG5 zj21FMeQ_KpCS`OLqhdhGKB9U%ObA=qRkod@3G~L4_QJR_GI0YFu4V%I`E~@Z#%IMVc6A}DIcHUw(BI%W~yg^J0E800+nERzs+)Ouh-Oo(bjbT1?w06O?eRgBrY*x|CS zJkvB5_wuMNzrSk%Bv>n5$FH|(wnqXk;znvHu>$nsH{a_6wE#TczGdYfTO?kF1v&## zrKKlqAL$l44uv_*gfcz^!Sr=fD^bheV$bBMiZmvugVd+6*?(2M)tV$y zYs#QIxbb={alMMv!$hO@t+XE==yJ?8Z}!gnYFM%E0QG%{>EW}5u`WT1>ty31$tDHw z5ufxoDd~Z-L?WuM^22=JR`u2+y^trbPa(%Hd{B2Z_C=ZtH$Yi^1&JSA_|26Pb8 zI`DzhRZqqjq50LAQiqr~uRaCx8SXb!C~>i^itRCUDLnA}OoAgupDL@jcn0yrC0-)y zGgNdxgrPNVXfP<*9d}pdr`zT$GTTNT4!1$_V2SJX z%iC`&)*>RaZ@Ealynre zkUGF8AW%Pupbr5n#M0+7Qr_c<0Zo(kL%eQZ*~T#yo(rGw*rC~S7QT~@lx!HmZB0FH zLoR<4vz2*#Q`M&QJeze(bHsV?sD0}_9zLi|)M)qJKIP|^eiRdCcR1Z7LwjoP=8C8UhlxDrc$)y+= z9i5GRmcL`p_T`QCrza0bAXj4CPaZhiww#|$=DN^o?^0dn()G+!o*0{@l$)L6R1&3x zsA_vX8b3+?v39j$Nl3_fXyMhyVL7}<#BGcI;SGn#p6GPsC%1fXHTCOWFYWBwKhLR$ePP4YHYvfPT zi+fD{KV~?TW)8mFIreT#K9z3Q3J!=|`r_wvW4NA(nWK(3=K&_M zLypUH0ZC}S63!)sAMVA5nH-{FIgy6?a+0M_wdSg!B4EMGy-d!0YtwR~66woxs(#j` z=mJ=ZyhH`3aHaNx*`^hc3YHf6X;3V=ip_@(N$OSlxFKHxWwVMUMc-8`sB9+U;oJ|0 z#t5FAp*3K`t#bCQ>EN1-m|;7LUf~}u^2gwyCK6As`!UtRVZ2B*Y`$UCW2OE=U z(oP+CSdrXgHe`m6X3eZpM{VR^MpcRU?o6ezq49x1;|1duS!LDw7TS>dn4Ml547ulA z!)BJ+py*^JAWsI#W+sJCki<26oT3kUP zma-m-Tc$4~E<>)ylBya?jE`U2YE9sq8cTR7vIkE8F%g==@NVZ-MqrcZo-3ufn_?0S zVJOB>#{$aUi;dubk@QGj)U<4AC)L%UsH({F^oNtM2ke*l=EGchCJ>99W8|Ylb9KG+QI)Ib>B^CVBNON=QR<=J`}_M70#sHM>UW zgIWo6L?NovbO@r7)y|`J_polDMR)k#4Jywy_H|Akk<=<&RK6XAI~Q34#${}MoLzcl0HJ~uVX!SP>Ot~WBZlrITH;DI5h^+1KnBVhB|p=T z2PuQV4b}PhOAm4(x6-05HP{ua8`wL0?_g{89dKr3ZpZw9vM- z8<1e~WQ%o@ry;b^?94ZpQDP-k6vagsW5nemBwpLuh?U9qI=JxdR|uzTh)6o3=9$1nS-YN10VU$e9MsDnFK{Z-ySZSK*EGdOLZP-mK8>wWX{Ah`(DoEnxFO6EUZZ zKRtvw(87XQudg~helpOyHvKvBD1q7DH`;M$nCa@Bz##>bu?lAK?!i=hY7B93hz(29 zi=7KfP`}=8Ml3zxnGADHo5kD6IL@{`ENu}?pYgKU2Z2~evzC-4_TkKP0^06H>ho`o z-hW&O<>GNG#rb6uq$=0mK%Q;Ct~9uggvgkoKB<7DlBM%U{Q>7>3Z2u-cf4Xj4iXtn zY6FgmD@HF`!RizrR1%G$~96=ed}iHF*k=6)Swt z#4*a)Keg=FqI(wjWo&dF$@^my5YSVIukk}S2&4jQQAc7}V&7(ju4Z|)_$-~wWx9{? z{|Kq~{=$dx-45%|G6D0wggz@j+$vk!vie+Htp(Bh{mv8bP=5p<(9#D2!>}lc2XlS4hfnL&9+`Q5<$V1o#zMedN-?_lF z7iYs?>KjE!8Zsgppc?tQOb}|2;bQdKTKU|F;UM`31XYtpV~Cy9`tlVvpX*{t7TYhg zly8(B$mN@yrLV}Gqx9H(D$4On>B9KEJ|eF87p z>`-Gfl6h5u!q_{86{?Y+KN?7~tH#Lx5=18Gn3!lfb!iXXYLB*?9;}XCc7J{HY0>4% zhLXVQlqz5j_9sbwzw+Ox*pmRIrjYn_e0PGbo#1xet8kH#ryW(ueE?#t)@_waouS8{ zG~yj#B*OYy&m+?cuT1ypW_zOMyGylwXy6nSfcCBg>Q1!a)@rEtM@kVlLJPt%bxv~s zl9)_jM6_KHfQ#1w!Rp=F82#ZGQ-*Fe{ebTbH(L9!*+l8a&n z7FlnvBz$!{luAxWdX<(V`C2!4T#4P*MQSBVuE}c^ zc7ZOy-r}xiTRxx-tfHy~gaxXn=i}N1ho%-COR{;mgI=Ng1Vg+LRLY#4jh^h+#x-C2 zT`H5znfP(ANa0SC&zsJN>5S9dmS31`nv3LPlyZ;71uhdv%SJsCQY9%FedylV!#_(f zLBmv0l$dVlRxuxl@!v(RwM350o^QOU9tUvev6q$hk3MSrP&CXmf?SGuRP}N$2yHY? zEHx-zbpW&r(?Ipcnpw^@yycaQ4qv0=0524LitHLZiS=8{R27RnP}VR=)U9%`MruuH zfA%^AjR&sgXaCu_Wcyi3^vCGeOE`cy??_d5tRBOzS;|XKUpJ=_?U9$Pk)T(6y|)gAACMlqfs&dz|jGLS1ld_gd}oV z83-u7_g&B?%_a<(RfHtL+=t#N8@+Ch#cBVQDTsc=?#4?4goh}3!%2_YfzOQr0nTLv zZ6p(b^JV2uCz;Y;`dp7PvlJXvTK;JHEc5zPMhE51=<-v zaY1I>C|_9=CJZ}Nf=Im?b~Yf#t@Z%t4e0hEsh=!1(ZYt8=M`X5uR0Nd>ItAJ1Lo~H zqM5Kb-9!ZS6&220*g7zMO}04>3>GdNnIMoUY507qyee!U;nxd9w#jJIQX{d@e646D zVY=}#(OAUX=chk}9t3{9Zf!z+wIuRxK5}4*67(k;U!$i{^XY@Z%)3eIDiv+8chxKv#gUL_0G5q~P8VSp*Jow} zg+CY+U}tb3Y{LXNyjcj%!wwZ`cQs%>jGAv|6SgLA-hsqOE(~qW9S%_yhK~v8n@yeX z%B~|+f&8?QX=G%@$Oam6+@`-9+yGE1ROGkn;nWsro~+RRedZxe@Wn_`NaYE$ih z4LO!IPC=h_BK6%{k)$^Lt_`&Gb>xi1d}R(#5kcEGfVZ4DlNSCIqhOx3t_HC#_OA%n z=o;EKjj)8ZTxwBY$AO$vO^0dcfAhNk$~dsV-9Zw8h4@&Q0k&gv{>arqND01E-AisJ zaocPdGy%sMr$)Sf@)C&G&OYZU1!+hg&lX0X7n_;p)o6$pfYYmbPA92r6-mFM1n;Ii z>P4dii8F{mGg%74La0QzR9>?|U3DM#h+X^QH8&1rrf{22*^?DczS;*DMQ?s_<1;ID zz2ACfXSGEX*k1o785J3tV4l+fkCb{TY*6iSyD5>+yHH%4M>;ee-O`Rr9Z^2Be6)oO zE7kyKO?WbHWIlD3f4mRmE%7~{`DugOYKpU!78-}qZP8T~jv^qwDi7)DF6II$aIrpX zl+TD{d4**US;PS4_ zly4VbOoUtbb6Kx1bABF0 z1Wms70?c$x)<$~+)P9{@nw(W*;Gk5{2>CCM)xx~ihtIx-TV&pVEEX8Y3hLdVB%PDi z8;Lh@qg6$Ir=M?wBDt@|ChbeMiV(U{<31iU51mIu<94${Kc%Vi7@UTRH7LZ*)KgBg z=SbG{?wPiDp6S*^*}i+sa0@yHKK@rlpkBnoApi%+?`rm2s_ny^)ZuGOH61EpY8N zvB+bYgY#^FumLo5gMzM7Ie7t^$q)y{_o{dI?Q- zgtrv=eYFDV9kj*+d9P~>H1XJ&p2uh28lg>&hlJ=G05{oKKqxwXH`Xz?3JQ>phmGdL zUnG!?`95grVhkJY%etorI@T+iqXq4(OT%&7g<>4UxV6XhYe&)7|GCER--2WM6s60M z&+lj1Xo|~G@>imYv|#6QE!Spc`L;n^l6*qa$-rbsmhkgqktILk*DZoCP>n0ZP774c zCI>0}5J97j%iPmH4sYj##{X1W28uo0P;Nz7C5pT?a(hr%NMeZ32iy7KF=k|-{j7zQ z-12Do(sGE!C9%HMzO3mv@` z62wBo@lS63bZg#)z#IY}eHPwbS*6A9uycx-+{Ti;Jg-yV&!nem2~7eVcQ@fOxqZQM zzH#ncNe`aoI={hn5B!4R$5YIanOc`cA~JN;gzAKJhY>^egI@Vp-6|&q4T<$9=z(^` zWu(^OcO#_r3UF$p3C9P??!s?4Kwdk72NZW;ut#vXKG_|vRDFwlhv+*-)x6IwB_32a zN@u_=5F`+Zrx@|{7_4RJen=QB@eHrSFwuC+V{bG{Ldu*``GlP8yHLf?jfcF=K5Kgh zD43H&dym@pg}5m4=_C&m=J19KGv#jCeX-_>#`AWFzD+NL;`!wF;50or|36N%#+6v7 zxD~Ji0d}-kg|CRtHXq-Fqw&f%E^&@CL>d)!1LHW6b028h8~M5q#|j%x7>-8p$a1q3 z;^%u>Jp8N8nYg7pzej*VkwM&2&d`~wtipl7ke2qggNP>+ly){0k$n^@7cY})@5=BN z*mgvG&Pc#CPM?^WeDn3JpV&J(T07yT*Y)jID z=t?Z8-sJb`swm(l8Q=#kBZ}Wa3;thw?->?lmPL&!mI?-1k)~+~@gzO#hMxn&Lh0 zIs5Fr_F8MZM@ZOA-(@Y}^(H5dhZaqyEVSY5j-FG;U(~6>x5dC)bcKS3@@1iph{1LF zyz&RTjAqQen)gcF%1}I5lW(&7E>SJt1h*5y4Odzo6xze%Xu6{HvxL=;2x2oH(C)}n zyv?O;VT}`=^3pX~1(uc)vy|HHUz4F;k&S6_XW!(F>*Q<<>HM{JJ0<6?bQ58%r?wMCXgGsI(`^6tk~lu(|9wp}5b zz7@IaiaQ&$4*671A-B@o5b#9})f1^=0{+m)oO266ho5zDXq%^GAP#?OSvq|-bI~?l z+SnMx=JE4OxR0FKf+{t}L!|{~j`dbiCFOBV{LO^3tN~})cJr#l2*qPX-6;jJsneVX z2+$c%m|<&#@Pnz*Qlyuz%5iZ?W=?q76WwPnUA2NXApbsODk=TPy9tPUE!3P+BfOs- z6lTA;ShnwYxKz}V+0Vs1g+5_q%j%9lb+&N-SA*4hw=Gx6#zR+`9ibv+z;Cr_$Zsz6 zTyq$i>mA`Vo++eTDBYCDWi>SkJWHqplonmO<7dPrh1BC#D^JK=-H}S~Y1J!XNjOWorW+gq^*uLe%JlUa0 zFI}E+WPO2v}+Il#?!+E zc$PpbfcNCB1^6E>l54VYdmhF@Qh#hi+~z7 zzKz+l2XUXK_uajRW7@mlLglx(jA10mtqGGgmv#_9Yp%1A&o#dHBi4W8iH`<3OVQb+ z8^68j=|ha0nd`2426xqH(ZIsnI%Ep$!Avw6TEpZLwby7is;#^K)Fgi9veCv&?Paq` zb`r_xoY={p$r5Rsd(|VC!dE z{CYaB1$7Xb9{D*}wD7^bT98uf*sI|OfPs}}Qd>IHI6Q<&mk+oD0K}zae5P%=Hb9Rp zrpl+ot+H;N8^ffVudbdvxYj+GxqK?!G-g1($^j{}o9KQmtGwP$!;EPbW3gXpvw2Ir zBRzm^b5R|2GE)UU&PSnTo{7n!EW0!V-R!Y&1(U0GjsL-C1Jh|v#W2L%%*DBEVEd?E z&0otcA8tBVW}9I!2NW5FmMEe2f(zQXrb*>=rH<`y^p}eq4kJc*iW3M;j@fm))~-6K zyc<}}b=mP{o;Hr<&}IFCzP8!8Yg?Qp+Ce3Fbu5%~n(JCsqqHq5pWbetI)EJC-T5ez z)ng2ZcuMmF3%ypd0HMQGzo~NwrI&v2sjI(p0sgd8Lih$ki5Z#Rc|HJQ%N=8~Vf}H% z5t5m%;R+XJ?9A4+P+;oINKXT~tAZup76cno=Lt?BpM&B=FWG~YMp}Z$j?h>4HEw9W znqktEIi-Yhy@z-3xcQh*SaDj2qVWh;Yx%1>vcG@T_i+0Q(QQw zO6w|_A31T*t;Pey`hlJn+NN48wnnHM@)x}FTL|S^skfB-to`BBTO@I}h!s#y`3Y8* zdp{{5yw_b<AZI2DcCJ5h_{#4{VXnSfYBmRlQL^M96U(HH~{wr8j(w=% zQBW^(+RtY_lgE59y*&6>q$r`iTYBc$E;jnID9-S5=x9;K0n2RpRy&+Pw~N~T?#j6G z2n_5#s^u+c+^I7VFg^V@x>W|*QMjbSDxam@!Q#Q3Dh=?xPkmlFc!r%YV#Nd-Q2gbP z6ay+o(cV>mTS-W@YV9U+oa~UQ#gp&nI1OXcn>{uP`EFk@h)loOv`D!Ys8s3dfH4r` zzicLYoo=MP@pcc;4y&WzEj|6$5WpYbB{%mP$nZnmchov|=utoGOO5_oKDE^(2TI`; z;Dwo@Y%?H>k9Zf|JbDW@9gD9mYqLhq>mBRx{OQq$WGLXN-X%b&7BN2h;@eBt?18+R z2BcNtEu~C#{sQ}1RF9h;{-PRexjN7wj1k|F*&VMLix+e8RS^uw_zby!&;?l6^!rqM z8UVPY`#2`SZpm&StnEHIxzv~kNwNMNNna8W8GVVp2P(eL`@1tWCX0KDECx{Evg@$r zTQ~yd-`tpN9pvgxVzOME>A)=y8D`b>(aVTjwd%;2#scqzL8{-_ikyzeWGb|Tg?GvO z>SGSPtr*EdA2qAM&gn}z<^Vfgt4Q`bv+9;JkOK3at`OQH6YJUz7NO?cd&M}r*g2== z5-w^EQ~`x2o^vpnm;C%*rPb(eAa56}cCu!Qh+Z z!$N2UnQ3*O2>qNw>l+q!!$4WVEJm`Ni$E!{=*ZsRhWw`H=R-a37O~#5UR7=9qBgz; z%+_!Fhf;<;()BRAu!!A z^)9Q7@c;o&d=jOy`^}CPCrj7Wz9y2tbt?Xf8HsRAI)%SYlJI@J9BNX$_`Xx7tZh*J z4D6dN^S&mhp1n<3a4Bo91DJ`5!_IcyP2l$UXwQ_YlXY#vbcjI00~X`w9~>5w1jJ}& zrABt{*TwbOkrnfVIkt4qm{aJ@#68**REu<9)q^#WgKN(ea$~QdVs6(;j}2s&GrJnL zlG$3B-U$8+LCEjT!e*++_V&?5RL2m7Nh^#mpB*&WSUw(tame%w{HBab9RQWyIw_C) zDi~Rsj>|CkAHVQa^(n%jF`|dbl5fDV<0e}wIJRrp&vf0q`8XM{x*+Eaw=+k!!Msf} zgD;#rl$JOg4Ti0C{9Wc)DHMfe@4HvR;E{s?``bie^xRwZeB&>4Nrh|A!h{GWbgHEd zg^Wbusq+{@`b7{yiMAdU2Zrx15l9&yG;8P==xo-W1;Lpz%uDfdhR}?G!BcO1Ng2{W zJ~7=}38er9=NWSPXMWri_2>2uly{Y)zJ1CF&{iih`B4%x`-HqMxZ=*85RPIxX>8 z8~#-+#-sZoj_&=I@t{XtPYKd zkG-Z3vFFm2o1F4juxwqv4%&wXMxcXLn49iXC_+D?K5$uGx8q2SjN8gcokA@~iEY%&kF8v7lP~KIA2M(w5k?r1}&1Xa8jVYfYfDoaO*|D7>m8Ov$j#om8~=L;j0=%wYHT_ z1=fUq5zv+%WgkRecG7|FNx^*W{&@WJ>I$sXi8Ebv+p8L?&*^6xc(-WR65Mg zx*r3#=w!fBWX@tlfLXv0k`_8EUi>CssDHJBDJClFXHtK%&UvAokL@%$C-gSrS78w{~BmCL-RTIRTdIgX^0x z9Z3Pyup;*j5Z){+ORPj{tdO~0KKqKoIjZ{y`Rm48c3Oj5FN=~dc#hjLmJFvfg&&c1V(1b+_C0%&I8iKx}WUt*cpq*=l1X zY#u3+QpUR_uV^iFaLWS3HEsw!8E!6(O;}_UGqB zdkxh(bAM5>(^+*OiB%t{!<{2FEXmpC^5`7})ZekN_6S1$1dky7`CzQ0mg_>)mv`ri^9c}*FX%|oDE#AH1>OyjGv zM?i&jS?@D6Utk)7JV7q3`f)jW&t4kb8SO@PVO@xrl-8to5Jbe=@)D?hmi_sudW>VX z*(6qqWoQe27$~$$P5y%rk}~6OKnzyHs$_C=!=dSr)cQtziFhtLA+ezC*`sb(<-?F3Bx?S(Buewv+NA63wv#|od?Aubk`=EbQ;nJOdk%+B6TwFX2wYEEJi+o zX2eh~rS-$o0=*gk3{}@PS~fowH?&z5HVW>kFu!pTwR^%HOjPf-&j_ARcP8N1I+m!4 z261te*vdH%=2z}<>Xmqc#xtulBV}uT^-U%2OuA-S<|QkkKApBX>)8IC<=57Ix&68L zGL7u%u`)Rqrq0dbSf(>JT$1g-x{pZ6Pnde>esru7y~#-w)6xxlD0i}gsv{1X1X9Ww zZ?io+KxORn!s2)?lwq=>3Sf|rRZ;F$w+)zkO=sni_#|+Idj+0ihcH=MBFc$3jw&bLj(TVI zgpyS$?3}U^-1}YNNS1L{HaZD5rv7}RnfLwxvuI7TjRpqb0Fj6%u#@gZym*fEJngYZ zzdqztn*D5dnqf<#AL%hV@Nhb$8yYa`y7 zj?Vla?Iz(`spW3`cweJQgvqGOx^VbF}l zi~!?K{b+f|2 zx`nEogI;j~dbqiKC)xRtt_yBLTttO00y3u5T z;@U~TSJp=Ml|2x>f*aN@9Kc;Ln|w>S&Fw|-N!Fk5zAygDkzR|+Ru`hbTWOQVSs|>ry>--hRVFl zK|d3|+IZw%eD4jifZ(dtU7~bURJ%5-|>bPn5k(AUHh zcq(-rz>*v&vSM{W9IS%Z^c%g)ok>V+d1d7GmITG>Q&9`9^}1C_u0yv zA9IqOSk5VuLLGLW?Q6J2RBY?|O*C(drH8&GE54^7F&Y{QrUQP5zs`ha)QcNUd?+`I zidE$8{-$lGKgQApeWrBa@Fj81HCL3w`m$6cSuRdM74A+D3R9mT@#{RRo)Xl4+t9#2;)|%OlB}DA#=wiTo&p^c+>79 zf&8#y0-6cBvWdn=|AMstdkpquwbo-lrcQC_k+3RL(z3G4#q)NIJ8j{g8`Y)r~? zQ?gALtgaw=OqhQDN}=OHhg7Av>vB}Tzppi|52H!t0s<>^ zHcC0OBfz$AL4~>Emf=e_oy}lI z;ysybz`NCYsHVj2g4~Bl-pPX|v3z&eB{)hL3w#@~#K%as*OkOOF z9Tz3X+IYw;IZ4|5wgMr7dnZ!7BDs@GDSocIq|ak^7Kew%!9ldi`1Nv-5vOI2&{G`71seivwLKZ{zj523B^vdb5k#0cP28nZ0;UZ{MuMY+5 zF%0B@$8ikJSktsYE7@JKJFmrm^@KK4eP%o&Gnm-@!ea_Z-@t6lwQZaV!yo|Bh8!-8u$L)$!9O8`kna1_9cMp38nU(-tyy> zTOUrexe1=#3BH+|fvVi`LC217#Pue>+4_Pn5)B?OYSKnwNs&qe*{V6OXFxNuI>@Fr z-?nB;f=Jn=Z}`pwl{K%q^EJC)J+>XpFU9B$MY&tD2?uqMXyV!@lj6!d29}2*RmaU4 zNc~)nTt)Cku#_k59CG1X3Z342wm)HqeDFI-ZNYAvp4OP0P-Ou~>kkkz-x)}6-%c_z zW*)!_$t$z#bmzEbTc%Ku8a!!Q((&K)J$jaMQJ7S@^@DgTolB3 z7SOD9`GBi{psdUoyW}>f=Otl1XBfaY1oZMGm&&X7-%rLL$km_Vr!_R68OfVk>nf+A z*hsoo?R=tdjc%Ls^o8cL5QC-#ms6>J#2~LdhkGa9bc>#fnGpZZItpG$eiAPjAHQc2 z4;DGFo|k3BQw0Pe4QyRR6YCy}L+iJAP+{tvDJnYdw4o><3*K8Phj)H%$5jow9G zhGcwc`bf)P_#^$%87B7hT)U{|nJ|B?O>%W(Qh+I*c&) z5fwV6^2^u1N~O?}E%F49sw3E{i^q;{<~c(0pgbRq$(U8|>VZoy&Bd}peSVgMxc5a-Y!?f zm)HpHZ9j8BGSn?=Zu`NLXb_0nyY~d8wNv<|gYm#yKz7myv}VGA2TzGR0HR3{ECdKh zFa7KpCNnThsuVbjbGj}c=Y-<~R&*D`NaV9RZy6q3V!?{map+~k z&tG!p@4~@jatZ_T8-Mt;Nf-w21!ua2%|qC~5QF@2b`d(B)k?exf+^+*TUGeTC96GZ z!&euqgk15jW`BNUF+st&(x+2hW(2-))&^)#|FOE|-#*k!G5|jE-#mGHyf}*3K5ib_ zi&(kve_m#hYr@B4KmRZZG~qMn8}605SRHVuq&WTh$a~}8*0uUX{TyLs|IGtK9@&^> zG&p^f$P0YgD7H^ZgcpV2G<35LTtfT|N4nr__TPTYR9(>+IZpC=VMrPF7QdfFQx#Vk z3@JY%J@w-`Ly)k6O2mY2J1jzD=JZv`7gtUM{^2qhC3c{B^GfL?XIJpA9u?QUM2ed( z$*~m_64lrK=4~=go@M$iok}O%i>_-lOAAq6OhlSd45ME+Y_@;1zGJ2!IQ=19g|Dst zo)7<)FaGJ5L|_nmP9?!NWrX;Q+TZNio8omGj6YZQHWm0{420G`SRX#Jede^JB&|>T zA6|PQeT0wvH*Xj?CMNPZo!SUq$-j9@THDN*Q9t)=(k-|(!`pU56;{tL<3KGBV)#2i$R_edl1C8-^@(g&0JxwLqIebJ(MsY3;G7V9{N)MAFoH^ z(*F-Hvpt?}(gi{OSmtjY(D4HLGQnOG*jo?hU4N-g`oas&%VJPk{JKF zvIzOV%}4%A0ca^+G37e3{-Zr!{-Yy%a?2kLj^uv5b(QVsu9J?1(&~Hyet)?OBnf*| z3=b9yy3-?nIDl54kp4h$YuuaA`dRc>ug^Wiy|FCNRcs0*MSE3pWv>Mbyf=q4*Un59!C zUN76)TL|)A`8+OY{C!#*kJJll-{J+QsDOEy*Hus+{Rn+C$S08`A%s&{6 zfBI$W@z0D`+g=f+%R>I*QmnA7I@1E?E_2G)EFcyR0J>uPYT#4LTOt=(PCyK0u~gq%tmIZ7><@wC`mr0d9?u$^^B2Jq&HY1=(8LLg z!P}7+Pu)KS#v}H_k;kmu@6&)>e6oA)@o=(o^`Ay#``oL)9rwT9A+)F7HS8#Shc30A zM_RNP;mBUo1#*mfHS4iMZc!8}l5|nBMExf&`Lb6T=14# zfr^p15Gs2z=^S~vQCoa@4r@1oZ1IVA2WBm*>i}Ik;jx?3)GNQ0Pv2N0G%0N~Dj(3i z%jzubF^|T5j_?Hg(*Mr&_pWj6V!ku9!iN%KfBM`W@B($rxBVzmO}+4gqs~%PwlWeY zAMza05oodYqT@IH#(;C&R|8P{9gy(b<8^>#hJi^PY3haMsZVLR<5eQu#0@H}hRaL( za}8vC{m&L{UO9@0@#uXo&n#GSw}x9x*=uxE=1le@8m$L+hWY&@tX*5Xv3+aN8hI?v zF(^Ws|IY(+cf+BuU(F2leX7k0{a#^UEbdpA+~^9zi;b!N))2Z%#Cb4_huh!-^|Kp> zp`HQiI6d2T>gIsd=)u3;Y97IAxI_-88ulmVvbgH0^ zz{0GIfyAc}cKsy{A|ZT#lNEphsjrx3C}K<#Lz9~llK16VW>Wv{E!e0%AA*K4q||uf~TIz#XvN|B;5>E0)C$o&|8!r9io13 zuLSH2O(~E}bb(_`7l>l!a*KAJ(Xtn`nG6mu4wfi#O1NJxiV=0nEtJiuG6&02n2UTb z$Tq=sr6KZZf1XjWGu+S^P_8Eujw&z+UqP=Y8U7k-t}0MP&cOUyMNXBhfK<(*z{?i> zNiZ4}j2P!HDFY{U=~mrJ9mBWCd?3yYS=Sz&c}OO1J%Cy6gJDe>*b1|rtRRaFvgWbN zhRr8t)8A$TM==Lt#fur3>sH*td*d*8;N5z`{tEn1lYzZTRj2{?UDw4z)tE8njztja zBmobm3@x+{yk;I8{g!sK9Gf5y%)M2OAfQ$4Co+{wn=Z zu##$@3ljXF6D{)Ye>`MA9;QO*%sdKq0#DkoE{;h9kROEkDButDDFWx=vQ>O{3YajP zy5;UtrtYpByv^vbZDaq5*2qU?Ieb=g`Rm8pNfdxIKGBObSX23=0z_#RZYn!Hqo0M^K!2r12lzjY{ zmpJhc<9Ft~I@oT~ZRa1U|0>$XD?3Vod)Q7XunC+{7Uazqg1E!e-xKlrjHqE%GF-$5 z`Q~3syX0M!IO)e#8y0L%1Rk}-enhNCjAN_ft7IG(Kp&%0g6t(vB-IGBijP4Pghi+>@E!oW#lA{M&Qcl(||3reQ{9oz%p` zg%&ZTGimAcdLM_;t8QQ!hk-%l^L;cpn&i%}AN^}}WO^&XE3EPeVX`U~Hdn8|y&Dtw z4yo+2-gf^$AtgCqHAmnmPhwSCbx5Xfl=(Jb@9bD#&1Zrj=0mw#;UsSGF~CnwKY##r zRfqNMA_UadF^!d8#eiVu$4sID`r7jgU>Rt<0 zy>!uR6}2aDQ;%TJBcr@@)fiAH=`~Z0q&C(Mn=t0DxKM-v%tZvCP0E*5N&n#U71OUD zo@BY@c(A8i56Dh5M^TAKL|-y_?PfXhX}%(W%H?9WwjWmfv6pVqPSZ?9E>WHaa!6bR zOjt6xe0Pbx2L!YeDqxh66Rx!46!~28^T9UFAmyyq&?yHxMDw3j{B+6eO8?rF_z(1k zIph^l|G65%bpUjyE4B%rk{^JV`nkO%IIzGPJktA4*xGmaSnkWde%0o*&+^l1wu$!+x!wQO)4>S+w2e%Mm_ z!=9aLkvsQ!R>^bY1aY_1#~m72BLw?dzI+67mhuJFcg*E0?=-D+U?AyIVM;Wh+i`CC{Yb`mWZm(5yEl!Y*wAE3FQuGBE|&Jx*u;@Pt4h}3YlTHcM5 zGP&=w@J5g$1i5u*>sXCQx>Ol79cQgE&0{2~lFI|?abA@L!@>awNoZpS|aO%{L@~u*8JnE=PfdK(@=dLw+`h&dk{&L;QnU47yDNkN<*#?aP@y) zGSglvc$NC6h2KAX!{j(S)1gQ1c}Qlr`cr;yt*Y?do5%PQ2<3sVr_V5W3?}VYhKqag zm4bBEg>B{#(!CaiN3%)$*2T z{?5WMg_NGP?jXvk7t~hs^C!h!i?Ic>=|11*24sqP`sI1|)!Z$jrF;>Fs&FSL6f^N1 z5sYHalA2Li*aUW6r+UUf+To&1wX+TP9cJbnRK|jP7798cpe}4Al2Ot-;6UV3tdgy* z9>Y4wd1_i33GRuc2a)q*SFgT)=6*)gWJG(|1B+34hQ5=7@Me86TjAuK`ek90lklP z0>K7U|B-nS6G>Q1PdpH`C-xUxfx3j1^Hv#N6E=HvRBzLX?^{of6BjNTWeIY5h;&D6xR;qAiY}%;(H4s zO35^p?0A+vREHk52Cb@pup~YM*I#HKdYCm0$#Ns$bL<({nRTP>jphEzT<_F@;F7qE zNKVeZxXowEPv`BZNKVP9cFwXv{39Xj$1yLqU<}?Mb8}O`u4@E^QWyqysEWg?c!WY; zhNS6;1JFC1Mq;e=v1+)&6?f=0Oc(}@uRL;hmPZwQ zS%8-5Rcu_{x`}31eUC{VgD5kHp`Tv`Z!2N%KFVX*t!YU861hlra6-emwpo30YApjl z{vwFTjm?xv!QaOU?-r@npR0K0PT(m6(Pe+je5=Uf_rXUJ@7QEJDlgVOIDMA>g_oxe z)J^{!D%@AKdZ_SM8%q+^lqdAW&s-pDDSIULeC>t6eil!OPsGx1Z)Z_V*s~lvG-RQr zURw5Ro=&GBPR;4sGiyY7mbd9apw~Byt)*PVQXxv1zY+EVTMG|e7U$I%%v~D zkN2NHrB{@2n5$S~pinVI&N40+G}5dMY;R4 zWkrHrSQbG$Ze|z8;WY{uhT~ez*85EEk58!;2}Q!!hrCiXs)YT7b z;__f}ZMUv}z}sVUoQ8GP)J0<(p)?<;Mab@}UhuoDnd8nnErO4lj_dOE;q~_6eB<`3 z>6{&=MV6=fA@^ffr{?iMS`CY4%2GaF+v34-U$HHsE^Wahcem{_NqNF^x3?oXvlHO{ zj4z`gUQ4>!PqSvXSdDwos{B@@4$_l9>1f%SJ4-tJYT8YCMuF?tp-fvRRdpyp`<8O=Yq%g$?JnX1#UcaLA@z5 z$nDRf)CkUm|~+)F{=V$rF%=v za!{~m{#z}qJjh&1R`6aR(E&( z{SQ{l<1U#zPtd}^V28B%lc{np-rO%u+SNYm?brARe97xV-)9mle%YSLLvrOAt(UDYJn|o`80m5F z?HgKLcWtXRYg-WWn2S;5wAQO3OD@`}7DM~`GmN7$RG-B=&!jTqUlleIllN{Cfn-`9 z{MPl=D_xzoFxl?PLq~J-7JY8LvAs4=^LP@0&aLjQQsJ>;_z1kS%v(@1nHf^obP>~J zspTbaBwNPDi8|S$)paK2|w|3$Wi5#Ww3Pm|Ha2+$Tz z%i?rgPF>w97z>)Dn6Mmw+~zP}L2<(hzI!>e&t}qWB<4b!!;0duM;W>W|rp|9qm|A43Gu0o56|-sGl^`gQh^4QXXBy}ii3 zJUQBO>kZ`yH7QZWO=g_-uuc2xwd_qOO4~AoE1T}K4KI(?rO0rVoEfsIV=w^#c8GC~ zLW=$whT+Tmx9MfO!^=Sq`q)8$9v-<(2NJAa%D87;Hin&NGu3uMOWvz6LFTb>ttgJG za^q`8{4*9Q!}$;XFq+4}Kzzvy*1B()%IZ4v2ArnbRomm->0?osOzsMAFV%L!b=CRq zUTp_l+$VRiizCRB>#c_n32tkBYDnS3{^&Jvf=h{-7!$mz!~Q)7y%X^Z^oq&18~RPw zC6++`p~2{0=WwrXtYUq5prc}$>8$-ARd8HI9Z}7NXKTi<`qvGcR)_P^?GfT!3QQZz zrO!`Xy!dlvFCJVG`dk-r%~#6vFBTP6cj-6@y?Uxr`0;H=VO&nxEK$yc1jl6cbHch( zz`DvZ<4$4{O-B8Hw0WH5sJH##3w;Ni!>I|pMDhqcJxDpiZj zgFQwAwU+KX{f6hwi^(yTrtF<**Nw*S7fo&@ic8apw5)y4VcAy$2#+j}@0M1gh#h-r zw>jyfk3oZ{9APYYpNp8y*AEt7kwDYUb0!tv7=7WP9jlFQv|m>>_n^XT?_j@HLp?dH5Z@Vh2vQ!`;CBZquQVqa(EU} zm4xP-%*EExFJ|;>9Bx=?)lI1|9V2%(JtD?)?>=edz6nnuUD9uMFUh#Pj{Kaw`2U(1 z`N#Pp{Np7J@tj7gl3b?JxyzO$#7Ni|-N(0!g>ic;XT9G~NNBWrO`Z#DWYK^>r))g0 zN}hXzv131x7Ky&c!&_nK{?;0Cz#*m~L30;|`DtZ?{DPG|@`7J{z5|kQtWemz_uZV^ zRBF{e!rW=|Y}h4L8y~q14}hDyS;+kI{B0<(2Ib@ZK|dr)$k zj$aNe{{QNY83TM#rx;wLkYrHNA1{KC!|j1&V($ zhV~!7^)e8V`%d#op8Np+cc5>-f!S58Zu4e3GB8Q5;kMZ|Wx`bH4&S3E>H5>ECd)?f zme-=F06oBL~I?72vLnutj&$? z#fyPjwj+*Xf#Ibi8bmeNy~`HZ1aLB%ps=f&A}2mh%oR;zAg+RQD<5|{dBNgA*k7M} ziGLCsBu1#}-`g6HBC+3k_0~thwC>VTTHZ6OfeOm8*~ruEnkOrT7t2>?{J&4l4ud}> zB*p?e?;>Gu*G2+-(50{dz@{a84;5SGW{Z`f1^?mamhu{648-nGM0P?hoaYYUK!Ju9 zy$ISIz1!M-q&JC`uRd%w5;#Pz5)%#LjTO8H`@ zXTanC@TpFc=-(^h^-Dm1=mj7n1`y~3+Qp&~cd+!5RkNe$&p4_R2XHnVKX<~5p<LAn;fEzU=8irO_tRTTJCC?dP@BFJ|UbG|9yuBcTg2V)ByK=NwXLnb`+a?V-4YD(5? z6pT>x^@2zHAeA`eSMIbrk>4hc(;uH~OVCk8yU0V|{Ja_47IwXAw_@D%vgKf8JX}?o zyMQc|_`0|VlW*rG;Lp$6`9#jvP9BYWD`eB70W!f+PhSBMk>y9+uBXa8z+qFz zX*}$h-7A3?8?{V3@A4KdYx=jT&EuCvueM$HlXxd#-CoYVTC&w9cQVuLKR$;E$Lfjf z;2iRw#3k%}Pk8{1grr(hk@NGQLpA}BpyjE67y$|}YP~KJ2QZibCm-0DC1a_zQ~_-) z2sTP^LvPJndBkYDE`NM|A7cl>v{$V#eGGbd^;7&T&Hv_zH# zcYL;HNv?Zj-z+hvXT%Qbaw7v_?N}IFsn$oVT$fdq$!HYsWQg8{?tU~3U0ffMSOT~OtQ#+P?E2YMBo6$m0m1*`FcIQ)wWjRx`pyeP$lc90zC@NF!PD2@=3vGE&TUzM z?0Tqk3p;z#GC|A*jpBN*TD6N`JlRMc*PCymC_Mf`F&D=&+B+xs{qwcF+|0T1enrrQ zJ-89#*e15#yhT2SpOQlM8;lANl~{S;2J&3kZbya)SPu4@7x!&e;peT6itOGHESVy> zmgS*e2S;ey-n`R3Hwf}{y7vWlRPcn50{C6ot12k3)2#}>*dx;XNEy^Cio}z|%(^pt zR~XoK@QWUo^J&Vo9MBKg$Th!twD9*lK;gU1mP=+wsyw=@IJ3)bXR%vsL^W<~6Y!Jrx_N_5BF%0b|yb^nW!(`tMSLzgx;Taz|GL#fADEp?yAd^2$tW5S6?r4<{48Vtb`2Ws1 zs4X$>SxTnPcRYo@obATF4tp!vp*t8!NLnpU4$;csEl2$5ZKXTU1`E%;H9rr*RI4*L zLfhE{B{1PI_i|w>UILF(e@gxA%71z}d?Zq{PIIw&welh!>ES+c>`Ln1eFvbZ6Xy6B z^af_Z-iC}*YHKxNH`cNO+x-A83{>{@i$wxT{KlVO5|a94Yl=gIkYeS!eBB{7(6+}Y zbG%Q^sh!ty7z%S=_SZ?ub{*%`sEsX{*R=UaEj#e|FrQJYxiJfRGEjiv&rk`wJ%zZf zoAElFkQjGJ+AO!YiIQ_fCcO?a_I}p3@JO8B-JV1iwAgQM!&PhkmT&I;nX6g%j+K3Y z;OlWaXP@nf?n2r&FanF}&e9q%(V*aE6nAy3tw@v#mZQKRCJKaUg zg+&z?u3s#lnwpld&L^093ViwTaL|-vp~~XtqqtE6zFN1Fc+HK9YW5kaE~p z1E*b6c+_)WuE6WKNWObaBFs`FUzee=lHtDanykRB-=b)!gRozNxQ>Z;AG|*@BVoPG zwr|-jH*@!Ny_UxdescN|t%5}l(cn#d#iCobu+i6?yrI{#3{6|5!|!Oa^&SNNWdiU| z(*_9+MDD1P+C%xw034W;w`LrAe>YA$Sa%AzD8mMdoTvF!^~jaee6eES6lj%)twpFAw?6?3QAN%l0rK1eJU}yunUE79@%Vl zK$m6qX09)kEn4<}f*ieSYbKootzjv!@Ol*>P!E2klMI2?&TcOY*W!tjdKi&g?ZKty zobUU7tf0*ZA^v_}aHuM4LYw0HmR%wC$~p`?8A+|mGC81`ixaB`woZs+rPTJ-fcR2+ zxzfRKGgaO#Exu`1*o&y@?)j%jp8tnyWJO(nRS|}ka?c{}vyDPy!q9O4tJFDXA5J#; z_}F;IuTM(*qpJe6OsW92N#0`c6)~HAS4%2GvBw0}92$HIDcXmU-6=#x&iS9Ra$Su4f50R~KLC8wNIt z3HY8&Lt95SXTU125);1&vo4|qEY!Dps&>KxGy4vEjqWyR>RA>#ca_$y_D+|Fje#9S zYrp8XkZaMyXkfJ%7-R$5lx#5e-pYM7Mh=+{FMmauySpm8!k!{g=Rdn35RIop9%YmU z5p(1~a-9#=|1pu}8<8toi_R)fJmyXD`klmEAB|68?x0eSu}uKkUs*t0n<3E%BZb?bM69x Date: Wed, 31 Jul 2024 14:02:30 +0900 Subject: [PATCH 067/304] doc: update OpenSCENARIOSupport.md for RelativeClearanceCondition --- docs/developer_guide/OpenSCENARIOSupport.md | 14 +++++++++----- 1 file changed, 9 insertions(+), 5 deletions(-) diff --git a/docs/developer_guide/OpenSCENARIOSupport.md b/docs/developer_guide/OpenSCENARIOSupport.md index 26012086727..89c9c99b98d 100644 --- a/docs/developer_guide/OpenSCENARIOSupport.md +++ b/docs/developer_guide/OpenSCENARIOSupport.md @@ -310,7 +310,7 @@ Currently, the only way to know the result of the simulation is by viewing the s | EndOfRoadCondition | unimplemented | | | Entities | 1.3 (partial) | [detail](#Entities) | | EntityAction | 1.3 | | -| EntityCondition | 1.1 (partial) | [detail](#EntityCondition) | +| EntityCondition | 1.3 (partial) | [detail](#EntityCondition) | | EntityDistribution | unimplemented | | | EntityDistributionEntry | unimplemented | | | EntityObject | 1.3 (partial) | [detail](#EntityObject) | @@ -425,11 +425,11 @@ Currently, the only way to know the result of the simulation is by viewing the s | ReachPositionCondition | 1.1 | [detail](#ReachPositionCondition) | | ReferenceContext | 1.3 (partial) | [detail](#ReferenceContext) | | RelativeAngleCondition | unimplemented | | -| RelativeClearanceCondition | unimplemented | | +| RelativeClearanceCondition | 1.3 (partial) | [detail](#RelativeClearanceCondition) | | RelativeDistanceCondition | 1.3 (partial) | [detail](#RelativeDistanceCondition) | | RelativeDistanceType | 1.3 | [detail](#RelativeDistanceType) | | RelativeLanePosition | unimplemented | | -| RelativeLaneRange | unimplemented | | +| RelativeLaneRange | 1.3 | | | RelativeObjectPosition | 1.3 | | | RelativeRoadPosition | unimplemented | | | RelativeSpeedCondition | unimplemented | | @@ -643,9 +643,8 @@ Currently, the only way to know the result of the simulation is by viewing the s #### EntityCondition -- Properties `EndOfRoadCondition`, `OffroadCondition`, `TimeToCollisionCondition`, `RelativeDistanceCondition`, and `TraveledDistanceCondition` are **not** supported. +- Properties `EndOfRoadCondition`, `OffroadCondition`, `TimeToCollisionCondition`, `RelativeDistanceCondition`, `TraveledDistanceCondition`, `AngleCondition`, and `RelativeAngleCondition` are **not** supported. - Property `ReachPositionCondition` deprecated in version 1.2 is still supported. -- Properties `AngleCondition` and `RelativeAngleCondition` created in version 1.3 are **not** supported. #### EntityObject @@ -765,6 +764,11 @@ Currently, the only way to know the result of the simulation is by viewing the s - Enumeration literal `absolute` is **not** supported. +#### RelativeClearanceCondition + +- Property `oppositeLanes` is ignored. + - The simulator behaves as if `oppositeLanes` is `false`. + #### RelativeDistanceCondition - Property `Position` of types `RoadPosition`, `RelativeRoadPosition`, `RelativeLanePosition`, `RoutePosition`, `GeoPosition`, and `TrajectoryPosition` are **not** supported. From 178f8881296d7b55bca0ba3cbebba771490d3868 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Wed, 31 Jul 2024 14:03:06 +0900 Subject: [PATCH 068/304] refactor: format comment-outs --- .../syntax/relative_clearance_condition.hpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_clearance_condition.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_clearance_condition.hpp index 5140e728818..970650516e4 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_clearance_condition.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/syntax/relative_clearance_condition.hpp @@ -45,7 +45,7 @@ struct RelativeClearanceCondition : private Scope, private SimulatorCore::NonStandardOperation { /* - Longitudinal distance behind reference point of the entity to be checked along lane centerline of the current lane of the triggering entity. Orientation of entity towards lane determines backward direction. Velocity of entity is irrelevant. Unit: [m]. Range: [0..inf[. Default if omitted: 0 + Longitudinal distance behind reference point of the entity to be checked along lane centerline of the current lane of the triggering entity. Orientation of entity towards lane determines backward direction. Velocity of entity is irrelevant. Unit: [m]. Range: [0..inf[. Default if omitted: 0 */ const Double distance_backward; @@ -55,7 +55,7 @@ struct RelativeClearanceCondition : private Scope, const Double distance_forward; /* - If false, then entityRefs are only considered to be on the lane if their reference point is within the checked area; otherwise the whole bounding box is considered. + If false, then entityRefs are only considered to be on the lane if their reference point is within the checked area; otherwise the whole bounding box is considered. */ const Boolean free_space; From 58a69000dcaecd8046300b12537ffd541fa93085 Mon Sep 17 00:00:00 2001 From: koki suzuki Date: Wed, 31 Jul 2024 15:17:19 +0900 Subject: [PATCH 069/304] chore: Update Longitudinal_control.md with additional details for requestSpeedChange API --- docs/developer_guide/Longitudinal_control.md | 227 +++++++++++-------- 1 file changed, 130 insertions(+), 97 deletions(-) diff --git a/docs/developer_guide/Longitudinal_control.md b/docs/developer_guide/Longitudinal_control.md index aad9f112204..a79e42597e7 100644 --- a/docs/developer_guide/Longitudinal_control.md +++ b/docs/developer_guide/Longitudinal_control.md @@ -1,86 +1,119 @@ # Longitudinal Control -traffic_simulator has various ways to control the longitudinal behavior of the npc. +traffic_simulator has various ways to control the longitudinal behavior of the entity. + +## Basic Information +### target_speed +In this document, you will see variant called `target_speed` which is the target speed of the entity. The entity will always try to reach the target speed under the constraints such as acceleration or deceleration set by the user or if not by the default value. If `target_speed` is `NULL`, the entity will keep or change the speed with some other constraints set by the user or if not by the default value. + +### Set functions +Set functions directly changes the speed, acceleration, or deceleration of the entity. This will be executed immediately, even while the entity is trying to reach the target speed. It will ignore the physics of the entity and set the value directly. ## List of Longitudinal Controllers -| Name | Description | -| --------------------------------------------------------- | -------------------------------------------- | -| [**requestSpeedChange**](#requestSpeedChange) | Changes the speed of the npc. | -| [**requestSynchronize**](#requestSynchronize) | Synchronizes the npc with the target entity. | -| [**setLinearVelocity**](#setLinearVelocity) | Sets the linear velocity of the npc. | -| [**setTwist**](#setTwist) | Sets the twist of the npc. | -| [**setAcceleration**](#setAcceleration) | Sets the acceleration of the npc. | -| [**setAccelerationLimit**](#setAccelerationLimit) | Sets the acceleration limit of the npc. | -| [**setAccelerationRateLimit**](#setAccelerationRateLimit) | Sets the acceleration rate limit of the npc. | -| [**setDecelerationLimit**](#setDecelerationLimit) | Sets the deceleration limit of the npc. | -| [**setDecelerationRateLimit**](#setDecelerationRateLimit) | Sets the deceleration rate limit of the npc. | -| [**setVelocityLimit**](#setVelocityLimit) | Sets the velocity limit of the npc. | +| Name | Description | +| --------------------------------------------------------- | ----------------------------------------------- | +| [**requestSpeedChange**](#requestSpeedChange) | Changes the speed of the entity. | +| [**requestSynchronize**](#requestSynchronize) | Synchronizes the entity with the target entity. | +| [**setLinearVelocity**](#setLinearVelocity) | Sets the linear velocity of the entity. | +| [**setTwist**](#setTwist) | Sets the twist of the entity. | +| [**setAcceleration**](#setAcceleration) | Sets the acceleration of the entity. | +| [**setAccelerationLimit**](#setAccelerationLimit) | Sets the acceleration limit of the entity. | +| [**setAccelerationRateLimit**](#setAccelerationRateLimit) | Sets the acceleration rate limit of the entity. | +| [**setDecelerationLimit**](#setDecelerationLimit) | Sets the deceleration limit of the entity. | +| [**setDecelerationRateLimit**](#setDecelerationRateLimit) | Sets the deceleration rate limit of the entity. | +| [**setVelocityLimit**](#setVelocityLimit) | Sets the velocity limit of the entity. | ## Details ### requestSpeedChange -By using `API::requestSpeedChange`, you can change the speed of the npc. +By using `API::requestSpeedChange`, you can change the speed of the entity. MiscObjectEntity can not be controlled by this API. -| Value | Type | Description | -| ------------ | ------ | ----------------------------------------------------------- | -| name | string | Name of the npc. | -| target_speed | double | Target speed of the npc. | -| continuous | bool | If true the npc will keep the speed until the next command. | +| Value | Type | Description | +| ------------ | ------ | -------------------------------------------------------------- | +| name | string | Name of the entity. | +| target_speed | double | Target speed of the entity. | +| continuous | bool | If true the entity will keep the speed until the next command. | #### EgoEntity `target_speed` will be set as initial target speed of the EgoEntity only before the scenario starts. #### Other entity -The function will change the target speed of entity to `target_speed` immediately. -If `continuous` is set to `false`, job to accelerate to target speed will be deleted after the velocity has reached the target speed. If set to `true`, the npc will keep the speed until the next longitudinal control command ordered. It will accelerate on maximum acceleration rate set previously. - -| Value | Type | Description | -| ------------ | ------------------------ | ----------------------------------------------------------- | -| name | string | Name of the npc. | -| target_speed | double | Target speed of the npc. | -| transition | speed_change::Transition | Transition type. | -| constraint | speed_change::Constraint | Constraint type. | -| continuous | bool | If true the npc will keep the speed until the next command. | +The function will change entities `target_speed` to given immediately. +If `continuous` is set to `false`, job to accelerate to target speed will be deleted after the velocity has reached the target speed. If set to `true`, the entity will keep the speed until the next longitudinal control command ordered. It will accelerate on maximum acceleration rate set previously. + +| Value | Type | Description | +| ------------ | ------------------------ | -------------------------------------------------------------- | +| name | string | Name of the entity. | +| target_speed | double | Target speed of the entity. | +| transition | speed_change::Transition | Transition type. | +| constraint | speed_change::Constraint | Constraint type. | +| continuous | bool | If true the entity will keep the speed until the next command. | + #### EgoEntity `target_speed` will be set as initial target speed of the EgoEntity only before the scenario starts. #### Other entity -If `continuous` is set to `false`, job to accelerate to target speed will be deleted after the velocity has reached the target speed. If set to `true`, the npc will keep the speed until the next longitudinal control command ordered. +If `continuous` is set to `false`, job to accelerate to target speed will be deleted after the velocity has reached the target speed. If set to `true`, the entity will keep the speed until the next longitudinal control command ordered. -When `constraint` is set to `LONGITUDINAL_ACCELERATION`, the entity will accelerate to the target speed with acceleration rate you set. +##### Longitudinal Acceleration +When `constraint.type` is set to `LONGITUDINAL_ACCELERATION`, the entity will accelerate to the target speed with acceleration of `constraint.value`. - If `transition` is set to `LINEAR`, the entity will accelerate to the target speed linearly. -- If `transition` is set to `AUTO`, it will change the maximum acceleration speed of the entity and append the job to change the target speed of the npc to the job queue. After the npc reaches the target speed, it will change the maximum acceleration speed back to the original value. -- If `transition` is set to `STEP`, it will - - -When `constraint` is set to `TIME`, the entity will accelerate to the target speed by the time you set. -When `constraint` is set to `NONE`, is will append the job to change the target_speed of the npc to the job queue. - -`change target speed` block in the below figure is the highest priority compared to other blocks. -If target speed is set somewhere else, the entity will try to change the speed to the target speed under acceleration/deceleration constraints set by the user or if not by the default value. -![requestSpeedChange](../images/Longitudinal_control/requestSpeedChange.png) - - -| Value | Type | Description | -| ------------ | --------------------------------- | ----------------------------------------------------------- | -| name | string | Name of the npc. | -| target_speed | speed_change::RelativeTargetSpeed | Relative target speed. | -| continuous | bool | If true the npc will keep the speed until the next command. | - -| Value | Type | Description | -| ------------ | --------------------------------- | ----------------------------------------------------------- | -| name | string | Name of the npc. | -| target_speed | speed_change::RelativeTargetSpeed | Relative target speed. | -| transition | speed_change::Transition | Transition type. | -| constraint | speed_change::Constraint | Constraint type. | -| continuous | bool | If true the npc will keep the speed until the next command. | +- If `transition` is set to `AUTO`, it will change the maximum acceleration speed of the entity and append the job to change the target speed of the entity to the job queue. After the entity reaches the target speed, it will change the maximum acceleration speed back to the original value. +- If `transition` is set to `STEP`, it will change the speed of the entity to the target speed immediately. It will ignore the acceleration rate set by the user. + +##### Time Constraint Acceleration +When `constraint.type` is set to `TIME`, the entity will accelerate to the target speed by the time of `constraint.value`. +For `transition` it is the same as `LONGITUDINAL_ACCELERATION`. + +##### None Constraint Acceleration +When `constraint` is set to `NONE`, is will append the job to change the target_speed of the entity to the job queue. + +```mermaid +flowchart LR + A[requestSpeedChange] --> B{constraint.type}; + B -- LONGITUDINAL_ACCELERATION --> C{transition}; + C -- LINEAR --> D[SetLinearAcceleration]; + D -- AUTO --> C; + C -- AUTO --> E[SetAccelerationRateLimit + or + SetDecelerationRateLimit]; + E --> F[[ChangeTargetSpeed]]; + C -- STEP --> G[[changeTargetSpeed]]; + G --> H[setLinearVelocity]; + + B -- TIME --> I{transition}; + I -- LINEAR --> J[SetLinearAcceleration]; + J -- AUTO --> I; + I -- AUTO --> K[SetAccelerationRateLimit + or + SetDecelerationRateLimit]; + K --> L[[ChangeTargetSpeed]]; + I -- STEP --> M[[changeTargetSpeed]]; + M --> N[setLinearVelocity]; + + B -- NONE ---> O[[ChangeTargetSpeed]]; +``` + +| Value | Type | Description | +| ------------ | --------------------------------- | -------------------------------------------------------------- | +| name | string | Name of the entity. | +| target_speed | speed_change::RelativeTargetSpeed | Relative target speed. | +| continuous | bool | If true the entity will keep the speed until the next command. | + +| Value | Type | Description | +| ------------ | --------------------------------- | -------------------------------------------------------------- | +| name | string | Name of the entity. | +| target_speed | speed_change::RelativeTargetSpeed | Relative target speed. | +| transition | speed_change::Transition | Transition type. | +| constraint | speed_change::Constraint | Constraint type. | +| continuous | bool | If true the entity will keep the speed until the next command. | ### requestSynchronize By using `API::requestSynchronize`, you can request the entity to adjust speed to stop at the designated lanelet by the time target entity crosses the another designated lanelet. | Value | Description | | ---------------- | ---------------------------------------------------------------------- | -| name | Name of the npc. | +| name | Name of the entity. | | target_name | Name of the target entity. | | target_sync_pose | Target lanelet pose for target entity. | | entity_target | Target lanelet pose for controlling entity. | @@ -88,71 +121,71 @@ By using `API::requestSynchronize`, you can request the entity to adjust speed t | tolerance | Tolerance for how much margin to accept to stop at the target (meter). | ### setLinearVelocity -By using `API::setLinearVelocity`, you can set the linear velocity of the npc. +By using `API::setLinearVelocity`, you can set the linear velocity of the entity. -| Value | Type | Description | -| --------------- | ------ | --------------------------- | -| name | string | Name of the npc. | -| linear_velocity | double | Linear velocity of the npc. | +| Value | Type | Description | +| --------------- | ------ | ------------------------------ | +| name | string | Name of the entity. | +| linear_velocity | double | Linear velocity of the entity. | ### setTwist -By using `API::setTwist`, you can set the twist of the npc. +By using `API::setTwist`, you can set the twist of the entity. -| Value | Type | Description | -| ----- | ------------------------- | ----------------- | -| name | string | Name of the npc. | -| twist | geometry_msgs::msg::Twist | Twist of the npc. | +| Value | Type | Description | +| ----- | ------------------------- | -------------------- | +| name | string | Name of the entity. | +| twist | geometry_msgs::msg::Twist | Twist of the entity. | ### setAcceleration -By using `API::setAcceleration`, you can set the acceleration of the npc. +By using `API::setAcceleration`, you can set the acceleration of the entity. -| Value | Type | Description | -| ------------ | ------------------------- | ------------------------ | -| name | string | Name of the npc. | -| acceleration | geometry_msgs::msg::Accel | Acceleration of the npc. | +| Value | Type | Description | +| ------------ | ------------------------- | --------------------------- | +| name | string | Name of the entity. | +| acceleration | geometry_msgs::msg::Accel | Acceleration of the entity. | ### setAccelerationLimit -By using `API::setAccelerationLimit`, you can set the acceleration limit of the npc. +By using `API::setAccelerationLimit`, you can set the acceleration limit of the entity. -| Value | Type | Description | -| ------------ | ------ | ------------------------------ | -| name | string | Name of the npc. | -| acceleration | double | Acceleration limit of the npc. | +| Value | Type | Description | +| ------------ | ------ | --------------------------------- | +| name | string | Name of the entity. | +| acceleration | double | Acceleration limit of the entity. | ### setAccelerationRateLimit -By using `API::setAccelerationRateLimit`, you can set the acceleration rate limit of the npc. +By using `API::setAccelerationRateLimit`, you can set the acceleration rate limit of the entity. -| Value | Type | Description | -| ----------------- | ------ | ----------------------------------- | -| name | string | Name of the npc. | -| acceleration_rate | double | Acceleration rate limit of the npc. | +| Value | Type | Description | +| ----------------- | ------ | -------------------------------------- | +| name | string | Name of the entity. | +| acceleration_rate | double | Acceleration rate limit of the entity. | ### setDecelerationLimit -By using `API::setDecelerationLimit`, you can set the deceleration limit of the npc. +By using `API::setDecelerationLimit`, you can set the deceleration limit of the entity. -| Value | Type | Description | -| ------------ | ------ | ------------------------------ | -| name | string | Name of the npc. | -| deceleration | double | Deceleration limit of the npc. | +| Value | Type | Description | +| ------------ | ------ | --------------------------------- | +| name | string | Name of the entity. | +| deceleration | double | Deceleration limit of the entity. | ### setDecelerationRateLimit -By using `API::setDecelerationRateLimit`, you can set the deceleration rate limit of the npc. +By using `API::setDecelerationRateLimit`, you can set the deceleration rate limit of the entity. -| Value | Type | Description | -| ----------------- | ------ | ----------------------------------- | -| name | string | Name of the npc. | -| deceleration_rate | double | Deceleration rate limit of the npc. | +| Value | Type | Description | +| ----------------- | ------ | -------------------------------------- | +| name | string | Name of the entity. | +| deceleration_rate | double | Deceleration rate limit of the entity. | ### setVelocityLimit -By using `API::setVelocityLimit`, you can set the velocity limit of the npc. +By using `API::setVelocityLimit`, you can set the velocity limit of the entity. -| Value | Type | Description | -| --------------- | ------ | -------------------------- | -| name | string | Name of the npc. | -| linear_velocity | double | Velocity limit of the npc. | +| Value | Type | Description | +| --------------- | ------ | ----------------------------- | +| name | string | Name of the entity. | +| linear_velocity | double | Velocity limit of the entity. | From 1637e50f1038d078c1958a5b71b0c5999d203e68 Mon Sep 17 00:00:00 2001 From: koki suzuki Date: Wed, 31 Jul 2024 16:29:58 +0900 Subject: [PATCH 070/304] chore: Update Longitudinal_control.md with additional details for requestSpeedChange API --- docs/developer_guide/Longitudinal_control.md | 42 +++++++++++------- .../requestSpeedChange.png | Bin 361360 -> 0 bytes .../synchronizedAction.png | Bin 0 -> 74305 bytes 3 files changed, 27 insertions(+), 15 deletions(-) delete mode 100644 docs/developer_guide/images/Longitudinal_control/requestSpeedChange.png create mode 100644 docs/developer_guide/images/Longitudinal_control/synchronizedAction.png diff --git a/docs/developer_guide/Longitudinal_control.md b/docs/developer_guide/Longitudinal_control.md index a79e42597e7..65cf253001e 100644 --- a/docs/developer_guide/Longitudinal_control.md +++ b/docs/developer_guide/Longitudinal_control.md @@ -28,19 +28,20 @@ Set functions directly changes the speed, acceleration, or deceleration of the e ### requestSpeedChange By using `API::requestSpeedChange`, you can change the speed of the entity. MiscObjectEntity can not be controlled by this API. +For EgoEntity, speed can only be changed before the simulation starts. +API takes several types of value sets. Description of each type is as follows. +#### Values | Value | Type | Description | | ------------ | ------ | -------------------------------------------------------------- | | name | string | Name of the entity. | | target_speed | double | Target speed of the entity. | | continuous | bool | If true the entity will keep the speed until the next command. | -#### EgoEntity -`target_speed` will be set as initial target speed of the EgoEntity only before the scenario starts. -#### Other entity The function will change entities `target_speed` to given immediately. If `continuous` is set to `false`, job to accelerate to target speed will be deleted after the velocity has reached the target speed. If set to `true`, the entity will keep the speed until the next longitudinal control command ordered. It will accelerate on maximum acceleration rate set previously. +#### Values | Value | Type | Description | | ------------ | ------------------------ | -------------------------------------------------------------- | | name | string | Name of the entity. | @@ -49,10 +50,6 @@ If `continuous` is set to `false`, job to accelerate to target speed will be del | constraint | speed_change::Constraint | Constraint type. | | continuous | bool | If true the entity will keep the speed until the next command. | -#### EgoEntity -`target_speed` will be set as initial target speed of the EgoEntity only before the scenario starts. - -#### Other entity If `continuous` is set to `false`, job to accelerate to target speed will be deleted after the velocity has reached the target speed. If set to `true`, the entity will keep the speed until the next longitudinal control command ordered. ##### Longitudinal Acceleration @@ -94,12 +91,22 @@ flowchart LR B -- NONE ---> O[[ChangeTargetSpeed]]; ``` +#### Values +By using `speed_change::RelativeTargetSpeed` you can set the target speed of the entity relative to another entity. | Value | Type | Description | | ------------ | --------------------------------- | -------------------------------------------------------------- | | name | string | Name of the entity. | | target_speed | speed_change::RelativeTargetSpeed | Relative target speed. | | continuous | bool | If true the entity will keep the speed until the next command. | +If `continuous` is set to `false`, job to accelerate to target speed will be deleted after the velocity has reached the target speed. If set to `true`, the entity will keep the speed until the next longitudinal control command ordered. + +`target_speed.reference_entity_name` is the name of the entity that the target speed is relative to. The target speed of the entity will be same as the target speed of the reference entity. +- By setting `target_speed.type` to `DELTA`, you can set the target speed of the entity to be the target speed of the reference entity plus the value of `target_speed.value`. +- By setting `target_speed.type` to `FACTOR`, you can set the target speed of the entity to be the target speed of the reference entity multiplied by the value of `target_speed.value`. + +#### Values +By using `speed_change::RelativeTargetSpeed` you can set the target speed of the entity relative to another entity. | Value | Type | Description | | ------------ | --------------------------------- | -------------------------------------------------------------- | | name | string | Name of the entity. | @@ -107,6 +114,7 @@ flowchart LR | transition | speed_change::Transition | Transition type. | | constraint | speed_change::Constraint | Constraint type. | | continuous | bool | If true the entity will keep the speed until the next command. | +It works the same as explained before. ### requestSynchronize By using `API::requestSynchronize`, you can request the entity to adjust speed to stop at the designated lanelet by the time target entity crosses the another designated lanelet. @@ -120,16 +128,20 @@ By using `API::requestSynchronize`, you can request the entity to adjust speed t | target_speed | Target speed for controlling entity (meter per second). | | tolerance | Tolerance for how much margin to accept to stop at the target (meter). | +![requestSynchronize](images/Longitudinal_control/synchronizedAction.png) +As shown in the image, the entity will adjust it's speed to `target_speed` on `entity_target` at the time the target entity crosses the `target_sync_pose`. `tolerance` is the margin of error for the entity to stop at the `entity_target`. The target entity could be set by giving the name of the entity as `target_name`. + ### setLinearVelocity -By using `API::setLinearVelocity`, you can set the linear velocity of the entity. +By using `API::setLinearVelocity`, you can set the linear velocity of the entity immediately. It will ignore the physics of the entity and set the value directly. | Value | Type | Description | | --------------- | ------ | ------------------------------ | | name | string | Name of the entity. | | linear_velocity | double | Linear velocity of the entity. | + ### setTwist -By using `API::setTwist`, you can set the twist of the entity. +By using `API::setTwist`, you can set the twist of the entity immediately. It will ignore the physics of the entity and set the value directly. | Value | Type | Description | | ----- | ------------------------- | -------------------- | @@ -138,7 +150,7 @@ By using `API::setTwist`, you can set the twist of the entity. ### setAcceleration -By using `API::setAcceleration`, you can set the acceleration of the entity. +By using `API::setAcceleration`, you can set the acceleration of the entity immediately. It will ignore the physics of the entity and set the value directly. | Value | Type | Description | | ------------ | ------------------------- | --------------------------- | @@ -147,7 +159,7 @@ By using `API::setAcceleration`, you can set the acceleration of the entity. ### setAccelerationLimit -By using `API::setAccelerationLimit`, you can set the acceleration limit of the entity. +By using `API::setAccelerationLimit`, you can set the acceleration limit of the entity immediately. | Value | Type | Description | | ------------ | ------ | --------------------------------- | @@ -156,7 +168,7 @@ By using `API::setAccelerationLimit`, you can set the acceleration limit of the ### setAccelerationRateLimit -By using `API::setAccelerationRateLimit`, you can set the acceleration rate limit of the entity. +By using `API::setAccelerationRateLimit`, you can set the acceleration rate limit of the entity immediately. | Value | Type | Description | | ----------------- | ------ | -------------------------------------- | @@ -165,7 +177,7 @@ By using `API::setAccelerationRateLimit`, you can set the acceleration rate limi ### setDecelerationLimit -By using `API::setDecelerationLimit`, you can set the deceleration limit of the entity. +By using `API::setDecelerationLimit`, you can set the deceleration limit of the entity immediately. | Value | Type | Description | | ------------ | ------ | --------------------------------- | @@ -174,7 +186,7 @@ By using `API::setDecelerationLimit`, you can set the deceleration limit of the ### setDecelerationRateLimit -By using `API::setDecelerationRateLimit`, you can set the deceleration rate limit of the entity. +By using `API::setDecelerationRateLimit`, you can set the deceleration rate limit of the entity immediately. | Value | Type | Description | | ----------------- | ------ | -------------------------------------- | @@ -183,7 +195,7 @@ By using `API::setDecelerationRateLimit`, you can set the deceleration rate limi ### setVelocityLimit -By using `API::setVelocityLimit`, you can set the velocity limit of the entity. +By using `API::setVelocityLimit`, you can set the velocity limit of the entity immediately. | Value | Type | Description | | --------------- | ------ | ----------------------------- | diff --git a/docs/developer_guide/images/Longitudinal_control/requestSpeedChange.png b/docs/developer_guide/images/Longitudinal_control/requestSpeedChange.png deleted file mode 100644 index 6b81cf53ba364aac6352bebf871640444bde123a..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 361360 zcmb?@c_7ql-**^ADoUuVC1eRDAro4VUCF*iB5TOLjL~Ve71@_jD%rE|h6-7Sgsdam zSh9^}3}fcKess?JKF_(|`^j^kzjDg?UDx&9zn|~&R9jPd|K4MJckSA>U*+1>8@qNf z!glT2eU)xE_!~W>?i~1o%I${o#98Ktxu3Vg5U<-}!`-^Q8*UTsfcc{IF$s zt?}XD5j~`9)k;ON`t~W%VNLE91`TKMivQz_{_AN-8Tzbf>)scJ(Wmp*Gc7E@#ZP@h zB5oV5#)&k)4h2V@N4nO8V`-7;G}D0>QVzVQnN}z}u&;kjG2q|P?Z2L~O=NK!QP>%`DG2M!I$PPbu7g6wB&e9f>f@dLfsjE zr__Nk1zzNv>M%?~`pNBsYfNZ`$cTPhksn9?2U+>sn;)53jEgjjrpJmT<(5xp5DzMI zybv=fy_e(m!Bjc0hK@nR;DbfRego?$-3W{3%f2qRqOCg~eW%-J#FL)NOX_R9uzg}X zAM#_Y`<+Db$;D?I%)cSE|L;vwc#%s&{HnNluLfDX?|fB>nob_ymB5-)3a%BP^F#2kOC9n7?-|18DpI8_ZX=Y^u2j@2l5ksYhzT3(bS%L4y9xDCuh#hY$ z@yzkd{e*l?f&G#8^!It5e^bsC`Xx>&=k!AJfnl9U=iitT@^h}Y@a7yO#Rj+BXHQ|=!)Q; zUsw1&qk*J9SX64lfb+9dh;W!#UWWnbubbRzg=BPQu$=`-st;l3sTlubf-Q=${`q=Lm07^{fE zb4aUHcgvbpXc4Dl0qx^f1{PTVa@-VVN z;t~Ik^aA^AeTw@J@rWOwMr{n>A{1Ignw{pAuS{^kRH;=iay<4_JGyNOk!`SNlzA2= zlVdW(sGac>`HIcU!{x>@zF7<#5RVA!3*uVC?-mi4sJOR<8Mvnt}?nHY}sZtdL- z8a(L_m^W_-!M86f&ZkX6gIBt+uM0B%dH>%!9=XW2b{m`ul*2AV8vL&pSYxG}%?^dc zS@$Y8pk;JF9%sHbZP5^A^h+aZzAzl7%nS2)eNl4Czp_J$>L3e(BVVJ}>cqlGC!J|| z6f72~8@LgETgMUNiqd&2ERbVA*UqrcR|} z35Vfc=5QnkC|K-+iB|l~KY2s~cynKDVi^tcDxjp*f{`HgHrd)=DJ)W|se>Y2BF%T` z-HuQpjlt`jt5&)Xq#0Bs0{VLgeA+K{vNqN*dQhBt_LWFjjKYmQRWZMwfgGXu)55}g zYP9a|>?rl1ng`%rjB;x!h9lr(lLi()K0e%%4+eo(mvrl29s1WidtdK(cBedJpr(GO z6kt?A&2&VQii+)YVU6b0+d#6Tbi(ek6I)6~!z?a0JKnC=w^Q~QDb#$cd6!yo2D!+} zbgyG(!gyT+w(LAQ`1us)7CUT>Yt{-ICmV0=&>TMkU%uJj`NdQrP(hfQTJ%x*Eb5Pz zDXfwA^`!0h^Ixl3yMO3WVAHi7iLiwqElgdb9pdbaTilo`jFRwfx%7Zd)mnKlUSv^AJ1*Jp5K0j zYP6HQ|MS4p9e#O^fi8CX#~*Gg%(1t@od=yiy!{>xI2ggsV=b`7K^E%zG{?}liRwEd zMqtfzdb-$**i%kyRMbffbfrh~y94m~sfZbpWc0Q^9T5h1Ze(W?I`h{vUQN z)vVFem9}H{87NTB2edvrbPx)wkYTV8tv&DyZoWGdxeMUNT^%o7*_e5>wG?U;l^qL$ zW!c)%UA{82+eBs-vheF8?o!+P?=Seb;BKELP?JA2AL%<#R{=FSQ~GEyDGjJeRY2og ztu2Nrsn@K1JN06RVsRa!gk|J+>zJDN5RJ!kZi(P?5bRO)m*uvIs(=EtXs`@PW7^q` z`SpPIq4-f1`;jWl;KF&EO&<=MP|n{C4Z|PWA~HXaw@+u)BN=x{7v-_Ab4aTYK7y>>OIJGS>pS-- z9enwNMqtHO6oY&P%$&v^wE*5NmHBOwSQNrw>iY-JxgR|t&IN3dQl`X_PXp7~`c%Q| zd$$!^5-7Umiv5r2lb%i6$;MM^L>ISy$ z-fwFm2+`}wMJti9M>qRR&xi)_e@9Fdmjh04LOO218b)^x z(m^@Sx+l?BDcx%yrZc^!x>*ZubDxZV2gx5|LJ zD*iu&n@s1hK3$Z(bU8KLKTH|rN%zQO0`g_=a6&6;Cd+sFRxEU8^%ZWs%r~a0J#&3?xl?PNE=TA? z%Jrb6-JkW;bF`+rTNahPZ9RS_`_47Sn0oX!-AAldHx=%ACJzyDDEY2CN)^2#r6qO)LqFr^#$53? z1Vhwp`r^45Lr-qIo8JyrYu+=6#8~&5c1FI~!+8WQanNTPC#^|858nUXU4q9eRI>XE z?=|-vV_l0&sf9i)OvcIgv8NbY!#D%heyI4Lepl7+R3W+b@ECbL*~G${u#u%WGJM*x zgd_!gtE9tSCBm?-zNutCxn6ZL+hKDW!6s@V-DR#M%S8cs(>K-CM2R=lOB1aL+4kcB zW2K{E>|ag7^^0LJPn>r(J}NgcyIBC`=h}JIrtd=>Dws{o$tRS#kL^^6aO>mqZ99{1 z5Nt+sYR8B8xkOv{Gw!O?!VGygMf1SC3y-F@nQBTog|itRtKG7Vf_O*(smx@5pr?dxMDQ{h#<1jpjuCogXo76|f`%3_>ni+Yl? z(b*8Ga&Fw^*LKhWk&(FSeYKq_0k05K<|*=9%ge54ng=!l8Omn$F6`rh!^#(@uM_Lo z%;9MbUqb_jt-@sPXcFe?6mf}enm6=4`|hUsVf_gjtDHWQuiUELv+DH%xN%10iur0; z`Sr=vrG|@hE|PbZ{1acYV4IS8`}CSUHh^-=lwAGf`-2_3R^Pj-uCTBmmv$Y~i`>H{ zZH#%%NNll@lUPw?uOp9vG@EH@URK zaQNz8zZA>M_?EH7;CvC^TiiGA%t@^j7&B)-7EHRnmo7}#*>ljnXDrSkzmcCv!w7Fb zKUGQ#LyxfJUNbrIVFaLY8mrj=xAM+936IH6psJN1gtG)&Nq)ln1~dt#wIrVHmTw-P zyW%^+`iVCM!Cp`zt0#~0P6J6~??kL5-Q48NO^zgiO*7dB5pARCJ z=0T*dhyCjn@wXDHRJDsOyld8Pqx4jhn``%Q51gNpriEc$8aRom+?$hzk#A$nE}#iR zzG-@W{-jZE`3iYb06r2`=*Yshe1b>%YZZBYX309n^nBxJv)O9C%s3F_4BP%k<(Hz% za`u9RX!fDwbF3}5Ro!}=r;)-v8j;5nA`79;epba{il+Up&8O48mgAd*BR8AH(0=3| zG}*n4;Bw0i1Tn3l@kxtqp4AfRCDcI)PgmyG)XnwQdb_BefBtQow(VGtI3p>d>PnjY zVKJ-977GkM3NHo<5IT7qo@v(^=&EtazIY(e{NAE@t_$-B%0_W}y&%sTAb{;iUbARL zi&5pQqqADrW&?uM@H5XtZdr&&8qee{RE-hNDYcX}WbbtgwoWDwJm6Q4xFV8*NC@zq z2a-=J?9^=?8f6N+OnM+n{-I<(nU2 z&=Z3qFQ;h@+N8gYZqhe(@A69xJ>O)GkBAvVZT_@bvd^t5p1L^F%px@OqkLl(i=f1x z+vuXm;bbr>c=yi-mA{Sgc_jL;_BMKp`A?}uE}i(Y{600T$@BZI$9~yG-A$?Up@4d+#J@T%1|^`eMy88p3}OU75gbE(V*o z%%dq}nZcZ%Ddl&fXc9iXoJhjS%ZC@AB&E*ffC~~?jU8UhmtX^QtW64SuQyvyp5u|O z9^fB(o8-|ah-lJDKC3(b`t-Bn`MX-aM&$UON`CqAmpXXBn2K@u%4>2RTN?-90x{Ek zbK0*{L#kCDSZu+H_cV(SB`{v~68MV%1S5k5v)1-htIjo99d`dKK3 zyK_KllURb@bj(2Yf;}4gbjTyOtGdB za%aAkU5r&Clv|HEqsPu9+rx@OHuSR4ov6pzn^CBtz3P4xR!5?Z+)^Bznpb$}arwpx zaXheicgvnWStT>0)~+@a3@xAX;UOg;I+hIT5x7Q=F!@crjp3g-s32326tF%;6w1ts z;K=p4bI{gs-_4}5>JE$<9F?)5=pRhx4+_Y{n-z&sb7NO>JjY)&+%aBms5|!>9eR3I zdDv#rz|Tnl2*vW7(!K65F}4R$&6~C`XOD7!LIpNy?@KXU#WdkPyFlW-%f`siDouH6 zi4qXQ93y0q8ma{@PN@*}LDUibec~7s2i20ZPiMlrpvyDksipEkF{5hcWHJE_q(*86 zTSXX>W%+!}y)+i3gc_~7u=tsoeZq~2s+JMHP;*nBxwa(~Zw_az9f9CewH0EWSb$5! zoEC@_1s~8&40+>{BCYCt56dfy<4>0id~MG`?FsfyAP@9+JpZ=StV$M1Bh1e)m0-as zyxSQ|`*cihGcjZ^*EfpB$x64<%yE#8u6nVaJuROt^Qw}9dY;o~A@^*j(L>;gl8O)L zyq*j{9$^(OWx)_Zh;0ZT_=+>z4O3>ieg?59Lyd0m7mg`on2kEAq-9~bQSz9}$JUOe z`xznS-NpA81oRG}7d|p1oM%4xk|nc7?`?;Jc~+pIv*L)$KDz3WXTpcl=xzkhGMKMj zJ`~c|aypFLt>ugcN+Yp76Q@({y&Rl3;v(#w3%;}JXw5Q!FFhG_j(4(3sMUiyi1$=k ztP<=PYYE)}(LK&efdrEhMi4PKZayP8Efd{AgmrV*{eq3v3!4U}B_xq!;}u>adTyb^ zi%R__)Im55N`6IAy3V&~U8e5?-B-ursAhP~I@{<^1HOu`$|#I)fB%r4RKn%~;P+db zh3#XO`X>nn>1FVDqHH-FKPgr7{?5~eQTnq^_fgWTfHE@Sx*?BmWqz5N49yvf-C+WU z+*?@j%+lr12CZSVW6!0z;Jf=jam?o6ZhfN;3eLPt?m=wo!uEY7r~9|-jWP%CFMQz*f2n1^<|{@MB)^&$&PNPZ_(L(6Rk8&m&2ji%$E9Yt zT#TjzWi?&PKVzZ_vWF3f$t&DVR#8jAqUER1Kl7XM1sFMBq0)0fGFIb5Bfd*eJgP(W zcBStDu+3uF+mRX(_9N?S5r5Eq4e^D1m=59Tu8$zedCR}xJ|3mtmRm9R-Wyl@XD>i` zyz$lN-?>5IHXV@{ar=yUUinx{UK~mnX$E3_-q@m8G;f&n>v!-x-XK&kPEo-a7S#qj znp5~yl?d`DnWDXuaW=_uh@}K<3**J*cE8N*V%41BbJ505Wh4xO>^AOy$72;wY#Fec zz=1-jab$x4{0BX;0=qd!YBndkl1I5I(&14T(TkzZW87;sd+=V56oc0)!E-Pt^$EDW z!dcHvJaI{$6W6tZ@7A$-e)i(i>vFUXUR3qg9bG&79A7+>Q^8Mos+)t$hvFTruTLu* zHb;AvQwaLN;-_~7^4=@9>zah@`F`jAnPsgDQ*Yu)4XPO5*&=;%wzI!51>^~Fl+_Y+ zlFvlPP*zd5kt7asQ~R6SofHe|otF7MENIC|1J0FYL_>oGTJcn{GRyD zhQ0pDb*VPAcv9+F&mSF74A<)q$UXjT?@C&dhfzScp^e7HdE0Qy72JsXBJtw9w^pk0 z%B+Em`KZL$jYB)jE@10|3$LCvHcB$5vnNXQ)C`Yt`6oObY+zpz<`I1MEtDmQGEX5p z>j~)11P^zQxFKfk&1HQnJ054$1S#PNXL*V{{Mk7xK!w(hdhEoPx0Q;!>d!WdL`p02 zT$MEzYo>f;s}^rGhIgubf41VW?k3-VlW>d+`E&-$<+o4^r*;gUuK_(EVec|s>-QGV zWEE(-4sKv6u#Ldh=$r?padeLiIm(_rI#U0pX1g}+=>;dz!*Ev!@>*$xM@%+%dh zy7V!;-}5T#n%>kcoj4`CKIc(P7kxVS94SM;Dr0WC@I^pZQ!|ifvvEh?qyX4_%md3& zHL4ttl{Aq)w;f@up3-nu{rT|>_2(JKSr|7l|F=0XM~n>6^f?3^<6B zTZ;1XT~o6=*F8Z2^&~N5Ly70!8SxT7N`h0lV7QoDY@-#)#I02_&7>K}iV!nrMs|c2 zXSn#L5*DEtG9v9uk1=+=8$LAaW1RI7?mSc(KXc+s$&lWG&nWucVV-h9fisSaw94Za z%WL?+JHm&0)N&Ixf-$b^OA8^fV}I<>fWA2RME5Y8p1O8UT;bqY;!=S~e{tvyfhkY7 z{FM)Hx^e^GoN|_;4r->#J*a&>V4^ihkLG|hkKjfDh^fod z<^hu%%MMO{YwOO$Q$T?8-tdKlUSh%@*(T2YwlRqp%&3`r(5CllX;pj+>yO!wLCC{Y zQFzKQT}z@j;)HFHU4lG<{8L5(2PH>Y7mDs+$79URm=7P#WbNq(_FH4LUG$iD_vX%gUyy- zj|di^e3Qs+vh#^!yzsg5nVjAYsdepY4-o5S`})XI)j|nHB>XghBXoqRdNeBU4KI9R z)XE7hKb(o{?!SR8Q@mYG-z3Oua`R;`JYcBQn{$cMD80+F5#t&C5x^_^ET6f6 z4-yy;iyEAEgh1CwH;~LK<3O~pT-9m6N;tu@Hj&`m#v7YUY9p`rpmWM7(sQR`Dx6QJ zv+qx>xw_(rmW#XTSb#QGtaC zDYQ(PoZhAEl2A8=ds(80=F=tLgnjZU!w(oWTTZlB40U60O906e$NJ1=NetC< z4nNmCK0UFw_A#f2K}3vg1BATj1xKLVyA2yx7D=K&bed)|se`QeM)Zn7^r0ccHq)@! zz>RHsd+}mgENTk#N!lqwV255pNx@=VH2aWA;+X$+0M4B|<-0hLtXa)$q#bh zFxGX|_=nrqAzk?_qp23C<%sPh}Xu&9?0 zoFPfTa5=BO0$9xpj6u-{Qp-n>POsWUN9DOC$&G8d-+n5`n>U=W!-qI6c!#nOa@u|>F~fWbh|{Isx&DOMiD_- z={C;IC$lWwB$MzlXt>JgtTV!w_%a=9yq~Tb1muy+Bi;jEqoGlEyZevM+vgoPZ&X&= zzml8e`Ia;e_x+itTy;WYcHUay-nY8fhVUMb; zL{GTi7;mWNd~@FG!DZYT?jS*~ziM2+_e0g;HG{g7d)VBW>zXH=vO&@qX|M0Dsg<{{+l!A=DF_+Hkvb~ zl-iBDn&J!C4$Ix7g*jKu7VBWnCEFJu0J32Y;=~Hv!B|$|BHgMqm!IH2g$LX#<@Js% z=g+=eU0_gGr?6%^Mb97#e+>3*^_y&NMF9{DQydYlP&%3Vj7S2G+dQsbdJhaiY&Opk zaqDU`&?uf{K|z6DS7P5hPA3w1-UFBg?6s!l*arB!A6?@-AMa3Ah8|+5V9_@@Q-&ze zy~$fOTih>NHUZKV)71VJE?)q2B%1V03#Ap%pCh)C9ZsuTNGTKodz+%>4qg?odi?+YuZKmg2oMAt_zqDGX~^ ztFHX&23swur~;_DdK0tNP)0Tf6Nm8Sk^)eT5>uPg5nCutIwyOvWQ`+Do{>VQdSIt{ zrV-LC>$O4R6Vn6xM7d_}2drqDnI9+(eL7p!=W~>aqtSXF&=GXg0H}l$-J#6selud#$Ua*#?OZce$cmmWH!g5^(%EP* zWBncI9?YD;2gsx1_Z8-i_G8H&H)8Y*ZasXYA478%0t+PJ=#E;DQ!F)B@g6CQ5^H_J zGiOQ32U*cXUXXJ^b|S$`b8x^XiJXy{6aR7pLB=8a+Qh4D!u5|X)DIdU1wwD+=a_`5m<4aAZL?B!WVhli#ob9S%MI&1t>nfAFLaFgH6Il zP{x+6{u;0Z`FYl1yk?Xxi)&dg%f1t}ahA@Nc_;P~*-dN5->Roh?XDSpCRXHuTblkp z&E$;~0b9Zd8A|KV=RNEDswS2MFW?P_=SO6-Q`P3Zc7%O!AH@o$CEkd`WF$F*^f%%x z6q4ws>CW{7JSW1Qm#HKwTc4^H<3H!NB+(|F8YL1kD6?*~IUP7%qrL15vJR)}Z#UHV zW;;R}fLDuA*1id|8Ui?&BYI=r4<{RWKQ$CSU%AvrF6q>i<(vA(Fu@KO1R8w{tSP{> zcs|vKV?bjgV3I49CEuu)|FjO#-h87EUM+o+ni;k5hrrlDbwe`SrBaENvjN5IOdOZ0 z+y>7N-tQcPj`37esav}P(ooHuiz82XkC|0i)CP@_PR)3Nko!?jq1%U^DauMNBD;|y zAh-Cm7)x{p>5t@;2?*jP6&)pcyb4;+t9=a~#*`H*0zcppp;={tb5*z}up&nNYE;eY z003{`_0JNVtG&50vGq+;*DykSS0ajKY&9j?^L*2s@NzhYE9 z4?$~VeS9${XVJj+#G7Gf13^$CCrts7T>EnMsNdzqqw51V6clfG#<}-6FwGmmIHGCT znlX}kl86ZjR2*XA0e6cSKwzWuiI1czUkSLsH4E$qmQbIzrpuQOC;?%E*fK@{MI0rl zD&~Gus&7ACSoxWl(|UoY(F~v{YS^q&wUX_ukrU1WqFIpMy151nYycqnZmL?}h3=VU z=klp{@uZl|iFIGt^OzDnVB?qH2&|kmhvE(yH63&eO%Uz|g$s1C!u770I~H|aX!5OE zb>$zeGCIEY2ean;M$axGj0EvLp`h}D*EdwZGrDSG*;Qe|cW5a&-tE{dD1#5?wU}U+ zxXgP-P~(Y8J17>}nx@?O>JTn)wcLCUReEx(g}{EP`1Xq#4fUsaygFVhN>a&#nq{Up zJQd)CnIBpDk#v()qhYdkP5REtFrSwX;3uR@di7YC2J94;0jR9wh5<=eUhnA!ve%-_ zI{bTa65{*^!f9$+tEd(H^xR5vJupw_4`lCI-AnXdaX& zP$Ju;hm#gQLFh?u)P)WJFqr7~hIYLVUU7@mIG>*7yW-J?l9w-&`&vF6#4w$dYz}Ov zB(8)x&_wFT6b*VB zc1cr}bImN;+Bh2fFy3(3>Vwq)kogy%Gd#v^*o0|VORfXyiaOhDJ+n*zVW@z4rI*W# zv5Y&BF5lFfjIj^I2v1mdrvM{w1H{o;Xlv@_fm0t9qKVgsvLQ_;j46O*Lqe{*y zmSq8e3P3Nqy|*iYpLFo?m#NYV2v;b}&`?;A*EQNtH%C~K84jeeoBjlq!~8%i!xxP7 zXb6dbrubI_b5m)@(t#IxHM<)Ig~YnL?|xJRUI~Zu)ay;(mc>;9)F9gzn-MsuCR+Ap zjyTIT>Av2eLR;GKY2ry87&LwBwe{6V0>hO@xhf0`OL(V>V@W@YSa>n zG$!Dk_1O=!Q{!Bmy!#Q9%}Dz_EI`%-*ig=Xy`N2r0gxxFBJj0xBHrFE;t-RAh+dYn zyIjedjZE5BqulQr9JW(h9*&!;HistBHBDf~Buk>V*dzvr-yjr-`0BkfP&p=9P}5-1 zAiW#bVCDUZedsy7LbAt1f-+-Hxv=rslJAG>#rTT`i?2EZzdt+KKeV!hqEzx@#?Q8_ z5bj*!O^T+xQ08hZ0ac%ql!K*skX4pBK6WWf88Kvu=i(O71}!X`t_^JG6G8f@bIBF} zQP$Od&$v$@Mo zVPQAB!}GBjU?1m}yZ7hLpX6B^i`3G@A6o$)(c{ZJfZQGt5@n=CsA|pEKC;<0U1#|z zA35(Mj|SGQ>&;SwJUMS-nVz05x#qZ`vZ82DQrIE4o%B+ssMh>ZC&aSxNOySHwdQh6 z0OgV(lh->^&+vvuj-Hw?X;eL45}XB9U_1RHR@EB6I0u!?W}} zp9QE#r;vMb2oBm9a?7S6%-eMcl-aJkX-aw0(UH^c0Q0cvC%1>o%i;#xiBb{>MV*L? zD389ojVo1V$EB;`R+}q5T62aS`Yl9IQQ|f;TwVM467T=o%+r3xeI1lH%{9nSe&l40 z=1+p`{7RM$AJGTYV@xCUq&)8*Vlp9rjeh?a$UWA$%`7A@*xgoJ7={9cAQib2P{jmg zB-+sOR3Pd84UG%BT+~4VZZ+L+zKxf6j@<{1hQHqfGRqMA;d^zQ@NVAr;4Wr_fdC-% zAB`JlBvkwo1Hu5I;i*sowQ-R^ zOt3j=1Riu_0-wuK^IVl&Vf+smg#Hs@j8-$3|;LO2+^m=J3fkig6C~-ZZW} z*t=D=iSWA`Ct5!F+SMb0Ohz*L@u=Vy!x4VtlH-fZkbiAjnw}j1)w_s|p8)4x(VXok zTV9MM!@X1U+f)Lkl%uU`^C)&^F%av2Dl)1cbNA%D+RRiSf znCaIAgO@fSp;G%wT6ipPLWp;YlGj@_wn=i2*x0Hj2hlQ25BZuf9-c`K3}!VNU6fO# zbdLm++pjQ=&t#XFeSO3M66MA&sJ$(6bTMEMR)ejg7U8FqELOSjF}mOw zRb9Aui&ezA-M}+gk)Y0`#^y5(9G$L)cQgm?rX@w3n~qXeSny(On=mMUGuLuvf6PvN z!?C?UU!FJA9zSSsra2#dSfC5DxYT=kH#O$4thf9f{-@!c7#9G(rSwAWAl_k687PhG zR@SO+mU3vaeF-(dT~j;qz^s*YqdiQ}y}WA9Jy-3kiG6kvzAl(epTEBqkC-vWs?M=v zEP!mMSI$e%i*#50vQvEGd7H+t3s8l}c0&>ij9ldTHymR}FMS#xF8stOUpc!`=z|O# zMyM7YV;aEV3P4kdfcrR9Ys?InM6XY0F7ZVhoG7b~p{fO~55}!R+1wl78;shVyPhtF zfm*MYYSY5BKDvDR8!6?%0o68RD7*%cmTt0fQ33qjdXs*2L?Vb)n=@sU@BIY*K+nfs z8KVo2G5LW9^S$fn0VPJXaqoK-8^9V6bm!XRy+Kn}_ZxF(2oW=P^RL>~7kAFGXnI6? z61bIQnVUq3^=Bi*MItCI>5i9;N7Y)bjCd5kCya~j&mf5IrAyADG7f%wx~Gd(%M zKb@Cb%AumaoNj}qB-+&(z2Ood(XQJ z8j4Vsad93En8rh~@5!^E!rw>$$_b|~jy4Y0!H%=99&;H*t;G8uEUW~0m_U!x1vRm%`>kbloNoKSgq)Kj{a_Rz z_%5e%Ct*RyOWhc5S%&&(@b2r6pr$>^yLAE(< zLI{9T%_PhAtg{Kfk3spvJN1ff*_#QWg_eqw5Dd5mT!&?9XIeGhUvjmJI|8T7p&7kY(u{w{P5r8$oDKyz7RBKPpLH%>p5 zkF(-gP(Kq%NR>A9Gm#^J%3J0C1>Kqq+RR}hMHPw)4V}rWg=0hgjwPnmb*#oGH;%pS zpAG!3L=fT*4lJ~^xRUizU+mgjKgR;BRPXJ`le00^%WnZ7RY5vF-{YaeAknd$N`n(oT`ZvV^!h0M`mb^bgSy2xWLTp=`xfOwx;U}n^og3 z&Zo=d4uz$L%Ux*10f{m!8QcUgdt4$rvJGm$ta@WZh}kHi6Pc+y9|EEhA352dAFkjX z;%NmRA>b7yRkMydJ=uBn#~N2U^u!E4q|8|f?NLewQMx^ zYauRylcJvS)xGP%VtJ zxQsU6k9S-YZON)P4$waj3cinGAW&YbiA5ML)z@cuTpG_JY{E7}0$yU^Mui`6@)P4? zhn{%68RF;ha^3CV`0`x3ucHa><_@qTg=T7gkz)1n&s6jr28r#1BRIEwk^XlKM2(?v zpU7HeZv>h;;-f9d@?7RY!g4a4rTW>5fL^08d1z9`Ll#tDtDZH?RW7ypf#x(-yf+vm zJ*+h~>6Ufa@SFkY;|aEpy8dS`fY1XQpX+3NQ|pUxkSuL-M%la+6)o37%w3M;dwP&L z_6yk&>S^dpg8FQ99Pbwpr1a_&!7!t%BWzkp+`6k604XPN^}ejahm!t9M`*f zn!pClbWWQ_C@Z)U{Q;nlFd>lQXaE@h_zaKqzV$`F13(VqZI+Ve{cI)PJ;=}S*!6LSI+exj0ovShX#3bGCoFN${94fMb*B5%)%0c zo5)C2YmWmIFr(!P%q&{}XP7Gqv}-G6f-cOh>z5g1LdV5lv3tV=vG>7P`|v;%vj6CetNnv`wZ&5)KzNqMWHQJfs1Or<*7@J<}O$;eq)KGmbz>%`aX2n|#q16G{6N;d0!#5cV^KhmSY zIN{azB(op={m2csL+n8Ds1=7iw4c!|s=bLa8O_~4nJPk7>>;GxVDRsoecvfS#tW<}!}N@MT33QXfZ zuR0$zIg&XUjYVdc3|*jnQI?B022i=(b>UXQOCYFX^x$8q9m2f_f8D|9Ms-fuMJ(HZrE@;qs zb~Zd^g)SuwZhF5%QK!1Y?C{Kp`cQm!ALPHh;lKkjKPbhGauG`5Ll1;=E4Ls;JY@q- zX@=S%HM5Q2%+g%uIn0i>FJ1Ui67sxXq=RZeg{?1rCO8aQXkgbC&hq9HZ?alp$H7zb z1w{bU71oczW`5C!eFAYWH_E5FgYBVjAq9eJ?e$c`mVmAQ5+`z#e3%J-eY9AQ!8oTs z+YAT)Us*jmzk7FXct@h-XI+5{ybfHTEC1S)d67LQC0#V((@DP5>1lcy`!4WE>j?#S zotzo3INRANn@Mds^R}~*Om`xo_r#I+9Eru7tNj>`xjqbqgrTUbf1CuNhw9f{Aw(K5 zoDVXhBul0%(eM zTXm@dF=no>KMc-VQU<%Nq~I!(0;guJD68{2LH#4x+J9Ww+>pR}ki#5a(uK+OpS7RK z`EFWinA=IgQZ}*apq||7xmdZD9|TPx)cx%CbCTkbJ`@YqZ&ZUGhn7Z3JR4PhYjN2( zv}L@r*C+PACUcl36wjbkPf*{plAL&Lz32v8XDtDCEo-h!qNmPoR>HUf&|nY?8eQU} z!fn1ftx5!awu<_3Cjo>nM?Mr8Hn|QuExD%cWGO~Gl&BAUIr`w>lP>0Yr?a;<5=EMm zdp`Z-n^!JS`H|{XX-=hbOJWk(m@6>RZ<#uw$>zEW4psLr^qTLZBZE4zeq>KvO|X); zBf%i+qhXtyi*E6?+zb-vgbXY61SF5&;CB6Te3sQ}tW7L|@PRXOc>&DwzSD0F3G9F7 z`RYe?D=5)UH^Yqlr+ASS%HNUQq7S@9>+Vqlx zdP=KX&NiRR(qF9P0*S_ii<3*Rjd78YeIgbNP=Mlfl}fcG?WpWrX=?1l96!0W;Rlf$ zSH(efd&p2~7LtFR%;Rh`E>#$i%};-``|i%1DGf@5&?Hdh;3^;W2IR=}$IcH*#sm&u zJDzNxb(I}cnr!V&0pVvn1*Ey^656;DO`0HX(EOB6idxcM*?7e66l?CcSf`>1bu@LI z)|cUt7R@r^EA`3+zc|XZNGo;lJ9{Q4TPNtMgu0&b3}Thyg2q+mFc>3tmpz^9%^dqH z&-n~@;x06RyKwP+J*tz;crG@}|9ZF{Omqftuc~o4wG#0az`KTuyR>u%?Up%!vSogq zyl;Mnr!)~mryXn&YUThHhL|HcJ-#0=)6gYWfb^D11y~ ztbvJxy!<<6OjN-O=t1qrJDyvUGYcLs+_37 z2ObK@{Nm@!aLGhy)F+)~G{($lD&1G{!*{4d2#UVic(u<2-RvK90;P)d87sbSx?&S3 zLxdn`#195@gR*iP^g8yI+3`}_ff<||C_UpKn_Uf(5iMG0W$imzH#jrnq3DU2*T9va z%#~3LJt8AOsm2=KZ!jepq`|u@zqE+`d6{j;>q@^?P>a5yo^OwW>e=a@8Q%$4Q~Xj- z*K}3h9-H=j!HN7s5SK?|4`oas0s?N#G$Dm2p5CTUh#Qw0(p7d)#^TXF zZt>BQ_L(US3uH*+lSBMKca7K)3#SNz)gL&IX0W~J3O|@k4m`av?39gQ&nIYmZ0DIs ziU4#d&zb+^P%ranYc?Ch)sM)D5tNkHP&h?Ow-0I!x(^*nXS7DPxkTyiwI8+HcJ3*U z!Q43~|0>nLz~SFB0X?Ix6Q%B?1}J++!6%mFUC10T zyuVGU?k*`K%Pl5bEYpT)$#Ny}jb{EYHHuE1;pBY7q}HMyH8t#!;$M`yb$8#`gDpz! zdm6ZSw;{FQwqMtO#PA63zWhspHAlckhF=WdJ^SRu*6Wc@&~AhOoZ(KI#nG%()RCwE zWJdpOsY|Ncv%Pj;<->nYDdpCXyRv}a;>uu@d_9f|3?@&k&6RJlrDE|A=aIjKJ-nqHRigU?9V0OCasCvj+Btz_v^^9sF1T)k&>Jycj=iX-~M$(m0#^!jjc~9Y5yaX z3K>pxG6V+q+FuN3|5|*hc*~#Er2Hdt+mOP4r$P)kN`b#rV@*<6_3G9$F8ni;;%v?F zfGW6q|6(}HkTUnSZAHS5va5&d?tz;eE$ffjubi{%><(7)>_Y>y{)rMYcJCfAh_@o3 zbzbFsJUm|a_E*Sif&8O<<*eHFhK-PIYxVg*wN{bdL(hPvsVCru4o7y46pjm@!MQrj`!Cow48niM%| z?*6}vd=xE=c)aBwA@-JVfJJyhe+h4>s?~ASwzblNqO0(>h(+E1Wf%#2M>{91`K)@r zdSm?@OTQ!Fx((7+?U|!mv^7IfIc#0z`L|k^0PM?Os}gNBQqIYN&579;kwB1#-nQ*z zt4kq2h+XY9+v3%c@`nW!v0z+2yY-C+aE!2HbS8++mGNpqd8316lusbF3a5j%Dd+aK zGZ_EXlr;o)3PZz@5i*t?x!83rT44uUsKA~-@mnsF+%NVW&>sFe@@5j6nP5K4VsZvD zpEY13g2|k(*f9%PTz8}(c&}Nv=iNWoC?4Nl^Cz>P2^^bv+h=0IS!=Mi06F088o~uRnYNJRkJ&6tV3M ze94^)Kzv#SY1wvCzooYTb1py1zqDP*lRK=|oEJ+^R_!NDx?aMj1X!doLY)}lpj;4|8S z3pF&1V^BG-Y<}?mU&jjzXC`eEwB{=P_L@V@Pavd|Ogn6{?F4@B4z?$NY%%jZ7BCxL z9r-*Nsd?e2RlNq`^JpLY=u)ylhxqumH*+}V-=#U8-;3xvp!rVCtykMHY7g0y%t#W zeQyisSu_Vjh)w=ET}byc55R)Nk?+-Bdw&tWP=tr4boADLkmo3`?)4vu z8@)P1-_@SxUrdxSq&Se%Nw zm9|ZuLi%&tufXHXyO9a>hp$arFZKQ0_v-=!v|!mUv-H*J_g_F7nEKLW2T>2xdtRVy zoJT6?Z_&{JOTA6AM#$kQHFW9m5=g$6r#+G0R$(UqGWjf%83 zEaW>+{Q%tO4ntR;;4kHmWq3(J$$mjLJsFZcY94BPbSG=Qj<|xr_%Vs9aj2a>E77|5 zElcFvB`~Ec1FfxC0!uE!h&Ns8cokAqLAxjI)-nS>ur5W2kS&2WkFf5wdYq#h`AX$* zYcy>*l93>WR}ZWKeXTKAP>d#mF_RYvfciI%COLoO2m6HOLlX`w(=Y4t zq~|g(GztA$DBONE#Zsidr?&CP0Pql@m%I-nw{`k=Al)OEA#yFe`ttP)U8Qhy{$pW& z%^0jO+U6+D?nt9OtTsSl9){M4)2mN!ydPLU@z-MYl?&qPRx#JVsFgW|UQQn0!TQ4^ zXTXulKaq`d?ey@A&H2H!v6Y=-Xt8M`$4Kf-VJDvy8>tI z%M0QTqcOKIT4iSYd;`YAcksqb(18oD8u8kDE6+9OqjX`gXzUp@1CREedh~&-#!QYu zp*0`&+CHvFbK*lTT5UfPsX0^gA3tlblZP8}t0Hwlr>%9g zwSdMRIto~0FHe8C*eC0Pc(nU)n@Dp`TtJUjVgNy(t0`LL9o-x1@kJDtHuS&jdViC; z2QA4w+@t=*Wm{o?CqqoJ0&kY(-(HWml@a_Iqtw6{);9WJ@_vfji!p!4$88=G&wJS$ z^Jg!>tvvIubAR7tD;`Eou09{8r5pEKrVF|i*kKy`LHai1)nCBmpO=J~tE5_k?NOR` zX#|e@cP7}y9zxOBB+@k}}z6ak^_B(2^{X15t0UHhE%^v=J>EvWyAUb#D zhyngLZw5Z75FPj7J?nqr#kLH`R)BA{4z@+@;9J2^=Lg;Rxqm?!7Qh8P0Ac<%)xg$g zK(>k*LCL>;4cT~Tfl$=wGo-5aJ5smxJG(*nHKOo+@b9u`p$;SYJF0WNvHTZQ_}6Sf z-eLvudMqle^6%=m52D-t4dw{>zuo))_jd8!fNo*6S8hTzfd6_4B$6HoNX_Kn?=SyQ z4+G9Oaw#k7?@vwH09@$y*Ad(S`pgHopvDvMFNz)QkHAZdkmEaO4zh3pFKugW)&1}9 z1f;nP6zkis4d1`R))XB0)@tJS{r`<*;8XPm;9K=;KZJh2pYaGQc<1ABl`ntaeqVEH zFW|u`IZ5x|&n0<5COPutqImD$=>|5EBFxz{8jef+3nKjeEzsXsz-iSDI57W*wYLt4 za&6*<1r`KEK~xl}RY^%n>9t4!m0nVTr9-;QIv9X7qJSbO-5?DHAxn32q+3810fBe+ z#B<<09N*`>-}jHQb>H`OU31Mf^PAtyOr)s&_fIwt!(P}rUvl7|r0c)nb3oUR(6Fs9 za{f^%e#aM35AXtVD!%@IHzWMUVHt!)>`DH(|M0fag4A$gQtN{t$}+uYYQz@|)s4fi z5Fb8pk7|D;JpGpa^g|>=P}f4(P&hV>6+JwvoZl>WNzIf8P7N7uiS{Q2#Fp2%HeX=SM- zdNdW1sJq9*_<2%+PA?q)zVj>0T4| z`+KMs{8GKT{oIUYj|o6IlYiYrJ2M_f-`nG!Ke?(h8Az2fgR-)6 zvFAem<5h!$2qm(jf@EJvo!R3%cUdY|EpN)-IJCzwe)jCHFY z|H&2pdx(Cs)Uf)qVvKovNqD>&8LWPbn0_A3Pp(R?9q-IcJ;fAonK9_{X(%-PwCAbZ zXp9_l4hwZaRE6tJh9lMcjC{{ko-m}~BRN6zn4lVk3nW;h*j_1b`nJ@wl`Y5I%1a&4 z&Nb?BC`A?-NsP6;#j_e-zNd6h6~H#X$F1P@*Bi1O6*oK+9M{$_f zuLmmG}GZHOD`zSM07oDRH5d2(JLML_?^(zR&tzXww#rIflR0|Ev@hh(%W|Dh+ z`lo=rz8>$!OdYM9C9AyOBdUVSNYcaf>qxhq)o%m;{SnyH&hZIR2hc}XZyb6kgN#F9 zm(RzoD;w-3EmWjuK?E-l*Zpi;i?Z2WhMS_0e14UGA1Fb!uQkPESQ#bz`S}NjP6cZd zFlu4bMDq8V-q8q{-LcNa*CPKlsef$&s%yi-eMH;iyf3vH#ZQvfn!2uWZ3DafvUDFM{rPJQK-S4v-B&H?-!G7b^hH?^j*CX1 zIY#$7+fYbpP;T7PLE>dHyVUH?d+Z~)WLP1`%-`YKERA~SY0VbSV<3Pu-O{~ksEhi&ODVf8Hx2*M^MRe8OCY`I0O^!E%jWW zy>gjde{y>Hl^#3KPaWX7uoPS&1|dm<_NS$-ES!G& zOTQw_gs%_5%#UpS%?akc6f%rLYbaGa^OygaJ$o&b8%uKoH`RBj!+HaEqJwN_k(N(fG zpQR3%6=a%T=qt?ZEpf3Ojwc}BsRaG{4+nePjg|CxMyXR*+^xO_Qa6C{z&>>R{j0{Pot!N&>rUpf8s35M@0FpERP4dFgW)hR|9QU|5|HmS!2J4;yaSXG`yj*E zOPiURV>s{t0pbgJ)P!>X$Jw1<-0`SNa6Skg(%3EByOch%i})cZICBi2U8a7SJ+Fcv zP0{X)#>FbPVG4AfXkz?cZdlP{lwViYRO|dd#_$4{-*tE-S>BHlfTWjC?{}E zNNhS%!h6d+TzUzK*-z|vYJ|Ot;Y8z$>F*;!B248WEBc}yB3EjtNO=rn1*#NZBX$ko z&t1GEi$4n|wAxhn{P?#iSkjLN<)&>!Nh&oNf2Y0r37rG4*xv_CJgWcd!X1)vBCR11 zf)F>KRpNbw^MvDTUt%Ao|7{$9yc}i)nX)-+b?MKC`R@sbWA$A-BL&xjX;bVA9FpMd zZb?2Cb1BnTU;ED#A${<6zfYi$nHeQfs3}mQQhMOACqErcWLt^h01BSgzeP-cto5oA85c zI&^;ECxbH}mgy$)Zvw!-|A|bz>CR;dzU?Q_B+=$cW$9Wz=-Fb6_(B>rA^-gK?4IWV z=z5SF3M!4gh55IUB1MS3v-TtK#l&eTsp2p0oTXYlKMvKTD9T&u4GlV+?)Okg(0pWS zC!+VfUabIL^W_pLyX^V#Z;M?k>z9Nx9OgIq{C1$kWx|G;P;#eS`8_^hHB_!wS9X7M z@C=w6bv1N+>yJ@T<(EDnG)!;jO#G$R3`xIkJ|lR4cBc^hO+AjrRw6ept>HPe0*v&i zdpj=_yg|qy=E%oXU3_YCPJKSL<%1`6)=gas*O^C)NczzwPqm$uAf}aAy32 z)&c)Pt78{M-ctMJk^TQN%I{S$%GDvCxPk{U9J|!(lIAevxC${x2Y-O$@&1d3}g_uUo5g%zq|9R_qej$ zmNCmW(;6<=7LXSyss*9m65>1@2>tKqGt};7kOn^>9CvAUlS4)R^HxE@>6K^j%iVQB zfqOeot$l>Tepy6})>oEk{7&;y;ntqc7+{*E_ZS%gf`VXf?YI$B>Rzk+=X=l#%&dZn zV@c&&+b$hgi^kt3w;(}~!tW^Jy_B^57rFyteme*L=Ow@vgZpgv$OY{6>7VZ%WgwV4 zewsrf_bSbPEKH>kCZS$-3kxMwz@#$&rfu&(JWAG z{E+J_Bn2+>9`^>|<72sP|Eivjb3us4ZZZAak``gQFM~QC@i9mspqm)e6 zKhcc@()b0r==Ci6{ch=q!9PI3s|4FfE^X?PiktThRoON=@zqee7f&O#K5d0P3=&RZij5mtVIonCVBbX;v?b!>5YpCP0f zBi2)>pQ@3Lzj>7JFzPrF|6Vu_k}3dZ-uS-Z{axPD-yU)_#TR$r>8!`)=QKMP2bDqk zS{(WP)gzvV14C3)&j%8q?rM1e11Ifq1mXzQ^HhW4X5L+!^pEr9F`3zrC?-wg>_6BW zzyF4xJ$~~da|sje8>gK@a4n3u^)Qv^r(>FCtAadEA8{&iQj*p9k_4X$6k~x$Bv@eE zn`b@^RTwnXQ#I5-Jv^q`k)r-+&cS0Dx?80}>F4WC3xj$>*1c-@gxM6wsn!&$o}3it zx!x4`!E~=>raF}Ta;Ts0#({%vVLb!hRfJ4$SAs01)7Pr~sY_$^sW%c8lAj4#ri=th z>mQ`$znrd9sH_-gX3~>mG7SZXAK{Ah%iL3LeR`O3Ie6|CI6(qp3V5`#Wus9K z4Z1S)I*fuOlR7i>EHO@cK9EqBC-s<4geStLCXitonnr2r6+2!B)AdQ?4Q``&>I#x}4|cjjzXa(YSt&OXA8JHMX0GY` zTW%uaXn6G{G%$rW1Fx(@kr*;Ap?blt`f$!SkOQ=RdHLhU!kakn8&C_$`TbJb63cmX ztD<3M7d5Y)NGL&7iSyizOAijIhjVJ;I;5kouR|L54V?n3#c8zTMw)hR-cl^22v6d` z;+7!_|d zIWFmAw4_$rRr8n9i;W-4=~3^qvd*n|nBDEl&3}J(iUsKjd!}gw^(Vs5OcbuuGP1PSfr3D+@!?#riKV z5(}9%BlE$qG?V0?nGa!6YzIbC;;b99ZG8l{Wa>L8tZOu;h$cIP?`G2upj(2mv!1rF zP5)ct@jgiFyu@HvNq}C5dLUi-Ruz6FHzGTv-SB6gUVX0cI=5!4B42iy6&WETpP?@r zI@o-Br)8pGz!G2TxweE}$IbQW$kS&+e}I4pjs6&6>yrZ-nfj6|kkEaZ=&p!$?`!C~ z_Q32~fzI&vN9ms%A=*ciZ#mf6sLubM<;hNQVf7N zvJj*#($qP8Ymu$_9J$Yo?5)son7k=+Qhc8xBkQoO`g8aU#|DhW4D~nNB6|~Vd@-Om ziP;+CO>votp*`M-v0#3raO)Ik)zN2y0!@ujAxvwy^7-7BxyVA=Q8$9+?>Y1I%Tb2! z|3bibVbK7HM;XP}`nTx(D*RJc!nGri0@L<3WVZ#1}ana9$) zH?O5v*m+hz|o_(cI@M` zAC==a$i+1Dhg>nm6fk+X8B}vznnX*IeoT{oacoLw5#Ac1?$$qi4;f=w0Lc%T)XAFVstNvkFA6^kb~Yt__L2 zN)Wm49ZKX9rq3VhKSJ6!=IP4}UW0Pol5LBD;(XIJ4C?D>U8rPRuS+dOjk76PvruG_ z!-R!7I^QA@H``;xs%T!uN96y2k||?l26Vhi3MCA`ZAlswci;~U$}WJKB@DYYV>$&^ ziN=oe`0?`X5<3=%px$hK-Q%;XL3MgvxP0el8^A9fEZwlY zH&3;9TcsC|+L8GlaFjL@<~BoRAv}^C)^L5c`5T!L+&b0UJ-1CHd2 zK@oZCjrmEBXrV&)m1%S_k6tmmxj}Ox4AEnCK7C~h>If>Qi1VxFcs<6=bTvI4q9C>D z%}YM>r0f1nW`#bd&un)#`i95A#^8Q2>DuQ`guRPR#hopC5eR;E>;O$5?RYbzTt}=7 z2JqP(11G(XciwW%FA({I;x(q3vfKpFOilHTvigVn2URyWRyB|7yS@~IZQGIjCN^c$ zvMb|-^Y)ks^4-;F{_@^a0miI1OB~{)ymXhPpf?m+tWFgQ5Oow-_nAq9ee=9Et?C{v zl_#{`F!OpQXdYrYR3;1+l48(Xa14ltfb_$eXa9P!m(Ok(mHy+LQMH-;T#fb6M%wm8 zKN41!c!urQ_946Ai5-u>OTq6P7ksenXEbMSyc^s0qawy`1jV};W7_-?2(}}RmK_^l zikyuOFNlw?r1-X+KMx}VY19ZOGuR|SC|j`!y0C+m<*P>mG@e)xP$7+|G|yU%X0pt-{3opuU=Zf+d>C8M(pAhsS4rphn}{R zf7?(0!%I{(ao+wLMnnc{r5-1-Zii39aEa|~Zs8O!|8clfc7 z=~KmH79*UIVloE*<8<$sef~4?lEKriz0n7EX%UnhXvti^d3P*^IQrE2Xl>VuwQ)N2 z>|0mn^i$xtYw5ZDMkOu-tozggn}HPE{6MPEB6v0(OU9Q_Ssj&7u`U^QytH-b4owVJlZ|FYR?!+nS0fYvMt5(5Jv46(tA&Jjg+58_s4x>BLc zg8a%=cE+;FK=>T_>y%hlhu{)ksrI|#4O;k2wK``?W2~z`yCz-nCo!Pbbb!cVN-rS z$zBZF3wlE_r$4c+*epo!S`;pY5`^e2@U}!lVrst5<~BL+-p?PTr2Csr7SO!%b^dW6 zn?dc#KRy57PTRj;Ub~DJ|NK4F@o#oBnw8KWjvJym#%bssCK&T;5l`-X@4<%(AT}?z zHa9Hiq@kN@nqGF-dkRwFJ`t<#EUl6sr9}`%%ioeWz~1v6KE2)`>nx~4XVBBajNTKW z`{_ep3q!yIHavKtExXHmd{3RV|HHfo)8t^Cl_oqT6sbN2PYFkx2t4IrzNIF&Ei~#J z%rSX%_WG;KX_U}*?rlOQ?9U%CkJY`bBQuW$8tw9U2k*D3NbA+xHV$*T0mAM0dE5hI z?Kvh+vbp<)|I2Qb(+4pT8vM{QyEAY=fbb_By@mP;iC?piM)8)0zxk(ES%m)J47uR< z+zQO?Tktp6Eh@s_f`gy!QA=|0q*jd4Z;uP@T9UtfdQ{V^dF@&}gyrcibxK7-GQi@` zF1^tRHX*$>DXH?7;(q&&h+89^kEMU1;tc;;?EkOT-}RTETm6LmUCe!w1;${Bu>jRa$*MbMmrR_q2!JWYk7Cus7WF@Pl-H6 z!YxMw5EZXHF^zO|;>YUg4**bP%mo#mzL0D3IV@mI63#e=Iyf0(a@P*g@_)P@;dN)o zUfgN=sAb%@+mp>NaknIf6vgT<>#InvsCDHb5EBh9EK`$jg{xby6PWCYzU>;`-}m`w zfiDh~GIONKYIg|tB30IY$j@V%w5hiWL3H=dXyutbjlQg-!ZPU$PF#vw@{MeF=6B9p zKi1GixNyKkILMxdJA-CYiMgkNc^z(evydgcKwdO}(4VCN8ZI$dR$%XnyMHq)WIbPi zFM6Ks*&63DUsUt7+IDyzT*|cY4iHyaZQMcc`fy)skIG#7R9XQ{_apmKn6cus0KKG1 zh8TRltwZ{|e2#aYI54svxe)d5m2RypUgs9>kL}qVCBA#gkh1gO8DyiCY9x=aF;88=HCDiU3D>r@Y=3)LsW1Kl z(F%N$jQ6YSJ-YNItq zjAoqbf>LU?gmu;q_UpZ~d#MqNU{&;8#IsS#zkfLZ*8bhMk?MX!_AHx_w(>GuFUMHk z3Cf|R;#;Jhvy7HR`+KlhgCU#ujfjLIE5)gln(BFwLCoDwQ|ssVG|m$5L>Ygobp9ha zqfhWcGGcD}U%o9KqMUjY*Ew&CU1tvNDt~>_k&~c0{H(ftJBz?pXR4-3IESiCpJqB* zDBrj)#H?eStE5$i!?I!%_lSgBXHGHS+MCcnG4SQ32Nu?X>9e`B&o;=($=k8f0_jN> znchS$EJy&bif{KJ{i-^@6zau~2<^Cwt8qT$Z- zp!axjlNg~`#@}bRGTk9LlQV5SSXzVzb0aO8pC}X2j^3Ed1PA^}qM{2bOO07zo0a@? zexb@>p?RAOxY%5s%F9apekFiM7MmJow1-=uvhvKEVkM`co3t8WrB3<68}J{ukmq;1 zT=76BLVuzcIcu>!^pDo&FKq7u#{MUxBjhNU=uQ%ISdu?YkKc|GBr|~ksX(2_aasF9 z47knm_=egkH$U80z}yM1L`UZr!XPZLQRmPRYIkhXF9Mh#;sj-#QjVxdT(9G*WKoQG z-06Y`QW+)P-;y0+eOuchvoXWsT8jb zT#I(dCl&v+ZKz?1KPZx+R4$8#Ud|YrRs=AlShsOnCqMz;;+u7xL|S#Uy_P?+g6}la zavQ&m(Ar*K;I4U9p2Y)hLiB# zSqS}AMKWr$#d~dsIHf0C_`CMqDSCTvMQvWNb0_nb#CW3|L?beheBP$52n=P3z{R}c@8b)G_AIR6=-@3QjiQ=Q^r8{ z@rjq!K}?zDKb92p!MF5$9e`WI!^e0J06e-P}@SbTs$ z73x!kxIeK!Mp{R4NTX)wgVPdkdlNqVj&S<%n+K#Wmi1q?B9cLge@ZAP4sc_O;fWOw&JF>LT+0h5w zyzo3H@VN0HDo0`aY(;w)z~^E0x%_y%rG?Vc;A|%Ks0S3qP6jYt{PPOG1>mrPO@Kc= zR|s#BfP$tG3FW-y-``&!1Ua6Uo9M`h@2iJU;aeX(ptXLS8$Bu)`I&@FuCTBt-P;37 zwc>t^dvIieg^~g@kphVRZxI-3<99X#VjkHXWiFPF`WADK&qus*UHsA#FY8gPHi#!R z=9WUKMpX`(`sIFyCUcXAnRzY^&xFv$Y8u#?OE>kHRLwntB|LDm*AJc)w0j4>wuoFd z*|LJ&&}2(O2b4@tI;-|}`0bE{i?LoW#{~BMy#q%g;;#DRck22B_CWFZ^XfUqb$6{f zG}59hpcBkDO2JyDd^yY-M2)B;7CKjr3*GYT(!I&vE7yE+_L47P3TTaUY?Y5yqC{6b zz6S$J1^_(;oSf9EJNr|CXJ9ZlP|}s#h!oez&`mbBiuPg@v3b65E3pi-<(S^|LcFVm zM`Zc3^aJ{P-NI=G6;kdtj6OdW@rF$Kx-)cte+#6mWaLWm3$`!pKJQp3`Q4U`)0q~l z?V5{Amr5Q7w9ntdjV+}-m?J%U#V@NV2*q|hy6sfF-krApC&TM5ubmMPU6;4FohT|M zUn{mV$|Tavgw8Vn^4%W7l5H~yfHJBnI^uWnxLwgWv)3J!`)M?M zJ{iVNM&|VYTK7S8_%jgg3~-XOI^BL%y+p}V-h{R)S zC9j5vK&H_bml7-mK8muf9?%5Ka9i9P_oaVHYpxWEfXvE=dNVnrzJm4`cMEJ!R+W{H zHxK?)DmAKz%EC5VGB_-+06Io~ak{p|eZ|5Fn%uc}ns&yS>G|Jgavdg+mGlak*`90m24iCvQD5=)?2G6g`$Owz1rF3RJqhk<-sFM#?>H3AEmnIGWk)5sbUN6Z zU`DsFY>7d^hAc|j(jnF5+g_ymU7qUS9mm?6etrcHJjY%(2W@Rv9J<$R04I>6^cUR| z1hx<#E1O8G#P>FU?i+c)N?1(u;=UAeGz@8u>kvR>h! zNUzQJ2YA)skb9z8R?w8rZBx?}TgM&Lao>LIb28XUy`gL?QnS9pW`qbyG^VRih zf|%meHn1PZS57ez`gf&iC(MpC3tD%kMc0KbtwVH8!jw3oau6cy$q<4!fSSRU7M*F@ zEe>dJn#T;{8hTLUWf~eGwgeV#c2l0do32@~)j7zv!s4`Xix?kX=?Xx7M|(&r#DVMjrsHPpBmU6*xJ20?#&Rz@ zL9_S{jxNuN`4GJO=O|d$Akorv%HtHY2n-Hsl5#ehDMN_I!ES1CP|aAy!$b#;^Qci9 z;+;r*5B2IY<>zkW(d9l#ptCi^N7bc56N`Z}m7wZFv1|6WrxM<|4Momnvd(&>p4%{KcsU_V{cpM(zs(OQ%*-6!QvV_#yyc9Q>uA z@Way7U|GpJm_*nVi7pnc2Fr0JGOOiW#KFndZ|}lcQIbZ`hHY}; zRk9%I)`gG^{{^+dd;J79OIb698+l~>XHsiYR zQU8%n{LNxQ`+?rzy7hq!Uhm8x8*3G3ov0NM$F7!2N7~%+bCIZaNXuk<9v?1l-uimd zlqD5feAbyh;XA(8V-(JtNqv{z@wUJ!9hC(5K$KrtF<{#u}>5iV4WTeWqDo}Y$z0x}aNTTB|RAK7h3CEiryth5f{l8$c zyEWHWZob+vKZ6;97DxwrUA7Q%L&dD)xR=suTT}EQS8?#<^R@yCv0sJ39tta72OzDe zF^SU;D$f6Kc+Wq#85wQB!uL^%1mY8~oM*eAX3+~=NFk`=CrT^xcH_O!1kO~f_PtCe zGJ9Hn<6jc4PR(c;Y)QAwJzqx^+D{lT zy~gT-RK<7VOYV=ec|}wX^x2ds^|1=&-V~agcZCaLw zXlE+Ig7q1PE~b=+o!xFU++h|BFqL9%YN|<`gEHZXGQzb1!h^63&jvL~me*O0Sjs=<#ldlf1?0Bf%QpWb#E2 z0t~`+-HCC?l_8MB1S`qiM$0YdTa)s#Vyp)*y^wV0B$OqnYlmSWNeBJt*y>X6>#+7}rr!!ZSp0j+P1tmq%u0lo_Hq5>J zPQF?0)u-7CL(fM<;kjV@U$cG>ihIEG9$EbclOwYpl z={}R_0gVVCbm;Z5`8Zbgnp!^0EQC|O3wlT9TfXU$T%Sxh$F{uw4fY;H`JzSa(}hh( zxz$s`*1?7j;iwi$*PX!b8E2r7(pKE zKAoIl66JS4+&F&6YZ$|uTr@yn-{9N@G~kYWyw z1l`v<*bw1sxa<(+`nia^@g^6zksX2IVLrX)Z$5GNN~i=ulOZ$rwIbwNx(`0U&|B{1 z(Vv5TF`hs9I#iiI^tIQ3Ma7&@Gq-Xt-Bn^z<7<`9`dSn2@ymCx+H8glnlnN(C*^(` zFW(#B`f{KaI3h(7-z_DP7UkY2>z>%iq9m44B^rd8H@lzjU9X zWr-CH0nevY8;99-2{u;DhBm$rv1S#%B{P$ze25+~=ly^2zeq}838mOAGU^{!F-wv^>i`p7T!^JLJDdBqI%ckAb{m+bbk?ERYBqw~xZ8ZdeHofl z5=OoQ_8MC6#=?)aWv{NtjJvRS2t;H+{TzlyrZO7)nB6ZBcaCF3$3Lu;rm%on%p1c< z8`Eh&Uo>H{f-m&1P+dI4^4Qlf+O6X`ch7S@9PqF@dpZ2#lDS}4LL=S%6er@NUw{j8 zG8(ZTHX3e`O+b^aM9`*Rixcmk;vK6xnj`1Sek|_y*q8S$6*iY&y;9;nf#z$y;5(fS z30RKm63IR^vd$&sGSjI<*QZfw_C;fgBT#IbJ^lFuCT}gpuV4&XY=ATK3Lm9Tly_o* z=zat3@Yo4G=%kqJTqiJ;npvJAsvvoXkg9+R(N$or@-F!{;Z?!6vP6&Cy(!E7Bl?M6E!l>mr6PAak zNK2)U5ZFS~st+vNu;0&; za>f7z_sIy(5~CJ@xMqj<~Y%W?8^Ia&Y z11h;qMGwwy18eb?IW!|u>42zKdg=T?Ne!;XBlIdNODFg_LK*Yn3ynlLdwjb}2^lFa zVf5;mT)h|p&DH6S`e?hM2(`etXo!tBwtS9s=<*J%OUuSB%P3lak)*^5Ptx8O5c9idFhqLWlVz)d#O0J!M}Fp(dMYT2?XJ$s$VshOeMPn(kN2?l6p zUr<1)4;UnA1GHX%{S_u~(+OMEn$e|w#-c9WUOd^Q5zA*Fpk3kS^|bu{vEZ2+X1x_y zRXz2$*DlbhE@m|7TbF(R@+hCbG(%LR-|kKXPg+lU?kVJV$ouSCXYERGGu(cT(Eh^VM1YoFQ&k;M=^9Ii+=I9XeVj zJc&FLc>cWu*K2#&HyG42#26#gM@7>a4>Vo<1xQ*A@yW2>DL`x~#tl*EM#S?+YYRjJ z5*0;L7Z%=N4j5lDgGw~Rfb~;ap_%sNghVee$_GMXMS;M#=L&l$HnNuQ^DElQX(cp0bvZFRE)i&)vmOmJ?apSpgiy zu6)rYhi(ONJAScf&ufvW`q4CtHbe?Qz2TG}zD$vvhD6nYj095otyMYHp>ejL;xBCjzh(Ruxi^ zuo|l0@QXDiG~|S!c)GHvNLd7+VgrYDS0RJKjm2faMxUvlOILvAWOlwN`DobE;s*RA^sPVaxUC?Xw5l=AQn8A;JdKCG+D1Ro*Khil+KQ zAA9E}y!jLHw9z^ywydBxU{7#H3!RVt^n>eKp^aWXScy%ivC>$iG@U=scvB<UL%?O_UyO`ZW=@7tjaP#nljplD zc`XT~;-+)e^-cf^-gdAF%)7x!G(dOw?u^!J7YemcLjMB8mc)%F|EdqpY+- z$VTOp%BU}!trl5yRu~9dV&8_!BdJDJLgF_6uZEn_rnUwl8 z`fHEg zeeeWd(oS%Yl#sQVrJbYz-Sr}R+rRZdo%l9X4U3nJZTL|1%GcOBB zIx8+d!o3PXkoM_NqXNq=o-VP5Ee~RnC-kB>ICFtxaGOXul#H|-P|*AwmTsOG0_-Ih zU9B7s#4bJSX-XjNYCs@La=!Pn`?-%h)pAmagpZhxFOvI*pBn@UeLA++7k1I}y4_uJlU6deMrOyG_K8AJuxTNF27%aiG6o;JTOYD6rlCpa zB1Aa1w-mN&<-zKw_gn0|tzeQg2=P=Ex={OcG#Kdy2VLCQM&3cz6IzOl`cTeM2pE8u zkiYfI6vW)_IC9twLYm6?>1Fbd!cD4~zJ|$J5U52L@wesB^JW4CjjL!RfflM$m`&ul z@Z*kNhZQ<3X(vdxw{P{&7|K^_xf-r2+ymu?O2ZAQ%x=Ht0@KsO4HTsKMqHOHD|9aK z8^s-qGAf(z&i=ri%)ha4jEc+e0fc;CY1n|W3d0Ic6(Gn+dGt$N-=k!68}Ugu*1791 zCRgy@;-l8i0slA9e7>L7KMq3qHQ8Grc=;ok^xqDxMSnwJan767-z7VeHqDTk3@lpI zHo<=S_zq|p=py>rr4QLfx8Y`ok1w$}3}Ez`zG%Or2_B=vv%Y)e>~5CE3#E$lZzK=o z0YVE#o(Pfu*faErM>;^betx|37Rkw8>kqC#)iIFmEG@tHt7Z5pA9iDikNK!ad@R8e zGR5&Ka)NUedR)F56CaN<@*G=M2zx?M1@`~4h0X9BxRtFxMzs!|6s*nHU6y!qoC+9u z(y4fNkaGiCT03xS3Ihef=|HtJB1Z-#9+#V>F39}39Bm+16RQ_OD6u87%shN60(2I8l%|IV z(`wCG%bRF)W%b&SoKz@5gDnEsIPK>Oppc)kQ5~3$jIM3Vj_Nu-1@RiaOH*%LfhfRh zlRGe77<5N%P!XA>%O(x27~eU0%>4k?5`=ye^A;yXNCCqxLQ9$Z1jl(nPDtskPvo*b zTbm0$9xcR!lR0$v-8t~O_{Cpt`q_~^4E9ZPwRm4u=!^`W zomogfUwFO{YF_!hk|6ow8D@C=pH^!hVe)~aW4uk~;uSw`Qgm1Qp0PlV9*ib+E!p1M zV5o5%`y761bu{w}Rto%@>C6|^;sVyMDqqj_6{cP~Bzk$K33wBju#{I-65~W{ftNRg zOYw;eZXvc1&DF2dE9BMAVHQhxjXg`dU;x<@`NhW7jjmuys=e}Ubsf{*FveUf3Bt~v zFpfTd&WF&yNo(?2OspdwstSrjcH=`dmZ1m^Xt+MqlA%WE58d54YpgP$Sbj>v ztSj9peST0OP*Qc6YPC7LU!ilHa z?!dS@A)-?3{H#W!^MEDZLH@;e_#6E}ynh_vJ+H&PHhhONZ;{gt?~GfzC}b|x&;#`S zCY-YhSI32q^+i;`nHHOy$9A?5Ob?b{3Lv2u?c@G!^6A?ijs+JwO2`&*!rL83fNpnc z$t@W)7}{slHTnQSl|;PNc2Dib>2r)Xwvz&%LoSxyo7`+DVe!XO^79yaOBoK}HqOp# zKl~_pz$oHe{covjtLTCn?dT>j57}6`bRoXVhLwz%zhjrR}p&Q@C0eG~!iE zx3=LNU#ZHxr=#7IHwRhJ*MVP5Hh|}D-7Z;cS5*<64l~?(uLU*hJ=3|VKbD)fCA~L$ z$WL_8d$Bz+8RF z+cPyvx~x5;ZLQ7P{m;THw-MN;{b|c3s2vsVu;-{I5)dW-Y>&w4`SQM2Ej+_Un1l+4 zT79BVC`~Jl1YCaBcebO^fcqBmASdiWoeJ+Vqx($|m4E$GM4^ayMu94=>lSXv*032E z>1hmaAOvQx36@5-1*9A~U_Uyagw%Z$8CUij>0j?2d93zp+PDSktH(mwo3((kZ&PiT zE|h$0Rm{&B)2h+&CwcyfQ>Xfk*Yny9R{^!+d=@>3yct@OL`y*f4zvq2ZO5cH z6BjTjaOuTTzj5_Z2p%>19q6?yVO`%W;yqSB5e>=p7DlpLS@*G4F`w-}bG$J#`6ONu z(&GZzpl@2~!w(WvY3jQrelP~lgky#6dJ;HhmQEd+215dm++x=OjcK}rhwe3k=v_9T z_RmpkpI6eIx0>iWJt7xPN`!vpCUoPCf05vp`P5?{{ZPMn(l^rI_82~sZQ@SWd(we_5O2B}!1-_Gr%Mp^Fv!03slC`~MuN6sYvUkANPHn^5lgS>p$eb0SOD8BHeN3* z;?Eb+R$d_2>PLj(#$dg`e4+OS%G@ml8B7uc$1P0iXYVaW#1oh4!iYdgF5>ZzeGGk68{u0k&6jDo3ffYMN(lwPx(M6yh~X@ywiyU@h_p z1N3a2fmdQ|$?bZ;)lHv2tDeFh-6M&;;x7zMX1A-kZ{T8#iKgKT7;IZH< zC_9Pl_SGW2Bb!_Og%%7@a?ohDw!kb&AnKW-Nh_lj`^h>Zfj&|}$->*yK5SQuvOdaQlef2z*pbA1FrZ@Z~c^*_cg(93a0i_cc zmh`|mDp^`noEgTRt=~F3QUWv?w9XbV-TOk%50>P!ydbC&cb>h5XEAhELxAs7uL%hS z8#yVywwp!-HpdnCDM{ZJep8Mi4zth%UM0=i#uj)GJP3r!3$c!0n+t7+!mf^K3EB?o za;gMgFC7CLr>nL8Ha@oU#YEoS0Lc9bRW5*H2BHB)Hr)aP*B4ZZ*}v*GqPay zCv*iv)bj#9`#9qY1ln$acyOu@Ke6fhXzV?&NCe5J33z+;$qS&|BrjBKOC{rgIVs1P z06qvu+yi@_P6+#QWlrH<#MnSADlL>g-*f~rpL!mYj$(H~oONv3jZV7`2{Xu0k|>_0Mwjl-e3z)YG2?UM^oPqlx3=>X&MkEIeR zD2_@$ldyqyo7z%BL#P$cj#1Ch6-~G07Z?Q${Nl_lz##IL#=4cF_)giZVYWjLQcO3$ zyrc03VWvP8#f3qdm)@82y^c3(aumYY42Wex{TCFCGVUI>!$fe*MC#fHB!HE${8*>8Tez^`wE$A<>=qz}3<9SDp@v5< z>oO(L#{;Ahl~HFU$xh-8t4yqF&lXDTXBXt!$yX~A7VBEj}v-|0)zTXgVB7+ihTkEZGok9|39wd~EY2m!m zL?#+H9KaMxO;W0<;;waM{R<+Z6hyPXaaeOg7eUmx^?}u@{%mWd$dNH)=Og&kCJV$W{(xRE=xez zOG|2h%!R(CniIy_K!om$xGWv>MOg6D3+G2(3ts&>!3e)nydEf>a@ukX8;Oywc^3OS z-+fpUwc#23#hRw)Pd)Ge@qMd(p@zNnA9F+y$C|xwGUV|soe6$JNDS3+MIsHpMonnG zT1l27^5e#&mpX1|aD@`s+7K{8G65NV9)}E2_3n?e*33m21kY3*zfk*X1omPq`{2naTuw%8qlo86{Ay`U+s*DF*UuE#7a2L%9GYMGS2~<5udc5v4(R{_1|C_mYzH< z-N*8ENWY*oPSE^D|Eq>&!5&DL@Wf|#m$kBq&euosb``L#ThSE0Dv9g2UY@8445nwsdN};cO z)Da?2$9R2PRhU?m!~m1@t$lva9Wsj)d*%Tsb)bJ_nNh@g^Y{Sv2Cb&X75)-)@b~Gh zqk$qC{&Be@ojU+xQ*7Z#EwZh2_0)*Y@xd|=asQXln#)8(F?yiYn+NaC#%_KqxkQL+ zK;}XnURR7rCS|ggD~&#>_{TmQI1c3T87&B#0K~DrdT!u8qruEHEgJG#ePQIRT*up$ z0Ht}|#vc`4$|&OR%PwPB+Jd-RK%`O`AR~biAu9gQ5%IljinRD3ad7f&f3Q#4@wX z1s~iK_4tKXqG`iMLohSzjq}av2c>_d4R};>EqYFQG-`lBRZpX1k=$^#PM%yE4Aj>v` z+DOt~)rheCn;$4uLXZ_dCuq8+hd@kgG)OkQqmv zkYaKLLMMIo$K`KZFs$zbOP{5)gljQE=;pN2*^n(}XgJbq6j%6ijK{kS@&k>&bk{oH z3LTNM>H;_nrGZnJVc1UGh+*TsWOd*bIlKG zU18NKl9vp4UCs=IV>16Um#?Mkl=sq4>|Bv_UjY93TZ1my@bjM<%-wa_oqR*<2wd907CT9YR{&Ut24$1oJ0_|kNaZyufP1?> znUTrGacE}3vnFV2(CDihF&5Oslr2xT*WUl!1EtgRke(5L-tjZ(!YV@ui7fyCux`a8J0fSAEJJLojqxo)s+K}U7G^;+0kc6E~_j zl*42j{lhXp;q3?Zb<|#0jbd`A3U%lY)L2u+Y0kYI8V-LDEu)Ib>R`md=y-g(Lsi{% zhd$S>;Yc#L;i*8Hx{?=yIUkPOHalX(ps(hc)4#p+V}SoG-VlI8B-YN-ee?lM*6dk% z-M=n638EPQ32v<|j0su}z-?JHcs8|bI!WQp=E8>51-UvSg9CHB4( zwlg&pnj@<3O0f8J0SkzIp{5mduU?}08kes3+Coj00&2ep<1fr>mE;5sGi#R0$xJS~ z1jemW340AJ=-jQwB}>=!ENK2%Rw1Elc*v=6`A`o7XI%-4)zaa$Vm5ncQ2I%2fB(yc zxgpGc<2?h1Pu^NB1#$DmnJ)haeO4d~NoQG5mo|!8$u)qMPM#xVb5j6#!EP$tcAFW% z-y~VwUY%#ersm|C($hOhN`(;M*W21->qCeN0|RqJZLKr@%E&P)uM701xh9EEe@!$b zgYufs%dXa)9ia&8#kHvL#b{pR7GAsYvX*b3zgaBy#Kg8XIgdB342bJ=r)#R7zxPQ* zYMT~^H?z?O0Ep9@k+e7V%W;B*)3@e|jUUrJK-j}d)5M(c_H{3=6ic{s zi|!Q8I?pLFj=eIRN(I%sSp{IjZ!z+zSogKaduc{OT>q-Kp;AQk9-Wrx^lhLba`AY@ z%46T;A~jff!j>wFCO(q~!Up>40v&tie2$t!#4;V3y2A7xEjo^e*2n%0$MWZh7 zL6?H64}+M{u#I3`2PbIqG;Q_Ah1gS9S!DUKT)I8YvBJ7o=+bCt7z?@TO1lrb?QH1k z8a}lA`9DBYu7yXfU^zzBjJl*-hQ_a}HH8r%Zf3d#XXb?Ms}kXMP~I@oBiWVm>ng0jDt=x44o8m(*JsT^SnQKSRj zncfwiZ!0{558kNALM-b9Ht%<)A!ziaf=pIx*Eo>E)p<<#PQZZ)a1~j-l$!V4fV&gg zAdL7QR+K92&XG+M-y(-^fcGA*8<`pEy8MosM8yXZan{z+fknWBhU-rI=non#}hr zejMpDVBM6Qa5FLi!8G3bLLqxWB_~b(m1p1q;cT+C%InD|2=)oUmb%!-i0W5u z8EsIbp9)KL*DGbsIlF|k?PP_w?$NujdI%I~0+MsmLko&PB}7UJHhTo8nv6ql3zvo$ zKR-NStVo)y1oVIo#>A-CRwa`RO900AsV8jB{E8B$5G8a})Ex*{p<@pcvgo{7X00N2 z>~f;iMUUGpLSMi`AV|fR%l~)_w%sLq+Fg&=s_u(z*9x!-q;3Q)--jw#jyyBkP*TtG zlULeZK9G~!gHn$k^%wnWCIE|1%fN&y9ssKZM4xOA>WUP^ME1=VxAK62vZDG&B^1#| znPs_+FVq_|p!i6Gv&7b!Yux%l>PtLUQ^yc!IkJ`Py3juy{sGxX`FD<=qYc!(hYA_WXfAW)QbY-)xXc6!#iQoZIy= zI?g?M?;Yy6=HndY%d~&r9To0teXh(#0$l$x3r}D?o~xNYJAp#4!C{@vFrU zLuhAbmGo|Ft`^pr;Oy^yiYix)tzYm86*~18Gm4uxy;#>BLU0J4Ub@iI$wl|+FK^*%Sd`%FH8 z`$J&d7qqWARq^Ss;HlJyJOP$+@e%{-r?m`UpwV9TNA%kLitxpP>Fd2dzodTks7=?i zBQic|`#))ae*&#YV8WB8WK|!EM@5Co;hTGA$zx}v9@5F{&)mBm>D>5K?vKCfaTmS% zs6aqxP2nCjo=Nw_WBJ=tXC&OWkAC=Av-h)4J%)$Cn@I7|`t=v%0&rKi@-B|MbN$m` zIpkry|8jSD&qvJtnix-1Q!l_!J(s0%irB-1`}E0Y{#*nRNZe; zH=uf#9A7d?4YU!*xwYS+J@M;GISudOb4A1(hu`mk5P1(v{r)xo2KK!mM&3h;(XB%s zCIsYXUYVJ0ShHH)Q8=`J3!F+k;P&bCD<+W?;u|>Fb%AFjZ)M5wKUI>=zu0rt^H3u& zS$s57CiS-S*EbKJ8eVBvYgscnwf}?mrRqeIIM^rlbmkKA01!xH`rM*h%|6 z6=j~IcE~(03Ln0fJm?F2XZEz>FS-S$1_`Q7=4=bUT(CXfAz$h{p=$8o!C0lYv7ARE zsogPL=)A2$c55F6^WD?L=Fyp|no7c?GCBk4b!1t}yNSKuV$w~~w_U_?R`o^)%EJUN zY(s*}>;}s_So!yXbd-B1afB95Vv)h${z`aweyyVZA^U#sACII!imZBhP6y0s;KH%o z89RLrStd*wy5!#E>+=)Z+W}M^yFGX|jK(g%jwr>w(NUuG>er*F8?1UQjnATJ9hwu} z^tRir#;wzzWp@=a=U4aB^?LO`l(OLL*4_kulaUAj*I|^q|{XPyPtK9 zWcYZmqE6&IJ?wd2^6Zmw|MsKlQAl&MAQRe9C8PX02I6{i!_^Uv{uF{aN<_toJGp6> zevL1qL@?w4=GcHCB2s2G`2frMytYl(i22QDNB;A4|K(54pe}CNkf|}kqawnA_tpIK z5Xt197dPAg)#23XR&e$^fC|TlUl^{-mkjbrah7r}G&*tO^w=#}vgu;V=l`~3H1x=l z-D*xcg2H>r5QnW)s93u(u>VoxvT)%|wXwFYR@5PZlBUpGe{pi?>hdMaUx^4Oj-{*o z7geW@LFr)-=XI>BXZS$zlnSK^emcj?$BTE z!^1`ja@Dhm;WslR{yeGs_Br_Nl!kv5Cex&G$DrYa@l5elB~k7V0;e*NXyU4vxtMd`Idz)sqXy& z`&YptV#&B56vcj<=!@Gpj8lz9Z;+|BSc3E~_FkG6G)wG)-gck7AS*+jJ62Q<8Nl0F z!li>70$(5aEg5+KYh1(|m8;sc5pv^xWq^jEcCgrwAL{!)+^;Uj{KO@9t25H|LYKSV zc0!LZ>&=ob+eP(h_*&*}bh@&N9qj!*tf9nRkWE5BeCHYKAh#B9$tB%DPjvNV4PsJF z?-)Mot9DH zuJxS$w5+@M1X2;tb{4xUblWyb6IH-Ejt&>XkCQ=yfOT5fjMvROVz9Y zqSo_rKonhOB*Ffx4WWcMW+PiL`iKO?LdTO3EHL+bzx-+FibplP`F_GObJ2lXv>H!T z9#bmhueX(?XasqJk?Y&Ni4;_R$dyqQPZDV)G7NN0wn=}G5UFPBq^AHCAkY}*19kwz zTW3Kh<7uh=bjah7fOtj>CX11H)8)&C_}tl3Is_=s+&*J}fdy{|0eY&de(iLT_%KunaU>*|0st%vF_rtiW@(zKOe_A zuy?K{kSg(`bNZRb1+)3xI`ms7#4vNv6;lq3)glA|j&!L-)yBa&_Xxj%Beea{T{R6K!+a6xDZ_c^$c zz>{)|r?haq?vIhW&(z)Bhc9XqD2C!87s81&O63L__wD8;|Bhc5f&yF!rxx??RPW)(DAy3#OELByteyylgFLYum~OI zyc|BU?hY;#mE$BXKHrC4Q=$&+{q_Jl*vbTJ8VV{EE`auRBCsvu;tqNF8}JW$4PfA5 zWstNXI630Yl5)3fIrFJ!C@{^kOhtLE2IIMK~8-AW3$i?rBFz|5orK9u0a{l-OjAr?>qQs%f2z^baWp)e5|9U8YaX^wK*g9 zE8vQw3{-O&Uu&|+mRad5_sYJMIp%_YSHf9#J@={pVmq4j8K-5TFM#6MgDDZ+R0)tJ z#HCh3!+%hM;c?gQw2u`}0U>RO!6joMnjK&enI6GoodMd7;H&_bWW&ag6rid-%?6fS ztkY<~<~;DC^7!g6H>?r8PmFmewKUVinY~lDV(a{Z1Cbn^IS2|)4^GL3?qVQ+fQfV$ zYi72h#s)$vv0rTFVd7QsF7!Q5Hes7q4)#R1QVJ@Ux-_4DtNeKrAdX=2`v@@2XFv58 zu^LMT;NWduAX_(R#PhG$l=~jspx(G+T5CG7GNPMw+?cUj^&Ed~k1zdRM?r7ZT|sAjPN#H(i;YrpU)~^mko0GNHZA8TSB5+J0t! z4>T`AOosX_3z4BHW|lU^%k34R?jNZKny4B1xw8{#5 z#Q2R{^mAz*DmBl3`mEl@&zqZB?~f?~rQ7Z_c1=U&i98t`8U7pG>Tpd3D#_PsY@x(QB3C)7S1%p z{e)QYcihR1b}Lx#?#YV7sm@VMOY@$p{oJ1bPSsPuez!S2yRM;f$37ug`H3M(CupwB zWBd9Z;G&0MVn;?_-=v}-jALzy@mPaHH3?j%2rfp`AxUMoiTfNehQYmU6t?{~2|=CB zV7)!NA$%^Yy&*d@PyEzD&w<_@5Ld2lx1!%}>DT(*ftYY);q1 zMdEOlRJf2A9sB31?Z3wYvfbCNyVZ~d!hJC+17%v_kl6^y{&bFt2+8L{a;F6dF3BLf zoIMhgt^`mgFbSRGwJ93LfA&^MK>3Km<9cKEO`mY{K} zt>rRZCVi1JVB=E|qLqQelD!UXqz)i9gsO!X0|Tsgxh)n9d|&1gNM-_(l^#!a^==%; z3Zpt>5%h(hl01S2P5hDE7%+sAP4jaBIzckr0Ld^ZMF|mmZovSbTZmO>FXB$6x=Wnf z;usKyua}Dv;GJBhs`XKl<-H*YkNC9HkQBi4s~P=3T}6znBrRWHHlZm&pZ{^qgZy}u zk*@RnV?COg(U)(L~*uIZi30Rd3T_%92U{y!%a_ zyPl*mrGNaO(IEKV=+v*|Xs6iusGfhlP~1~M6HWWs;$IInIRw?Bi8xSn9`Fc2a*s9K zb)iL1U=A5D@?0h7qFr3B8q^WBasl%F*_ZB!9LFWFjcN2i;zV-pz2C1ZkQ@%Qc0VWdW|FpmK)#%c8To1 zq7K5E0b6ycnl#^3z~W6E>xE3LtydC#%i*##?F+Z2WB)QZ=vo03iKgbfm4v6UTeK2D zQjL+W%GaiJM69c6KIx`<&x@g=o9CICx*Dd&bdK|{cCt=`;92fvDI^X_FyP|>y)?S+ z2gH1h^Kw_eqFb?JJ{Q4{8XMYK|M6PQDy-CxUW!8Hq*h1|L`w)rE+qkZr0)3v%)+d~wkg(XC#a&9JJI+A4jChTV6fPIF9((Cc$AT8VBJxI-4JrK z{GT~y+1<3!?&5`II$))qE~EZ+31W*~-z|ie)LW24oQ8H>cd2X0OlXA(o>DirKV3gg zAMXUC!UEe2`FFIIGl$&u)ET>v$Y5cwG#t2h&I)87;IbzcVF_L#Gnqj#hTO`=JJ{lh zn5Qc_4fZMS_xaxdKVMy%&9UCB-<2XqqcGP3zgK2S!gvRdn5e(f%`IIhXBJ2b?8?DX z6^LI_US1n(a%T5+75e)H+B%K%(_kDiC#AShd>(C{mA<+vR+#P1M294F7uQ@ZivmipNRa!ofj16PRqw zE^FQ_`vt1~dNc1x?ru^?x||3KpdTSC(D5aDAT$dt^z4at8noWBq3~FZPG+Ib zW|`&7iaBSq(GL?eaQnimp}QR)%)&IZ4P?%in|a-nGnB3eJwMhSQ7oUyY0O)Yc7j~{ zT)H6QaA-`N%WSiv@wKbz!=^tG9TwbOt*lfQD&%4A0L1V>KBw}cg$5>WebdsS4M&Np zd<*NHQkX8F9Rwym(H{$J1vX;Uv*=M|1kMhz@vB}q`{vUm*I=Hs9}WDYviyLSa;+L# zesk|binu-0{Ewmjw5sgaVUz;NC%^Z|1<%97iIG>~ zIl4$K;t3a9mov1c&LnvwGleGUza!4f4$bc^`R-UAjEJw9o(}06{L-z8J9@$nJE>a z05tIP!bQ!3v_N;KLN78R=2X7YEibf{DPq7FOlzf+Iv}-v4G#|#2VkZaBoxVh`<}g%dsNU?0{i&HV^{cY^_GtdbKS3Q)N(|g(oAr6e7#yV;>L_eZLV$ zy6sAI_3yPv&mXrLy?vLJrqSW{3(mL?t7Gv@0rW*il0tQBiiywgm%?x ziDfgmp=+!TrF%{#!5A;ZuM#&zd3Evv27qTR0`W_Iq!BKK04hxeQYV7Olz^f?XUB>B z+>eIAuijB7@R;MCcVFw{)OFjkR|fl}^rOqJaLPI9MRXBs^L3y%pm?y9JF8wHnds&g z;APHLo|L^R(m0Wp+hUt8&4=UP;)}S>r$-?;8{Duh$Xi0n8B_Y1H1V+%?jvwN5tSg>F%+V3kxGAJ}56L?~OwT)z zwlf`G*IFjDEHuu?r>_ywaX9Owx8^EF zC=dNDRlfM+vR=#awrJykKPFJVW{lhNrfj~X2v^4(5umTw!iWcd8Wa7+gtY3kg6A)z z-0%SrjQb!9ozY6^`+3aM=R@s$0;vwGlOP6?$5%wftiUOr2$l2hHTgkeodYGTg4!Oea|7VP}>F=+?%=#%o__s`N@EdY)+!bCEIAz5O_epn-!=}X55 z!&Mh>!mBMk9R|#SG}Lt3`|MhZX$`+VFSt{$w@oF)<1)e!C{3nWP>I}chFP5(r-zTY87kg(jch*_XBnAzcH&{el8XN;s2^D^Q-(pk?jUM5VMl zhNaFUZVnke;JOKlv)9uOI+QgmRI5Pvo<~+5?hrp$O6WlZ_f|wVRz%IN5sZ<(a3`C) zen8FUu>0qopTfV6N8K6riNiOzxL+s#CoJJX2if6G!bJ@k+7qy)|K+}hCa@4`U>+S4 z(gaqKqH1?0_*D6Iy7eA!W)f3I5lwn9-h07sFQB6+Dl!Zij57F#a{E^6!&nZGs_hVsDYn8)F;TVL6#)Wes!d z2t;JZ!WrZ~3_qNP@ysGzAr36H)7S0n?eOPhmXK*DT(ML*b;%3)m5mPD#XoexkQ%^; zPMPu=dA?Zd!LptN7DphCwX2Vv4R4ixVbpC;-2nyXs!hX;d4^2ztyKnrUoom1kfk(f(k$YjD=q3)f zMuaO>A{`pc*8#a$boKHf`1=ZgRmWIBx9p04DucGL2k z4R@4sXr_Q=uFZrvCRq8 z089}yv|Q=8ZDf<3Qs@SjOf%BjlWJ17x1`3?Dnq@+-U8FUx#$=tpRnd#-nAlL#$F zv_E8zZ&D379-7>jt6-=ifHD$dqVht6+TGm?wx!sND{1F`6`{u&d;r=gR1KYdt8|e* z?M0+d`+mC3b$m@!<*XJ=3G;0U0#yx$Jd1hK>m6;*QLJK|@ulWpD5I+5B6?_#%ZI>WV9yo; z!tArV&qRavHQc=O-5r9cyIA6F@IJ^P+x6jnpLhHIJBF$YwJD;x$$HULAqhG9NxVVo zr_kSr?mm2#Y^WX?J#iAB4xwqKwZ?Km{C;<06|Cq_R(rMR*A?hXy}x@*Vbl|&2mN27 z772eNR=^)5(kRNnF2Kw(WNRMcqg={QWmWBX%WmjeytRA>8^L`Tu`5hXv~jNgUK)LW zP<;!a`i$nyTH)~f-!|0MrF*xzDtLK+-00CCd$u14lfFg~;osj^L zU1oHtP{A979!OpZ7=iF8cM4X*D5V!6t$?6mOVY`Rq%m_$8M5PEh^pTC<$BeqZp)q7oozPLzN^|NBaV3(lfrFw5QlTvi;CT|>hBeH+Ks+bDN0DV4YQCjsEDTJrKZ`dvZi9-4sasT&z zxku<&Q?fPZAS=vWpT9Pz#-QZ(HRlFzw-gTBVmh= z?oE)r-QP+Eo{$O8vDfN1%pe7zKmk>1gLNAFtaYuDDPdd-EJM9 z@&_QC4S7)Lj1ECI^`t=%>d_GTSl@E zy*)|PpD0I}?g~?dnn=mw zkv|lx7%tqrNaoLJH2DBj9sidV{fA45bGB{AE=C-jJ&1Nr?yhATe!t7gz_`tt+uu9z zYE!TKao%rG8E9!kQH0E+Nb?QMstV=r zEl6@J5jR_bAgE-Kq4NDI6>7Og&w*hO(e(tJ+qewR3hOqwIna1~Y~hvL+1}C)0@K6E zUIzqjKH|y6`MoPWGNb_NxN!#P)$M^*k>BEA(K2v)B-Q+m8+`188b<@s+q;1GgP--! z&~T^+-FR!gev9+XkYrz()C}imVmsTD$+*OJT`7cc^e}%bHL){Y^+7lb2R!cK(j|S;(r(X5yQ0qP z`GOHOh*~bAnveSNpvArfF;hsrkIdDDsjV)m*Hu0PD5IS(F!vsdF`mFRX^P!411Y zxyJRB;Ldamo%AA-b8&_&3FaGw1X~Z$J_~~*4ILo8aMlZqxe{%tLAeoZfqPS;hYN;nW z^PD%KJn@9{Bh2bQ2c>th9s#ubU=X}frK-(p!C3oO(2&7H7-c6)hi(8^_@B5$C59v& zSw7qatS}mTz3jUN<<6n@%J8LmmKM7@7}Q1nCYSc6$N>*${Cl&50|Hn4>t^I{n4wXG zCi?8U8`t>85Q9OD0T8jiR!nC%3(W?#iQx|?;-u*%N*66~JJ#UkpbQ{+I)F03a?pKW z0VTW?!NcI->T(L=fSD-sI%H5nr@3AJkn4tNAG9A@?E2z#i*Oru?aX?j9*jKI5PUn> z<^Y~d&^`lT+|-os-uK~%Lgz4m2|E#(Fus|X%iIrFeSQT2(eDMa0X3tTuCHi+7)rAM8vJGY#637eFzmVUSzpe({M?(wVbPZ^ zs-c$S&qG_Lv#oyWTQVT+wX{@fDo;YHY$n29T&4*1%GK`EIUJ)Gfb8HVcS_GHJe2-_ zhR0V$QNHDGrP_~5;faFCI$JP8`K=1DnW*7)*c2;>@&EBU9>VL0tW_qXq@4?eOX8T+ z3}k>!CHG1e$rnIbDmqIi{+tLCH;jf!Zq^i$x($E7jjRBN*D!5|N&QB*qiaYvvDU-) zM|tQxFM)gIE08?0EWuV{>KQ`Jg6NroB24KHv`4OsA*WE@1p|DYx=NF(7JF(4kt$Yli=w0~C%fiszBZ z&UD{5;K(Wf!BKj~jaJN8o;b^Tr5x=j&5ngxOBxH|&Z=+|aodc1_+U1KkV{l%sW!Z# z*`cTQ_612YhzT+~B~e1qasK&XUeq&Acy06~J(E^rN|n`kTMIJENBOQxi!tWz*7{QL zPX&gZw_D@ax38m0-2mSUyFAW74-%_NK=tW|;vZfH`}p)D^|iBaU}&61ZzF4I6L<2a z`0*Bpx@iE&i>#O^BX%x7B7YAzum%0j+WRlr`pVEx>Oe+Dg$p(4hW&peyHWd+UF(d19K`D!rVRGBJyQTJ zh;+|seA$;?=qTRCkT?x|i=&G+(C#)hlyD^e3%eZPJ_toDgXL`6n?7^=mJrNT8wI?3 z(yen`aG=zFfWwTQQlGkKTPU-7VBnQ@cRjM>#CcYslM`zYDV1{0W(puK!>xINnQL>U zZeJ#$MJ~;UFKfTye`qt$5)eUEc#(xZE6!IA-hoE=jaJKnihy9B=%sK_*7q4bZG9`- z0&bAl0*wdRhtNCFcxUcZ^;{vG|H`5A|C;3KZGWL?)DA%aTVY{Amd0Ysl>P z2#9-u)nk*OF8|45@B19)->QZt7lRF+vS*JDY(=WGxy}lBIm2_W2_`G>q3}Lj8wSz& z75`>kBxyr3PD7UcwNog^4V zx_W5>ydmWQHp?~M26k9=>aHfM7|~>nQ5w(|yCMmqN(;=J{Tlue6jw>CMZ+k1`=8(3 z5V{)zcybCa`dCcFVz-Z;C9){o0sKb=rqs_FUi!gt#bBu&aHKx<2SUbR=t3rqDNN(j z)QAlQazp*9IyekVx`265K;FBQXn#;_#%{f#vx_HAweMT2&rN$aJuwfTmI8q5tBxx@ zj*YGyU^KJ@wt^e=I?(+JGSaMLLL-#dDQF;c_3HZ*Zh+fz)gm!5m0mcGFxuk;x@On% zZMXb$=M~m#_=A)=Pt5LS;;%YwauhXxdbOc~k)c)BWhprGT!O_P{~sRugj&hHmwz{I#6r!DonwhXJO`+0puo3h;a`LsfTpl3@RD~{W!@q2c~iPW+2QrEtEpBAhjQi z@DJ71;VuuHJ3uD z^UT1z)a>W?&l<7ymkq#GO2lVAe+%(04W?&W=R3$Zz_AALy%T7F34S2c&fiU2%hh_R zt3P{@+j{R(2t9EL`vce4nSmdc>ehY~@AN5kmIu9gre*+GJ)Ni5zpheqS`}Y@2;x!4 z(9ZUK7*mX1g1IVdwlAN*!@~=4HjwcJ7oKc4$-7x-`bHrIc{S9VLtj=)z$o(HJ;{W~*_tD)I!9`AA*3S*VuNT26&{8AMb+feL& z7{z-M!3$Bec>e`2%zcXg$CzY{EIRL8ATQ&KYtSrZ_TX)al!8*f{=Fs3v;6>pM-gFD zj9}j;R?k6=lza3MMh4yFLdVejnye4GiJy3mldjk?U_nvQkAKze+|V*#?i-Ti6L<_& zYb^Im`RVtlR)Bvu$vwK6@P$w7pOK5NEkboi_p>4v5H(=SeZz~CIA|2Uz(iRxm*c{y zXVD2U`u!kLTo&5kF~dZ@m!Wzqy2SRjK6->r?+5L?wT(@Fz;<(5C3odJzJrRI&@;(# zzbqWAfAl!omJyz<;V|CRo^k|3fewoux4k5$p74)|z(Kq1DyRQ)i-45pHqYZ;TKRjZ zm8;g5knzHfMd>$Q?8COHi0*s9tl99&^ZnZQRCT$|cyyq~g#sU%SFms)hl`?pbHugf ztqbr%_;DtzzxC-DJLJJ_Q;oh_Ic9Y~k#6rR39h-XnP%0W()9Wl^s>L_aPfXV8>Rv` z?_Aef#*s0&$*4ShqIrUk@s0-k)5;-M(2IqS2vOR_S(j1sr0gp%Rtt-YG$eM6x`rZj zZ%5-KvjD2DUbWVD6{kAdb2`HTMe>>$NTm_Ov^UzVNW6qt|P`jt%!v0fH6vJi;uCJpyRcodD zUvB^G@=NdCPr|U0|SPNY$g_~)g&7U2+Zbbomz3a#VY=U?zC9EHXi+ub5Zebe!# z@D~*)#K!g~^>OTI9hW8LMV^C>L)AND1e!F+YpvM-T2;>&W6a0bvFJ0+8{`0O zk{`HHl~1jmqI*6gPk3^8Gh|~RhIlVPdFLHiY}X57EI9Tr5KmF=aoazTMrT4$XfA4# zH2}jm4_y+@6KX)uMzR0+Ao!b7g3M(%wt$uBwvs#4Cw7l*=>B6{GC{wK93{A~MLsa{ zx}*qQdiTZ1Vx#U1EJMUXLA_?(fV7;gS5X9xi_JF%wnnaOW{uF9_Tk+I$*4JXlsVx`} zZE<|c1;5KZ(tUAdZvWZncaRaMUt{!nyyLTnN3E3j-HA{gBgGSy8FAOb`(Y(r*KQ%j5G ztsCdGbu-&{$ER52U9#c8Q#Kt_ek(?mbzp)gGdies?-gHE#2HWYm{6j_Q}|~T&s*tu z&VFK<2Ob{0Vp@616gd5pgq!VU_4i;J59uWKO2i)$vq`)x9J{bW;;c#2T~ zA?8g5t`hIFk`SGHB6RsC7}}5+VufP0>uT~-frkr&hbufE)Vg=rF5ZEMt7cHLIG^#4 z_u8Yo#+0MK#gn@$xON(3niHiQFZ~ao$Oy|!2Te-A(#vPH;M~pq;u4%n6o}n<+-L(< zG7X)BuN}hspj*{{e`IK6#Ecs9c{g)c*H%djgb4AHL2vumzVq8F+px0tvQCA=>8M&{ zB>wB-KX>ImBp+7)BjSR(?p)W2q~pqfku{;sG((nz7meD1nHvwYXm1%5_M5Qo4@Rpe zfdBg_(EQLM-@BYNYnH}9^CNJU0yL`n-4v~x3m-E8&7w;`A~trBxDQ!KSG3l6M)>)3 zNNd?~TC80iZWZkH{NlVJLHPgPiGR_2>di@eK7KS2;dOz(N4&RH@#kCn&&Z5pcNU*&gfixB!WX56gs}lQm0>c2ESP6S)`twr|4s zUe{h9IY0`Nadh--HMX}pC$0T`F&8x{`q{Ore*b5?%t**;TDmqBqeE8_J_R1lFo#$3 zj0vD)p7?iN33J}(KsJGV&<(1pO|CBn&(h!T_O}1GT$Sj@%%lGOHwM)ZBI0*eeX@WE zo;+xo8`qo1YJw03NheTNpAEwf-Ji7LC}A>ip*Lu{O`%sAYVLjPl}>m78HCEL70M0X zZ5Gyy)4f|}!lbIxoYv{skOx;k7aEZXz$(x~ zd0vm@iGU~j{R=QQcxf8>moA6K0>2KK)^x{j2nGsU{+P9~oO@=d-kD>2<66RQu&CW1 zEI!&?NeG6MNr)55YiT6T1Q(VJEIzBly@owxHqQP3d;rx{v>S6+VU=YYb7BgZ&B5V8 znx#==n&WbptHd`a!sCPomk;i86a#9`1lXme5nr6p;$88}XP&;(nB#DCgHFyBTAb{t z@v9-k5 z(?hXErnt(ngcQ(1+Tet4jQ%IIoDde17u*W~wk-dLqfj&Rrr1#Z5liF4?wquA){}bJ z!<-ctzC8c?VR*?7+RD1t=A?;)7-A`E@MEEg5T}Q3TDxC;E9x1jk~L6c1zWXRJNkaX zLA)W3zGE))hk8G){1n_rTvIrAu(5DU+{5;H75L|JfUC=FlP#@%2U6la6kTjwqBKyV z0AxnBYHS7j_hnPKN}*#yw)g%`@geYB3BNOa7m|wDJI7I_)8it&&gIRnPRVz8UTvWd zaUgU64?X>1?`6w8yZWS8p``uAAEGD?I5w`<<)n3MF_fJp9$GwH|93yu`@@+qEA=jq z@TgTufFE#a^;&8P6Gm>qPy-I)i`MF0^C5h{KLCzzmjLU$}t z3=}L@C6fss7QxT66I8vO(2ni^k|M3z;_9vXF`oUaKrUid;6*6#1x>O$iU#=YI<>@2GJ@*iz0H*)r&?bOPUS}?A3sJHHKd| z0^Wz~5Uu_)GAmA%G8j)pqo=Da;2#uL9#+mzPV8<}3Bg0)FqQU|^`sW|aP~5`FO~ZG zlZ$J*9EfGs5)jf;VVIa8MXr;^UP!`xK#!6$P4vQCVuqG-kZ7tPz>kB~^40r|ywM=B z`JhxKaOgvBaNZxO|L<$ZV+L<-L&HJqO`tjT@~kxY#$+>_-$fH~S9%XzVfr#vH`G-$ z&WJ~l z?BENFIs#L}Ve4Qyd7kc2-kUwaT-;O^r{9iyLQ$G&UO^QCKL?bwknzoVwd z4Tygk>R>E(uYfNf4W{dwKtJDgZ~zalOK=lik^Q`|XM`t~wRqdSOj8ggO-Pq@uRGd2 z^k-j=qtf?6)MVks^FGhGsa7$KIU%Jo7Rs$Lf}Nl`I~iHefAp6pogd0JL)OM_L$fhw zRI3#t;0Ud}?blMvW0bKWpNaRUYJay1bJ(h8&3kxSjPW1$RxZSr@l99s<}j-lGjty} zK0oq6lV!pZ>56w89!0xt*!{m1{V)hO9F>^3#Oc|UyoVS3h71`xrx&vy( z?@Z}0ZD9E0Lk-Zp_S-2BBg|XKZIfW5C&8#Gn)z5(H>gXefV``MG)?Z%>m_RftQ|OY z!9Gpl&65ZrmlES1=dW^AS8JYf`;QQvvG}=V(U{}caJ@Z$t8XaD@ON3~o$G#C{I+X^ z7rsW!Gv5!JFWvP7!-CxP256;l93HEMZtMt_jjsE{n8h=i(i1YQlbpQ5CyBJqY@N>k zcKz}pbnI7-SIUTKBM^f876oDo_A+%Mew<=cmWjKCcBO{ui4&8DPd&Qb zo$q`YeK>g);n+JgZX?_l-1>L+ebBmAMl3iPt?|)9-~!fxOn8fE*_;D#UmnI=-U0=* zOaqK!k}?Cnvk~#&VWNw}-|Wg-BYLc()7}-d#qZdiKa+;-#(BaT`Fq>R;A)Lu=!qp$ zxONInb6J?4O6|A<^gUO+H3GC>bxv%y%P|*k(^3_&*L2a|A5?2IwsmEIe_LlUt9^2Z z5YGxODKWciPB5oA8J4T&-nwk=-Y@qqbdP%Pv@{ie)3-2sdMwJ#|W_05H)-m1QHnFV8dx#(KsW zU8+ug?`5ryXK%JUYgAk+Bu=SU{}) zO~)i@f=9z2eIvUeDn5L+cCCq=FqgS;D)3Q?*;tO;uXQBY^MjuE-rKcF-wW+LmFX*e150oLEzMYz76*IzR`}uCj0Ua_b*XL#DsE0RL&) z@BS%n6}{@hGU%dHx1|Z$Q2O|g&6(L;c%f?_heOnLBH2yb=$dn(EBkbvStCzkqYMZx zz=T#d?acoI?tPDM>r+aiZzJ=FSmgLWgWsnzs1pMhLP)$E-(JvLRw|Rbk=H_$WTf83 z#;RXc>~F}={zYBo;iIryzupfK6HaLH)60*)TKeKH2>rQLs5_0vj5(FV!6Y(c2j;-} zX4_W@u}H1Uw6wx1iB;afevxO!spf{lrX#8japcX8NNPW`w=&PP^`J@6i+1cQ-Z=>o z>hMvhW95q=kI^n-c{RR&d;GmyMs*-Q+giso5)+oY>2mLcyhnD*@j6u6xa!PGFNdYu zL`yVxE5Z(=YXtqg_{I;2R;+8Rbv}2F;pqS|)$CK8$2bi7Q(ppFjZyi;I-gb)$E|e0Gl9CST z?iPdYZs|@zx|EjgR;0VTQ#zDdGzds{*ZHmeZufb=@4VkV_l|MLU^vzvYY%b%YCiLs z&z!!U*LsQHKWsqx3mn#*l3VrZy&Kj8nkcdvDR;-H-%R$WynkI}%6M*;IV^np>U6yltIA{1ZBMtjWZb0HxX)Q{#FK0+9xGf(x_Y{~yg;WghYm#F z88Gb38+>r;kGoxZsh;5<%3vJlCr zRNe@;R_VNQ!d!I+nIqx?p_{C4i82FjSK+HKhH{nGjcdLF6mRaNaj>;YwW;TNBRf&- z7}$juyI7m`e0YDT>DMhkvp{6thVONiywity+GX9!H=ItRcf~&^64DD>5^uF7?kaA> z)K16xTUY#kRPWFC+j()>Zgq7{3*1Cb7HF(KDsZbV2tKUVy5%c4ZDE`+ZgwxA#j;iN zW=e@+Ta;NGn%Gj%%-C%`Pp3V0oE!r$@A-a{Yvh*e%9vzNe)ImobaAy|SeI!o@uJ4O z;E_f3&Bp}KxW%k@p2a$jIRfg@Hl5u2)Mp=+!nae)3Ki=WGh4T&=3hVeSXu}^JUJwk zi?`aZeLlR~u|;Bbkg z^h~b_@7cgb{DUK@5q_DWbdT0}Z&r}bUd=$i`A88Yte_Yi$^7Y7ktVhQtLkDIrdpZg zT#a}tM|jvFPK00g(n&1-GWnkm@mp|+k5Yh>ntt9y9@{phuw$ z=Zwbwi|0xo5m0Q=_;)q(fA+QXRjkt^_g zR|4kX64$c*l%#daid-V372wtgGaF3KdtCxK;uB{4<+Fs7F(~ipek&tkmo?xOdy)j< z@j6}z)f|n-M>PTR2GT;SO5;oStt;PWG=A%n^iqBw785yyjCqG0ysuB5IQ7-%UiHs1 zX~FC4-=Ev*8Hd@)>8k&p-Tz2^ToLKd&pLfApNl*V2C-|(P4F6tsXAnR54a3_`=8tUo2b^2b*hw$C1A8gq zbLX!*x7o{22wB|BW^b$Q-#wOIaI+TPb!=n+A*JQQ^;$Gj9L}1q@ed@Ch8Hh(=U!z< zKFB@3{;HO`Us$^6e)(=QV%cfvo1BG*nM+=h`dc-8dH#X3N1~ z%+D<HDK+Rn|96wCg_ljtC}~Vl6=OIEk+H#Tv|Z+7>ed7oabbMH*Ny z(79BTmupx_I>-f#<3#qzx{d4BEnc4>xeM zHlW0Hx1M4Tk{CFctgVP zA)OTk@GxWY|Kk3D!e=zHc;3||g)FKIAvD?Jvi3a4_Ifd62XrfTc z!U3NX-k?iV}EeS7y0-#RI?y)mk`G{vtlurt4_ zXsCqX^8dK>WE4HeoVJaR0(%yTW4_S!M-`OZ+Ge3hL4ve-hT4_+y8g%dCQ>c6pRcjM z&BjJ{b9`L>ZHah#*qyy)N>M7~t%m0Od`rUN@%J=t>ad5k4qkT`)t@T0gmg1@>)lto zkbmiXzNH6avHW0sHx276n6%si&I6$*pHlubQ$17M$Fo(Y`Hr7}}-g%5y0H_{s zq{L?`b^j3o`}landFdV7ssw5EeD(fV0&d01BD^`_kKvB%aWhW}$Yqx;lX%-XB zj1ko2_XG@hL7C2wdI}8~I zPuLB47QHzw*xIgVu6y(;35=An{b~)+QBa(;Io-~K^Bk6h#5Ny{w#LPtMuZM4pKk4F zSA^*-fEU`1u@g-oM&&*Fbna`#hTHQ6_OWo&z3W`J+fDaaNRs4(+1I9NMFlFw(N&)2 z^a#uzyGV>fLX02ODlE#LtJ4x=rqW(YC%H66JKVckw|>f<$Gxt1$PSUb+2yJe)bre| z2kD-wei+Q#^GbaMwV3L3g|Q2+$D|V$BPLX{{UOyKBAOb0HD~c(9XQhtXr5fflu%a? zoQN5g$i-FyxG_=GcV5WKjV6v99m|%Lk;Oa*#XMo}d+TSkws_&K`>pzQPxx)xZ4=0! ziSCb6NwK!Q)|jJuaoaK*kZ&$Gm%ZTO{4%pND+9Vyt2Tayseijs!7Jg)KTF|T?|gT} z;Q8b9`x(@fjf=8Py(a`8qX}>-aS&zxT^ zKy9z|EB6S)sw#>=?c|D@?j7k<8|cDQZ*{?6j8dml|>EX_RZ6 zDb3Jy=K%DhQ+rM~vXf$8i>ey-p)le5H|Zp{;Fgx#fIDE8ey_?b=UQ@N6ICxl z;T-R*hMe*c(FE>8>b&Yl1;5e}buq1=IUWk^69SN2RxMQO-?36_RCO^Jw>-T)d zm%yR~Bs;^-qG6sO{A+ssy^+@_qMiS)$N8ry6Bh&6Wn6^*3#I+$;?z*Qyv^sU_Fs+LUY|Kcs>^sLbtmQ zQbXdEC&6@ny0cez^5`0#sz@$w0YPS)6O$pCIf+!cOoMN`CVqDV$+!&!SwkNv4Kfmjy|7pVd|pt}sC@4~i~YbPb$H5#9A%e>@BZQOn`m9Fs7hP2gis9PncHZN!w{l&0|gaCSay z3gX%PKGOqPsLG19ekK88sGRr{ymo3v7z8_PUZ8VPoTQ7WK-OPl4@^9C5F zpnK1I=rbsRGpenI;N79e;(Qwq-xOTT` zrl$RU2=G&`^s4m!`Kk9kyJBGq#4tYId9~J2%8$!B&?JoTg@y#5iY5|jO>J$)J{~KJ zF#(cuZEc(>l6uvm)PuZA>GJpn-fdFRt+TVU%3qtfzZfhnoDU*3mwCruawD&80c6m?;NsyLgI1 zwreE$xclF2bFEE1jYN&9#?$R>m`k^lj^}O!;`5YslS$5?G?C93^yp`oDY<$(ICLwy z<*Ir9O`ta|>vA!$H18w&oR(z_Pm%c3Il;{ZZ;M$eUXTF0S2&Z7Cb!@yC2{}V;zYJn zd6hq=Ja(vR{iZElPK8D7u@DgPgu0Q-t^VE6=ko1DpJJwD7%+&_chBi!hxe!YqEm&f zIssEc{fGC+_1V&Sb<+n?ReFqsyEqlUp_;5?UHFgpPerupzfJFD`%f&ujCjL=sK45B z5;JT3i|9k^S)fY&;iOfH9tvnl5Q6z*&dB=`OvN@OvfVWSJg(^q!as+3Mhphp))H}- zM!RxYF(Xx`y*}WhgQ(fnYi{5v!{!qj?_Iv@UG>bD2ayOQltaDdnp_=$43tkrg zcP-U7oagu&!BtgF#?|WVX+>@3IiO(P<(SfS^%}1+f!c1gX3?n@eTj42uD%uckpyRf z*=D-FdA5K`9n05pbdi>BZd@(h_#CjK!yF$4hK?xp)l|FQ=fuRx4DIfmtLeG~)D%O! zyw1+p(}C?9<%0>0fLlHlFw$;gVM{Z@RvI1Wvn!w^I6zl4T!m>w+x{hg9CAC1s(pfm zadTvNbtAXMbKCmix?sv)2W5;}7>^U1=8QSIRpeMOwO%K@zdx_@ zqd#PJnC(|Jg!p>qEv5dnw0nK;R==X!4<4;sibCC#_WlZji}_p*0(YD3v)4fNeZHMr+ClEE zO#?SM_sjI?S2 zp4GmyxsysaPc=?z4+We=AG;1GMsSf_ykF+WL_s2Sex_AIv&b;DA^wxsH& z^qty8K_PpFa_JACxW#!BVYWy;)>`4WDO+ukqsAX`C2X4#@UD<3sg-*(Hnnbt$+7R z_PJ&~zZzWodVe=J`rdYpRm+ZFokmBwd3+@Nt_aFlcp({CKI3H`?s1RtNb-Z$HsF8w6>dn1kG@?8Fk8AAHO<6hCm4v&ZpQhP|A zNq6VJ_>b4!Qw(t3A-;c!TZoZ+XT5X79}%fr3i_3{$lgQDyM&6bQ%ALZOMnRiEho(B z7&bdr5Be?q#snJ)-2@nOmANe;GC^h(zwycEE zYuB!c0b0-sXr5?IWV_E*hBsjMnKFFT+*Ubw1|;YYBuBGnYiu$kMs)&ft_$~iiApHt zPlr<;Q)N4W4Alw$`6I_`tI_NYi;YX!K;mEg#ad-)TKGpZ_%u!v{k-Q@tAYdeD2PJa zu{PBjEa9H1vPiFN5a*Xc;>MtF10PNN>^)w-D;C25Hq zq|%~aF};P?9}>DUT33?Tbes`R@4Vh-x>`)$xslhvi_BL zKAUSxX}zHm?rIfv)YMa}Myzl#mr63NRB_J>2l^_f9qIl`e>BkIQu;t75B=0vQMA9? z2M_XmV5$i(Z5Eu|%>VR6BEAv

  • DoC$avm9-C=nlQXRV^Krv1OAlq1>Y$(8W4 z7;xFZTjE*G>MjOLk|hc>-ywP$KNhbHN9!xD11+H%4YO)*7Jkx0+{=}5I)6@xo7rNf zOxzyY_e-{r-foJtOYL+R&*G$CuFe`Dit@ar|L6rlkUnrNvunDvht#}zb^v{tuFEzu z8L#cWA+UZKaNrwpm=f-}6PW-g@2G>QC4zc(*QwzE8}3Xpmy@P4fVtqTgk?}3N0uy5 z57i&9m<+6gv*q_2g@WN?9(GU=^)i~OgCzU%-~n|HR|>s<3=3mkk0{DUom?7(2h<-0q7~@?c0{B3$C?5D z&|}hv<--mp>4iLUp0MiHcYCi3215&7+waWBvzyXh)$j`m!&DG!(hH^!C-Tc-%PqVjnkYkttPmT1SC)#xI0J0D@U z(Vp1@Yin9r{5QPz!mp~h5LUOOg_wqbbMU2a2vGg$Ryh@~^YwpuEGr9oo1@_BO7(AZ z6wLQJo12P`6zNwIs?kg>p6ZMs@H&ue?gxSZBcJlK(Q=tmDJvzdqbKnVlIjtCIiUq) z_7d$_H37GhQbD$rQv%*lD(qj=`mmJA8;JG*GNAwfRTV*+87Vaa0?{&<7ykeN4bWi9 z*4O-#R9m`#KuNLRo?m!JZh4!(3cEc{73VUPqLZQ?2lGC7Nw%l!!nWGkl}-wazr#yK z#01v}yniGXU)rTCkDW{Bs*trFIP#SaGD9cZVs~(@xbAPq914B}`=w_gNppjjLd?y3 z{r54M*5=Qm%Th>YW(H9Uqe9>jN5nYwOrxJV_ZW zwd50mxOD(M2Y+Ct(OJSczA7$=V9Fc%`lb$IhMLLRQT@*B3KG^Rc;4IU);!3h(iDpE(e30kj8|h=cbkAWjm{u?6=@(VqE|v>7*o?sP!#=`r z$RA^de%F`FXC@PS@ty!^?1=x5c2}o*rskbEK>O@5y3QKd)ILh`7)>j-tNgTg$xBW` zmhH1p6M$XJ1CM_63pP3zN|9!d5|JjlC&n-W;vidaU~qWza+eE!$K3J}dJ4Z&sfO-? zQ$9p3aOm7q<~nvAvaJvz4c4(d5mPhG7f|rEKlN(7;Wwzt%K}jYI*tS8_*3&kMLTuM_bmn#?gY6 zrjIWBj$;~KrZcNeZcOsxa)DopisWncankd%pqyVh0fNe(@ zUP_)i>2gQh?fp|c_qqooXiiV5#-Q-Qkjp#-QLLRU3aQO&tgm%?;rW>pBBKqP4z7n8 zUU<_2`v+&=eonhx~%_2b}Yu;|Eib%h1f+lhNzvbQ(o4Vj$&80USv;4o_+#?i9txF<9;8y%#ym5Z9nsw)8`hgTG6{V z%=-pfWsjYJcUA^OW?#tIJMV@~1H&B~gPo({0%(-RmQV2em-8S$Ppz!0KqLyLR!-Hf zL7Dh0TDGtu{h|~tzFaGIQ^yxxUcJAUSxU6tTa!1IdGqXCX*xb$3X%LV0KtD&K-Pyk8KxL zYBzM%MvIXS)Bh{5BH zvybu%s9Waf^KJGL54py)?2d~#Q^tXarxDC%fmLlrrDACW0)jUXg_*;MIn!cRP8hYu zNapo9Q69YNS4STB?XvGF@_<@IC4@L}L3NQ)iwh`d*oLVjtQh9zZd$)EwTf%f)%~tP%Vy@%jGF@ULEd%7XxM z*hpXWTwtL#8_N@DTYy3IzmvnDa^hBQ5`Q{x2vj10fvLSB{~n^{5^{}Itt#T_rTUA2 zw3$AJk*Rm90KL(NCwEdpL$PNEe(SaTc{4nbL>$}ax#K8x0K^t(Nt+`nqz7nstGm}) z#?^ydEJ-!#(%Mumia|E9%85TfN70Uw@t7wJMOz-{Ag75@3ivj-qnhhe%(bwRGWz zGv9?gY}uZ6=a3wJ%!u&mg)E!t_WT*-&VPW8FRFNJkCsd1PV~ydu&eeJ#>dF={R}a~Vk>?dIQS82Bo)Vu-OAL}!J)HX`|tJ(<&nDu(iwl%385r?Qaud>b|~gNPSC zEZMm&Pi8oIJ6L$(Iz!zLw$W)Zb&>0^)Z*oBO9rAxI^-1kO#Ro zNb#`Zn;;7MC`)!;5AyhUM|l3m>K=s#ApX#PTH&1dj- z=>G}Q*}XB`bDN3xP`Y_*R1OyvlZuCl3dQfxJU5A9f*If<^narh;{K{NU6{s&b#H23 zIfPJ}%T2Zj3p>KN_dB_r-vhvT@?YjPL@DqFwyc^4yq)LZ1B9ZtEHcH# zIGD+VBB1YSfdFKP0$Z0W)I*f7q~;9Nn;^n3G>FU;y!OM-QTj|4ZPwbBz>uwt{UDoK`W#H6XrPWW~xl7TLt zN^v)YBcWuT>0z;W(s+F0Ea7&TzelHr*Ajg zq1#v)AZJH(3Vc>s5!vEh;XT5FA7{4!0O7j4M}>iYgHFi?V(cr!o3{N;hz`upHGso6 z8o(2f*YQMh(H&_|3@=4KgCBeL9M^MXOx3SGTq4dvy(&h>-~5Qx&$xdy)X zOQg1_?2Vjp=@+jNcPsu2;Ltq3?~uQ%<7gUW@ep3ctU}%dxQ?p_z+$tw1Lj-SW7m0}HgD zq>x8odwT+pFF^p1VCAxP{*a^@uQWP|atxo)?Dl14D3UucUBgSHhI_bc3TXGyYvq?# z=~^>JR#HG4LPWgVBp9s%GHiQrdc@QsO=#c_G;{;GkvaEQz;5TvFxK)UC5Q`Dijqgw zcEfJnmn|UVhDIP-+gc~|xTW|R3uUqiAkWYeEZjL~)>{xgjt(3uaRfY<8G`!H(U?A5kD>PqIC_()l8Fcp#2mH-LmyA1q#7sFK^AjXD1?N;jE@q8oH zN(d=$k=j|VM&BBq0u>W7B`GOTM5_XICJCM!x#}=pt0xQNRPPd!rBXd&T}5`cxBecG zOxDh#-66F{z?MD!Wiz4h)~=Tn8;a4{>0AMBA9b{i7~8?ng*qz_25$dylM3=&o6mxK z{|5lfTx7p&1W`k_Dy=>z4a*flK_D>i(+Peh(bWGf9s3r(FYyV>`k2!~*+NAPKrVA# zTK|;y;^D> zI~!fDuSEe-<;@uiJwEqgcq^R)7QOH}2$p%sQCt^&be4<0YKMBM$nLgeEE}KyS#Sgz z*-O-GVddgJqqO4L&T2~a2d?+jtx65~Q_89*R19mOVz?abk-?%0PvpE9+ zD8PDj(wabwA^>pA#Iy7~nSt0zpMRzYqP z$J$a)wjg-z5{ieCulZpb%R5{9G?F3I7E;#sHMQ7_rW#*yeoY#k1nWD#f%uvEjP`17SJVTIMvd@RLfr7Fo!#r($w zN`D}8&L;Rt6D$mZCJU$!vwUl!$o@m|$F)(4dR#%3>D+$kw18eoujZqECZzU*t%=00 z!I*HPmcMS2k?S8?S3SdJ)&L5>KEO+Powq|%olW;Z;NZ;(zOWIV5bbVw#91b{^pAAB2)}%(oEBxVu^}2@YHI-;NI-#ZL21`$lI}t5b15>-xn}No8&t z*a`h`=0cQpW++N#lVfY@53hu((B@??`Pp&b0??6KwGIhAQEpYq-x-g&#H(JC97cXi zDV0|MSv1E2%OrWJox+G+*=U||XNr_nFJb=c;|QdWG|>wL@sKO*(@tG|#rRIUs&OO>dz)fLh3|#%QSoLx22CW*oHTs_>sxBCw zF=7kLvfVPPHtA}avU9A*mK@T_tA~~!JKPu?}v9Y0fs`q8(++xI&;|>%*R_?Hqp~lqw5wlO@AM0guRoU zl){=aAwKwsij2~9aMgB5A|NF;B469}E_G>elgL4vaRyG;sALS+=$k?_@;NL76^f@v z_$ws*4~MTQBbNGFXq*#w$=Go)d&(=$5_DothDAp6b5B~Imd21TD^_k8Qnu2i4P=Pc zJ8S24onA}hvtk}-K(+e4t9-hvY+IDT6IAx>f8T9BZqwMey@?-97?(r42j0WPoOImr zrX42Y^W@hnnP92<#Ewb+>EXivZ~k$|)MRbS-}-63LO-67eGjOTdR$Y9lLVIo17Cj6 z5>&1phO@pTVVftIB4_=mAxF8b#`4XA$r*~3HB;pt@pIZ2rc#OJ=~xEiIUu*Uw4yuA z#-C2hQ@!dGR-Y1^)GmI<20xQrXBCH1&m$6d`2WwAqHZR|(0e7^rvo;cz#)dwzfKPj z9qkH0`;)}=N=9FL#yI|;<;`<)W_=O48m>ej&_N@LpOCsk)BQbMA>L-U z`LjJBQklf1vTAy`y8&hK^<}xaexukCa9BUSHOP;wq@#HzCEluVxJ;PL@qHdL6KCce z5?*(1&+Hzo6(~2G1eKqj2}X_XP(GusOT*?&wVZYkpPIPgRLV7KA)I_UX{3&gxcBOJ zJ${SaON4E@Hp%qmlcHrUrY%bk`&d1cc54fxDTT%mvL2MAb)^GLntx59!Q2&7Bg`Vk z5=k9K2UAZ64}+e<1+0KI%OOfMK-N1}LIS`8^$? zw7Hu_vYd$2J^tP23%b+2{(RmL|K%?4|C+*7cajD_M{Z@WRplGh@8KGtbk=98OL{hl zba6|GW65JxY4`y7wjO3L6@J&&?yarB1QGh1QSE6n*w`vEwMD#4L=m}~TrXTy`S6`A z5kjY1P$f^)DbJ3s-EzZ8O>`?ais>ut)~0O_FY@cM=f($U#8tV~$h+0JFi6w^Itk~c zk58I_NZ(w^gOU?eWO_+X`E#3-Een2(bf`6OVa87|Y7kI{#uA8~Oi1N{k8ABJ7PaCj{8!L>0R}^G57rVEBR#YvH?Y zY_P;2d6ZFrA6|LUzEQYjZfL~g>wy5VQqs`175QFiCi0aSx_MpRCbm?)+s~;RBQz%$ z$*l`}mtvf-=RPC^H}~G@R`H($Bdo}^dX9TwP(CeW_%4&?`5pQ2r{dNlDyAXOprtlc zuTEnRns;fut!h)sVWqx0*oA~@hq7;Y6m*kegC5|b7!-`bJo(JiD^JJqW*bPX;qx}qOK9ZeGVdO14 zkABdg@^=hQ1au|}TC_6}P{ojSr0?vwj$k5jK+VgEt*j%O*(4lDQTgcP8VhyNf+^1v zgA(6kWVeozxD9;Vn+**mJ;5(Mw;YYHcoNOeK(K)~7u5$KQQ$&gqZ#`?TMrOj+yP1h zAP%8r?)7qQ8XfGH+=7bU#Es1eF7@9241|}|>bx=NkPLDC4^HfzerUvXfY|8Fu&2M2 zjSeOT)Rm`7G{m`k9-%FeWV6)t2}cm zaEve}L%J<`^|~|m`vkquOH(&0frWOYH0o-$;@cz8kW(COpFHCYVkgclcRL*`ifh7e zLNDWlAjr@{D*MP!THZ7W*M%3S8^Q#Q#AxIqTL81yoI2!r4^4x|gYi$6k*OM7vL9{Z zT9_G(_?z>YFqY)7rB9(ZdvtsDJ;@>irN|v`1)2_sCkyouoiH%sHQM93;KYo_h_b9x zR?FL0+d^#{zbu#keb^@V9ZcC{$&Xh}z5`aReJCxD0DD<3A!3iDh0Qsuf`op-5TGqW z2-C&vKHQhY=%wb(j%ajS-eK+2AX?_$Z0cbioRtu@0PkF&ev%wyp>N-mYa)^K$A`)y z^@mTrX}M`3;K5TgWp04MYX{e$ellyDQNAB==WD6uk9JzL3NrSd9+h z#9T8BJiA6`isSPF>*@|&9W54-n- zkzc|g*}c8t-bXP|WJgAe^i_0|esaDc=8zAjIM=t2T}lo}v_}dTRI3j`oT1K}#9GVq zhRy4qCyAmqy$%A3<#p2Cyv%~*d_E)DsI&XmEf=S8`kI=OdP5vC2Lq72(GlWdOSa{P z01!}@r{5S}7opuN>&pld}BGAL`aA|Z#-rWUWSs1eDeO*>t}9O39fQ^0N%w5WnoKeXkTc<+4=u;_)*C%!-ez){w90i3#OPW zvQ+hPXj38lkOnDjRdhfe{AU3)baG1+DYju_le$sjs zw=J9Ok0AzZ5b1ST<6#6ge$YQ{qvZfZQF0TsZm;TJJI=HTu}SPzhVhGLF&?F8Dv!h}mSXF9u}NFJAT8UO&CXwv`!# zk~@9rBBAF{X&Cxi`*YFfd=0Ek>vACKXXV#0WJek@lFnIkZ1U;vG+OV!8>`sCF7d6s z8#EOMVc$2RY;-P1GT{fhaoOPH>lw<>n^V77lZr@|^iR&>d zy1?D*ITnbvgm0tgx;}b4Itv>ZI2aDdy>o8_@E7sH#fuXZC@n|Y_~vLC^9uj`!b%y9 zvT`Z5h%eITjH!a-%TYwxj#!lTA4O3I2mUm6eK&6jR$|+ef?B^TMlLH3q+lcdy=PPHZ?PZ_{~7H6sR9X{hvu9q ztFe^)ruOOn(aPU_jY$D+M(DVXVNdTF9g2Kxb%KBf*(^bQ8M^fZTn=mmtmFHID3aqW z(>uY$pgPbLcQx(7BPr{&jO;~Ib5orY_2J>{ZTEihb)inm$85NftHv3p9dw9TW(9*0y<(zqlBMr2-7?VL8$OQEOH}5+TCPd2)^)eF8*K zYk6glV2_$)I0h`H`3{T0FF%YvPKp}0-EV)X_26n@uBEnmIWj@FDi=>4k`D2ANGZa`C0IhNOENTB@C&DufOb533a=P$ zAum3PDbkRXXdBt9MtbhxN}xOT_B@Aiph7M^?=%zc8i-EHFvNk;-YGt|JIWOBcsR3P zPDmf8eh|{I7VM-s&MJ1-B2EW&JPE@~{V9I@A*+AP#m>u{5pDb z@V(q#X>_o?HK)H>m*~U?>+u{KCG8TklqB}Pgthr+DGZai@Zg2JH1_Bu7oJIGCb0rT zAqKSdAHIAJb=5vs(V#>8PYSILRq|FT1)i;lQWBs~Sa4}03Gwq=hDV>G36 zv`UbqJ+JpN|0udf<;Dr`8$IB|i7C(gH4U^6=pCZ5#cUZ$Z{TJT4ZlA`Qdz?Olk(E5 zt?>vCH$rNR@`yL`x1d7F1KXHSc;JeX()hNz-{))SUO53;(Uz}?6fD&e>4@oEP9e&> zQeo%(ss03Xa(Ca=2kB4M)Oy>y7$AywnShq)#~<>sDos}>wC4*O7@>hd zME(fBF$?Z>(WI9VgEL`it8)C1?vFHQXd}Oj#Fgz5JPIQiuL+h-VJhCQr{fKSvz0S@ zA}$G?en=GgkF$-8z2m}Hh-EpIYzA4?`Y5Y`t-Br6mw$%tINkyUx0cbC$YdSki%Rn{B1fhafoC>O*v8trjXFXAbtPF@tmwJMC7wfJB9N%u-2px(IeP-}(PrA3Y*thFx!TNEG5}maqrXFP z%>c{8}BPe zgUJbt=SK}v%x?<;SdKh~UWl@z$ftIOZM4M^Od$C8k2!h6$7`q&+xKnZ=1s_k0{*5` zGQBk%s4nZdUw1wFcm0PrFO$*YULdHtTTwE`WET}GWK{z@C1SYEam0yxd}N1eheXHbf*KMbm6cPmm3)5E6J`v4eWU$=(sb*v3ssv<05xVFZLLPFWxYTc%_Kj>YHCFL~{!!pP8{K6#H-a*Y zSq?Q6&~fo|%61^)x7|8zJ9=w%C46G-%Ka2`f4DHnJ#+%sRQ{{tqedj-?eOTNq6c_P z49U7HEdF5!n^S;-rP@6YL_oBc9IwxRY+d}R$sAh6^7_HJ&{rPP;+J;bov!^BUQcD= z7sNDK^qdb{)aS6rnWa5s>Wna$??O#FLH>x}1&Lzoqd)lZEquiDb8VdqKMRYg48vuq z7fK5)sVM|fC^kRELBxa#0PVkuiubNyW^RQO{k6{bGEssgPlOUEk?JPUM$jb0*RqB& z-*#;Aw;*XZ0ec5_ItGk2q%MV4=YZUeBxc5!6brj(60)G%hoz44k#S&+{s74=pshvj z29GXd28`7tdNA}!hPG}7*B^&Fypn@d7@`HhNEpUORqxc!AX1{(){>TC6x-V0C zEI*1xAyyy1Kt~jahm6RC@A-D;4=+K}&tOj|8&eu<_1?IDWlLlXo7|TmQAXvvN0&~# zY{~&uh5e(DR38mhh0dH=?-b}$!RfCNg^xCHShSbVQ%umm<9;z@hy_{ZP6p1J4JO~U?q0Zt z6ndY*mF`o^Xpw1NAxv1YuugOcS9bMxQORIFLZUWmzEa?0TK6w7LRw-^R*js7`D2^6 zL6;;Ww%`7?-7P_%BQc|P5w5d@T5wWQ!)mS^vh;3)ugA#na4;l1>8g(Q!e!D){ay$h z#9AHxyI;f}-Ef2&X5=c^_5c0Nz%CvgFvk|@7LL9Wibm{AjFGPTi4)v75|6Jd$8C zEu~oX(ofp|w84)>;{`W&@?+jOtr;7v%-mhrBmH(Opq%K(OF7i(4o>+DA~Tw)2kwKo zmc?1|lsz}!gdd809|R%#%^2yaMSK;@Z>jtMLrf{Dp7^q`qCVI6mVPwFh&=eCu0~rp zl7kIW;@TydYOZ$RXah<(BG)WFLcB5cc_t-%{uwwtI4zja>Fgz|k}WHYw?;PM_c>Ri zZYFyVK;8Q@_0$dfmL77&TDti(nfNEksXsIX$Ox=7jbJ9>nQlU@pmLTzuFl_TjMHpZ z@axI~;S_LEFUD1BqimK8n+-1&uvseB3+56r^(q$2P&Rs%`vPN(hocjfN`hu2gV}ZJ zSqWwe$U3uyGPc>DyAonBSQbZ!q($+OM2ve_Dc>7^;mRIts|UU7yz1Lc8}c1+jCatB%`KGh z06`BaQ&hCm*Mb*TYb#xV&SxVA7}=ZivvP+q$PjQWH8UXc99Ga zCPJh(r&U&x$-c-(>UE@RRRqTOK>3%})(RQEQw&aN-ECi--H)4ln-33dYwHtxFEn!v zMa*_oc9KnGKbRFb7Z^G+O*7q^zz?YbyKK1Hab`_mVOE%KD^{ua#bz<9G)iCXWLA=e zWnJJ3tIw^u6DeP8eOv=1iv506#?*4xt=LGsN)*conDt7$G(2}vT(qIXcoX{@Y(+fu z!wFcsNCUheSO{sn-2b0n9PQedabBWdP>h@W`Nd#HiW|VVAP)dO;%M7{1*OgHZkc94 zOiY!BsC}{SlFhu!B*}K1-8~lDqmw(1oy|ThlldTt-l8)bq|DHEk7;6UYrCu=1Y{mF zgd%;XPc|Oq?sR)^Jyxy>1p1RtQ_bi+wMje%ZBMP0HnKWHn!F_jx6+pkd&=;8amEs# z#TY)~s_J!eti7Qn%s2@_>4%`1Y)GG4a%&R5d;u+!#dg;@r6`q!=hZB4SLahuye7w86? zV6poaO%Z~{Y30c@TngW_L3&Ag{LHD}$S81QX=Msv%z0g`pXv_LHcT_ali-(PUNjNo zI-h#&uv9LpF?eL}V*TgY$!U!F(6I(RwGPETPz3wd%)f3~oK%7hBaBs8!kks4cTf`k z6}92UGF#5H@)W2FZtytP7`SV(yU6D;oa+p^U{yG6LX|~Be%OSLfxQ)FuePHsqcPbK z0)l~{a2u(|y10hkybgu-ICGQ+^8t{^(VSsftTEsGl-b6lF-{LWTs?i*v`PMqC~v?@ z_XDRcK>AwxeUy01oKLudGkyUNg%8YR3qh&YO`-v{xpTjCh^373|SCD`@hlXCMUoxE*$whs0MF+lDff?acV|fGv$m|Ts4SgMu9)I8qgQ#v$Df}AnNc< zV^`tOL8Kgi$&i$gpo>&=gm@8fFjH;vtyJnvgR-!_EIIk(xR%v=NEErr3EF$)G3QLo zg6E#3KlD*gSUm3d(i)ja+-?Ho0%MAiKt7(+6?05jXj%rFDjp$R7_+Yo)R9OG^8K^s_v}K-}VQhTIc~ zoC8py^q}d5b3=1JFW^CimbhXtjP^c}05!}dMN`oHYS=1*k+F;=Dl$=7ekk`e_j;6Q z0FQHpg<}fNLL6Gu4K9i*Ncgoq>WRKUT$rMm>zp}@?rvS>0vg#_L1(#}Z&$auhk+-?6)QswacqDs{ zrFNaIM4{5+cABx%^}=HR;a{nO46EfuH}y#YC|JuukBV3S8<46AUD?(Rd34mlz(&TCfs=I1r9aVUOqTZ1I-YKa{Dp=Iy<$Zc_1m<=Z1f%)|6aRxzc-pzu}2 zdp1Ct;vmLi9RY{KFEKF=Id07O{p3=kc{50Ei&4kYHNH~VmG4XHYMc+2(i`@`{hpb~ zvJuaDvgYc>d@#(G;2-+>Bkwy!wW4OXj-@D*Ny+Xb;zybeO;}o;x887)JH&|^Vsa*U z0-@tR{<4M-Gt)H>2ERqTt?Jh?0p^T1L+^#=X09xtuWv zu~G$8D<35`yFskto=!5V{OU2*5!#|iW9o^>xrl;h6C75ht@tO3(Mqgg1mIPkZS7pv z(oDGQgjKW!GRUwXgEIdrFHkCG^~4qO8I(6jL+RDA2Czv1c991?<{e@!H`%raLJ^8E zE?1Dci7WGu8TR#uS<~q~zi*cYtvVH6wS`7SM>xd*5A>~c7}^`1e0pq+x9?qc&7#9>SF{1~1=W(g7VARtSk8$hYv^O)lo(*pQ zzESVd7N5JB5)~*ZziIRYZk+lfm?~{5hY#bNb$p9HU#bXmvFZ8ISP=fPTkug8+vx?M zT@-jA)x^5AI?|Izk1{A(rd=NO$0ZpmB=e(1jy+HC?KV!IKosCBgSzyqcM=;}R0=N3 z8|Q?^B%U{R81h4su23OoBH#M(tGMR^W!ysue9zN4!Hc~-C~tRl&ZTL7nLptnwhR5& z^$TW`NLXEFR=kkHEQeOoXD>D!08C<5nO+w7Ocs>K*G5~5p)hG1%{SH1y~YNEA17R? zZ9KtcHUHCHFLZY>^+p=Bbqt95P&$9hK=pjHse<7T2D^{t49tk79a1(cfS64vvde$= zPM)iFb3=fmN11+A!YoCSjCpV6Y)?LBjHVfRipUt#ptL#f5Dl}F>@1^zCiLT2az zjhyT>YH2s-aabspJ=gg;KKTYYa=bA^Fpm=|mL{Db29ai2jfbiblFuHSB1a4@i$_SC z*=FfjVL|IPC1C}7ERpcl=(!brd753y?Jpo`^P=^fqo$%Uvqsj51($=i!|_JO$Oz)u z!H#QQCoZZ}0H1E$mT_G>_?z#Xq}dB2+J@L%rz=4C3*=&o+yO1LQc88^$bRQCm-at< zog;cc8S1Zp-UdJzqYR17uq;(MFvA5CIy=6wVofU-pUuvDT5KzdR6PXwz)Z|Qx=Wjc z^@mSf0f!YpHj3_9d(4)ddm!S3l|fAVYi8>oYnt%q@OP62_@THJ%}7gb<>;hTuotrH zosD_?hEf4^2KTcn2J0rMEh9S=kA6#sp^~qVI4dQ?{ZJlq{A0yBZe6q{CrE-PhLQcZP?S64| z(vt9*?`EML6ODHb^q@Hg6(P%c4Rllb-l>AN>%j_i$B54kE~n`5zxtvV-7)7^@LNQ7 z(1^j^4Qv3|JJ;BcUYLSiO)95;xC|FQ*9zyAA%DI|&eWWXFlQ$giQj(tEdQgq^gJ7D zy0i~kW;8h~0E&Vco_+8)XXbR7&9!(L!QU#)g~v}`r+rrTLyGB;uYskjYJ30=A4m{e zT$h|X08yi;sme+f`#T;X263BFj9P7?an=lP!vylgtiFnJkoWM-_b1AI1!q;q~7KA5Y?DJsV-$K6_@2)AhSHPnDgnXi}oy1)0`$zlTlOZrP%YK#g}XymY=K!=?Vf5BB!Xga4}H)he7bZY4Myz~OeG{` zOrWuI>zrs@=w~2UhO4o_T4IBy&SmH;2lk-N(8Rad=egW=GDydF&@&Tj7qRSn?3V8o zdE1U5#Lv1WG|~eY$$u`3whIa^=_Ajd){R5W|Jk0Am!&Am#v+UiJ9}sIfvx@+X}lcO zmCE0xMR~Dmt|80!zCTp?0}(}N&H*^@E7~i5WG(D;Os=zPOUn^yWAfe`4BmTZL`|3n zAH4#TZq1`G=T;IAmx=K1)GVROeS+xEfme)F>jZTSa5Jlv)qdhsuy@*hq`4*;M=ZD@ z2EhJH9l_uc?T}oFlUWvv3ucv19P_-Rf-VVO;1LPzK{Z-rvzqX|B zV8w>b{oIizNC{@Ytv??wPl_k31b*INkB~rBPb}I`A!O?;?qmVA^ZuXif2+^m%XYxVk zW01GlFU0HdUyB!YuC~eI#2F^$V+|1>OfuU+{sKKz1lWOZrRUiAM~Md80`1T@twefz z=M*`&Z>E0vf;xdH%woo@j>32^Ru+M&W>c|QBn;43I4mzb)R@YC4=vQgk8UX?YaW@u zX02g-Y~B%71lxd*FR>-XA|B?VIibJ}+<-(j?ja%5a0VgF=AWI{c{D z9J>V5BSN*gn|Y8M8Kg2M=*yTw7&a5+tk%u5_a!|P76W10wwDpw%~7oU_2bJ*bK&vz z9$UlV!mK$5DN=`LgYsp<=VDYE9ysvXvYkrKp@e% zd0av}NP?^D@;`D>{Rh!>DPrw>#&m#)+B%!cZoVCu49mNO`L?2~cJla01QMHtJevep zEtW{4*>qaYbNTGoXM%OtI9q2%PXnE%BJd1LBr20tw(g@^mspELs!LPG0?XZrv09me9T9ykTOl^Qk>*091C}jx-N#|4R0`+ zFwWtnAM2c%AN+hqu~4yu?h=aB3Ko z1f+``cok?WF!=Xrq|B3*Zc>tbAL+^d*gMY+~K zu-4LVyX`iuKF9aDKz1VO76r%lxO*^>T^ZvZah4>Z@5^ z{?Bmcx9u0AOM9WLJaPsG&m79%Ix^cPt-H5q_tFsIBLNGI`i=}F^|wt1IT8GbO7g?u z^P@pZfnSD@Y*cWrbNh)pMfs4(NM+|+;oB)xz2#Cithx9C>S>j!Dc$qs(U1c`e5+Oo z?WGAUl&H$*O{?*s8hf+CylJOTMvf_afxr?w-B?{y6ieJ)yY0KRy3zj4*JvJ8yD+*K zFy9i1u~rmlVf+hA=LXsev`RXUD7n41GTG%$7V^O4)z{qoqjQQ?Kx0M_#U>3yxV4h- zrIR2_MCpXufWJ8OEi7I#j#+C2`}N>uh5`7tx@?K zcF~@b_y+L1>RC;ky2GbnRbO4-dZq-djj`R6yEGu*wGFmZtW& zM5CTDzz9xdUj8`I@~d4tv@}h`e7V$*$KkL>@tbt(KpI|FBhQJ3U~VgAOx8i6#puJp z=LCoktT@lXRXDr0Q9;5?7ZUb_dHo6U%Xt|3)C;!qR1B-FN8f3;Q3?IxlF^d2zz|#$ z8P6Iy!*UYWI44bbJi00wOj^hm_E)N48TeQw^q3>VZno>tLSdb_T zJE9#$5rjl4V?opHnj7W`If><%l#sSE=5celi;f~_7^FNxhxRRkjK|8SAh`EI>L;fC z+mu2p`r;EtWU_tX^0!%3y7DM?6H(|Wy7^WbzIw)CSVsP9xzfIn1pK}Sv<|e_@Qe?{ z?iAIFkjDNzX&5IcTb{31&Xp8fPI}cY()#FP{kl;gfyaIS?gF&XSS=JX`t09y8hlX{ z!9P8-9gig~`;mWjs~Sx_L=pJyFHy~^Q`uanTK56p^TyiQDqNG!{apHxiB03Lw{-X~ zBLr*o8(dy)bcP9Rp3Cq}AtGi3t~yNM@7f z!%jIVx5S;nYd_G_fP>K+(3xO|KCNDkbzmmO+qkW%wD%pQOl$*tf&Kvs(?d!LjPFVp zhw)X5uPl|UzCfP}%Hc#iVn89+|Mq;N9*fqEnBV~UbT-aggZk}&hEVOqK#&{;oPz~U z{v7LqzfAD&ZN3P0?d3`8$DY30h6vH?cri;fpu#n7I{KdXb0xyFA=X6nNDV=n*(~Y> zMeYcgr~VKGpCLMmt>6c8_MG=4PB#`0NE+F$tB-uffPB4v?Xeme@ULoyb)(0OyxmBY z27wg8nz@heIYPay{#bz^ZVbosfyA5h7B+Ec8;j*+0~2El0ZgRxHd66-ZZm=;^`o-R zX9JmmAtDWUBAAo8rCA1tos9!`(d%c>QArMG9tpw(0G(%(qUnr}-V{BmEM0&Q0q{N| zhm?%mqW*lw?piq{G+ZOZ^uTfV;!L^ha^+Z`pd>1x!C`(VixF_IvRR=}4-X~J?bWO~&8nDf%(|Q{x(k&g zz^e z)5TFh@V|Lmx1vn{z-2G)9SHrfRK`qwPV&=X9utYlG=At9TqZlrx)?W$e(0bGyW!WJ zt!tH~SF3Gh@vJ^6c!gnxMs1Tt{6Qw+rAlKn`v*%LXA-|mIlKFX%QVs{2yV5$&a}7f zrVLTBkHeaHLFa?6>W*`MB&17;O;arauN04yMBV$^gtmb;4v@j-&D@FIk+S%>(o4L^ zi5lMQ*g^PjSv53A{SWr_!qaiXm8QNCZ)|+loL-qVaz9;8=gWw|(3FDuic>-t(d^+KMOdX<=(TKTUKV>Ix*yi4wDIr`yPMv7$Dty^_PjcTpeT?y zP|gR?RHF&Z*?@1;Sc-7JM8*%y=}^|c{N$Q`lE!4y`N=C!vI`6C3b}U1&#`xMD6yfd z+jZ3N16+PlaMG#g7J4Gbb1>v0(^4%Tyz6=2B)zpbHBc?I$y!q$e(b{U)C6|Rrk=Q0 z!s;dQmv{w`88Hqu%KE{PGYjc`H|^uGm#>6Z41R~Aiu@vy^)!1)D_je z#g4X5$KH*Rs9A^lVNegB2Q;_3TT;0vUS5!FDQ7;oNOHovOj>bjiYjCbU zcA8u*E8avU73x0=t=74Yi%h{71hQ;w8lNBCPvA=g4(jBqwaH$F0YvA0{d2a8hSS}% z==cADt|rLRI)wzbQU^ z+H~8QUnx+#gaSjgghv|R6%k4L;iq$Z^+&WQUaobYa+256VFLC_rv}h`luy|fggs$6 zmG!X0sg4MNcnL< zHii%>LodF+0kc;{e128IchvrC*OiN052&HEC-lhD7E?U2w%6sl(@TBf7G!GdjLMfK z)<$T-uFS!4>mzTkLDo*aA8#rYynWvIl9Rs1QbeURq;vld%|2M5$_SyNaXCU^@2F$p zQ(i7;?dR3AbPIrm?N@64VplCsgtR9r_}|85IruK^GrBuqq3-mEk)?!ACmf+%IE@(W zRg^1iQdoe7#IPjyl%azGAlZ-Ri?lwMesw=P!iuoB4UaxRE5x9Vz|;JKm03z{h$6%I zdmqVr;W|BEV|}$+#a^o@_(SwdKndkGEvccb{B=HgeT+(?zf4bR!mCsOXeuZJ3MKVL z7@$)!>!Vk`S>w**E!nl|aV1rp0LuM`U+o6=vN zt=PCVTP*lc?c)@yLsI;03=bm#Jl=22Xl-@$enC%P0laQ%P@18OCwdV5DDQPkBu8mwWG0w+KE7x0~k-#*Rel&sc zsCN52BR>FE1uviwpkT zflwuj4A`cklrRWrRh%(HjBe)6n%f@yi;N%!34)L0JIHFO9fDZ8odugxOqJMaMt6I< ziJ-DkNAe9IfQ3(k0jbm#FtW++=Hm+=Bxy@0-=PsXsm^wnQM3zAh{S4+b^Zn=Um7UPpPfk_jzl^mfHqv- zee(FoMu0w96~{8u)QRURfS8MnF9r4nV^wZbYwClBw>L9-w?(s&vP{EN`^1Hov(|Hg zBH^*IdY}+MS*Kc1DZ?^H9vRmVFI3ORV>vZV&2#i;4R*|cW%8&U^%<*LhU(4lEmSuG zyi;oKqiKc_;N7OkZsGoPDN9g26v^u(u0GA()_lccy!D3}RN0TfaRHH5MD-R?c6;mJ zKx&4sotr@S7prBJoAUR#GhOLu%S}#CRPutxmi2J|Ne>w3tocr&thu5kKUjT=xmjDR zKM~6*l%-EhFYF@cOi>0NHzYd*8l9}#;_$t4oy+SDEIS)x`G_jDV{K8W4FJ`l7Wqm$hf{hY-hG z6aZ4+lqDg5XL*)!;c6;Wp^^-cR`fvQI<%pT(oO4ozP&hrF=vW;b_QH-v!An^38r@l zg)Ie4X#_M-JEVgNoZD@CV~FDkS9|r@Z}xQd6r2GXL0@6Ez(^YsEO)h5&^k`P9#nHy zq2)L0T5I{WEX_$VX6A&POpGZ`9SHdQ;t1S`2+lZ+SV;gB$=C9UtI|Q6=xsT(O#uE4FX9mPe{695 z>cUmq-@h6#EV0WjukQ-c#=`SHuA-f{7W`Kse#@JxkE&V21?$96oih{<+Ftae$y%_g zLxYWK*|C;QdaY8I9+1!*xsgQ3Z;!BUiI!RPK35Vz!A$Z{Jx4-hFs`snx0C;CQ7R;H zObXfw4GsSMODxx0Q(|pk>E^k`o$CvFQ0q5+# z1nd5d8O0my)N}f>cBhb`0N4wN0|QR1G7T|U`L@MeXge9r80W2Cs+yWF&b1w&|5=uK z$&}UNAD8!*6s@@~9+v%L_Y4Vf;}&H!`;^E9%7$9N%;nbb&=F&ormCR6w-Z#6t@Ykw z`zbI1)>YzH!kdk@E*3*Cgw+&=zMLXOkMno@YD|0$5?tlS5*WwCumi~s*ABgMSnC+8 zg{ttEn^!2|vSLB7U0~CaY;dA^8A1h4{B_tYA7=T`+>FqAC1)n>6^M@2uc5DiM-n5&&rl8doOF*&d%ZsOG(NhO{<9X3gDGD91tWdWkTP{9{%sCuz zmEJtS132|vXZkuw^+?8_O{-(PVhK7_~+hK6NZ~U5-=wP5|z`s^-)J$49lUMa_NZfbHwA3`06;!$Q-e&*%? zWJyXxfImXxdl~_s79+yEH0n~;-&g?W?d0xBHKoVUaPvZnvkX<0HSwD_vw-@oT#8bz zibj<{{LlFs;w=R3gKDfP(Q;a^Ca_^w_?jO-CG$j^gHT+^PeGNB76D;Beb1k42!|s4 z1~zS?e7uBIzQ#fpbL>!et}WZ7f3~SOdCl`H6Bc_8m2nGYG^D#vE%orS#8+<;da%l5 z7O{6Pa}=Vb?!?{Qy#3Muh;P$go(#-P44@cozRvS|5+QU6RFusHb;26~3xtEcziFZK;wzbJXjSBMnG1Zqiw_(`2 ze3-FH#c}vh%F3RZTqLm)RdKnrcK&L9l3r@PMi_RaABfEeD0PEPz&L!^cy{oM-%=i- z4o&J0t`}eoo?`e37yWP&J{Fwe^#*KZKf;ILwM{d^d}{{EGA&eN zP9^w&@arxcd#b?K%;yMgX6ZgJj;yHhE8LYWA1m6{2e`@md%4qx)CG14_t1K)M(j~v znoPH|e0~N;OE0&APZ-!!8(?gtc=CWstIxY4`5gdBaO4;)88lk33<{a z_DJ&!^d}gm<@|JK2*EM)nsgS0pSIyi`x{q`FBDk6e39{d@~u88k?wd z>&*`&)>57CnGX0A{$Wc8t$QXElyJ*d*gV6QV^hQReL%zea=kktbIaCv*MB3egy=6~ z=ZiVSGaCPaoU%x%mB|wP6dq(j-5x7Y{by)#H<@$F%ytGHao#d|GR#*G$%z@*WL7}> zewEg1H%(?0#Z`gRX${|VD|5)b=k$|BVH1PEs^N307^Ku$HB&sS?*VT^KgjEhp(uDT z=NaY3yh*OU%M)_nP@}aW%d{nyk z>(e1esXsFkR{u!>7{k=osx;y22YrnEn>5=&uoSbbx+(U!Jy?AvcZ{t?knKI^tA`!9 zuP~Zf&$84z{9SvP1a!oWwPbc7#dstoW0?`n!NJo_pG&R9c2t6(ST;yyFo9kkb{IT4 z4nU62%g}Tmd|5D`zI?yVN=cYk)ZTuXTqVL6Zmj5we{DP3@972UC-3j{UOfWa;vBkc&lQM5rZhwW?)A^Cn)}Cu15H@QOgeM$I1akU7M{a z+h(gIJFHRn-3W7>B4(s#EakNuEpJKiO#wG_;*(N_t}I0%Ei{D|J=3pk8@pK2#cIV( zQ~d{0sTqBe>%9mE@>KqQ3g5~4F}o7?b}RD1-%%${6M7~--E#a>*ZTMx zD!G@-bQ&;tGDP*CN1a#7T(Ii_-XK1Eky&zJi?@Ey<_TsMCYJ2m8>NpjF!RV2hcpR< z1$B|`FOSwkRUWTaHPz4!Sno1cTzffoS3Lgv@5>D~e-=$v47A^OfKrX)>6Td<{H{5P z*o0~#0FWm_=$rM#!wkmbL`E9-C1LgWcoWG6vfUGa`5G4hK&cW z5X?Q}p!|clm%M69-sV1V)!!ZET2mdS&SgjN6klpD3Jb(>%%SxGsTdU_vU@xj z055)|?`;RIO?m@ya<(&DsE&J1|JYbHy;;I7{_HFH`vev}TG7@A@DdBp@(~vP?O6XjdDiZXJ#?y-&lRlR?Zt|7qTyJRr02HW_udwnV?}Lmbv|hs+I5`d z09-qB{DzfVW){eGV0<5iP{xhA8n0z^5LC+)2n1xpzB@I@%^y7AZm4!GwTCNdnQZrA z9lf4?Y>uQF zp4SNI6?@40)kNs<=x8Wi?o$z*EW?}zn4Hr`L8j(nlB`30bk5G%?D0f?WMqJYf6-1e zBk-|^c>P2Pdhnoq$e4yD)GFKV7I5=gWr~pqq;?F8jnG%e{>Nh@G~^wx7Tsv{8@~aQ zdAq^FC1aEJ>R#ZA>XP{one949@ZMu*|2ex#=&ydOFL&4yy>^g1-DU_mh^TmW=wKU_ zRjp=tCB1(Y<)**Q(ri6GfdVKC=cPBS@`|+el0tzZ?bwkNYIVlJwa3Kh&iv*Wbb)7h zq+zvzFsXD88cm#6vh~fQsw04Oh;QA_*W=OkmmeaQ8QD=qnQu$eyp^dodOV5{$6Yi? zz2;{ZrKh&BL9*>hTndsI;wYH;HQ@j#+@2B36tX-XDsNul09HdX)vJ7~oQV{Jt?I!3 znyBq}Uj$KnM>3Z>y(q!o*`nT8)9?(2eI5cM@QCv2||_iZrA4u_|bv5;c+lm9wc6qS>Yc&~o{%EPEG z8z4%La<7euW>CDKeO&hGX{o9<@Saz`SfAX>itwlsz1Oy|r-b={uil>>b({X{XTL_6 zgEg?R7KX_a>N;8^yW}9ngzqa2AF#;uXb$PgsRR}bdq^xdW9{~Q8mIGR-f~~cz!U!f zD~LyNj1hSm5;AnzsJAR4PoHFD>hf)EGurSazClIhGn!Ne^zNW|FV&f0*J>bBaVRN8 z984x{&7>^IEcm!ph5#Ll>pj+9O{$!e*As=*KuQ*mg-K-%GhU242^%I*i*6{BSK;p@ z=)RKS@GTIwP-hRJi6P>b%4Eq`ylk|FB$uiH4N^qy000SQL7pJZ#NPk_KT#$BcZ^+% zd6S+LBXDy6l$!w1^l69wZp3 zuTed^i(iwLpd_$-j~Ym~2DZS|Ov7U5Y;LWsbp_4IOX=6DcUbuk1!0VQ95xbTbdRaY z|IxhpqITN_gI`!>L|U7C%!;HktU>AebZ+5_7>Pa@+tncCM4lx)63b-_9f(gO;v0tB zs9y?BguL0pZ#C2{x1az4U#K)5r!5F!kL?;7Mjb=5g)Kwd@@j2+fjiWKCv03{z0UKr z!@Cwbflo3Yl)NLi`?T!@9;{`Tt4UXmSLN`n^z(4M;>&RfF1I#!<0?APZUFUXX9rX4aw-h-geE7% zZqngAU8aXJY;OQeVC@O5F<04u-hp@R<7ld&LEq~NIE-eXh%kkfGy$GOHw^&2Y ztr_^b^S!~#Qa~deEcLoxm=Yx^$!>{rN0WJGnfh^8ZG(au5m5#!vM0B82-u1Q>#!l$ zN~pFF+Eaydn|KDwJ&?rJ3i4o|`-u`E1)JQL`xMnF1Dlv20n673=L-Ve(4Lv=HcgI?yN-xpUXToG&})Z3jw1^E0HzdIugW@V@l`u;G7Q22{|IxW~Q^#r6OI z0{{%aQ;p0mP*eg?YZ!-Q)xFxjv-~m!YoaPDc^S7?3WCbJGUo}%l zI8Vz+nE6eLI)0IYaB;%@E-I&Hm0|c7M|l-|`_QHms8(VuXN_B((OT=4p+1oi(1ke_ zGZ2Fts5Jmh5XgS9N$aL4fPZ)o)~mmPpKo9Nhit}#pts1}qaer!x9_J6q#%ty8q=9& zrX*#Dr!!LKVOQD_*>=l5@xJYuh96MdB+dv9zFZHQzhVk6n9%|0U#Aa7WZ0Y_za*2s z5yl(N_Y0ywa-Sib zJS0HI32*81-URJzV^{@Snnc(2xi;-BeXGly#v-|0_ovE)4OIYP zqI(W>?RwVuche(rNia-`t6?-vW*XA%q407yKvCo65p6)=;@<5uha+=W|s(ew*$_@ z{$z98*0xv8>fv4QSAk1|_VOq%IX_U6Ji_jbXNu`&{eO_>1~kFH(t5B_5};s7+gGTH zYbY12brc~`M+GQJ0sw@kh5Q_rV-YpRYk^ z+~C>7pOR~8?Drd3$VK35FGz)&XqEb&X(E~UfB5b?T>QocV7b4IN-nACqkmlT_~cpw z^nB{DH(ArwkR5cxA}2WnppeFas&JG}tUTrYimPUBz|$|(qh7fL5oh+gl2wHo=2duV zc(uOi>5=h5;SB>mNYpO5JUNS33;>Vn954cIO>J=Y9$x|eK1c7Qn^xlQFIqPCa!m&5 zfHG=`>}v0aYwoq_@*|>1nuTY&$o*l9I`&UNHw#nsQ1S7!AB`VtFlzVH(m>C)Hz3Nl*Mpeix-J?i$dNl5)Ex5!Irf5VZcnViGv90ako=fQG%Wg zrFk$`S%78;!21})L{Chy0q-q}#UF%X3+D3>0=#IA6<_3UrR1>8IlIdu;)lVRmiZpn z?i5`4HFvn%q}L+i*=3;JKF9!t+tTOAT`Q>9^JCC(<;7Fi1zJ!WC@+*M)P~PGl-Ef(90twnVl2$FfXkuE>F!L` z?|~!0WxO;|OwM9zH$yULQz}k}q@mVB?(7l}t;7H;`Y@)J^_QMc1TPcUl-Dw2O40$S zf6`rc?HA9)27y{uXJEp!j2o@r;;f3yiSMHDMWxe`;z(}`1PgH->gK{l$Mwlwg^DHu zd^WZJDA$ft^NClwz-7z~0C8qvjbC}{CBZd~dBFe%ViSmhs2?c+B-8!-gm7jNhc%3> zO(BM`;+`{@hjCKFX7o+y+~#Or3Zw^TDRA$a9gb{>GOEyQUk^^-m8Ro9*GCF5^MPX$ z^XwY`1Ap>GW)ob}Q9fGybBpHsK(NN| z1Bo%>l>HewU7+&&#yx}oeS!@`4XpTve!+uFUC@g}6%IR+HM4UKJ~cXmUyRZ9L*|wY zvkO8F5n-aEnp?z}7eRa%RW8H5U2KQFc9pw}GDtx8@05}R=@Wt7(*RMhV4+#JO z0d4`FD2<{k{{R3z`e5n!sTR%c4>r!2FE#jgKZS$-IsJKZv3Pp5m|n*K0L9~9R~nh7 z)AiO=@Vtf$KX2=zpT#f{tB=v~fM~BfU{LHyQcEU|2(^e0CyD-L@2JH001YEv!f6o zN-F^{Z~$&I7{Fuo-6lW{?hxD&KkFMu?oa@*c=AWuGz4r-qWT!G@665R>J7pBSy{Ts z1O+VcgbSmeZ(o8*wJ&a5B=ka)#B@W zL!rn?`kl>Xv>ZA0g;*i zsW+x~FaQK~voRQ#?BSGKfmebd$JxrzDRluz;M&1eLFgr90 zLamJz62gtQdfWQIU&35`V!={fup&Neoici*b#qeI{DOdZDJq&cqXq_X2}5WA0+Ij#0l)#CDD09e{{R3%Tq0hM@Fz$hvh;ue0yI>^ z0OaZ#$-%t<6FZDTrvi;Fk3><(*LBPApc67{+zhq`3EEZZW5PHX8x*p>D~W!=&m6(U z`vYBc_YK~WN<>ZEw2M?9!bbH7%QSWi-Z4fLyut9#0--V}rQH@jF5K852k-=$0- zx=U@pg!p=*|MUA$lVVGf&HaJh1xcRoN#TAdtlX*8=YjZTq1_+>ODhakeg$&Os-1;y zd6)pg_%&20szg!b+YS}tBfJI*J%jhgSq4nR769m?92beuv&2X*!c$y*V_;@W)9n-6 z_7mH-Ik9cq$;6!4wkEc1+Y?M|Ym!WyoAlY;b+LXsi7(QOCYETO?I`1|03+`MIG;8fAhYTu2uUZxOZuzSg zjjlJbS*^;hozt*1j(Tc8e4cgPEQ0;F>JnvU^PDV3T%5XkkNyZ}kYpy7WI_JM%UU$w zTnc!mB0xv@t2~P(}zZeql$e=*|v=C@63OVdtb%e`M1UQ&ngHiS#76UJAq;dT$ zE0W<0`7r`R*mKX*HU+=(W4k-9dV67lh=L_BF|9Fb;s;yBv>K1}E6}<99cP1RXm(Q5 z1#@1Qw}F=>8oO~r$xj~;r(J)jiLxG0|NeCoMagQw7oo>!SW@d^qW)<=)oxUvxQMq$C>t!5MN6@GQAtW1N-vF|7obxkhgP5MO z*O~fw=Jk6P(gJ}*20zg3X?al-fKT5*CYy2cRxhR15%U$_!yQNDwUtOe*dxuDkV3nQ?cjcnJwVn`B~mKgpl#Xv$bFJ|pW_ zA0*gz-%0=gtr9Xm1Ew{1kI-6%it?A&DgdALa+*ZA=Wa1$`A45eIiE`SN!fH5Pa+X8 zB_fsBxJYpWf#(uYxWF!hZodKG5Zvxfe8-!9(BQuskj;hI0=WOuF0;|`<6^^gAXsvxu=1!AAg!I=Nk zR;Zrg?q@{CXPe1R*-aK=p8f8rXAy+8WJo)PQeVh47zb&*)=$seEN1f+^%uAYFe#DvqcE2-UgP5btrau-)G{aZQ5* z&Lh(2XoWtgDByVj*ChJ>vs7yvJd=O`+S`*g5yqMb7JMrB31<370M-uuNv?Z-bEW>- zftcLxYYl6PWw~UNB;7G?2RKGNQ4*-d0&)&s{<&_#%QiGWx~q`oVCv160)q zE(et^lpOCF*5Lp^QvuUXgyyfAe5AjBxfAcra-#ES>1l^RSEk`yk!EEWi0TxvDkl73 zMo)dI8#%pdQYmiD_T(%qEDI+*`szlTvGmo|Io_+?dw6uO?yiyh&evB!fdU+gxoci~ ztdG;Q{`BTd3jqTA%7rde9!qwve~CU3kJmLji|+M9QI zX!aSNTLrgLf-FOuZ{1&?w02+v*=vL|Z&+4mNx5h4rc?4y<-|X-;D-RyycWVX5~0O= z=h%97Iy{(B`;kWZuWt$jS!9JW2hTwrY<9u76Ci(oee_k*HTr}$Z9WRXP2~Pr-;dy% zPiaJ@PHKLHbrtf34NUx$6W=Q@STsr&TC!0Ka1xX|escNBlbT&oZzcoh0&X#!#9dku zY*5a?6W6L-U$Zo5a>uR#M;M4;aW-M93gu4rqyxLc5UAPB@j=H}zwjJW++{p5p(uuj zD!j&Ts$ymH=f1^-!Uj4d`O{6d?Pu8KPAS`WeBu^@8`+@WU)|es2o%2rsH-q$F4&d8(BHtha#id~RswQs0#Oj|o` z(lLoqAOD|}zbUhl@PQD}qF?vF3XfrljQpn@Mh$F7F}@Gup|RAv+FCSGMGz*o@!eiN z{gx9p;3}KJB-R9Ing%0H&-o*!<<-vj(ayvm#h|UA`n4V5ymc)51>meOV|5R5t}JtM zp=1Be^N0CCE}u`BJwp+UavB5;Aldz5aeqK^xn;{DzgQexI`SD=Kg)tKxER<-6iV{Z z%-=?>A(%P^f0x3NC!>pDBfu4ceJ&XfjgD57?X$ac&6(U4t{$>Rx(WVtk5Sw0f5`3YA76W$>~b-}Q2ABsl1_ zt6WD&q(b_@K4+G(jMWIYs#dcEj2+=*bP@AGJtc&6kFf2(E9^n^1r>JK)`AAo=sEW% zUy%Cno?6#n7sd;Bz(Fo-XWa)y_kab19F}4IP=`Or00cr}p^vQnR@RiF$=#cHselG; zhW=>?d4+t(SZ$*7!)#3^k|RrbY7b|FvfvxRCIj`jXT2+#yiRMsT+E|#9qk~Zgg-UR zb$ZiVijyCU`G7D%5?Uj!)X3>AM2)rRUADsDOA2Yfz6v>iL$j&V3cs91dUuNOw3kSa zZO$DYj6Gj3*dd(gS70nD67F8k94NSJp8&<6#_y$lpCfgh74m_CunMLI+>mItf&1Fx zcj2vCzZ+hb<8xG#gzqMPE~6=8m{&;V+khzQO{!C>>YXhVp(CxNf*y{VYG!lr+coAQ zh-3i1E1xJNb)ALot z%-xRQsQ$gy36}+9MN>{7_9OB|e;_gdI#4J1Oz7D3PR{wh-TDm1sAweu^;IGuF}gEACIi;2wfl`CJ+Ds z)O^WiYT-Y|DHs4`rY!!8nLYhOze4%|;A8;K=ZGazDC58np|8X6kkkb3H5zjv1k3r_ zf-8~e${z^)XDn<003_(2r+;`HAUgmX7y=Rpo6P0;pI*=pZG3M-)@MeR!jusa0LXsj zt|p`7rcNj_^!&gp2}xzOXto?ZSRcqyZnPn?u(oOQhcmXhkWXeYVWV^af?FN(m1r@^ z6}Tfv`4^gUUo*b=-!o1D0AMw-m;jJRj*P?b%BBw#U0tn5bx@)l22A>TvolEBxE@=p@9jlKt;wLfUX%>-3%)s9RdF4D5l20HGxOQ>@ zzQS|x+xta*;5WAbClvZVuKwEzeF}2qLRakdTb_Uu_yBO0THQT1aRS&?yGTDZS;Kt1S!}dHaU2K}tl-nY@@sj4 zSHt-mru)-;D0coykV14$9_Sh-6k7sGdVKr}oh^Ko=8s#x{&M#HL!a-7Z`{+O{cGX({une_EV;g?O z7Ev@P2SAbjp6PZTK+j)@@hy}WBHel8(T@%^JHQr$26nIn&KemZ6HH3vUnQW?f#GZ- zTsyAkcR@q51C~+e-suN_^Jm)x(?^n3afu{seLE>aj#iTMyz1c4gJaQy8n^!?(N-nw z*A`Heg#ZCRzBd*OZ2T+EX)fO5u^K}`qX0c7V9kLWhaKPtaWQ}S66XpM&nV;Pk?LVKJ zye};1{>1_m#dES7$qfMFVOnvo$lCRiX#a&8C}%n& zJOEshdDie3x8_3VDt&4n9uF)mG<3FGlgD#kO-TS zla@bKfZwBC#R*?qw7ZRRN~ZJ3rYxnD2*6Y2Esl9O_jNw@adb?=!$oHuhhf8}($i+C%(7NT+ETQDSH0GFa zCa-0TP(VvdlWYk9>L1Ms@M#2y&lDO?3?|+Kpe}w?!8_%DX+97s>&t9_leEl+LaKQc zcP$}fK6G5;1jGMJh5kp8g1i$1{HF`D4))jcE)W2+ z5qa@_Z2nHXt?U0839>5iZ(A_OhD;YA>MkIp{q=_%`QKgvVit~lK1wb2gCXsQ^%)AYdhV!Bx&0kI;MVEZFA!vKHQ8N#_3#lyd&dg9j8&qtIx)CY{h zhlLIh8$QnZ#9eB; z2TK^=8uTE_x0%Rq!ZxkyjmM(gmeWmSTOSjySiBOa+fXH;;(+J-Y(j+#q@?4BVhQPR zsjbp96K@EDooiP~d$)R{1$zMa_Xe5170*_18$ME6S{Z?iOQ~+9`QbD@JfQJ520rxR zU7o4z4r*Eq>j+vtq4*k^=MzK~X#@UDiBu zQREC4JplJe29C9_`*OJH-1hG3I?99{Z-j}%M1{&Zo_z1`P?CC)?8(OClzW6?xIo^U z@{Rk&K7R7LX#H{*9Qjd`V>TqAoJcvW24+0#OQjiP4Y4{W1rQr>WtSThFyJ8 z$1bQVoDH5PSqIH30(7nM=Ex8k;_pci(l3)~Lx00XM7pIBZ(NY5zv<{e0Pq37uuKQZ zm9ahfuYm%Pl|Dfe0)Rsdf_(z%`$cC~7{o)OT}H*+EFlPWVPFgIZAlX5L9I(VI-die zwMg_vd=;yPr!3so3qko9Z@~7R3HpTzRqFkTfA?D((v@Wu&!ia|DPbR;1KjYd)P5m9 zOs=LdC*X9ZbivgJx9n&5bSNp{6PoT%3O-b9F53=%8YdDg^Chw`1*$|>;@6!f*%BCmAg&CqSeJZUQ@A2)JSDGFE~{?+6GNx z#2tXQ=r}<6V6Q$I1vDmx{D^o(K zS9S9I;)|@XIo(=C<}&fRXIm{nv`gO;LEXJ>iNn#?`F@HOkjDYvCtSGAlRC$ zSH4E4j4U>k9d(bI&u3|s4e`=@%?*N_C0B@KIRtsS4aH*w3jp8v!p8Coo9KVA`8wAS zU*~-Ci?(1<@op*$#S=g%!t-HNKzuJ`!hmsQ(FEDGl>w)g2YKEJF|Q1b=jjc}arR)V z@e(UQ`K$8?ad{XavaqO#7X)|GWW6qYtNK+WwttRM%m1`Hlb~gE$yz?70}{EdC?8+1`S;m6-ecHD$}=Jt2i^zwhM_>>DRtEYK(6Gk-HGYV{Queq z0TF}a|JVlsDEJT%3@d=-81+E)c{6<15)g0^q*JsbR4WY|XxI9w%g0^+>ynULDFB53 z%phRlnUCLC^bmQej{gooZ$|nyCX0|6^TBZ{3YG5`CA$HWUmyd#hu>Ye9EdgK$ zkU4?>=tY=(RN%UJ!P4vH4t)}ec|ZWbx?UKTnhdBvf->jXOe@Ld`SWx@6CwbCc~4Su zFQAb(SHzTUHHa`B4Y8&J&ATq?oOT0dlnZJpL>d)g2NwS(#Fcy1v^dv|vgmBdnycUF z(*hh?PYhwk5byE054sruVd_^V2cZ7TaUL^?DFk!`D+57Ck(AIxrhNde2bWzb@K&B0 ziu1x5f__ETKr&@X_dpYPz?(m!B+HQ0E&!6lGXxA9;YxQv?7mi+^tH+hvHzU*f0y`w zJpl1<{?mdm5W)!QPp?%(@B8;95C{N3`S1k%@3Ek$km3I}Xz=Z^4~Q#LqM!gE+yHUV zDLf&%ONg{=u}tg*6nXFztDlZ4L5KioXpDXi6F+i^Ja`jAXfpt;XQiwVg5qjAfMEV> zqZ5PVeuMx2rUk+^&6pWLlnDSKgHV8M0_L=+Afw-avgXDE)_FqHFBNfT73<@rBuA5j zNoM&r8h62+0+BxJs4D{TlP0QWxB^kkZf+X?9IzG7pX)^{rfUobci|v(kSau*OhBHA z^u9Wd8R@7dp2D#f!Rd;YtPMCHY4Agdw~Ii31(>ceoLUQ$IJ%EGg$z%q|KvjuoH`J= z2uZfN>Ku|`qDq+Ej8OUj=t5E%vgznUZ6Kr9Ig7Y>fvjH<)>2>t{lXYieduQ@DX^S8 zq&T6enEs5*$qJfYK6y&JSwW{&2cIY{L2+XqcYa+gu$YGe$SLxGf{T$aO&W_=o!td+ z{Fw#0Kyfp6RA0>FM5S0KJ$LZbU0A$<{UK+*^Rd_POBMHLnTTI)3OB%Udw zG%65AB{+K0)&(d8gW)4iP=yz~sj372xm?0N!C~`x{{-uMm`}y-@@LLz%6E zqyqq`{n?ixdR%n<0Cd>sYBbFGz!HMF+Y#0$q)cb0;qhrmK$U~Mdp4uKoGoj51}UCj z=-cDHAb3Oyn=xN0yeZDJaNbW4t-<}u{`z0O4g8mHkN!V=dt3gCZxaG@du5uG0HjB8 z!(sZMlVeOg7s9S)U`>OjTQ$F8gl`EVz-k0Ad)GixKM|#rq=A`08u16!O4q(Xl7c5j z&L?^zry#jer!X5vePK(vvgR8M>R0ZC!@^v^iJ!GM-pwOOv>n`NG*6}G`NFev51)nd zZFyV5Ye65lgTRw>0C6DMgmOF?t7@-+JEfS9|93NPMGEZSVTDOpULY*Jm^Y~G5X#XYIQRhlQfYgB+Zi+WAMR>~wc-Wbp)gP&tQ9rSU z98%)5!xNopBG43y>4oZ(z8unv1RqDaTzqpqM*in&ofT_gAH)2IS*dG7$^oyr4m`20 zM@dh`xEs>?kM{MTb&p|YDD|!Qy$EAz8s!~niTp9q5OFp7hn>^Ritu|fd2uKpQWkuK zYA?`vox(efOQHInkkGg}%CI22d`Z!Rpi3mec#AYh92bQEKnKkcx^ont3^wj_UiB-n z;o$<-rR=)*fH9vSndavlD&7-HVx=4`|0vIJVM%7Ot8@m5MY)ZuRtawPdd%?jI;eJ{ z&G6$3J~=~_#VFMI_~v*#)=I*kIa>hkNxiHS*e9aCg*N03@{v)Ux4$i7l&jG3wRZq) z=u$17_y!LXG>Y%waW9}Mx)brH7p(okaLk!70N@}D04VGUXUc|G|A$on!>R%P007cz zxVXmetOv#q%elw^1Y}?SJ#&>M*lE{e%kWQn8p`F$aPS8({YCR{f<0)c0<)9a63mlw zsY)3B*3Jh{;V@Tq;NT;r;y&~*qm8hYZ#Fi*)O_63eSplnMYK%34L9ANUFdcg9)Y3u z1Y>EL zObTh2v>=2@j!eghc4L_9wKw*lIH^(crt!pR(sy=&pUX_jy62gHi}m&M1=D}^DKk&v!23{_ELQGM#7C3UJ-?v6?nt1zh^NSn;t3| zo<&5ewC#Ax8VyI3?J5{<+Nfe*yr+dgF~4t*idBIi#n$MR3M<|5h=JExCB#l9sF0_A zz<$2_7Pd@7W6*A=DcS4o=F8g1)1nvg+@aDMIh-dZZQB6`R38>GWM)&sWHxGIL`=wA z1B;ru=>>YdrCm!DtL`vRW9PIxqTGW<-X_}6E-B)&57a_GnB-a~6o33URHDi+=g#h? zpOo8Bzku#f5eW}rSQ9X~LhJ&Y82*mi14$*MN}UwyWz*~IpjXUjx-@(AtCTJm_IIIZ zd(>P1@7V+HMgg&!=%WYTvR~)7SfK>F5>wu7S3+>Zz@%lDIwueH&b$aRCyo-CQ3GOW zGBkS9E*DV)re`+VfSQsiS0hv_>KECs;%Hp0X}RLtWC9_CV^DpQNuqb7t)c})sV61_ zXpn?ZgUT5pPp0kwnjr`B>dBz`#soPUB_?Z?JJnbcSSqFE{TL!;pUyvw>e}W;o%=TV z&^_|OiQie|q3-T{*PH1}#-D}7v^j@^KrEv4&*E@HXD8Gi6VgcT@;lC}HIbehqQfR` zgGhXkze(h@2a~*$feA{GiENcv8)`4rX$9kpO7hBd|Jb8tKk zch}fbpEd}0#gp>%n4FBV^o%0dOhR&JQbfqW4Uz-E{qiuVU&iA*Yvu`*W&?yq& zI>`3;;$%PB{}_9p{;~UY{W~S4lCLV%GYSJNugq4o2c=wL(~Eu3%u}3LF7G~75$|=M z>vubjtwZhY%LJO~23-FW$Pp_4jDD+#cX;}DzO4{4T2wr@A34<~$jE>C2c9YES!*); zgWEv`leW?CpEHXR-_x9MhYI6H1C-aSRztwbZ|`2KUs;1&^g`!EA9d`lX2$)7youjp zS4`;A5Y2>tr;2W>>IZtyKQX2#p>7)KIdU0kJZ55K2T6ZxTwKS*J1RY<)G+s}3S=NC zn9p)BL~bF$(RzWDM-f+*k3FM!o2i4!6byo zrBzZmf{}X>Da6_xtS9M!XIqpJsCt}O_yiBe@aq{$--bY6lY@qG8$#Rx>|vadCiTS4 zYSBz?$si}1=4$mDtC!EjdZXH!yP{x|%wWRO;jmRhjY*QW4wXP&1mMrg;TKX}&$=*VM?1nSaE?mwIl~fDo5>}t z%1~Fmj*nn#o-WU6yoDA~Xms8graZnqEmCROj#3UpYyzZTJ&IBEXB)aoUg}NA1^2In z-tr|R9)Dh?jYDrv9l}Ar3s@y6q{2Qy2N>>rV$+2^^u!BZ@|gl+cd%&YbIvJ zbID&k9pW);-3~!lCWt}OZU!5%@d!KW@{{!5m}}+`B!dneo`GZ|*pR1!UI#>OLL$14 zbq>9u$|B6Zq#!9>I(F02=B_VSytmQKtn435@HR97e7)}DdCrT?iv%P;XNq9!h~k={ z!@ZWSp)q>)cSc1>-XpSySvjgC2fY#Y$a998keGjqjh0%Uh1psC)%tnE-w84ryW-c? zh}Ld#@>GA8+D#2<+pFR{sennl6pfRBiqHOTu?R^W z=K=*j09hjyDlGU^r)_)E%%3>?az%_SbefT2BP$!&O6%%vm1%2ZE4X^w%D`BSKAN?` zAP>ZQWv-}H*kSHeovbDj>I1#=WM00GNit1ER5cc=G6G!ynbu_9)6Z-umOfAo7{$qj zgWiR4d>oOv(!}`uG&BUJ4S55rp?yp6+E_n|9b(gAs+*QI#`mqRuqWmN$l~LhjZPWZCrd6jafxbx*eq|IOhy|1JKdXxS16Q4~ zcgdbcCMQ|qc|Y$$^i2vwj8cWa9W4X&2}^fQ0Nj=csx=3o&#vaoVP@hpK<-a26R&DW;^&H<rl1)$}N0+8*bYZ*rJvY4_0M zm0l{M6ycv9ab}{L$xg59hIvjz_hOccuuNMaF9VOE#aecOId_Ca&s_-6FznYvJt_|I zOb<+4v%|6zsTKi(KYX~B%Q&Fy`i1LL zgoP09BaN*=IqKk_-_R)r-n%|`Rdp|7pLDJ=_m)RL#WLqDYTzv25HjRAb%Ch^skPmb zJ|IhFoE8nF6Zq##D{LC=%{RfE%ifHKS;_J|{+4Q65N}&4A)F6|tQ)e^;>TsGXy}3O z1+mn?WxB_7UH?!SGOj{Ng$7^bH))Cs+h(aO`M2MQbp@{vzdc$bY?a{g=|$IbRj6;x z+_T#Jgi9o7fK_}4$8$4|A=@#W9hV&Z z0HT}XBF(|c<*^9tdzZzAHV^M6uUqBwYxGq;r|gvNK2pAM7;&o zm$}@|spQuMHZpx(>lhVF9~1on8~y7X=CD0~2744Rve-gm&~ossgtwzQHDYLu$uPWT zx6cB^;8_Uy9$88;JDNf@r!E!oKPIQOQFzJY*ztl3#i-5No4UwNMxNo^+G+>XV5QOu zjIqy%f9DYJ8$p~uZRH~FR+Y&El3Qhu9NWR3I#ueUHW&jM?{_e`z2pj6@)?PxT(6eF zfOZ{{$Z>Oyao?#AUhy9UHV!%R#6nZrl{M}m)8Hq!!D;u{MgAlL>u~4#rr5O$;!gxeKN^sToCTSyh&L^hZEAy_^h$wim?4drG z8=VPhB5xzYTaS@BRZFcs$b@^*;N&(_I{ZJTYg;FwdFfan9&}ho*SPgy zm$;0Y+4{z>!gTlcqy)SF7S{<)a!wyqmWVe>7j3y~uJ>tNI0=rcxd1 z|9u7ZA8rIuVVs7B>-@QU@ZGn0DjIn5tR*@;*@>(S{!$8@>4%5KGJOcA%kd&M3tX%& z;Y}G*^f8AMw(WG6b}u*qw44MIt<`I4i*B$+v1kUfOw?VWX;7YQM|N1Gj|C`IVsW#L zrsaC&(XnvG{~b)}knH4|=oPRse+AU`P~l)oiFJE~*0|^ogfSeY)MUyTZq`X8xoC?0i4G%mIWBbi{y6qL}*??c0 ziUZ8q^-=Zi5;LvYvY>zAxSnK?Ia9w|FXjiy=QE3{?SnmoXi;QkR~g(S@wDNp{+Ulf zLr?9(K+#@&=+3b?59*2ceiYLQhkf-$$2^^3%v*lZ zH8Y}uq3cYUXTXGFg@>c0&@IAi$-nGo)oo|bC0ePfn@80I%><_Dw)_UJM zLh7ryroGUegE)`K4>c2~|o&*mz-bldLcy{(N4bl<^W{ zL1#HoNM0N3Ft}T99g{#ahPwK;@(p%q?=Vs94@Shk8Rnoe8ynd3cCOVw$LXZWpHsXp0mda4! z*Y;UW5gK$6Ag2s}H%u^7NXQlP_QF|$24C}K{2A;f$_%Sx$SN*Cc(?RxuT(wx-j)|o zgI9EFTQVZ%7%Zf}r+6N>$P|%!YFAITo)wb*1g12ld;-dsemz}fKa9rC{2|!I`a4~VSd36ZzYMWX&V@BWIvO#-CkHnf=N$EN6Y3OaI zexYY$-K%qFj9v1)nX{f+7VV}f-Ck0jc*mlb@Oj6%h zjB5`G`IrVcudsw5IMy9QmN{SiB;EsbwmX=kk198^%$%93g?j;M?fNqS=%q9UW{@j{ zEI|vpH*AK`)xM0E+LR-FkFxnYZQS#K?UFooZhp zoR1Nv*B#}3^(rSn+OZZ!aZLb6Z<-mRivTxOk6FHWcosZ@(M*l{$==~9;W;|pw~6yJ z9p47^fk7Of*aeKM)3l}Qd7iRPu4j&Fsl@c*CiTWE%@R<~?Z|i)?RZVEWaJ4Fh&f*S z6>>&Zmi)XUmgllAjPoKsoOe7u@OpYRFck_s)w~h=VKh_I){R0%lgiaerC;02w0_E0 zL)6>H8^PvkY1gX@E6%6j^K|P>BmHj|Au{9 z({j4*FI{5H#CH^L?NZ}yrVbS774h;n25}hemJF35C-`=v)@trZhC?)Z1%Ap1W3v?I zbT-nLxD>34&?M1!k6Ok_Di?xhlLvcRi8cbJDW+1qdX(s~&H`;bI`nFc!z? zJnYCACZ=xsZ@NENO!~LIzx8NljPr;8?h**=XYlT-!o`5|YM%Wu6w6L6<$9a6lgijl z+s&Q}f*2rac?i!@t}(^20RP~cE}V59gS~$K`^}eIn%FfnN3u|QOaoEHS-PjUAu1EB z{&z@_XqCHk74??YUqu+`CxO#M9^3(x&rt$rIJ+M>!EaN(w8^o0D2y93%>Ke+$KF2< ze?{~jDfdzjL+1%8E`96L>v6^>kgvXhPcyM~$owT|B-0G8nsUX6ZY*i1l{{R zTbQ9);j@A3J!nMby;sYM{y-NAK2|0@G76Uf&-fEyxm8wSXOdJzo9}N)TJ)WcLX;8s z69C%<9NLAp|G^6_l6m^F-@i4RXjL_xfNqYnR02*SAkyoUI{v-l>X_LtLSE|!6z%um z1PZFyQY$qr8&NHUOOW+VDfl)O?tWSF9Qey8B%{mGcB4V!8Qow3(tFNYL|SGc&p(NH zY^<=+84=rnMc(uRT4$GuT|S01)R3@#V)i!W%0xxfv(1AMVfuS^QgrAngx=UftHcoC z!YC)p_b!vCHj~bZa`gCo0kqIOLZ65TPzXLc(9;F`2h~RTX!~FW>d0J?JWxH|)t6#? z@QHc}**(3_owSbYbH`hatF4N3JTJjVTYIsf_U#=-UzZk6GW9MZ^AKr-MpK5z9@}oE&}dfW3H>Qi(h*oSn9e~e9rkCY-UN^a zui{j-0eh=Xg|2#3uMm&1q16t8Z7-LXDTUaqn@?_73kUuZ-3ZD7Nn+$HFkxsL^TP#kRbG}2Jym`3AFob%MrNbM7ctO^W zKh)>0cOHcv9vVoK1-*-i|~6tOkeI+&!06e`-v6_E;e@ z=4WQ>Qc2wKlu;4RQa2Q4vyamAaOSv(2d;FDg%83ag|&CA3r3I~y;a4S(CvWtSqWa> z-(*)yQ+Qvzzt2g|RAb`G{u*R1+r~amqImXs26Nwp$Sk*Wrk>@^`rM;$u=FpqIBee} zHALYkwvlAfr=eOVx8gc=No8$UU8-_<)WX&+MZOdJ?~_Lx&O^h`b7T2k;ZuYk79?M zH%Bh5_6Rxlj~N?+r^T5yUQhJL{aU25k5{$@9wB~2aqy$mEs2Nnix@bgb^C?`&sOJ& zH6lwPIr=q6kg1bZNms1E&wBoEKl12@)n-l`Dy8+U*^_5Nq?2z0NggECFLWC#<%ojo zfTu3Gv;^w$7p_>~;5=&h-!-9-3hfBJ z#++eUR=(AbYw(VI1$VB~jTG8%Wjb=8dj5WWX{6^96*B>Q_Bd=?m*d3T4AiHN8=Pfr zlTVr|=*~ARU?2V6Tp{Q$A?H|j1B8L+zIl|hoMxHSKj}=+z?>;20*>JMmC;d#QqkF6 zc2TT?95KYNZP5@Gf!?W|@XG^nJW)of*YApY4W_le;}}%D!66R8tDQH$P;kK|=@`=Jzi5dnkFS&x;+RqKX_Jj`Nj`NM0F81lBM6!$i03GXw~5E3w*4iydZX z_s_}(P=2Bq5?d5umK)vA&P7?>T?@(UUnGj#q-xVvubsI=krzst7u? zL$nw1ittgqDZxXR4MHoW#`r{#4yYn}`|&477b)id+}uZ4O?s`PSCeRfa{Bi=`cqNf zH@y#mCx2jOc+jg^jUh2juyb1?qK7b4F&X=*?LdZ|qacqAvUnqHZAD~K4u$hQjPj<) zA5jEjnzr#x*4@LlzF%z3YX} zf0P$f(w&jSL%mp??4Sxg90G(lez%G@is^o}Wv#wL#};_*{s7aQh7seWYqs zuB&>MF`hfEaPTx7SD#_s)4 zLT;uSOZ4x^741kb0Sy6%{=HPExEUpZ($>o3tw6eH=5vMw-@Gz;7&D_PWa;jb(rqd0 zTCh8qpGaYocQ_a29oO?RuuhsF@ceIc_<#arc2tqs-%sBwz^dC z38=SoS#o+?ksj;2QuT6>Rp6L1V9&u-Qb@{_-n)7}-MF2{xK~H0?R2gN`pO5E zvgl4N72*C>cki%CCUf?yhq~odQrTxNHP=5P#G!T&j8eRr93c2v{V^j4$407;QEop? zLV{(@{_N+BePHE`p$CNH$Q1P80jx&T z46d!+7WS3wU#m9WH?tt1wGhM#vtoU|*D1{CYu>t;w)V>E)arxtOM%o3^%43Nn=bYCj#{bQWBFfu?S;uwoVMGYX?p;yx z6>^l>B8<*VdKlXL{GG0NZ2{GUI^##}k|&7z7B0mM_i#ULw(Tzm>r65c9ZDeTPHIqR zmIU5J&yEIe)$#lxaW< zqu(<+_3jn9AqGo=F3?*1$UVsqz5Dj9Sq#Ev8+j-)Yt$^?O?RXjI0S-g08)2%xT-S3 zfi!)4j0`?hy@=jf1`SY{=Y-nKDCkxNN)jE|wcGj3ah8Ar-S$T++IhTg?wKYf zVhyUuK}LoA9-dMo*U9B4Ax@xjB=^h^UCl?zrgb)zgbo$o81)?riPQ5_L(|Hyw%*O4 z$oy}i-vaO`&pZYuygg}aD@M?q6?SwoF@7&qYGLGY$HQhflP9_Vig1g_z$HV@55ke; z9EW*d54Cj;YkEN{P|nIVs>Gq~N{cI+qNG7m$S`Hu3b_~}YK z1hrXW(fxFhss?Jz>&G~@yH6jnwY39y}1lWghO0E-@%2b+}_5Kd2m$IR|yil%ikBJ+wA3vW(9`iR-=d* z;p##Y>nB5!h?p6S>}S$tB=Z|RM6c{9q9V~uAxMaA@|kYPNHZkSF2k%jYMJR?k^Op%%SiID|zNP$S*~-tZ*lOq-rN^WDLN+MSlV@ z448^e6n%mB)%^8>SI$X(A3e8gE(c3wiOYE*+)KAqbybxL!pg!p$gu*eAP@Fz9 z4{8X@y20e8YkpfbY{~yG09-($zZ<)%V&(@d(;C~1`AbrFLVdtdJzsy7Fw&D`IVH9K zLD9&OR@vL<2U2ccI~6}D!QmA}FJy%6t=iG+a#$!S0t+cjUJdUjezY1A;G%aFz?T1y z(h>^#n+!m*CTUeEHR+bfBacz`LNU+dxNR1eSDZs2y94Blp8fteN5SJj;*(PYg)$Q} zMJ^v#`;KIp!;{&Qa+K|hv%FQ)YS|SkV=ftl{Cm>b+&@r-n2bb?EmIgE4a|i&q+?On z>O)g{O-^5Pmn%~3#lRna*I{a|{u*AW$5R*{VNnI6$0D5kh5cMTxcc_bw;@O2G9xN&60u^W&BTj5_+a*!;tcx!O&x8(@1|2gDDFuNyZRL(f8rP!|o z{{Z_HjaQI$yy8Nrjf}T~t5n=0hXPp<_x^Eo`myH?U7BUW?|b2VL?&*UY0{7K=uv`1 zz4)Z#eLt=|oX@xIz!DUi!03MF#RaqwCZq%TA05T%+k_zphpS!la1L!Ru{tZ24xxm&PM-VCssaWl8t&UcT<(D1%7?7mc&|7T7Up6#T z3nvb{8 z%$-+agmYt{WLQt0B~ zS*P$M|Mb+{P<4YSBuw(nEs^6r&x1DniN5;^Z~$m#>X}WP@Oi+;>%VI0%ik9H3tJ0J z8-$)h%AS8$X|9jxY0M1vL)vaB!W%wE3^Au2WX#LsQ^o#7CH{3T;NV!H=J~hxqCCmp z@{|yG+T%@m4C6{XKTo?gu1cOKX`xe92NQa+hIrHD@J&}Rqdme)ZE(7}R+}jPadS$S zV;-vSzSbK_Zm2xLR%;W6dmaSL`X(hA4FYPU`6( zqy;rO@TL#q>x>et;!WNEHrV3I#~Z|*y;!TtiVn( zQAi}9<(g4I(;qh=v(lf$aWQAP(V5VfB))*zH@9JYGM5}o$3En23sxDk$X+(t2#A3r zBfD1+6~Yt!{qTF4Tqhf+Q+%=qT9Q9VLvfFn(>N!_X<9iqgN3m3|NOoGCD)XIyD6+%UczB%F?}CB!Xw>{^TMiv4Yrv);?=yD-Jo zgfN>xR))QFuD`I>RIVzzwp0*^%Zu_eZFIG&n+P}GpzX`BcGjT@ro0wT;78Aa6D2p0 zpWZe~%`lu&blnZk9Gh2@U_RM5)Y!P{VB8ZmL8dksNCgu zax1cQ>|o%Y*7%7zZZ3u!e_(?mla`1`#lDkZRAnwPt!Y2u(?d)un zEk9P%)@GPW&CV}(9NWD6s^susb<#>V{uJ9Omn^`)sG;9)Gh~Q)Q2E(nw!jYq|J+op z;|9UOe6($o^>RsHIaqr!`GA;KFw+bv?2Z5Ch^qVf%Db_^g~Y9NZq2T#9ke^^=x|4x zDRF0dw9JLXQLIuo18tClPc-Rbs+%`jPVn<`L~N8bRCJNLl2Uh-bH>YMJDkN7lEw)# zobn?@e|TC)^cwIp`w~4PFHz)+^uI5}O7!w(R{n<0Jl4%ty%6Ki@;4~gWhAeQ)%7Z`b~X3pKT3$T&V-7J#7d_AFkspZ1NH-TmUjD za0|p3LjnWm(PmGTYy6m_cTE#zr!%ZB07DJOvB)2<`IHXj&GqBtj@}bgNQe>Tpxk~p z6lZAH^yRV2#zDFT3LOLV5-`&H+Da|Rx`oYuY~yG`t3kyNbFQe#U@i2KuC2NIEEN%2 zJ+2>{BrI!hE`E!@I%09#X07d+#!Km>FWSwC^%NzG7o1D{_c$n+AQikO9#qB;X zv*-X>1kwk>Jwlt-vT$w}Vw?RHà# zM@HK#^lMEXRSCkHy3>`{aE53}yx85Y^xprnb)YiKZjRc*dlkn0C?3t^rskQU8&oKl z%vq^)0t03v$v%1Hyjra~!~6%r3xT?JA~7~->_6Yo1&okfx*{wD;az2~Ep^TZF!aBi z>o=&yeiD?B#lqjXvobo8v`D<7igy4Rf znKy1aql2%`-|rgnMpRE9c$o*EaN^AX!KW*B1;F@k&E2dQkLraD z8E5k#S}}5x;JsriC>&ii-A#;g_4CxNBDG+}8H79vYC?LYd^RPLm?vqY+;|JHlw$m( z-L&4?DKi^e$3BJwOif%&323>7oDoz$Q~KU0Ix#J+Ipw4ubToj8j{jxM$TrDG3R*#R zT60ZV7_o?2mU%hiGrDu5XhFu=Jp47 z2RLja)9*u`?qiz4@G+eA#XY%()0CBB;_NDT-(#cKLqdijG6V84DxLU63kw1a7ZSRn z32K(=c4s?qbHQ>#?d*$;v#zjVIc%DGM;@p%h_cex>8bY1Tx1q;N&z&JT+)fn(BglW zfFD5&!L|s~F)S)vhGdc>I+7&U(mN_&-g06doJwwLY{nZb))Qhu>VXN;ia*^QgPRn5 zDe(wv+5In#>URZc*}k9WpEqF}UE$~#`5En?%UKLX=PgIuTX!>K)wzx^T%}>AWECes zx5ZmsS+wlf9iaP|Zs21*jxG@CPOE=2@!lkpWmp$1%UsF06Tt%UY(^(z+-oBxFtSlW zisXel?`FA(I~v-<;GGGDdLG`*OfGrm5L=%BE%+mt0kKBkPoC#|9EPj44WeZuSxBmK z!hNx_VnLRfLOD?7p zew3;_o=7cfkb5!tYx<^7nX#Ww_hzOk>z;dQg#pqJf^Ufpb$fWGxpm6RR?jYi5@bA2 z;#N=amzCK{ycTgNaV&dQnlDQ4KW)#az8HqHRxsZ*@sj_vAw13mZaC(33C0ee&u>ka(Vrq&1-2PY4>1zkxQQKcu*3x%<{5xuYV z^QAGoghIY59J9>Mt?nwLUXb2iw7NdEklABx3hm*CtzMr8tjz%N4vhEKGH1SoXC8BN z!;-AfE-&NrXBer{bc=Iks){L+KAv3%kcH>0mofGPIfCXR<{?lj%G${tGj`@-DXL!z zAH36{FZ^*{mKq&jsAyhG1tAs-PR5Uq?V`+X%w$_EMN+>EXD$G-DGs%SC~%Lgj4j)d z)|1p;WbKz`U|P&)3J6o!4UcMF(k#E%_!r6GR;H9!NxlTRcz}Z}8y?4KEdwI`GnphF zqi*+Zw|QE?l>OvaG=L+lg6m4dhyLyL?!Zj6f5-RP9@Tf#mAz`gp}Yg7?W4tX7R|6@ z=|Lyu!cl2>>zlK>gzrgD9ZH9w1W^R_5?!9HcVXI&8KAaSy5rfJzI0z3wvljs;sHPA^~5E znGJc*xk@m30ax^0sHz7BN^`g1uxXyoVD&7sdKmC$Utmw?GPW*@INy_}$hu?@69j5J z@}?xn;v$leq?H?IQLW2)hq}#jd1(0L#x>O&)MO$5Z0!=@Ux)Y*58L$fbVkN;WzA93 z8<|Qh4T9M-LZKrPqkTC=&R!!5IJ5cOAWhOKLUFOns9O0i{IS`ydy${1zZ>`iI$4uA zk->mxNW6y9S@KDFB80zwW2MEr_n9*d1@gzWawskelC^bTEkh=Gt-6c{QZDehOG~nq zb`(>Lss%)ep=r9{Ci^O~imPC<=m_`auGt|(aHD*G=bUIKCB*PqPquTgjJL}89BU~x z}KYzb-!V+8U@KPmN{Ruc-SR%=@jO*Qu+=U z4^==SDcUge?O8-t6&-pW@&iu*)ui*zHp+a&qg@~|rG|-c@zTipXzh!Pc*U;uySDmO z0VwH?C($H*BzEAoE1_%T9P-2e8R;p<4P@9ggpWos%@Lq>6U{s8%Eq}#pti_i3eLAT zF|O*wtt`8)(!&M=OQC@e?l$dUj$&pt*+>Ctep*(JqyXlA>QQ@|oYr`Zbt?)@;> zv)_As_E;Y;^HW&qO+U!S$)V7Cvec;lDftJ%{Y~3-&%aHAnZ%i{r#{gXtQOycKRCj1 z8P4C#AthTAjS0=K0AO56Y4-0rnRIe%pdLr8p|$+~x}1Ub8N3wUxZ#S#s2dZlGHG%e z3a31qf0cnvx3d(du_<3sz1ey&R}S|WATl#6spbtcUF1sm(84(GjGg>{^>lO7CxkIK zG+-3Jk=Ihv2$tjfi9(2#yk4<^Nx*iV^XXBKALu>EZciqGT&1kF)!s_R8 zHtJ#zhX-t}x8zn{uMt|1aAw)1lW-fY{s|_31-q#X6Y1=J{$NTMKl%Pm3) zd!ouz2OpT%)D7dA-_-!-LV`saN3n_?YTF1l>BmK6ctR=PM4>()3@GkIwI&hU^D7BJ z6Lns|2d{AV6Nlx@VkLJMT@BEWT4a)C#G{+S{cU|J^`Lnt4gY^)@>ddfGPV*JO=8_$ zO>4>b}7dWo;tE(gfW`HjKCt7j=+ffB~ByD=_Z^**c=#%GGw^p!FLAg<5Vn* zNdxe5L#*$c&;OKhJIDG^%r;()EQ101Q4%O{2ACs5wPR|b+il71bsbq(o{9{*S$Yxu4DNmGmNr#wE%(?B90CJMUy@6OXGB2`35 zh@t(2Ox>;#r`Al-u~A|O9y6K3o~sqmu`gw2+^fO-lI?KJ9pmajXM$k`+md1I_QRSkp2{ zR51)(&Zf=4{^FKF+xL>2+n3kQ7K}nXZltI{*dxvb@5SD8u2t=C*p>?#NO!S~Cb;u~ z*-p9^zFvhlw@Ug3c#qUvVpJ`?gkUPuq?PUuBHRirQ$LdAX$~;TlG!F!SHE4gvbsA@ z>l+p0h~8>Pu}6OR6kf2lkg$gX;<1uo6zm;+=Qi~gJf85Y?T!m=7ORs{k-oWV>qCRQ z#+uc`I*;;kn|v&#O@udvJd^*P?QG%;M={&;-kdKslA***igM-Da=sjnN^X*rHqn=# zdUnwVxTE3crrj|RJTclIyDFn9%QP%@{vWV2O5YV$Slzj@az@H(Ph`DKwLEgR$*^4D z$~GNw>U z$m<=dLwN{A=S6I2W`zyHp!r)Q;G%P`hHK}dH(;#HoG@Zf>6JVvMiw(D80-352xDlZ z|NEUaS=|}xMCXzt3`!K!ZU!pKxvysanu*r0G?_tHa5=4vSWl|U&iSS%5Ko-dLH_j_ z;yl{{H&|F*%2BR)i)h3tDI;D3nd=s12g)!Jq6UNHY{@8D)b?3R8wY(!MzB^kqDu z=WM{d_5Dur{I)gC4^jm)@{)HBTa{NGMcHUnq+6U?bUUh6rts{qR_vGGuaN6?&yK`k zoYP4SJVz_PBkIP4_baZ&(4`pB)KK57ZG$90Vs!JPS3^@$WPGnJn+nprxJ4bb_~v~d z0XW}e%078K1SZ(}`Uf_hN#vKws%7522H1oM&nl#YArjg&+PCpy6O{hkl;&s6>L0M7 zJ-@{i%W64_W}ulQ<*@hWON0{eij)j6yW0$9H*%wWxJw&w%DLDYP7ahxP@DY-R33an+nf^8WtF*|`oA=dJg`qTfbO2m* zS}U&Cv^z@)rcW?(`kfMGJk%;l{%vtkE!*#nXz%G2*X~_uugi$Us!uG>Jg1j)%yi~g zBvsN>DGwbjOu~+6iMK@|+z&KMl1T}aivsJ8GRV%M%!@(Xp`tH_#F9tKo=gnjOw{6U z<#t4Xo5cQP4_56>@|>38r}LFa-??+M{X)Z>$R+X&mD^qB%hcFD$~A#RH;V!Wh}12H zo6_Yh^9vL2F4QVv0i3b{aO%KtCwI#F0!Mg@|F_!gWBt4hM68Rz4)|u6lCJnqKf7{v z+~7f1ctumO1-L7lWkrkjil64zgMp{gmI94{ z9o)|i_lS$B8r-Vj3h@}L&&p3(J_(H8Gt})G<|dp_b;2V19YkH}?MP;)6?J>>2)4w^ zAII5fv(A#I=;vVKMk&wkzK1m;1N!cr^REn^zF9yk0;VWh)!o&20nc9i0XLdaqeBdf zV9(2=(LKl*Ashevi5itbZ`sK@Z&{TfTkBN7kL81@=O=-bsquC2zXpkDHM!57g7z{BG}>je2r&kUE1uiBvMn#t!tKdWhQpss zqx=+fS>IUzt)bz8PP6L+BmDpI9qpW>x=(6)`W^NXeq*(h0P6%PlT-wlJNOvqueJxU zK0*<(i6ZjCl|pIh1D4;FYbbh*)%cSR{Ftj0OBWQYCal4Sq-dpf7+%n?B4q$zdueGf z7F)Kh_J`NfRt24(I=<_C00d+t+|x1NF)iQR69R4rT8efMLN9X+Ws{w1tHaaUUPEyK zJ}$+^0+Hc*0&0d>Kfn@moV7S|&&&2C=#EjbMvJUi-)Fz~G`6;!1}}5;Gyj+BngT6U z3u~Sj2*KiPt>xaYKrUhZUdueKRB-o5{=gw*=wsviF6prS0sG4=ysO^x{%8t8_bFrd zVM#j@#;-R<8{YxqdZ#r10NNwlDE~BRePfzo`kMWD`Nexeaf$%sJhg%N-k7`B#4jKa zN~wB2BtRyn4K!K*peE>qbL!WU0&Dg?`u86v!(IIxU8ebt*ZFLkvzmum_%ly!%X<40 zu0l_+&OV*U)VI2^Q-v`dqCeTXHg~5}EuB>B0FAra(Vmm#%HPcB1k$#uHf_?QX{*qM z+JeAo(nm~oDi5q@@d-C}xK7~bX43p_Bp*}HCp{=t1d#!Nm$agQ1yX4)A0#&`VY$;R zp8<75$R%Pj6ycZgKM3z+h9_oh|2sB>{!e>qIHTYT#HfZ|aaB6MHG>UVNes9H>FcIW zyBCF-`I!GFs1oag+-WyNY@P2T#Y5e0y`&VHi-l#rij`!u+`cbt6dhZB5H!KXQ+7vz z2$kVw8=RYds#8MHer)KZFxphBtOFt#T6vz32pen07iH!u0=bB$^V%^teAMd^O{GLcVbh+bGU);o6s0#NMP2xK1b$kIY}ar-RI!nq&U%~# zPj_)+O6;4TK&orSw6boITgm8zYApboz9l}J?1c^z=bb}df4IBqB2xgkrS7U9x|b9< zOUP8P?>u)u?b1}tzjAJna$k8P61!4*tBu!~Ia@v&Na94>(oaM>%$n`tl6el+R^luv z!hgK`(MJ>!R-DZ7HEpE>mDCxN)_d5}YJ7HVrRpt(4jllnKhJ;_tEIehe=DG_RrdlI zqa*k0Wnr-HA}K(08X~}GkAD#7?EGK}-_g7RgcWDU=*7Anqw8KYUWM$qAlhCv{Ns{5 zS92|Qhj(QD%A0fYi_6UOhF!7~3<~8IoF6ek@bSTzY|Gs!MOt-{dctU*maX0!=&^*}ID_1I<>D%1T-?r&x8|K-Jn z)sJKH@`$=7@Hogpkt_FKOg37I`SPMn?5v$rukEMIjH?QEFBAXIJTz3fqHNF+gYI@Z z(?aTI-SRA!+ctYG4=jM1cP>fA>cJm|e;KL4J7NF~*UsT5_Q8s7bS?hp<2SI!;{;ZT zwEd2|=?X?eP0PG?W+83!Uob9+Eo&tO#ee=V$6U=l{WrNcde@OQimM&f__v7BXpDD+ zUrS!*WBTsLxah}C5%y|Jv4XE%Ug=%Be+Dq{9&t8HG*LH}lE{al>A=xbUl3j7QVhYF z4ZXR9cpE;S!Y30#$bVMp>)B#~PrMy&Mymz_-NK3W_Y^iK$|5Rwe`c!|<-=Dx4VU+x z+2#R|uNDYT*5-H3VISOS^(c@_Uu>bolk?i?)H@+7JMIxg|5?WL zF;--w^ocEEuIfC)_SEjWNc0f-AvAvln)#%PC6koN+RNqD^v-2atloGv`-73Lv@jP7`*mvN=Xbl!bx+~AP zkP|2@!m5Vog&`kdzTHW^(&)XOdUL3gc`nbo3t48w0R{5ZgGGGVPV(};8#VnvnD@#J zi02#;b2~|F)fabYm2fr@?C%kC;?ke`n4pXB_yhD;Ag+uv^hM*%G$ofC| z_&01c850Wq3_eKv0(1+{$OrB8dJXna;sl)`+DI5;@zLw*t?gj0Zwt3P%zeyqe7j~s z4&-ykd0w<@9PXf$!JMo`guzOaf0+-X$lq~>FzL6ZMdB~)cDx(APR}3iYX-olb!pWM zYD^|$xp|jN-cgIhj0Hp|tvy0mdjhI073~DC0{T^rqzmdxUcj8{Q-}+U^IgXHSY`(EFoR*MeQ4hCtx_)yu5r`EZ&7Wjul^MJG151gl2HL(YF1-_2U) z15$#N#fx?j$pu~~y z?;AaS%*H-b zqdEUfhwa(1br@(64yK6Otp#AZy z4x?{u_s~-LTgquaiDNhuz`))Wx&9>0!i6`gLW&71;7>RMxKZFD`di^8&Qo1go9^ib zdB$vP!$eu+eRG8%fsbbwfB(<2ht4XDDe4#n5v^M-8{ME^wx@-e+>ps9@i?m0A&Z~W zu#{IBcG}petls_llvE0IGU#ujQ-nbxsNm!mgIY9LPr0)AagS81jgePV~vTwllL>o`EvAg=G~p zw>k46^+KT&3?bG{Wq`R5TP)-bu&Z-ivns$Bo&_iSYr(=dIklVCxHYOdP(`*~90`=XQdkR;ki!iCiAog!^_?cW-sllJ9by&r9)ij5C7wE;i=qDwWN=$GN?;c)~tY# z4MUkp`>y;INHU(iUCJOQayWoQ=1}gIb2n%+^)Qgl7@)wUY+GwK5u&5swM+2OXn0-e z|8^CeazELI@+}b+Xl?%>6l;hs2i&dZMnuCn6_`^U!V;`;1{!k0OUrjqnPVCG#X zbj9O?&|kCI3!+Oa0-R!=I#?)DG55x^ii6NTXp&!=&jifb3SdbO4-4Cb1GBXwuqa#T zic>{UKbfd=gDniN(5QxCvmE2Nf~Z05I*9W}q<664-dw9`u(!W~Lyx`{k*H;E{c`~M zj2EKlq~*1MXaMqXayw6#JcbL>~-?>SQ-BXC#YF3+fhpZ4y<|y&BiBB2G>nV3egA16B|}} zlkrgg4O=^Ho!f61YpRHyQEFz&G^eJDPSE6#g)I2%Wj>MP{g`p|{O`Y{H^gPguq198D4J&3fnV58*G(V5ttA4}(PF z1Hla>gC@CmC5CA*b8mz->%0?J0rC{usBe>!IwU;V8tFE8w4=4QYzlWwZHhHw+rF4$ zJ4xJRefuS5mwRB@p96}GtZcb^(AG=#V<So5Wr-@Mqrt5ZSlppwoh+5pAoA0AA)JE})K|`a`0cE9t5yEdcPo<}>-XU7FpbB8) z2HKPcYiKcZ_ay9E%+7NS>x-d;4F&ZC(f?w<(?Bn(6FOm+!25!j+GsEO`&)0tRM^V# z5-Vgohtn_aWG0z39~`pDkhPi{5rs#b>d!}Oq`K7`eDY&|GoW=)cIW|ES2!@^ zivvFO6}VMQm;UK;mesd`aD`=30^6*XFI_0)A>Uz2_#70?|01%QGk~J=JJ4VDwXq<( zho{!fudkz57xt^uVY__TCiAk0Cl8fmo;Rs|1(pH)HyWJth_zy5F7!MWTiHvy2)U-h z659rfR_$fTn9F z1=pDTMTv8U4T%k|G;KmM2Kb$j{v=?Vg6;9DOR5|aWCv5BxRjHPckXWdUuQtD=3wC} zVY)_0YbqqMDUOKkF^3D9O*OKmbX@vLb?6KwZ`b4AcjHwO5!*nIr6yZT9HER1S`8l> zW=RLA8nqQX{eG?1AL=61JiNPb+R3`*ZTCdzIWh_BiKG$`?0(3F7xKFv4#1-jp(xRd zOLAG1`jR@E3xmYV{IAV7QP|Xzr*~d%xQpw!xOB(OqU?>$x5xd%zo5hIC}8VzEN|a{ zK0FHH9!9m6@|FjrcxtQ(AyDxnMg}uX6US=0pI-DV&LEn3i+3&ug7Q|wGh{{R3zR=-u^P_CF_2V`V*j7!Iz+)NHT z0$7bqKu3T8b-pplPw1u4O^xl9Go(<#3oC1~sg!c73*^{eGQnht^z;*bT$H_PvKNv- z7}h2&NJi58(LA{Oydb zngtI#EVt9^tJp}jC8IelQ;2Uc*&M#hmkJ0J*ymdxlo-_U-Ax{+W|vS`oaoez{RxbS zLlP21?vVU4FumR8cfnf|o%Kfl65mI$rZtMM1;3cO(_!0u85zJ1o&=^W_|{ zNT%ok$p)wq$Aj%Ch57ZfnJLOrw9-)0FSi^^tM1)TjBotmt3vbyXE>b{$nnAAjVQA0 z00s#pdkR~PCAr!~m2j;t2nR~gwcApCZUFtKYCs@vZ(a@Dtd}LaiQIG%9Pgn8-2_Ep zPr(J=PhbR@R>Tmtuel}or$I~Js+769>(I_YqE`%b;0Sucg`wN^ z+3VDr0!$=iz?sEVaRMKB3lg(ZgoZi3>IgNeALE5+i$rP)Vn<-7P{X4*>W2?l6i3^fHuT@TuP zdw>h|yoxmR(Q`zwv~OgtP5VxRQ9$*?Y@Hs`@0JPWlW>AvEPO7Us0#k9c6CW`t8Xqv zC>Vn4xGx@P7V}@?`qU=7j3KH+Vedj58q|+7SR8qD@b6ZSb3EJn8grkMc~5~PZ$12` zhCXm)kOrxpwJP5Rd7)MTU5r*2@&E)?REY`5<|QWb%A&+dXvfADLbbFp9r!L5%3=&# zx|DHH5aRoQ7th?X+-vw)b`Ap^lG&pE6849?T1J}rA>RP^&`p$js*6< zz4Psmb^+pOAVK(eFlw)#!aW#ynljG>HC+>Tdr@^noC|&UmbSy66f1!**gcxpgO2Lz zv&=rFn~#s1J%@|BkoNu^A>YCr++Qgbgl~9vvuSYV73yJ5Xv4^w2jRyl42zf2Cn!T%>b;F2mx+1mv zCspX6E-bhIkQz@gzqaQw_=f*0Cb5|dG`p{DSsbw)}J)9VmoO%wW?#p2H z`P08qbJBcGq5#3(M8ExaRxrZxitR7yFZ$)Tp{tm*6APvfUZXPe0$kB5jgoFl)~xt@ z$+Wf^kX!n;poOB&Y6Cuz{2^+JDLoMYMmrwwBD3$wCKBkxNf!8t=H1lr5>q7K4eqS# zprF{b()xg4r>Wk9GQN`24$j6o)1G2s@)g>rp^?x41elm*8ta4YnpQy%`)Dh5t@}TQ z%D!@4C&_gxv|06}vOA%If#mmG0^`UC;p5t#hMebNWD&Q-U%btb)`( zDb8>p(vnRkC(wUNql+*SoCIvNuKSK~@QU=1H*|40;oBAxb=GTRYZ%Vqm3e7CL{gvH zEgYp)PO+Lq*M^S6@4|5qQoKi@G)qe9P%Wq$GJPw?st;{-|GWk^0p$Sa?G?s!m2$>A zNOJcvSc`JIPXO(%3qY_zHtd60uElx1TQ-`$cr$g}t1E}^zwQQ^r5qwTt)rr8!9LXJ zCxD5b=I&EjZah()0ssNk_S3hsO6V0Iuu>b>f9>wB}y{g^OEv9p6t8=dQxF7=Ca4DD9$8fiVjMLF31 zG2khsb{#pR^P}o9LdAJdzHw%ICE-(DbU#!08@bH`+Vdk#wI>P9Wel5^_OJfJQA`K< z-ZhxthCOjW^C*5^I7?Q_l@)l~g-t>YyOq83vY`;qN*Bk4oCr9HMZoq$(1$q2lYjtG zAmP6OLPfNIYtzR{ zT)QdS%2#4K$+zC_!BYu%z=znuF7u0OJ%F|e;?V>KIeS7tC#^iA&JV2bvEkbUgwVk- z98h5yA82X!x_}rKiLJ~TH^7_+Q7(npwmrp-BvmyKpHtdu7GOMk|5L{?4>F}M8+yc+ zh9x_7;(S^={n=pF!yGP)-=#I1h8=3emQg(TcSEuvo1S-UApBDr()n6aQS@O*bWiIM zRL>Ko)uukNPBwe8LU7OTslZ%{KM$;@G#hkHhq#H>^#Lj66k%P)n{xGI>*Pq}!RI1a zOiXCJS`WY)yPon|M7ta(@T?m=a%Hz^qgC`|lg-anvb=zWy79(z`+N6thDTTWkPBP8&47a_9$ z43Kq5HMS&F2){{$TI3{gb1)KjB1*eNc|h5Wt02x|xA#H+z?baT{BpwWiC!+;>C=HR zJB#u^i6ffcG0A(g8Tmk-@CRtD*S20h^oR41>xhSe^k5r5RO(e1}DC(-$hK&wwF@LTHtY9V}z{-$krEXw1QlO9exe1-y50-qKJ}}mo*;5jW&gPpZt&KrYHsjwS~|Z zs4GgU_7bx@`&2&oskE-AcdwQJ^`|-;qjT>4iSFWO^+&RQ5qbqe7XKvq^l(lOVT?-8 zs2hjhl{^LMpAx*^^yHL!AO}rYV-plycGW0X@g^tn)2=g!vdNB{4998QtXrQOw`9e7 zF#nf~rLOdkZiQc*lHNGtR!7{&%-+Rv{lxg)uHB!;02$RCjxB=f%c={S3 zAyvrQ+ymfz9ZscaoV|EG0fqqVAO4*2tq4_N=C&9Kkj6-~mTN_u&_rXi*8rF6a`j`U z-k1hz6=bq%h)<5#g@kHO6;dyKpTc15Rg^ zC2kR($~PJo#PG`nL2W3*M;i}yPaI~5D0-jRAJqv$+|tKWd2{+6kV;0@K-ZzA^bCX=eb>)w;7|ZMCrmcg4xq@uGyLm5mfyExv8Tg!Cc6&gVM7%r zf#A(klSik1@b&vBK%G=XQn1cO#jh}6COY`$Yyxx2wF)!|-!waK03bt353V<|w;?NCnJI8N6y zT=z|ifsD+F1EADI$hVDrXKRjZcioLTvDyYb4Uq|PGie3G^ z!l}2|O$-6V|hz}3Bpuztxpb{bFHuB`&{=z)v?757ts^~-&Dlk+^ zK8lxWP$7bh@faEGM7NZYGqY%~e7nVxPT+%vfO_m(W&WSnMir^f_1@}&d4Iob=r=& z|MniRQHMY#jY+To!o~f_p;)FbLag&VqKAE-I zMy?Gk_}T#ZOGG4ja9quE-8xRLo1~WJjFK>Luif5#@u8dQ@$BVjLMlnJSmV68(hy+J z5)_4K&umT3gWT$94=K<6mws|~u@vKo_r#nB#dIk|oU=IxUhHlLo$r|TA<>mCQU;yN z^fc7#lo-yPq3@QBQH3QY|07-Tr_J?{M#5>rr5{d(2NobrIFEgqcuxD`kJ`~K{jskD z$yf0MfFM`*_~uOi2ufJ8GWz9ybN~(1Syx727hi3$AsU$NUGC@k#q(Z~0QeeEp{s9a z>c_9N$USV+!2n3)5w%akz2c8F8h1@4yFaY_R-+PtG(*vb>ZI*Zo zD_;sWW;2OY+Yi}vO)Ek{6sodk8Pn;d^v(DZi9#5?PxEe+q1Vz?MKTCw(%V1E#b%`L z>+NqGnuu2bi-z(2l5UMZ!`pcVsFGySvq8KSr4>sdgpSk){&sH+3$Y$ASt`u4@b zNe?(;iZ#fhZITb`4cXbzpn}o<@$=_)=Z#{6rx#O&E!kpI;2J84VqQ4_SLP;0B|IV` z`pLCFS$3A7Yd#sgEm&_%r+rKHwk^*iXshK?fv%uN9kWTnZ`_s+!d++wy@@~o^@Ba8 z-A6qls|EzQYrp_eoi$L_7YMqD2(g=c-*Y^i6ob8Rl@w6^b`s>ZsxC=L(?KyAAO|d( zxdRC&04MMmL=iS5&PEeu&{}6HOK+(CZB7g1ErMCq7uSx2`>M2Hl?Qv%8c4X$<1YC9 znFrJg_Se$=6}kZR5I{a5E(bV84g*ebO&^uqwN=@iCrmmMx;IoVz+PxXXp!RecUUO# znFNQW-%L`%O7f6UC|U0 zVhA)JSfBxC*=Cd#05H5zBXibDl4>mhP}&W%D4oiukqq)w5NRGbv30wEVK3s4uSK!e z`}w+Zj`{*)&0~c_A*F8VvUA7UgAP^%2FVe?Pzy&Bh{BI+>*-@3N-9Ml3_|Q~>2Jmr zN3=*aVVoZv=7@Y=HNMSA0xjATXB(ZQcR71BHBFKJh@R4%jB8E1q+S0EmsKyP_z$Q) zLp$sq$78@`v>_lZT}se1+y^tLtk3AjSiYQ`XQzTCfMPaA@7`@!@eDdk zGKr%BGQn>l@hY2u0syW+QNLQJkbfyhH>SJm9L{u8PZGkT*#x-m=fSlwdF~w-;Q}){ zgZ8a6Fi^%14>Pn%f%};i=@U;Rql3`X!8rAuz_;}iaHIc}D~VVIad*v`eVaYrJ~pf` zPoUuh@2@(KKh?Kb#eBFUMR4ks3pyuIcl^6`^)SG5X}G9(Bj#9=USdsuDK8zu7o~us@wvir@9@rhF@1g$O)iQN=UdS3tNV6*R~Bk8ntlS z4j~8?eBWR*nlWS`wVycFa6Q*LS=i?X}GDp ztz~ZX02AwJ1IUrqU&8>G=(m8Cjw)jaBb`VdL&*NqaQ2Q)WNH8aUimiE?kifAet-iU zv85Z1k7Xz=DfPHtmGkIGY0R9EWD?ZhxT+Z*kBadgyY>`|rY8l|r9dMwMzbKn z_c=pv6!wD-2^wms&0GLY0T!Q>&?BCzMI~yQ{s3aY0009p0iIkeREqxq02s1+1S|gy z^MHyLrKA1y3j1QL%ShUL;y~85G%E$pD+mT&!saz&f+akm?b)pCAwL1jKo`UVWQXFF z+m8rHxQmlTu~UE6yyD=;}SORKo0$_@IQiIRu)5bh##SgT=OrH%q9iLD(}Qi zn3`$mXyxWe1E(D=!PJ`%f>0RHMG= zCU*r>2af_{WaHCFwmdjCXAYG>2SlZ40N0&A+K>YT)jxwcjQZLpG(A8;`m`SB>_V1+ zfs3R$#0v4@4~moIRXNH;%nHw=jJ=p+I{)Q>1Ok1pRM=Z*fqGMo*Y;W)^MY1&hqt&v zr49nj0A6a;I6grJzEvlsb`-)q=j(76oIek)>p_vdE3N_VC2_)oGpHFPgO|L@o_a#V zpcxnH2%$Gk`%c@h&9H_Z*k`(g51O~22{V#!z-Yi&w!)2o0ykGL*J((v8W$`j^F4%- z;07B*IeQ@D&Kt`B3Zr!#UKBrY)T#(!HG_14iD6OiP*TcEy5z=t1RMDD|1TPGnSg*C znk2N7t-jL%*`hZe_$XNOEpTITo}c`CAFBqDopRd<2iq;wCnh#bAfzwCjkUso7Umc{ zi$DV)Ns4n;$D1_apaa5(ToM){ZsV0e`W#)oAb-!mVJP2$D-lQr4kUa9`i?uzt?tHF zptDbuG8rURb2Q<}s{8^-t-Z>YAVn`sUa+RblP?#cHfq8hAEg=D{pPWO9zq~qo>NU) zE2_SN001<}5&2hJ$p80QXs`m>0009}0iIk;REqxq02s1+1S|gy^MHyLrKA6bft-GF z6m--H7?9vAG470fCA@w)2MJv^c>2ghIE>WKI@PFMcl4nh7BUk-ka{zyCUn^uXt+~C z3Bgp>XuGYVN3D>w(lk!Yf~tah=xb06={e<_;e2c#a%Sg`O{pJFL(@C_4`5sX^sq?< zF6F%!3Z{A{-_OZXKGX#zYM>~MfUdww z?$yi~H6TBcnAG&XjdSOwJ5d1W4PD?Y^25+}lwv8lhn}l49OAot4&l1_xw(9FhAB@B zSMj7kA!5xTliePS5Cii=@VrDo_^6D0&_5qm7WxtrEJToL3hnpQki+Y)GIO$=KatA# z&&^CY`Dv!7X?(Mv8peioEzUbz=MrlxWGq3`9-%s_vT3ZL;BAs<1WZ7`fp}MICLJDr z;w|ov`uOQ_fA&p)oCN0D(Fi{GUj$Qmb*pWrAYfMo!Rncr#~lM$@Ps;2JGMkjkz{c@ ziWynlHT~V%D8B})YW;jLM?1V3tohK3qZ7>1xJ^)R| z&NYK5G?PxB12GXCj8q)$GMqO7mb;7xUrIE}sq$_*9x%UJF`SYB=I?HME^`*T$Whi2 z6oPfk&&7gyl!=OMubLkKG$iOR)ti(6_=q@MPXl_3z-*sh9u5^kU~H9U9tTHADb>D( zQ&)IVg@xlFO^-}chR+N!29~FdA-DLaFX&sN2M?GeF@WaAjFh4r9Jpt)RB@Bh|1__~$9;b16#RL~W!g!<-LO z@Fed06p)pDt8$p$_4(^Zr(t`JFb<QLv59veopU32d6 zVZy|`5`nfd5%L!AffdqbS>s6cl}_KilMFe0jq45986;Uq!e4pwJPQSBG7bqWfmT^) zT6`c@LZQua!@&JW%6U{##tlH8u2R;>e#s~Ue;6}!?#VC2^Pz$p^g}{c!L+ z1BVXosv%av`v;G?bivjF45o_6Fbm;;mil*2ZF}f_)R0+VCufUW9^nKzdsn7b9(4_~ z_(O(IIBr&v=(A&8{vyX@&os2%N4eLe+zI)3}Wvu`i`W&9U8BWH5Zns9!#oci7+c`K_H4 ztSnA0Q*Mb{;f~q_Pv8UfA6z5{s+)OXR{vRg-QZDEC30CQ{Y22#dp32ObzaxCk?!}Kh8 zrnK|5>L!LKx%Vc#0KN<{#cbNE<6!R|RkJBB9}LY(OI1E0<;N&HWIa680zb*bVa}xx z19hy5*BqB^xp-ErZc~L=_n!$=aU@{vRg_3~B?Gb7Z~&9alLPo^e4ZQ~;s$>J69i8c zQb{%xqZD16y6G6tV9h{IBhU$TA>BpRnjgzB_d6F$m3ae91t*LhqN*DozBF$YgSYvV zUx3WtOMlG&{Nu2VzK=5M>}~G-VTS-z1K_EeDlCqkUnz!FL4?RVQYzqjYbXUTxx`LnD zKu?4({y`IU7^wxg1m)^5>hoGoyZhHrn+~OG;0_)|KK1a#p{Ih|jp^jqdU0l@PPyX1 zqYjo>j81d=9p#&{S;Y}V4VDw+XloG%ZP{!g05M?z00I#~nq3IZK!CQkwzjlPrT_p3 z{{R331NB7r^_x8cpqlGyq{9FJYuay=4Tt~$8K&{SPyzq|95FyHvZn}SpAI4gu&V$9 zCTmyleO#3za|~c|kOe}7PE*QCLRmrMqtYx;7^VOPIfi!P&Ms|mJw6kfUR6D!unHDazd9(A}BIeo85M)MAAOOrepM?Mm;n}gd z97l5j=f9x~puy~GUJo+}_S;aezI2QKu1AiBa$>Z6_ce09cqK{IhfIG>Rw)In002VB zf%&wubvASGMy^@{dU3O)1U(v#r~t@sAmP}|sgW0;l0I}(mT2;=xkfJTYH$j)**+E> z0IT_MOTD)i*wI`xzz=evs~{`aKT?m{Oe3{|*dYANGV#o@C(v7u5zo05Cz1v<^y=Mc zz_W`5+z2F%Juh7Z+9%>S?;3M@4Qcg0jIBR9bb6WF$|!(hPMAF8tNOB1POwA}0Dn-B z>hQxrVJ8ZpyskzPW)UFr@+pK_sU$oIK#!!1)~E>&k`MEzV`)UkZcb)Loql8qd16{l zSL-B>IKN0sdZw(@Ci5@QS^*AEG_$Ir2U_=Pv0$I9&J%IU!FO-<@(qNj-NlrKzQeP+ zbIdHPi%&Q-3)KE?ko<-S7;e4(MWG9GDJ+br8wqO4GqvZ-AqcggXpjbd0008vL7rsH zTtt5W01y>~DG168EYOHMR{@grKl}Q&!yL6PGvHpuepS2+I5a6x4{Q!Mrkh_2!utm^K7{-xj>DDNcm zY~w@%>Nn(Usih3c3-1%)fk$>jm&#dmSM~{^$JMiepW(3p!#RA?b8R+%Lry(F8%r(5 zE_g692=uUdv|@%GlCVp8os3-(&<%;d-ajkUf-#m<)I)s^Gnrd#p`A)u*89M$=8|^< zq<=h39$hvwr8aaDK5%YXt0#E@}Dke0@el2E5F|*fq7Hz#&_O8Nhyi3Z*_xw*W!RB!-r(qqC(UeRd(Cx$fF!g zy+S&?y8~Hk7vBqr1tY0oIweU)RMMk{cLMO0H~6{88`)z1Ng%CCvBC><lm=)c1>%O?O139XvM100C7OmR(k0&=tg{kEmoG!yS;2s$R`UeyXr;lLt*@ zHRR7k=3BH2lQiXQ!`J=4aA@3UhL2-eot0PwSP21Pu-FxI50q!$a+>0I95{{_lpA_- zUN0JXcU(XRnwu)jP!KED>unV3wW07A+q`F@&HHEQP{f z=-|okEE-IaRYCqBEsEBxg#d#1h4x*6CIC6ks3q~PsH!*MfDO3X%0004s z0iJB^WQzX)00RJ}9yIuCfALOMZN31I=bMysixfOc3G1f$Rm~=?U2q4oIv^M$UKRag zu+m{j@93ahhy%FBw*IYt=X93xS$c7g>ovq)u|*Iq{Fnx}sygweK;tbS0%|E(Dsu`5 zl!x)B>!GVZ|13k`cuZEt~LXf;WDHlZ@0$q@iWG^@wdr z2>XrlI6-KG?ehi9sr%hxCxeNW-rTc1zF>JDnI)N39ewZ>U@AXUr@D{=1m~ael~^T3 zGhAG_Fh@ZFjh+BXH^%_GunCt&q4qtIL%*S9DTyL0(YDPBw!i=Y0{}|ykHlJX@DR?t zf#ezj)ULQsV@5LJs+~HIST6}82o3lN2nD9$egeDABmrg6X#qB;qWR7!wG4O{>4iWA zHs0=8WIvnRfk5mFo;VI?P57%*1eup_BPM^W??a(i5Qcfqsi4@CtKIy2J&rk1RE=P= z6d*Jf?NS2Bj(IJiAp%`EgNjRr0EsEMfwg%xK@$J~LV7`(ZV2r_fVQ@_wzjlPrT_o~ z09OD22ItU^`eiHo`u1*%9FJRMcfy*GMn2KoI94!JVMUFpo(Icm^MB|oCwJ-hm4hUX z&JVhBwo~?|Qyxx8PMjqlKeQFJj>-Z~6Na&jQnL_yTXGhiP4>Z?!}%3sg!3z|n|}DN zXvbTM11U+BaT7rcb$T=;!Y_1g0y;W1?B$T8ep~5sb2H6gVeKNojq&nUSchTKUyj4U zT;B$L7Q*ebjbu#b++9KRO){$9K+@n?@<3rHav3>Fh_|@x!~2jI=EMzWA2!yCS;gZK zUbH;{Aftm8bOfseSwRLK3Q*wXX_raB#t&VmKnKYcDcV44$S@mIlZ?#7isB$L7C1oZ7`e4DX`F$`5 zbJd;iycqfwUqJ%N5uJUjAEq#c*HS1&()9IuQy4vq$T3o)ZjTf}^g2t;q`_nl*>vS2 z)&r`#!~Ka%r{0JUxjn_;%};^DkKUIr|Ez{+xRXg zCL#0ped+2@PIj`YfMkK>kj)gUuD237AKr`C{1|D~c>hF~S@DZ#kgB7iwDfp9#ZRWu zyzzo~LuiGgI*R4Cf%H-Wa%|1E#I2K1uhP+Q8n?;8fT*tR+R5`Z7b(`K!9K@(ccj3x zg@_-`LS2j6hrF&#m=kl+F3>p;aS9TvwF6^o#?=KsVnI(A1@>vw1=BhW=p}~ny7lFpRx4AvqX(xE((7y)7?CC%sFXv$^AhSj>NdH&-c9#66RU-YP~AoB1^ELhuiTDEw(%0$AsqR!+7gr zx*`N32fvrucD+FLx9EXHKQNqi74{_e~HbBR_1qF9yqi|D+$AZqr>^2d0B0Y7!?(@j<#sA(j zO^iN5iHCu$@QS^_%XI9TX`mKn9}r;%C13^I9D&KDe;Eb>dC?RSAIM-+?+CYj$2miy z3T?|qJ>nB>>m0qo9{qq&5!gAli$B8r&50$SD-KAUT%wHnlA4~gT3x`Gkfk`1Mwgd=0|NtN}I3FQ+PREszBI1CIQtFe?d++(>XJ z>yWAV3tPq()j}>5>mp#VBTIf2+PR6d^tLM!uil6Gzb7t9N!dHi(7UE@Dq~JuV1!&E zGI^dxU`wOZWU!k80&95|N}ZfNU_kjD*}WKga+G~)zl=p;$mFEGndBx`s`w_4soqt# zL^wT~=4fX3?3HQyeEPJ(^3#S7rtHdmzOiDMqHrwbZ=>f)2%$kH(9OD>nxI2AGzyTr=*d&+r`%3abnR-Fp92#~v6y2lJjxNHHG%n)a=QKCJ@ZDR&^)cx zx`;WUz~5ahq9Frvij=uoi*J3QD!h}1&+C^p;ED1>)0ejSi>UMM7WU>4wdaoP*KJ#| z`Sz)XZH+ngK~h__KN5BrHq_r3CKb|A)d)znN?uZ^)3%-(YCkIPootpXFR;Xhi zIr3tj|IkYglmRHw8r^p#`}lJC5Rsvm!%HP%*N=1ZGKNUtHr8wWyPP+=0BA5_$YLPRrn$A)rWftlEn?=wdiiGRrVohK_{1f zda2J6aWky95i2L1+luKh+YVpEMxX)C6nqyPg&fUIzYZAirDC6PDo0)NGcCy4ZE{i5 zQU@9%B7#f5*(QbK=F=O|qMCt`_$L90M=DVE;DJpGP|K>fy%;e*=9rRL3XdlJM|)GLqPY2KRqJ0A4Jh-?sU z{*8_UPs;ZB63tBZJmc7=KCQOeHppHyJbS7}1Ct4$L{bK&S;n+z;)8(#GPahTO#Gc} zRcMfQAO=QccKYK)sHp?j*_UZpFiVQS2s4PAmcgUfumHW(5qhF!9jJ&H>vB-ABPuZk zdvy~EQ4Yp4fiEhg=0Mh@r@^zubCIBHPa3R09xiYFHal9rdj&{(0u9n%s_Xg17c2TP zEB)Cd$<6oILT8yitez5k{$0xdvR@*XG*oLv-eOZlC%YkD+4Z; zm%Jt)&@9B3uUvZ#@jUvD_4vsscN>{CV)jQQe4o%KF_%J()~U*qEYVd? z1tHjcvk7I-iNwIJTEnIm5LqC^Rs|CfB|a-CDdMuPm)!>kF#n@8F67=Qe8X)pD3AoU z?c&FV=%GSufou|`=_V9(MrrU9&U7tT4)CwPL9fUne!lO!rTq7bA8e-!@`C#kj^EwI zC|Gd2o|^#Lz&te;(Md#hcNc2qZ;5oGEeFlYAUy2P6(G7{E}{~9gVkD;Efop9{mbcW zU`9;r*Fs*VDq_{5vM-gW1YD^b_DYB6i33~!1pUi&oc&)oB}E(i01-Tsg&xhA^>Nt7 z-XV5uM&turf{zW{fOc{{kC=(PMJL<&%n+XI<5190UGVV3Vaqoa&< zg;Qy_4Z6dD1omAQqX(T{1uo|FN?sErZcsIOQgHM^HLT@%WOuy~NZX0`4mrgB5K_nE zd-;!pi9GOFcTZAj2#*{vMiG^x&JOD;Q6C`8(RdvZii@JE*fW5+fRJnuI;hB`mE`o~ zS!3IH{T3qWdw0!sM_G^u`#4P^GdAE`EMPo0#Ze+6stw0M3(ABK^&S&1S7e-&wMdx`x*#f`Dz%Qa#LsRCG938!?M+zrZUF zNrzcQ60n;x23Z}*-(uf%qCT$B^8l?kSRcCP3R{nqs{n7^Ryvl3K@b*R>Be8x7hAW^ zFHGtc`SV=Ke|C%#nMaMrW!pP-hhNd|*r|%0A|o`}ZmTrbJM0#&?O6$&{tosIN3^x< zIxAryt1B<3zV=y+s~qA8^0%=)50YK)(AaDYbY8klh;54;P!0q)o^fli5~(>X5+V%Q z#zM}`J-piFWp^Kx$mt0BPP_#Q2}K%NwV4*|99%bQ)qB2#Y(tPSLE#8`ZamOBKhmu- z^*{s?fR#|@|>11}opxD+YsHZC(A$dO{5r?J-j?d6eJ z%ssXuF6<>5GcPTg9bd9l~7G9s$>UBQH7QdE`s-2o_z3s;AV!B|k; zWXuB_{BlkRkmGVZ;lqk6Qnn_DM$qw9um@S(WSUb3!4+4p!xz(6~_gd@sksfP+p0``IL>L+qmBlDJaaq%&`Rt8DK@&9VaIWNxCl9@2(60W$H2x`2NuY2qUY2cjJgmriS*O&91 zZ)_s(<_WR2)-iEFDa*qHh*-y34V}Y-)Dcl<{;4)+Coh^(0}kQFjW60z;HkG( zg)!Ump?*H!DJRe7^V4>x>s(>L43yZ^q>{%EFi>6FHO-D9+M;I&=SxjL$CwxDUErW9L3m4;uQ9E1_o4j222-H z9;K+$8NOtNooQ+OR6YZKd$45diap*1%cZ2-&3>UtAnP71BKy|fFCr>Za^ISenzb(v zlP)gaU6?ASI{Xp?CkxiIO7g30a0{9Dx^gGjbRRLfd9X=n4rM&UX?Fgq&n=Rbj{d=S zAZEarTXixN-#`y@MLxg{4}Xur(&&~2m%=&n&*@FMrf$R+Rq0uia5N<9d2z{A z3X}R~X(b9=MfY}_xKMO5kI&=Ols@H0xO=^`nbcVPzp*wUiS&?05u-Ei&35&`|WAtG$i@@xTosynWcSbr~3X4>1IBkEFF6_~B5 z!S-EnMj)h^cDA9hj9kKQCv3N~nKD4n<8`(?8@4~FJ&#r%mm&UycHZ}`BNJ~x-Vf`U zC^LoH1ls*q%c+Hn`_kz(?}hA-#d3F7Yzsf!gnYq;pjkAh5D}}e9 zk;Xl7-4UD#oXHjd1W{JKWcJ?nkF9EUt45n6D5b`M^_G(!graV=Q8o&I6{5g1QT*YP zMyD3Ny(M?lv1y=LcnIW9?rY8VZwN6WtX*~@GAMPeT!M*iu{VhvS(sY2p5tNaQ!8tw z0a>&$sYg}X7vK{w8X(>cAo6_{{DbjoVGC>)<&hHYq=&+*E|l`kPtj#XqAwN)b5aA5 z6YJ$e$bEvDbTjh++@2Sl*Ogogd9A(Ss42 zjOtjCXiobXhy7pv08*kEkG`Tu*A&$a9p%2m0*#1xLyy-4Kh(C71}Jv^lo#M$Xhp5@ zle?FoEfu{1u`<*I2&MW)&ksQEyg-w#yigQnW==Dl1p_{MkR?K3)5+h_Ym8Rl>Z+%q z10FpF$?>``Py$%3$CMcOO%EQ~@dMw#%0h8(VE0nK8>JzBb)(Y&q<=G5+Wdcn7PwKi zefu6zSlE4MmZQpCssQVZFEdVD(}$4tVz-LI83X9PhPiuf0ww8db_dEJkW~PF%nh2G zWChV1W1<}zjN5uHf{!#Eht5Dghpi#9vsyV<0(xfa*s5bJY}9G6K|1)MwK@zWF~^ms z5_bbKaI<95?!u~&NHSB5(*ozCCXWT#?Pla>teI(-(@G4Riw>tj?;}CPc}SeVJz`3 zG0da4B_>s{zC&1Vpky1Zl63%J1mE-s4?aB-9d;gtr;>tQk0ZEf=*u{|!V3mYMU#G3 zYq48s6osIuX{2LOqGM!xqA?Kn)Ul+|C|ey&9(o+hq;=3@C(>+`x|0*j*k9F4)OoN< zRqv5{k47Klbr%0VfkkK~!*4jMTfvBfvjmtyC)NlJZ%voyxePn|nM^y}r?z~FOq$-y zQqw3XgM5%E#_nl;8u~-00l0Grb$~AY6rd9NUc5yavN{km{;{jZ4KeY`sJ=W1`>T|$ z92Up)A#A<(G)b5<5OCumWOow46k#8S{=o{kY<$<+w2L^}@d zR#+${R5)|MWWe`{tJ=v1qo<_I?BlJ+lNStg8*)d@ER`{SZepO{P6|^Grurj3FKyMF z2MW$fwrtTB8Bb1FO-q~eKn%*)xthh6K1F4z4Pwo=e$_!ExQY~U9s8nBx#E01$m$r^ z9XsOE1u$)&A8I&Qot%yL*MI3pF^4K>o&mf?Bzw}rK??E@!e8~DszHHPNzY{aHg+&z ziy6_+EpuVdTq#lN+R-P1{o$PUL3W0{yuJgldQYGI=z~>RujTejEc9 zu&}Ys$z$!qe*daLi1&j1^I^b1IT*JW_Cf`M1rrP5A}c+YctLD-V+hl}G^ru<@Q>UG zv#_KrW9y-j%}4IqxSm*L7}s7Q^pZffN;$_r_aCq!ISb?}q=t8X+ENm1?kJEqVHrZ~?UGfK$ulILi3(-S<53z6RSP ze8Q`Zo8)YHOW-h?gmTyhO3i|IZ@oqP9dP=u8a6RklhW=My!bO2dnhdx7!PVbia6eb zheCXEu>~Yhe#$N-vEju{tx|Snw~~YH4P2yV@S8Q1Z~hVt3`34Dv7P!CEZ8^_gc`-ZvbyR zXlbq`wPH+Oa#TTb-T};Wairw4(wK6UbcI_@{N#`|1GR zG4~hRTArGgG~o9QDmZM@PwEU7P!Q4uTT&dal@@8-{V=@*pvKJ4}rygn3Glxx~o{Qmruf(g?iv2(!yWnaml?y zevj@4o<7*AelWjF$6TrmV|H{~{_GpNmB!C~JwfE7Lp0XDJluL}&hKC}w~Tj}VXmBd zDvZCxjs1O2h{T89m>ZHe zswGtkA=rW1WQhSzfkdKEoSMu**>8l=qRcKt(4*#?R}2S}LbM(30X|wCchpSKl($VT zQgBc`WOQ-#>sd?;OqDD-h=@KGCn^qtvWFYrKddUbMZvw%^m1jCaQScE@a^R)qku+~ zkPq`pHcWmJc)A;)WtqzXQ%R=(fF})WcB95>DtTf=BLq-4|1otrraa8D>t9L}^re!F z^RONU=cLDvss{a;?uT_N#tJnbBzXzBF%d`ac1)Vs^dyn$R%_pJ)zPNbpQrs|MV4at z>m-%(2s#$|k*-DpfOq9CAZ?xRp~#tq%U!{b3GMkqqZ>&-MAZK3WKX){^>(1m#WF^r z!a5^mME6rpW-6TnIo0`-Bar%oXK%$(9@V+RfxG`PK`e;d@!Cb`P0Wefr`tc?Zxgzr zZ;DZwbGu#Fs4_F$z3$l#f#51%?r~PYvRoduQVFzPuJbAGAN<6nsob7*NR7zdxwn}V zQWo(>cP1P;N+s}7rq40(ae$!^I{_SuLlXx}%pVd>oLkmX=FG3Pz-ONM`PG7x+E%vJ z881=jQ#qHvWM7}@eXfv{kN&?qkjNzEr2OCzz-vAu z!=D{YXuK%#*RaMsO3Xm=0q{0g_EmD{xf-b4Y%HjmV+5zkzi4Xh`flA$s12CEmr0>s zD1pU&OQov7zo4$1!8!g_WUdGJ@)*P! z55d*prQ9`-h}~fE$*s64yDDrLz|%=BvL6*-^UrO~{59ny?q9RGrHs9*^_KelWI&;? z1U~DR+ZJ17Yx-7Qc>V31P4XN)%9xtqL1=DK2$OhrqFQi6r1@ejfhucGa< zr%2dubZ=u_K{|&*nQt9Mr(6W)#x%*g3<_)hv*K^$Y8ljChYsR4m}>ZIG%KE${E87d z+i=;8o)9)sTBR3(L_sNWC$OJ6*QaK@TsIC-k>N`ePDf)zR|g{4d;&I9vj{oQJ+OoZ8;#m znuMl_j|BQP+r&eag#-OfDLQXoak4MhCp{^|rr7?te@Pe;y~c)rKj~oW;^edp#3zy+ zop*xKYQh1^v4gK{$nXl?3>OF!s%iWGN=H8e&=MD@Cp{XxW!aosq_h+iw#`PIY|!L` z!iB*MW{LXsLvUgvrdTMDYd;^k8!5Oz!T0tj5T6CMk$Qva=c$ic;>aoa)zkrIPl$%NkAmKNN zd4yK$wMN#nn2)e}Gb|NzGsz-gM7P1Kkh#QHChl$ie1M=+%>pU4qHT|ZxK-yp)YVLR zpDeyE59zTWGByeJT0=jZ{xb`h?J>5c=MSZ?;jwb%D}NEd?SA_!iNO$ubwyn#MTp zW7<0RF@Yobl8?GRIBh}T?9W#fr#)$%VE?z|=^VKzdqBD^I7@1~z0=ahwOE<$C?}VR zWShA;X+%Pedw8*stNf-mbT-v4N-1k$6Vef$|e`$Q%t zq3^zwJ3PsFt%a`{(qT$aTWhw4y^F;ie zje_%aNlgBZk47@Tl7ZMf;X^WIY#X+}O>?+8SIn zK{ZbrB`1X_W+hH4j8tS^yWR`?% zy)2kW$V0vY&kR5ayo+i`uHcrhR}H^-;@HCyT39os z&y`d=`4F)?{^r(qmi|Pf6%YXzr1U(mSfYpxM*F$V z$oXF{3?n&peEBRBy5IS+YXy};hWXm`hfRq+cpW#|KG429LEcJ6Lf6#)EfFRC_Lcpg)-Ew;_P0K7yi`bY;ULR~%yR}kSi4dyA>3g3qa+iC2+XiD@ z&gHC}N9vXX%V#==;Wrta*KDFexp3Npj|+K)L!RWV{2F#h((bh(^pyqsq{HG}Xwzo; z17DhH?l@!>ZLTOQq4@gBdWQk{U=Cv9zx=*xVuLXy;9h5(MeO@qzr$TZ!W7-myh%?GeIWvNWeO zn0Uo2VL#m_@E?~S662tj67c}Z)@!r_KGnx9sF#{kJ~zk9Z}eN z$AOP8q%h=9hX0q-mg7H?g8W5};|RlamfzfLOQU)WI$=ax8casq@Ghzak#bx)S9dO=tqZz#oMW{t(m$U3+Ue-Yv^XXT z+f>i~-4#L1E5=Db$UgAEitJFoPW%VZcSgNq0=*eg3*^1SRwV8UmR$C6@q9B%#v+w6 za{CNk8`j=tplUqB%0Ew+9p9RA8sQRQ1tf62%e_Bs&^^Vdvwtl?j~`rn1X7~+;eVOc zU=(%kxqHzzT`}{%@m2wkG*SgPP`App+(C!klrQKRgV7O4$fyyK=-9 z3|*H{0H=# zp`>MhS0UN3o_IhgaMVfkIn<%i?kG4HXKB?N=iN}A)y+4u%A{wU3B?KS`Q!of6K4@P zs^i1LSLIO&%OV!ymxro#CgaB_}ETHxvSbP*g3B zT#pikG9Y|diZ+~YNCY4PrK*^kiZ=M#1BWDpGtF@XG|nMEe$BZ7jsZ~V2T-?{Uu2vH z(Ps0Sns#KHdz>+biAh+bx{+)8)PjLFkW-2EO)_69itt`oh?DO{n}SWd8gPhr{Z_7c zoaqwzsQt}B9cDeRcp&waV=-Ck+nsnH&PN!kseo7Oa6(xSVe5xD#_&WLH6Y>!0~2AA zOPdwY=>SS%vV@d`AjzmO09PQbU9m~H%cMWotj7-*4lp%K{?$hmB>xw$&HJFk;M461 z(?;2|R8@c04_V3vyMfsCf03MOii$A0F)PDGXWNM4Q7_mCzd6 zukBJojyH(f2r1+T{L^^>{(1Ouai_>eDzu)CCDoI2y>>Jio(-mqAEflGN5%V?6Pal> zft8UWE1UJ*E>UIYBIB5}Mz0T8S0%*s#Y=SfjqZ=v7@k_5(UP>%e(n6a0t3Z8T1kLa za{dYB0?d(E0|+SOe%QxtMFFk?BONC@j>S0LYpo0QlQhLKuYC0I^%8hEO&o-*y)R9b zGkDaxCY?=a<4-E)wtYjqU!O{^Q!8jIm<=Ey$oG}cjBaFPh5AwqXo~eD3q1G}X}7nO zK>Nn5@(?iE&no5vW9D`8HbuS1Au)EcFGUBd^ZiMNk!z#CTR~#@RQ-3Rd4I>k6`Fy9 z3q;%YJ6EQUn+=dfI>YI5>$BL5Wl}r!03MOA_Fd#e05EsP4`0Vhx4&IJ5^U&u`O1aw zLBmr{1~7z96b}fvM<1w`H6KglV_@2hZ=v2VJ;%>lf}2|l&!2pzR4DrjcDRcZ=9|A{ zy9^)4g|JKF4qb$+`iK!0ChPZ$sC$UpukVZk4IgT5U}kf9f+@20YBQXJ^9@&;QH$UW zftk5}HeurbOXAa3OICg+Gd8e5wye@b$UwKxQ$2smO}k<=pZOD<@@1E{nv0{-|ML;> z%yWW!Ft$O-ABR2>RDo6oW46M5`{wn^(xEEP4G*iI zoOU1avJF>TP>5a(_khIf+`nUX17Z8`NF5ei*6&ogRce6-aoP#6K$V%E=2is16alt0 zS45}2w%}X*YVSK!!k}M}gfTb`2)hW!*X*dEV?-LuGixSG>LF?C>+Yc1dTCaku>K zX?bHuwRqRy7~X3)vXlZ3qP-N8dR6l&@90K?huX*W(LQ_G6Bo!j^J;9?Ey3U93!bgW zO@KB2T%DSB7R7;YfceK$yXfB9e+z-1UTCu5IL?n9(@WMFH%d35&Cn9;R>7f=hsHA@ zCY+6C{3SL;|D{YVdD9YG@(~1snwNy;WHW2%m^*2DKz}qu+-BbS#69Y*Q_jDHW!QUV zOVZ?C48*b>OLrP=M0*$;;mH>iEF}IM|d{wqbH{ripR*x>(&bhlpv+^dV73Ey={4 zG=X@vbRW-&;wx3k=2u?z<7<-YRtxlSDSwoK06M}L8`f2J7V;KVnp@_-Q3NSk+Ozr? zlzug`2#-^mwRs@RJYM8UEs(5|bue!gg9jZy^JJUqtGzS^fN}aO;5!4xz`{#(i|r)3 z47|clRH7UH`Vw8&4<0f2!g8;1F@P{9w^iAw#}1G?{ag^U5ziuWq1B{4{|zl?#-UI# z*mph)6s#tXnar|JQKNY)h`Gku($-p@h%dckgYfvYRIFMR4_Mm&{Bo*JK4ii(OQwpu z%0^j~^BOjq7}lgJ8%b-EkvX9;h~Q55_zX38M94*^+{x};RCDt19+{ORJ<~eL({I6U zc*O$?hrrR@)mHw=wEN3$Tlo2$0=sH=s@ZI1&R-Zl>=XA$Qvs?p59mG7ZFhR4gZK0p z>lPH3jEwt^S| zo11l=JL44+L|Hv+NsXRD{^;{a0r_dlQF%Bew+a(sKxII$UYj>W93l;|B|CC5~N{_*QPExH(%aufM)yv37!?R2AX9Z^)i>G)hPr{ z@?W+|QjQ9#m+_n2o-ir=w}k$P)AOKF5$I8cI0J&}qBstFtAJz@dug_u5m~pPTzzTM z(EI0B8l|2#qHVsew+pAVQhY^N_W>AoXLX0wo66gl!BuAse)K!ny@U1L;X!be#30;6 z^g8FQ8DIegc74n-m8d)%?DHHZFK^fiY}eZD2MeJ7WtxDv4}7*G|6t0=1a4TCa~@)(4rH$Hk6KOt z1s^s}fowNlu&B-1je<}bx(M=FB$D|x?E{cOEmvm`MbS)Dg_@OVy@*5<<+FQk7b1x7 z(}`kkJ?gLy6dt&!1`Vof*kq#q*ksag+F^2vTCp%kay(Fjjd{zO8_&tXfN74rWpgB< zNrA|;ajW-@0x@JQTlR^a#`ytdf2F?fwF9)d{`D&)WbZC(H>Fe0^C!+cf6 z6?{O=6!XUO9Ha6cTldJ5wX%MFf)WD<@r>}Ixah0er`t7u3*?^*axE5Ru~rZ zQ{)Ujv8xBhfWO`Cn{;5+R+HVec78lux{-OA@NpHJ_@j84QVo`+So#qH&yk|{mycppE-^^}kJl#Nz0@Og$KNE2Z65Py_fz-hLG6m< z?TwV0!I>P*1&WXI7=(v1^-{v6T$1s{Gs*&Z$rp86v%_Cr!STBc6U8U+|C zz+V;9FdS z>gYSwn~^wj=AOx^lglV zEC4RryaB`GV{qUfWGBTjHRqU)YDOyL!F? zwxJZ2&9YduAMKdAnoDHv3CK(MwWhr;W36U%dWA1aVJR-lx`z`7D66>>4rQq3o;{LA zPjLpyJ}_!TyUc^wEdRIx>OnX)DvH#=V5ABCzn8yXke_e^tmgckXi!!il!xC`_k5Fx zMq4R*tguWWQWmSyW>G}11UyGpOGt*pkiZ6VIrM-5j-F-uK~4a^Z&t+`zeKOezms|lR+0Gfb*oW+|u^`w?qvGTxm5RmwRP&uOjT^ z=|E(dip-N4H=|j$ldnHfJ2eEGkZ)!kbrD0-Y#e)~(M1t3b!v+|5a7wWjFUg($6hb& zlBI^fWEux{=2i%hyZR$(f(YJI5Ab;yz(3aCGE=g=5%LOLT2$|NRPz!7m5_^tg=&KX zZZ6aF!3M*re$fwG9ZJ?yws%?X>p*8>sdKuS{cj2_A8kQ|yuW+0|bcSt@ z*qOG?0PR!cs8xy+`XFI^eTi&#(3T@mM&2_e0zRW_Ok+3!`%8=B9Exq56x)^R3Wv$s z0xp&Mr4V~%BUjM=L~BtQLXaAC)|oq^Hop78k?V>LOfuTLRz%w~b-Z%htENfzJ-*}k zAFCXy{ z#uPS*TC$>9Fbb7Pk~Z{^Me~Rc2gCWG>TKS7i~5}-6SEQ!{2eTzpNP@`zwjj(-p9b1 zqfFd?-iBIaQq5Le;}yPYl<;@IiMq;k>ou*O=YnU75`{T_LJy6V3E_iQzXr>~Ld?VS zjYrjlYzkJB98oYct+4$&b9B4I$Xq{D($l7Ab?s?-5qFVVk=cop$X&+2xP#vM9%Saf zn9*}oHW1VHx!7rfg<++E*N4?FdV}ydUX#A=spAV`JwrbX8U^>Pwp3S+gDq8-4bs#YLpmi+hO3r@&DM+=)1t}$I%Qa&z4xP9~wXrtp?|b!= z*Rh2V!{_eqj!4>5+8D;hv*?HA1>N4D`Td4t+Cb;UcM0{(lSIX1t;L-6l7T)BaE#LJU+gzkXN0zDh4K9pbR)gEN$h8to8k z{)mFw210X#KBWxZRp=iu@V&vfLzcXS$+Gj+@6=NhHGyIUh?+Z(0XRA?NZkjWVsC@< zX-udM&{*CX(giG#ReGtxFc=zjgmGD&O6B55!y)$@^bs_ILs=NY*0IJRfxNf?FN?E% zYUD)J;N&p}!S$aWCzDvcHE3u|=0FZSX2pY(uRwkoU^05iT$M)gK`u2R$#l@tY9soG zY4tTjQyR`sMWk|?jK|De(RCxGuL`N))L?zg))cE}c6Mq+%w`ne3 z)@M&P{?>IxKBCF7%!qbA^OQx<=s@2ooc?l-mA)_AU9AEX>D1Fq<~oq~5}T)UT!KL* z;ysUBoe3+tN{V*l2=ais+J3Wg1g~>%*EUUo<8mA8^>r>+8sbj=(s9L*02*h-&dnk_ z;z)Y~rI4O%qrkMpp>$02OU{+B%Z zUsryes8X(!bDiR|z4q|JVdj#Mfw|efpN2cC(VdVHc6CU&+Y-KW<_2y*DLD zA?j?qIotxjaS@6awEOB$G=@W76TO|Lg(b*n`Gd8jT0yX7FS%p_KjRT4`b?Map1%=w(fiSpw0R&F{38cUus-eSvrI!%j8b_ki1ri(d**S88m&{{Q>9; z4Ja#k(eT&RK&Ns(s}H~l>PPH!TQA8d{=PeCd+O|UnV#JNCl$kyjM(el(ux+ANj`ZP zW(uZsz0Yd)Opabo(r*ab$(%c{0K z2~8pdSaHn>OHBLS@wlx>jPQZI3K%vLZ3#Lomm48FQt&M-!)0G?J%ut~tD8%2IrWmA zJriru!axm1qe?mFYBR8hac%Qu=3(dYiStrTfr-Vrx+?!Nr!ABe1#!O6?O3&RuXt|W zJbNnjFHfOR21cj2#5ZeJ)S;66+w(qXNjz`B2)iuvpi{By8*nesxOunv6(f1Zr1#n{ zA(Is8(~;Y?Hmqk+JK8@-P3d2Z+CVCuin`wf4vyw8kEdjOKzj~@`V`N)%J>)IT>GAG z{9bRdKEI*Bxjs4{B-{yzi6^UMxazjARF8+)JM+=>iH+O?IQZxn3MHV;>kiNzLUELH ztxZ$hjf|wmVFHoyCU*}YzU;EmJ~+Th^(AJRxQfr&)R!2w6U_ejkC#Liwpi zrt&AtqHm{Y)6VFaZK^-;!9sE`207KE0-kiP0GGI~itce2-giseO}-Pud?O_YMe^Yv zT|tiW)Z<}=eHKVEzO}QQzT;o)QFCEH{}mDWV8f zH@ox&RCK&rTL1~W^uK253h-T}2J{5`ZZ07%%3L{rXrCD&AUDaO$0YPK0sOQz!nDL` z1H%K{N!gP|l71wSwH}+VgxnKZJN`ptct@p+dgM>T`-Z&e`3P>rPRF3{mH9k_;BlTA z_0c^*Px{yN@V1j!gtiu`>CT%hjNRwaJBYcLF=_^|{#A*9IhQwMTUOrOK6;Atn(vU- z6oZ0iy@^IPI4Yx`m8%u((LGmcJM`G>#r$ZD7H|*>_RwNhMzBDkvFwcgQOBBNV}_rR zpC_I`MdhBt1>=LDfm7!AqfJn`WD2rb$LO&VfX9it#LaQ8RxH-I6U{57;~dG_O3==@ zWxs}NUBxp$l<0%9A}=dv<=5_+P){}X%vw=&9>3CyCj29e`!a=KE8Wd_L=W^W^t$*C zPKS&T#44!DrVygZLZRKrDEQl0a|HZn1p}v-!hZR%9Mu#6U$-w_odxm!+#t&DhkgYW z2TJ5j2X{dljM=e&ePSe@84O6?bIXo(#>64~NkjN~PJe~EO~`tHD#`^UHL5`4x{TK8 zs|*jaHe2=PO7zDPx5Xu0Hg4FQZKc5*nDnrpIA$bsfYs5Tb&e8^sc1DFzJ9>4G);z$ z%;!uKLa{x@OstH{93g5?Z^SOQRa)lX%OdviBO5g^>iw*XWbiL?b2wS8i7;l|VJjr- zGONYV1G-vBF%kXNpdic}%9CShb?Lo{CtbX~hwjceV~O!0JUbDzbhSK83UQ%V(MEyA zqH4-3?3y$-SypK3tOdL_-( zGe+BKG&|=y+akwEmK+;viPgRry;9@$Tyj?np_zqRza&0Om^VmA=L#~yZU4^jU5?_JpYJlVQB0xPhzc zL`&Hf^EmUcn2Syv-R_L_$C3OLpleQ;>IM>D{vWrqS5^FCf4Pk*ZlAGSF3{#R%Ic3` zgShm_HOrpCOQMr@|4Nh-0xK^}aA_@fNrxvbRk?q7xNJ>+I2JbS8<2)_K%wyn>d^@$ z^>BiZL>fF^ESUiUGHGHr;YriqM^e=IFYAr0jm!ALx0}e>)w@P&2k9vR449;9o@0|0 zRf=@W&T?Mhw0-eD+aT7B$VE`P)t+Ct)y^7bMmP^Gs5lnry8%;=#z>lbyxd+l&suoW z$enf~1|Ohc)(8tiqW)Hb8Gs=x98hlZRysOoM363OKQ2AjaV^^{C}W(@tcqz9_1D6V zl)G;KP9Bz16TSp^CTV8B9zB}Cj_uS?$Bs9sDTJ%uVJ${7sIy>lRr#{M^OslRQk|X+ zn?AVNY{&nH{+&*{u~anWP0o3iHo~2=7qd-@2Ax(=2~_fl{v&C>3otx4{?usM)=8jLf|+(402n$PZNz(=u{D#L5;-cMtxU@;{uD&J?PZQcX~3eABb!OF0z zwhC4ABRRz`$OaI}BrVf#^?I}(P|9W}DWt0BoqK?dc-M(hK=JWf4Wq$u&uu|V0=!gB z+#y`nQ|47lDoTjo8p+2)Sg?gA44Y1574NX?r4gs*mY^JgRtBX#dXl{Q24u}nrKf9- zDUPe0fjP-bY}jt%iEmg>D$RNQU+J<3hrrzh!o=J_A}1!Se&VJ4@pdJ@@RuviFgT>R{{5yYaZ238!T z!EzA_I=oe72?rRmEmcfV7YT$4 zarmNUx1*+dp}L_QWZv`pSXTY~2|cN8WmocpFYEdqkME#7Ry*GN3uT!Ya5207)Xu(W_~^8yidc}HW3A=X3Hb|c1(OU)*d1_7u=Dd6R|WA5 zG~n_%)0?G;QwK)LhW(~g0WNwSb@C&E*u>SuBmlbU%4EYmS zkr+9t3>rSLVOADgm(|)+e3o3+Dw-*XK8a2QVTjEon*JdU*aQM{BvOkHrx^iZsBq4! z>R;b2hfw3UbE7r8d&o~)5ur-i8-S}lp(c|D^qmVw={;@z$)j6NO9K`^0e$nfy>mbk zy6)6W#R+0yq#vZG2A3rL<#V7ciNHOsXCu-+@nV04FmF>{Y!B@Xh^4NsV;vlU7PzUU zpZWOjx7f#P#$7tph2;d4^i{^MXM0JW?LyE1r49P4r;+Nf;G=pI9}BUyZ=&Cifj{u~ zQ}z*3fN61)?=oUX8(iN8u+ts4@2x^r2ZvWIA8g@ObO2^kY{4b6D((&ZkN|T*9*?>v zE|%3&iyH%K*mwCXJWKWm{^`stu-n@K&KP&R&0dxRD7$(LCZN{sRNl)2L}hnMk0qI# zVya6?eeMsa%-U~J_pV-<@K0f<@i?<&2(K-Is9DVPh3o^q9#@0mgZ2UP@ofKxLcSqR z0CV^cRsgganN`w-sUK$a8*=+}i)Q~&!o4Dg8$2e@CtXvnZCLu)f}_%WnbRRwFM%J9svhi8wG$uM*?E}iEMi<=6j}TOMYs61 zy+P-23=KmIh`)!WFWPORu5l-3uaVTA$WW|pFhm{q=#;4gVpnR)Wia$2Tlj|5KX7Xl z8k}H%12Lq}9Eg>aefppf>RK0$j-k6)Lo6tR6sHKe38hn~S^$?vj=LGMmR#s-rfWy` zM3=xw`%)cy#W?V-i>ndX3YxB+PjrOX5Dn3`*)*93jm1gRr zVENas#O-H&u<$miNt73P;dY@gh(nS#5BGKPafVJbmg0O4v-tpzg9Nx*GmkhXWz?Q= zCAMnwTuFTRSeqK9&=d76`C&Vq;)MB9c+xfYn~n2nT*dC^d+uuyU~vv02bF!DmSei# zuQrd$hWvYBG(UXETKKWx{^~6udT=*-KM>3te^F#0Cb9#t24 zB6{KE^f-O0zpkx{qS!AUBBN((xN)F+P?Vt=M`$SjwJd#KEVl_*uW!rU-)L+MSl(bd zD}c>{IU^$%?Rz=n5=$zWceFlr+aiDg29YrP+I-$OTuDw|+Ydr&6QIMy#X;(WM=IT1 zT`6E*8jDBOWdl|}5k3e*7)&34C#^+7=h2^7Jbt%V8NLpQbyXao=dHpyILk{H8qXVX zWq1uabt)V)UnmoT{!Dxyx~J&T2ArV+n>c-kzycL&bS%=}Behlu)MdYJoYRhqSqU zEs~av6y!~=KE$X%vbA@Dx|43*{N4Os=)1$BQ&jcF6N@>>&^ce=hLSVxqYO6{0L%U% z17d9lgm73FZxhayuoK|~Brp0U-$iW-qZ_#PjLnXy^6HNE>Dm{%xHB0fuJl^LdT;#~ z&_81rvo{pl{xnZYap403Py%l4LvjqA(6OYr zj7sHi=8eI?1%yK!%3(X%JZ3 zlYcV<9)MJ@9}Mq8;$)+p@`f?J0a zXzibGUW+|SKyhC<1v{~LooQjA5Byq1YMkaSn)p~0d9hyy(m$%#H&B&RMW%Gd_Xxv{ zgyu*AaIi!G1QM&)rsd-C`WNv>hD^Y(Opq@w=HUuRV#2LQyz=-*)tI<6kgXemPybVk zK98?p!Ni3#Gg>-H`Lbc^s4s+tvJ9=sO0;f{dl3ogNcpn~*==ZWDY=8xp3_7LsaP@u zWx@%C+@AoORc>e!>AGp^Tk!lrEItme8VD!4s%wcF;Vylq5L7E~y7-s54h%aAx5z69 zOz}BO_|6YXl$ka+4CU561}J1(yD4a)oqD{>^6pZ$*cQ9cLC#@gz&$ zQIg_(iDI=>`;yk60BE`XWn>*F!#2hMwCR}r@Nz>3j*CRE%nrAaaiGCM5W=sV;;}-r zgB&nH4lFL@Kh<88kZx`54K=$7=i;TmJ+yb9h=+EJWWfrQ$aynTbpr};V zu=s7!kVGSX;)J#*@zV0*Nm_RdhLE5l4hZe(XD8z>W5Zi*#rg986xs>*Pv-g_x`6_n zi)_KJv}^9j^q0BC3zHD$f@Hb++on8T=y4mwC(H1m(uB>OW}Xe<#Cu|QN zS;g*T=EYyJ3eDm0>Oc3#bEo18lLmvPI+oz4E$%#2JB{s<4fiyx1iXCC6RVKr_kDz_ zX^XrG)q#j)8Mn{8bD%N+dBA}?9ftx+_Y<>{WYH4ra#2&>^#FhX3#Bb2PejAN{Hx=( z@b#dWfCbwuh2Uc;Qh)bt-)Hh*gyipui3)Edqe0PDfeg2yg}T2j|6kKV1t+M0tEYy; zEmWU!U%*49G+|e#3-6R@t3CZ)84=)Jw0dD2<~3HsCdrysz>&;D<7_(wf0e;YTyd&G zWJl%iD`H`44aUtuh6#(3Mx*e@@C?9F&Xf zf~{Ifzuo~)LVfFwkY6ZOlpMVQ%1b4tyA_i&bf5S<#( z?sUKkZYYi0vVZ`glg&x|3V4&FT^fOWqo`=6U~pEmoMO}3_dck*DHsr6q6c){+XM65 znhx@KAw_@(teL4D3}<`_=VmC07ggIu;Qe%l1a1}s!2Ww>{MuuqaIdB z85?y#_sURU(g}4Ec!D2$i?|@iANB*bkWX^eCShBN|Ee2yZiLezL(Le!(aK92h%9-e zLkqBPLvn+BpSa66^t_x9BsyQ4V9tX920c~b84(f}^6%^J9%CHbH){^%N_lVDH~z29-=abV{!=OIqJJB+%X9&4Ecli|jR= zrzLls7kD+)DmEm|hUWr5tCZr$QMWus$z&+5cT5On5rP7eL?Y|(As5!WBblKzPfc^2 z^}uVya=-F>&g?U(#(Eqsn%2M_AI*v*FkpH>OJ~lLp!1Gi8M@d?bD5S~9NNqin!~NX zzFMFlHFZTB6udJ=A56##wHOw_7~ZW@Xje8i0;fU7k- zBDN{srj6JBQuOD?;`OTi%a=6C00)U##4#UR8sFlMMcTCFrlPWeUc{f_18V}L>coaz4pCLPSung^IJ_<+x@8V$@t-siV zhPkxYb&o?DS^=hp+4!NH&%g?=SpPaB+(QBkoD z;9@c0g`9H-NmFT1Ol*&8f=!cQQLGFy*qv?vg?|wM0Ds^=_?p#BF=S{Y>4GlKzghA6 znOVvpA=tH%muzd!D-_&Q4Y>g!QZt*VoV`OwAp}1>MI#Oo5RunV7A&Hp4EqQ;G}+Ts zl?u;L00T@hST)~NmC)XnCqhLn4etY}uqRvtPFy7*CM$Yul<;AM5t0Z=c!_NIW4IFKV)xEg>^t6wNCSoK z3&1ggiN3ef=W5iG4+xnpRiFV92pM}E5h)tk=Bt(7v`cuhVv6~65T#$}q0fm&{mGFQ z)BONB+}EM@^i~nqMP~y&&Q179X(wCKa_n)y6Z!(tsP!Mxfh`;YzBrF#(a}6^gagxh zU0&!(HaiOxRstRhpd44_@+X)Rv$(f>CN{MJ#RjhXF-p}CY?1)QKSajcS^wJN+^kRr zzTspheA_a7ESNOvC+%}o1nEpGHf8-lJM%;DvR?lR*50{DD8si->bvz1Vspx0kK{!YI*|H-V|brZEi-2i=;atYpchR@`)-=vN>{s$GZ66Q zjzTvg^74XIaE|GPg3Fv-$nx?I{1oAV2jI`30KTy|pFLYZQ&s8V<)3c!Rq+ark{j=g zqxLtXvsAuYG1&OBZntrI?P9#Q^)|S19F79;Q(92rHqMDm)`Ylq>M(JgiGN>^d;#`U z0RDEr>ojq3geu6Ycfn)~t4gYpX3SLHh+2BrPd?o807+w5(uRKv0Q&?TZ?-{LiNlSw zN8=ZLuH2%Qhj24YnFc7uhU`$tRltl}Y@azlhEdI&YtU>nrWnQxhIF|^1fT@86B~}2 zNT%59e&v4jvFVL~05M?z00S!lo_(xzivIur7jw~0e$W6^k~~O&u()q%ZGxf_0V<^j z;5Pp4!POM4SA#+EAWgVLAA4CN(lAGE@El#9cc#>hoIOuK8zy}NMO}0ypNNWHVVpjZ zH^G9tKvg1w1n1qAN_0Nhkc|tY@C}_a*HX!RZvJYOkLCA+ADg|j_{kU`y(P^)foD>rOLnh%VJ zRhbWmI^nrv2@Fu!B|#DcLgJ)(UUoTfY;f_3gj18q~O9Gu7pajp<)$Z21pw{ zQ$}97<-g{3hSHicS|=XBDBqt9(~b`OAct^_!^1MU#1nEpBq)5M$?o7 zq3<}N-WQ!;yfXn)bKRv__>DuA`S5Y#S%ML9zNM&CJTlv=3RQ{ro(B%UCpfHvAB|d66ZmewJSWz z6kf4LD&If|a~+XvlPOcf3Up?8QBRnd-dV&ThOaf+4|9<ji8SAP zYLzrvXW!Y5zE<3Bk!~HMpaB>S?q1W#!A@pV8AFOXQ9oK&o7`7qkb{tbJllokh>T4! z3YD+bfC@}|_6HeVcpAx_8Ui&xeb837C9gHU!fq3~1OO1k;b2JQ^3f@9U(W{e$03a> z85$PiTucH-*@egi0(eTEE$M8W^Nwkg0=|HLJSq84io=Li%1%6jrADAbyd~Z7jM)(7 z4xp&&Pz^YutB-e{4ldMHKp^70Gy~m5U1C&&;<&oXa_9gn3>ZWecI}lkMS!3HQ$YX# z1I_`Seav)<{{R3N&vb+9!r(M9FwLvdPFdHQ%MNe|4qke1A|F{`xG9xMw29p2AnQR( z5Ff<&eUUe2P`h_XmQcv7I3dHKnWq*ccc9Mxh8L66C|ib zfa*9POibEK{H>@BGEjs?e!po0IrLe&A%{Vf_42m5;!qNf&U%@2 za2*5S7z<)ki5)YFdJBuIoM_XtcoXhJZYv}ICC{yl!~{OcRCV~RycEQ9{t=I)J{Ihb z>~@-{%tat3>r4P8*WkB4)d6moDtJkBpsZ{iT5wD7NmZ<0IjjHPkc|F3$8K>ygQNxB zK+Ux=;uSc}eSJJCE36q&sog4QK z!V#4j7?z9A!yC0j>5rhO$$TW&J0`IG)Vby`lwY<`kZVPAW$uw9{trP71*-JH=Pax! z66j;lNtp2I`N%c)PonAPSnueNU*(GP>ARk-glL%HCP8ojP>xtl%t#?rssYMDRnF6u zWxH&`nv)%WSU_yLN&i4uaNBnzvF}$(7N|}hWjOMd4IAK^Xgb9L^cSW`YXY*0P~f%L zsTrsgZ^ZkYqr4;`M1pTL96A7*dpHmX1ORv%rQ%7F`{TavGqBkRJ&rUP18L zzzGw$#qSy!5ZxfX#ESYYi8(mP0hmT@mb*15$#w{iRRB8Cfn?=67#e;WR!SLlLl%Wk z>9<=FS?N}L=Mgv{V-gir6A;P@m0YIzMe_Wov$cdhQP`2vCmH_e6`}Zu86gGnUTg#6 zwD6Rk0Nvqt=`(-5%X_Z>37E^w+mX3>R@QJriS8ZH1RjfLhIIg>w6*_43COC`BA;y&9%9|? z9~A9#F>4cr*U20WO)^S9`2<0F~UoluvFLW&hc0THPIqL-=i5*C{Jx zn1w;#G_U{$#e<_O+W;qNOtE&vLQf?cX1%5rblTvFC0;9@Ez*Cpco?> zeCM2uH(rIpBsOkd`(hei;%BxlPHz#J@Vb(Yo?BZU82HGB00N~J);eU2f`+iq>ziMVX#+-w5+NXq=%-+zn z54oyuZtE+gr4kBXEI%NJxPi2Vf{g7c4cf&vH*-0~s^n5VvUO+!$02(uxf}Ng?9?Mk zdl-%8e!9(mv$p`JZ3uZ>c6|E#TN^L8XfZm_$E^1?4pS^c7ZS<|n9UVla}$V@$QlQT z6*EbP7tf1{>pM?wobzgI?QLO!ADUnImewc{R^KFAZswm}v_}4}fPFpw ztt-6KF$2+5JYgS-H#jaDOJDU_c9HqxO1xC>SfHx70GoPF8NeHP$(}Bs`Ep>tbKRjf z`u`f0XF{>W=nw!~Euj3Uzg zWPrzr7_d%xa=73ah~@Fb3N0UZpe-LOp!&I2fr@Re5-{k%W$*@Yr>z{$6pr(9+=d0hp7)0U2-)g>qY^m)!eC>K|K>oZQ=+?zotgX$$ZdD>QMvPbYZA;3xg=H+}(k z0005`L7IMspg>z&TU%ROS|(Ef00RI6{{R3302AE748obx>Da$42be>&@3B$WLc22# zdY}q-jmw_^0MTH@uMu*jpz+N@yJ_Ti;P?PHaVyh$hBO9)etp;gi0O;SLkPeMIV2Sp zI42)-0AN6U@_bP;GCJHa+O2P!5Rj`(rJ$(WRJrZi4Id%2Vn6@@0{{y^B0P+^Uw{B5 zct@bty%+9i>ab9>dVh~(?-4Lx*Z=@FI!Is{bPi&o-~FY6OnQf@wmQ0bg`3c@sAp6F zTK*lvma!-%37{dM08V}<*1B-&4yMOok~M)K*=P`6bTA1QnVI0#j1rHTY5NevCO6Zg z^fFg*S?nYho7bgiwp+vEqC|rzmRlApYtVGjq4oBdT-e_1fx{d4<_3+QXYd5r*pDuF zN@$aU0~VqDANY+srjRFjl z>Xspt@Bhmnc~c>G^;-u$$`EW})Rsj`3l>>0=?|{P&r7cxd{$tP?vh3T*TP@$3j(Pe zGXq6oQZOzgPAPCNJKb0S3l;_otz>6t!sk$1T9z>6ofX1xq~rjtfB*mjUqPOROnjh% z9fuaQ$QX>$ip5}|Ifp8!;DYiu1381o4cMn?qSQNA_CYK+7{()Jfw*k5o- zfmakDZY9Ais956mrh>gD1f^!FyinIE5(3SZ9AcSfW3D++4R=BLcqla%U^%Sel|VzJRlqFUQD>3gZz(%3@J=mXU=xS z9%zAJoN60m8iAnPxDu8h+Kaoo;y|%T-mo9os!M{rx=`zVOa6*PjPKTJ)E00lq{8gW z=5#OcL$rXRamT){KHYf8I+QEQgRB_co%e>y<4aNN|<<%Z!|j1 zqKCMmy%Zp}3tvDg+Z`P~Ekk!?yMw@)W{8m^!Eke3=V(OZSpaaxy$A&Pa}tWU)O=^) zfZh|P;fr7b^SO`!0PY3Bn~m@?tgy&0oUk7PR2OH?4fF99I=LXdNy7_Jc2fWj)mfP- z#LXK+n)-8YML$|rIk^YmVk&?v`{Q3cKU)z zs-d%S=OC4wDy)8%^}T?1n5c$;v#yO+6e?F5;BuGjbaUet{cl-0QisExPXlw7b`8+2wX@ zVMBsA4Or$n(T1?n#yPKYGyXeBWeD2kl6ztDZ_(ffi>#sOaW-6=RRGLTP>GUg(%1of zOPkwv#AbW|0CmigWCKG02G~}jD!qt7ajuxk2xtHuOkwnOCoz#FPi1{5bN%Nk8WV^_ zU;_AW!!-zMH>K_%ory-K3Ot>`j{pZR3~IHm4MIBVy7aGEuBJy}1DtRG3UC&#^_5|T zRd&c%^jVN6A*dVlOsl}cz@De0LS$fpZ>|x_yi4%>vMyV;%{$pZIN%O#`cD)GT)Y4U zQdwJQ7P;gg1Y?&z94N?Di}YZ13Y!-L->9aw8GilUO@JN{003vZL7I-{pg>z&TU%ROTP9Ng00RI6{{R3F*rX?T8XEFWX+3OuZQ_h7 zyEQsqpmre8em8xOSYCoUA#bvl10nnYg z9&>z}slx>ZZn2*Uf$)Y+qcH^FyJjwb2g@(`t^Ls~A{eCjRnH}~=-4E>PNh;>JDw5S zD*aM@x{MaiRR3QPX%dh^w{?&hv{qD})hrFV;yMK$FPpodd|37>T3dxXg|pk*{DfK8 z_cOnzOcBTAuTmZnQF}EJsMwlOm_XlW7!T2Mv}gI{h$!)KwUAf>6zEl`rAVVZ2~>D)WY=C)f(R)ba=S%_cCVMowmIRGH(-H`?rB9 z)S21}PuC?aEX^y_873b_39(N8?IYeN=esKxNIr@5 zoa6j_(UQ?YYxbEE*Sj9D3V&UFAN#~TyhwcDN0a^Vmvx#DDn(Bkz#z^NVEbx_UR36G z?2(&EESNMD;i_)6;`Anfn+${YGaU-XuVmsj!-(jq03?dLXoo-o+Nhm%EZkz?864fh zf?zSizOL&TY&(vR%FA&^m9E+-83?TAZW}3&4>P5ktZDr(n0~;&=o$S3a1pRxUXy;_ znj`x+xJP{WcXbzrA%>3KNJbZVdqvuS8IhqRIbkr`g)eS=6<0;MmFYhMSX5%ZuJ%z{ zQ23SwrGB|b;r)SL;=)^&ZF<3fh#!GFt6yCVk)_0qNX z#49+I)b*MNp*fMPjV@k})T;&ZKzfIW_F_lABa_eyYhDIX*d)XfCU<}YwWWS`Iltw; z`a~}V()gAX1w2b|ow&lQ(~hl<05L$$zjU{8Pt2F}j?Jj^3un7(%a33(-a^wApCR)k z>k#|Oc)q6e`w2jRs+~?HyT6^xJ<3Av48UV_2lf*svr-7tA+^;#H#Mn^JP}3u4=9yeCvoASipJH6G>h z0^=TqxV;-9f}?Q*oTiCczDoN#Y!ZF{3Y~0-iwImt5f!QK#q54OXE}%k+B2<(Hq^8O z?r%}U1&Qkspkdj0K}?!pe8)hEei1xFI)xQ5J{p?7cMuhQB|mBzESqeSLB=2IM9N7 zZeU{!ZF1Z7hXBYJ(fLg1;H}!Zu%=wP5bw~VV@uf|H(3dU?>e%QuQMMARKtti(q4I8WK8cD-mcm^eAK)dLpPebS zIoi<6nJ(c0;IoRiA)M?pC>n2X)@n!El3MJ*V7W~M!HCE`d}6Cy$XkSd{XaHLPMe{2 zT>fMrZS*lB(4CeETzIX2`7c4B@m5vKDrDNGOD^W4@%hRBSPB43hD3JpG;m9>H;;j@ z78!LaEj|`J>kp_gmhH#Y%OG^m*E?zxgUxo-|)8QLq1W2;}JxF zJl>7eOOH6JrjC^x)KlX>Q#x_;5R4eozw=lOUx^6`g5qboP-rF`HnxxHQ!y;x%&N*V z_UHs6d~T?EyH%GX7(d|C-xC>3J{|)K0E23r-9+E?Z|@R~SCsD8Tem#~&&_MR`CXYK zwX1cBx7XZlsCT2pBF8#^WuCmce_;l~W^XhSxkbvX464;1?C~Bz{jBlDLxau1lsWV~ zPG)+|VQxk5RHT;2exNJ5X3Dg?p-YHuMYBamwhak1{y4+XvySp5+Q)(C0fVa<(|Ojt+pt^#7lSKDfg^heQaHIW9?|W6 z9D7vR%f+(V=_&!npH18y@ZV`p;zMrW!>bHukcVW1;}=I}DT-LpzW;PwH=iOek&klN zPlejw3&fa6!N4oUwjj_<+&sEfXS%cY37=bTXID%zvl$;GT;kLWXJ(GA-qqh*etnum z5*@+TCd1C^mjZaAM|x{0Yk|`{Ck_4Lm)#3Dw&Z^E6!(I1dUHx@<)CR&V7&hm__(v< z0qdo_{E?y;^5e(o#U|eBjF5d<2+gqbOJZ#3MJl7BAt^f+z19*C6zyaIU@te%JV|<`T z9W-nI&D)sMd?ij?uqYvf?Eax^4j;%U{&kjWf0Sq4e)MmZ*AqW4jkUk}GOVfeyaq@# z8;Tz3AWG2R!A-b&^|w!m%APk3Wsw@$Z!vwwIV)pPjr`@Se)2z4c85hysQ&DQdd2CF zBP~u`6?#3c1tNiSaPFFEjk4+czxt0PK)X^ThH&0@C3r^T#o!l|^z&VkI-jsU7j-{# zO~$k5JX5ydE9F>qCBpFrq&)|g9_UmIYUj}7+jDK=r;trdWk~nd3=BY*iQ6MSYu>5O zGhzCp2YQD^EanqN42stA(Y6PFLvrP^GmP_GGuquaqo;fPvUU5*SSeLae|C8FO~DqF zs+B*rQJ8J$P;-I=(z*a-6$G@8U!Vlii7#ba zTn)bqlJwXOkKqxcBy1+lNyY124Fe$1;g5{KkMZ0wE%WM&<~`Ymx_})+%m}5R(**fN zq*_BiT7Ds@DarwT|HFW>PvUU>HwjdC&{_(-@8#wt(fhD7Zo%4n!40E9uji!t$4GIw zsoDvluZn}F04?M)=ZuoWpKGYK-S5t9pAG$h?OY{JZ3qZ~XLBs1&R2R55umIU-o(fO zA^R3^;mlrB_)M{dv+$faS$n{HIxL zX;*cPoyg;(zaqmrg35)ic;u=)(=xXo`V*;Jr`Uy)a&2<~}EWt0gu7@T^> zZZ+h_C`1Le%CIgCg}FNung9{Z4SKTFXF)hfapg)Fwa6feg67CWcb;@u_IWhz1*K1` zIocTru?6;qqy>p&G6J3z+)s^#~#)Fb%H zxToT>?5MVi#%^vo96{IpN~kBNuLIyqj!o84GilxPupoCmF@{g&4Oqp|XaPdI)I;Pb zPgJvrFOt=ZQLc&bsrmfx_#^euT8|{H$xbOf;87yj5Himyqdi9`(LjAEh5s97?tm2% zN$qJUO2mk@1t6Ny8-^&U(a3W~MvSMFdagp}`iA)38!G%^-7f1-@$D0RHG{e2Ekm(5 z=0Kv5hBm<>{O+MHri3NX0frQp5XwolyP5#gGNRWmfsaZM=zGsztvYUT^;fjjzV_;Y zhC~gHx?=8cU!kk>A?dtycaL}dpX&De!WbooG^@7D@bhiX50ZF$`Yul7H<+h)%)tsA zePe2Hqy+nv&A!is>#rYp++-r;a6o&r!?y0!PE46j#N8Zh22`L`;EUAVi^QEY@s*y* zhSJXm(HA9u5fE^%;qO;M*$Y^>WTsA>SCVkgZ+Ip9zUREWmHLWocd$bdrMN_QXGq{3`*qv( z@sW4Y-U;V_cdtJhgT9RsnbrxY(0AhMUJHXP_L6;R@++OhqN8tz{xmRx``X8nyo28z zB7Py3OgSd674f*+g2H9d}S)%1`spDg`|MoF2{EwF_v=x;yscS)BQA zF&Z;>Kuua504=J;m`CXvF*soVzA{HRrAmL*sJ}DR^B)@_4WFj6NU+u22%^!tc5chf zh9rnAlfxOukwYwcd*QY!t4y~25E5;!c8b}RvxoDjb-e^RM>mDj#!4*cOrMm`R z&l`-!`(#>p^!n{%t}}KI3{!-VXCBH#z5o==cqX`yA)v^Zvm;DCvEn( zgIXH=9;A<&w%i7#t)zkvN^oWeC=6ygO6};1e5a1aI9sZsEt9kdUv1b%>>)tA+;1Qp9WJ)nrS_{xKncSw1Es; z_f#V!->|1y4E&R3TEx*%CX_!j{1!!F|SnvH(%E=6V z8<`a5Ic%(Ggc7RO#_ zG(?mPiVd-b(IXF7s#J4?zDV{5n^aJVSwX`zV0zWs!mU8zowhz3bM6)ROdTQ(Dc=%0 z>vB$<^B~-LjT!X=0zJ06o$+MermS01CfSkBnzyGnBYu`+SVcl|JMi@$eB?8|?K@=; z>&bR|`2!c^0cIIuCg)8Dqtp^>t?w{Goko-GH39ZZwL-n@#^Ls2?v@gkQ*C*xC%-mw zIT3yBX}H8t>PXL!5eh`+_N`LFD4E0##RpwBTl!g32g!YNIpB8EOsENbdK^=$#EcjN znp%_R#W7=Q3fV%hfCFq1_opfd1#q$Y=!GyRir=T(K}n*ksd)CisP&MNJ{j@6ro_!X zkc(q-yeFR-1ErMOeH3iHmoo-JeqzV~z`Y8D(^TOC@5e1J0)`X5xBufB@YT{8bNq0`40(*VaXB)y=V%J0%&yDKju z`c$LYOQtaLb09nf77+y%Q3RNp_f$|#Ogil07_$iWigepwB}u0eTa``O)yp9>gTg(A z0R0x@$jB60nKfFDEwzS(z5TvHY{1G0UY97ES4Btj5JRkqvyB`ziLEk|8rYMbRo=?UW}2pbGUY7FkMP z&Nn52CN6<|{IC+V1}!&~u^ub}H14cz$#I36J+6gG%h`7*r_}h5E1Qvw*rViRA|J&$ zU61!d3w!gpF6iBfgVUC^kUbK~vElgFUrWn>pJ6rlM4bU||Fu*|{d*P4Y1d!XYU;9m?CKqSn3BHt#E#^Ic(3-^D#OU$oZp1}hhv9prsto24A2_amIf~iGSlps3iz#GVAx+0hqadS{b*{~t z#B0!dt)s*0gD0Rb4*46Z@Z%7BN}iLxMiKW`@Yw;&5E2A%Y$k~&a(QDk1%BLnfBK=) zXUFu@NR;$*dYZol>rGcTWbsRCIYH1e{UpWa!l_GU-L46T`x!~}f_eh?cI@(@wc}@I zMk4bZn^t%1b}C^eJt0a@cP?c`Q0YI9Z0b|Q;aE@S@86R+=|{M^m*0X}8DOTRt#Ee# zH_TjpC*4_Cmikm=X4h|V0!{nbBC8c<_}z@%ShwOEC6V=yg$uRm|MvV zjacte;Aqj%Mq;(-29NRZzgqb9@`$j>UZEiMjx1ZN)}@5WqdP-HXA$Y_;PrwM1*SJ& zabM|=n-wl^RfD9wZsxA=g0n08twxq#JjunSTAmkE;)ZUmcF4=D(mr^rf^Emd(Q&5Q zj1L<3-~)-z8PBPxbC33%5P*s_G}47|py3LV{l=Jm$MhfI%kPfs{8Tw`AYy zmq+qdu;6;`{Ftpw!%;VwII(9o1=nKfe(jOa`wgJte>>~d*@yAcqV83)MaF~*#xcN2Xlg{%k96e} z)Dcp&F_4fuO8F>kh%XJAX?PNiFjSK;AJm-@Jw8&+%wk78YunJ(iw7$u@0(WW;wE8o z48XU!vdpab%#yPRS5Q^38G008eo{6!vrh}Dh~W|3_LbA<6pyvrUJ&Ur+b}=Y{^tBv z3d6B^yo#)prCYeSL!y6XPmtmhXHidatYKukeBy4wE#gdpjQW?5v3pJdCyR#gf*t>F zRD%`Ckxak74~Fef1r~J!-=6q5)HA@Wh^4?>ok5`9H7(|txA`U+g#aX}iZ3be`6 zME@|!0$eNE!>Y_-lIQ91$O&AS{!u^~%TaaLmKL9Q6TEitt69!X64ncbq-TE?$5?z-FmYNV5sT zI()8Y6_>ltEZxSdc&x>KW8LU z_pUETfP1uUZhLSN)P2yV#)_ia`yS;ai!a`cfothX-F7JzBdwzR9Ds|@%Lv^_*83KQYA=SSU#0dYU zbNp+3BwS0@gPA5nj9(BZ51>^9u3Cdu9iH@=vSop4uY0z0etbzi3~2(D6)i= z>EFIY+d}IM8$b5E)w~=IewA+Rj$UR;%uT4VU?dd@xP3J@OdR(RP`t8^1OoX+J48z0 zRvK*Km{paVx|ssgM0V;7eJ+k;rE_ocN`!O{{*=imOxN5_kIop5(({B&%nosuB(7m= zE|4TQD-N3VJ+XJDl#tYXe4LN)qfe%Nyb3ibI_9Ld0%S6O=kl(|m|sRw?)Jr@03WmI zKzH~=L8KYpeQHw0wwj$4=5bP+u3Qrv_JHKP{c6L#j?xKTq0i`+M}RZr7IrAeWGZDo z&1nDY#A$}URt8Fn3N@yKqyAwNp+V<>WAgJ=$~y;vO@aAL$V+{x3ex42r+ZqsZ||yt z`V+U_qm$N{?|ZdIxRkw^y&nu~Z~i6G46kYK^Qels1i}`Zb{#kj2ThxU6E7x zPY5Sdy)B}853{8(XqOhKB}kdv-Ll)inMcG?^X8SPwaoQ5}T{}U72P4#1nR5jMzBI}S@Kx7g@A23QY8G4}vhv89SdXnjT7?#CVq4k!|P z;d7qQ2;sKx^g_daVr64yPNRC9gfEsX( z7FvtIxS0++;E`t@I27uBW~I^Vme<*yVh|zllx~QCv~JZ%hG2Modsf5HY1N{4k>eIJ zmJCwbqBw*aS&H1+QYGn2f46fN5l?w4G16z}*N-$NIn8}GTV!4@YG^t&vwdn{qT`1 z@2-TH-djZk@QG*+s>wP=`TiRv>bBA~_SO^=wQB8V@i|*;WgliwX`aocNnQ3H4cXhYf(BDdNZ+p1N+^WR1 zK;6F+S18p>8F?DIPkCwt&n%#5^)yJ zGF-#PunRZCBGicXBBXlAV>778-9hrl$+Z|)bof)fv}Vl0X? z34XgAX*!GG*+S{|8OCZs-gDsNQf8{byz2GOs^lgD==J*|l!^*;_x*x_Ogp-#r&}ok zl2dUM-&?~(kL4g;xmdSmf)y|-=b@xoNwrZErHa(cOUPhEo4yW!phwiuIy&4TRxeHx z*zY5nQ0BG&mn9`2PQ$yUoY{zhK^m`r0PUWMu+#sF<DS}Dg{(?)h&0yCaK7V*H-Qt&zKuM=Em@B`*8Y-?nnA<2}i-^c|LB2+iL;Fv5w+WG%ynF$YtB20O6SGLFSO9+u9Jz3P8UVM{nTxPt^DWS4DRMGo`9UX$-b*qBHK`l9A#iT6F zL2FfF8!B<4g8-HAXS&||&31zDI?oEbbK9=5?%E(MW8PI2#=|h|sF*2Qan2e8_Lz&A zclywX5AKk0Mt>b^@}*MyEr<2u7Si$Lj-`2bh?x!qOrNg3)EqL;f4TZxpsAUl3!1~pGmEQMXfd34@+@tg{#wLnbgzaZSQbi(XhQkb~#8-pRB$wo3JWW)Wyu@W>pL~=9}?itbnL9L2u#CaT7y~1TCl-4B zngNF(FA|1Hc&f0MnAFt+y=7wP%t7V@91W209PkcqmJiX=X?29+*`sub5)6--qQ13W zOtev+Web5ARnF|9!;&e=;QMRn0UQ9+*FqgJ)OSej}WPv@yxOmEXxgtFC5n-_Ur)4(8K5C8SCmT ziWdn9;vweCLRFr8eC%(HZW7UCn}w`txooy(Dugowun5u*lNvJ~HsfbOytH=W=S-8- zV4|vH2^r6lzXnX3?pEprmb3=C7nBdFtLA{{yYL-bzk*0Y94I`f%k7%9fk98<>3@>< zWb`97TffJEqSuX?I^b|XaqYS_?f zZuns-O{zBsz-#brRXAizR$%3cgm}cEwzQR_VHVV7%E<I!c)*IC8A4*m1Yi8&>4hJn+mGT8oL4TqB}L@B%--uv)U0k~)~URVWW^gL;e~Zw z(4}k4gGJN|OGiGGQEw#5Gk%Yin~prxc#R@28mBYx3XAHKYT(5h6L_6Vk#ZvW+o@*l zsg7~4&;^6Pavp@Qat2<1tlu^$_D_ZG!jYlND*pAL3W_rVPJmdh^HOz6CM>$Qm~m>u zN}wm_IW|txM>gIpnYd(eMi-;C$A)}b6OpTE)F;eS=*8fPRXKCw9X4zoC_zMJEEd*2 zK^2~Cdzh@H%r0I$xNG}XA7|o`ceQ46&f6=-Ff!RT`-B}q=!lvQQj{P<$NYd{l~@PI zgL2^a27qf(a7Rgi5Tez+lx zm$-F1Xb!gVjO69SJ94B@>iVe+DG%972g^zbtWbdRI_`%8v7vLvo|QxN8bhH;5{iSVg;KjZxgPJwDE6h;9BJIE?pxMwSx?pCN`E z#tQyZN+$Mlwx0%H_oEYljzX;eCXL&FLaw^^p-a

    $m50jc-B1WspGBlO0fxr!+ zjn@+pdq+6xOBud!zMPXjb$mSGwFocK_v2CsoSNuf9vXv9@>#`S;60F_$oA@J>&y@n z3Jlb(Qp}ojUl80}|LWBF=#bgli;lv!7Wel@fO{Ep%(h^5}u+a1X z00RJf|F+2FD{4;OIDZ1>lJ8XiMe|Lf`Mex8@JU2(nlQtfdWk>LKjn~XVR)V%nbSzX zQr*?YOV&Z_64$nmgnbNP7?D3a2Uoo25k;(Og`L>=_|^2Of=(!uA_2$NOVSiJ9#4$H zn4rVRM^)u`Gh0nXBw%7d$ro}3ho?TV@FR~~4BXKjieO-k@~^xw!KP@`AH|4Tt28@& z|81nHu#d9BcJq5!B!2zlJQS<|0T9iq2t9tz_DiFD00095-Pi*0d-q;F!^$b%BydezUrA8F~C^le6n_*DVfhg zH$D+5=>QIH0I=EP^#KLWZ|~AmEva}?dvR#M>~3j73iVnTpkXJtx)0zbv0d#R84O|v@(y1kB`6_jahmSu2?)lP2QoG!sN+&vc$BaQ+SZaQbDf8#NADI6kBS_z3+=>Q zzc(vQk7}Q^zJ3Wz-b2q{&zK&Vsqa;qJ$P}=#QjVJvt5patHvNb(Qwa1?%n*65H*MT1;ifnd-loD-|A1l?B5k0vJC*jPV|o%;qDpdP zxwBV{+)PU(5KI1JODChd5K4$K!(n8jG`6eLdjDAT_xzh>{3AC*yz#j`uM3!9Ktiw8PIy8GhX?zc_-rmSqhdx=#lDK%f;6lXg&8Jri|&-fhNX7}LC`@)zL z&@)@`3N}vx!{X2rS(>j^9;KPMYjY0`bu5I9M2kecwhPKVR5)E~Dw;AYnkBx9_A&K3 zdfR;(BvZOl8RxMtszpa{PVJ$&!yQAY8tN2xG#J-B8kfrR zI{o0h#zu-~U&%P8J(`vew#tVo*fH~gaig418ieD~K|wQthEH@$p46zo9Zs(gcHXTj zt$}i*1Sh}yc^{ER4#a@wb7Jx2a07Aeor1&jTGC3@o~iT-NsI&S4D&*X`L5`KOTNKw z*Vtxtb6N`mm>?R~V9`HKWSC!lm#$K?w!v(A)p`44&b7P6E5sN{I6?>Dj*}a$->oKO zM>cYWiMi<&3H%9ga6#hb()0)C2tv2eDixdsZ)}S0ERU{kD54IWs`HeINJb2csN1vJrT;l5816VRt3J%602rt{3qNn9&UeN%W zHo>GHcKaubLZgmzZ*9sT6qtdwGz_2yM2a0kABm}LD;!e_P7O>FH+WIi-0LxMFw1Q=ibQeBN6p|iJf3RyZMbCK$1!0A&}>QHQ`w9%S`qz z)vyZ|!q~t7GchB-MZyBzxOG?%X5&NS%E|qx@FLsE=a!uSr&6QMsQH*axZP?8zOg;9 z+g?#4uy(850M8o=67RulKu3Qf>=yBDf=Yc%*ZY;;78&68z*NTkmShoPG=)n)tNo_Z zIY!&?m2)ul1}=bS?Rkv~O7acD~= z_`t)a6Mzr;!6c)P?d$@p4P&AkxkszdADv1^^@fT=ClMD3lEVD*b=j~%$c=6lJqIe7 ze81O?$qmto;|XQ3an;0+HX(F~Yx*89gYCtBKThqQhgm^fMWWX1ln~BLsDJ-S1e}1C zz{`R-RTvexl?l4}slU9yY6duj8gRHnJC=Rx>}R6k`7b|45*{7KRNcRUi7~P={Bya` zi_kX6I>g3zvD|UPs8?fuGT=M!$w}l<-CVbpvKMRww@on|>mIb4jJGTQsk7xDqt-?m zE-ymjJJrw?CXR7qmY6(OfjYxLcRDJD)_1oJGxR60JT?t+WX*_fCTB#qEPH9t7{ukH z2C?+de#=9hgdb-WG}Wl2+oO}9YaioH0JMjJx#UMG5hkR;gMX873_yr|^I+rr-sb>j zGmI${1tU&zQ`6@t`T)i6y~@~bY7!_o-=>a^bl_F9d6W;b#T(iRotPUKWnqN{ORr`C zm#Lgf%_~4MgnC`ZPPck8#nP0~dJ0rp3~rR1PD@S{_dzAB{;LC0-<}L9)egIUn^>JX zFtut$&NRxa_?Cl0bXu0JIGs+(JRm(Z_l@M>mE3>i*QMC0d zR%T46=nIU#sCADZ6B=J4f8#6{kW6kQkoR*_SNkh7MQPRy5}3k~&x2QsJTZdvnTQSx z2@P4cda}p-z$F-)>l-5)T4Zz&nIA4&^04IT?D<iG|$QN_H$L{=bmVpi33FAkx@1s-aCJ1&!oqK-!)G%vSGR zyEwb-yLRQpj2pcNbn;D-6xCUa;Vk1 zFKYtQCg=9n{q5xC#uWa^+$+{BE@#^LkpEeN9siz9_aH#l3!eb)q`K4_H(ZAh4GrYV z3g+y2XcLQvhxk90P=!Z*zzCB4QwkL+smISA39C~Y&=ZKg9V31u&(b+ zXaE2{HtdJ&(q3i{oM<$Q=l|*$5vJhM2ppQdLOM`mm=KO7FW!~jnjE_k?bkj@G!ucj zt9ZID04don$oh64@rdddfo^}b_oF4(>KjDqy}eu4BhNFTmDOAf2j*|4Ybk8q&|8aCCmaV_ zHK^5Uq214MeU!Eb0f;pri;XBc$CI-dIN&{v)z|;oSW4$4Ej-1YB=3;G_V(+xTQcyl zZ|B(?ZDRN~r{oIlBfnQ`aRS@sa14pyQ*Q4_MD_#Te%`X3c#6Xrrh5?-*^@^$g>7W_ zDd#$RfGHguFepYd2RcD5*bY@FvyY3e zXj=1W4$?9m3cRb5EnZ*lN;!>1_qNs{`Fm6MwG^?VvCOSgrm>CP*9ye}#LRcOc|}5f zHrc;?_!%39cXZwZF~|unEe{<^X@jXxrK684Ut$d~KvxJgO}Xq1sn026e{+NR zR+TT;HsM8JPD9Y-uH-%+!g~7Pet$R}WUGgaRV7F}aq!{!r8A{E;C z$WU!FXKifrh#|JRY^&0rLnBnhLU}PtiCGNe#(oUJUR`|X7mWavZ>u`~40$9iy$<4% zE{V*M*es?tGlF3_9bIrchmCb#&KsA0luszx=!T#(Qk;EZj1^ZA%uewbJSZp!@lzN; zR=|I$#_3j@V&WN6asXg{AW|=Vvyr$F2lB3oyjdkLSrQ5%0T_2}7v0&zo!pl=^An`Q zXj~0KswdE7r^+DHTtt6SLWP-MAhP%xNEb{u2a6i{?}049*lS6T z1qrN@Av_b%MqKDcDY-Tr{d`kp#CH6gRIu*ftdhlp8KA;&z{mb^Jdx`NNb5+f*>YXi z!T4emp6;p>PV2Lw>FhjdSwgjB>CA-?@}t%=eG-p6D54oqNuLE zX1!3}G0c86HhL(CU?4Ze^?Nwwk=xmFw=vOcACXoMQLNx!qIsGq{FQ#fj(8+VA$5NJ z1s&k%hQVq6Xa-PegPhZmy0=?qc)1K|jljLu@|vv^{1|UnfLzimj}Uf_odJ4iO|f4e0tmz%FWa=mtI8AeAWhC)X0nOG z=CvpHlz6oz_R$5(1*_r!s)4;yVe5f?==0OmYj!DO7B`{u*={Y&x3HBeZdw01a1mko zB8X5ZLIV(D_{r``JD_jxQ+z9qX`4a1ZSpRA9!X@-R?NGJOe_JfeRYNH9Du^i1OQu~ z#aMyIGuFmGRsxLqAAj3Cr?@RZsp^fTXAov~|81hU*g}ILj71PkpK6}=uw?pSM>tNU z-s~rrM8P{oy_0CPa|$%u&`L}#P5jZr`%f}pH=&>GgGeVl*kTO?lxJp`Y)J;)LZ=G!A z6b9E;MqnAPVWtXb;42a{2269V=iov#bMpm8*w{#?v4!?AuZ&;ol&^ZCr`M=jDQu^> zgWhPC$D)#nwn@wUvca&l#$jH5c-;wC1*N3fiogy&J|}D{Ohj*pAKvy946~^|$t6$~ zKF)*GWUw&nFw|`8?HKwh6GV{@UK-_Wtf9wOI4B#u@5V``Wyk` zWafbddmi0J)A%65icBL`>bd9qj2b9iU_3q*;jgC^pKMsTToW1xlnbuVajrhoMz>D7 zFS_{C7Qi+r8S+qRFz!jX$rz52)RTz45jRAc)*tRTzf&qcxmO3k`#sB#MHY_x0!V+C zv`9fM#1BL!ZU5?HN{%EHYG(*tS#L6fA@4P_aLq8tu=GT6Rx@O~l~+d)6Dqkyr8T^% z{6?{bW=Mq-CPgx(!s|)JYPwp|fB65iS3uJECi7MpG&l+}3L%PyDGSEs>}|aH$ip?3@QKhS{GN%D`b_g1Z!JpVTm8x2yMa3GgN_*b_H__OeKiP9l6@h! zgQl#|Tk=X#WMrTyJGSK|J5_BkM<>aQJUftS+HHA)Q*aZ*Kh7RcjcK}_26yRN8Sb|E zWkWayRp-25@nb|m2&9p_EMWn~xUS6)(cZhubmXrYt`$_!owkTj2md1E1lDb!_sO== za(Gi;IjIisg6AuOOB$JWB*zqdf3x-jHkjL|zcyJi>-suh)H1e5%8!5_nNDsuOH|Et z)wc7v(f1r9n(F%`qK#QInDHm*-nNW7@9()N@gG@C`=623Q@z%kj`d>Zv~iMQHEiRi zX^>kzDn=w42>b^?+!a~AX)^JKnTboAAT`_J$uvV6H-ZRx1h8N@ocWj@iilMO8Fp*4zwO~ajzeWOg$V1A^K9NsghFGfgmjf{AG40Uqw2;1bKfp|c2BJx|ZnWt|U!Z1teDbCDL$X?E? zE{La~*2{2@9ltZ!%2Hh{yMO7nB{4GrTASv#sq|8`Ad>mow%x!x5AkyF4sEmtqH~}K z(a&jm49LVH8c)6_Neo$lU%nAmcXtfMcRE0Vj+#h@9D$<9wZh;0Vb$pYj@X$EuP0hO z83L~#eTF0us)-wR8+Mu>nZq~#*rNjc( zNBdqN?IkcizjWO|0(Aj!9~$d?KSJl&Lx#H<$)KciY8z-nKhBT&cAfs3N;m)~8FWLH z$E;@Ss@dvTWx@W9coW{N&=r%!(>zLOrY?+%ngi5)kOR>OsYb^ zvfA;Uwv4-(z($!I6^dR6$q(={<__~;aLI40KkKt0+X6vV6$6?gZK~0u;pa>#dSh;l zG9?B7bVS_4jxH00RLT z=4NCU1Ed(h!9y6~mrfW8yE@B|OiD%t(tpbwAJWHP`GQo0+0wQw3-UFjL+Pv5*UK_) zSvcu9f^>V$$-EQW&6S(LTVY*pwg4#|8qCZEFPs z5J!2=QE3b#Lo{32DriV+EyL+%&9`pqJ4*Peaib(_XN##REw2Lv#_SxBX{fc{OZbvX zqt}*1f7Ci^^^Ru%%1Esbf~TiR?r_a0e+e_W?+-CZ%p)|V`Jv;}g=BzRACnuG*}hEx z<9rpCPqE}Ergn-8(Ylg}o0?`%KD~lDT?JmXbkDUnn~DPTK_yGsIaj?w$?{N9M1Rd; zacLeW2@xA)x0%EdvR=Sof#b@x5qRjw{0;!JV*_l3utm1EeJS9`Y1hzIlKwVPbDAc? z%{ZUiO+^qu1%(UarhYfUZ2YX{1Nb&Y(2hSP2%JVtG)?s!6aCM|dOi|T4Nb!}$;iL+ zM#78GKaS1038?J-)Ivf$!NH(lyuAf*9m$q0dcPXVE^Dm6@x8jZ+i_8uWG=dXU0W7~~D1 z2u0g1E>VGubrNfm=T&(rzEGgfN;<=Pu}BSB^zHBH_kaWx3EwvdDl$?dpv?Jg-=jIv zdEt8XW<>bUE^};!>jdL!z7k{ncqCKTT;pI(kFxW>|7R2 z^kGM>rAW`=eqZKgJy;dc&w5bKll@X~Ysp;{827&A5qOW9{ykMm=6QR9!tV6**Osg6 zS;V?SdiO#LRb0RL-I0W5-Ff)))?3Z``b88Cg)jqFUex823K8d^Cca;?#Kw?6g&Kfl z6qk_P2rx@d&=XY&=JdAZ3BlxjGAT5fE4A3i6b#Y>FId#hV&F0}cCdQB;7dxShf)6G zog4Kx&PPs%I{x%l`nDLEYKuq8w^xsD;SD3Vg)?}}=qA=oi!&ov&p_|QJ=M&#mgOL?yic%%1a`Xy+926 zbl}A>k$O3%bG-J`TP|c6^Vi~yvgtnfZBbi!>D)Nz(nwu|0k0^G0J*KhE<=4hG>5Ff zA)EQm)7iljLVe6&=^#@L-&YlklL>RjyWZd$sc)t9*R6VVL>9#3D(M?6JcnYX7>dqQ z>y?u)$oaezKyn3s2NJ-#B)J9R3s`-x5+FS;woyUYX%b5BXvR!Rq7yky^t22M#E)M? z38F;bHU(j#d_?oLqm2D@`sV7-i0+5?HAFj~7}lk~DopD47|+3uIX|G=Kzimx$U9%7 z)|5qoWYhA*HBGWF7BR)m&R;$yKw8))j4MZ$MA2%(s&X3}zvTPNpJ_4rzWfKZY;t@27CZx_dTk+N?FUh=64?qEzuSf3mtA&r445Vc&d zmKLJ=EUGO;h*JwE%St96y!Ll5B`+{JwkQJHL!@S&2HX+9q=>JIGp%;QH*)TsKH$kF zg$1eePgJcy6Z->SU5D)sD}u)c(M`7&8U@|BGIuK_=t`VKRl-^E8Mnp~LL4~)4_D>} zP8YgSSMbf$`y7&j)k=yEH%ezZVqZhB z40Wek9cNcYW^f=4_^Rjmy#YD+0$uv0&!;_seIi5~;tQvi?9>+_9Ft$mUg7SKKiZg` z#%)GJush{IR4{!H2p(dWyfuE&@c-_f7v!@MG} zvPF%m)jv)yltivl=TZ-aT_wHEp9#O0TaLZlf1o0RyHK?%;qLR)&AzmUe)~=_G>ZUQ zff8$Sd3QH+w^7zUf93T<|1$*UL4_v5I!Yu3THSb%0u$znP0ATY6@3?_z0qsbbs>SE zHG2LxX>5gx(LBcSq%~mAv=MwK{%W{I*P&s(Es7+)mBOsr-X^s~34BBMA7IYAvijai zM6c+Y+!%9gHn~)C75m2Q2LUpNQ3Z8pRkM9S&G`ze7#IpnBo`e#^9q`x6XO{ol>{jf z+dPc6iPNszFy<;=kl+NOOLbTkunU$0AgcROc{IeCf< zf57x~Xjwm#@}zq)2jmVOpktW{M-l(GxsXx3|)@$-PfOO65 zd5Uzzs{$mW|K6Pl%Qj3l>x~RQg?Mb_`P3$ zTqn3s9lT({l8sGKQP$x7(!H4Q*ffbL;Kw&gvP%gM_5}zRFzs6+yid^AE9~+PSq~O$ z6?s}V_OhZK)7FH>%{>N5ULn7aY| zWxYQnxfv!QM;7u4Tk53E4+K1!-erhZGUs}bhKn`Xxy*EV1cL`e>FE+>?0Iu>2+UW! zvJ0DzlZO&FxD%7r&-&RK#MZg!dutpI7Hr3l8mm&d9)EJpd2-ZuwEWvAVPM0p}rFL|VAC<99_y)`l;^rYvDVbaK7Q z!U4$*%}bUMlILl8eWbZzNY@gdiG0yBDfz^@1`FDxR5I0Z-X0e#mDn(GIz|msmly3p$1Cut@I8Ynepy^TkdencEn2+$oNqPM88 znNT8en?DT_hAtLW%Qq!|_*0$f1eu=y1U?q|<|2=>zA>JzZw1l}q^j&d>G(j@n#nVH z^oZ_WoIur~DbuJz5KKj87dMabtu7y788lG{CD;AaClaS&)BsRx#`gw4#gkp{K5)@m z%n+Z1C{)n5+A&_5_1XuF#^53HaFgRl?O4K_#VL}Ut@_Xfj%%80Wzt4v{`KR`$3ppZ>8fgS%)`_;K$6Ck!zdvLJV!`ni zK^Dr{_drahArO(2kT8B?UrH5>4jH;nwp`#!#|b$gceHsjnVNB5RbRzS_HSD0?SOu+ zuY=YzEDPhPNT5h=8Y&Q3aps1Y_z8E0#LDZho=YXEn01;EK9o=YTmJ_dLdY zjzwWUjrlQ8?>=sb(VM@}$7H?@w@b#1z3o@b zn*yHVi)I&d+8(ttI%z27GH$&}u?E%?;ggmrC5t`(fp;YLGA7q4VVqd^q-7?8m8M2b zCM2+Odq&Ij1Lq{E$zU<6kLaZYez2~Na{$=p86~!!KJik=!a;29ti^xpRN7zrAG2VB z;oYei52X1^Yj)5sOYyz%U?gG72(_9@-`dL;$s&#fgzs-1CJqdQv=lNbEW8Ay`NZJ zln~?PklF78*RpKT-9iY~8NE0PXqHo|v>7&V zW(+M-r%)!=&TV&EvNS$Z*Fpp~K||=xn|BN@EJtxRiwK#pj|-@2Lcvy8=d5~u;Xl|r zF`ec$FDkyRyRFv=FY5M>%|KZYV)wC(y!SgIGBn833sBv;R;9gEzjv}tGq2$9--`)3 zmz)g5pfq5#cn!mB02;3CQF>T44qn+{ALD+mbO<78r46wq~>L2d-JM@)o*UY4nt2bB2yxp@=5=1(UEA z0wDYZjlyUZfT}Is&ccTZq3vrT>CWcTTV%zSa&S@Or`~#0rMOH(r)JLCWWWS9At{c* zwFIq8i587!9q9b(8zOA&1aYoKb05ZZU+L}W+;wNgvI2IN)G-H8V-ieF%ZrFddF}2w zK>1A{)*q`Jjq;&c2v%j)F|Hy9Y+8gFtK+oPm;h&b{bP}!P#%o=S!Y*dPJ(!g*jTB&#LhBlPowD#&KlZm zd32D(4_(bq@(q{-0>LPCXzoXK*F2R3XYggtnA@Q}qr=vZ%Na`){4`Pt92Q!f{Yl;- z07UsM=;)KZ^~@$x-41_6nWAcAUge;`t7bk@Sgl#q5^)f-Vk9^S_q7a@Dg&k~(d=utczu92US+Uo~5RGa&_p^9%h zHF({_&96b2GweG+tuE86;|s~xlsV#|CRR0N;<*S-kCeUX z%F^g40cf;L${NKAnkL{wdn!=7ZUOfuk4&t*%SR--7`#zLc@-vyGnJ9sa1`0jlQM~( ze4S;`MwV}R1d6ViX`SJI+*H&;&`adOa^JGC;vNO46of?Bfw#KFI`Rl-UOd`?Fj=_$ zDR+ZI-%D;QfIb7lmH5vVGcFk+e53fIm2J`$<{Hs+#6d-|Nb&BemtL>4t#nMwxUASZ z7-iN@*JFSSH4t)@SrQq20b@6{Qa6n?A?3|CUyovEG<^F?@genR-xZLcl<#yF7iOauig`}Y7i|K}D!zoneonk04`%oXuBjQM}%v=>p4du+L5VWM8 zs7}<)9$su_p}E|P&NW6OUOU$P8oir$Jl?*A(o1^dxeb~=$TM|Wt(IU}<8tjLwuF3) zWkv=MrD@ZxpM&fAvR_x~5N3~3ORnTcz45*dW4wHCzlqUb22zc(W*_F={1$E*Z%=5> zF@Sh-&`_^Q`Je_jx;TPQVs}IUw<<)mn9zB6Drc~wIcxE0S1H9}H_qH)Qx-71`nu^d zz~I4~$3q7yweZFO^1bGecg<|McK(utEk@xv&Ywh5CwSFkR5UiCinbok7zF%%$KQOZ zUY`l4Xz4h9B(|agrY&G@`2-II12q86Q?E0L9b5ouv6~%0dMEW zaNJH7;0z7#!Eh4r>(}UD4(X&7DlQTUW&uhG5MIKAUUFsCv>{8#Cm1`_qK$5lPVChm z=EkW5*!Nf^%O&paEl+3naGJIn3DmZWA?7J7{lMz9i;^&)anvl9;N3yc&_NeZ*M9(ki$18CE&@CV4fh%LU$m%hY{mM>QL~_H5}!8 z1MUiq-2>C=(sxG#RcnQ5ondM53KSDih`S~`8tNZYyq|7nd`A~;ox66cYo>ngpX8)x zrK8vN%2B~!%L?yIVSg!AT&dBT{#vb(&E|vzr_>Y8ClYoqI?r(1OB}1pqjx^po<+76 zIaLq_IMiagp$wtFUTYx3>-4`dsyJ18*rcaWlcVN)V{vu<_$VE@RgV6wtn@P*S|qT# zbHh~RFP4tonG|A*u-8udWZtmp%f6OLH>b~z(JeY5nAq14eGF!yrng4y5DaRCHYZW4N-YOKd3j@FGV5^3m7a9sk`V^52SLM1 zq+sH-J0?ZGd6hh0-}9x24Vsv0v*KrKO@rFLlpf2uT-1#=+J;`4pK-xb^iJ&z_k%No zSFTAwJ>||Q4H2cIe(wwq<$>jhLG8$1T@F*q+yzU%+1--WvyYjZ_T8 zJ+C4q`&s2FC+*I{c5gm6%M-EU*VbB69U0JUGDwpdmoT~i-8L%A4ve^D(_Jgy^U9Qr zCKgH61XPt{9m%0cV~s!?Nj39Aaw^9?CUjnc1EdS#*0HK}d`Q|h7V_yY2BcpWwh|Qg zlhl_;_&#dfKOFC#@pKAK!niaGgndN_vQ0g(J5`7z^jzW#MFA7HC-4;i7S{$?fq=3jxmM zfoU7OBf5UcH2^H_aDU(n6$wQ`g0`9aRBa@g?cUJ!ux!RCH{oKL&GW5+q7K8-!z%G%ghKQlFWrIhmi6DtjUAxHoi#sC`cV9tQJX z%LrYk+%VMJY+my{Jkwxb^u2LTEF)(;g$opv^pji8LCtqP1wQxDo)e=ai`x+XidRrj zjU~up8!tX$zAJSmFC{XGkM6Dmr0)8Ui4PrZgwKmkeLHSMe`Hi@XNoUBb1o7vR*m;p zC?!HwXPbuWlWVUXeD?B$4=r*L%-21EyT3kbvE#ibJ5&7?R0`HAj5^RJ+6>23;~qo+ zDQ=GB30YSXJ`ld_jj4mtWII9gg6&{bG6iA(hOY4*PC5z;*9eka-ri43%Wnh^SBOMZ zSbL-=BCf%&f>UXXsd+B0KrBn%iWYt)!S#^KkOqI+h{6c0-~_S|njpqmfZHH|$g2D5azTD!A+$R%QC+USdzZ>VeA3B{Bm z_tQ$JG8{KG$*oBV`7q)^GOq)VvI&n5WV!}G6Q6sOdr;jM4bQv5gT9UtNZ=M-pEJyJ zHpcdYmGk-{0-i?Z9W6NF#=~V-pDIFhRD$bt0Z*^jOWpJsGEo{hD)z6`3E;3#3=jzGt zH>wE^8Z-=m7zWKYb6=&MmgNChut0@g+dDI(Fj3i!fb)AdXqm+G2TBAE8!Oy+RqH7E zZWfDuF?~y8!rBQ39Cb)=fXKZCKPD*{gwF%7ddxcI>#%lwC&`~AmO1L<~ z_?%?dI317gmYYXwEMq5Gx3rl_?VG*wfXUTM&8r>GQKb1bL3GPt#m z3i^pkq)&f0j>T3s7tE`@TG^`jX8YZP+-24gss>YA|LY{XjqM~-Lb`tH4m+dbL^3C` zFe=XH#4FcEm<|!4Q?^qwduzp&)0lJ)6Ug9)WEuHLo?Zl2E4>mc0lTTEoNsT7S#;eM zrC^DMEDI&DlXz{g0l?P|o|bMNWk78R3W(2Z_X1Ub4s z#oQY!n1q1{IgQ$$bp#rK)rw&zOK-sTgql_x=!aT2BUu^JWLWjt7`3!1Dsw}S`khdvP*wNuB< zsEn8yZF@?o60<`{%nKGOuog51n)c$8W2jfy+`O1Dv(Dx=_!mp*A!$BxMIu@Y$_SC{ z^p>+LlSG$iw(STkv$KaPtxqG3KfrIYXmYMH2pHtWg@~6qB6=}7=&cBt0u1iU8?g0l zD%R{T0RTw9I$xIsqIx*Fes*y8dt(HRIb+u|%y))Mo0klXMU3SL47SlTYdV7 zoJo|Ygj@8V)j9g@Jd`nnuw?VQZRk2zwsySL)*V~sHsg))(XAxdIQSVX?1@!6G5*=+ zb8f}P_5o@3>AG_bFkkHa#kBQxI{Ku^v6l|gY3brB{9P9~rgH2^qTBi1`z?RfvY`HD>Q|N8*iC zpjJ;tqZb9quuvNL1QuJzpl?q?PyPv=z~Xg#+ySV?QCnm3Cl=h|V3xg@^n9+1E$>68 zUM5#$FTPUEcGvIdZ3J@x0c}2N>`*kbFvS7Ac+lJdq3Td}_O%Sq-i|y|o@CgNl6T1Y z=;b&&7Gv_V1Un!5OaI^=r4lG`_efl5;zmz!H6NE%UQ#$cIxkh=vrz$>X~B`e`>BE$ z9r)1mb5f^|hCD@T1MBR&BHJZd`yRdz_hLQyK z!0Vc^;}?uj$=NtG2eN7Z>7RBN9S$m3ks^6D$urrgu~uZ0GQ^<=GTot0={kMH`9E6? zFq<*=)i!3FnYm?ARVIMaRy;9tG%_Y+e_lD!KSCTcue=|j@*7)&qvAVvIZx7i6e+sg zwBR2jqp0$_q~_B|MWhHIxS;6^2(=d|3^`q_CklmoF%yh25s>mOU^|1Fs!hb|1iyy4 zHRVdl-@5fvBg)w+ssLHI<}ipJmB|@0-8IM@#Zx*>boV`1l5^r~NzQ8MGQ+IR7gU$6 z_L|!UEZ{Yl&O|(Y;l4}qH6@qFdjt7GL)@Pum~vGQ3Z10V;5SFq9The-u}JAHnSeR# zQbNr&3=5PKXtA!ps#-n2>3a`3TXHm=p+)hkr}mQnc#qdUhS;mvx}JRq&2v9pfdMlw zO!Ndzig&%8>y1WtT;!MS(cmK>XEb~rgIaeQ11)8=)LYQ&j&bck$x7wgcO7<$+_(he z3Y`KbQb$!$+MhpWFAN3^@@3w{+c!y!`7}8BvB*5lACAlA3u*amV55=Sks!TKC|7dr zGgiHG3Ud<2Gk`Ia+((O1NNkTsM03<|tfnNA6sWqWZmR8U(UunbR~RRXDnsd8cRc9T zrvIojPXuc^Iid^P?55~?a~abPWHKZ8+3K9^z%NBz&j=?f4@N+zbXAgY8?>-g6IwO?6Db!)TCU(r9_)xHeN-ABplS$H3ZXSnxl^v7bpx9_r zXklFHdXT@Ret!T$=undZjlDlET@s!>_ojlpntjYJ7VdQlWrCo+MfN%(>!W|XuC*2I zclXBS`Cg?wM%b^BS#%K6#)|sj2>B9E!v=J00Gc7N-GtpO(Ng$w4rM!!-;0w7A#g_p z(h1K@(EY_l`hIjT0d63f-k-j!_PhL=rn9IQMb5kVEyzbV^A&YLYrKTiLQbhx;eJkC zatC&{k5*}2Wt}nXFLt^+sBxz0B*$r(Hyw<{)wHND#9i*d&drm}VUG)lnK#w7MxX&+ zTZ{6J%a~b?WS^=vkFc$RSQ2b8iwW2f;1mO=*&!Y=jlbcK}Fa!G#Ujvi_qe@Z3XTvAMf2ef^3IA zd*&FLo4^$WDAH?pfbu)5)i&{MkQax2=?bNS+L~gSOI6wKpaa2RJ98a_2VzD6_^=ma ziDucFpybCYOBL5GVCJ;++9h3mjBe4fp)zo`hFNbS_6y>AV_0GOt4!VaOG)Tk?V>nA z!|Jj;c27i-cldEZSogRg&rev^DR$xC(uKLZtKAfPkb$m8P}Nvbx9r)0EM&bib+lvy zyl{5BjcwJ>&)Fe%@lbe%KmT(K3zo^AHTT-#r=P)?HI%6vE2EWB?MHxBVhZ!U`wu=ye_&sun(PtR=9&knx2=7C(hoGwobG` zEI2zjNVXbf-vNH+EZY9m)tLs3CiD<5BM9&RIG_U7z7?~`;>faWw5Un?`2cbx4M{Pr z)jK?GUdhw%2gu;3F5Lz(7PA-U8pi|ng5_eGLN`?UJ70u>4aMwg?K^YhV1hS03AJH#+N^?j7$a3HlZ=q*%-vY%uwR>T zU_rMyO|DM-H;9tZJ5OAct(8>@-f?;I`p+*0Vo!**-Uyt&t<1qOTg4q}@Ce}29d}_k ze|*}MbTtedK0E#mc%f7%(2{F%6Icg|=8}~l-_%?S`-dZhmGdynYkP7%em47gb+0n} zE=`<_yB_W9m}=W(rlb};l(vWE&Xn53ODl6WjKrS$E{xb5vIgB=!%MitT87C4zHo;p zg7_V}M8jawPcSk9cf)K5I4oJ(V+fs36K*Y~a&-6#QTgJKj>hvigai zedyJ|lX0tPJT-tQ5R?S<{9&o1j#J!W?tm@uO{1^~+@TN%ufp0;m08zHKIW%*FjSu6 zoZOZt0e-P7s6p$svY>rQY7I8_5pxAR5qWcipj_?tq;BG&ClT70@r~Qk=M7kcon6H| z8rxE|waQ^YRPA?i!dncQRskDHW$mCM0fCj8E_LRZQLM&cTv#ye{wVHEgS+uR?-iT0g|0~+2He>h@W z?C+u&*KysD-R0J;FZs`w)VDX-eg2{F$=QhxZ{$@Dq6GOT2a%dZJwIl%12ZAAmCZ1p z#|BXD)R(2s3B6{SA6ek+t8Dl`uE&Hs6ZKh1nUzwc6^Sbj8_gHoR!!bHNxk`Ac;=WY zxCqY=5Bpe>L5_00s3o+TG1NcTo=&lTkjNg6yCtCYv3(svO(3Oq|u zUxKS_0x8=DaFR5)nD}tMu#12fKruBL(dt2)C;GQrl8lfo)#5^gJ&l!=g~ zGpTiGfAx(b{HzIhF!lZDNAfh0Bjx1MuocrY%oI4fKPk{?^~Ah9Ll0}NYU}VFqmFVn z6zu8_A>|O5{6w-T(Y3e2>yN%uRzi_bWaiRI6m^kd-?~9Z)8*Q8aK#VB$_91B*UL*j zxjnGXsMJIpI2?1AY@<|{(3DZo(JJ*tpT+u!`=;{_*%poIsH&vXfEHbo= zIG)CCcclC#kRs!#Z^VX~duSFb=o?^m@G}=r5+R2@RPC5dX4TteZ3dr- z4En%8k+hB_MmTGTn_aZ1GH>uLA_?m6nKMEuVIHCOC)2z0-LEh{k;&?I;4lO{p=A30 zN%phG6l97lEE=Ld-UNQQCVms9o)F(v+A=cAr#+&+E8w0ghS_8tM$75Qt3F*Sm?lFQ zMjja0z7P%_s{9m@2Ir?sr5R{g8T1?-7j!$F9x&EmG9SP29ra zM^T0ZT42*$=8BRm#<*o8Ypt)bZ=Z^4-uNqv)^ACkBS6Q#vx#E4havTlX- z62!>p;9k~j9wjY)0zx9I&_oY*bY+l-7pt&QV%bY9aF<5n2NRAXa-ZN80_Uig6Oh+kKD>JUufTJ zO}dM|>g;u`D^FFEh|)nyq;Kawh+yr;LlKA9j0o}pHHLBfig-HYLB-^cg7T_Fc8F0M z62VVZIxNOjd1TG>ZvwN91NcWv_{~*vi7< z40r}CD4&V;24S&>-LpV))_%pL$Q$O;>P}$;{J_iYUd_|{8Mg_wHnndzAm%YzCcyf* zWB=A#2)>h(cn(4J#2*O#!rn8U&tismiPO~D?3d>Q=w({6KW(csL5N{OarQog&p>CW zXC{pS+m;Bet!d@duQn`!1Ah^WH=3G*p^;a+%vb3_l;pux8vnKdTF@HXLZLaQi^B~j zp&8&U|1*gF+R|lFZwD?*L3EeqUn`k|rst>bi)QfHgg^Yg!hwaz3a5Yngd*nvK}#bD zBeo|_ShV!9Hk)G!Pu+cs?d;9eU@#4oc=9s$(J)m1#~`5%H_d)!kV4i1{A#=0dQ$?M z!#Ad)kMX50@O0i2dbaPMDb--^;xR=e9E%XuHs!L774sT}c570)B8R=^s@@4NDqyaJ zh)j%D#VHE&yEdl27vIT@tT+%odDZqn>(o!tu=QB>jiU=e{rsWQ0b14;XAQjw7U?zu z8fl&s3%(LNPo;{89+vnRWE@&xDj;ud%Za{Yd$^f*!sIgq$XUbm5NSyBI%_LA?ROA) zngf&1=fvHR#NC-UMuCH2+7#a&zdG;ezo|6RHg5rn8lmC0bh3Z2efc;m%7(xO6U}c0 zv~AQ)ExFWrMktSq-`l)s-DfErjuH~S^y&7bt+PQ=xSajm0~FgGrWwm89wlyLICF-8Q6LTC${iG>jbF%F-h+jE%mX)FBy=FDPgb^uDi=@l_ijYOUVSqh%U!scG z##=m-8kL)L{CVd#jQFUI)LRCrks$yr>@lpwrE#R>v~0rwbxk$!rV){{*VfnyCu^pn z=sSIfyr=Lj2{!(A-jM+UX-oEx%Pj%vr0(*d==V)#&26|8)+#M7xuc0e7;#VG+#82( z+)1-dk(dHC&`wucUUx}veNY&YJJRG>P26uQC0K3|w33rfjU_yeC2;8ecSb3q2J-QV9Z_ca`aW%|l)6IfWGJjV^3P^B&iotM@|`viu>Q{W=Y$R~ zn85s9f2G`IqO=_P^B^b>+#hEhiYm6fx!;KnIeB z7INGObtmR=xuR zj^G==H|jH?;$@GE%CGG0S%CL)OgyDDWG}sNW#pkBz&rK7F6IS;yO#cOgksbRNBg5( z0?@wWwFk^IW6cS=5wUx<{!%j46x?eCMC_uMl~`*F)j+jP*o#N7#mFz(GitDi#&_=h z1Kx`GvoBey@)3st&Jd75F_yg83hLX$c$@mwfo{z!g=9GIE60Jz>Y;#exV@RJ)`;1G zL~P@tNQzwzjAT6D2BTLd?_zKf6OzW))Pk&}70ze!tpfeBH2aY61}Xe)qeilF1(21z z>?fMsba@RQT`I_Zh}jC$6!BjBvT#5vR@e1;JX{Q49a0ukI+Cf?u)JfyncWXTnZngWyn%Nu>R;q0qU_>DB7f!Zvd3HZB5l5D813 zQllFRC^MA2-A>`Kez9BV0D=Qi5!mDkx%Q1gZPQ+c?9^+=LQ^n zV_`s&Yo_sn*_KZ|T9RENoE938kn zVBy>pm2nKaf14v?aAK1|_;$3eQYw8Dfub~Q?tVksxcI4F;_I*i71pKAAy~wdkj~DS zYfsZJXqh%_3BW{Chdc^_v2yfbqYd69Tq3^g2*4Dh6JhcxG(wxEBAfzSLR`{rP_2Vu zLdE*~WhlZC$rx;{oLc9tk67OFIk7-R-vukE_Y9*9VM9=|R`Q|ZFp{hxvl}z;tbg7d zB@jp#D2R#*{dx!E5}RDDQkx#u(VLH*Ev7myQHW|TbW$&sYuJ3Ub(zmy+cb2IJ+66n z#~^Xc3LVek2B-qeV0z_- z*+1&3uI&6L{9+tYkT6zZO^l=Lc<0J3XMOdHdpae3G+|AxuQ|w9kvg_ke?y9GLc$V{ z`|s8S(H#m8uch+oJiAe@mzDk0Q9`8F-}HbdD8H+u2GqlZh!#%0J{h9Fxr`d5sazyP z=7->wjgrCDW(V!5r~94G*$5oTG8Vye`)Z7B$?LbN?BqM=E7DclTjLF@+vK}T+x0u2 zh1JGtNy1xC2*I;(cbm^)v*QEnm)=y(sZ(r?#a0R8i*+3PuaW3C3L#0dw?s){!}L7} zr)Al=VR1XBgUB*2H0FqzG%L#zhF)$7f%n0>?34{#&y~$DI*6p=xW2>b;U3S!gM5J= z&8M3ZzF;!bPzSltz$3Fc@>ct#r8HP6@@+dQOojOO;{re(_j;6_x;$Ay?4c!@UZ8&h zccw#;x5IJO0qnw_;`uSvK0C3OJ?TbEvMXqHk`uQ}t0d89)O~F7(MMe{W;tfX14(VO z{a4l2>dKrjo&p^c3df)>-U>G_g*04KW0Id;hS|rL6dh?VtHHN}Tj~7Us5(B*sGo58 zy5Lp7WYF29`99vNe{URE_M)7cLnjs&0BO}g0RU$8OEdwXBX^|Ao-;5R*amEef2bXW zI|RTWE`A9C0Kn*eFRu*%3j8Au2O9X@T@L_d{KE_({*R4T_3sU^@gJEF&<}S(0O^0c zi3ThEBP&Mmdjlf$M~37NBw*4%GDLsRfb4LV-G?@YDauXMOD}8vDwhNR5C80NH0b14_9``M_h?z<|ISc zHBH%kq8|5xFwfof)S~w0)newgY<=Qym^*avXiQxMpFqH~b!DozN+(xkH&C1BLI~9o zFH3)-Q%SaS)&;fttZ0L2m3>e#P1Pgx^^6VIr=X8ihMK0qO{^`hKe_|D>xK8oVx}CQ z5_@(_P{t?}K|6A|kV#cYL0LBA0E$GA&neJ}QaY7`OceesSl~oGD9YHsy_15LGM;zf ziHeY0Cs=9P()#I8?(4lKyx;A59BQrA%@LLni2d;SjyyV>vang(M!IpWxRk7Kz-#S| zu+Q&?1LY(dh^W*1IvS&Wvkm|-Hx2-@;w8O9K$V$D+t?De(;sv9bjUXoZEjzg`itek zw(T^b?~iRt+#s@)l{2=?@bi8W;Ao@SI89SWjt-3&=rgI04l%=}=aLfb?!Do;Rd$g}r>LJ_}KT|u|x zMf4Vl7Yog#p}Vdyy_k(bHi`#cX~hc5!cJ||l5r=>ZToRymp2b9aUPtDRsKYYS*XMXg+j&z=axJF*P_e)z7N4}wM(@=md1$(54aq&a`1_VFr1~Ll~H}W+^;uPcWY@@vOl}9(p zqMUsHIFk@Epwz2-vw>-}QP6;UzvF%~HzbO7A-|8q+D1EO_^1v-C};DY&xgN?fKbhZ zx7Gyz;S3l{k0c{LhAC$N(PS=C3JIcOCW=frQGIe59EyH%3O6Pci$9QEwH}>|9smIF z;m<^fLiYaCR~bt_0Px1|9M~mn*&mnxNBVC+AT=A3R9^C9FvoBjJNRDj&8q2%p9jDbUo|487km2UwLCfCD6fbV>O|93dJ(;vjYovjf2 ztDWVm{;YtEK*9Il*98F}V$aib{Z|8!SO8x3??Ra0uZ#c9&z2tm0DS%69RC-m?4LY9 ziT^mw{%uWA$Ei8MC$?NzQXc^S!^fdk$OZjP5a|xIHlhLGy1(~T;`xIcE&AUOe^~DN zesEiTaG(8)``>B&JH5NaABd+ue*(9d{h1Pm{xkJAsIU)nfG2+{79|TX@HA60`a4)u zg31?4(BCjXBQ7IK|E!9h6!4D}aQbyvn5xvwpOAhZzW!4U*2G^Y)*nPj41ewV8}UD@ z*mnT{fGGY0|3wcSsN6z6#%Yr2mpZg>;LcpqxrM^Ps+c*@IU+nSbuO! z|37g92><|^U4Nqg^@R8f{_hFkkq<)44?^qzYr?;S{qH4U{U3B6r#EGJ?El=hc$a^A z@wYbm-&y`u1ql70d}IGV@;QC@cly8Z{oRR=>lYYS;pZH~RyF_@<4^CArU2Y`2mk=C zNEZNb_h;$99QHmcnFm8VffRX0=Cm0-B3IKxSpP7~amJ|5=4Zr=AWqi?G}mxZvi%y78oMgfq;BFrnzq9aU3^%5CV zW;8d1H6(T6y0TF+4%y~Kt9TyLEER~eUca`$tP7cSXCq4o@A`;=Y4wil-L-hD2{93A znj6N29HDz~yCY07cSq~O?~K<(+tbJ%J%T&*?##AqaS?2 zR*ri?2a#LcOb869WI@r%M_AnHz?Tr->;}sgKyfW$km`-k}|78Ln?B2bg)0mTkXu|kZ|5=fcP-R#Q8ZcWREg+0M&DO_eTps$PbE-%H6KE z zKSq&q`R1S9t+Ew4X;kM+QWkV^{(y5E7UTfd$hJiNu zHZaLQh=4uuc5?b$s$GwQbp1r^O>G-+fBAFR*lInjpR5c{2gwu0&B31`!ud{&f|ld0bvo##T!`=Zn+_d8Vqrz=OdPVgi@X@C zhq1prtK`VM9Go+@Z(J0M)ht!cD$a09h4{7h>0D#-oz^g`LY?W;d1t(N`4ucA7!L#! zc1od4SWjmz2{(j_Nrxw5jh{6ahfcZC92|^#mYA0*L1d~zQ#~uA;}VGbc6Y;OQD}gs z+iD#>bXzCE@bZa+jWdLQeD+Y$iIye(3=dnk5UviZB7n<&?$BbHh9Hy9#R;f==cj9g z+E6Iju$;8e_t_fqgDy$9PoiD+6a!_Xhv`;~D?HwOkiOSFwg~ERhQ>J04Go*sxiE z$3Z+4v9#SBN$o|2TCQfPKx%ypGrr)LjW#*mOE>md33Ci!RKLgNo9Tf10zNA(5wxws z#H_;?GCfg8VR0W_YnS^v0e`LoH=J~*keS+^5v%Uo1wL6m(OTnz+O)6Pf&&z_}&BVT}Upn+Z@7c zYTDf!nQd}t5FPJ0`Lrut;JX0dy7~4T~C!d@lwoF^4Ro#6$Bg#!^ zsZ{qprqkEHCm10nJTeHj=AuZZQfpyBbN^CvEr)KP#o36N*C!|MxuVqzM+alGy=_h9 zYR58;^TNo^0$y9W8I{AhXSeC>`!F5%2&7?={tovu+bgwAA5NB4Cuo5F9pHk)W_wk9eP;wyJgSmNJkwF9c-c8R}iUFk6ivM~F{YeLx@*y$tL!#CHBJsca_K&a* zNKE8Uqz{)_eE>FH|M27v0F!_U^>Z2sCfyp3T|ab+0HUj68_4#(TRK83HuvfxughEt z?U$){kF6f?2W@{> z^Y;?qp1&wSp27PzhzdKu;Za`(*!Tc|PC$ij2x;Z!--o^?_XYty68vTQXTq58LrTzx zl+*uDrGTgS9oDr3`AgeF&?oK^s7wabtAL$5_N%L8ll_)s5!E|kwBc?_yV{HnHN1a&j)upE#` z^uI9v35H|;A#0dFmCNk^@b(sPQ9a!s@ZDXyyIZ;iR3vv1X%H+zKtkyj2?bmb2`P~V z=}rMDX^>R9K?wx}kq$}ay`UIB`Trh$-sgS&><8!0ojK=w&dh#i=FHr?0dQnVNs&?- zfVz*Gc<#iHFDxvf$*Dwkp;{*t(Ni>GvvvUkI4^}6*I&=7Otg`7c~$>(O!rRHt?Jvs z;BS;^i1X495%>$sNGrVe;JKwvQ=jeaJan#1V181}*}*n0r^09Rs%yjDY>9W`{qb&v zU%Z+HP#pZiD>y^QUO#D=O1b$&g!n=>gyRJ2eb3k}O}-CvMmID#a>8csR|9EUqdc2x zj4aN7y_&QE$w%pl|JV;{ahfr9&^16 zCR+95fn%b}PjFYJ#hF*PA0~3^oD^N@Z}gO#2(2n$)j-=))U!J4n&Y$R^+@tf*ZAn! zd`$I;W2|9#3)))%iBq(g1zFzwFAN6A4#btlj_pwZXj@03iNl-#rBXMQu>>#&49l=F zpfU!guIJox!Ye08NGxf?4RRV3(>Me3q!k!<0Z^-RFjh`P*9n=dQ}A@QjEt-%jV+ZB z#zk>gr@eiQw5qZ>68y8{(NjUtejsT71JFk;@JES*1lz}Uc%@J%Gz-iOQP z(P$A4c2U{>NGQ*lTzB)64hAFx!B??<+5G1*)Hy{#$Q+*ZMv26PH6y7uUn~Kj75O z9j6rrlK|B^L*kTh{a(Tsp6d z#{d9cf;1dj3!JVRja{y!vBNbkt%{MZ@wgZWC*D_&<&wo@)%{`|tTN^ATT6vcaGZAI zgT9Ca;pO~S@IaCOH(h#SMPpYp%QmzOWi#!(5Yw-3It~F05J?0v*n$|^{u;y2?)sYk z!I7Zz1oNA-kjE>H0`m`)>fl`dpE4t`WcM(4lD4<-x6GUh6-=G5?%K(g+ z$Zz6UKq~u|g!KVjB^il6?S_WsYi5I#`#I3msnNBjQ;AAS;`9&mcdt~xLq|9Xhex0+LzIobx` zM5_hp)(-52pcUW(Ctg#jc>w@cpcR~&#hs%KfN=wq_pBUNpMJ`tXkc@CyBblCU-ULx zJ2<6<=;}@2WPATrsfNLwX2%qnl&*O5CHpoW z4W{hg^cvyA3GH{ceoGvB7i2@r9IgM74Q*KTeu|gVrLhC5CA#Drpk$Fw~_aIjo)1L3v(SMYuj ziTQnV4BP->Dp6{vl@FGR!u-@Y)mM)eIkZ^&OX(v=9qwR&v}8H|*9eY8{E+)sTxbo6 zv*Nz-zvV(SI*m`?r~kk7d)Q~t(;yRCDgAF%{uvWSg35zIrt&XMSYS>ape74t=&+p4=fL|WMZh$o9&m~S0F~RH zG4!?u{V&=eKHK13tvq?o8dJi}Qq3NK;FkfA$A^<-vTjlEH&hG<$yC85@SN*9iSo#0 zKy(7~3L{dU^QI>vHgSID=~*e>F$Y$bI%N4_*+xe$m0Nz1|jD*CwwVC~YL5l#&GH@%jlM7!=$7I~< zWx4|3+m(PZ7@qw2a_*fLOJcnUu4utKKA$Fj0|xdC5q%IF*e~7Y{|Fld4O@v*1b%Bg ztXG_d;hVt2lP^CD2m9nv(?g5^EZrqWp{{NTbq4d#z1F_)8-b_uk>3malpwSLvD|^g z-NX6su^j3BNvxOEkBg*v$4>Z<%b!b29C!lc=6g!^e?pT2Q4AEv3px}EDf)2})*1_* zJc9Vk{I2=%#KZ$osl^{C#X*zLD7qF-${*yv)vU*QFM8se4yuG7%D$OI`|v1>tKyLe zdFyl!t(v1deXXE163>^A;ppafZssPRpr zAb4_%$q{lE`R!QF0UTWbnp_0>1EmOnv;r&x>2kV|*AL^ZwOnTHKjy2SRjxO?Cy&SR zn$bS5Dw0rulh+f*<36GH8^-$w7^6UpIe&yvz88&%2IZA~0ZJ^Y<%t{fk7jSFe3JjcNBxt=G59P_4#Oi_K^n>o!60vZ zciqcY(q zfZKw$bPI`n6zw39%-u+ADV- z9cHSKuUl+~r%5m%T`N7-e<^pM9X&Q}(`>|TWm~(MMq7#`@-l0XuumEQOn2)*B=`Pv6Kprqa(SWgd;o&?rf#f<#oriUmV+>s z3U1dL;r7IGpK(;U?LNP2tQ;=H@XY2DCbKVkpi-51(jEXq4Dy=d>1+Zhktlt?`TS?{gNY^phP6H$_QukuD-)*m`GB}fOpm$v ziQwM^gDZ`nMZ*9rf}o-HFvbw>=QKSIH^BtI81W^Y+w)g2jH)lOcS6_!1$)mpRgk+EC<-- z^*N6wcI1a+g?`I?F?P?%=yK<#PK^=$z-0|`G6RtZ30~BLZ6x9UNDSl5cczl3_X%KCgwG7l}E~vKb=(Y(-)!SKhLR-B0+a-d9A2f3MXZ z!iqvf`=%YS+_j%suA^%-@|b$SeaEY+s)skwnpQ;R8BXvcr-8DYdL+Vt#oYmdkoS4o z4Z{4$gAy0~wHzKM947>vxXus&j|EVVfd-wf69v!@#s~2DVKBE#!b93W8N@+-n6n^l z=YjfQVhq1(#n#t5%4oHOTo;?mz;RTLc=}Gb=iTiE>o-ET0p$kX4Mq{Y+Sio%$6x}k zQE-HTjSoD6#6|vR&NOSX_Mc` zV7;_JheB#K!@o;f=ZIR2r>2HM_JABa(Sn(YUXCCX{!{%UK`?M%7zl;LMg3={`BobX z%7AXG_w9n5QIUl8YhxZs#97pe4qyTYc(P)!6dv!yBa3H`o9iW8!k)U)gygPRyH_gO z3X)D|n4H@ zJwp6*;_&MZPAj7RkYx`049DYZ+_eBe^A7ooP$(q@?D^xXW`~(WV2pZT9W}p*+=-7j*!<7))vA8=9BA94|BAScNl zWJUu3FmLGnDl?k(=vq<;f>Z-u*e$qAUDZLS1y6%Nn1bRB6cIN<$D9q`seI2#IDP@Cu} zzHBK%(&v`gHzt!YAK3;>jm?!!b_VTMi^M%}K`dO0Qoh?%s;9N~K($)GUP^Z- zSro5l!6fOyP$ME>_Idz%-h((>KfycKDRx?}J66}_sQY*ZNcAY5lxkS7La=&J7 z!L)C^++ueU7e|Y)hppsc46Zqr%r1Na-OLeBJ7L(>c0oqLh8mqWR62ixfL$=hUS~V5 z#x&Y~h!aN6Wr4-^I)_7X(HT20B{~)-I;#M+I1gRoeg5a?%8jT4`@p)j7WRNaT503u z6NKJ$GP~F{q&}9~d8VFBBF>j=OPwUNjW%cfmGiaD0wTrwmB}lP(&%`N5idE4i z9M=AR1-IL1_D})`+}#R7J^}@)%3d>t`JH)+M;aH|<(bhgzkHZHeL-!^WV%qHQKqRk z88vmQ^8%;yik3&&T;TXe!9pkvzs+v_YdryROfT2;DPa~T>muUqV&gqV)qvok&}rwb z;xI(FyG>u(R9R7}IZfWV3EzS}yS=;Jr#)IuV%c)kk3^HsV5%desn6S;50+GnBo*Ip4NI1@6yYd%wwMlaf~&Wn)Ekj=mAGHN{%C|x~i zero#-F71tLhR{oIm+qdNc5hJc58)PVN`3&-ls`WtJ^g$P{4L+eiNOYH_N!gyZWIXR z&77cHTcN`wpE76U%kp$$o>_-46R@KWkJeu@w93dcSe~wW`|$1AFc$n*!ZvTOpBgd9 zw8uJ!9)Ok-pLK4*dUfDdi)?Yfx!izpa@o`-6>4;C@+%=?r_89pn|}JW^qcRrubjw* zudikF!Xk}Y?=%E^74$xpzI{JDEKR-d;$jMawN-cGSakekWyv`Q8MiW9NO`m(@1h#3!mQT5hnFy4-J=w-mJDk45n9sSJ&R+ivdqQId`d))MoS!*YPI6iw5olK zW{2k63%Q=3nrZpk?IrNp`%Mf^p@d$SD&oSIzsZ;r%dNQs;Tc_{czyB9zMHC>U7?Z( zX5*s(x6o_RPxo#VBP;cEqg9CcTwRoNhpL=OT6t{5_#!DtL{Z1W?AcKbOUK@1ahbSis`~*SmU@Ri8Jp zA6G{BNy(6wOFNzMoOai9PS^K7+ahZ)#I~^z-Y{}{27_pGM@Mk zf?T6Sb{tOz(&5R!wowqj^ibw>Do()-2QXNk?qR1u7mP_Ap)<&5Ub#cGw`P`P$`tM) z$^^-J+DB7;?zVgUJtzh?`f?KGtr87SK~4H*tJ&J{=C$e? z0}q~Ajeok%c2(Vb$0*H;`YyjB{|y$$3(7H}dKzcV2k3Hf*ZQ&9M}$=T-nS}U7u2tG z!@BGKpvsVa-1=;jIzns)Uk`(=gy~ihw7OT?I-iY~$0mrW<#uz6$`WeRNsLA|`!4dV z{1ly@(cyW)LN}_yM>?Hy))jnV9L~9Anj&?JyGiPg{0$UtdqjRn^LflP(4=-^9P*64 z;4I$)#_LPjHR9}}1Q(5-6V?`xxI60)zOjyEtVuIl2G>qdtm1*Rr&gn9g=w}KY(^S; z4ajJV_w2ev&PWO?$`xN<6EeF_$?Da+A*E?tk|>ro;yZGiT$1@RUSs!^i_ z?Y_y*;soz$eQU#dB44+OUgJ)^TxlQ^$TQD!pE6(QEN;;Fd(Xo6WVTLR9`@XEn#mgp z(w_vM(%78~@w2Q^MW^V&K_xmllIW9)p|79Kl&%?MpJ8jdM6JhKJh*j@J&NO2SV)Cj zJfi`ljOZ*gUyFX(_S?tJN-6wV<&SkRuIHmUhvyCS`MH!*8G8=k%sf-5OHN%=;&)hi z8mx2%<5N*^ z-}0yhVk8ml$RP>RB4U8Qfw}FDel}LmVKr*kN_*-zXT6>aBAVfiLx@8-IVjb z#^($x!IBEVlsLgkZnCgYK}f4Qy`ZpXjHsi%t`Zi`Yu}GWQb?3F_^(4g8o03oBthab z+x}>UdEg~ZIq$H|11XfC!V9SE0Ju$gWl&5Vj$Tl+%@Vtb@n0>B+I_ZNjV1SyBtBv z_<>Qfc;KmsT?leqW-nudJyo;dSzq~}{zm6sM2^6KVo1A=E)I@QeEUFT zs>{Q?#-?c;wo*mV;$WkvZy4OP*AwA))56*0!W?0ZiT$wuSfchvjqg=)Kwln&J+uCJ z?hjUlK^{ZCd*}!Rm=Ct-kzlCsi1M7VppZ@dQ!9iYp(7R{lUDMisA@slNd9v(5(5Xf zj|t~eI#ahFC9(KF&xq|$xo-xk>iBNmPf~$7cMxL|}vb^HvmsR(s+7J&4yzM8>c}3SKqS`Hioso^Da(1PG z5*Y{jo2;f7I)oEF7R@&4g$1^W`6bcQYmHO8h)<}7*n~<6B*!^~q8mhB1tQP+(-j@) zzkKAE{(Q+<@WlJ_p*v-X!2?VL2T2?x6&yo1;V}1oKBn@LCPM{B1~Pd8*;J2)ToFli zu=9lIZ%JCNwAu&YtwB}4B+~X*P@YQ~*H06&*uSqSVwQ@IA~JcSlhAnI{Y`l8!l_o7 z)Mp7+F~#i+)L;kw+3SaC46u7Zj1bY;$A&u&D-c+A)>7;SYIJu!3zGgS0wN-VbC`sX zJx$5eqcEIll=+aI8orQ!wL^P2Hm8gc#l#2U?Z$u6Usu*|`!e{p?Qg2(D}XGXi_Kpi z+#qe|(@79?LV&*l1P{%S9?%ZFSAhmU%k6wR_a%U9>J)V{0hUyz%j%o37+1L%b6#=I zODw^!CC7u~&N=~l${g2etI?6#Z+ON>J7DjV7m6uui(E+7YiTK50&anidx`bUq7|Q% zV!C|K@{07pNkCZBKz5C*gE^vFQWkf&lPJsQpg#8%z9D8ZjgDrR2M%+|P)}oJi74m# zH2CIq5%(2(@yR=Pcuu>x#5xKnp8`&}*> z1tdWA#XV4mjk(ip+;9Wm3d#B$Ehm`YeX1kFr(#VlT?gf{YK^}eLjbV`3}IoFy?+(p zMJIF1LM^RwNjF`ic91E#zTlb`_7K2*ta7u0ZSCxw>oQZq=&uGGn1S*Jv^5nHSMld# z*Z1$~O#yz~n*GophJym3dA(BrK=R==`HR3>@D8+wnVgTn>UHjVhXmY)l~m2+%4IJW zERL=`v2Ja#2d)MEde|%~T2H$#7YQ+xlD*o#wgycj`pP}u6&)m?r6ABU5a`cC7z)YK zFWLbNRR-wz#DXb=;ir5wqE;PL8z4jh1)x_&=L+Olr&?w?3Xj{(Z>4=L3wbpQtj3gK zegxd6Q8_;17ayXSURfu3xQ%1C6hcv8U(keDKUFra4I?Jj?Vz;ss&?~mrq^QSOMl|3 za8s0Y`O2$V>033(pL8GE07(R~=YrV(W}Jg=pzH)O#?exh1t|$S26A034&mrJERS0T_G$_FyeDC`3*a>(oZ~tuqbm8 z$`m-U_9#46PZ1=(Wy-Peo4a9LAmBm}@ZSu2#{oXTM+`f12vI%!8(=KX2}QbVA~-Zb z^>?w;7Smbicgr7Vk@N>nb8xP`^y0HNT<4R!TkS7Sd@&r?oPnlBG7IB!%E`W>q-q~C zKd(+3kq0l1q<;N2f`3T}0RX5(L|6Xbk+Q?_VsqfgZHKMHevv$f%0UsJ{5com`vkyi z^XTYd*}K@z)@j*I*EqanpohUf#`^rO*{FNpT@iNyPhC|Ym1o}O=Zc4ELbb2pXvh-8 z)g|v_qtCy<&E`e!YDBLw!p!FzJdz5}y9O}-!vfS)5dStJuHio}RZ!LBf7Lk`1E5gl zew1B9(oO(_A^`48vJC*85;`a)U_|=l;D5u4tb>QG`T_Kf>$HQli>oK*SZ-Y5BYYTS zFkS2xmP1d2GlF^~&*ua;Giw`J0DI^!AKEOTbXSJPW%1hOdENTh zqv36w+B5|Lfiv}dr!lzvi73JwK;vj?qrZl8{|-gFcf4g%D3jtU;|MG zkCkpx)JnAcLm(s`LOUmNgJ#*Hm^T;EiUtduod>MRW5F9S4 zha5@WJ!xpXlFky?h$tkvHnU)+Gc|#8L3`3!fbx-W)KmZWF+(Uu`t>H;MWBEFVQA37 zq6d5;uPx^ z*nt56Lc4GX*KMJHbbk!};)3fGK*X7Jj3*d*^56Y?ks~x%b)iSeqq_k5Z4eoF zjILklU>EdH!%bhS<7X)u&4nv)%#$pY=9HdgX07KhbSy-UjPblhz@`!o<|b` z{p3+m?;*bIoyWB1gWkT8`6*(jU#%GzdD9Uxvt6sg7()>ynwaHoqA~0rd5L^Y}{;D-Z;U8~rQp`*&bp+XLqT0rPoTr^w3z0UNBLTyn|5ZGCuy z!{R|br~0Js`mIfxI4F4lq~x{##DuB?LUIKmasSO&1}Y`^3>x!Q`Eh?!w1bUu&{E<| zy7ja!QQC#0q~+Pn1Ge8c7Qfdq1R))4=8pac%KJ?jLDz3t--Ut+v~Z2hc)mtr zPC8ut4LSmx5gc}n|22*M#;@9BXw?(%)=d|#L(S*ssdCdkLYrNee***_!4(D}g@PVx z`yVrFG3PL%ezHz$V!B$tz&w1iQ;ay)tV4;BZ*>|iIo{QJO6)mdpPJNEn#uAp4F^EM zg%l8nh#p7#2cyFFkFf&mqtNp&45NdnESH>Pl~lXLZSd>7_IptzA#7a>kR~6ffMikB9{f+-#WO)%3syvl;6`Ij=H-c@ z_c!quO4W2-0N&OMymOpHRimvQN3#~ZlB%~nB$o^|q2-!S{IGKkSii|?NHNHAzmP=; zL)=aGz0s4awYMLMQTRWZk-YTc7&|V)fx{lK_&?;Ue<9Lq0T@i3idGa^9Z_e6(y#2X zKMkKk({%hPc=OG}v?oDaAdfEoEopsysRL-~?*#vqJN}GEzc=)cL@g481oG&j(!cR2 zw8ZB(H^(QsO#GI4h=!x3LGA#nhdTTT8s9Djad-L%p3NDqF9*5*{GiZ+0Kj+kE&eT^ z{U+%jvVWPm{!=Sh7UBph28nd>UzrP<|9e%Ki8u21+=Cp7rrLx5a7MjeU!0*3Nxz_F zLd(~5CK9-ezGZVsd}!FwaR(KEA6GdF6nWS;{@1MaPa-A1vC5tA`)X0Afh@i$GVR&& zi*-t?q7G@7-%wFK0wIA!x;X#;1Cg4ad7L}B$<}}oFKC{bQ}e!+je5srJZ%W$_XeQu z25}W4qGwtEfJh;UW+i1O#3C60fLCDaNe_}>3g^&Lk+ZFEg^chZD)0){{((CrL12eH zKIdXJ&~MbXG!EQymxC`^2KKEC*B+EdC*_&xbVeQ|p@lCcd{jQZvR(1E;jtRMmd`b< zth6$r5;()XXyh6ln`u`ib9*74C^w+9jXl{r6VaZTyT>`ir zIMj=h0H6@$4}otC%-J}^rX48?0F3L*oE!bwmz*^BA+}SvJvIGLJjfLqvV_LZ^m{BU zrMr7sKiFTJz6(6B^MSf^_%Ym`NI;ti6nYq3L&aYyTd;A9_^z`NqZWnbM!kqQ<7str z{y{&1&Fa_T(Rzn2_yrZ0K4=bjsBHhg<1*N4qX__&`fe$#+6Q@XF@?;ZSVE%X0GheB zw!%bYo>tr^=xI9RGu}MpL%rl%2c0>u)@*8K(`wkuwWW5Qrv;~QS?{})qXaq)2o4M( z?EfpP{bJ9N#}8)Gzk@pv4CRC*AH-B3PVam!<&ra#r$gR8GhA04Ca4^eqner1V!tLI zutY8DN*A>{WpM=MNG>P<)e=Mna_zpwzj5s`sPGfv0E{K`%davGKZ4gVCvmVJz#w_* z@HAl=K#wv!XPlJTfTi*{0B8r3X7Dwz`~OOL#{f7qg66nhE%X%=>|1G`Ym+FDbwF=}fLLpg7aPWvIaazKG?FRHO_HSG*m=ds;Ybj}d zqKZU|ZEA2K61t67ot|Z&^lQ~`)*U_;1P;aff6Hz7rG_`*2VhXtj{Jd=e+Z*|9soQ5 zsMa2OUJ7ojqeEF>~4at46zcD2F+9gKT~i0HnNrMf%_x z(uJ~oqW!7~H~1QMlid^TJQw>eFyX3Ru~kn%D;}aJ#w^Ee2iP`j9u5acR>1+{PiYsZ zRKV6FFJJ3=E<7UMf~!O!$l>vd0({qZ(_AG#`Z@4tp-*d0Xt5pm|KP(sB%+#Qs~~R@ z@h#&!Gzvn{xwVLRAm=}^uiY5jj1aCJE)w#}2lRLiDB<})I z#jfhNoXY*+y)ptc#kINkIWy%6pR*Oz# z0fNqtzq|IEQy>ViwQhs@|CaHNocfQ}|9<&L6Wd@=@n2CJu8yjixISHVJ#1`J>392o z%Hcd^Ia@TGX%HurAf&1CQvWF&($6BKCBS`#uDrNH^5ybRWxv~k3d#f`An}-gMQ*=< zf_NQDhSndo1mtzXk*epHAsvh`UNek=r$P;I8HOzB7EuKK71`4snZ_(`vSftud3>JR zRIis~4`Ny0Q5_~AQ6RJs5E}Pi@-7Vc_Ym>dctH&-&s`(HCplu4dKF<%pW``gc1?P> zk=ee%`-MAy2!}b$0iGfUa{sTW4!7Fy*$^?9Y5$;I*glbEB~pM|7P4GJRfZ*M&)4qA zGzxvE@BG?fye@@;LUy38>`p*n zo+4)E`pL@Mfkh)&W|zzyC77n~!*0FGH95&op1+?&uz$TivJN#zW-NJF1#OT$q}f%K;_~VAUcyW^bkEN_GfqQVmkEG*@j|14-lcZT*)1F& zwKpGg;$O=;&O9;N}hDCT|op%@e(~d6U=j(8-6dH>7{C0 z1Rkok^5{5Dg(=pBOB(cJca@&f??^0*DP`uoWWLgqhG#x$-3>!}JSR=GSIfAuA9}hW zq)neyVDxsd_NRTf6J{l?Xq5zw<&F)@r}_5`93-7G7D_CZTi%;mcD)Z!mF1Wq*5vAp zXIN7*8iJae&0Ikc7+*8&)tKWJ%N|2|nz5z4H<`V-UN92n$6&6aOmEz~$bozpp2#47 zk1zeXyf*1cbIHb_&8Slt?2e_)jET!D$(xrwLRTKDn^azB%g^2^8NMU+pzRzzq1Yo& z%$93*La^P8I}df9c|HCd3xsW*aivkn8kW=cIBn&ZhZ=`B*!Q7jM8Okx>)vjzXc3Ph z{`>RDTD0xEvB@8vLAlQ4(BZ>8=FgUme(YLRddg=%J(D}zzjrEQ0hc`cM(0@6YV#=w z-S9LO*Y(Qt3DC*6LX(&F$6JKPPfD1bGd~g3lhsLaKQwA&;!1>GQ=?^zuV$H_rLS4zGgFqzu?z4S zUuv!o@_!PZ#!v#4#6bISHdgryy{okh|EudClHRf2qSn{VUD7_!d558hHK8Auxf*ZfOwwmMVU(^<5=hb4ZQguh)fB|RTPV1-r_z@N0664M-K@ik(g|G2v1%`? z#=1TxRlyLSt&+)&U`sYHqCB{pa-OhtP^Y(RMDTE#Gm%tZQd)qcw$vle3cCoPQ|8z= z(d=Olg^w&fF$2f~AY5&W7=+WM5p8!JW3M`ms-GfKd!tTPmcZ9fuGAIQE@)8b%x96S2Bj1@?=wVaqs|334l0HHmpff8rBRVtv4<6`ad?`7XkHX%dwsM<7 zg_QxjbM+!3qHZc;E-5M{6u6(0;YOzLKm=uML>zK1-_m;U#)qVV7Z2ps6@-);SV>NP zcqzQICZ;J;9p6qx@W4Abq%G<-$Dncd3r)6H00p*lWSQ$l_ABgZr|CK-_~@qGd%QxX zDm-hwvkXk$&Y}`snAke8VcG4R2GJdpO7pEePZ@aHtCWFs7URCKhVGRU`fWuQR4}lN z5P=mHh4o^r(n*hNH#{TRpM1bBkH{aj0;0V)uMI7yuIONiHmypJ=s0Sua7)?Q7%}q^ zw3#7E!tf)aRiH0a>Wf4Y*B~w%Sp7L?HQ9FE$b)kqnw)WM?kW$wDx`joUrcON;nfag zW}U8%w>Jks1gD5b&dSp5xt`6py>mH}Nl5X%SHNB+Z6*1(iY#v3z?#S=)?RD-$>=!Z zH@0Tc`kxm!$>-7*uISmt^_$ihzPNTi{B4+=__d{zn&NTN*gDc@Aa{7%_^!##J{N?N z`-GiW+O?&5Ga$FrLDEk;N7ET$)3{)X7xgUQ;ofAdJ7hZHqNKr`hPAL~3F9*Zt|^XTy_ z?1#7r#irh?hBMpN8q&eU$(L_LCUKeLVY35l@zK*IYHqrnn&ZSO!e7Z(H2%Vw z5O(I-nP4~FwxCiSmeyoW2F7`z`V(1Fds|buo_$#M)sftJM)cUBqB*=1E=)u62&IgP z4qsTuBK~S^P}UyRDZRc>=Jx=)*iLg$Odj{j_#h9KEbo1fPknveRT&k=8og&faA;8b zIXx3CaeV&F^F~y_;@u_f{)zyhRH~=$`aNB=*Uo#c11-owoC zPA!Zm{h1PV_3Cw@br+k0^=^p18}-d}W{MO+VBdHZqhWTp+%B1A(e%RjnxaiES4)Gx z_G&0_zBQVx!1G4AP1^mi1=V4=JK;hybpR8~O#|^0D%b@fxn$%!QFEvCJ)3Kb&~?!G zuJIeICU{9OYsG0_p}VYs!sy*eHpny|MNJey|FUtX_d)qyo9`{@cO})S9~{UtAJlX` zy=|u0cBRMOXJerrUK{P9S;L3q#v|g@(!7A}M(s$7{tdAxo$Q8R!3%_huezwF(q>TJ8vJ;pOKGdoPqL_z!yOBw@}s}F z^}?D#!?iRIp5eGHU7=N$vltaNyoNnBJ?ccZ_MUnTeC26sg(UCln=vbJ^8|RFe~DgIFsLi@g4Tx>ga&yn z(c14428PCw#!IQ>xDauJAGq*;16 z)vfNH^^A7w+d&wlq20AlKBLv%TtgclWW;?A{%l-+?L#TUJ zT!$?v0f@ZVfRD5B8k^Xr$wC*e5a)vwx^&D!M*pjyQ!>QQSy%R}hnUpn%AQb)eRUc> zwrVeFxh&$vu0x6=B}!*5~^rYc0T(mtBASFkV63HKp1afjl!jdGoA7z zxMv@1l)!v)v3z)(A2nTi5iT`_+FDoHm=atcUqJn|h}kAPpdahB>kK-LE&r-m6N-$u z&nZxZd+aM@T)Yhdb9L8O$%is>2-_veZOoR6eAyy-PyYDW3-^NUFBV>4j@G>?~ z8g^zA@ys(bbyZc2; zB3|aUM$~<=`x>F-HYTWqbEAA*uLT~3aDOIymB_BTKTcptf{eS`G4$~hqX05h9D6CnGGvl$-3UF0 zR^arzu=`KO^FNDXE zu8TAp8|Mu@jz&&Z-T zc8T9}f~r$C8dBLyN{MLGB$4SOu2Z-Zzzip&e8j%Z@Ws(bjeWA(wm}?~G#rBk>4vDl zV9T9m!>mLJ`tl3VRxP6u5ptdI(zLSXs&K;bI$PX{%P>{tjb2`)?Ib< zJlmdjJXP2!LL~1!QaQ_h1yNn9zh8t>Gr0D#Nt{!csV4Aaj+m&;19U%cRaY5xMxM_T zin5={0#mNfluA{sPWgK;d6f2~5gMOpu5mJyky&hH@P|&U9#3b zpX3}Daiq7r#0{`?h~~rWZr6OKm0+#%{&mOv;Aep#R)~1Q!+mS;y$JYj69(TG)DZVX z%dDG7MkM$amZYw4*$_$3iGw6msUE=2n96jpVRpBlQzFJ2c$83wI@i=QcljX zVy<5cxJ7L?JyyiNbyW&~R(U|-Gk?K3H;<>PFYm6zxn?dBGG_HWlDwV&MLBQwQ-`-q zR`@ynAiPVpXxPIjUNokaL##RO0tvy@YJNsC27+4)bQOjZvN%FD*h6$X{j7TK8nIYN zbi%vF@g68jsHLeRS9P`xx74)W(bzdw_VZK2?ZYrLb?0oXY=C4=?l%h<`)&|fhiU!n#|3d;hpgBXRP(nq?( zfrsCn`7OZ$IuCqFaXh8}zr{>M?K*D|fG>S{^!i)1ARLcJ%n&K?3dRsk6!tBbac+P% z8ubd+;U&g!rg)WA$IXys%nhYQ2Jk5!7;|Uyt?Ni3gRmDOSMCTK=bSiuB?orf0NMiM zu~RkWflh7a8dYAb{U+^e9OdAU7z_syL&f@A^n{A{oqZC+U9mNwY4-8kc5(KQ3=f7X z^N5R^2$fSj;7L)G^|m#e1-^Ru%!<$Ah*L5Lf?E&^10Aluv3UyFNEMIs$h;PTuG92k z70e;_Bj?bM!6huX)K8^&I{}bgiK9SdWE-f8Lju; zxm&sMVk30bHs`%9QQ*3ruC?(8EK`Y5rI-uDX!~elcEky-?=nl{BmLAu?i2Ko=3Q1=p(<8#|$zj z(%U;70jq|>8Xct+OB&~_hnOb^R*J;z)qdCQpFEB zP1gdfa!f%)H3^zccfO*@p3Kyi)Bm`OnnN!!x{*`|k!! zT}9}o{5V{c<&7Kt%aI1j3k+|#sB>m0R>Gu7>r?iS%ngfE z<5zBA#M z??WyUq(~$po^k$Q|HB95Pl84x$JaIhKnHg>ydym*YtT)c^Y(HL07(W=f+X6;7Nfuy zQY?7A+kA$E)?%DNle|yo(FNcbzr+!>52#?g?_^6Uc*^P`wuTw^6^>M%{A&2)-O5yB zwft?qrhzkhx(bc;wq)L{(`%Qs$xUjXG3U$mhoIuCw>Zr0$xFj#xm4#wV%rAYE;dY| zJa>?<)6Zh>Nhh4EgKySGmNcm#R{7a6J=~)nN}#XdU+*0tRqAN+x>fO5{pF3f5`@Zk4SzigiW>6ybg7VJA1Sw)0?=b~@uFZSJ$9FDFzOb14**2cG zYIMiLn8FaG;YZdr0uqdHlk5+s+}K67T_4Ve`6Sl6&~8B-dsL#HtD= zdiqM41k}VR{%yFNTi%+LI3BrVq1^+n_v8FtJ|Ilp^+YWwdhshy)&1sd1Y%p*LaPt} zOtgAUTX01+_g?Um3x*pXRKWgXYgMJtCtZV8-2qGPIX|!rzIi8ahyk13$=vsWDo*p} zndCkH2l1#c4Q9etMRERt5IlvW0X_oAkBH&=eF&hje2;4*9_Q4gNA;-{X_OD(>g$4= zlFI0}FOdL%{_0CMEzvG!v+RV0$8%A7Jd)@MqKT5V+RP&u`8mW1pYN9`5040zvUu&& zN{v6JO5dn=S1NYDH{Ix~mQ__o+;Cz*^q#OPO(N##t_N;JiGa5D` z&gFE%EWt6m^y8_%M;)_os^v5j7XqNpRp(wwxSpak!mJK7Z{%l&a7TT7sO(n9B2a z@lOuo8;LY3Ub>LhFuWcwO2~U_x4<1X>lwtRak4f1!hWF3)@S8*w7v8D1bMG%^ZHiQ zdDgw;rCu!E<+-h&VC>WXTr>LpqLCDd9`U%ekM#6BKfQg*8Ol@r0w!|mO3g}~wYX=d zSK<>@0tc^}I=@L2e2A0-cdu?}_xYm=xcm%5nUcH&^Ib9%cq(!7rc87$OC#)kZ z#R&3r$b!^&Olw|u-{VG<$dp6S2=d%VI1Rai1-S&;8|~%%r7GGoeVwxbcs;yi?FAFC z6?fv;{ChI5iEJUKdyRPGVp-iO%?nCCJIua0O=`E=V2Zwpsv!TK80}_!AcvNy8ISw8#RWTIvx2jKsq>m8#c37c)pAba zYu$Ukd;ip`s+F0mYCn-r#*Ww#p}RN$j8;o|_)6lr?H;24m6t_?sVOWB_h`2O@HIZ; zgI%!+r|iz7xyJyrt5Jr9jyFV z7$%u?4&lEpslY!4bD92ICSl5qZB#}?Iwt9eMoR`8G}u-{iB(uR712faYbs1`RYj5z z2?L{$koFA#uVJXu!LPVszD<17Nt+ey;m$+!{A7?v;N?hzgR2R^vo2O6=ySH!rKYkp z-kgO8?rc;TlN4>sv>FLQD;+uap&?+&!vn4`u06C!;VO8Gh*`>cQrx(PtxU7I%USvGsP=3vxW~FLaY(S-nj?cS5 zJ0E&ydCw+ITap~B5S&v~R$cm-GX|t%77IwHk0!NE5ddgqMLHZ=j=O!oz`SrQ`;Nj%(8VS5B09pQxqy zkK)01(&d8_Y%yL1Q-oP2+PS}VAM2vJqVXz!Lah<$6&JOr5X#>?4p&;T(QWBcui_cr zfsKVa4YnK8K9o$rMMr1rVXeewa3ZN31@Uw0b?_wB=QU*XvBddtfoWniDlmD=K=UxG z%M3jX9p8c7=*5G#&@Nfk2B?@F#{EOQ3>-scVU>PdTo#$=^ke7-wf!hgpIn>-PiRsA z-WQ*6G&o-knTolOMz9EC4HhiP$tE&SA91KKSM{GTH|k(Xtnv(N%bsD(PAiKNIGr#=v$&wu-(K0vu# z|8y+s2(rQ%Bj4P-Hc*ewdb%|>L^Pd3!EB)jeWb0@UcQjDjAKPcf{EhP2Xlmy{DC#b z(|l`cRDQ*NpuUd+W#(MSH=ile7v%{(E!t0w7){b<&2hrNNsU7?*?97_)^N2GX3haA zA|_dn<1m_d_{KNgqhr=+LtaU%)Uqj(uk{jH6i4uynWsu={*aXZpK~ zP-X8Gr6_ZhbWsLgSh3}XPAYK9kmRvd|2gN=F5jyK-4<<5mdc<(^PN=f$3HcJmbAE; zlj=0M-PGDf>HS=4`p*eusvtL$ja>zq>gYH@)*Kbb0;_DH`x@=7yw38I4e@-!1stwW zUb)J6Ty1V(bS8ffgb`TPN$R9{2R|4T2}OvOJKqNI-R|rg8%Yv9ff`ABlyJfKmiLa< zCdZ*;CY1>%n@-6v!M+!O`g;NX$#ty!-9B)osUr`2UC$t#)kyqwfs-`g!K#2y zQyyHZ@&=(u58`x=>NBr(qjZNa4((jztvs`HdGW%#^40uy@n z1b=Aq1MU2FW`=dDTL z;&76n{M=R!>f>u+FEG9uwGN`v7cfoPu3yTD7r?=jA}X&Lz+aJAcQ>X*=bH19pNuQ_ zm5|cuSi^QuAFh$}Mu$}8l8V{m%e^^$TKwfHenu3>syaJO7Hgr9*DaXqD93+Gb zw%WJCfVWQbQoF8}49w-ls`x%(S+B-Y$EQ*$W~k5wcXdfyYF`ij(9@aRa(e|+gk@84 z^24p&pBMO%%j!yXJBsW^=g@6WMFvr{BU|iKUMAJy8^ibj=gb_#8E;A6(>(&S9hjj? zhU9mj*-AW;tll_0@!n2Fi9Dqfa6OAZ6*g{cU^HU|r;2XIyFb2-MD6=;Pkx7Zti$56 z#D&iFvnQorFk|xqQSJ`ye=jJ8N+{F`e0ib-mRhT+~=0%6Q<#sxD$B-H^;hC@=;T?Ld4+m}k^aRQsk}p~R z+>w4yp&-8JT<OSJYM@Nj^QQU?V9zY4(avo@t3s(jX9et6^j|2P{I!FR4t~u zf1!kl;=+u5>!Yr+b>{4gG7`tWsS41~Z)DH^U&w~>JG*1zBk+tA$nG_`vXrA8I0c_@x*7Y>M^QiJ|{=kc_xKpB3tL-k9zzfgewkQc}&SqtDN^(t|_cIDvB5Y@wco zi5Jui2XM^+wv$x)gJ*FoB!LI6ZqYQx$Sv%vZzVDOZ58Ndt_3&Q{z~^X2A6HM5UNdW z_iLU5(e`|GC%5@7*WcFyxiFT~v+gkP3fqE6m5`=xy+*=>vsQ0u7{(-{Z;<_fa=HI8 z)c>pbhHP*LGo4c&WpS-#Sq%C@3)`%tW4@4yye@Xw_tFcez>~_&mhE{bQiiA*YUP3Q z%EM0%G9Mr`9UV|b6CIS_~`zEqC8zVj;f0de&zi_9epYbJ=N7q8@p zNTVBuZHXmV^}K2S&MbtNX{-omlY1MmavjW1lET|#ilwD8n&7{Ron`h?VG90JFz4ty z&-RRCctitBdka^L&$)t|16j5kXD}V#U=eG5;Ke@o=`)e*^w5pYNY0)teT(P&7_g<@ z#5~a`3@29(eM+0w+IhS*I<>Qa+V&E1rFpqC!hB7r$|-M|I$csN+;{VAmrk+~WtaZt z=&iiA#O17BN_`?xwdb^4V_<>5YuN!Kc6PyWK%v2*Bw;uZ^JK)B2=hxAyFj7kJ1DRy zn91}1C*U~ihK^yadAfxSU~{tocx|MJmd(e1tRGpLQv_o9L>A1egibsRO{ob+c>p3- zD{VLrPF1$k{H%FIVzBVbc8WdOh40-YX3zG9pbci$Sj*~6r<=3F*@If(X;&9N2AFJ@ z$Lpw1joOlII{6S+J@@Pt3DU&6yW!((f%DIo*cV^chL>Hv8Cle~)Ffe8&wXscH3fw4 z#2I2|)oKrC%vj)%Nd08wbEUIvv>3fd<;0~EE^?E7>?V~}SnjEsur8aL+MS!&k<%RZ zp4)G7EYa;ncM_LTGX8t~u;SA1%R;0cJ+>y1av&$N%=^kf*Sdto$?V)S3{fJ|s|^~a z+Oq1{*V+IUm(lA5y2~c!V;m=-WUEtA&&kj7WuhGLSdD1z*7z%`a=P@3A`{!2 z+Ek(erfvcGmx@Y)YFUm9GVF~)*!O*PUx9NhLYvro%NqRbPt@E*+-__1Wso{#{jml; z4Q_H1hLc(ViDA?%sP;hzm}K?pZj-zpjrda~O1C$1tODlTvy>Z+BCC0xM{Zi@s1BhZ zXu(QB#?GaV`fKD4ahQls0oRarr1#&Mvs7WCnn2QPgrsa*x5qJ^ypRA2lCMGff!-0$ z*CSt1gZy$z*fhWU`js(Me8FwOk`qslGfR1)pvk2CAU?mC`KB4r^M)R#ig!{+GdU%i zbR_-pf%&u3B#ux)-u?-SXr5yWSY;gN(~Wn^+2|hj;jX1M(dj*pEKhh@b*W~{;$JRR ziDM{cM9t(C5BD}4(R?*h&bzJy%*07ISy-fYUK(D78eO%NvDa^yGsWIy(}sC!xk7P# zoXYNtYF44&_cUnDr9zm5_v3V+l1Q_N`JY?tHupN?(h3;2}s5EEttuw z*dJ3ZFugJ!fA~UQXf%aIFbsgjegv;a5A0$bBg1VOE>Za~z z#%MwjrYW7K1-DQoWE|Bd1vH@GXZEIulzGWk)9lK|BZs+-N-_bY3A4>ybUn-5?~VSe zAi{Nhs+ux6y??8e`nJ=sPI2VHD)juKa}sSeImDc{`@)MXWx~*E!!%Ze^p0wOLAooxwgQ9kdIjaA6N#sV-5m}tCM3zp^G)toYSD$QU_uQP^gW97_i z^D8e#G6PICDI&FR2a^mRq~C9 zbl*0jq~#K3DoNSji=_%n8=uu<)}xe&euK>ux?DflXC;$D593|wO7Ys?7Yjt9y~O>A z7A_*FU>hOxsY>~Ar@`v)`x8g(7r3^^%Myn=G~9lb`X~ag95g|0E3-D-w3!j&jL+HV zJYEs$W%0B#a_)`Io%iu#R>b9qcejsl`lF)P>LJKMNEHH~l!f1|1K%O<8&ddoy9!zH z%)UFaSR=DNmv7i`^}?g!Om(5#idnFVZ*(?`fOhJNzo@AI+hqHQ-Sf7M5hIVhhh=K) zzL-lu#AcjzER931=+I9Lzma~JQe|{U`>xN;H(YVXI ze0`4tIthoNzT|#M0OGIK@FX}09?(KMi$JUe-Hzu)m&WW{q-tw(e$S?F`99P>^7eP+ zQMQdHxqzTA5g0 zTmQfu&xC)fM~-sDl{QXi4roo%g&I$d67KD5S&oS%bTdFJ%pc3-|FbC?xZKv!5SwWQKTl&b4=JFp6QR*u6Q z%!`H|=2jnknef z;fR3hn4_JqU*+qgD=tgkS-E|7Qj}WkcoC#AwcYA(yR4yf=Q{?G(mojgr?wYgPYkL*I+ic&$rtxRREno6b7Phib`2(Btc|2*^Hy^En zXoV)D@KFjQx%(?^K74OZ^;oG8UxHtdgNO7`2vp}xlqo$tSbGav7N1OtpNn(zf*0c% zO)j0FrUrFv)^f(O)(|tA?FMu}yy$(iAn|Kk@O^y{iC->GUUAcVJrVxG?vU65-H4@K z8clUhxg0A#4lI!_Qmyqn7o^k`a-4N}RlWLsd*aoy%}}HNCKfI?m;A&y*D5G9=<#p;%U?Nt~;lrgANST($S3MJb_;;3hchgofLnNmRZ-_XtPXjDRHoh3>MH?|@1xaPo4(VZ_fYp%8^X}9O+=F$3d3d1xDL;06obs262x1V|2fJON)QqK zsEIPW&x4f@b`tv@#m(b)aoejQs)5=`)F_j8szx*B_N=r)d{eF9g-vJ)FR+DRx|BPX zel0sCS@y*#qb}&zX2tRp@EOMCB3CY$m)5k&38B2PrKdv1>%n)E;n8t6rj$6Xd||7D zgho_c*eMct#@V$Nfgu^5NBD5oq&Bfr=6UkTi5dBNO(Z2>03N1CvmNXoKQfb=JZ_af zaKjUs8MOjOZCkQ{aO<`?YE`*!D=5xzxS~iIJK@B+lYjmP)nl^FJcr(m1htFT^t+L? z@6TeC(QK6-J*B0+ z>-df7{;6E~efBG)IZrJ{Kc=);DgP3`nh_~VFee;0yJV`x25atIT$%gGxN3e{ZbHhA z0i_`Od4m_!qvdw(^Xi{R$X50@|X6L5Cp?w(!z)&x(6iD4jI6($R7E#vyyloI7KPTG>{l+>JMkB9r ziHkCGF=n0*wrJ-L+T$4%nL4ZZ3Oo^|U?@N<(q&d#-VJ>>W$JJly8VlrH4Eqd+NSgV z=I)RX+n@q8SYiR~;c%F7$+u2Jz)O$DXQc1zp#(Q+!ARZbjah_!ioA%2K>C>4YEofs zon>ZZb+{Z4X?7!iH$02Lyv}w-n|H>A(n;$i)N0I)>T1@$=DeCQS><5F*&OLlc)Gx` zdnyyG+uo~D_!cd&P0~E81{|72!;E(u12>k?51E5Mf0*t15euEqF*zGjqhNC{iMLz zy-?;fTkOr5ga-tH%>{1)cS~;Uu(6)PQ`4m+3azL~d?6aZR7B^2-DX7*GV$pv|J?Pv zgO)u~v;7@RdhV04WeRj{q_2$D?mCbyaP{d}xv}+5o5Ox`_#8m#qNk^j7d$}nyUxy& z>xy4tLpEu~-U$O@fj?;cM~WY=1Gg=<7RFFB`jBHa;S#PrT(u^+`(V%&_;YS4LS84$ zPUU$|i*52%e*20P%?JQwMUDX)0Af`j3TqbJ!C!K@6Wz<48V>BgrfE@cPibJ8`_&Yt zI{`eLA3=~dqYwl^mbV-*Ix(2oyC2nq@{TAd#wB56Q4K=Nat6EU9a~DvZ$S3?K z(v?%q_Ddrl%@d?mmqGEr_PM-w)~6vO6%;{9X7M_ zM}!6aKZrjkYVC?~-=h+KJaDAM28g;WxH2GG-X$#oh>qW;>}sTAVdQT67Ir(z_eTj} zikB_SK!Whg2w$G#dXgk;)IRn=EPukmzhpE!#7ClbvC!mx3^ovI4pguRXK zQhT}m*?y+$t}ipanC;5td`}Qv&>sm)#45p@arOrECBQ7jt{k=v1Bwoie|-#=y2^N2 zp~A)BXxlhp!k;M&X$V3MG`Au84)(J&q4?cD<@jkAPX`VWAO2AkTZ9-}=5NI|Clgda zR0CK=Ql3J<1%M$6gF-MHyprkfeb)9-rlm|MpcGNnkZ~QxnT^b>vBvIz#cxb`BxrP6 z$q^uTJm+-GH|N^Q2n{nbir30AC5F#WCWeFvfZd!Z!)I!BzdTuH7dy(bUW|(cUSloG zt2rw7J{m=6zlth;G|4o>&JOn!i1g2L+`K_te)F}7?<^U(n_#Z+e`m=o!ieOBJjLAG zF7}Vl3JwO&b|l+>){3b8Vg)LVf`t^0J4uh1U0gve7q03xQUtO;dm_YyO(w{se-Zg9 zIN;B%qT>Euv2cgT!6l@olwEI#SlG6XSI_44H5Ae^iYU%M>08br|BeHV5M|#Kg};og z+wh9AIDHU*(*85lFG|)H0+6_V zE4UrpxR~&%Q34x|)M98Vqcyef5L|HZmx36_G2jV{)FRvpbH@<5FAe)VE81Ff%9?mi z&PP7GaG>cz3KfUx94-BMJ%BB{)9*dq>czlle@O*J@^>kD7Lq_H1SGArSX%03!rq)R z626EgpK7^fHE$Il4)<<89+HP(lIA`_B4LQEmN}dQKiGa~U8C9yliV#rc*O|K>)dsu zB;EFXk^K%fGAwBA9K>2c$u4~09rcc14p&_n)ri@6V3|GyD>v6%R`VLWlW5RSC50#z zO)Y2*sixvhktGYFZHdaDrE#ry?;_j21Xuq<^?=%+Q2ACxMVfB2qE58;eY@L>&EP1A zNzVbz;3{^jLJwNd`U{9UZm`EeJ;yUC#A4okiLUVs{1UwI`0;K8&1L*F2i@IOt#kL@ zTP?MW=Sy9q{RWl|iU7R{q-mfeM)ZZBJpyJE|6(Hm@EooT=x{119?0D;>U9xoEc%vkm?{N7hd)nr$ z(+V>rd^^jeC)_$H>@M39K9y+bG{liu(J`toh++uB zk>+gc34(8Luj9TRtnqGryl=+RDH~tHnI{z&o%1vK{$`LqpDM_SB{EVI#kQ8HvpZC*}z$oaPi9lE@$zUsHWRzzF49Q88&y^v7zpbN=zV2TGEf|dh`d=JNpZNB;HWUO zq$w-_43l1(Uu8&)w95dyMAqPyO*B$Zn+sz-j8hdQSt#ju8L?hw8CLh3zc++LHa0@k z{3Ma~M=UO%t|8+9XkwMk4!Th0$*(o>=Q!-+3p%ywd{WR^_GRCU(0K<1cLH_RWj7!Ov<9*ogB1h664_!V331ajGT~i$A}O}k(y5ai-mK- zO^oMx*T`Qk(A*!EzCmh`wOY4j6?);$0%ct4ppvwYNw_-4_S3)ew`gC9YRpQ~rnyDb zznG(cWygfwNqXLv#*o$!r z`AI{c!J0}QWDZ{9w34P{eFg({LMwfB)x69X=_2ZH@S@#wSKN~5+tx7jlvGg={i(0Z zc?ex$M?aXi>`Gdm%BL2n@yXI@+_I9=>ZRzi45XKyhDhelMs2iDGoNukhI*g8Kp!hb ziz#o#qpm+uU{1Bex91W)Z9^+Zrb<;nL^=#am#JV3e9|8nPcQW_RQcDsVhP|EKjse=<- z_a!g_IIT5jT|h|uPCpvnRR2&3l#j(AZxRZ;aSOPUK%Vkn(r8TW&v;wJ@Kjf~PSPl#{l_8M>?zo842ZPLU~Q%!_@cvmW)LIQuGGg05y za}HSZ7W%bwc-Wj#a-OnZPLi*e=f1>$tEmDUm<~$P{}CC_TV%kNArT}o)h?$snu79l z2q1h^DU<~SU)hy3DRv^Gz!wpr&Cjft4supL!W&ZJWa%D@EN-~HuwB`#DY-3<9!{oG0o7>EH|o;GELa{tzO3&&?0 z8NQDS67V=C1cE_j?5qcMJy!uC)JC{!(M&9PLd_XqOvwF=(d?pr%+;#I` zEX6Va4UV$(5l{(>9Xz$HO`P_94@`r)QD?(B@M(Vd?AYVcNumL}>9Ek%%>~XtB<{`4 z1t-@bj(Is7_R{0)dh6V|movO@aJq_dc3)hLcDP8X(|V*H%t-qwmMOjE1s1 z&<15N)J~?U^429GoW(RT65b-I2Vu4Zq%qJ(j(@gil=&jVBbo7ML<(ijN1oRxlepNt zq7W8pnpcLufTG@jtQ1EH@kngP)cpst1S+uz)VKY7XLY6jrT+ifj|e;f>x4xgO>__u zKYtU&zRHgw57K3OE;?YfdqiIF^Vfp3A_H7R7dUp5eDIAi$v|-;y+h^x-zrU6qecP& z^3jyquZXzAOEghW!j|<>PBcWo!-d+{m%+2tFmJ6mn8PxQx zdy)|OP!8}cm=^6!P|5niVO9LWkq2U4dF|--6`-JycUALY@~stmVvemXbcEt|{=$VN znpwS^BANi^Tr^6F0Vs*!8ExYO-vdo2surwc4N6g_Io}FGhB@{SwOgzAPi#?&zx_Zi zY<;V=DLEE#1?UdYC5({K7PDO=KIC~-t)thx4m2#Ct93y+((RQ=Zt8Vh6Lfekk=5=; zKa>5Ezi4;B7Nc=COh8Lb^We$B;oV-@A+2@mjD@l=oPU2h+cz)-uonSIA#w-?>EKH?d889UJW9%@H4nOjwUP266Le4P*t(p~u9aYwLPPjp zfDST63u>q+=;ny&yg=ZUFGj zZOp6;bii;rKxP9@sP!S*rF0$V)&p8UzC4%TG7npI5mzu|_ioKGIKcqr|2LXH#)M9~ zo4?z;^ZB-<#>bztr8cB~;xjw6*~}z30&fti zs4pty>uK}m?x2P^*d-wV_h5wR{G)N0)043mtsfbfqx)I+KM3dSls#TXT+4Xa>M-+J8$ZE-q zhp0jo;3txHI03QO7CmGiT?M#y+sP^h5V1|FaVNpbgpb8&u%E8~7jWBX zr}J#z{S?QJe0}71tbld3AvGX{NKh2+*xVXWCC*n=;AM#Jk?GOLaXXeHGj!~HRVWf| z*53n0Bwsz7H4kfzuUddO=j+-4-L-u!(>tn{jS=cQ-C#K`g=eV}N`!^$LWxXvKqyTc zCQp#OjPQoxdSJ0Ny&{1k8Sx&-Fuk4#*P>;}?rrHZQObq2z5T)lJ;qL0TN|Ka}=##um35BDxVt`6@1PoiN%BMmd%!61;yfb|7d?)Aj^=T8JvIE(|CpzV)34cR43 z-w_Z{3u53%A zi^msvq%Cx=3fqb{z9XZuDe;vbZpDa_6n~jY@B=8-5No1gmS5~>vn&UNrl5}00pfYX z-!d}f2Q~YA(S;*7yf_*?8AfGWEU0^2;Ep+(< zk>5SCbwCDC`~%DWqfQi@KbCS^Cqj@-*W$nll(H0~ki^LKP14s{aE-i3=1(Z6;I0*e zy?$1(;0dVi$nK^TOT9MUK1N@bF-2&GrG;5MkN4?2%DSr@;oUHgZghT-eP)RQesA_AL09hDMZkPpH{ z%Kp7^pX&8No^M-kq^;_HNY1^lv4TInOn%U!4{^^=k~s^NQ@J zf}HXTySE2seE4nlis1s$OZDKQSb#SZie|&AONfOyRdFXwS%0Tv$@Pa(6(O9xPAVeN zsT8ss-D=(e-^_2MxxK%|GzW?D+4+rJzDIrl*!?)MrmnTUi9bdzSU3Hhl1q^HqP^90 zPqn9*jojf?Yu;O)UXxO!Ni6^NdgVK-s*v`fWDAv-VUxHgRAojDz3~G(-*Daf2_KP4 zYAG@w6+hvb4{tgrlK!Z+GiMRK=>c=fpCV=Ybw-6*!8Aqeb!WrPH?DiKyRdj3-T>yaDVK^j1))56=q5{05@^<;DaIzpx zx-{R5>O#O~*5OXR^F)mStOtM|;K&*@X_(W>HLOL)6C9%$uFwEkz6iUV73N*C ztY~{i>G|nd#RD71U=7w*;j5d4$R`-r(h$ZQuNPPs7+&c%-2BrgsGMA8#KN3P$lX`D zrbZC*G2&a_aZz3eOjE6#Q`z&HVGfriG{Nyokyo+;eYRZ_Dfo%CHa{=_djh zU^VXgt3fTN&l3yw%0F9ow*4noTd8uPn!LFDa~!k(+(>uNrF|gv(r6>X2%fSDb?l;A zp%@T7=?fbx2O#j&bLq!;(?vpNDwjW&@o0qhNJ7#DNeG&D#reaQLIF81Nd2aQqO?gc zaqHqUy6zs&x1B9U=WGFXYLvePNpw=zV3s~n(rvb#{eu<=2mJ)amjLYA++Mn2#%%i0 zu{H5qCqY)d{AqT_dR5wZzJM{Q@%HH6j+}m$=KL5=w;9oJ+L0Ko$U+l^lMg?r1g+;P za9o8zw8ly|HOQ7HS$<{!r%^cTCz#vPK$|~?{goXJaHComqM-qiOP8@$ z1Q1`NLDgept!^fE3pY)h1yNTh_yMbjYf`!Qq`xxpp`XU*?;OwPT35gjJcWmQG1tT2 z{%_-W6U4PTmqtBSGN!7=(j{0kQ5-bpNPm0G5 z!c!Q`t`u;W^BWtyNZhAURQ2_sj9FwCB`I!T1Fw(Zinf=0p)Iu;sRb7~bSW7F ze$SM|oy~1V-oc8IQHH~CGD52{Z*HVBUai+)dBB7UwsDfCR%qiiUp)g2G`$I2S)!Ai zSuP2;Nd*z_UC9O%XfVvXlX-KV|FBJ9LX?}aCX{tNPLRW97U3f(M-OK`-+(acT4Ym& z+W2VJek-m7)fT>bAb0r%&zIGY9nALnY%G3S4a8;wU`=Fnz~bGmC!%KwtG>h7m72Q!q`iY(+CgzV|+_bX`QBigkQ$E=jt6vuX zL2|ttC9wdefUd=;Zj{Me^i1uz4KoJll5unEYZw9F6fDxlBFqg8^rU7R0_Dod2!M(UDD%%v4?udKuc zRoLZH_c#!>(xa~r#}7<5{@e{bsCx?WeG&%i{stO&N_b<|oFh}Lp>k@=?{IwQj17=P znH6!s%zxOqqmtmk9GN(NKLHYEfdt8 zbNtn{A0ZT2v|1epAn%*{bbsV<5k3jiwtKPWbL9(G8n?rx*{-HsKE4*eKzvg ztV&AJ#oSxBUeaw#9!bK~X7c}q*fx?gLwRvJROgEzPSTi}7DT>f6F=NFNs77q1lLl` zFT@DgAdw@Bt}i{EiVPHU#VU6D9P0$>d`X9JaY`RShZID@iwlAqiljCl=CStCfXk!g zO0f9gsJu!sHNe<#bVVaS)1LNYp(Zl!rk2t(rg~qzinJ`lv%p=qAs&G>x^LL3 zrIG^sX)*pP05Q%5{-ABoW0p0yN`V55lPOEp9tq;?^rdNlBn5r#LOuL8a30|>%gQBm zxRBPU^cy+QH-+!~XSD)U7s_vC(+rZ@WLpTr&gwt*lR;SZ7o(}Hle&D-Bk_!IKTwS8O{{vq>z+E04Qa>kO2ZKvChs z_Sq}im2h+@7TU7bhI5#%wmouHV~CN$#bX;k7U}1_3>IOMlswkClX{f)M3zT|@akR& z)0ietZ9*yCd9zY^(DI$*OfU-nhcjaKOc927Nm7$Vk=Dy`LqsNQXCyhDLI)+VeJSFt zjA;ru<7}B|x>X3wcNs3wuWuvyPgvyJWzO?Gr9-#hfD8GxUvE!{w{7*H7~}A?z|CR! zI=<=}LbsWKfITMlCiBb^IM|vVVrE^`3{$8oq6*_`)Ml9|6}zixsn5^JcD58%eLsxz zvJe>D;7;%Zzf&lUnp!aCSQ^pf6{M;_{<(O5Kiv6O#np}_MOd5?=$*}XU%WU>8-)g~ zx6xK}*&978lf5oVaM`xJUhg&a8%F^jjt<=GrVu#Bpyh{zBR{k?x&Y$pM~*iJXMe*I zp5#}tQ5QztSp$gTpE?v7Ve3RVN?Y~?6ye!EJw1p7(C*5%03cku4N<)4ppjxS8v7+M zH+Wz|0HAVKiEM%#`fRwj$^X1-Nh=+>o}FI+Zr)%NlIEzC;6wZV855pIGmV1iCyek0 zCCRKAQVq@|&~XdaxMmH7P>wY^sIwhst&OAi z#x67N*%;H?MjHs-DfnBtT>IYH9BjR0QI+^#v#?1}@1MVT36;nNzgL3sdnNvb5#$A; zR)S(GPlk@50|JsREBtcuKY@UdDLfV;b`9C&C!N3*y%T(DEBsa>CO%D#^?8*>x$u*Xs~@GWH)Q@(EAyr=2-Dal#dls574JP11&~0BHhOPE3}t}Qc_<2`=PO?Z=mYv111J4M?B!4`Tir^|5a^$#x4K= zK<5E~4F79z#eeFt8Nate5Wp?!SCm|79ssc0JbIPCXxf5- z_TR?VwnqHD0gyV?w%R>m7!z5;$=)^sm}1^bYr*AFcE1UMXfgrZV|7TawwiPUARGvb zAFjgn1xR61f9cmwj{pL|OVXs~L!>_?P649Q>%gC1T%_c`cu>#!PZ@-u!68Acty8L9 zxA97Su#&*x%K)H5z&FL*K`Pd0&VU~m--!Qj7=6EI`UV-u5hz#pABFp#Mqi}l`v(vy zJ40ejV2przY4Oa6sK>^N+yz~`K|d4;oJD}|BY-L>Xnaf^%=xY%Q%7Se z^xOwj2m?eTJ&_v|aQN-tl5QKwLPYYNwwq&qNCWB?Mhn7$%N#^UNAUH|?OG6Km%}Qs z&*b0{rvUW`oNyvA{3k6MB^vY4oilG3E8xz4P%hV5dM#sn_lT<4}B#%`p!5M(7aPOZW_LKau zuYxp`b=9c@0AyGNX_oi*VSeFZW`SV(za=Rfe6|5QXjRxodgcu=r7M67Y_8jbg-lC= zW9t277?S%ybhvn@zJ9xY^q5=UJ}=@TGwvQjN zgH;U;L#?-pi0}QQp=Y2Dg)+TF|GEGFL_O&H8=&xS)M@^q4z9e5x3{qe49zUise(!K z^ILxJwj8&{yLQfjN}0_w$@g7H-MpR8gFyXMd@gx6(#X&;t7b#PrlB&F3#2ZD5IcYk zP9pL*FgRBVk+$X(h?qfWE&z%X$Xn6tB)GoMsV})^9U9{f=_d{oiGGE{*LokCGu$E> z1Pb!B)7PE?*UGIdIKTPtq^c@n3G+RXY?>kua)X@_4JVAY3ouBCX7g8T5SP7O?M5E) z^|U@^i=qdAh9k4AN0Y1?$w+_r2o_2nDzQ^I1-%2QmYTZLHx9f)WI}R70Qp1E1Umge znCG;YLsgAF*i%rSKUT9n`|+L{@Oi+J^7u~^yAkG5b>R~KA39W|9#KN?R%0a+E8QFb zoqjo!kKpi{FOtzBxEINZ;ewxmJi_7$3ZwOl5T!?|{dLHyKD<#u2>x2D?cRU11HF$; zdR(#QOp&!fE$T|?`8x_hYR84DTxYBDzkbP#hjRV~`?NZ0qZ$Ay_@9em_itw^7R=N$ z{h!Q~V*HtSri3)-*omrcM`Z&pn?zk_kwFT$;!g<4O}F#lud7>&%MOm=mkBAoYRke7lLbg1IJ>|7j2p#G|JbKvg(sIrY4I zbqq$|0GOoF#W?a$sjopSSVvsKW8Gb2=@VkR;0;NEVRClm$%CAEcel)f@<;${8wk-R zH7MipFZPZXXo1Zx{C%(cB6166h|H&e(5WplLov+&X9faG2Z=Iiso^v+GIb$L^2y|m z^#eYideD&%9)PHYxH0S~v7KC^F$BCWxqH>tB|>+}+*C#4(b74j4CFzq}kD|Xk zxla9orQ@PoBap|go7hCFUHvjdd-&_zMv&%)%Lg@2r9jDkquiGDIb#Nm&mp-6T6->> zZ4od%0_C7|ZfXYB@RR1O*bw2X<9iZ9+lu6O$JvHHVSaXCXmNz;gDfji#+7{q01iWm z5O(U6JQ-(b4Ujd$3Ru5u^y}7%=efIzL?5PCJSjG{4Wa6e*y82#NtRUCxdHfPLgWwo zv{&|bxIEC(;7+ksct|Wb=;*-H*1Qn;2bC}D6F>{;$B8W37JWXdnaa-B_)Dm7;P5oJ_eellTd$u%?C78y8S3{_R?y!`9>cIejd6Iz z@M0NiX{geiwJL=>(d;IcVR=eKM`!nAB26>H*225DXe$EB3v)2L(PpCX+n%xw?4#D#P9SK`M8L`wHV?W^%}5-#+uakxZ8Gb_P;CbY2IJojS~iT z943!`wgQE>0dc`;GFJ;&;uTr$gN4N^P<1k{JBV0jc4#U=oS@Hle?2zP3XuPgxvzk$s#*J8dvChCq+7bXyQI6M zOQfZdO(W7E(jh1*At9kO2m%TyAt2o$4I(0Up}yzU_nhjDEU{x# zmHq|MBUC2?k)}I0po(z3IOch2E}}6!^pA=I3yqc#j&sCX-D_eDd14v8$m8yBy6VD# zbUi5(z0_|J5H^M`9{S*EMw{~CQ0sJzECHO6@rk)9HxG7fKS3lQ`<@fe&7qEuaLOmI zY;WHf2A5j8*!lFKdPoUQR6tL{H$P_whj!gm50;~Jr5hE3_WG@E(`&_<15$T7Z60=D zphP7DDDTrTEh~mog{sjT2j0T(c)I=m;$X< zab-1tG#_Ad0RUu8fMO5m1t)_Trt<&-`B%j}V(AUl;Sh8ZKw$#FVTGM~G2M5jEil^G zLW$p90LYly+h57d7f~Lw%fh0;Hw7Y=NNK}G`E9yn0pK0ONM%w3q7>xXy4Muq6tEoD zH3>ok-}@`mPA!XpM7>9mBK6M)uuITNY)H^Ws3Ct_vG1x2`2K;Mg0%ymF5Uj&V*Zi* zxAQ-K2)AElFXTv8xcZA@jrd-o4yqi2{^Glo>z}5Ga9I88VT(V70#+t}{Q4;nLJEk$ z|B`lfNWB0yNeCp*<-1b{kbXLs0wCCpy!3EzS>`N!58b0pC{j1tISQF{MPf{u_F@^b za4vE*0AWY!x@Pxal_|aY6FneHfySrwW|cqe`V&Ch=IA7Y5K%>hMwp#?yN2NP)7=dx ztOv$0Vcg9jV{9Q>1Z^ya(CbTvl~~nL?+*qcWI+FyMz_VU#??rl;Jmo*pEp2*Cl~`* zw9OjIu;$CpR3lL~GvF3|54g>}0iN<1I_>rQW~;?;)Ur+dTWUFGbR`f%&W-!$U)K{M z7zo3AcK|?1ia8M6rWz26^CgG+&j3&;#CJ5Oqm17bK#orQs~ymkKqHufM)>YyU3s=) zB>=Mg7C~ED?C#0yd?svhPITx|gZRq(;Bppc*0;RPOQ$F-BR2Sz9Gs-Jm{)CJf#Oh zVN}O5(OKm0G_7C+WFrep{Ed@72cM51tLNORHO zMseW?A6aD{IG`O&bdA{+N%r;ULtW%>wL&-gA3y(i;9$) zIK=cPcTx^uU1(2Igc1?b6hFCAFKo5q0w{tqM@!g|jS1Wg7pA?sHj~Od?WYe*ey|cV0o=foa;iwC&XvplsuJ%YEidRa>a0yI8tRy2 z!NGJXg>zx4tWiL2gtryL_Bt7sGANa%YkRQh3BtoBM;`ZZ{X zDP;5k)a_Q7qy+sXGkw4&8t-*-t6urZO-(58TX%4aFvR>q7iX!OF|6XvGOX>whtly2 zp-Mmcnvg(RO->ZI=%|O$6=$$A;f;VVr9{I|me&2}He{lX$JlhRX1?~2dRVsn)$9Tm zU`mv9mdom2z121d*81{z9olHG?#L4#L5-G8Uep?^zSHVM0o#HBi?b#T!5r!Hkl|Mq z-@Yt6-Pw`kgQdH6|;rI+I9mC#WQXY4!Q0$BYFc-{sx+2jA&n^b&2P_|d zS#E1JJ39mBY8ZE?2Q4umEE0N@Z~!6eQVv>O*q-R1PCyNy2=8E^ z15bScmQzW@^m)tlsJoTG-@Fn)ym#*B3O!>pvyRFI7zPupd zV7(EsG~mG@stdBW+S7np>8+>XFbby&P8j|f#<^N75%KeNafHimg>uo0$xj^MB1f?L zd7ClS{%nI3SMy%`?bN2McX9-aQXF_l86x`g((1w^+Fw2?d%TKll78gQfwiS@`bM+I zP-m*|o=M*-ZO&8aXhsuLrDJ6?#_~@OX}eeg_(@H4Q=0V(*^+8(F0r*Z9xb_1k7!TV zmfOoV-6P9lcA?y`Sk%5_m zW}$I8JO<_b7Q6MfCk^fLBz}vt;(_cd750j z`dN{x>1fgKv(NP84m%|tcIr2I-(NO_Mh@Y^4_{wfn7!*<{!W8LgWD$ByV=kj?Y+JL zW%(F2M?YuG0Zv{M99z(wgi@9$5ozy&L@?;2HB|GZ&|+cxNm5K7;IFHfVUJ2`H0 zeJg)K_55opyMseF|KUS-eLgcc9L1Cc=)J|gTiO@^2Q}@DLY01qt}UbqVT?! zPK2zOQru2&SYR()mM)`&`Nk#Pjkl_9lgavKAU6EJA?o z+Czt|5w{-iIv{ml$CvLB1V&S!f^kQNf8|aU-(Wy6m&I&E#Aw|xTKBuB(&F{flwZi} z5@Ckf%J;dWRtK`=7I>E88GPm(A?;XIcV?RgC0@?E5S~T*D@hy_5U5ET`ba%Bytj*Y z=Nn#L&o(aVm;`^M|L-o<+0}5N5+v{LpZ+~^#Zq5B8s3BntQFIeV03$V*g2&75%qZ1 z7aECYC|}L>quDV+WkNp1AUtr)mM?{uM%*ccuK|Fvn)RgD(cD+)whnh?kRZ%zG9tL$ zBz!cTwsQ?~6ES|VWGdQ9usOIl6-NgQg%nG*$TjjULca89zBGLBnB}xhqa-EwBk!xs zqBvcoVuVUMjBb19k^UZ^bf(WNt%kz4p4=7t+&;YcSU<&lOG(1$K-6(YA48DtLdXJj z-ksFdM_4YwWJ~7IYkTXemD=i2BV%M^Jy;;8*Hi7f*=7L&X4kr$KirgjQ38>}n5yF& zn_dIh=A>I(3y5foQ~(Z2EJLTLDtfdx%0Pw73tyyhX9)|uRt4dDr8jKs89QHOePc019%VAL*yc>usxZ(c1}d5`bRlOUN=|JrXGK%CsJ zsCa&>oJz}>JK$+|(sbyJ3!tb-vpXCuG|V*5Ak`y>ks8sznyoxAgmiLc4F|1HRkK1J zB@tH+0Jiz0OSNL;EbtO&U$m7Z#0Q*zkijZkAHy5Q1L6?|e={3uBLDy=(pkZOU8DpN zK@tRJKafpxI|ue`agW}w-;tRz8)+Uz3P8w|_(cfHb3Zis#Dyaw+P&i@S!@ojpXbm5 z9JCQfxRH>;YU#pi1Z>|>LoO;I`6Jnk*ZBMJGA9&R^cF%NgbK}MviHzN46r_BZiA^! zo%NNWV&Lp{8wTrpx#Ah{GVfYDPN+?a5j@;-9!^^(c}KBYDi_DI_wfy;iC^f5CC68D zQ7a+AwaRtP`UlOS!UNIOJa>iV*~FX>_>| zrvXqufHj|lSL9A-w5i!1dy14?MOlP3p3TdiSSvlc~7bBE> zeCh=X{%F3rhJZuUeX4wVON8|O;ZRY$Zhl`fqdpuM!%~=fk8X#;@Sk=?KLJ|?3^3k> zat~F@$7ETx+Q{(RrL*A3A<(q( ztAFn^z7Hy*UxMdh=oRRw9pB!o)q|HY%WVjq4**Q!yst{StQ|`M#Qp2W;4-3UR>QjJ zSpkA7}uzr;UVu#+A%^Y=zA>U-MMB+P}*_2ri*5P9FNfp z0%*3d)qVILDvCcU^8uCMn_`n1Z6aF&uM2&f!uyG@jm>4mxl&HZ^PBg59M!f~GdzIO z5A^m_W$!||pDbN->Ofppc`rttnrbh0K7I<90-Ug<0W4kO4o#pMT#q}s)zNRwNkVH6jDA6Zkk3dVdqwyZw!Qq$-h40P zy;u6=*2A=`a}qJq9x>0*F|8}RMr;&Bek*B(ONJOS=@~R)ab%X@=leny3C{<}IfKiZ z9xBoDh(>JXB#o&EK`TZ|_XjQ~PodXLkS%~onIiivb!n?)pqR>85Mz~jC@NYbhcnl%S>>>C_PX!qmASg` z;0GDJ&_E3&@1ffF(GRd)ivU>Pf`BHtTPzNPPY)$MKuMit2VQdw90_ZYbdi(cUlcJSA@pxey+E+IQm~$_Sr5RCEq}FTRl5aB~(*?M<`wx<3NNCEfbn=l< zMkni!;M{P4o*EqADPWWu_>SQ=0zK}Hixx}Lyxf5ss%p{GjcDeE?sU~$bM+YJUKlc& zze5Hs4GuU0ejsS)KS5*W|25a@%fa8%*yk~(^ZNjZ*w38crns~qkROKl@r|Dd09#PB z^$0K7(y1LpG=T9h8Nij2n*eZ+T~K+&RnPHT>Ay)LQ{?WgefHOr7&w1T`B56O+ztPE z21$dLTna$O38|Y^etFyG@AE^zSQiKfwSVuoew0^`iw4lM%{ba2G*<;wq^`dC`~Q#$ zkT55#_R2Ky-ocYiR%M>HsJY4i4b7Q9|1=j_a+p`kXFd zLUqHUn(PPTIKoO#74Y1?K@ZRh7yzpuG+ zg6k|pHX_9{+_#VgtqnEBVG^Rc4Lyryq-*8~8u2WgK8|5?JVFqTr3L9W3Zo>u@*HH& za4Y`nk~u1`n!;1f-v^r`V}*N;`65c=uJY$sJewWC#Tx6n9H-C-AbCNi?oT=Q@x$Tm z;<~AzGs$aYMKc5lcg(`9qcq$Ic<#=1vo=5KzsW?xe7oA36S+N#1iMm0vO&Ok&k-e2 z4Ub;X?9+11{_uq4$;&e-mwL~hzB9A)5Cp`ug=Fgm=19RQ!QQ#D9DmuCUi<(Rq7DUr zAxHKV3;v-M-3;r`$NBKOK^&4y0kozEoZ|&7UiY|LPhZN$ec>nC=`lm5TlDVHtQn3m z%$W(2v-;q6oqm$=C8dN5QIZt%#n`MvwgFYD;cFlJqwv;Voh(9DM7!1$f-mpTEr=dS zS8(Jxl6CO!Hm6`jW5^*V71$gX<46%kouR%@aAV~Y$-$ILR&|?sI(iW%bTRLLq8Y?+ z2bB`iVSFQ3ZyH^G4#mijImT`EJ;y{f=srygQ|h)E@V1cLB#ewVuDVl@sFx^BFn>qVD&HtsR)Ikt)(_Qq(HXPBHm5 zV2eK!3|3r1ok_M5s#mL8KqkJ7VMxL*K^mc^qoOzukRf)emJmdcU~|H2aQseYfF}m- z5yO*X5$bymA2XfO>0(%XXVUZfUi&6DL_iy^SI3{2!x*^HS9tdObp|mC9s3g<g;>VHq!=IJe+|QkVApj57+t$6qNdA$#9rfY+)aSQXgA1&u%6;my zXgO3i8T&`?T9~aV;M28lukZ4YR=nk6oOIlby_Hl$L=r~hFZ*%hX-bAR(OFlgjAC&@ntXSS)M&|LE#%YIW`m~b#G-g6zb zfAXV*6GBc`TG*Pwrb?szScSBu-%tRBXbd;o9u_7R7j;8uDh@Tuzzu#o)RWJlmrQxvdD zjhyKrex{JpPfFW$W=+j*w)|pHG!WP#S2(gISz0KH-#Jgn^>n=TL)DIme4ZW5wl}YR z`|RaiD)z>la^E=)M)YDlE?#RKo^Qjl0k^Y+4Hr!tX`!w)Cx&6*d}Ma+Ek3(qwdUz| zwFLV-LKPG_V6Y=unNm}cS`zUa7CMIGfOWRl!Pg9e-HquUoN=P!?q#3DYd&hVCD@p8 z+a79WA_kL&p1H0o%q8u@hscd=x>4ZvcF2ToMd(33>N36b58o-3T<*W3=}8KjHot6L zl++|m4C@A}P#c7@66Jy&n_!-~>g)$8&uZr+DGm1(L@YoL6h}HQ{ksR6atRT$4O|9L zEd!1S&(fZgJx0?)H@iuSWC+Q7{4hD=y(@FS^M;$#bw8e)%e1G>)By0!idL$)HXm4J zr?yjh>pk}HW)sH&m(qE;3X7?i`LKYBDABR z09WD>!U5EJDdeM}VL&sC4TrG)Q~8Gb{-a2bjwE^p98J7l7A1j2CQ-^m|1^~Aev2~v zX7%y%Q_7YZG>t|m05k#I_=4Qf*_2y!+DQ*!f`9K*zxU!G@cZC+2Jje?m(TXojRVtE z%@ttIkcNbOQwFD+d0&VVvWXKIbYoaRcoYGi_SYd_8zHgZr7(rGJ)O^C+|+CY1Ty)h zz-KZVF zwG?1}RSXgf+5K4@Duan=A^7nfHNY-)mE;i*psfSQidYl*djNaK2XhaAni?S50|Vzj z+?E2QVL*`R1s2ze3~Hg`?!niI(m)%)Knh}<{Tn7I7HBzl5YQhEFev`#hk)n1vOg34 zcIIFB!DcB1(M?y?MozpE$NA`|v3|&gTwN~E_00b-9N&LI$3H-ZbkaabU<~dlLU#{J zb=}_eiD=aBs4f;Lm9s`g{0EjDOXy#{WL=z(oC{5EPF@Q|4*ykW#au?eLRbNl)~N zW^99Ns&0T!yW{%U$Vhz>m>UL+%3gl?cq|HT2L}-g!;rW5sS-Q`lK=qVEhMi1j<*9C)vziNL4-lr ztBkrG2j!5DG6lw8Fe0cCZ2Ebu6n)hUrQs~|2X*G1}0~DQ0obtQ8IGg z#iT&<#W(mqT%Wc^pzv2gM65B4S?ZOvb$WoE%(DKx1!MVHViMMZ5^@3`JKEy>7@AbA zzU>rs%`x|zRXMK791jfs4<_e{@^^y3u*@_Uu!+(0=j6c{o98i5ybI8I_ue!t7ntn8^k|p4}X>c!@ice0=r)m03^mE&Debo#5fyBFb*&} z0~8+sed$iUPEnN+=Uo(mEzoF}bmI14YlrtT_^8D*kx&wu;%&*uN29m9EY1Ac-)MhE zu0VzfYqpqjlg2U=tV8lZV6)PB%@|jg`fq-KN3vTU!f?YjLExLJG!nOG$y{1UX{N@y zqzweo+ovtvhNupMATS8`nhH>wVg^9>vLGoURXBL8zCbwq3Nj+b5j_v1hs)mH9#5(F zBJEN;Vz)T=JX9N_PZ}wLx1T!;9^gfY7fUc563ZtT>Pg}S(5go{NohPl0J;GNYJk)N z0Kg}D-%SX?#i&**uny5D+Ig z^R;8}Pn^GZ>fnOhU^BXEpjNq3KZ?UPaS~}jHfH{QY%X>s6&6aZG!JlJK6~j7P-y~K z`QVOUe>87vSRg>o?z=MVw<4^xO{rSLipxp|5W{~+`|}%982|te5X|` z>dC(y{(Xjjn8KJS6yqxMk4k<8aR9E6yiT@1@78}P;@?jEqeuVcmi!?DAqZ3n4&8OC z{i*VbApX$sFLvGl^zSMJ_A#hx>f4ZAwQ!>rA@kVp4f=Qe$flt36j1qZ?DS8&>B66= zpdQ$aZ9=`SF>t8%RT6q%D>%DFOaq+Z0xG=lvMyBxHP*G_!`0b&rB9bM&8aAs zA5?lfvNsXdw(txj%`N0O583^rn9x zy>f*;UMQjP&|GgNAK3N6Au;=`U$O|d(y~1MS(iVq4uG8jLIruXtM~hyk1JyRALmuP zFaA0`OYVG7-u4AtB-1K_`+mMJCP?n%yWTb7`hdZ7)VdH3B!H#>-bm*Su>DKCiusDD zX}kvVn!@;`9e~KF!J*-caE#jbSkPrFjKm+~`2aR*^^1rb#D%FUsXSW;tW;8HPT$ts zk-6A_FY(biZ-=1{P@{x2jNxmt*;?F0FB=eW8bs#aLctuI+%$KKpfm8p#~_35#8GVgo)Aw!i)uB{=!^;(5Ox~ zcuVkI<;D9>q*w06k9L2Ih!%}$qWRN8=JKa-@CT%o@H-?Q z>oedPb>oHOb)Dvn6JNb=+GK-QqxaBYA>TiQeiv;E>HypzdG9d(D<=J0gZ?*uAT4e= zo0Wi|Ko1&gGxHa%IPRcMkVoJBLTdkp;2$RWhu{C4M*~5X;8TcqzfswLhDRa&NNB04 z5O+kP)wLI;pRc0Sztjc;71W*#YX60?{)>30@Mrn|K9RD7z@glZ-Q%-^lxqe;Us{b( z;js6AMFn{Uq5{Vg-c|gc@~90kxc(jhAEziK$NNI56JpF|q{a9oXJtQg0D}FuyK$n7 zs8OQ3> zjKMs(NCFiX(7{O!dG99eC?(QC{?ogGuy|qlYS*BJh6WCpDQFok0_x+ZGJrq`KhjdO zqallxCW_g#&!@?B3qGVOd6@S#YJ__quG_SaD)YlB^8x(!-|16oX+)6$D=#EHqkUZ} zn3R(LPKdP!pL+@SV|XI`ck?3BgSB}C$y@q`k^V0d=MM+8aKKGn9e>bb)+8yxqA5of z;dhKMfZPp4c^{Iu{0mS0+q|j3a|~7y;_9l-VNC2fQb0uZo^hW+fpU;rjKDgbMA z;=xxo&b4{_+EhR{iF6Nw`&TqT)|EF5jwmg&{YPmNsX`N=<@(?GpUc0H*zb4B-{Jg+ zEcy3||21z0g7y53x&A}EIWnZprTN7Ig+Mn>Vtla+0B-&reu@#$&Y%kl?qL46r^o-J z%*o1jsLAp;$%>gaE$t!U@uLPiaJu^Ezv6-vfUrOpbb0VkSpPj2^bhJp-mC4hFF|x= zS#}?OJ>4P5;JsTmX-{z4nk4Fj zZ}^6Y@%DKA6)Nun2=%^n)+*8u@&u#%e}O#zDh1#?KVlcFl1F)qH*YvDMZ6DSvbUoJ z(|zNEZEK(?v%PqgAq8$lNhohf7RRk&#Vv6++NREd3QO+s`vD8)>W#onOL)^A*@||| zMi9=Bbl#5h|F4dxZJc;Sh*}(F!^^j!DzHyM-I(*uM;_5tJ7+ylaE-mj<$$n50C-C z)r5LE0@T2t!;mZ|Dlh7bm0yYe)hnyo^3`o9}@ZV7)U4@Y#dmjHnSN|{B z6NGo=bRMhyN7)lJ$}djmUzm{u2h<5VoyWg0*9d4U!#|ntld{fKK;SL;dA*wYoX*1Vpv{e@dKxi`^mSF>N>~ zkIWe}R1sf{z#=sF8iD1<&+$|!ZQzX50Qo%llA6U22oO6Q9AR^M1X7&TIV7ghx=>DD zKQ-sKPzRSmuyy>369%|2Dmm1LIH#IZ?S>-p%nkJzxm$`*1tKczKhpLfT#-;84499BYoZrCjmac2TsU& zgA5~w*Q5}N0GKXlE@;|Mo6*q}p{Dv@XUw$mD4$M?FCAd5W2S#ob6QoKKIDtMa19La z|6<&^t7h;Bl8f{UAN{`|O)yrsd2+B?{WDho3(6%pi1I#&@)w%=f61CxMsowu7Yh4}mHwND|C}|iLUlh-Dw5Xfh(tlHlFZFl5rRF9qBx*GNkP& znJEEn5&e$H&L!^?2BLdCG(}-MnIDsa=&^76xsk6EDX`yY)D69YIk+8y(x%U)l^coe zZR5!CHY=14c&eR!_H=v)_Hv!qVP^g~-&xh=;r(GB+?8A5-TacG(ApNFyP9G@dJtrl zrl4!`C*W&`6*Oyz^2MP<=wIAdv@agZI49vpyvi<|MW|6c^}@|zxr^AEKjcO=AXCN~ zah^xeG`)^HL-%Og=?=P+PF{zpWV?9eks$nrnS(dIwYS~5c>@dfed`qpYYMcNL)jk$ zkDN{K?%Xu&HRsds7sMoV=CoWwr0!tuIB0(up?uGC`f0&!CvU{ST>H&R1v1(xVMI~V zQ`S^MmVoxk>A6od9s*9GpLUxd>A2aQ*mGySE$9_YiL4; z=Gyur%mZ(lP2`JjgnrND?ltRheiH%R=g49J{hZXZZfVe+jN!qOYwcng>*)0_Dno~ab|DXW4rWS1G)(JW432sZ zrwNm|m<6NkE~~>_*R5HaJ9}$3Uo*R9n5GlQhu@qcMSi7~SY;ZT( zQ(TmS!v}}|bA)^n>HZxW3ZX_LqLt!(vB^Xe7k=il723GZJygZXwMEADXQN0DGh8g* zs8Me1sgmT&v%g3tU)i&tdYhSD7w51?k2>q|#_!-zqlP*0Wk0*E5LBQ$_F3U;Xa4e) zqF&<9!wIEHcdhnf28vl$3_Qy_x)~LE!$h3}IC(4-KJ|7F5y+_cMRThY&=w z5fyx0qg_xZiFfEA6DNty@+fa__reJWy+_*9D zc`yPGZZ0>k&aG_7^Ywfe9dJF0II(xP$ost!oG}jZG^ZG=s71XfBRD>sR=(fgh(+LG zTQYo*|D9Zp5Y6RkS%M>0>{Jcs3Q64~Dch_+yf19uvC3)5@}Pc{ew+U?!vEE_gf#pi zcJ!;!RR$=1(2B)}0RGhVC3NN{Ur0Mszm1}=wEF>2DxsCeLRg>A6I{a3=~E<*v-@rvOe<2$XF{m zIAy>pWix3zqp4!bTXCp`cL?(6MHOuA?38((?|mmxjMfCn>COnt%xw16roDSkQ5^Re zIKm@OM${A97Fx*fpm!u4N1P|6)-qI8GL)Cawtgv3a`ixYY*wx7^k!W}Aoq)Lco@f) z_i+@PHtB>mrx59MjZb8fkL2iPuwoiPrL76+xPL)@MFnZE9GZB`+nY7g4|MB;mG@}P z<8uZP)E6#`N-bEHC~_t((U0^G#8-;?ROCxS(uGAUINAfEBZOaN7?2rGb2hu|Q_3RB zF*^9EYERohZSX$rJHEU4X#N>Va+zAI1LtKfu2*%qRKR&D>$i8i*YkyTO?mxxM!Qh0 zC6yXn1D*ypzB=g%rWT9O8<=0zG2;ox7X=_b#Ue{ad0ZU(mF>Q)(w)``tzB=-qw?ry zke~Sh8>D<9xjkHr##Q`!TxmA1XI{h)StdX6D|Jojh2xYlBQ$Hv&B8xE;1nbk{(?8n zCY5O*^A*Vca!%;QzwctUQ$6#*!*@q|DsHy!uIUSJGU?WpL;RuyVmqvMQ@;<@5Ggvu z&cg7V)FE$U6QQc%-dpLA$CUKGA8pn#;&Uh7g*#2o?6=sU9>&~1wES}TZOiw_AQDht zRd{TT%PxGqmYnTgWdi~SDb>qklRD(D18obzdZEWY92zh&U#Od@`2glbc;5lb52 zFN^;X*LdKz)k#5Jf`;oj8zh?SCNCb{ZBw_fZgEK;37mnDBP=>TTr(Hb^+M+;vWm0@h6QAwurtJ$D%w=oebX+Kvk}H?Av5qyaOj6+8M8%em3FIrRR7n zg>YK5%ELl7E+;^=SY!h}KNKy$ z9bgpcSK>1)S<#{r^chmB7TpWmmXZA2<36ML<>t{DEF^njewtgUi`)7eW*2X3J2|;T z#SE4lJ}&-?8!rj)aE+YryI@1nl7~VhC1UUab2>c|xGopsR5dJkx`H_gN<$YSc5oX2 z1~b+?(VuXTV>yYChDSWuKJqyHYFP9Id)rgH9PO?xLsvEc7`+v?jk7MsVfVS5tYf1P zJ0!c;)qw!ne4M^_m>f*dCe6Q2G*}9id{Z;XAJk1swd2C8lbJ7_Upki&#PK$}da3lN zfEp6NVaBeD=}s_Sb&nlhuFD9yw%sUf=s#Pgvt=I7i0aO$k3POXDOJJpW}5B6iDU&; zDEj4Q)p!d0_M!*L5dMxVq~Ke9Ri~KWX!#03*jr_kjKI}6ji|^=7ova&ODVahy0>@< z4%sj>b^>@*ze$+~h3tRO&73hvX{$XFZluh=F??r{&I2bU@b#pghhX`ld7#|Q&|8lu zjyL^}$7oFSXp2w2DHW6ATD6^A;}DC^V(c2~!tFP(=o&R2cBzlnQ1rR6e~@$|;X}p`UX~FTP1jBQisPi0Z#Gqq!}%P<)u*^k1rzf`msL~e;SX@$Hlo?`hKFr+cwpg9M36UI(Oh20$)-`wQ0uD%>SDC!3yhD{%)T#d z;agnRkSAQWNOCxle__CX`1O{E)6Mbe_C>SPWV!x4yxFx3J6~LPjU5%hwuR_CJY-Js zV0Zb;w7x^wv`<;`h5l~va$V=BZYl50M}YBEcTsYF^^QEX;#pPNpVsfyX1GfWkZhr9yq{7H?_ zlV+>rte>7kWine% zaSY?tML)&r)tDubHVBcvHjPSvOD|M|n073hb`0%ID8x+8oq2mGe|u4NVRb@3l86CH zjc+z!o?FT{LJ9r4jB!^p+o$US+3!@)7E=T7EYyg)`@Xa1Eosy4GT7UG+=k;b{HBHEkZpU4VXd_w zNA2*EZP>Jp6tD?< zu%+c{#N+J?4VnqwKNqAATQ)9Jnb#n@{^X6)R0Z+jgO)`BCIXAk7PZA2 zv$*+LvV95-Ur5v!y03qd6HQ(fM|j4rWxSJr|8z35&1YrFZ5fVHutGDh&BLPwtiV z#XMhpeGuWJ)zB`2Z)3cc;{Jn8_Q;LRKq%#JLW*wmge%b?uh=vgFF>l;f!%bB>mA%T&55?k$uSG+kDV$RRImfihAQ ze4KOyOz<6w)mZN~AN2_oq^xEIQMRtw=RA(JXAN$CVEfs@)w|?S(JrZ)EDcKSb2OCHP?Vrec2Xyqqz4?eq=F+q`N#e#s-nVEcsD9ZzYO z<+MN|`T-B=1{-FDfDg@II}};q-Yr=p+Da_VqT(YI3>dimm6Y{nC?DQzx033KWE51} zvgFPhJ@CM;cS`fkrsAR`i$#0L;9-qsO_Cfnh?#ohybLYwX4le2EF>go4jb5c^AURb z`pZzs&DLF$1Y-t_dUi9tqNHUk)#pT8Dp4V>&38rOUCC>(x<5ZS?06EFK(sk0cSG%2 zf{A8WS6P3^oF3uJN_~zrZOS7yFBXC2&-ILpnDPs)Yf)bp zTwok7iL>=A9p8uSzOK=+_9HPWC&b*yN~a=B@ZT4#)6`K2Ji9#;u7I0Y^_&#JF!b^M z++$LzXb05~1nMtB-_u$x)wei3>kV(WKd;Cn5FhDKwK2|~jF}=qr``W@K#WYvVnCB~ zkW(w%WTkvM*vz8l-p0Y?8C7m9+{49BFv8t4Y#NrT_V1ZeRqIvJ5Fw4!fkhu zjfPVyUFJ=(Mc*WYS9`#-vyPrx`pR;Qp>>J}$p_xdLMFp**&@Md1g_Pg9b8`{Rw!K3 z+qVv*(S&(4$z>-HMy2o{ej^GJld8@c3Rd6by5!7>_dwZ{INjQaKdoq8 z*B1~Tjz9bIMbfb1?%5sFu`z~eA2urjwYcXY5$7K3A=HOG+kLu6Wg7C_B-aJzyN$@o zg>eL=c3z$;^-zA~Rp?0^a8O>-jjbWhzdMIxH`<-n7WP=-c}R{-4*Gd9%DjVnhZW_0 zTD2EcN#!V-*kK4n90k{L8J&6VdzTD;Ug~b?ES(!>GZXx%)^6}xDC{Oae8QQL_yD~G z0sU|?obu~nvnMYbrm<+r;f5{(l4DA@t~_lI2eX?Jdl=UJhj%_Yc)k1TkY66ibB*Q3 zA#ak_CF8zr!pbxA#@FJR4BBz!Sixw1oNpvZ@b;p3vm+yCi!{NH%dL zvN1=KJ$|tpUj7L9w$2BZyvWUOgNHJ<`czrmJK$L)xTW2)-P*zH8m)N}6%TfwM!Zzv z-0}*Y=`-Vi0+8_0Q^lqvdlxTN&Gt_SKgqslg7EByMp2%Q9VZP%Jo>#Q z<)>{x>CXZml zKqOVG(bKIG(jBOWozdBlW)N#jLH@PMr#OAPi)hk3AvW}*a(DRd&8FwlMj@bKe60M! zoQlZj=XOp0c9t1! zX~@cpnAsa%N%ePaZ(9^|iTG8X^yR@Hx<`0~rNWGg@|&hn7jqGF2juFzv0nM3$_E+G z8l*KHYC}v)?vYg@g^C!p8@|X4Jl|j%5Q5CLc%n;)>JG*f0Dh1dE|dz?Tqm zNE-EcA+TXQB&^|{(`mY*XPR|+p2d-OIwt$mPW^l-*^?9H<@;~Q3)r*zym9ZmMITHl zQE)eBRM+qB_}q7Rm$>|Z`e^5X_`}B=X?`&ADD?QakA$eL7eeZbr`rY1X%=Gl@s5@<=hIdRL*$%@PWt0TWBznd5TgXWZvZ?`2(n5Ko zyhXx+Fe>eu>!;LQhus#ngqBS*Dp)=xP6Ou$#OG{x^G(g=ZH>j!Eje8qF|h7m`y}W} z!|h@CFymFEW~i>k3h+jBBYAtHNxEE+x0+|Xph~;9l^99&A$?t8b6ly3_lZzgXv>q) z1gZk--V)4&%)5jY-$w!vbnJReAi`Nl6(WZgtt8z^jWRf4?3<}xm%HX;g0ppXEvwIl zT!g&ldAnOO(Iog}?*s6u2kusjG}<;|81F4vxyp5KR0qDkmQZPCt7y`{u!a?EcT=P% zc%$(w*RuTVz3aUDEpu?El!=9XpKe8#-g+0jkGX)l(YD3H8Yn#0c5N^~ z{N98My5u>m|Bd`09;*HxjzS*SNAF!}LtAJ+ho{Fsgw_@e9PZ{6BtobX2gVU2 zme|UT#Xb^R;%Xck4$`+BJ{Kmoh9p-Z>Yl2#8=g`|ozW>si&~_7{JeG%C#$MUGOqQ= z3#oHcVuI!lMUYTk;f6YUqQ=?4v6yckTOtt?@@kMtefXO#S3B!MW%#l?!b-LRSsnnO_jJgA>dXjnEk7;9wtNM6&K|;2gA(b$? zxGi#b`UEHYITO~!N%E#ZFn*DXWKIQ9f_4Nkq&4n!AscmFKw`sImG3I4JnXuB=#!zx zcg^QBv5M$5k+1dkt7C`_Emvk3ywywB?F4)<1kh!3d5`5&Hnl9WM0gq1ZfoLvKpLG! z*0=10;QFNQA8Fi)B@z)M;O;*1tcnblI14sHx7WNoRQ;M6K}r5?Gb`4e=xDS#fI=T=HR29dDdS2=CaSn^Qh-Hn-Mk za#iJx+BV8fNhwaBl`d)c)&@>+btA-Xn$2E#@zJ*2i+o2VLx)|6tj3#^yvC&5KRvoH zd1rqlIyMqDfDE z4rTejE8!gSSbwbYGD=!lQ^`S)9FwpFSxUyL-e51W-9J{plS2zB7tgq=awC#F0^2Q6 z6GBPHAVb|BM}F;z|G-3(#A?&2j#Fc6s(hNmDoKO;=j%@)$%C8f{KoX1nH>8teTF6P zw4^2TEI}<#%OZnEE{HzpQnTKZvTq0b?rO*h9|dhkMHDl231jWNAJPUa3{aG3^rVT- zlo;7xX$hoOP^&y*ugz62I3}a!(Z+h%W9chxk;CU~ElR}DU%%j9{p>QqUh5`PH%;Ta zTA|uAA=pO)R=aNQT6v=rqJi!%Z!$<&*M$oE$NXNjSEhH1E;$eq#6l$tn5#!Vj^$LC zb4hJ&(yVyixYS3MmkQm!M5K2+i9#zSHA6QO0GV zvRl^u8&ow-X<|Kna)ox0DoD>CMr+*ritQlDeB;Jp-;!tiaaDw>I90FB>&U`7i7%~T zA^j?nVb{HckXEvAJX94cqn9<8GG=8K>|DCbnahtpK zC}&}P+)PAazJn#>hq8}=m(otTP}Z8j&v-PtVP9-cC5L!y*jH6H_k=o}XA9=I_4zhZ zt}Vb*!lB1}g;CuMLdPlOPDhh=D}(qiM;C5iSkm791@_c$LqzHS2L`Q;($k0>1vhq}Lu(I^ina{pI-dra-V3kAFwl5B&aebK9J>UgQIXQ-v z(4LbDEsZL6&%ezy8Oasm-2gcMX2{_{`c`eL{wy0JX~9@LX$s}jhq~$nPnPWdicLsNAohI^ZBRN7(I{I5;EEo4xCT^Gq-A?^-v7c=! zKoY?Jwe0YVYX*mh4MK?^C&si0R; zu9tIVRF{h1qIF`BJgE`?BZ+ueh0wPoyWS$`sFXP?`JHjut+)cjrS2S+uyDY|YZ&pY z2?Hi`@>9MUlFICCtv7gnLqw>`;P$^)K3KZ+-~?C_BraQr+RZXSuYGfM<}3VUyp^Vf zqkXiA9_AxN1W$VA7^(RrX2DCfks@^|$p1lVU|wJW$o@;jxyZsBAE zg+yBki5op1sfy+M1Mo}z|C*oDmJqk*5QD+%ExM}o8kDqF^KCR~!+19|6CwBB$dsO& zQ2yhwbPYKQi*7^r4LWZ`Q6H30tA-5_VM?9$8wa<6fgctioUEXBo^X7Docp7O56wr| zFJXZ+_yt7{yk;Y%FfOEj+rWPQqCqxA!(uK=#eo_E{LBAslI2VM=;5TkaHDt2eFlVH z|ND+GG~%%IF+Vv>RTP({+(Qp^JR)F22rbCXTNJQUcAB_G3~g(T_EWCH!!F_Lobw(% z?{F5*&w}pnH=ukp7+XdVAa~s=)=a>HC^>2BUxHDaXN@@*!u#8mLv*QN5lMavy?S1- zd@uyNMM6zaRQflUzkxu)c6*kzbr;~>MF2gen?WY0vI1KMX=UZ5P2%w^|cF6w7!X;p2)_K-7rzQiH9%-1;e8S(qw#B?E_#{b*4-^IOgu z5%i)ikRDlp?yh1F#ltkrxb!R=--||{fm_IxhYe1$)oMVsHEvCri6Pkf6hmQNBzf17 zr?pqa3MO|S7=!GEyJX)}Gk`KoPJoY35l~jjfc=DXcRy=EkW$+{e%(52H+8*vaz->MR^0*)-XRvv2b{EjY==u* zxe|O^oiXb;+0ugm#o`@)=n7`wT0X~*7fV)!lj8G&23%X;UOVsvSBnjbF0u$Z72fsu zk~&vkjWqq8tnq-d5?c0KXAP@u?AA~1{|TM`u&b}eSE(FjlCE2^OX7w(HREG;c_oJ-*tHUdo2;x?IO0Hvq^er7G#evUyg= zt%}+u2euk7n2By(svVYg8Ne&aOSEY$Fs8%z#6>wI#C0SGD!gg{^(PYNSH>gJ!KXFP zm^t*sL4%JYn_vd(IOciU{A`5KUP+LE6|iusu2EPF1Rjp3#QoZ@bN|xkh=6OgDvB4> zS^GC`M%8i{FjZqragnmMU{$dwPpsFBmYH5k#!E8QlXls0a6D7Yvj$fC1RfeM~OdhK`>?5k(+H zF5_#vWAnX{qvyCh|Zp#VyMd!ll89S^1V2=e|OwDOjiYi)WPO3JA+2mc|dP- zoc1@lezqWmF3xPP{v`PwyD49Z?1Xm0m|w6&{mCD08*n7qMIKog0J3o302(h`qeuV% z0|D?^8N+1mpg;D~dO_=RWR8rkhPn^%*xyQ9`Xa;>AIh7k5j0W{hSxDhTagtAR?$p9 zFDl5Gsu9O!XXZ}!0<20-{m>?%Q0g_QZBQj%{eH@*B9cA#HWUi6TZsh{TK-&g*5>t4 zz@6JMT~GjLUa;Y`TUH^|)uev`R28>OAQA!50SbP>P_E>!vWoredYWghLg2sa=>JR( zg)ktk`Mp-=#Ih(J1W#}TD@3Z#?pua$a2^d3SW^OMFXehIO)g{u4Y5cZ4-_UR(P#4Do=ahe#FH9+@<3h)SK|kC*I_&&RO_ACCkm?V-^6dI z^j5GU=)+Bnz@PW?_$D1Sjx9};8>u&2=Ct571+x=kwGH3&86%gVcXIh26H>wN_YxkO z(dt$<&);3E#1|$T)A>$+$3D6h*p?-X00LqS1T7(Elv5Iw<$=Bn}27d0z!d zD?ohsfg%i1WN5JK*@Xxm(&FO~n z&(uZm=V|rINShN7v%^JtAsb3ah4n|5hJNg+AY`1%G-oi^grz+zbpJ$huoY=Us@-PVvVSpmQdQtGP5n0^a=14{Cs8*6?a;(w+=8|zOcrz5H2^oTnKvcU9W@v4M&D&VImCKrU7JVl8 z#-}_oCTgDdtyo0VK4^@AF8N9ofBGEK6$T|D-KFdFYvgB+YVSJyWv~)IATOxaMetN{#-o@hmpM; z2SVhSojLJAAN$4*$Y&)WYVYxx8s#!LG`fDe{xhpnNN^m}k>eCS+Pl||dJd6g>S!FF zY0zl1RlMyb2hbh)UpVtvBPxH)0(3C%GbN6GUCH#PPL>U3@s><;gF_6pxNSNDy~Hawb^^@05$&9)J$Y4Uj@n`n0P2Dipi3XG zcMd@*Dy7x{HQ!Z5J5G9OD6C|Y2*m2ku=$p6N_MNiV1#dT4_r$@Qdv#<#&OA@?p^TS zS=&=tq_nia@8y@I15@8`InG8=Snj5kQPm5~%z?rf9skX=la55T@B`T+00fK`%JTo_ zq*%%V2W2{E)TkT)76vJ?e_iElvQ1)f0vqW1-^GtX#LRx^Pc z($XtP)7mPF6XQN~jZ|?&t}}$=99(0_@75%C{2>=FfkcjZJ!eqIJ9>$I8b4WEGxjuC z4okg_e#`-+L;Ts>I;qMZ$Xe3ttEVIDAb{6>HE$L{*|{yXm;^N<;nWg1!HWH$c3zqs z#48~>M&app3D;H6>=H41qoZk_tY?XhUe5pbX7E<-crk4kY7X;H|HQN46nqTaZ05dejv+j&R40E-p zuS8+tCFi`)#jcry+m2JRFeXWay{l(}I#lHXC253XxyGS&4&-0yMjpTmpr;{kmdb41?l*W@>@&`W7O@gRQv_1`eo`6` zt!{5asBK#?GY3JBKK$85PEel_v(7tb0g4c!x#DrZhD zM~ZTi#_UpmzKCNNGShIiJJN4{l2L*Tkpr%s?V*L^au;I7QT5?)35PWiZ~%h0Kmfpy zYC+R6jChi+l{756zhG29jOWqYeGv+F;n#Llc74pad_E+LP3MN$mq72{>OL%pr?+_x z^a(%cF<0#=4q=1`pgGNw*REMY!LMhSY$wD?@Lw8p;_hc86EJyMkt4Q=`&ydP(KjZg zp`O!^6S~S8wDZb_u|#M3t>>8Qy_k_C4SOB9v^jSvSlXtLJw{MPWO--VncZ>vj9ckK zQ5lP*3-ZZK!gofKD|Odjxx*~X(`_^rFOAJu|r#Jrlo z00_fq00o6L)cSLNf{+f*ajcAE;N%Na1~Bi0im!OzeI?ypD6LQ^gDW2CYJ&A1rgW>P zVf@R0e|M~Y*>v|`zM?i z0UHBIDV!u*=c2ovn@vAwj5Y*aGrxWMIw8OHW=ejc11 z2&rTK1`-0i%$8mp=MEYOn34M=?lyHSO3DxWr$nds@LJyCQ{S5$aI=7Ix4A7I2-2^r zbRngi}^o`?CnIgJPYfrrrT`BFB^e>AJaGdt_flTG4%rL}?tLf62_I zXd?2tMSDd42jXn=!+YF&SKHbzc`3>a^6NAxUJsu6gF<~gR8vNtN+D05m_H7*n?nA= z)q=e7-D>D91OZF#(!c)<6IAKDlUD%QoV=s_^mJbNiP)v4nO1-6TCO}=u72qL>pZe|8QC@(jUt8!zyQdtgF*gjc`;0|wO>9ZlUojbE89xuR)S=dFud zi!XaO@&n!r%9p*~pDoRZBDHLw#7(-VHJ-&Te7FV460TIxX%({&RtOssV!yq#1K}FK zHNuMX`}RGX69sc@fEosW#wmqVt7i&8JH7YGO(06>LT?^r%Ghm10$t@s#0Sbf^0DL- zsqxP}<$T(_h>Ac__T-by{N9?-*VB85EE#;K4FKcrDwdVjyu_Nk(tU(iPG8Vitn^DG@WZEefJ#w(z(mUI9nF|3#$%wekwL>RW*8m$g=l~XT z7yfZ8UbhKIh+X|U_t^H>$T}CNU&1`X4WOR2FqV4Pi8Pja421PbC_dP_{}&#=8ZM^d zj5V_Nt=s>5Dxp-6@1grC=ropSZk z6%wt{h9;voas5+;wb|GG@89}0M!^RaTuqHBGmpnID3ph4tR~EfsUDlxYIv@X#wIy5 z^ep4Z`5yTK9Q*1t4@kw%72&ImC)A9)<{Vv1f_B@{qH``SkyiRKuQiixnrK+grOXjc4^9*Cr0< zYu52y@aXP&8gY`P1`J=xV8{aw`RMyeHdRwEw5zMQ62@4R$B>SG}+1a99KvtZb@)d1p^ec!vh9%_cjY{|% zDgXcnSO5^nwKpA@xlWf9D#l1BH80+eP^Bf|=ZRZugoYkEj6)|}m#8(X6v5K#-VF}k z-(-)~F?9+-PRpLS)~eeHKlP#YFg^AHmq=nqci?or7155wy2lgshxam6QxbwxzI`z_ z!>`df0}}kOY3p0+AdvVh-lEMw{ftc|gU6?H)@dbI2(^}R=rgEx;cxhqx$<9SDyjFq zS30fD3xbyu7!S4M9Jc2F?Wu5VDqo;P024p}H6w9!zJ)30Pz~CiPvuazgl$x3zugDB z`ILK}{Up4d`xl=?{C}FMoC$3ebwM%>D&BkVDnsm@dt5&Hiq%++7yX1sYlEDI%&Gh1 zVo0};{2em@YmCVd2Nu|lbuOP4H!zMigsL_y2H78m1zLXiC8=~l6BnybZK9ut)b}re z&!%haMRO*l_}Sazh`#7sVibmde4k!E6<91Nf^4Jd;@3>{6HH2d<`VP8a}T%~fq~Q) z6d>(lk10#c00$@l8VPdlRQ1;>^f1jwqbe7>$KPST-#B}^DAYaWg7IoQBugyF(?-6! zs&zJv6-9B}wx#)x_xJc!Hf;D?uh8ZBBGDQX%U@Mam5|7OY6p)EWa5pkK(p<4n;pq& zzasfUw*^#&{e~@f7(?&d?-qu(86#SQx!yzJau_a;&1X}(>-z4tF8*gYPu8AEU0C`j zHOSo-hjz0ys-nZXLG;qF1-lBk=zfnG)?yn@5*c3Vxz2Ji@GaODtiIHqQ2^>*I|Mku zWwlk`nrO9cd-&_TG9b=m_Ko#ld`DP>fvhJvYhVkafw4@@0H7mWP^DMe@{}+I9hv?^ z+lbbOE{OW;gz9r@@NQFP0ywuAZ9 z(A#D5Rvi0i^9 z%=Bl-k2t&rAf{&dc0O8C^vTl#4uslup*tfVu zWMQgTc1)b(07#f6*Z9rZF&Jbp8b0FIAV1NGs*ioRTl%O^;YA-y_(-`y9xTv~-#2TP zc9L|&-7ApontN4O!8OV-41zOT9GT1<&MWu6nIq>zsPz!Nd@$=IywP~ZZaXY0NL{{| zw4>&V_HRnh((^U#D*Pw7R$M>3Ru|xRG z@a2vb>ZTNWTsD}?C{~^HZQKGoAIUJ$0?wKsCelG2ys9bjxv~A9VecyyZY1#XHk*-A zUI0Cb_|)Bk6(u{b2mGfkQ}WguODt@%);-sYfu9cF>i-`2@n=Nqxvl)lC*8Z+{UM3) z#oNIj-*fzlc3V7!C{)iX2;d86YzWYPA&p2^qn8Sg8~&kdaNLuXq2{k#fA>S-4_g}3O*j`KP%gU z%_hGZ%|>6k@VV)Qi$gYbx_sf^1lCcrqq0H_{gRh15)s7+zo0(4{Wt+n009SUb==!r z4OkD@FmW^c*_kv6zj>H(FC@zuo=0n)FD!5fda4}NKUjXM1UK>1v=#aLj@KS%L_Yf6 z_LdktVFl(e2%8N!Ef-CQFmE7DFVdx|sGSqjXX}}gj?7Q3?3Dx2+rKh>+ zDL#vU7GQv@!-aaD#Qv`$w2*XM_+96MwPxZqNX1dbaH;De)X04lMmX9RhT>wEu-y;56D4pCR z4Br&YLk}%j%aG2R^}y_K_#MYor1|Qwz^2$9z+zG1qjfaKi-yYRH8PjTwSw^YZ)aGo zP#6adMLCH>mtbpww0kVub7u=UQ0PwC%YD<9dN-uqcIjJRK8hGg#Nz;LI=`8@(F3@K zR_u{KM5e;p@!DK8t2DkVV3Cw6d_`ePgloViBU(fw2NJJNF(x!hyfnx*`{QkaH|~t3QkcQh@j!|>1kU&3J!d6ma+;}nq))FT3GtaZAWg@HrUn7OgD>Bkt zhF~#*g{k1gv3*{uh1r_wK9Xn;^SiADTS@V8d|QmFUs?~q1w@DE&G9LlvsL6Tx7uxk zN5`w%SsFdBECR2ZIvZN~zKW)wB-6lBS;|C`8L!~gh$8)i(0^SiK%yXY&dc%bdkmv^ zrF#co(q>RO%EHfiIOkbYX3}J4F6U#z!G_*IW;xeM*GQ3oHwzHd=68U$t`le~8YFhS z6mMA(09>7VUL8{qeyX;gC!Kp*SmF7nSgcBNhkc*`0C|7_*EC!0J@DThB>54hQP0|A z*OT2qZB`dDrea0WSQ+*8;a8?SqR$UI3Y!xTz^MQXN{2|oIiS8i2Z=`+&KZL+J1z{WAc8 zC=rUM4)cNeb%mbL^5R7@2Ng{(kzvPlx z@G>zk0rwJoK0twsn=P=%*fo2yFFS~ZQIHWa5+yEF|CMOK2?>iqQ6SX_U^BarS{OAL z{cB6MP^#z{M0d4Sv0COu1^aw5grg&3n&IB&*X%=^1@m-yuMS~=SLAe^UTt}~4sk`j zx+n!&!nZv@NQx}mjg8IA>Wt2|>m%g6@}A;C4yaJ9-*n`Sn-xpacDD|t_6AFQ_9JxX z^{p$8S2EXh1V}`cL{Is_+T`Y|09h)%p$8%(84%}_Q$mx0q8X$I2VX5t<}|@?o+>;* zM8%J^jhGhx>hIu9)ttXMXDIQ~7~qADI|*))aXd!OF1_NVZkQ66V%vHhaay7vxhmd2$~ zi7`sntjziiIX(h~ntOmq`L2U%09K+#Qw;oxFWK3GX&+{Gr81w$V~6Mf5s0NZ>4Zl#E*UFo$vg%qdDL(-oQ-|-& zzyJvV01K6Gppg&el$IHj`BL(p(7h6%@t3*^^-o6JZxCR(__ad_rxN#dHULm31|4Yv z3-)JSuEJ;pM#1&L)>r8)1L!Of%??<<(ccQhH_RALxwGp+MEo>uAn1Agw&B7Eg@a2Jv$#~xGIJ7DH0ZS+JEX(jCBJeryD%a`ih7G z@m%ROU=V>iM_Be@j}n2JdrCs$WD^?jFr9J1+Zs}#QlP7uhx_hyl;$5WvJWoo=6#ZC z=V0lsx#O@!XHw~wr>voCvfH1cE<+TJA4v|X3(Dp5HhiFv zBm0POqa=(W<{3<@djr=sT8aROY3n2olU*Xnm7G$*K$OfCt4}6?q#73Ert=Z4`HqFx zJu7HC8U<7CIp+e40ZQhYXeVKs{HSa;yyoOh5bRde;E40})g|{5w6C65$0o`qpZvhU z6;HI}8}to_ujAPd*W)?b#q2}WeSMYL%*%WhJvFYPz05Bt2tr34X&oNo2O?i^TN|PN zEK#w1D!HAge32B=1ej&yfxu*Oh*$}0Y zq;U`TUKq!{M*g({iF!eo6{~~9(1hH}NWf#s6i~Dq5!~mkxod6-%}wDyHl`;{Pp|=e zO_?EQMQ|VtQsJa%KJ}FX0Bu7^tCjt)dWAum%Jk_|fB;~C0HfsNRQCzS**0OTZL?-l z9dbN&%l+56@F4AY4|jYYUJFX665iJBe%~(OGv@ZM#M~BH4H`=h(aurIh>j*X1u8wN zkSSfG;nY?ysz*AE2OiTt7yKipA@DOzKLGR!P9I|)A|Lp4!O!`WUV#gyyPSXhvB3}{ zg+ZCC)aSDcefJD(qYAt;4fd#&OJ5BQ7Sw9zp~GuqXoXhwQRh9(ou;iq;3g2AhLiwg zn@!WRBQ*T$j_qWIehh+h0p?6VQYmpCnzCRA8a(c%O%_>6iHdDx<`2L&@nIxjs&2GO1&*;{7;jIzXIgvS<%%?4Y$?-TJ8elI z{Ym;*Y_|SxM5=|6qf}$tR1cRH1dZa$xFe1;5Wqbc@P|Qa@?4a2pT#hNNJHYYP&4DB zz|bRJ*&a^PNo&V+z0dtp$)CwxJ2kfwA|B-lsbtM>UN$AnGDM|5ln<#71|LY}nnxsB z6_6%>sS%|wS|Ze!*42g%APq7OK?J2w;O+6L~4d5U@P~ zsHhN;Q(dp$wW7~64$$&~XK_ST7Cn&)4REm1v=m#kpCflrZJ6yoDhO8rQXNv~=Upa= z>3>OcyoxavI(?r$_n?+yoyn99j=$$k@q`u*^m3UJUnTB=*g=sT?LM9P*YtHwWRWo+ zP`dC5hx3+k`e07{WYFx5Z40(}gxkBlioSk`jA6uVt6PDr)fJTCZ*+~iae%O)) zoAo)+1flr&tog?pBT*yDf=zEe_sWf-wL@OEacd>(T;6C9QCKX+AqD5z`7;?CRe;gq zf1)U0Nen`UzePLKm0GP;R*JM7x@&BX%FUhKkc^jFnn7-AaU}Tc%}<`K(*#KeSvxGg z^X{%rqMh^G3B#RiM*)Wt3=KjIH&*ix0yIcia}PTAmI;w43PG7wfe$&t`~ z-2McB>!HR#xV&gKUw;P=O;%05qKNxa%PKexLZ&ztMS^=yFeoftBX^cKfJ)7^Jpvn< zJQBl@rtbW@P*iudn1cxqUK)GP69z7~UtrYfl_dXzGJGfI{GGj2=1&<1)6rL_%RFM* zfAuYRIcTT(?qbq84yMVN6OhD8ohJ0(PQfFRc+0F3Au?Upbt}-15fX&dEkD_cOBisB z2Vwm!Nei?+<#Me}KwU{y`v6jpe)q2?JWEc|Wf09jO{2by06PExNaRD-;t)TMm@tNu z`|tPfTX-b zlx}2`mO0);b4w!zE`_}G&vUAL7JthJDd*?d(7}}d*s-2K{)7xJki>qU%rbxzwZvR4 zqP$&JHP$@uA0N;W901=yema_$M;8a!E^7^2_7T z%=$_}<8TKwZ)3$7pw1(L=rog6ZvNZ^{O1J!mJ0%>`-$)nJmZV;8GeGl*@|sZwFfgr~-24sRHs^^98Tf52v^nf$qe#bg$u?o(w_OirG)uH1st%)} zw(Ii@bPvg}$~H<6bg4OEymBH7l8f>^%G-SF5p+Vap!s zN+#Hm(J4x;KV%NW(F0b%UGye2m3fHP8;I{_S`J^9GYy1g|yBZ4;}*UAv;t9K_$z{B2!zyLL=_%j83P6?K(tZT)xUIgBNpa|I7Re#4~SE z`x51{8JV~6S$$=!{A|XTX}{Rp4X!Gb)kL>$%Hxk6P@H3rnzpik!0moXr9=&g=;ADA zBzF($Tv3`X1{^KjdS;ViV`+^!2LWcljDtU33u0lR_IbQIQO*vv21bFHl(rhly~+5}+@+|%~wL@la+@YkvW5gMA+13qCoCOtngXzj|H8OY#8xufd1 zc?ed@<(*ILl0M-NPTpQi%OtLjPhf^cIDSkm#lI_{K**^|vAyL%{>+jTc74!DDmmSu zpKz1DfeSmYa0B)e>ZuMoAqF28M4x5HzU7HUu0U6TdE8c= zr%HBh$pl5InKi?Z=`!lCfAph%^xYfKYMMKaXRobmwMq}3HruXQi8$}A zWpI_6>GXI}t3MG4RBW^oCFq@%s7*)Ecq8S)YJJk z))5yU3GLVpOmoOlK8Z(&Cycoh5Fz#{Mv}phzvh}Xo>pWyy@Z7bVtWagOwF5hs})Vu zK>LNLZaN>}&JjMVFi-o(edoh|Y}3Hswc;##!9v)hf*}hKUjuq3Z~WbDmyiZl$>{MP zCMEAZXm@&XN5U({*zYK}*Nxo`D=G98zM-i$em}e-!!A`eLuEI+^Bdw+U^w5{?fW@V z!8C}cw>b^5kfulY~FjPHg^D0&>!3cVRH=wtX{(+eN7$xe$ z$)w0fi{z2=TLsZ;;BHq?4JIvGB$?7Xkx#l<6YFQ|^R z>v-C+F9G_~AeYOhiUyqqP3!!~xQwj)9j>)K_T&9n4EbxzJCRUU9A16IL4V7sbYt#! zSXB6YAXBdU58^_R$o%oi`Y$MqkS+zhc_wN(N#?@PERg(}Mrg7i{nh}_MEJ9WIR-Bm zIXLq6ORX z@+`6HJq_wIuX-p-QV-kroJZJX0G_PZ+ zb5#C8B*7eOxg8d8*enIiv1O#TqkZQ>GQbG^|CyRmFm3@J&HJ zLxSJ6^~|CvQQ+z+aWudDNcSf;bUl`o+YqC4_Rf;~j>#79*-*s%xNc6f{gDp`Jz|ek z#6gJ~j3n3ZV5Bvv7CM(6kPu96j0qI&T%}3qfbsG>iTnmXXa749n4NXQVaqQ88h9>tk^oY)m z39wKgx-nb6$6cA^0Y*(?zm#@bdhAk(w{oxtoO6>qSSb+gk52Od@;uEI;KsNu@)nnK zW<9dqjQ3D0JE&0QslWZWSj7b; zPwtT0v7WHcy$N+3-giJHiFTl1aINky(VqIDKjhT_@)!Q-6*;wS0?}r|)c`uUQ?n51 z%|+@m_gg4`R~V=d=7mkBQvV!b(wq^?Q{G_)-A3g37m|mTDLkk>g2*JRX42PsBJ#itL4|Koc2)+xFCa&`p#QmjvV!_mn+iW zNN`E(LEe!$aSt?)e7b7aZ$96kMgRZQ+x`OO$eeP*C*YIl;H1k{BfkD?^m1F0g-ERr@a2-XJy{HGgu>Zi0DXV} zsq$6+Rr_kFto$7M)Xf>@$du#W{ZB`c7nvQfviOgRA%hWzF^V`#^Sqard8Ub**;5R& zd#6MPwZ7)baje#8&r7L$K!&4lMF_X)FKz%GminwH||Y zPj215i4J$=PBjQwE*c*0;LQf}-?FaVd^<1f!)!?xj$dE2$nf>x@EX0Oqhvg0fgrKv zkr7O8q9B<;yKWJ_cdN|7AcO@H-N&o;PbBD2(^5EmV1E?QmFb9|{#IWXaHF3c9;9(6 zSP;>rMRDC&1JcIW8Z~lws4>JT(WntH8u}@wz+S4%J67TPH87|OXogFbGeCA+#74_Q z6Kaov8JEjv!wTi+889hbmW69s`>|r6OUdz}UNEogcViG1PA-OFRNNbmk|*~FXocB$ zsJrj^U&eP_Y`A$d)1p^69g!nQYPrsrx8Ejkqq|9%|A2=ZrJz9YAK!P8V}6Iw?whkt zhp!|ATqcj-C#*9JgQf9c*lX&O&hJNxs-c*$K2lpUTlGh_`I<=BZaP%C<{zR5`lswO z>yTNCH8orKVrn}*hke6cC&9XF(Wg6_!S*r=S|-uv11R%qiw+3ypt8DdNy4wTk$WpP z-QNdbqMA2r8s}v`*IW2lM5l#6Mx?>}l~lnPoqTA3zwN|?%gS@XK8cRtiu%Ru{zyz4qb7i1QW$d!m9~20qU9-dW^MX`l`{73`t^Pkp8#Tw1&YKpvi@QvG{poSl?wk z(bm<}Tdnlp^_GlBfsU_*Z_~r(>Gr&r@kEE!ThT{^cMCMYb%Nong=*uh#g}qP&h<)i z<}(d58ca%-&S{FwGE{s8xqWzlp`bku)DRJd!GE6<4I|j}TIUZRyDANFqAR^hO2K;# z%rtN1@1b1|6;?$!H!Y0dacT<)J}`h`0DzA1)MU@Dv?3B!7Z6^c=>@l8^Gylw{FTn-B-)Rp!1xh^nSvb@J0!tyG^$*E(M0~262dj#KHC~D7k zrXn4o2Lz6yk$D9__BO<&u!0kLON$+9)zS^x;v<4=Zkgh8LL0^cV z!^9Gd-CRoTJ~;zd@a`T9HhFFKmj;{O#h1n^uQ{e*-)Jlpm}jW;A^_F}{lUY99d#S` zd#hpy(_O&?$rOg9bVA@nNUM@_W;{5)>8W8rhHT0-!DbJ;K&@{ewkj1B?>>N?`5*aV z5-P8$^>oLgGlE@qU_F;z3;v{ms9<@9rxD zxTI3|6{}Sh^x1NWI?}g~Vqov^Udq{mvn~wuou>(F2Apyq1fKw*1Mgj5MNf|!IRwa* z&Fecsw0Fh$&;32?P&w{_NMq=?O?GU1%+dF-+a2q2$^`gzqJH}Mhj}P{_d9hK!%;v< zkp+9ODS;)&GGPV4IQB6K*25y476d*)*Z6V(11#W2 z8reV==ua8D3vi+>+v(t=r?H9us-4cIJ@Y`FXcdz+oQO5Y*fMajKEA&3l&`eL@U5HI z*@MaF=s~l#OS6P0CI}0t$`;^)#^sA_%;E9aA7jYSq-t~Bi`zt9k{S%3 zUq7lPrVhtvKux7ni0?qqRx41vC@`#Y6*>3Zzw}%m{+8W&+~53fcg0&C71cCnWSJxX z_sPgyunFvr$4t#D+6r884_czs}k=E~NLW zy(waaQp1U|nuPXhMwP(X%_{Zl>3&xgk~Q}F!uT)QFk%p;UeGd<>;W)b7PL=-%em29 zMO*YPLR_LS$?*YT^W>O0?26Se(Zs^lrZIrMWe>h@Z%RpFP5`*~kfa3#R2Cc~pkS^q zg*kFmZV{o4ap9`jODo#UqpD3$u25i1q3||0+Wc~)#Som2u9!}0jLLVBO?r4@&(k$HPQo7oBru3sK+1`2Zq60O?vRoDZM`W=?Sig;zr`HuG49(yyn zTYt_@??0{-0%s{LhOQZBl7TrvZ>>$z2oMAkHg8W_@kPx{A3g<#O-~0x$_Z=nKN)tE zb3uDY2p@J(i~3k7k2?>nE==5SXx)nA+bL6uixQVvbvzWptstRnFQ{C6Jj4R1MT?8l z8pLQQwo&#KNsf?+J)_jXTl9}hkI5x%+CW6>V`E#uqIsg)u`o_jSFf{ZfW8oX#DvBf zs8D8qI4-QBxf2tq;y=d()Tb%MM5pM0#g1&;?qsmrORBr&y?+$L(E!rix4}upw)XHS z6FuwK^H10EL5kf!3FdAKXWRsRg443?Rl-LC{Ou1ziZ`1yRchM6j|S)Kcm|srn84_! zrch>-C1&MCQj)H3ttz1ZptC_AaSGn8`ezJ%&=9%nt-_=YS14!IyW#>6;e9!mNnx3uxD-geO;(_#tKz((8qN-!llNO#b&)FMm|{MNI+32fLHKO z7h}$C74%rtn}tRVlQk5sXmBTVGQtUGlWCoe@;YZ~bSsVIgF1~~fjH6xQ(_#s!%vRY ze|cg57FbHs1SSYM-c;Q51L6U;Y8y@Y10_a(Y~LX<)c$~X;5xzlFLSGNQsYHUI+fLLMvU7Uo&TQXMOD=!_ z00RJwWM`wDH1@sGkTchW|?7|n(f7Rw-Yko8>+nxM?L(l$!MtCyDlROp*m-ad_RC6 z-Q>Fx`bdi<8XjH9aq}zF<(#V}qQ7hzz`0RrJ3rW3!DKwMlzx`U+^_#p7;fZ*txdA! z9pTo@J9y4E8A|&iWGK?4U7BQ*+kKKBal3942pY`*T?gjv&G(4)+aknJ1a~jlGFh$Z zr!?%3=?0QV%IbRu7UjlG9z2X)nJ3kV5eVOsgv0sXmwjJ6dglOABF&vnT z1koq%{D!u!Ay@ruCnt!v4zx`V=0F-LV|27hhuj2`>^P(tDyoa*J_3Q`0G!_0HYF#r z$1sZ{-ZOCq|ImM9I^WSdbRd~i+2YEG3YG^H@RDhaFveb4^-Z_#D=GHs|2R^<1$(@L zRLELsnxI1Y#6((FRVF-Sl{0UWjGn(h1$?qm!C&ax;b8o0PYA zHNFD*%7=-Rgha0!?)+jJwNGNtn7}D6iuR$oS?-e^6}zg-H6VLqGlAs(|HNs+>i^CZ zeJm1o8H3=m_(}S2V;x;4eZ0E0a#B|r$5q37)pho2Oh686s*Oo$Yq8uD$Gf`FCiLV} zwHIX7T801om%Vd#QV0<@rhziuEw2eUr*$0V$K;&O<~N5u68S6${LW&dW|KtzpH;~v zQef@pbIj|=C_)PKPMgw4LMxK|?mZMr(UDua!ubxWJlZBVMs z0{0@D54yZ8_wz^V5u33H!e*zyjC7KQ*Fqv<)agOf1U2Q&53Gt!m+RBuHuMA1fXS3d zDOwDw#;IKTl8Jo?V;7k~%|G4)*GLH8)VZpU{pFdKSNPcXM^y@SiyNZ~?L(Vc(Ke3& z85@|OVQE2YOzBRrgvzdsGE+lYQc#^u=SYfxx{Z0pOpxBUfmzfbxXryR-U>gm45>>l zVdePs<08Ep2G15M;?dqG^pS~(AB5dKgsAOlF^6=g0_zA@YCAzAaJN&fU$9gnCSRJ# z9N7-oJY+<{k0z0R0H?@Lr<_(JhmokU*lcz-vSB#x(Un!W2+@%xujI~Z6zdaJCtq`Es;^p1Z%u@Jwi>^%KjJ6!l?*b3<^ z(AeU~)b5B8UGzq@vKJ0MI4`aUC<_-3ApFfuXSiL9TL$T>GUtk6Pmq;CsP;`bH$M9@ z6J%H^XJkNpOna5eP96>V+jV|`mthTTe0y8&NJ%~5;==j^HclBfOU_3}Gdu#7YFt&b zi=y%ga+DGZ<~6uJ6hN(F)AHzF!r*^#k4yj~%WyR*-Aj;^rl?&IH@AtQc3SWIt6 zKkxVkBq8dReJ5iX38_T}-O}%?&v=VNqzcR4n5#u1dRdsU02$V^|A}$n91=8De9GRm z%YXszX`f&K00s6+(nEZo!Lup}V@wa`Is)2WY>A1^TdjQ)CqYD>>OXu7qz+ULVJ*xq z;rr3fZ|If)kET~M_1}ogS(SG`ZP(0-cqjCN*yj_wEoxSj#t)9sSZ8zR0$2@riMG2w zsnk&;xv2Ieq&FT$eCMoFsa=2?OyECVV;bqzfTDOs3vEKSnZAc&v1c)37jH}iL*FtW z;E419q>@~`JMVyMV)nY=7@hNYwiZQ=PVH3tu;VyWjlcnFD2{9@OE63s;xUeX+Voy4erb)r4`28V?}{27jPNNh z1zfp4ScM&34TPV6e0_QrZ(DCj^e?!xE`?%3LoIpzQ< z%iQ2b5x*1x1ZZ;pzuKJVCYUWu zM!fMMO@;P)vio3Qw1)_-QK{cJe%!pnszTv_}cRU0aDBJm4UA8M$zu?Pmte~cA?m!s&^_M{S@!HA8%JaSQ z&--pGE)Iu7%zkxs?Clt{VU?sDS~30-Ft(QEsQ8o2&?1g@H|r~&EY@K`gts0Vo}*#4PK(Myla*>W`3-#StwnHivc8)Sl4(^!7Df7 z>3>JFRBt>*aUo0b-9vw5uVdRLPVWlGmDr_`ZZm@fZgQw6~~udWp_S^j%88`rCUNNp)=DD?V|EH@}grbrkoj z3Ec*EN<4+gL-f5)^xH0OrcXw=_dZBcy|VeH^b`Vw^Suu3|JJ=B4K}4&^uM=4;lNPq zh%!Fla;^8h4z^+MbW6vckP~GV8uZgZjVH`eq2MfzQ2}%6D?6Az-zTl8j+@z$DEKA& zct?%F3>h^T=%#+;Fk;)mkEA`)v;%LBE7deprrFAr@22gdGJQ?N>^;{rLXgwWHTSFA z)Z}-OF3^$bRGf#!(V>6Ff0IQJwG#+>(+a6bK0ACJ7t&+ATSe{kwhRnd3-43iGMJ=- z?!X~_T!7;+53LJSOD>EPi}Y4mrV&+J-NoH7{t^& zyL6uR6-`isNVfouB1Y<&&}3%0F4+bntS$?02WsCkbkZ0Kxt*uJcRc)_n8J9Q@nb>M zcfFAGnEGed2KcY{k0j*8s}Q)Qr;`0}>4C0T2!+xj!Gb*~q!^U&wDwm&5N@Us|JgwHokJ)J%7|VP1gc}aQc?n=8orc=d`t&-FU~1FHokJD5SH%j`9K37!mG68(-5-nrs_w8o_cT zB;wH{?%))VOR#_fCpl-p00093Syuya8L`mlLX!1w|HYSf^0?IMY=)42O8jbZF+^yX zxjT*%wC&>IhxL4x?#ZquEPN(QCRf^$in(IpTtB*Ych}U*_Z8}c7-IMWE8O*3 zk3g^~E?cO=W0}5@S-=1Q0|1FettIqfSe&R=ls`ss8FN1VOT4|`52$V^@x-;#(5 z;jFwGKppLmJogON&l$EL=Ss>u=Td zO)Urr2mf=nifB>U=kJy5IfBcygI=hcguX&Ja?xF6H!q6XSV2*#l`LGs8bZGh=06FX zv5E}>Ak=12<2mmwL?JnOQoix>^U4`LFF1l|LHWs3?0sGg$!TkuBP-0m98$yzOhZ)z z*sVA{!o{IC_GfhWP&O7wkTM!y&>Yia(uD^}RtJ~20Dv8XajbvBG`;6E8Lh)qnP&7< zY9wQ6AHJBn@~=w#VR>pC=X=}_XcfU%)_p9vl`Cq4xhAVPj`<2VEn;(#I;cTMH4LY zW}Id81AQQ}dcLWViFK@M)>2H84kc8adx_(Pi~T`j80b~73OlG1X<$%MkIx@yC|-f5 z(@_KuE;3KJBQ)hxD8AnG7=v9@U_lp5`Z#dbQAyHJxTm7BEBu&VR2s#%iFMwr(e0~f z-2tZrI}L zA4mu>|2=3%6oFJ*h9vk27=(heJpd%tL56KI8C`PLKyB|a7G1O*F=;+-r4OAwzeDIX z&nADc-Giyh$jm!QTJebiWGx77XA zzW6OGnZ(G>d+I~Z+bAHl5%*Se~0Og8iN*(W2q=Xgq7cnI(wh%yK)r<3* zg8d05nQFcoNszNW^gu--%{3naBq}ya0-c>c7d&}sCC7HqagPxUx=ilJm~9ls9@I;O z))LATSH}JW+65B`wmA}C2MJ8pclr=Afbn_)GJ+AcEB+!z)~naeX|r1fmQ-4`c(A0GKDNWr|rJ2Pbb1^W~lv_3mICGH<+&|P|Fc8_Bul3;)iLX>S zh+52<&&1WBNwJ|j;NR6HJJh?;10)4% zO=h8=1S+GFmidYly#I02EyVvDn4e5eimjrplQVo$ZLQj}FVkiq81_3>6hAfr4fFJ{ zN8NB@eqzxfa}9ccf12DAf)IA7{C$dVOHR*Ty^4B7Wvt%eLBDABz`0=Xpma!s7zGy8^DL9X{|9HX;|=dhJ8#or^_!OhKYdnAs%3oh)f>zf}LZ@jBU}MkxJ$ zU-sW=jQd1sgufUsr%VceBFPA~YV9j6Lq>PR*C4~NB+z;w1={{9^w< z{=z8xc^vDxQnt%Jh%AzEEv+jo>I|Q(wIso``TrR*z%?+{5CCVSq}Eg4ROgIF>LL`l z9Lh%TDHu-|J{;X>zgfm!#HDQV_Q6!@BQx5nm3Ea1do%;x9L&lpI1DC#sKfh3c=#@} zj!b3U>ng{Un;Qzc#B8giS)L0}hX+ivV_q#bDIQ6vFo?R9>?l+@dNd~dq54uoZ2AXz zTMWObzuq(upg~KwvMKlE6rhazM@8zGY%GU9WMg8qBNgZp!=GiOqd(nXb59?HFFUgw zI~Kw?RQ*A*s~F`zK!!Z}9~q;8~zoneD^gG`62{FsibepD=D^h-w@yfpji9V2@?K zM}}j7Z|wNy8*arjMl01?L}HRqRd`_dhp)ixzsJdj-;{*AZb+B(=24}De5>Fj)#_-z zx}T7=TicrCoTlIyQq-yMpEvMX5_Y=}!zu?iIHRO(JM_xnD_BEDe6iaD-rpJLR58~; zczv1Ioz3(>VA#mvb4yKr$8k1c7n36mm$0ptl#PK3cV>vdq+N%XStkP|7mBy9alV(z zy>KOqw@oUdD67@}UeW#rR8xQd`#&mf=yh;VZJFkJKzi+a3dO@Y?1eMQmXJ(ts!yOK zZ(XK~L2zrcb6BhajXAdX&mPYZEfS%5dTHnlp*RTW;fjF7)(K`3Y}k%M1kaG=7y`i9 znf1$cd6%Q|3)by>y$?zum1s!u5q=J+jH?KIX!?Gw5oS*RJH5swP*d^G{49=d;@8D9 zmb6X6rsVZ~UA=kF_&su4Yl96wz{U;AN}9u5yH>j9o9%L3SZw3 zUlkBg3#jC6Bog3L%`==AUocqD$x2G$L)w7G&W&df^m7 z0lLfLAf8BfsMthdfWUm0Mocr-7$*kgv3VRuee(X{U=uSQszk_aGkRObGnfx!hVS|S z{QKNc000Gx*Tv?9Nkfxo2RgSDv6TMdE{A8Kye{;nd3)9rGhQYadQv;7ocrQ&D?rd7 zcQhankGbDH5rMNT%6V+RZKB|&3JiQBjSWP4%NTW!;6hw|PSFjLO6RxJe{)=h5m?IT zlJ5bHEQ@4J{D0W~&?3Eh73zmN3fOw{->z!vx`$Qxhbx2@n|6y zxP~weq;O+ticou@=9pQsqalkXmPSyaB=1x|z-8&@ZsN{8Ut6T*vmli$%3 zuE2!jN~4XJaErdfaU^$L)AYIunMq(-aGbS7hq!pH4MySK4RaJ3I0Jd#KM(}ww1y}5 ztrxU)rD6aNu3^sdpg`gaK!$Q$nDvN?q7NG7KJN0b+xL$3kwq>2Q$&X1=z9`|G8j1%DaLK=o4J{Km-H8*5X->HuekOxh16ty+9itPsTS?GK zp83r>1O#6tk&yVvGoG_{#2>|m2~@064YM%(~R zS3xKoG3D5M2~1Gcm{mY&I|(zGn^CqtoTBu{$N&HX0009389v30wDs5gKD7)d-UDz! znnL@Z7d$Knu>J}nZ{9*l0onbc=%LF6@!GK{LqId(jF_=IDIRPA*I!`KYy_EQ$m~`- z$q=#GXEMI0pFEHo4pC;Sxw!fBlac{UZ*=Nb!?izjy!4yU_Fa!Pru3KF7pw9gewrX* z-k@t=u=Zr2Q~nq51ZqGgCPh;2<}SHBsKdpdonb4}6mJOry^_@0E-_#XdYkx(k+R#9 z)!y|bGMVtSp38JNMu}L^q29^eR$;t6Cgl4y$!OpaReyHSos1x^a7m1-s#Q*W94Dno zS|8S#R#;!A%b+?vZb+A2%2>GEgO%#xr9~cANh+iuMh!~#Xi9Hgrr@x!V#G%QkiCdx zR1OMe;7~x#LW7=rkg9VHiyKO+As0hmvqJu0%jlm%g@7?w7h>1o*g{}<1q}tG+~m+g zDprQI>_%*cP_ve52G@NA-OO^j?%?~&(l7N~*`DN2KK(!d6F}LVF&R-x`0RgK{Bv6I z2wH|&|05>`xs~Y0Z*8Z^gmknP|3Z3WTQ3aC1QLOauIkx^qGvbJ)#70WXyj*bEvg9Z%oc>S~T zEl)%u`UUT1E=60sE*p3>Osld&)^q3cWyya_cdlD7$PqS*S&`)NS|e+hEvy^5nc6t* zNv07a4z$#9HIzg?LYj;9JGs6QPGCXlh#-)oS-zM_CYD+?fMNlR~a87wGd#Ckb;qakVOqN+-K; zl@SrfFd%B7>Oa8hFuFpC5{pwzL)u3M_KmK=&mUp?+&YG1#0ILp5UBO*Otd**Bczr0 zE&0vUa~zCxm&ONO^fY^`ZiA)D=ihklJJFlNgZh=jaw9xUzqyLuf9P=r z>$|w{y;b^hk9wE?jl`@pYUJ$kNeQ7xfT6~3v`fVNwc`z@%jAWU%D+c}1kZ_r=D|zNNT&HvxDX03 zC|z?Wbgm1H+9|+6@RZt6Ss|3VcW)ET*|MC~W-riQHkanYTPDIBB*g*HSZeiyLmo1& zUc5Ei427S|w}S$)W44SAtA)=YStiRS`WrB}L!OKhlq2bS`3nijWI7EO)v;^l-~9i| zBW5!1C0^2Sp~YZihN8uNKwsMUFo&u^N&0E17BbG1W%o z2B1HqoGW2v!9iN9`hM)aM2G44QUrmtkWKw5;zAA)0oA^bOA17K+s26GgQ^LX1WuZ- zM@lv)UMvf?HOk_&a<7x!y%OPSaJbd`OILMOcfu#MofMn(JWg<(2(K&C)+7H7Fu&?< z#`{i}hSN|tf1K_j*hIpYI5)s4_U%i9px`=TLveym3gP-=0tn6_HY43&Gy5k|s^H(~ zp*yiMi#sB13q+T_oJ#B?Wm%JG!SFjF&b(J;iOY<1s!pWRw(wafGR+X3M4ZeidtZ@; z4qXCBq^!@`{k%S5P(=IVm@k-*pZm&YX%(%m{)fhfkBk5@x+!B3rIMKc~ z8hX%{?GawUatCCSFT%2MtItmqZsZF8&wJ_bp+4R5WBma-W_j+;UX!;A9{%CGbwK_i z?Gwx3_IBy(;%FEE00v)J=(qH{iPS!z@KCJ5we1k0wc#@OBU=8QR!>{XdW-CwvB4Aw zpeeO&e=#QMEYNC-`m9!UB%Nc)2O$XSs*4DnZX^Uq!wLAG8|x?LHO6M!B^qov$Lc;i z7mghCg@&Ttq6&h=V@WS`m<(0{?U^u$RB0PKgiOh%U`@@NVAGACr%h?SWMG)p++tG00iQN z?=Dp&?*IS;0L0(ZE}gbj>(RN^&`^scd@*;r704lKJW-6|IcpVtQaawe_)p=Xtif;4 z@c_1!PJ@^v;{-JjPIogJ_5K^eS{nsLk6SUACqluQjGQhceg%uH$Qm{RJTi$$_E`)v-KpzEz8Bq<|;S1IHikVx6g0lZLelaT6iy zW@Z^IId&|6{+nRTTJAXr4=hU|?CUK1G!%Q(q&-CKbT~&j>hxBkID{SM;(Bcm>S>45 zk4*bLv@|>&h>4yGs!@!!+Cl|@lHZn@r2q3!!ZRF!_XsBB)Cb;ghk1Rwc0Nr4rELgU z_{?^AFi)So^C!+ZfCCRGEv{E^TYIuno}@N|60paw7N8(@;C>wp$M$+0%%{jB?1AiH zz#nL@wirs#Fabq<+Us|O$9;LUOjeJxua%%eA5pSGg1@*egMVrHcn{75gUVm>Zy*8` zb}kyK$)7(tI_3y-R&M0o!be}$xsi2;!PK5I-)GJ<$?K^&$Cp{XCExXxeHiF$=FZ?_ zpcuL5V%ePW1@yj1!ED--=D4YRkkh--dno z2)~DLUII%Qj|sey-Wow@T?12^xI3qCH~^$4wJw>rf!iX~+`&_~2~_i1LD$nYMwFmm zrsLOK_!A2lXtPThXx0iR4yCh*h;*$*W%o8FQ&KENO)maIkO(o^X3L~NZI6Nv(n^io zCrNF{E5zs4;yB? zw_=#Pk8Jphzw4{*EAx)Wu31710JpJvPK|O}aiHX;lt z5AR5hEM$9@m6bV2%kZmuf}#6b8cZ--^l0IAhRoN2Us$|r$`m28d^`Nv4!BA{AICrj zvEo|mzTHh79slCE+WW_TSyBF7KbT-9(MANC0Jn&6VG@JdKhZHM1I#6>{9=xu=mGdi z1cFj;8xW}B`Xi&5pa`KRa&@pS(3j<53R*W;0-yMe=Np~%AC*^y?5W-v2}ChBWnzg{ zdpI{1%PG5QEhzLY&n#Zy3nq%|DJyls{5&u0E$pYC`Lq}I-7RH7KWb6sZi3pnQBJF3 ziwnWLT`*zayPIgRN6|YRwD$tY_vAR`e}>_3>9ihOM<+lBPxbX1TN;r{{Oa#WD&E4Q z<*0!%bE?bH?N9hoICo;15IL|@z1dB_Kn8kH+{mviFJ4l%_$kX}a3RCX2_>Hr<@a)A zkR3@Z{uhUBTpZWt4ridss6I)ie`K=K<9G}W-)2@?XlKm-P7QzmJDFT^p>rQWWKPj< zoKVA&tJ_!R6uF1?Zse4KC(v`x0wc5^e^&ec@LBrc#Y%$Re8L+y)ebDF_Na(gn~>YB z1tszeN5<_XJBnQ^qF=w(IDRR^89sC-e#CGacJ1rILk&@sL&r~jsj1roPsF#=R9*IC)7uL$d*}~cL90!&?}CDVSOHQ@IZr>e++_ZrbV-7Bke4*9fOg6X1*-0s9A% zaG~uAn3J{Z0{au^&rgtMnKUB=#h@)uKuyeO&gZT0F?$FwYYyT|YjzA%g%%^OvO!k8 zkjuo_B#m-Mpg9YWbFSW-RWZWop|tFO>ed&%K zPS+SWKmY&(00093Hw)%T`W-(pW8D9x!S6$v!{(eE=Ko2Bq3O!s_fC;(f0aygKA($q zu{S5r8g=mXrz`RN&830UxJ*}a?gsDsFa@TZoeN`0tqsX*GkO;qGbuNTc8!CaSWw${ zYb`J-OE`wRXkQzzcUQTM`czEx{V$ZB=Y>L>;5K;$jZ?U%IE*O=p!Y`0SKSf(44@tF^v5Ve!s+ z6%?T{BxZ^9JUTg+!wRdH7h1EpHquEQ$u)Q%(?*kMy$t`w2sM4x!ZygD000aR3<5C} z)lLXYH{;36iqRSmgGP{TGv?YCr^xS`Tc`l^*u*-S1=(FbLqWaVjrL+2l>q!&M>;Zv z$oQs8&3jL?O}O)ie5*D>JludLG6fx^8(c)$uC)Ei}=cowR~H71h?oV!XMFnGy7 zo*okBTs(rU2#JaMNS=;i?5a`#9HhN-;ZrOuD3!;fvBD-ZKD7|(;V@~+iDeJx5-MaTIokE=WM`zYlYMDHN@?>lN1um0|57;7A zLr*Ke?4preiLxA$&G=4S9=S{~po;K^iMZh{9RLHBYRWrY+-oM&ws|Fdd)8fBbTV!b z7ICb;?_K~WE%h~iyx%S0YbmVSrG12HXG2c77)_eArxzT^Hh(b)eE^EO2J&N;Qu8v0 z#e&r(oeYS(w3apuzB#Y~t_r{Bh%&F3tY%^=~`Bhh$RG!b{Q{W_VpLdPNLK*{s z)?qiwIg>-hGMoetVUAkV8+j4{?6ZzvNR9y7zo43H@7r$>mOD*RxRzUaiHhGSf2vE( z=$bJ*Di>6fnuiEW2j^d zfiBRl?4BLMg`}0k{t0);oA_&BuzYNt2}4Q#TDCW2*We4zbaaTL4{WbU*=HR6E9hbs z8caxi#Z97V$pJ^Px$q}{JC924@u8E09TzMfKmM2OEWG2}&|oc1EUX43BbQ}#E_c&c zAgU?F|8RUwu4~9ujW~Wx;Tzi!ziizMdzi3K!-=OJp^2%_yw!)F}ms zQN*Ai!|wYtv%SJE0PW9tJ4dguYm()nP3aiXqH$Hg=QPVqQBT?>c1+sB24A*6x3Ewt z#)QUs)?5vRv1P=HvmJ&DU5Gj>vAKNBUqIBZLDa2Yv05^4VZ?+3f^&RzeS^#eu?I1^ z!@MAYN_!jecN+5aKMWVj(`FXg{4Zq%98%rsJGdh(p)$m%0cNau3Gi~Uu%$_{&d1UA zOS<>QL7*0s%?k6c)S;aDMv03@LgUvD?%m3b?^By|yI!Q-5sbC~`6l*1 z-UY6Eu9T+3IeOZEtNhyqxBf*VXx0)aT!n@_GPRUbm*ietexktB>?z&m2{EwCANsxjwfriN!|@w%^mW8KuRLQ@ep*?81t0a?5Ru zFw;pteGhtt$~;PwR7?seyPpEEBQ_jJ~a_=3T;wW z6P$A4_Ie#;V3)VgGQQ+)u;=;xhl?>&Gu4^o72p>AWN$y2+lyM=6FwTCDp$ke&6^*@ z&V{m>OJv@n`iqW`h(h@7eZJ`JzO+~p7i~O%Vz(}Z&x3oOSll$Y6 zjD!pGRFuP~Yf9_v^hIijgC#waWqx;MjDB87*TH7)pU@UYRYzs7p9n zU%(KiqPCpS?T1j6pQh z2F!#*-hr45bA0$R|9`l|>AAvESR(zI$$$u;W~|-@X0biO_cae3X1HUV-8Su2rAvGy zM1Ruo%4Wwec$vXKfm`d$>h-8OtpZSjT}kau@|bC82VVL8(|*_{s$8!*{A4O4@z$7u zpvc6bSNBU-l$=M|>!e)uR2N3?x_&T&3bzp0YCe=^Ns|Q9IYs0NdSM@2#%ROq(@*}+ zM?7l_Aq$6;bxCLDR~2DD@DC`P3C+m^xw7JvET~FQZ)kW%ju=#)RlOtIM2keZnD|*E zseme6xxGCzlVRe?dYd0@*-%C#RM*HNN}877nXsreD-y|Xfxe8;c~hycm=)xX%|n6`_M13B)p|c z_%7thh+Ae{Ds=*CgnP|!!T!hKb1&kvfUWWmSNnj440uy!VxldcpBI7W?w#dXx zorVi-IhPP1+us@>SsC_j`)X^Vl00{cI@%R=g)GMrm|jm8=ZUF&$;${M!e&zcq6O+6y`O*2Lh}FgOIlbf9 zB#DwYXnRjJSyKJDUC9?DXt2VESDQVg&~MZ9WJ0iwTop$Pp)uqL5_=*=z%Yy$Cy=D? zZHEhvU>3!SSJLE+lTA&s=$v>aza!#>@SY<~cbC^D^sEg@TnrBINgdv|KdwwqH3i~1me|UV4^Pma0 zj7IylsDO!{z@`|DvsY`Bf#3$BVG6-7lsE#dv=+y+cBaFjh5?q|mpFZs?pG>$t*Z_N zqw=(%faOBOhwRipROF~6gESRnn*zg_3CK%sOp!@sfP&qPh+aXh zov|k7eqpbs@J9m^34?>XjNyY|ApSrb((_dgyFp>yR60R5c3eJr1if@;Uor``hh(pc z6Hlt&P)L%h{(Dn07;ssG5@7p3agVlN`wmeOA~_SH<#>BoNBM?J@A9Da~>JP zlFXv!md4c#mvtLg#T5TVfA9h%D~_e>2Cg754 zS82eQyga?^{q_QgWmFlkeXaq7Z6)2O9tGisx(K(h3<$tZW12O|G|FMg-wdzZ#|0~T zy{V-H74&4`awYE|3lzKzUJfD7lguHG`^?(|H6Z(pL z8@g0M5X;QLfYl7$HjH~5HC!*r|)5wRbYdoZoa!HB=#lI!d8SV8cmf!4hW3Ac6OsaZ?zOi zRq4mzBe`+|-gq5N{mcP_Cgu+Z)aN5iVsy|S!y)&FaOwxXctf}gY6LecSi9d~t-oa8 z(0L+APuHo)7l?a6w8wdvX=(F5=kn7+zsB+hhgQ9e6GKA^#Kjmzht(H!Z zrH#TsXQTjIK%~Dw5OUS@c)pEG5*3m=7PACI&id69Oy4lBTN`%ArD14eC;Iv=UT`|E zE$R!Q0hF%msLJj5I_dM}0@qiOB}mjg9A+OW(4sEFZ!#GK{;_mLtT_-$TB?%=VTne~ zJ-VO`%fVCP_lW^)Fe=y(6i%s)L$d^$)E62ml)Gt!92L5@ySr1Jazcy9$!<%WW0~+y zNyXOb%tS=u8?$=bASL!$YUtWanhf`pG$^UHXBNy0RiK?AnUfVQR;F98Z=21nYXX_j8yvHw0}cmnG@aJlv69b5dI^XT$? zn1;u^0QfY2duKpz=NOy3IH{2_z7HiJYa2=9@c2@-_$m(?4Ztd%T`YwOG^J^<1#p=I zvxB{C+@@;vq;VL}k*L7n-~7R}0~pfrQ1bp1L4;Z4l_KM#^%agV44#)`Ka!8b zOUPcjmLN~`ZhFM!I=fkMkT&lh5y!Jl4Z$&Z{IDK&yGfLmvRXEV7@XRUn(xMK`JN$j zvshXo9kDkY7`&>A8rG055BN)w^sfYbq$wt@H1sCFgo;+pxhOUT9pTF3Q3%L;O)8-7 z1T|2?t`Rn#o_F~i%6$4J6y`@SfP^zcpv^lc5%vM#!~d)xH!#A*1cg_xUsJ&vRsWB5 z>~>m;t|CbD_cSyDr}*Ce+Vm0aJHi$i6&4kl3_8BX``zG6Yj*8=gy14lz2w-C>bQsi z00RIR?b1k9vyVMo?n7_YIE!3_G}p*eSPXy%;cu#VHl2R!ti6)}8F~9`c64`s9luEp zFTqG?*VqLY`)CX{&xkegDTEBM97zP}B6*h=wgrM_nIGAg_(Eedi3;Gj0 z%E!d=6cg4sTMn@XLZCa+pRJhuT6OyypXke$WyfM+4Gxs?yw4V661_}+d$xaqa0W(B zbRxErnGW<^3BkriG_xA3U|eq~G+>l6f{!G34|WlX+$X(&dz5lb77a$~=Xd*)Ee$7~bH&dnop}!LG z*$@TOxb*dve9bi%Ez@yA?h6(FDE>EC>(FSva}k7+3tR4l{C~tma2j53Q3#?Ix>&kF znF>f=qi^JJ{+#t<>{HN=bI3jj%<+(2*)$j>W9Jp&(R`^QgZVktJQ&^~Q|sg0^L=dR zaDe#S9uFqtdf+r^PS-o%?Va}()^8bn<%=w%r0G^=@ah`eC&Xx-jw*Y!;?C#AhxV<0GBKG_7?07Ap{a)T-@aWNfF6cKHtWUbP0Oe=@t@( zqWp(3*dJHDx4##v7QeO`Nti`mWOn+_`LtobjJg)Z^eiR;-Qc?g^BA46cs~D)a*$W@ zAf8b9*xmwj|CYPJK0n7;3FIJ(t49p7F$R*Y3SzWGzpX*1ZH#G5Ex)_P?rjhCHpe9E zJ+x`V3%Hi}4PicS9%+|To6w|lLv32`s<`$_=Mx^bI$do%7 zE~K_dciV53wI28-rn}jl{T$jE<5JqxDfhfGJ-}usuFA&3n2jK*g@_G+1Hh{10>hzO z(u|J`&hpFKyZDvX=6@Z?%@XRma4vZjn9{|fmOfy zXPhT2j|7*5GQ`*X)Sx;H$IMXQQ>9^N{Rxf91}*)~ z+)Dqh0VA><+}&+lZAp*BVbn7->1;AJDo8_YZ!3>do#J-AUa*$FQZ3>Oqu_BkG3G}2 zXD8DQ&@k=xCBw2dMdS(S{TC>6H#(LfM#3uTF5rv*H&|V(IX6Te$Yh`=q{UE)DGG{W-u?9?Rhn( z8=zBZJzXfa#ZhG5LA5NqIon=yGxjFjLN&a_A zF(FK?akAX~Uv>om6bcCfApyHnuyzy8>9+OKP4BOvdg)rFI4?vlL_$aE=A^%WafMk3;PCrQb+Av=$U_Voh!arI7B z{odlA*740<_Zd(35j}gTJD(weU5CKPQ{|z`c_0oq-f1imQ`L6wO@156NH~vq(_36N zuCISvY=yf98Ov9WFe}VjBw11;81lIvVG^x8L-dhDF4P_XS6YQ-R@TTc=V^1zox;yj zuay-!_D%Z}Og4qcRjsJ!&UKLZ62u5;K8DHNAWyj2OH~QOKYTUsxzhFs8Rr%AhgXg(~T6As1zw z`m$yPRW5mRh)=58eN8Zv-~R~``SEgS*R=`}%l!fV^H)oO0QAb?zvh-+~`95IlSV& zg)R0(WNM^{TODDvP$e&lEI84jQ^t2laSM3L>Q))ja@fRwzG8WPODo6{cf=lFZGkK% zZ;NtZ9isCJ&6XfNhA=zZvO@uHd!GruI~I%(d0C;biK)OmFt+niQ}YneBq)_UtBjla zLb&bC_gPuwO0NHL-&qGqJhQyUjR~RVOqA)X+h=5GJb|=Gwc?0C3G1XuiwgH*l=k&% zH-CK`ZRp(w_%C2SutHDQl38AWvtj5z8yoAhqm%>NV%sjp+SobJJH~%U8}EekuFvlJw*nBTocnO{TH%@9 ziktWIZZy6N8TJx7heUH1s)}`J>W&EXwrs&pAPt5UDQBooy^UprV5bi~TYb#b&PQ?!8)GFvnMU0QTS$!(#_kj`mii}ys>A?mny@!9gkSr%F{;JO)h z5Xkr9fJQ?ygN96%9Dvr0l+Y<&%Pok|cLSi27}my`s@i)uozENh<;=cl2yFX_ya2$q z5+R4`r}84tz!og`DN#A`Qq+HWyiSvW8^HbFz6${m@2`NYnaPdKCI4XRq=ecCra7U9 z9iPkKC`$;|D1I4!k^YP)@>`pRC1NOPO1Gaiars_dEaMCjBDH`uXVJ$8%YFG7yrxs9 z#TCQkiLi-nORF{arCMYgllR80n!X zA=cba2L4`$LM|WikZetKA^z!k>`GPb_|7Nrd4r;^JUX`D&I^}0j2y!WOB-tI*}FC5 z%BOZ*a}(Hh7Rq&4Sjku9B2%$#1=X5gm#&Y<2wBOPVS3BWp!|anY_ZAmjjXU+LYEw7 zmTyAYiDvR3ek(CjUp?YJ5QA<&56_3SHe0v}JS!VS@8uOxz?o1|WI9-3*zVV1*aiUC z(;8pT6qi`72PpHvT~x?$awtSpE1KUfEHQPPV|3M{$9>z>ktCD0`IFD1lrN%Xb~zRb z|K{ieKQpi(&4GhzGES`$ARW9?p<`Jm|Q8v;Dr29S%Zj?B)X?LDnnI&Hom zqnWcGxa89kFIy(2Ir5dUS;g*$OP2wnP0Q2<7%cVAbZIaAuM2VavJNFLQZP|5rYk#V zNLv8yJ2}1}sXjz5>r7pbA(x>TQtX}d5rpxp!i+>@J}EXbjvAM+Fh>y`Oj2z2wGGD2 zs4T_t%fEVU`E$4urwV1kufy6EH%J=jvD7~Ed;6I}W*)q3NdM%Wl$&?(_EP+gIzA@a zyO(IUArYGqfA%5=0eIcM=6kh|)z=R}!mTJr1XLpYYqah&BLb4MWe!TuPGB)y5jC_s z&uYw73-*X@;sV28j9^~_ro^yjqExB9DqeRm61G_7!znU&44tc)2{?h(|fd%-> z=C!CI=Vm#2VHb0t4i3N%ZX`sYi4|ivec5E&#;+n%L2Z$9H_P-p%O=UO6uN-6xBx{G z9ST=|{WtLLxhi6-Q1e9At!us-*HM~PPFN-YpHI>z{v1#!lX6p*cxEHxTOfKPgN5nd z)y3qOc|ohN*zUG;)Lu1Atw*)W*c`b2fa=K}6H}H|#Hn@C+b{qCPJGl4oN+cHdrGmc zVwE=G$2|D)d-6Zze;&ARp_TwxbFxTNPWR|Q1l##0tA)iF|0v2+e>0ZRoOoXism#g4 z^Gc&Nw<0a?uF*-g|9$u_EDsX4x57)YUaU{LNZR2y$2iY}qonjCVCHAe=>K_O#=`nF zQBBqpvX3xB#Lsb#DmGjU@%^QL$mi!@>He6x=C@hk+eL~P{SYx7@8ZZUGo)kNsEaFJ z%Yn@+0C{7oVqQ8JL$uCFIpGTFYjIvoC4TlGM{@rQc(=01Phzm=8-ZxlmG_0Q{Vtpz zz>ZHx^05)6S77*2}OMr{sa9Ts`VW_m#mP|4!!*umeJBU zH4)o&7-h#)x{e)JZMqd)j2B$GSAM2(uU9RCAj1I*O5bE> zo#MQ3hUz5OTts$J^lp2HiP`aQ(GUI)213MH0wE9D6#D}O>dTXY(0(?lcp~;{7!mR= z3DB(w(DPWSA=q9ciCXamz*;%kBSo2Io3>XRJG#jQn>fV}$73ET)Q)vt9ov@d_$u{< z7n+3AV8j9q6$Y_3kXy9hMOof|NUE9KrjN6Fs!|NDrSpl?{H}0fmLTt<5Ags zAxWrov}_ArF^Hq4nEEfoLo$53G(!YwL}v#lbMz;XZ?BMFU%vu_826ybwH+2GRK_S~_N#m5 zl8Xk^h^jA=IfDsRq!;jgwe{J<0gn8^H8j4wyaO@$s!T6n%0!q2Q@HkP6N);z?u{+M@%%1V(WV?g6gj0Pysj?EnZSaW+6OcoXeYBxSB$N z9tGL?Elg%T)kMf3{wb|P+(Ri~_ErbuV7r>{6!262MgzrG*xX9L1PiE8$g{~ce_+-< z2yg-VS->06ZQt4LYhX{_I%G`}H0^EVfMI!eStj`nL(Ct&@r0~C zBu%&2XpC1c!cR^{9d}cTamBw{q-12j&&SYZdQq{rG;eUte}H@A0a#T>=|w5JT34&? zfT?7&FF*mc6*u>Dk$=xJwfcv4#C|4viekr`lWx{LX_t$3V(x>&&ZVaZ*eF=rsXszs zWx}5=EBb})$@iB9>Ex65i=&tPeEQ`WKHRekw2Bvm!x70TzF^G30Qj4y+5ubW0s2(E z)F5b2=ntZ=vw0y_Emrdcgky+3I|q|+inkz?5OV3Ltb5L(a8@#R~kCFx9%Tex}!1dZ5y z!yXq_&?%gOZ~PW~C|@oFj{fFKCvSRbD?BR%;fXHMPiSWs(>Vf75TdCYnPe}wnp}rj z&M%j6Kw1P-$l-4GZ1e)HsYJa;GuG!@x$SD9%E8rei>B!9tWxvjh6eyn&b30SVY%_7 zhNIPSLXnBqKfX65^A=X@q@uyZR)T047G@$xCj;bX&A)2?hLqDqg&t*Yc-_HAptst_ zipH(_#q=()8ZNre=4u}EF;oFwv>XXHGi(&7VSO0@gg2cbpi8-X2Q(zH;y?wDNqMp; z000CKvtN3Qi)Ga|27exQ=QMGsv^L)Y$F2XYsV><>k1Vpj9N}VY+{+YGGG@mnM7@yI zk_3`B)`|jaCS?C4Yt>Zfi;rhu8cx;_6?Ip?EZBv?4XsQr256g@ zk9$l6i(;xj9`D&KDQzYBT939U$u=bvSOPLCAh+T8{ zVv)aQJ;zD&c7nYU6XAL~LLRh{VCnRX{(H(99hzlR3-mC15)PU^+=EG+ zJ=oX|K3dlefbUy={$62tfS6?Whu~R%h27F!URY3V2m)R_1N~*xIh)sWZ0}mp#e%-B35ngKuj;o& zPh(s>U2!2u{tFWB!8ENw<_O!jKcG#`(OXLeu=L^kI`85GphZTl*70S2c|~-DM{AQ!o>9gY9ztc8nX;>3@Z)O zA_&L&>|d6qJp@cmfxnQLFfP6GzISQ1kT6EI{;;sdQcxKnzId~6?W@N(1rekxU{Q8` zXjcoEN9cjcSYJ*}v|7FyTk5e|yw>+nJum~Aq85!xA_?(jWA7=XmkhyBP3Oq1Yj7v` zr+~>deb}tUi}>;mLE`M5T6>PYl^rA!!rIC`=hb8D*tO&wh6=o)B-by0k5NQ@%5RB; z@h*v`Gt0&@cgbr%#7zs`tM{&0M~5Qiiy?x)rdZhY)GOYM%a<~a&R8h~C=4DpJ%-bg z-a+I%Yvus*;D+7@j@z}ZsR>FBN62hrj;%s7zMMC@L$mGzFK^;Nk4uOrGy#jCERvE) zV?idaH9nn3cryf=G$ojd4l+SKc+Y9%o3Jm}kC{C}>ilh$2*`1xO}Nx17I>z{;A2t} zOE72$2wScH+B< z>`+pht(J)#+bl0b0p7|z-6@G8@Qgdhej6N693h;H8(?~Ki?afy)(<(yE9np{-RY$2%bd+jdJl@^LS}^godi&1>Rh zOn1p$wE|1b`oJ{RqhszuXZi%s5e$}Yd$gE2nJ@Q&eCJWMxh8|o$!`@RD(bVp zq^N~(f)*@;{HFtso!#OiyKwMYM9?+Q$b|Sv^u1ACZ1HWuH%Tu5AOB$sT`7{~Le1y3 zrx51D-WcP2W2dWhZN%>#qQ&8QuPgab-+?wr69>Gx_XfZ2vD8zhv`guPy9WP0Wkvc0 z#`#5|QV&CTU!?Hg*yj$2-&+?#tKa$ay(-VH%#~R3)!`sL0r%0qBOc5x^9LonJ~~_N3_d4`E_kC=wm#G0WuO@1wto;w)Q93phA##8%F>Dh6Wjq zUkH1`e;-9)z!GI{1m=~RFZXuUKT7jbF&~|QJSidXoO2NZ8lG_J3P;N!jv;jZ+tbPB zr&S+Yq!XqT!V4h8(dI@ZA=eS)150|w%N>$3tz8-{sT%qO^ z${R&QcA*Ac7rFM960^^+8^rJxL%m3yIUM9$r7xcEQm@?`*cLE5a3xEC)iHNNyhIFuyH&9!43c8=E12xlmn(6lK^scSE`> zuv6q;km-{j)u>A_FG{@-V#n86y_@Q!k~y9dHUv*SIX&BhC14aN=tsBz&*72`YUKoL zXRHwK9fLj8w`JH5#~S~y6T?vh)l`Bx-_)_2i{n-#b&Uvfcm`Dz(;a~p0Cm4XvlMnb z#CiQt5chVWjPp7zA=t&;rXk5L)OLhA^zJNlJ}ui%xBHS)Jko7vo2(EWKgM$g^wtaS z6O*Ebdf1VAKcr}3*NSa}gH$`0q7>v!RNBx~>K-^~8UIx1{KyDxcMe|yLpC3I=!R21 z8U<4NB%|-U@XLKM)rm4AvjFiYtue5efd0CR+ulR49syp_FQ!=<6xWho4=()by%*eG z4*~abbkY(+G`IxPM8EPxz6*FMvnCeI{wud~s#p7pJi{7a zg)f7}z7>Y|;=~sZzSt?vgN$at^-@sbKOw>L3>FJt)Zx;*Zz3aK9ggFOY<9FBgO=mm zZ^Wccx`Y#dr|w6UKM#uhJ_iH3OgrpgnG}&WPMXVlT&CIOxE>@q3ZQoHvG^}w z!77RYaQCzc_kW}_% zu%nnP^@e^;%eZ(*t?;_Om9vug=dWv-wk9+SU8$KW-9xVpR>?5Sb_<^FA<^ZAFa;|v z2+i8f*2gWEFM9GB*?TScKZr#tNiCaPXTjJhO~;P#9`(FBUI zH5tnUHeK8XP5?-qd4W0C!{MX_^uR31@ia+As%gE9UmKJL=TwEz52nezH1Vj97xSL% zSOQ~knWa8c-ihz}kPkXa_rVuRXBNx9Q0y*H000T4&8CaMSRqD z0TDBy?H)M3zgev5$EV-U_a^gj#;c>mV>r)Ep~sYKXrjKnRz~ge|J$F1`3QMR^f|etgev1KuyPd+w@(P;MDKD@v?95RX$@av%1T2v7nl8M%Ba){Gm8#1MeV3t0hlb^ zh@`tU5P34pq^|`etTcSVI~IWE%)_!h(AA}N$kopS<2?Ze-rX$@rA^&U(bZ zO)p?a40tQvlp(zG@wc0?GOdEc@v_-lx8w9km%U8u!(8QNFaDZ;3x!AQDgrJ$ zi<8SGEQZj6)Ye^>)Dhvp?-g0`FPs)@dAPrOm%PEWAi=BonC}BZRD3#`4?5lF=!1x- z1#z&9<@2VOSPR_$u+SlO;Hgky)^;lB{FX9Bkd(X?#MP#B<)`i z+MeoT!|hx<#RnaAwQ^N2zm=rr z7JVJpWtD(~_{BP6o&Xp6K~d>p$qH5Q^nR=WF&x2d#;5*JA z+U)ZTua3}1r^d&Md+0Bo%PlWS+&5bGOAl$E!^WKCc#4GlIfXoaRgB4r(~5r}AzjCe zjhG;w9rekZnpJ9TiNwpit0&v2;5a4T;hF5Xq?O~{%PRQ8%$@5lIb`?Z@|!U}EMeF*+Ib0m*|e_y zsa`q+A0}(DkagFoh9=1dvrY3mZOPK)EZze;C!yFD=KG_Yv#k7kW3yBXVCt0C|9B2E zT&^@mj;KI8&D!|5Whf9+TJFS<@hB_TXqB$=3;XUtvhHfxziSom)D*3wiU) zKZIDA272V7l9GmYjZyYVdYj!23B8IeI_RTH;AdJ(;D{6xh)CWZiDHy9=`UbMyrT); zR7ocA686Mizf5oDMbe+Q@`ZavprZSgAG_Z)1uv`aQF8ex2Ehq_H^awwHS|;-Tgc@3 zGr7@|;xQgV|H$a(0s#%GmUE!nhj?HWd@kW#W`R>ep%}z{y0>30)C4Shw^KMQn6pXT zm2+@gS3Hslvk^VsMbDV(M!l zET9}BF#$$J%1tN22kvHLnoyU37by!c-B#)+;h^XwCf18#Y|3Q9T=ueu)B}5+wg;mh zEuUhb6(F5cuYo<#dVHqB&$KJihPCqET0eljOyS^IT3nvKtRBk_I}nyaEY}iWuog6g z=}TC84V-0rX=`AWmd;n!1JJ5a3vh!^-@-|iqCA|4)v%{5NxHgZ;k|XJw5L1IL%2|G zAN$CU3@J$KMCvro_@y5&Hilaik|qg`PI)XIcJ}jdUl=S#wHv+f1r975xW_#8panl} zcq#V)YoKRMU6E+c?4H!Dweg`Pf8wyOxs%g9)bPo`00094fWruJM5P9x@N8X3yvT?A z)OMZ_k+yoc5bME5aWZ%bEOa1Iwx=Ki#`cK)_Cq5eLA+TC)y(kIGozCPt!DP{sKGjE zm>S|TCUSo6uS2t(43>n~*_gh^s#KXV@X}I0^Q|lsEC|55K;V+Q3$BbtaNdCKESZp+ zXzyqJ{Mbzaptc#mTYH*SE%;yrrzG?jfCl3`YhqtLC5})VeJNLiVKc-d+0>LT2v#W- z7nc!;&qC`^Y!ro2&lhfshh5TFk&VQ)2kj3UGcyEr1uz*x2(K zbcQ{|K-6)%_440#kiTr?X;6Nmk{5$9bjMEUE}xo|=JY{{V$A;wNUwUL5WI6_HL_x9 z%7-f@8^&oO?tmBWhDZ}vl9GtW|gC1`rJrKFnPlzqQ^G0%!5+6za6sibqG;Xj0GPuSL*NWsTL zef@8cC^{YMto-8-j3!nna&1HEk-t^^>nmS7z;e?^?YpJAl@Qb6vTA&q6i7PC%lv5b49NM;$tU4mkiLCzw!kkw1LF3iDr(G(U+>qegdN_ztaG3& zMw_I{VOC7#kk+j)rPL54-OGfuMOL)*ZvK!O0%E)1Z8X$$vles{WmBoVlXa_zfENY~ ztpl|FInmC5z6P@gRUt;(R%Q(Z1ONDi-811!_~{~445J!ARI>yHKKz(L9NjW$93aP8 z_bYY3^Nq&*h8qIsl-!TFZa!;kK|>Asc4?lAXq>94Q-TcI*ne=Fz`>2-*9^Zufs`2m z6%8v%tzm^OTX15iOHdPzUzui$S!+oqe_aZ@F`gCw9*;QaJG6a%^#A^6`ZW4sD+y!L zj{+#7kOs+8G-Yj-!%zs8H*MB%ljYj8;=>X=Y&H(k&I~FVF5Y#MT_j_7dw#2@!-ggM zy*_|CDoCB}Ub6C940b+41Mm+f?jbr-$}`nUj00u-t1jO|n{87{$k&s@Ul*Nu#DuZF z0@{9qHP<7j9S#ivtF2O!QauwAS%n{-Vv0ydTwEqAKZ*GyuXCOqRq9yR0ssI50K=n# zd-9Z=h?hBzB91-6^*I{O*EBoidcXZ+S8&f$7qf|qEN<$6Tk;Wy>o@1Rj8gp23Fwxu z-Xj_9SXf*cvs2A>p6+qa!>=_lDi-r?`Ys3k8Z2t0S~?pGEkzgO<-bhm{o18|WtxV~ z@BlIOPb9r!rlv!qq=j_JPfur6I(!Pg8G((QO0G#~(4h~?j7HZwiannz_|KxC>8Na_ zEbKws;!M;8U&71ALl=6M;0lIi6#w#FP6y!9ptI|o!cUP7sYl(tsak9`XjtsNhK75E z+m*xE&KrEi_TZ>2>xg4vt9V9|u#tKdwtB>u_$CN-c5zCDAx$)rYAGe8kukIm2`;t? zd)n>Qc+ch25;J7HZ($3`Bf?4jXX8#IrFJq+e3{CD^@ zmpr?PsCc2K`EyP@3Dv+f_U^iZ`>%GRKb$*R%o$yoXmK3k?R6Zz@f1ZjpJaGLt^13T z=g8UYt1~$B_G~|8UQy9c@0PVA0c94u-G~}nfpx^f(AS2W(y9kgjcbxOQ;x<02iox- zar$19aDewR%=p*1P}D8AoAgn-1r5P#itrqfXaw|(SgyeN5{{7{(m_?mFE;^P_?Pkx zBrkC)C=V!IgN8Bugj@4+&2fIU+yU9V11I1~nhKbsLjm}cdf`T%0hH+9Ho*Z_bvt8P zT;b6opVga?liM3Yz{PU=m@50;mK?7&ZR&evd(j0i)|AkB;Is5_N`-vTnjI!w&+23D z&(5_qAcQ73aZdnE1uMaK@UW%e*@16x0W_}AyHizDX1L>B8Cd197~&9DQ0G$#FU$;j zm|61RCNTBcCl)+NzTH@5IdkvK@&wmcIv?U%#4*-w7#UT(Rmn^Tvn~b&QZ~O7o1wRw zVhzY$Mg^@eI%M^b-jIL%+MukcWm3|}hNtE=qH-LZ3<9^mBGwpGlV}Wp#*mwE0AP3& zp^BorV=-Kl0RY|Cvg)pO?`@TvoCU%8?%={aiSfEV_C9UBM6X3+f3)txzR}s}GWNff zW^mhjq+l=dD|=9pmtchuQwhC|Ft6_icurU`7V1jN&Hw!ep2wRn@}BDx{}S4Y&oYZ} zB=-r+1c4d4nd2sDcDZeN;teY?(L&EqCROgwc=9B!b9;LFSK1Lj#Kz*EJ$8~$r;b_K z1#c>cUSn-}1PFD%h`BO@cdzCo?490~J5+J+rPTcmhFV;mIDAf*6~WUNLYcygcXHPP zP`w=LfewdwC4WGMRK!3wm5v6H)ojQ_&m8g>M}&e-z8(FnOYagV>cN}SACy-yI^pDf zXMjKe00RKx6UpPdfQwGu9VecRW^XPZyatv<36{_Y5%i$s^BVw6SYReq$E|P3vHWgy z8uVzL?g1Eph7$&tW$Q`Z07Sm&M~}P8v4GN!an4W2O?M}#RxOCt2y*1GQuAt=GY+9E z8p7{DY?ovTr;9TQK)^k5oLt-5x0vMc3dP%3|1zoX;o$9q5064UeCqI&C^#vFiUBP! z*#bM+KxWxjwshd;RkY&MUm1kFb&5iq>dx;U{FRV*mJ3hPwOCL92pd-3X4^NEQ8poQ ztlKh0fDkngk3(>h+5DJ%Krh)Op8cHRvAKnls%*Yy55F$hATbqg&TpB;Ad%jgWc@A3 zw@!-#=bQSe8J`|hH7E-@UfVRN{sP$^f$wsDW{fJP5(~tpl|WgS&@yG(fySvtT%-(6 zQ!qtyaZ*9Es_}i^DLxnb{GOq9mMdnu4zE${}`GLwW~p0RYA|5LhEx%M5gqG``0swt2-a{(N6;v8=q3$3aJSTdzJ zwjy9sNSt?34*u+pCJuO~SO?*r4(|8U_Lky<9g{SuPlA^ToDp4LQL-r9cM<9eTOVo87(?%zne?eRA2ES$C5 zs9%H?2OZ8d=>|eBx`jpwOF^^~s5=HA`^$dP__3aqKJZ7nEW;HwZm{otVrLOHe0c4`?T^lPy<1b{q&Orqfc7DE39tubyi zmq^iUC4qv1{6l7$hFuIUxen=6j!BZo^-u-nU{|Zj+9y#|CdYWCq^;g3%ogEf(bhz= zNWzcpE?!TN`T>JklwX_-f*HQeN*L0JON7GrS5K`Y^uvntoSd!bFK*pV{}JZCl=z`6 z60-a6dgbUcozQdRqqU3iGV6)b{l!F~=*#jhR!AiF>7Q6KQ`squ>b3Wpe+){AAjtOw zRs4PC>Qjk(*iF?31@I;CZbOjg`yvYe{zuBGC^>V$f7z8T3ucGR7@nJA zqMpCSp7qN1n~PRcTsSojDq}T2oRFrOW>w}7y1Frq)!UuwL{4;cjHrT*owN18=e(E~(`KUk(_6I>GKtAtZ zV7o&OpRz-tDkQ+}zQ)}+k!C9Lv1cP_d}*D?TBW3{q5o6YO;!FKD*^-omn7CoOG6P* zU@zt*=$u8;%|PXn-afW`r(Vt=aI49raO^L>gs01m5eSwfclF!Jg>%QLBv`-z00RIF zX=}+2z4E2tQTeAW$mi+kPV3QVCo)PiEIcvRug!q7L3H`Nc+ZW$mS-#3iRsC?EO{3> z!a@z^_JqiHgu~%@nIW+}#zW)FI2PZ($7D*aPAZM1FdM8wZyj;RZr<2YEjYr72<;2;@@Pf2q z$RqUw+c_Iz9&xCtqK~~h+Br`tTw^omjX*GVA#POa>>?d<$=}cwY<<6MgOu!QnTR7T z(=Ji9Z>5&@Gg%@qCu18Mwrr65FFyJq-Wu~I(NsAj^z??Pxh6I1vaJNJ@T+KA+qx0& zcFrvj@;b8oQO_6)GgH!hRfT8#`nn9#V_zwz@YAAoTF8~pnW40dOC=4^;%ShC#K{Ic z&&iAr>8WQBZbZ_nGZ8HCRJ#e#voCS42q>)8dR_$L3E(f|u%sXZ3o;sFKQ|tT00093 z00%?7lwa{9pvaZD-1Yrv#4I&pkuI`szxuO&lV;iE{XPuhLheHkzVu&l$?9+NUf6Mz z*5k+*ijC<{6{I2%D!icdBhiVIQ6+g2xNPH>f-sx?x*zv8iHkRM;8SSc%a*A$iVd)_ zIVSzVj{y>H?`XW*jXtN@0zzo2z4kp+C3&GHtSZ8*1_yU_m%oSk*bC`7nuD(`?oe0S zeYWF_nzPvYDteL` z-fb@`AoMhUoH-;;{J%GS2DfE`?F99ZWaYM>0(dCXAKtw9i4p=}i}X%>bkH~(PR3vd z!B<-$T>_JpBgLt$j?{cqnQS#H5R8{YKX72I%x)acCBNIO2}Glc)$>1U_Cd8VdB0}& zwDad^pY?!fIX#i94XeNSJt=(vh#7HV-mTs!ZqD|R2LAB>D)G80|J2Srf7eLK0b+Jk zuNsZ8c1o>C(9|%aCsVs&oF1(`P~S=L6D#4tIvPc#XHo$Gww4k}@XU&~%TKj8{GeRKsf1t^Kc!rmBl|U>N89lkpXIT}n=1^ip zwrs_zddGGPbR4r+3+`FNGcqGqtNn!S3`||d;tq8tKBOoY+%=)suF<)_s&Xq52CGv9 zGThtpVpI(}R-4ZzSLno1Y;yQ(*`sb|z#Lp?-0fOPnko^H*xw>F=Z!ZfT8-Ftwref* zaL%?Yjyv!d^1s-0m?yTUJi4K6aQvdH!XssqX|zU{(f$Ck%`{zLLpYZW;{J~pykFh~ ziHHDKK&Zb%>aUr(A}45Bgz6!6_>1|R6FqA*L|>$EF_sf$fJns8C@NxxE5<$yb@%EJ|z8ZsW=U90Cw zMjH4Un^Is8n9@HhKxmHj%81%>{a!dK=xK}(oKNxPwSi@bx($;8Wz2YjGU9AQyv-PS zL6VVwNm#GcOotuvcwGvXEkIl7SmZJ73WQU39DdEbuFJWA_uYKaQKyUja16uK%%nW1 zmon`IG1K^dDyL}79TtF?%jL*c`u6?b)ky0|2xGC&fJ7F(b&uuP7|2oq`e58!z6%qc z%1>HVx9isq1+!s>B$NbxGa}SjD_&+-j#SlAz#Kz`6PWHKAf~iRmDTRQt2NA>PLHgSM#45Vx^F+c~Zg7 z{oBt?)L_Al)R54l4741z{JAPuSatzT5ZjLde=^J5p<9)b2J>s+jq9Zb86BIM9sJ^? zBwD?4(-O+%kN|p7U{+zWSsrVfRcIL#wkYpdh2(B8vj~qh$`GQg1W}G`gDz~%cm-;h z*e8I*AYD6Kq8J+VI5(q~maB%unzs_Q+v4rZmVu5A?Vd)QX*`Ytwu*XFyhZ2VKbdUdSQa$#oUvEzFtL)jTx|u@W3GRB ziN+}Xuiv{55bT=H*;>uhd@(AZEoH9^gtD_0pQ z6<-*me7%vosMzAROcg+ngAa0rNNQjJC=18y^`La8p1O;od4=^7$qwywC{uEK z27dGgA~EoFm)t{?%w?$)MHt}1>9UxmQ;U7G-DA1hP zQbCQzNQkPB1|E$De45b&b>w9An5ZiAWg@Uq_6&m(Vx>rbIvSb$VNgI7EcL#JaxwM= z2mSydxTDL?k03a>TrZJs+?0{3ptx*cfStDVCPfPYPW0PpC9qgRE#A^y*aj)#o7a6O?!aVFu^%yIS64>>V5UT?N!dk8K}@5yhs1RrJ=GHwl2IJ3jeDHrw*Fa z}Ka7qg%jZ+SZ4qr|Ju?YZFV>-Bem!qP5*P!Uhl z+I)#nv$m+d@%xvs9%sV}OCH;hRJav{c0hIVU=TJ(yW*_=tfplR;G1gKk*T|5=n-0i zEc||GyVo)BzR7WIZ6vM0{tvw)66N0|1liAths6$k2OxqOyeEYm!89|Cox{6_6#h`R zKo=oGkg`xYT(Z`S)C0FCBqSSE&2DAS8Ly!14r5u%x-2|wUQt(c%O=Z}-!enKs{~q! z!B+%OP?Q!r7WS!q=Uk^DLJ<)o2HUCHkE`4r0*5b}Dt3s9l00RKtvI{1^0um6Y`{Jp2=x#d2&@JcK8Nw`) z$9;(7jZV#TbxZdOJgtd@jN?0kJ>)~ulKIH~i~{HmCknn0RsBg7UgsT7ftO3mTC1d2^$#sIf zrPZRpE*vUja42}!r-KDowpB24^=6sUM**RT5#YnK_%-UtX@Lccf+dR@>bTrREXkBU z&_6B)?<&@4`E-d{e2L9sKBv3w$|H`tC`A4L)SJP3&@E?I@p5J0?Hiyl)Q7ZE)wDWH zxL$M}<)koXA*!Vn06(&}4W}ikcWrJ$fo~B1!8w!Ffda)40~@$Qr&Z9K8jHXarsSjK zl+)UCdr5Y7h#^CrXnp;sVu)^Rq~>#!oX!oH_=x`(Odj~o6_WT)?96+H!9wZUes6N8 zVz7somipv#eWX4-@Dw&eIQjPIR-&s+gpS`BEH&Gts*ILABX{(`i$@gyd+8#lDxXXC zM(`!G!v6B4s`F;`#3<^&W=cn|$dU4vgXwxHtNtTH^pA#CDM_lAB)i8jihcl~mQJIdO*j>8lu%F9kv~Ur?@%~mlmPScy-)pIb!B`v$d23FBQnUfi(0~VSamXW%erS%3ibd~7pas&y@4rRyFy|o{G= zagFLZ#7|u8gG8Ktct7`2&4u_s;j4KEz@`k2cro8FXeS?!jqkv8>@AV-+`*KXJnVdtBs-vlM1IOXpkfHVDFXH8 z1T8)>*?pf)V#%hgu9PsGaR!YRCo-oP6iifP4{@AT{pcxx5?cPZe zuEia)IM$KzoE~1XP6nJ_pgXfXOw9PmD8pd?b@{jp=zPvo`Bn&KK%zIe`m88%tkA<@ zk!LstFix~KO&JJDhQmTFg&f=chlZduhrNwzO*hZjAt$$-labLg4k_JQfaFQG+MxrK8cDKK~JScbNYR!GUIqTdyBQl{|&twk9mW?WQ z>_b{>R2T?!@sg{W2U`2iX~Z_1!Q(}i0?UFWMB z81>7+epu|5?Jb;2$8YkEq6KsQL6wb)iT?om%Y5gH!0Jf;3g4p*?bIQm^xry{7!jQL zMJq$UcxQK%d&Z`#j*b|#N>{HjJiR>jLN4<~nwGmPw7^6c=^+u748Wv&;O;ycX50J0 z>8dMRU1+1`@wT*0U7HHq;onh%V*}Jl1A}{3zujVF)e-{pAbIQbeG?g#ehZY1P#41^ z_~~rPXCxP|@-OTtgeAawQn)HrnE|hiM6EO*AEfSAoh=@%UI8oR!JDT`ySp(-s^Y%V zDHsUSi~N{X(w?<9AF(q<|EU|P#>xQ$+|3M~eK~#{ZsC>Yp%qCzY!z(!Q;Qh!V=RRE zkd-RhD2Us4IR0Za*k8J}-<+sqbgh;AI(NURN<1*NID^nc?M}^LwG<>Oc08_=v$O5< zv)djvCtpZ6ooKqlvc{AX3SdHMC=UuMzZ%g^cUS;SFE$w!iX>6ES~S#szXCh`90&cb zJC-8f`Oh#C=I-x%0xmEzm^j5Bc@-Zc0m4u8Mf>s4w|s@9c(PcD3Y>3z51Z!LU61EN zdW7V?`yth?J7~{pR}|{+9&1>z$3k|j0$$no^=;0JC1ZAqN0Pk@%AP{HffL1Rospi! zBpuJY-*Y*z3-Vy>^M$$wXS$II=pkKl8oGv|YVwtJec3;tcBz+mI%ux_t26Zt#a6{x zHnpJ6Wvhs*2S)1nksXt#ZSM;Aucns#J8PoJyS5qGO~-f!xJlG&yoUHWg4W+6Dh{U_ z)y2J?FDe8=@{KbvS1Mz4Ek!=~fc5_PY&)lF)mfhdC<5Kf z`+{CXz&kpQbe*>6&54w+X6oLPhL}r^b9+&?r4iiJ4 zjwCADAH`l@4Zq;Et~Hj_sWC$8g?wpGfXZUkyy zJcQ9&`IGIb+Ju%zMf3Lo|ex z6*anjq;@j(YzBC1TVl@PC3#H@Bjb<07>zVpKZgTo7>WqFie7+ zpbap+ab#;%-^Iw~W`vaI+HJ=}L0H1EVPM@kVlO`vll_f~rAyomsG{VjwD~($JG&;! zVqkB+5y!?ghrk6tc8(MW1^9k#^KjfKlWN_-<*q|xJUQyl|89Od`ae9t{I8zIE8H*#0u-CBNP8!bt zicKp4ml~IpeZv4d{@R<=zyO2)x<9sG(W^uhtmkgt4(yC$Lj#Lsq6&6lY_qDFpy1J~ z)bwBsLWT~j2$8}fgap(et-rhf)VP;z;Y*oyI30_DtV0<;auEgiUpQzv@NeH-=l}o% z00g+lAmgi?ve?5eznU95F*2Z63m`E;|A^WR{S@rhIGA(pDV<~g!_CHEoitUCnTd6>=reCQglZW{X~uw zBS@5Bzm`X2!ZG4mkou@E(Ah51SME0VxV8OE;=-J2&Hc*&>1uyMGh}Z0e~G7OGazw= zzs_KI4VU+0$ETINDLUrqa2F&pWHCG=H^Id?qYuTkYw`X-eJ8ZS3_{X##3zUbj)W)A z`kP3^^e^s*_xcTKqU^r=;K6VVRU&5umcTTfaxvL52u2E9TG>Wm@s^Z}oZXGQyywk> z`4c^mNTsWI`Xn5E{t2l5u3*y($qjIVn*|N_QcJZ#XK)k-Vc|sd6>=1qYp{v&q{f(D z4nK-59Bx^U_~uo)h|+}4nzboqc9eGT$*8ncoamXY`@XPK?b;;{}mxDlQW#=AEm{;o=ggPSaq)W&rXazkWJe9*bjJ zBRkWC?)CajhR1-*@JfXSV@f;%DY@%j@_JFspgiD?<>&2Z=Zqw0RB*=+R9Q!Cj^ijW z@;GHm&L}{xN60A}V$49eYp$Y>Qw&dJ8#oJO?-_<@u+Q}HR_?YX784Q~bmazbp{uEG zou<3LuhuU3n1f{f`)HY_)%d!-MG#})DlX(N*Gmk&cgamBGrl+i_2F!nK_P-yd5C4rEJlxaAPMmeB~oK-4yk8Wb4G`(+Exi~Mv{of8}rxB|#}V6!Z@ z^C{dJK8o0g0~v}jU$VOFAs-y1?>colJ0d4E z$DQ+3gugve5SZ9v_D(p#c6v!n8pEV#ZAFcS{b#9^Td&~G-$L9QkDsNQeISM(;`{4T zK$wG8kebzc{Y9CIG!gz&saBR*nk*lbBWnr*I2hs_CR<({{OX505+fyq1!dyrJMR9b z({N6W2hUlw5-~O1q@`V2_{g@Z#w=>;;thIwbUj!kMPlN3@9iU^&2`Zoy2?Rn zxU2w$8m*a3b~N6%014bnur!X#9|}!1?l*P~PdSb|)rYYuy{L<_vC$!_wJuZGaP7pH zC7F)^IM<*ybXpX*@y8k+(sm+d31ygfwMqN{Qi@1mthS%~7b(bVBezh&O8Gtisx?T8 zZ(k`zWkI^nXvFZ({uoN1CSND=Y{G}3%+8)uzq{M+tQ>b8=iLFhJ>cn)z;ALsR=Yow7|QYy&LYi|g0@d$DC#B2rG9Y0pZXg= zBkt|RxG%CBU{pL5BAEN72JKYtIsVjE~D13e2x)x zr-w()J#bK@186q*&0!X=c%XLQM{j2x4Tb$34(QoIGCkq?fB*mpf%cc?HHwFTBMYPTewF&d>fP6B-15|583~+iCLOJ!s~_u18HMHiQ);f&pGuI(aqQX4 zUV;gyKxwiVISiM^l^F_Rh1LYb+12K(arnX!!X;O5ppS<8){Mf#n7$z#2JLEyR>S-( zhe8ps2npYV_^zu1Z~x;UdB@&f4PJrZkf*N1fLu^!AqG>oLRNEH+Rr+zTdwtcOmf zn%uycB9K&<%_-igTEPoP6IlfIbjQ2I0&?9UACoPuLOoe}|8 z0eVl=SD%%=PfwQGbiipes$4F4`+lT*L7melVg`A7YS|N(IgUOceo$6f`>in(z*x}4 z`=H8=`dz?(7ewxWnJJ4|5GJaln4~C&3kWt!vimHR}{9DbQL~ zuJ5^0H*d)M?+u>9l0j)%4Hw(1akz&EbHk-8Lf!C#x>rMLh8azcO50L1_B|erv2Ufh z`Cx6ZpByL!@)ii(680zXD-YK}>y`ShRnM~0ha`0_nH7MhKBw7io|Umh1$2H`%(RWY zYV{(2Fr^532w+fwQ zY;QG@9w&-^QHsD|GF845F?B1ePpv=&HsFQ6WiTu zl2%s85}gQ=)0gK{9O5t_Rwsd!n7{x40{|S|0Dwev?5Ta{#p!TlB>x0U@N{8UgY zFwgZ)1Go8)2P2HHx&A8`1IdTVlADx&l9*>UL?->hgMH((HuUI6ophI+L*F^j00X?j z4ZlOn^T@@X%C9QR60GN|Pw4445jYOzd${(-mHQQ zuU(F8)mt_~`RH#j{yz5R@3%K4D6a>ZaVv9uh#Qn(&~6xv667msY+TO1X|b2=p}RjT zOnd%p2UZ^NAGTH=O2T%#E42U}d9U0yvh5np4KWh=UdiyI&R-RIpD$^hOB{{50P}Xp zuoQP<=+-b^{rC84+u+}iEfHiND@5f7YrqX8=F0ir|KA~69BxKjZ6yLij?DZy2T)yf zl(&{Y0wb!zxkTe8QjsX8YOykjM#=d`{*dPQ)h`4l{(I{|wdRg4JEq+f1|xrJS@v|r!}YMn z$D@sz%b!>9Q{E&=qRi_c8-k@12oh4S^4cbp{0=-sK;*SUB+}mwHY{7wo2ZdGkoc6J z_)ORANYG^0+*4_Hh4o}$&|=i&eoNvXng*(K)P~6UEdT{j$^hr5^!e;bS$Ja^z>6&c34gU2EF{5*C_#ggrI1PP2kICQzrfH*_IcNDRjckr*%1n7O#6u zhjey-{yYrWaVuNoj!H!s@xG0lb54zWP;auhH=2Sk9xJ$&ef|8zxR_$J(Q`DOUycGF zR?2ik?)W1!Y3BUNT$awzT&X6eTo-$%pQbkNjWJP2W|JB+G@?V^g@8DoFE%ih^;Gr1 z{Zz!dS2|nVKqWEjp>dBQD#F@}52b6##pCKv1FtxW7)3xfSR#K+{&(ut)it*@1Hpn& zj6icF)M^M>HLLv_XzJ>7B?+Q>rjZX??Qt}KjD8L@jKeoG%AdlRcfNWFuC5^l!Fnl(QO(wTuV;d1F;6fmt8C@WYj!gml>sL z85S7oGK7?w&dpfS+sm^(p5s4yc+%z%1z9B@=NImNU`itiJrHk#CLQV>#vLqHA}AcP zYN*VQeP^!aoZvevimmH_BH6@5u2c;tDBbZjf3<@PF~pbSMUHcR?r!wEHkPQz)EsXM6-XJNZ` z8ohIg{y)0!XvC=Mj!+V>D_tjUsiyU~>`@;o$_rg*aI||yGXxijf7{7=*jFmaSU+`c zy5-%KnwY1C|JlsL3CFdh;YY|!DEHA-cysAx45BI3eSTc&^yH2g(BTB`(2NwpIdvD~D^9lTo#>sYvI`ifm zgeO-rXitk0edFf(dJCg~?8yiKoRiZp-3;JY!jS2!(Er+Bs9GG{o;ZKWIE1vs?<+Fm zpY8;xLs$C~(qQ>9lt_E@461P$=DM*Z?JFQ}f3v@;ni>3G!HHP{bh)j=3veGpZ_&>M zvAXf67)Fw$b9nO)si3s zPA-tCo&ClVG{r|*iczUnmIiTqbX_m4TPF<;g(l;_QSfpnnxM}%Z$>hA#PeE#$g?;F z;tV9~&|a_N7)vZI?|7O|2@x2E#eb8RBO98nb(})vlXgX=L`mvv#l@|R^zC}fzE(w0 zide5x(TT#Ffb+zA15l-iKA2NuLch%+1@3+oTKapk#*MZeFN0!hKf!J_iq-ZyE<`I; z+mF4;i@Cs0KUI4fxM!fLmM!JrQumHtPU>5Q-ijP#c%|X=Y*+L{BORWi7su@u%*MqJ z)fMmX?)U>8%8LZWLgk{EW^BfRqVa@>$#CQs|B3~s&dm5U*R{oW6UCSjhU*3&ei3!a zaG^t5d9H6}r19@pWS`(NoEgsMemcM7^>o_zvZ=T_l52)KE8`#H{%i#>g$=!=y`-#3 ze0)lNWs_2-%-ci-f=8G1TM6=RGFS^>Fc&;<2v(fpx7;l8h0f=P zXubcx1s}AqX_gNH0;vWLm{OwvI@(Q{kPEkL?g7n`6o9=)632Of2n0Q#KDD;LGC3kY zU;93&OExB|Pkhack;crNRbVhHaOTTFxWOAxaJJ+vLw!u>D(H7CgE=_y1s&qA*3k>_ z$X)MV?V=rAzyi%=l0`(q-?4d!lhHM^bUd=7g$|U1a;sfhZ(_i)vZF~0xAKXJmeK-E z!L(B-TqN^a3gNk>xOd*)3oKj@V88$X66v1GJV>6Yi4#*Le-wp%rMBO;*UHDa#iI|8 z1+UN;na>WGGOKn7Xhap0cyG#?y>sVhMUik*v)^(()%V>5VPfo0D$+k85&(7`5 zn3SUC{_lN9%Du-$Mx%Oov%r;RVGR4Vn})!Z@P%zgk(Wa65t{HuAw5sIhSMbSh}DA9 z3UpLUjI!wI`>AhLV)*PgB(z7G?!MuxCnz(n$go3z%Rr%Tym$hXK}VcjFsg!D;@v#T zG|{i1uH|vuMRyhG2&9J!-h$wdcdRpq(!t__`4~iqaz};#K*O6X@C{7z0009300RNs z@Ql0Dic$C;F-I+}x^J<9(*_j8Gm}m=KrTeC?vN;b zNu~4EBAbhNpTEm-*K2dkP-I#|`TIdF=p<&1+!|E`#=-L$Dum;03iF5c4$ySaz|W;q z^BNbP+f@8Q&Bp#oKvupWB^W^Ba=AHyqCJ{A?g94*Zw5u42^vWEp;`bD&|{_r02)r& z7F+7^6|zt&hPpZINWvyhZYzsFdTeN3m~2WhUJC#N$J1LxuJGeW6Uj1nFuOqLQm?BN z$q$y#YoFX;$arB@7+2;+#{t2+>|wn?gI&0MyolWu&LNkYPlp8^-}~}DEI(fOt)bDZ ztp-EHU#lhZ2f~Sy#PGL?GJ;Rvl&c3VKmu&k4}m)(UE+SjtKmG1Jh6*-G2iFu8X`xD zDxk$*so~WJ|Bi);!_qq!Y}Ig?sCQX=yQ*Au&+yk)q+?7fl!=31xXB-6s+-~B7`JDI zt&Nq=rDQ-{0ol?z3JbCxj>ZQzn=tx$~u(OFXM*2UUu64*rDk%ius|)zSGRah6g{(&&iu2 z5h%UViO`BbLh&#A*X@Y2(>fpLsS$;qVzg;=-)-wNOem7--5ai>jJ8vQy!#|A+?|Ll zgqX|BNgPe_IbpK)T5UvXcS*Sc!<3A32S$wN#hJ{CL+4)w|C zP8y1fu&4U;h*(5mvwdz2k*Mfj`%q!|bEwr9#9SAexTm6jdM57gTxXMWk|i8Ekn*U4 zf$^RrCCCv2KeR!s zDIAaBp$APuU_=*F_a!zHLa4KdP&!|L6f^?8@JX?J{nD#OGqoRhTQ0840)78F zJQ#S6utu5uDS=oa;aZ#vIlb|+#iiLqO5d=*sD7fF>*^)hGkupA{Pt-6B>TGA~Z#n$2EyCo4rz}DW zi-qapl;00zjoU;CEeA@XjQPncNe8no_C@>aYXoAl+L z$`v`XpNDjeUt=HiNfRs?2~82}K|Y{sXYVzPYC}D(1mjb2FOm#iV$Y@glnwj5R%2Wn zy%twq@?CH^A;!jEnDB4sMeC?idtWWHm%^mXK6?R3*HYg67e4?Yn`U4pJSPDa9#BzOf|JaB|5{LAjFsd7RnP@5f?X2W0*pLD^1bh z)6xf!9g))ia+NSGvG?m>M^SV2DRWP)%s6JwNV+q#vJL1|4>FnOS(%V9Hz zHvu#eOk5s>5Vpr{?(tHSe+Ztk2y~jy4v{*Bfuu(hCf^ptOwO2gs>pm@6B~PSpsx2f zl@ORyqb{?}eFl~8JvO?O31*RuAz_j_N!d`tBIDSshhwb4s7)TZJg)RbeA{k==Sr!e z#lWu;W+};Pw+a73z|$DhkS06iQ49T$O^|)i@hE-1 zjX@yn6(>lNbpY&{nt%_Ss0rAl-0wab!K6lzo2y6909raOCh!@R0w2(TN3MsUl?X@3 zaPq2WsO~y?AqQ*~i=i);wjW-#IS_dKX{4#{A(?3lO=b#7tudkl7W_ zWXt1+@b%HihQ&JzrwrF!ZKv2cNPI2#A46Wnv;O#b8{S5-?Ac5!^o8)+ zt+9I>{QU2FWQCbXLID8*@eO0?X$&bgjdRX!Dv~K(sb`Od)6j3&X9}_Sb!xFQ9*)e& zF2=0OqU0}O+Z@0=iWFOC4N>e41iPs^jL2#~rX;Te7t_p8`DtvbVNx~hWSyEJx{j&* zY7N&;^uEO2#;3~5`V^)?b7Y@D!OwQLJ#sXT?#XKs8A-BdE=X&r?W#lR!{qCMCZ0y97k}YkMj^&NE^Q3s7hBb<-ro~-8zn3^BjZoWO!;r%U{?r+J(M5EL`Xv z4)#DeBA_M8D2`?4HrwN%3`%M}b0vT{g5lQph%_B@iv0lGM(Py=KP* zK<;ulPUawj%d>VV>FdIhQuI>bBK!j9^R&aS0C%-m!9mWYEL;lPNH1%6qZ7W0g1b;K zEH=mE9QcZ5 zb=hIsvB$#SBzgVBjn6a(UuV+r+fTewwel}WithgY*}3sSZDDOW+J+6mhrQCW-@?RAkn z1~{^|PQ*gvod*0K=Nvr1%o4D^trtdWAZ{0cyE+x#tnr1(nQ(3)T1c0Os+l-GfMx;G zdg+A2)k)zPhY2;veXPn6a>giO35;OZkVblgmnb&vaD#FcFd3JXR^=9e5v@b8goIW2 zEEwDDopKeF|K|~-#gJ9>MF`QW%kE-Zs&c+~QzCObZ5P=};OkIix7>%Ik;ZToSO_?K zyd`wA=aqGcp6 zL&B+H0yAhM=@6ZB99Gs-KMXE<5P+$f-L0ez8;0hNQjmx3G>HX>jdt&x)3DN;b!wpi zZ9C8#5P{hCVR{%jYD!*SgtQ39b6xTk(93!2_5N{uZICrc9*EYf6 zb$LfYPz~1zPiKE8$8<86v1ZGFU=}7%MIRMrBTtANL35RM+kkPS4U za=uXL4u#9nwdSqqVlg9s!|(*{(XxDN8mOeUtR;fYlz;#%Z)f6jlKC*m|p6<~)fcetQR%QxOY(y#GcH-{;qLP#`FYs-s zpXbrN64cWQp{6F6{;fu8R=$6*UH_ju&VeEwAMK9lVP32~jK|@Wj%Zh+%!tHtkiZ1t zJ6#y8)+?HNHFW58XiSYWCEf{5;Ao49+<|z~=^p`I-@h`y3Z=S;V8;Z~&s!IVVbQxh z-b9MPCeFLq994!DwX7(IfBI@^xgcoSysd00sQyOxMQ z54q^v|qXWUqq5gphog+f=lWo^tI)p?xMpsj{(LD=-}$_7tA~y z&XV5~+OHNQ$qPVuxvk=NhVU#Dh{pSPl4jdapz<)`+Mbx~*u~L6h8;c zSEH~xydccXh7-rX;fAl392N5C)Kau7I>-*?!(PCk`$oJUVjkrRQ&hGwJzU^H7j;*>pWPiyQL7zn>cUD2?#s=D z3=1n8ud-EApq{&$_tvd-V)cIuzvXW9)3y14a$Hm*-HD)`Jn1qFu0C+-7c*?gQp0)W zZ%%StZcxx`IFOxMJrwQdh?`ikYAzA~h_hH|fm0AMD^Y)!t2WE78<4W1I4*1(L?Y2x z>^2CLX>2iMbb}z*4X|hg_tTvGwrXK41kO!iuR^>gIemjhq44XHzL!}(jEPuSv0ta2 zbk@fbgm_}kUoVBuWg&g9THz(?#t&<4O2if?T>H$W+k{5+)8w9;z# zVc{Df0OjDgEB?-A(HfL@{?72tOMn0X2-|K_Nq?&%r|Nb-S+xU*bzG;Sd3AW8Wg%`3 zp+H8?n@;t`zRl0dDLG`#?s@Dp&q;OM7#0zIh|>*(xHmXyzM><*W|Q~^@5%e5)K>!m zAo0mvmC&zQcX(M*on~)+hxrq;IjQ@jqE#(of?~D$Q$7`(%Rz(eyH7G(_ko$10j)92_F7k!b06ii22a;#j@&UoQ zdH1sis(3Q}#rY8FW1o!1WeWo-`sM}#000931sR0uITXq)7F1Ko_-yUiq zn31LTGtinE*-Cl~+&C<_#9GxJY4vyEYb64}XpYz&n@0#$#NlyK5LATWyAHjKoIXCL z?+}q8cE|-f!tyh*`KCSiY(}%2a)~S@FaYMnUI%ZVzRJDMeUoFweP-d7;I~`qYFMS$ zg2D=6X?Ha&PFmD|qh9`9|;<^Q3ip9(zJK%5s;9DhJuBT$`XG^p93(cH8;Z?G% zN8(!BOcxYhu&3QYEDwS1E2UqVlN-Wt>G_V8=OK!w_%148**uH!>}t@o^Lp4wbH4VJ zZ>K8 zxSg~eBCXlnfp|LHWD(jFeC~Q3`K!U&XM(z}&|L2m>QWysfRBb8V$DMw3YomS!^uF9wJaJU&UEbe`RCGfy&ehsn~2 z>`KyxeTKlwKc4LpZVBAtE8A+aJXhGAB^MD+b*LSJ;5&FdMIM+?mj-ClVblq0On5P#9>mC7 zA)Z*>_5D}=Ho+wgA7Rxx$LwO^ls29s|4N;7ACXfoO@M*30g3KvtK`GD0wlF6CkI^? zxw?UO7w-YjYo$1&&(z$fD?NQ?5J?o2!^5X^S4xowa68CNP+j7prrZKX{HOstYH};D z|8lSBbI?oq_!*LwV~_T06tzZ@bJ9kc)5ZtN!DEv|yKEt}ZFptK1oLc=M~T|_o{r)H z3x`g+=b3Mav5tH{&q?epw+6ApdR>2mft3FzRx10ww);%u`$@As2kycl$%o;i$kV9m zqW7?7{1UHMq!`p@UMK*C;7?!9<7w2{&A%(4!T}2xzMiU3UVS^c6gqpsbmBN74@D5S z3#SnY_W2>Y#dB<})sZ!rSg)Ujtz}cgP?*?ok{v3SNy^LgJjeM2zU^lh&GA^8{ina$ zT)anHLkoJMEQA)@2wk14<>6((mS2R)wec&!&{Sghjf-$p+FyBTJ9(>B;km{Ld&8jR z@S4$^>xeGWOqv^G%WpxD7NNyJn;{xpF`2B@CL<&OQOm$4Z^nS5|6rgH%Me-Iq=tGR zfz)zbo~DINUb0=@eEsG26ZX+@dJ%^_|9woL$l3X$uP@Qz;!j&64Q00}ipl@QxfQ;O zGrOa;$|~mDN#M`k(e0MmqY@CMMIKyP6Qlk0n_ zVn7Yv>dvxPU}Sj{$At*oYEZ0a-vyv`X6BeKkEE%pW@ z6*@b3=mtYM$C$_xGsBCoNCy|ZInlO84ez{qT)yl2v`aKv=n0|cz}~b>2kG{)lFJ{V z+%@wh@$YgPjM^GlUoD)X@-j=R(yCByoTF}78*SIS^Se70o%iA1G?}iI#y5J+Wp~C7 z91lFc=or&YcXkglQMYntx=n~#7a0o5_U1{qEUOYn!0zYY(uTHaZ8PGDmu(tc%FTot z&C@c;wdW?dEs9vOd!4Ox^Ut;y1z7hP9_(Lyrx02~fjB;~>utQ|l#3gug_J@}-w14l zhIU`fPC9EOnK68+a6Kl$mJzE`XGVh%t)?tRqB0lDKcr;PTWkv4+e~)X=D|NfocBp ztB0_V+UoW5?(-kY>{D-i`z&EYl&||hZ&2H*b5c66locqE`)Rv2G5rR|y;)Z6rll)_ zo~GRKq04qejQ#t$doHDwX=HBmT{D4O5)Mc+cRj*dk`U>V@s9&yL6Z1+Hr%`QE|+Y) zxHU$KNbJtR@8?PwMg^lR{u2#r;a8A%3*vNvgl70faWD(pVH_G37Wl+5EtCbU6*J8b z^_0J1orUW*#ngj0o$d^SNU*WllFC7uK>&&x^E*a$t7W;!l1q|ipqEcXl96F+0->Y{ z+#SV`fp%k0Kx`|2S(vo^wi+cjliSQ{FQ6ri>Bn!YZ;Du$ak^VEfQ$)* z7dYez-bn`Sv!z|*$-1A@jS8`(TKIKI+s;wN6-3+ycJY8N0gf^-l`ehWUUZVAQhpu z-dDe8Y&&W>YCG%!6Zy6U{GFCZOv5K1*_gJ=CKeUh8*e0hxr7i&1tWptgoVU?1zc2H z*ZvuXZlsYe0qK^I0cns<2|*+jq+5XjlrHHKkOo1)KtQCCkOlz>>5v9dP(c1?MiIUD zzVGXOzwds3e)Ai4ti9H=*WTyZ>+G{qm_J5hPU4cse=`qO70iRm(&&cz=k#5?piSMiby zyiEqn^v?WxYe8@D$$J*8i@o4=G48O67}`ztRGM`0zORVBp_=2CAYj7f5ytST*C1kN z=KOc?S==wH_7=ss?@^^{OGcWzh&~V-?vxB-2}bPt*;ciB)oc!q^L&J2>IC?z$e^Z~ zzJh1I9a+X#)ZZS8zCtRn^kUd2$dO{W@WOUY#wLa$%2*t(4l5#YQ$y2@d&#KmEf>JK?FYv#VDtOP3sj^DdZFMG{lPEMk8e?Q@yO*5`Cs zd<+SxhU=vQX~NGrUeU8pPc2Z8#(e>R-+NVO0}waieB6L z^?Siu$n;e4C&gO+wK=;Fea(W0x9_M)w!F59dYeHjSU9@lzDXvlWT-x(L3^8h}vm;+C=Z_!|Z4(Z{VeY~mj~C3%H^iWNaJFZ;gL_0rTjY=J7Rk=K#T zq93LoJHxT0XI*4&SKqwJyg63g*ri}UJ4%;#PS({qT#f~Tv+Fn0>3W8Pd8*s~@k4cV zjQ$rc7RC4r{gDNAkz;SAb#7qJopJjN{-)bw z=fJl;J#RFWw@ZsvI;wd-Ja<)~he83FVgcWS`z0?!%6M#2Z1nY#944mjjuchvD22S| zWa4~?a)_~agZwGM#E8$)6hA# z%|f-yEXuP*f}V+Cv%b`Rc3*YN^^4GHb6s-`TZQ-Kt!o5?1f2^#yc=;GLRj=PzQB!? zZ$J##vN?2=(p7X5)x7Sh_IOtTP64D(1E0tcN>I{Pp$&);i`}03Ld6_70%JwG!b16 zQm)>Tql_9|O)@Lk9f>;~2lqp$!n8t^Zu?E@1+7)ST3fVDTK>u(piud2d_I+#fvH(Hcmoj zh)Zch1ZK(V>CW01+4OH)QGaT z3+0om#Rf`lD)R!I+EZ=_J_2y*s1D7o8#_l@N?lp32I&1y$;~Tm&6zJo;WS1Vk;{H= zZfe%w2jU<@n@tQf6e z(&F``r;p9|XVjf?va@pQ#~4GqJ=8pSQWmtBryP^Nl++ucT#-!gV>4?h=1!u!ki5m;TTxvlcV<$A! z;Lg(w#(A;RUpw*B)u8XjuI^Z|kH!p4797;#gvnu|h_)v>WwP6Jd~guG_0Awi^erBG z(8rV-_Qjmer|zD3RT1Zl@_h8|FgjNCLOhPhPY1pDFp0hu`#OaZFDmRIX;9S4Q%ge% zJmQh}w&l>n9^Z^$Qh%1RddQiqShF{Gp05~g7Vc+Xvn67TEx50VZsg!v#Tl$dQCEi{^7>k&uGGprk$CX*~f)^f~?jqKh-F-F}Pl($}jy%T(Ar85OmQd2=%RC29=Qo|X8G1XuJq zsj6|o%wz2 zSwi0y_D)lWiD}_DnOSRwIe2<=2WHWPyXa~&@#B3un}qfF7F`-v-}O0uO(xz#7ni5R z;_{D*K3v{@^4xdD>8_n)c||jP|6190Hmm1g2kdsf^jTGp1j8M@m~(04v4)$cQ(4dU zq}_FvIeWdP)W&b}-j+9WGy`-|Vd7n4W)oMk{D+F%M!8d^uPga>Jt2CISRoe@IY-i& zP#GfLe@I={n_`<+yR&nZmYEd%rMs#ds92PD?Pt^<(vY4rVPV#(;WRqyj7js-ADV@u z{>B7buCQ!(&n!p~HRtC2n{#dFyAStWxVT#m+1H-o2Ubg5vq+XG-o9V%){5C)cwl>o z*{Fnd89D%dX`RVEwbS9utv=N6#*;gIDm8+%c2;v0ue&fcdeW<3Ka))Pv|P(bT;I>l z(#YOu5wo=a8mgY5NpsT-Z>cDk&jlC!&WKgo$QcgY2+%Iv^Hm@ZV zw-;}gNSj>KwK8j~eEcFbFb~`EQtAFIXL99^JH|k8VM?vdDz~GzM8U-ceaf=FEh~HV6%WaH{Ky(da_T@u6d>;eE>aRWMMrue+RKd z__)bJ_pdyDx6o%!;%l_Hf9(>~UvxK@CfMl`PR^Tq>xUnnoYOjU;|(8CiLBy^*??g| zv(BFX+mW!TrI|5%_AV~TZf%=$>aJGh;a|iVi3Gwdy=3O}Y+L$MSb884T+eO8+$tTCR8kp``d)P!q4e48~KY3ATZSxX)`SG-bdXdEt~G3hgK#l5^f=8o?XInQ|l z!FO-W8KfCLd=Sl)hAtgkRW8T=)bP$qq1#f>*dgut0fVGpAD7g;fuMv3v#qFCm$mSW zlerj^o~4GK4~lKhozQ#M(RHYO%5kGG0H}RNl@#{{_E>4O z9~T}sL>Qoq{+vm~Hf%TvZCxaL>S)PBY*QdEC0%H80G+|AUz6CsU!@|q{)N`*44-#w zW+oAhX9`x@-*%)Mc*(yCw3_ax`nU{DoI8rlzxSb!_G}z+qHRyFj8z>CVRf{*s2g2Z z_1*{LRzhLOq1O@Jmdy|!dU&w3)4~#Q>-m}kEmw?f7e^an_s5MTS>3N=!y4zM*cyXs zTclr$GLDNBKWE=sLK85_kU3QvbKP!1UGz>?B5i^*&jX)VbtPR{d8ZQn)@bL1%5qK6 zW(TgeU7d;3o^;qtk@CI;mV)UZo>D6)R$>X=eb2`7yYp~ejE;Y)Q_#V>i9p#W?xUyz87v!@H7*i5`-i>7Oj7}6tUy(*)$@0jl!S!4qGMbp(BS~dD%9hKj&DKL`dZ@l)t=Ixb3 z&3D>B2%tCMx>e>Q_~H%a#-3&Z6X`yk&_$a9?G8!5jDd?fX0J!%(S^d#%c2Kp(^ph0 z;XLwlB3wrwC2NXLVrO&N&xHd{ty4QJBRxCjezVu~uT2~p={^&@Ud?6sJf2rzp!+F# z_qlTbZo=TJCm&{^qt0o=kgp!ovyT0447>VQ@a|T5YXGuMj_RRL(-gzu?$eWeOAt|8 zox2w!GUIE492VLV8agJnt5(IXA9Vy2rSK0>E`$$NUL_}JQBwkD1-zwXDGAm|a>&#p z0g%#wQ0WZ9XrjyD1H(dql^)`$0X|2_p-|+2K?aM;s zH3jOfK2~}u5&umb@s9Z!0DuTc1_gJ>BV=g_05!%02->Dj)tUhShMCzZ7z|NyCe|!w z-x|~OxT#1SH$cdsfw~}p!`cR586e8V_mQFyK7d)49x12@7Ca~k=piFA1M?6rT5hwK&|pd<65&Tt(6X=c+xFb6qz zE#`eY;rAAxVia)Y0V+TU_CFwyTd|7PKY{^}5qKqJW&|nA6MY&Dq#5yb%Mj=EEKCJrH{YSkpWu&0wTx&#vQpWs1X;M4E2arDkjTgpn2@1+mR|eSO3H zn_|!-nCAchxCJ6FRRjkUoLK;xcK1~nfHC-e3IQZ#h;|%xNA@X*#1_&P(wDSZ044|+ z&%W(@8TvQ1*q(p|z)6F@fYEy_{Hab_YYK+QiSah4`W_cU0RlzPeg|m3>$`nnMmVQ9 zS;LsRApi*o-MI)raLwzD>X9uZZh{8LMeN3*;P8Lb4dP4`fmjEz;OxPHZE(ya;?UWj zw&GWsAzR>t z0^-YZ9^6IPixqI3g#D!ipx)9215je`vfq<_i<7&n(|Q&DUGS>K1B41%1?cTg0E&Ia zb~b#QjjZV7&EWQrun}CIruEwT7fOkukErlSBr}WxBHFqG8Umy4;!KN+ySCV2*f1AYvex$U%KNJR-W+jWReDplA!_pK;qhKn zO2JK?t`0n>VTQ=*-f&sHQ?74`yG5zSWF#Rw)J7YUUXHNSMm&1OoXP&yuSbLM_;mWr zQR#G(pC3JNNDwx6iy8|EyI-bVa_cEwUw}#xyOY=hTO*6R(GoEeqwvhN=qQ#M66k_XW=jjrT$l zJe&<}OTb@O&zr9s6iHQ58&FB7mRH8;URxqKs0yI;Y};HNOird=7nzBXVG=N*z>QxU z^wP9E^v`w}t+Z>^>o(w6_r9Gp$BA-q-OMHneYZ#096!WxoRqf@;x>F~vpT3BR{3>( z*4l}9jUwZ9;eyuNXYb)>994QCarUEk8%d~~2a05NaCf4rkDx~dM%M-(Cg~dS5Rvk2 z-4~IjueNS8r#8x1vNOLqPD`nqU`ywu!nDbesrq(PE?tZI)YnBJX)f>i%N<{rcbBb2 zmde?Mti}ezK0ZYulqJ_wLZ=X<7^S3{K!0bk-N%vXg}XK3B>Kj<_W@zt%4B?R@rW|8`IrqgMAI@PQ@J(0Le&%3Qw_%=CTl=EFaEUy3Dmm1V@;qIrx zOC66l^-o7vl6}H@>~e@QHfmK%)X@Lj_RKB4*ozmIN3x3e9VAAJK4q)(UFXB-pDwa% zCd>8ZaIyCZ_m7b)bm`l9a4Sq}^~??HU9Iw4Z5iLj^PJWa6OWRnc&~P)+ zZ~>fu%NM)huvzx%sTbiAB*Qa$Qmp;xXW4`l9SbMP8w8qFEcLghl-JVy7j9J>ZLO6&v`izDy8j#-sx$pac3OW&C|UKVa|=`IQ0CzTjQLqA*+ZW1AlJ45EzgrU%TjrJ-n(KFnt zh!{od!hvNw=Nic!!u=$Y9?y_D*Qm(Mv~uF)1BV<8%%#n0>ejT1dy57R+Z{t~0vn4_ zX;^j)y4X$ns;l}hdf0H)?^dq9dLnoBgFLR{U=tR0Gz@J+^z*v()6T=^ZX70k-sfu9N6ne?Yz4y` zDo6OY5fj3D}r5qRpSWboV8@+t@Pxnw;6ngSU?7QWvYvOP=qjsoN8qabt_T=$A%# zz9b#B9si+dQ7?z^k)yQrhQ59g<_NEx*ZF&RK!cEo+0F0-YF_rZXF|(FIVtu;?)fTe zsoGLObs-65(s7l< z#+$eTb~CHo z@#-AR_A0Z;#S!$>yq|UXDU($YGd90L8$dFd&p?%=vDXA6tov}wOi|!oSt`uLSjFfz zj8`B=Adtga)*z)6GPv++GoyBBtXC`KFq^MQJWGJfx1u@n$b%rJ=;KzF9ganz_b_$g zu;&*gdgY7nnICIOC)2NAc~1b7>d8FI@L_g8#YQ>?W7=M>Q}>XOS)(D|nLKbb zgAm9tQ_R;ghBs}EQ_&CJ|8kTpf7M3zv_qcStvR$t)?j}ErjimGIap1RGadux*$d0` z007iUXE2mDXCjxpN#r}mt?%m}V)1R&Fhk@Zvfy$|7^B^dVbuJs7828J$b2G5{07Sm zYGMH0vgHLJ4|cQ~^+!?3Wx;l0@> z4(t@|+x@&xbi`l)@IJ;+c67%Dlh*8xL({HPiKwK|~|$7cl&+W8CNHk5gbYJ^u_K+XSG? zVC)IG36N|etI&;afwwwTmjLZCK7y5|`RrcQn|o(9-a%Tn?wjUWstjFjW>UF^nQ-Kx zL#kTj#SDjD(JVeziuD#mcMn8&;~3qqfPNr5NhHF*H-`KG3AVuoy$=P*2#*#2P?Liq z+7{emmzw8x8>hKe{<1?h5WwaCPI`s)vIeQtf!f@1Zrr9{c}2X-R#`#LjUby+uSqJ5 z!ec!&eIUSm5MbnQ1N>q7PYINsGA=NXPnrsU;=hahf^0;$80%$Y&A^*L>yG(VK9)yM zy_?`kCIlTDZ}(Y>A5isih95)$822qU%6Tux@*b8F^b}+TGRe^X%6q%p&YSe?Eia}7TzYU5Z8UB-kAJ)MHNu&>`PEjj?%F$HpScV-_ z3|m{H63n8kb$XV}&CVvdC)AS?KfckCWI{hbG{q*c<9#`Yn2~_sWqs{JW#LsE6VGvG zr%N{*oYS7-zGXdD1R5yv2hnCgGB|L54=vavS?9QYzs7M2ypcZ@!;5ZR2BgAKPyq5W zpyqoOB>=Gk7<7(aKI#gmpdegb^kLzS>AcJ9F-M5i+J2y|NaDzO9s`b+iD7A{NRxp_ zDycz;ku-Rs7}5nItd>qatMm*7WfTnbA$}*7zYOosj{A*tj+jQU_tq zmg=Z%K*IO1_KJ_-ATL3aBu{0)tq=iuX_YDLdgw0i*7``CEzTsrh_b)+6K7t}iK(ks z&QY$O7}y8T=*XXHJT74(xArhMtGXMU9>mqRb-QX=D=z zV1!J8zvAj&t+|6yX*(WdOhM!+v*cAfmqR9z-2xnz8r!b_PLbT|6ly*LMLpSH?-{MsG$&a%k>S`k3wuKrNtC38i$j_|E!B zOOuF+R0+utQ!NbpM!Lu$z~w!G{C%(}V*p7Qq7>rry$6YqJ@9}BYqp;anm0<{(a&qc#6s;c~X$fFlVcHiqxYiEaE_sMR1rw zTv>Gf(ybFH00s?+#SO&L+5cOl`!|7rFeUGv`(lNr!LnS#yZh7hajgdp`+$a5|0%=z ztSY-CkA-^+Y8cK-dIG0ET{(ESX97F!JnB6VKpG@N9QQu~fFDyNVH*e<=>Zlj_^}=+ zFiZ%hAriN80JKyMe8uk-czCzJWGZ#R%m7R?h!FfKLlwK%B2&iWcI<0DjW&9sWcrHj zJ)T?9PMmNoHhuCtk6pkoi8)b9xCz3G0^xD~CwNc*9ZHXAcuMhKz=Pg_0T*Gsz->4> zCLn5tkcB3XqAH*O8gOhnGrZumj!$3BsjC{e;S077{!NY``u9bn6iknA$jrG;N{nM_G2{_1J`v?G=_< zqK5K!nVa#i4{ATk4rfz|Ims~_>Xzj#xbN19{YkSMuD4IXh z7W7L2mtGdQnZbJ`yglRiQ%|hmf~zayvQ>%r1ut^UPNaUx{#|lCt*esWInpus>P@Ke zy=qqHU)6p_tV}K-fRf(^@NcIiVJ`ev15jwT5|5_Cr4V4G`=kb<^xf>L?9b!$OGp2$ zo&P8q6~7-flj5gG+M9J^7DE>_>kY|J#r?<3-g7F=B8+CTuG4q4mH<$Jm=o)bplg6! z&^qUTvi>tgGJWGl^enLTu}gS-{K18Wg`Tpn5Yv3|5-a`pDxUaJZWQgrzL6>5B7ojR zJ$NDio|SN9T>HJ3%NAWY{x&OYW`lF6^+K96aQX{V0I%HH=kMXK{B&<&PMv6XY5;M@ zfH+nE6VBh|N(cnN83B$TFyX?1Cjj2wm&F|gx&Y3HUKQMu!wM8viFx51Z|CSGM%6mS zUSNq#8F`?cV8Q?|O(0l0^jkhaM7^!kG? zDzXll`5qaiGhKw=>j_doD2vh=I;*NmKM^)g;ZZ9Z|4(!Ym~eb=QI1@QRIcKy(i2x; z^kE={FeUD6YY6iGdGu#vE{bVO%muT0P8zTP{C1>C<@yKDqoaPyrZ1oXTB1 zjYXJDt!HN1`nKo;9#81Q5po{wkBu?n<+v2aC4@H=#l^n(Hi`8pr|6^m`Bl62NPAB7 z^1iUGy}FTH(PlN}rAc_{ZF`}c4_o!e{KO;;jF>`#^=*v}{}Q~VHSUlTOkj|m_H8B@ zM<_GaomAl3WSwMwIGj!cS?Ey@@%&yJ06!7KC_zPRCtxXJ6LP^8T&ftF6XEEEh^ssFL>t5eJ_$1}`32Jt z7=MxYPn7xQ1SS}Hr~s$*>pb53Tkls@bi*987aRem`V$F%uv35oXutCp`#4ThCo+G5 z;rP=1ohl`o&|h?sX@VvlAsHsPIzO`|&Nqku9nJsJdQc~JjvsbWz^6cfCuo!N z7n}c5!QV%r&w4?mygi-Pgm*F)IJ||P+7A0}osJi@4HA%v>Myo&?S8t&`y-H4c?g9n zvi&(Q1~^6oiCYCTP;5vhfW11%S^vF;+r}dXKy3!@n81zP$h{ibyBI56V)!Aq)e7Y} z!jqp+06tn#MS~%|RJ^ypH$mA2F@=Me?0&)Y!_v=*e;+{ZW=B8<0YDheOz#ZyXuJ(j zWg%_!f_FkPFw9*Aa@^I!G3gHyp{4}%Yy%DW{BC4~B=f=)vw}1v-_ZcGh;{p>bgF4# z7m^RZ5#sL$kPvkjcD7?>$KLwUhv#A)i|#`3e_0O@If3STr8BH>jep_5lEr%&aU(yq zBY6Nr=0q70|Cmj%l{JV&XO!l@QQ)0;w-Z^EyHIMt7Y^y`Vw8kYr01a^C@|@I3Won2 z7iK+hjvgV3dQ&T3FN;Ix-0du(08_NNr4;xKFIKivMdxZ-Kc*~Sp^Ttuq~ES(t>jsWJI`#w#2ZF9^|ZM5lK)SZl~*p?-K~RDWW>1r8u@5pI-R`i1N$ z&z;Ep@DL(6L}VP`kmKnV0k%K(B$gUA0O}^{B{MTc(bh~nB}xyDE}}ZetGk$x5WI~~ zMoZ`8nEsL*g5!CX+HfPFzfLL}crCMcq6DDW1QCJJ;f>B;5dE<77m5Ewb;kgaO+iQ; zagSt8X^N#w1?!KrgcF_uIC?9mX~dq!!xcpOlq@lmdltqQ=6(11aBqz!W6V20$VJ`it9*_uXK` z35~nz*c1gfw&~&kNQVUPu^bdQ-3#If2606EXB>Zn-M|A(JfL^MHQows6}(n(na(8@ zotk|@-t?$jhQcSullxxVx-h`M_|vS%Mub;>(y0z@Yu}jd8?{0IH>177+kRnAAt&Ac z!<>QYgAfL#Gdwu$er7l9!R@x6+Hf9+pQ8DQ($jK*ciNzv!-Pc)a4-+i-77%+|Nhc3 zF>@raf>GTX;eQ8AUcJ1DJFy3?^C5TVwaYQeI*pWsI0SUuEjMh!pmXxCx;sTL+8Ut$ z`l(6YyRied-0DD6%y6dQrK;zs3f^>1v8Un$#P|n92he-ba4z_&So35OhO6xvCTT$5 zFO$-7Xdf^JNY8UY3c9jRKuFR9$P;0{o!5V6xWA4gCXwyH5hNl+roIJh-#cVnK@Ww2 zJNZBx)R9y*(Po*`45bq(=EX+YqygB%h$WXWDP8dVtkUM5Dk?!|BBwsL5m>0`Puzb7XJ;s!9m-hpzVm?w*4FQMo{>D2%)Q( z0E7~tqRpvd!b4MlHlmMTwRqP&J2>HQTvZR)GbM3@0FK8c7Xb$3IKPtr4Ca5%aSuLD zMBwJ~1`HB56ZR$80SSwqCr}UpJ^DN8RL@sgFeBvOC06jZ27IJ?bRzTv_c#t zo^RN=v`nRHOlE@y(L; zh$p0cNFv6u^dpAKOm?*$i~2nc4D*Gf#xu_~q0=v>1+Lybx@3m776;pOqPS^e=u&MZYm>Id0;?DH0ZRiRe zhC_2@s+!$W9xGBiKOo<^bN3#+Qc6AQQ%ahC3&z%pf*mnKhGlAcah23Hic3?GW1Z$t zZp;;oII(VHL`;ysoxQp>VVW2cU;TzGIrbUG?S~K5NY*Q9Oq5G1Kf8&>K;2p_Jj*?Ce>-_F+7k4$2G`hfUN`PqPjb?%ain&>M#|Z1wajOPV zfWWwo!#`Z8IsMITJbJQXo}vQuKr6k&jq30lFp`~htxA%0HaPT?n6XVqO{P^u z4kXvsM!9kYC!TR8eAaD|{elv2Dtwr7-uSLa)y-|b_eKF!H!aM}>w<4X(Je#r4$<@r zFF(gIGa{;yIybvrnz2&*I==5wHUazV%`-7P%KNpiG@xz%GHNY!t*R!Uwaw24)ng1k zeZ+Wg7h8wzx_kkRRLu>x^qa-!78z(RF{LOfAKAeD^daaUEqUKPqm`n_W$d~TVaB#p z3=>og3oEwf7fOVmWmD2QjXiGgWynSV0{(Vf&e!F0(V`#Qgn43VP)mn)KDYC}e`Kt; zIcHGiZ54`XI73v-6;V~u|7?dt$Jo6_dyqFla^B*Cblp&?zKtk*V%vDNb54EYhttXS z=4M0}YNyGXHgQLN*=N|JlBE+^N_hRVZk+eXCMp-zp=uww%wup7dv0RLR`ofzR`KiV zn0`|BBYHV{gFJ7Hhq_eGpHXGHji?n#B46MwV>~9e#fwAHjZ@cSedez#<h50lX@m0%db$s##kk<{OK$A5Xtte zn&|t$bbv5w<9wfr>-!bAwT!l-<}1l;@LZIyJuq0&Fe`8H*zjhQ_PQ;~+M|B|a-rLU zLW#^6Cg7LjT|5;mmx^(B*h^ZGrj*COg}cP)%`>xf@{pI0!e@LXlUs~z2&$X|&R=mS zFXw!Jv6hvzVewAz$i_U$cS}tU1!1hRpRD!qjV+N@wx9sv#u;ks( z8Tea7Lwqui3kDo7(~d;61Q}tp@@yQspLgSYus*?vsh0ep9yK`aONymRcw-R1K*EJt z%89@?*Mi8_UWZRU={MqyRl z@oFeR{cc@6Zva&Z^ERD{J|S@guBF33d9IyAJK2EHgUFA5Iw7xAg*)_u5`k z`*+NK$)wUeO_B8c*Ju-Aue07&jk^SvdO?av&k%{`AUnLot+U5XD!F}qXbD!Abvxd>@WW+QC+qvnLscd?x1;qL` zXY#&=6hy0i5ZY&$WMQx!4-t5Rwb$gU(#Ev-TDC6YJO(*|Dn5$@8Z946#lkp2=e^aC zybB`5VQ$xHahl4eYYviF`tB{nTaDB*nz)~qHS9N*H-1`~u=u`(m$-6>LR1mn#?!#W zvt|xOGeln3mwoC)nCKzBL>rJ|zeELK%Rlx9y5408i?X`c`6Xi01H3SVAW8^P{iQEf zxA4;_3$rl`bO2Hqgv#gWDE}I;LRR?6z->+IF}-m}1`w|mx0!!cV7FG)_WAPW=|Ic; z7KL4(sn41TgOK>HWC>5|Bnf75)IFS1o7o_^gL^Y%GoBkej|rz9T@h^>F9i2cC%t&< zdT@|({SSZ;L~s`d$%y_np8YT4Yjpqxyd{c&CkHs=7pTZ;0BD>@D=Rd0l=zO2ZopvV zy-zY^X{CVifV@lhX8SwaM-YJfAhqNN7yv^RL<2_GA-^Bp{_jTDSfG6{)D7YMN26=B zD`v-irr-lD27wm;u}~MecaSc|r}fs4UM7iTh0B1L7XY}0oRbcpss0pjbs}a$0*K^q z1-}0>(3^%Ickwuwg}j9@6lOyF8PNx~0kP;8?i`vp#6frl@sC(9II2B*keKmAtQ5k= z`!sTVO&$BBHF8G>Jiiw5YY_a`yVto9h=wQ{$!PXjh!n)^r?U>YW`F?1qDH182)Ro-<1Xi|tT3A2yuTAU{1w74P`U5RsL4Wl zMFB#S33(oTE&gN= zw+R7kyKmN@FTf5xgJdNCN@%}8{P!;YxfY8JswR5e4P*tXBS2@+A?T{fkn)NQ_rSw9 zZ$Ol6$+HDDnBIASvz1Cr-G|tYjPXmf#bGage>*VOTnnf_87UNERvSi}zMW zJOOlKK*1q^b1;aTATNz6RHDxB8T^@TZT|Fmo5sY?v;Ylvc&f_fYxUgn=qto8P&jSA zI(Ep{qxn6f&W0yfWUfqJKSJfb?U@9)*?$`}q;@|<7Ye~H{601RJc<91#*%{}AQLLq ze+N&9T5rinq0wSSm?mca*xs2Y2q3`AD%dWxwAR~4$xqVfdEkVm5^I2siB{NJ&mj9X z?17l0U3|ruV(ZQuivb%V7{&=FNiu*~gQQbaf9w;SaNwWa{9lwv^LHqJ2mYhAusw_0 z63&%ERzsl?0KK6TS&t2Fl|h81GqRD?_G>)nbiMZ{9d|EJA#eaY@@mF~DXW&*tNNrL1 zTz>h(({Yz}=ebLHdLdmSP?C$HQ@1{PaWRRSGI-r2u1-GP<@)9&U^z|{GDhpQ4v%NNMRz)$1G*$AsqP$)xv01?N|Lb=#h6@0ugecIgNLr?c%@8=%<) z(55hqfk~e%3|!zk(xXI|fa*SF zLM3r)?`Agnb?LqP=PVk>6qt(c9HT@Y0|Os!7X3cY|4%~26tOp#0X8ewr7K~b2MZez zlFBkWdg9SmWN*Mp0Vx7qb`z3O{40BdHUC>L#J(&F_l1X@P1o~woD!a{(PU@+P!0_M z&3l37|Cb2(&!CZEB&8T9eT+vw+@s?K#t+*-DT1EBEz{y(8TQXQ{_B$4ro6-bsNID3 z$ib&k1P0cOI)kga2ODo5&9QExd`$Twc>)G+2?PT!qs70^m49dd7O#-8ZX19Q0d#K7 z=aUTP6jSLh&{e5mWJW&ouLrDOT_QhpOsJu4O5qq}#0`xks!{t?r_5s>`O)^sjb1dB z1c%^4Q5K29q|*jTC%_@otcHTYUvrEe%L~Mw2VyVz&&%jeJ; z#uM;XJ?sy+>W;2D$NmH_KIUc^GRH@P_(wS2glPwL|Lq4}<9HK05lpv4nl)m@&Cps2 z5jupUryOTkl@_8+0mU~c>6aXEqrp=e{7nY^x#~Ub!lX={+)8&t9q$eKaSNZS$+Ya( zO`xg3C_1{X{POJAxb)BOfwIrxZnoI-W1jkBy-j9AkNehK6}xKSEfAZ}X4Ryhe2ysl z>_RKVwnECEleekB(r0T1e+j4@Vgye{60heeZqdY?A7R2i@z#!i|IaiIQa!#sOe)?d0!U~ zcv!x}eN2pxtngzzTL{(yA2Pk*{AH0lo^8is{{sU5#@Nu+;lK|O_13#TMI6YZf$pH~ ze~dAabd8@?@K#@TA+h4*z7xU(_8Q!8c=7x6_%}W92dMQziQP{$3=*M$@ zD8M=eA}I%v{07;5AC%u9>f>Rfd5$MIh4>1S*Hgi`k;>WTn$P3Tebte0oxD$851~n= zNt?TDy!)i*MzzLzL* zp+q!rUWRx?SR$j@M%6P!_;c+sNJ3r^B*@M$(f=uSmXAZxIJWkEdO#ACvTVQkNmm+V zXB6p-X1l*&XFl*4){hzWcXm=q$qlHXZ)4Cig>j$5Mc$GhKt-S)K1`UCcv~dQQAIF! zq*iEpEOsUd)ynyO>P-~+-cvUokA!t5PUVp6$<#zB^j2^@@4+$he}Y%h#^H)dMiF5c zBn|T|vW1r24Wjlw)mBKnM^lzv#F+Rh?YWTnhioswHaeqHhyjH%q{>`6RHKo)`eiji zSO?xqmHlK5Cc@?PAhYSU4d@{IlMuH_kq_ceesmA{^&=o9cmB$EzeUNwzc{%7kVgiw zg#nm~2p>X{X?*zslt$proKH(Uoq21(Z2bFtV!6vZq1gfVGCM{CFi3TZS?VJ{ZW0V| zCM?&tec(ii1|j}F1^#_Xek6N*nBjX2eSas#hx&`w**3GYe6?(g zyadbq$AG}&cGDmvkd-@C|NpUa=Rd}cNLGgUkYt5!lJ^^&^x6TuVt_kfuYaEle_TVq zm-r(qud9W%4UdDC0nTb#p12AfbGG2MRbgp6 zH&}3%77itS)E5%>g1_UvI}K4N{W+ZZ;OdTKZnTVtuWa_ne-I9GqYT`r?p*!9<=~c$ z59PhC*@>1<`eP{aGO^R8eO|r2PAirG|L#BXa?p8!(y867{}k{3WmMdUr|*wVR78nh z{S61oI!M15(iv|e{zSjM$50Vt=Yu>02BzwJ5e?Pz34-ZQ@wZl7Cq!h?M*@F3i2^BC zC4k#x080zp)G^pWc}GB3{luhVqe#;&IV`r*K*AKF4QlnnFz*kMsn?E!V^IYzzx(HT za87YWFXv0I-nM!CnlCFVB>g&?F72m-G4Wo@E8rtok~!Rq1eS!r-yk?-1LSA;fA@qfwmT+(QV$5ZHl@5ejoCuKuVr3;X}Ma7 zuHs+~-1BbH6DWFrPLaMy{B_X$3x@`|>Gj9?_+sl?;c8;MjXMAixKtrJjDk3Dngq#s zhx>oc!aEszNEYskbv0Zw@XC)SxHWyT&sLrf@SZ|qL!JxlIes>|hkO=cw1EGJp77~p^;SJX2vhHw?1?bS$O;r5Z3Vg4 z705M(KO}Db3j-6;QwhNl!V6&s2iM%skBv|RP+CV~@oR4yIzr4;sT2kx6pT0rG<~nP z8ySv_e^P$G0J^ zAHa?E{K_owp&_QsiD9}PXWz_hJ~Oa7`ZkKWdW)j;!syqt4A;(H<}{Oyg}{z6gQp#k zdlKuv^4kAm0Gybh007GX8)}2Jp&*gk#$vOJ)mBV)-CI`;?WaV#+;di5otfE1fo+xO zO~SG;p&oJJPyBm5r|FL&a+rY-LF!%qeV+UK)cY3!@GINMvtz`TQqO%fwzoUuYHIA8`~0p9RWvEJ{BI1Z#NQqb>1kqmHRP3 zn9BZ%0eg5*T;ryZMFYuY2FX~K1YTntNz)F&s0fW?l#=wIw-P~&oc}cU^2ZLj2;3EY zq@5KrBw34&nqXC{`($R^p{e(@zzm*6m*8cmPW8u4;Gy_$!@B7tJGt`#C9}ox!FrY8WnP??xI?gKMX}wS*^yUkGbtAn#ci(mOkxXmo+Nm2?N8?K) z^6|)Y)hRBmD115-9sd&Jt^NVUY26D3-YpZKxr_qur-oz^If*|mnR$N4<$ieBt(0>f zT?%}K_4q>;ZR?_~%#k0_>dHiq2vKqsuZpUd-WB$gQf{r6_%yeX^VO9OYxT{iOWxjD zaS{o}1eaNe@1MgyJv`Hft;{}DbBl9L{-vvIq(UW)WZTu#=C|oy^BCROeO>y2=K1++ z7%j}v0}?>d4+lFx*Mf0VVA3( z8QQz3?PQ@i^cd+Fh~%e^cDksWc$rRC-c6-b4bfzWmfwe;-n+2%!B^uv)86LHv!Ye} zl829ErQIjCnd@E_=q(EOU@cDQn(4{)g};#}6r`A|F!HZMPx8f#&C+0>Ec_HS_R_yH z1Z}U6lEPb^^vh@HSK$B>MPt~|gF;!>^D9fmHV=Zc8?;^ zzem#~%><{~nwD}(-!LOO!ZV;dXe=ahmXLJu2| zKfjx=5MF?9*jB2TjPjKmtz7}tStOp0+_N%#5H)1%yx9w1V0SASSe3?9F{>~bPI&Hu zeFq}-AZRs=^MzVJ!TE)zxIGzVW@7C=Fd0lAI4~lmAf5g29SX4XLHoRws-a&fr9qCQ#&^t&~KsrhjkPZS4 zML-1v1f&mO0coNXkq*+EsDL!7ilCq}uJjJQx2lfDzG<8kCw_btduGYNxV7rWrd`p-@ig<(?y42Lt8?L8Y+5==Ve=TgcGO=*9(ZuUQmp0-_SCu z$((q3SCIx+v9r_c%E4G!NLo`=pcj_jEj6L{_p2YW2{x_>b1se1)9;cA9b^Yx^;0iR#D z+;eoHE4moV)7f{;sI7h<#`#X|*x8zBU9w2qt|l9i>|c`R7w#X2w0#-w-R?TQ+$z2Ok!2H?4|YVko~b59d;&8R;G4o%W;F zUFiVl0T`7@ z%YCdBQW49kx*1`Y5%HLMIX#u1i+}i5mDTARfx#t<)_&4`&*^GkR?O~sx*=^BQmJDmKQQ#kN+Ixsp-a3w z>4slKf>|le3;&c{*HhDT{O8Tbf$B45Ej1BJ@(}&%BHO0@1|J%83`G@6;#v`9#|9kj z<(X81$Do&h1<(1?_a`r5=z}4r;GSJk)Gf=xQ&>`hygQA4eiAx(wdK@A>L;<5#*rZ0Cv=`J7Z?#SOVL7EQYcG z=`g71S!MDK6GP?_OZC`@H0MUyCWEdAsco{KyWp3{bLnqjIpw}RvEo>LBYaSVDJ%va z1f7s5Hv8lvnS4E8`-b^tX9iY#0=B&QQE824%v(4*{Tc`Yg)tHYh+)# zjvqLmxy>|IB$dz}w4yEQ9Le1XxrRn_90Y~hvhMI_Bm5uu3E!6>BZ$jdn-u}r*C~-J z^7}dfkcD8J+NQpANwwm&^>Gh~%e%0ks{DwYyjj)vLi^3CR)=Z!-PTaID079&u$>2| zNk29s(C|QgErC}kH{tO2ZSueGCj8b2&5@Y}1B_chNZ__Ghb8~6n;`o-Pj0e-->lQG z^M_V8g;EIkUfSWmX0HF@C}^Z0KcAsKs*m#=GA`*hxXkEV3vfIFWeacpzP7?li8WN7JHq#6fU;~iPKq$k0sa7t=XK@xE=h+siy7QqOS!(MQWJGN@fA06WOfxIn1bId4WULh0}zMqCkwnLIA3sz21!tY zdQdJrxR`cJ=YQ*Hyd?Ry1sQ-J0GNTQfdQE5p!@EEz)ikRznb-kNca;6z1h7%4Ohl# z7&Hbl+vnrv((e86#QQdC$M>%zTk_}gX)~=ZxLvgD3CAYA6E(FCDeI-Vce~=HYMtruJ`b2j&gIxBN8_n3UAVGjEYiGF8NG z>_Ytty$|B}2uA|Te`5Jzhil>XKjd&M$p(E#9gP6@oGA;ll7$4l)y(cki!LV7f2#IJ zWc;1+TzFnTDPG8TqoNo*!#+9^pzCDq% z!Ga$-^2mpUKycrq#5hEd`rvqtLX2BrJ&r;CtdIC%)0GEv@z5FC7cpJ_L`vX5IJmDI z6@VIZN8-7p&fZS zQL&kG5Ouf8MRc{Y&wzjeKtO%}E}#Ff8U^Dv6#^|A2b?eg{2)l&e~m(aVRH!WSHUo7 z87Mgll>GY?`RxG&TiWk@{>!kBJ?zX3Iv>Ua5Xo&2$!{>-k=)-P>+i!p_^B?12mpf} zaE}=NoW=O+!NY3+_shJ*PBVofM-WPB5Nr_VO%SKs|CW(|*wg2aC4xUJK>20p2b0+4N{`rE=f!Kh>VZ3s ziBt?X*eLRCeR7%m?%AMKcn)QfT!v@j-TmKlZuEKSrsiKO7-Qo(tJ|-Eph~>6sE!q> zoy!xs&yg94(h)cu1%bekWCVXEU0>FTF6KY-_*=F$hB@mzFd_@-=(Ch&CfhF#2liSt zdS6h(<0SVeq@)okGpLL)e5d_c%HI=VB-LJybpW(_pl0X&O9Oj2oj*eBhmb_=xWRKi z1lrnnQgSpH#OdCwb6+Mi=d&X6E`BLdB3jw@NM1P8DZ`uNQ%kFF7s=(-vm^1H@#nQq z7V^~SSdZ>M-bzmja~2@oXWOe6&8}a*mzJShIdT)y&0Q-)8sF!$KpE;Pn*$`E7GEY!+G${J_sqgo=_d7rTcM_iM#z7gJ&=(*S&~~8x z4R-r|7Cx$8;183z`Za9_J??^rrI{Igz3NzuEbREC2FzkmHngIeN zt!1?PIRX|!&%|a_GOl8+A`<{BT>;^`*+#6qh>=VR-6;v5On_y1VkMLldfIS=Ag(Mz zuSy+hlc2@m=<28<&}~A`7oFRWLD&?7;HnsV#Mjv1Y2N^_14pv)|CyUFSXO`Nvpe-i zwhVYj*ZgQxoAeb7#|IYv$-g2Kl^Z08c_jCb$nGOOHpjq)*n#Da^^nO!xA^T&AFuqDvhp$7grPa)#@$fQQ*2cF)hTzrbrNqa?kZEt}EE~(#_GU z?TTJmJibqzlLLiozp-wc&b^h7Q$55lg~@;OQH!e}8mMkFSo$0YlJ{rM`@bY*DLXS} z0NWD6=BCroN4ul>xZ?(G&N+)Xmpe8J9Epp)>rV%`)gx`O0v=IGXqpgBFb10}-*2$p(PRJ54P$2QClBivT#Yog$G4}f5O}AaY7Q-4 zO<^{PdDSR6Q$g4!L1YSU4&e3$`=BkX@~f(Vd<57+K$DoSCKEsh>I)5f#PtX23?&d$z<4b1sUL!{7m!CpN$ur-YLCixYtrzE$^V*n^CIwr%mZ&Pm5 z7oLHza!C9-v1yYFrb^D)Qx?pp^|5a^3kR-sb@jctfw!_b$WH{&>tbNKsp?UUoxh>0 zaaW$9^SK>q;2|x$IFEI;5Xor2U@GLy6;Iz4CovW!VUN}GeD9Goa-T-eJ&!j???U!Z z0kKJ2U%L|g$6%>JOIYS-O8W<-`(MYGooP2C$d)tGqp`EetnNQS3Na;htvl|VdrQvN zDik4WaV?Ym_(TMP<(LkxF=Xh`*Rd+_7*P-)XbH>yKE;8YTMqipVAYHLPzf+d2I>yx z^kW$6ItYQ8F+F@;%3xcANkyA~`h*|gc=G<)PM)PhRY8H_2Uz(pP@@rlkgha{=pu-S z|8I~kEa9&#f}fh=_ofO1jB+#q4Gr%*Su;kB0?sg6@Tk~?Z|e_PZ9(zDp!mPTez25L z2dU$~mi&Jb4~AnIY5PUS;1GLyS6zI5!3;dJ28T`&ogNoe`~*<`-{QPey#!ZLYm;FB zjm-}*(33Y1aJ=bVw#13!cmu}3||xrAV%=nL>&DxhcRrYEFUiMV?a z(E=H77ypWh>=TFy9H5Z>ndSc5E*KuJ5a!FvDB(~kwEgoH26aAA+z3!NQwTw!YeQJ; zM<=r4(VIFAlmOW55SU~U-`fbCnI_gDp_8nkqWi4XtdCp~cG!&ly-y<^J{I7XzO3gs zKAHD9#XxUK5|G*4MWBml4#EZY;hAz+zu2Fc7?Ov;(JmNDZ^@4jvYX7HQqY}a3wH(+ z{j8p^w{$RDBO`U(lS_=;?^D>7r+c7q9HvnqG%MJT90^&^_I!P(P9|xM8qbr7)8996 zPCNb7%W8WDh`a^4LnT)%DpUIb=A*nB7!Z*5Q4)agnNd_3IKP+O{CVx+u|mLeITzf$ zlkUNx_#Odmdi_;0Y4+l2pD}uGMM4)9K-my6U2m111J!OIp|;9XzS!ghakIqcn~cf1 zT4@Q;hrrhaEYWWzW0X8?bPd$j2>{S^qq6+pyQ8nAL~W-*x-=RKKvOtU4m{8PstZUr zOvJ!K8gYO0eJ)h~_R-HU+ZslZNcQL_&12N^!S|LEiPixrp-NKu&d%8U5Z!sF>7LKm zF)AM9_(u1i(0!fnw+NC3N+9}B<1u)q8dn%Jbp-V{l&*vN1^=suz>@CB*J!YbCv9@` zS0rEYe*KS0>?H3{xVD&jQHnX`0C)#wiz&c5=KDj}%) zw5)J&vn#=&(&Nc}g^xdFOO{auzLom=y49LGM&5hALjR**Qxhm92>jh+;FxR**bowy z+&OebQkKmGN{8WHTfo7n|Mv`oI}C=$LP9&X=(3Hy>7-V-0yGZy#LU~>gl~# zOQA|3-jexk_f5>@1W9k4hc=*tMORG`ag@*8}Nxr$E0$PBPWSLFhDB#c-SeqDGZxMFt@z#}jtloB8} z-Jk&gWE$H50DAl4bAeuTIIXTC@Dafj-uTE0ChK0o$nE>(lpjHqQRXmSy13bcZ8tIQ z>Nt0&GR%ir`6`b0o^PR3k)Wt46-1}=+r0&<|B?bvX4$S0KMNEmf00Z5iVO80YUBcb zLG)qc&@}_Vde-KTpD-c;i-VQ8?9elG-AqpQW(#enJ#i~G+Y8rvFWk0#l5ywDqS0|Z zNOy@yGdd9|3RxzI%^*sP=Y%Op=P05vf{%nK(HeM8k*Q^6%{ zjJjKFG*V!HblM?*yXi{gGs595Yo;^LY5W*l@4d6orv^rEPcF`fFkGlq#6`~yfi~0x z2=5XI?`KX&*U-1@QML8c2Nrd78=p0bo%z#GU`$?d?q7q(J?A5)De-{_8!>*-H?8kN zmA_o8ftKK)<6(nM7RU!7^!>qBR9}_%v)G?d3?Iqhhtnx#RsSRqhef+$zU~-88~1xK z zBPUJ~toy4e!!iS+yaA&8ZBG4ms@>T_fKg^W>rUC&_d?BPDgpo-vyLKPFgL)?{2eBM z!wuArEcgh-l;Jr!gcKD_)0BH#RpT%W)3GJd?rA6*o(hsH#?B=$+uoW%pprqX0o1lP zNK=A8l=qXKeo*0$@9Sg0#rTMQ@ir8;bDE!=wgW!p9Dx`TRRp&(AfJ(J1^{r_WEL$2 z%n@b`Xxs{NrwiAEDU~w`iI7H8R6JvQu8y_9gsIJx z5L*vC(@ZT_(fm#o>hJqrRNpZ|)1vKX@C<> zGqfcEh`TcIIdSnJgg)b6R>J<_(fyhXc1(QFOWCg_;Ouczc1c+b7Chnmc=rhWzXHQf zt9D-wXva@Av~kNl3Fhzadjk z;H7Z_lE=8^QJ%ui_c`__5yUMcSn|{#6z+8MhSGdCZNk!y(HO^#r+;iF-f=I9QdLv> zHQ`!sgH+HKvkRj0)vQcUY2+zj#w+510SZGBA2C7#e z2E=ryTB2e!*d_}CI-g=DW8zg|585J&{3t&qv%Y2Ih zMx6GkZrC=k@p4=j09{=Y)<4}SW2AP6hO7dY=n zL`}&Liia73!m~i(Ka(H9e^drA{gVp*K*Xs1#l{>+=#v02vWOKm65@~IiP_+!K4MV> z4{9`RAZDQzY%yQWp!(2!Y@?yHitzqHIKUAi)D?=HPyB%M+kpT8VAT9aFhMy`l)yvw&Q#httK!;lsPmWzGqn)5 z^fA%St2JEF_FGeD1Sz_pxwovL6b3pmU_!_es4>ugJIDX`c^QC10HENTZhL_s0N}Cl z0`(%G2w@f#*)--IM2*o z;-cr=+3sg3%!BEWvfwDoj~G!N8`B$#VhT4sM!`j|eQl)2{n1u>+10HD;nD08ZOji; z-L>x+BDqV*Uk6uXg6H&AGy2hzlo`t^;^8u2w zpH4}NXP(%JlA1YWU+r=%IDYu3pjV*yA(5G2>6Cz+>)qma`t^$l{OT8}Lhi37ti}o3 z5D)dFm?H*iScS*2?8+AF`W{OqD-3Xkl9%_9-d2ejP#;YhI3HZcI;GBxcOdX#b~j&A zhjSxYui?TPcGZ*0!lF{mkJ}#2l2l=1FH){*`R>hBW!P1e%-;u&C)L|B2aer*%as%% zVPe=o9@&C_L!yj6JiUS-W&Fyi=8OK-HhxjawXSX)$P7+_Eu@7fKm~B+zgW%DLNedq z_s%ksb5LsfkizR&n{`jVy~1mr+)P|2!6qY*cBQftZ!{CHeTm=F*OfkGFkX9n1^4p3 zro<~Zwl5gGj$!%C?~4oz2728f}aw3_OBr%oH$w{w}+=qS# z_ZJsO;{z~o$F>knA-3l4c+eMLJ;Wc%NuL1GFJJSCen8R_!F4uPRlcHh2tO_U)Fw^D z#K%LDOJT+3P#GL;NM3%Dq-Yc@S`nQMmV{CDy;L9xbz=x}BDm!&(!b=Ve*Q0@{UG+} z*Br#nUjRNsKu*>P{R|ogTqiw|#^e2DF#1DQ=5~Hkq}H=4zZs~nCE`RFrP^(p1!=c$ zwGoTV{7X?8G^fr}bn_jmS8u-}exJ}YjB4xcr z3^q+iBpxjl4^>+F&b!s5vMQI-JQi>WG8B}D_#|UbtsCIqD}mhUQUL(;$!DNZ>-m4# z*@7+)^EaUQ2@q(^n+OhvezS7OVY*Gjoa!FI4oiSq(3gm94IT;_aY}&Dz+|A*^oi`C z1LE8nnM=<>BEbYTcmGdQEC zdn0*TeC3!Hjv?i%(T`vp^s23=aAd%rs1R@D;bS4hAK74?{yL_D{c#Wsgtm1#gadq2 z2#Cl~HVd?)1Od z5~MYXv8cp8dOLsQD`G0;u&(#MRw(fB{y4(rdiw{^@puO67kqXR|BML1!hIi;18ERE z^XV4mZA^4m!24Yt?*Llvb0YUm9Zlv(UOW|(zF#a((>r!yNku$zfH!m#$4(@lK5?b{ zVw{A%Kn{Dx`Ai@U0YExIV4yjQ_y@!X$^D}yjvjU`#h-(4aRA4ACMuNPTFc_)$+A1pXX)p_v_kj4B=Kgx<{-1FS>i9(s z#W0&dbd&W%FICdfars$8Q$M-8cB>dV7|-hsDiHvb5rmZp!qWLa^HlV~lJd8F z_j0iiKrxJW^inMq&qzaDM1pm@=oaZ6@jK!&B)Gdfa{P0ixJ~@`wm!zCnTKfN1z>|_ z1I$B9dZv43z1kaK?j*-~3ah@CNrM~U4hb}n;e zJ6Zm5&0%0Pv{C4`>43CJ$`B*dbqmJk6(T_b{Eml$>Vg^N4DC`J^f5`>*}4b-eIhZ~ z;1YkPp}&6azB=pR!DS#AC>iY3F#`rgfWYPm8-*e{2|z$1h>&6iLm=OcUOXX)Pr#JT zBjq5bz@W9{NMTKa{6quTSV1ZYz487sNt>gJG}}bd7h1Ot3t5eKaO`3!0CE7THWq~S zGZ+1-E{;T_!oQn^zsruih`U1j?2j(ewvA}QIB9kjU|ADti)69~aFqyMs24^mNh$Qk*0On!>8YFseIB)&J12i|N0zzG`=RUtg{#@(-z+aNXm#Ec?=%^`MrSS^Zw-4p?- zrwL)arW)WNo7v3DDzKG_5K*8;#U)4pbN*I$pxu`R#`)tG+*2Xj#<`41Fpnb_=Ch!- zc!}c1d40lkRGimWK&LcfQH5d7b}0Og8u^6smg&u^w*vsLEr_)Rj?5(ZfkZ)~VP^*H z*&j3ikv~*c2YrJ9`W*ll3*jEma5I%!F7W)|ip>BC$e~mP2&gm&6PFugC`h<($s!ek zC|-#jZF0V*{gxA^4>L0~r@GH?LP2tDJmo=fZLUJh+|uPm9O^=xy9V>0H0Y6KVUOJ3 zJ?N2Do`46|Blvg}qunPz&jmgs2w%;w@!#jtEx^&3=?z(!m0A%d7PCX3C-A_j#r&V? z>hG~AG$im_L`u^T2QElW5tp$|0QMGu9yHJYed7ANM2b{N;UE_u@K1T! zpv|>Eh}jFM53P$689YZ4ubz0z3R%ZUrA{&|$k3`>!%8hrnEbbGB6z z;rLbLTUGlv%igT)q{VQzrztA2TkOo4pL>w;TVt0Ch7t-8iw(BOG5|6UzOF+8&%E97 zl~h4z{U=g|0odw!C#OWy1C{NB-y$(wTUJrZ*h0*x3jvG)2;z$Xo-ZJ`wE6%6u>~+* zqb9;U5YRpX>XZciZp9PuG4Yf~TE*@KMIUl5KN~wu22iXbIRQqt$FrN+q(kfETL8}! zo{=a;DI6eYX8Ix?=0W_IH%tJ5gn0wvNbNG39FyQm0txzxQM6@^X)^?#^aE~5Z?d(4 zigL+`Te;rXoe;nua(d8$3!9PRp^6H^!HTM3$*Ww7 zk_Lua7%y69my6X2TEzH5^se>(0SEwnqVPBzS;GGVd86CFpUxu7Xm=zzLg|Kn82JRF zC6JoKlmOW^MTqK{XNg`Ad*(X|;DZx~FaZF;i3Ml_ahIFHG%!zGTVvod3r7YNcwy+z zU;;3u@izl2i5|?1bOi{V26VoBXZqrCVF<5=4DF5ghR2&qV2h)gs_PYsmXYg~NKA>@ z17fw6JF6NI67r#&ezR36i0Tf;eLt~+WYfVRmHdT}*AYXry0grphED6Y(l=okfG#K; zwG6)EXYTxutbT`Gt=ix<3J|sJ(_>CFgI2&moh<5Q;;+vJbu(x(A4{-7Tn813IRhkv zU!cN-6tQPVY!9WV6vV^S*TN-T!tGbbo}1!mZE~o2jV4>TRv5G?z)o6((Nx})aO9UW zb|irfX92(=i10dy@b}5|@3Q+fgBvz^Cw2r+?Uyz<$`GXtU6qU+vuV3JZNDzBaw}oo zfC-^$Z5E90{Ara30Ihbk?GXe)RucR@euuE;D<0|StET?v|1f8vdH|35!gE2oyOa^) z0H6W?#zQy5K!t!yGAsWk$3hr>Q#OEID0<$O6J}+;%jgE-}=(+Ze&cGVoC0Y|?y^pisx9iFCqEraJyJu78E|-8~UdSUzCI6h;DbcK|s3^@05~zHxP%b#e2gm&e4ATI} zrcvrP9}Bj8cL#z)cgaW5Hps^8*Dx}kP|0>HU zK_08=^C`#&1j9O@(v3T4H9|OM`!FMV`d|j&(1Qxpm-X+>dgX3g12Fv(OlpV(70KnR z)d27TEH8u!j%)zmHTdB)O{P;5F%)V_AZw@1mivEeUEt$M>vjL=PA>sW%K4;o3%@`SG%peqKu$tNoKlF;@LEHFw8FO3V%Zh&O?U-*<#K8643AN0v{%fOw zuDn57__+n_U#OX(Zm`b+s!5GBrswLPE4O+yoGBvfD%Q!+l&bRyjg@tif(->=j;V#e z)?A4qq|_jgGHn4L5nvL6Z2P&B`H$V;?GZtp2n1HmARylB`^uw>phWCt%lYb6sq7)9 zb|OUQb7>MK^~}R9lrC*s0a~eMU>NKL-&P?J96|c{g_9p(GfH=%hK^f683It%flba} zdW4?(v7evkD-Cn{s~ zGD`{FB-F9L4)TGmgusU2*_IGG6kM;I5|Sous9%e^#YX0)<0(Ju+Q%4GF0j6SUJGgG z6x-!bRu8bbpC@jJq-V;!x1L{trF(kl^PGi~`dN3_+~*8}bC*wu)06O7-FnppRt5|Z z$ps;U-Ap_G-|J+-q{^FsP#sIm5jHU3=+if9_wCXsew_BJuWd)gLXHTtjbS>$eD`^r z#5+Ct30q^rOR(AOfh`q9bbQuX5K1Hne!si>UUrPiBY8i({{Ue* z3Ij0bO}}13;xt)stbYp$yXB>b|58^KYwPV5URQgzU@=@HToRI{!!@{E#np>(I`MwEovQ#e9Asbt zcxETow;uTDB)+2_SnB0OvRN?>!K$2NOvUgewoUFgf=x>wM(z59`d?zzkcOXlcYgr4 z^nP+JH8UmQCNxH{_VGA zyJ-L!>GMSZKWdLJboZ6)Crl--;k-h?dE#nb@=EhdsRh+|o*j`0sE2v>2PcxXl%|bv zf(76@6y&jIm*FxCbRQ!oI{3Qnr05-{ExL79wJ8#$0ID z$^{^lsa&2?6>q_*75vN{l5G2fXBP@a5_c-#az~&5tVhw<9dyZ5b0iU&Fzfk2qSu3Z z2=Emt0G|hJT2pZ3fZI>6$1#h^*AyxcFmlU9?e$m(05E^kK`+F&+`yF`L)BmJ)HA?Q z7>9z}n234*W=Kiy3~*w6@GK_|JRk%Y*TGQ{V88${9DoG?klSFXL6GLd46BwDI)x7O z2JND@y((iMnF!KS1K6#SF>ot(9Dpox)_HmZumJ$Z_iGLqpO-T}&!4(5Lev?<91iXs zcMaBcQQ7oSLdDJ?X5!&nx=FmCdY|n_1;_4nV{&%7OY>rWx+Y%7D{h!=pU0ay^A>BN zHH-@^A-JqyW!}!5;wt<7N;lI8ib3`%L^p z=W$#V4IUK!?el%n4H&?HHg(yUAs?}ba&|HNg}Lk*HA&ydbOgD-09XW!0rv$}YB7Lc zr`-Urh-Oy{0ygLqC^`lwaYuCicF*t)!gnlxeSw;&05AzM&Uq-jptEO?0=RO=k78<~ zlmQN|jr;=+{zCfa4Kh9Lx|(Pw*(gvv6f)uQxF^0Q62NE0<6C;S@ zTP5>|UBW(je-aeFA<;}xTP5U(C_*wpRcOC31K9Kc+7}#I{ufC9>v~hr8_c@PenyhE zeEt9s)^C$#;h;OOQJO!pHR{eRsc7C&YiJe|`~2;Ox`~f;s3Jg=4nn#J&wR=G3++Ss zz(I|lE8}0dg;oO)QD?`PFo5as7~*h`|6x6wcfgTg4@dca6_E>%xW#(T?=WJx@GACSjg+<>0B<&)0d~1ebeD zv&)3GMSMz$I|~bX2KJf?mM2sE9f@)#Y0bI_KOU*WDz)Nks0!89EOoWi@hS zwS+v&^=sw{bfPc8mw1QK`yway+D=Vn%H>DM z2d0s9aVuW!^oanqB{3q_z13r{{`HE$?pzx=&`C@P2{=i`iY&<J-Jo42rA;K0m`Eme=?V`8O^1^12D zB2h6}wwk$tyFrK`{fk97?laEY+Z`GBO1p#llx8P!x@`IhEBC3m9uGKA%9UZ(vy9f? zd0wX>A}QNETA`KpVQ8hvSje=*<8gOkW1688?%9W7UgBY6gNXy2w+9V}GnQ7c40sKt za&R9M6RoH5)>^D9j?Yk+yc##g5A}?>B-mFVXv%1C+8@aox4Gj&@tmXJr9wx;eWNUG z{vN=53vxZrab(+YVhK z9LtaKJfjptmp-{{E#j)ERyh%-d%D}g8a?q40p7yKlP@Z59F~2rmXgnY z{*>CUjQNEv=ZIU{xh+|UX3PF(IK0H{jm~XS*^ZU( zqV)%Y^7-B;Uvzlpl6|}>ktyMG+G%4CYK!|d4h=JB<_HjqH#$gF`~@RO0f_=93tu#oX7UIo&W9e?D?fLx3iTO z4VW9KG(RowGBFa&-FZHIL#uTK=d>)xJ<@O)OM;@TF~)lmz8Xx&)9rMTI!1?kfpos7 zZB#FQrWO>_tecdQ^~-UqPUjFkOp=&?^lCfo%2;)S%zALG5e8qEXqK0R_<;nM*-grzd>Zp z1I~|0MnGJ*%@d~wSNsdo-mTk|Iv+3+IQPEGdw5Ge z?z#T*cG$~ze47efQr=JRz+)r;%1d?wi_XN8Z$sns2l&nvexkJ|NJlVPjMzwlhONWi z-ltMolWhni2Y-at>o@g&{850@T3P~6Rg=kq{ojDC{hmmgI zGrMg~)(vh)&$c~M<<|l0yOq53PU?@as8*gmy+2Lze5+vSVx7`ETYFKrNZXrRCxhkf zZ=5-W@faVnAkjMHx+FK{K^}UayTeK~SXn2J-_SmH)1gPw%I{Md;U4U~zkQ?lYi?3L z_T$;67tSVMh@Gv+Xd(=fJ2~sb%sDUq`su+jan_bZZ}~VU6-y(s(4x8fW|dy&4+qB9 zZMB&nJs67%Q@xyJDp)A;>4^j0u|2L)=U~}ozmooV*CI=}7cNnwhGNLfjn2lDny}V4 z&qfm$?=|#Zsx^K;5T;{l^Q8<^Y2TIw;(WWibmX)x_3`FK`RwO-6Q)Dtr01Tn!|n^I zIa(9pOd|LsIL)S?x=>v-Kh0+0U;IvYv^(;m`eVA{oKS-5=g*DHTfE03b2zka2D;Th zrk;r6Ajl6$eqOvZa-LE0ng5GL3ZnSU@drKl*U#7=qjK+oe%dlQ>^r!!SHLgLZ=UWl zhkWy{ypHh3-2~jus2rX`IGh&D zkB>_pFgX5j+}N`);8Xdg42VU&5=w>rE$y2@(fBDzefbm@$EcbRw$g+v|1 z%+lhN%a?bA?$vmjo=LtzR0F%?R-~?-^H0*nDi73yVhY>G%4qUQH)i>48Ho{(?_Q;k z9&>wNhflM{fmAgWbBbZh3KG*LpVZ4-8*try=Gy)6x-?VZ8{-CN&QDvRRt6&yA(B|F zZBvvVLUG;`s#o_ixQH*}ek@ zk0Z8al=mfOGoL7$kL%V~Kj1gOp(^Y4+B;94S6H5a=XXoyc7@#ie#yPEAQRiQ>fq=q z7}1U*_np*Ftw94X;bF z!zbB2ILvq!RhN9*YQx_koh&HlMl0!=K2kj64~7oTw#YcCIvNj&!I5hX>WnI9GGPNs z%G@e%_vGMAP|;!J*{!Y^%}nC+FT>{h;9o>u3@GI<#_Ee-^69CNO|`=%bJ4KW42&`MGOEj?ix=Y}^x&WRA3?H$r6gVl%yb1B zT%))I!(odhk^We{oO@5XftVRL^T7VaHIHYX0;Ri)2;Ta%3|#Pj=7=+?7WIJLS>rC^ z(FgUori<+5dj>4J?yj;tluU!+r!c2|4{_C(o|HFo#k=ZmU!E_MZjiS17!<Y_>d^d1ln;%9N%d_FI z!0@`7h7!w5v}S!n*ZwqTy$b!g{Oop0GDyMME;{#<4AofdUvMW&HSauA;~{#_zS8;3 ztyl3yS!%CI8S51ua}FaVCAY59me%lVG};&hHCicfC)O%8hOjDvJei%O+n%$;Y5td| z8zaxPIccR6Ols7fXS;oqZsaCb+lQMj4TclU>aFmOlM_r+3_wH+1yx90`jyfJx$9+A zjnfaM;^@+s%6jQP`o~5DUI@Ive>fmN>~=Xq8!3=4-?d*l%(PLl62Q#p z9+W?yAj+dPy1s)kA$8uo4ZodnpTTh6+~-Eh=y4$`Ic~z3!95(7A#PsLoicdGc_d48 zq_|GQ;0X@aFcp7I6EbbqyeScyG9uExoVNs9bH+A%R=~^z#^V0#ZOR3r+WwseIbKdq zHsVm+X~+DRW$W4$xG^VTl|2SxF!lCk`^+RtEJLw7=CMS4CZa=L2ZFD$cE+m8D6n?1 z_^EK3uRJ(r$k9s=4!!f+fA-BXI0q%y7r(sU+dSwa>Dy=4c7@HfY2=~lu6G&ds?$0X z?BX+4mPj^frtaYTFCZ464Giwd!Qu(E#uFm$-fBS(;bj%>^4N9TEznsL?7P%zOs3Mj z@FjCuBU*y=zh2Zoc}m9#|I-_buovbCw}@Q9hXNBeYad#q`hyues(RR7+pJt4xCu+X z5Tj{_qvguFePTxS<<;n+QBISSHLWvuE`M=#fM=4{il1@V7FLd!Oc>R=DVpzOY$onG z!t4Oh;#rhvvdCP$X|7Bm^6{-Vv$-jE|Kxsn-eF9#a))z*Ee*4*UUcs%$#u+2>3qLZhDr+tRM#c3RJ#lQCnpTUIwV7`D-HH4+yy zpvhtc#I*oMkX} z6<3O2)p6)M9z-njUcgOMSXUMLzKREnHfPSzVmQ8ZH?F;K_TdZCcI8;6 zS{g{KT`HxeJsG&-DLEsn#ea=3`+n^d)!jkTF0R|fHE-}rVj&F;$z{#fg| z3ytYcJT7D|`JtE}i=TPZ6tF8lT(H~}@DkMLc`MWS%4^P0LTf0{8k-}+^l5x!`!nN+ z7++iOVz#@TR$d-5W6%QnPD6y+s3zH^A?M>;iEi`_1-%x}jwk13=cG}tDE1l*N!og0 z77}7`5-m#|wkidja%H*%FD`kSc^lT!c0i?g&m+}8%a!2`4aTU%mzM3KP+|P+tRXFe zRAQ%M%Z{Ao{&oV7psOA9ma8;)xQ|&v@!00HUOjs6OhUDRso1pk;iaY6%jB{Cxhu;- z;>+dkr%t5B@$Ew?H1p5*|Fh+6$er5cpRBr z6#g%JoRsI&88w(jLGb9%hsAo+Lw2fAdnEG0KUkd$0QBE|(G@OvzvpYre(lbX{BZv5 zJ&a?i-`WzC^bY_-^8(-cF;A0w@=i4l?2ezOjt1=?Kl3Ew>lq9N8(qDJ7bz;5)(%Pe z8klhBQ$?GdOL22cFQESc4FU70-EE{kqf*09Bc|V?%IRihp%d7KYW-(!KfQ%O=YIp> zPoV`BS2KQ@aGYm@r4+5`@=GM}!=;C1FOYM((!&#+WjN1c&&Gl?rW(Ix4*3*9 z#5G~28P;YEHB-f2!0kYAzyJUP006#M*8e5PN-iC-PVW3A&4lU?BUwYlnUCjE^}nFB zLF`iVh}+Mm&|#3Rxc>c|%ly7NT{-Wt_ZNnX5^w0u;UJTIfemVT0VgdqH2SBK5qRwv z8c!D5NDKu`j=9vQ6N*9le&iejnlAH>cGxL%`f)m|Wri3A`n}$Kwj4n$1|C^ko+F0xHx)-uh(|_DZIk1*<0kze5%ylMF;5{f8{$G_e z9|!J>_s>x#`t+wt<%IK8jle7^%Shh%AnW9NL3DnvJkwl41VsumMgK0sxu#3O;YY#r zg0gq9F?WQPkmY0}2|ktL@4{afYXk0k?<9EvbNh4m!Q>sA1a(_TC;5EPUw^){hCe}l zjs$Lbe(;O`3p*f~%hakXKtF=iC z;05otag=EuhQ7YpnIB3Ji}p)}ge@?+i;ib1<(ML0VHS!wdCLh{wfy^qO}+dT^q#Zh zIef(;A1|0(T)qV;4P-cvji8TBLvuf2?vDe{~=Q;F2>I2kNjrTHuLOUd{kMezCiN-xbeAr5Jw3+OQ_m2#E#)pvDNSZni z8gPx_qEb6|H9TF%FX{o)R{Ifa1NO*Hc1rIh=1*gS!GgINIQe(M&P^zO>As-1>!_x~6P6KXe-mZI2 zg#{fihw$oKtD_JJ+5_`6id%3-=P;Nz`JURpiyh1K|=@Ve_P+zt%`(zlAY*hvirl5Ha?r(tbU zNRv<*&X=5A3yLWFz>%f@(TpCIHVqRGJq{|YmSvVXaYmshBZM?x88|ju=SH_sfw^mP zHa~j!svyP@oJN0t*wJF@Iut|vkV8#r(@@~)f6%Ea{oBeUiLeF7DYrUpm!YyfQZlE~Mo#H|uhoht4` z1VC?y#U=yb(9$2g1tB*NmnK`HIU-@4PRv(kteIUOhD6=qt|C48G=SX%!&$RM3R&_! zAP0J%86$@MFwD}@5);O4TJz3i)ks-TPrRL*M|yX_C9d$IcSomI*|7#`fAo3RS~APB zOStEmMz=_YJE*kq3q5~2b*+xdvV##=0$KSgsp^U zn0{uX`OA}oa}@T8hFB#v3)#oRbx#I9<+TVBTb+kKYqpJG1$MMs(~oH@iag$6daK-J zq72R(apMn(pOxlY;f(=`Yt;d-LlM;lsAs)O`B=&S}m4O|9U< zjqWYH!bONwBOUF$d*uz7v|APJYDOiBSDP5|7>ybpc_}7jAt0`Y% z8(A1ybs0almYr)}oO(iC8Fkjk@3;ucA>$DRP|y1okMSHbo4OK@HF>^n-LXG3j>S5@ zx_?`CQ@(W%iGT`fUqZ%9_Jo2wuMr=EzX%Cn-T(jt00093c*XZG0Lj0BWjit<4zhn! zQcSPOt!8HVp&vShAm;%R{gh!wVS}XFJUCZ9YzX6#wo#2lN|;F5wO`XXD6nW2Tty}O z<{{NX6c;<}h)({Sd|-oetF8K_@)M&fLv^aSghuPg6f?(pIxx5ih zM_YAJD+{0$}E8m=&NiWAl=d@26LtDD(&GantkaBeMd{K(NV22T7Vn zBGF%>%UiCYPmzCjsORQ+F2>erPR6}LkQ1E%gl3_*5;3H3W3wpI0@}!?g^b-VKA_KT zy~%r`uZN_*p=3t~if7p4wK7p5@yoZd4 zoNZ>`ug$rhy33L+^xoTA!begM={JkHO@INfszdPN_nEX&umv@;9TgJF+v;Nh9BG>q zQapNkNjKTEV#{Byc;d5=dI~5(i-&2Z)kC?y6$NjIDR#z&R(crUeA|C8cf;QK`gIa< zF4l<_&drR?=-?AMA{Zo+09_TW^%yw>beum6W=(+jYXhHp4PXBcvQxgA zly_^`2<)t`XH6Y<9XXviKyP*7s$0+M8^%`q4@bXv>tmDAtS=6hNdxv)g0JB62A zc((3B6Oi_oy4?|2rhotd0|7SE5gu;h@R@)B00ok~u}N91mbR;uxawtHv&1`@j+UI_ z%X%N&){-ns6W{7^hDK~Z2P>zIeyZ>KVS9+pw;|~;Vul3O@IYu$F7a5?t5iMsO{7Cn zj@rrWQXPCr=3SH@Y`eyQ)8P7mwnOUw7I>M#?)rG5i);L;r9DtMNTxZCpYIEJxev!G zUl^)qh>3!W<6=0d)k4LJ@$Uc~rx`zuXeYHD&l8;5byD0>|Cvu4S1DVx#-=i?YBcQSlkZF50*;M_SJlPeJx zB2-A>j<@=L#*-MMTnJNWeAF}c=At4*$_J@DAh0}hD=5>DHm@Sut83AN>aBOp3DA*_ zcfS#^mDPV|0OFo1dtbWX=~MichrF+p7taZVKY=_hfa;|2r)YW?25!p&5$P=07?<)P z*>JCc$zd}8Qud~f1@NnQRmBpdZhziM>GNf#-%OnkVibPBk{Y--hsK}3dC{p+R7z8P$O$`D%MdvmIM#sdN@3xBxRr<&U$t!ao5}PhaN$v znB#w14<`J6_$X-Fvl6tXZ#y9nAv_+q){_*PHt_$NkKS*TZb`Yx?=M83Lrk;9>d|D+%7@yD@ooB1C;%A>p0X;kO?co!qG@L7^*aLb52C-+Xers^zshX@ zFWr%*WZ!_?5;SJ$*$j%T6Q@1BWqK#p*g9|R-SvpqsCGs(1?Ld9F+JqAzo}geLHEao z6WxqzA;!};%eneebbZ15Pg8v!WDzU?&u!3$k*zGFIQio+7f<<(_dv2p8&2-5Jm8jLNouxjsm~ zZ!dIhuCo3@2mS``)vGOm4sKTqM4EAW`kjyhyL>#5W%fZgpng4(>G54uwUMYvy4o;M zq;d@n84MQyFaR-Nb$4K>`Rvbgm4@NInFi~FV(DYTi&^$kA!`Pwbh_>V zGIli4rtD&w3aY-{223s9L7(q+#n{JV|0k;DA}u%A{(MVBuFKgkhD^onT?J*=Bj=F0 zl(yot%tdpLDu}oVKg)@yX=;UH^Ey*r2#wVO#Xvsvee>5uq9`b*AYxhnVJOF4T#z2> zuSSc&oAWZI*n^_}&s5`7)=BSr2R(<}fDW0=kvz?shxPT#qV?bDszgjB zU#^!*@!!HIqMmSt#eGQ+eS@gHwCKS;9w1; zu&{93Rq_=vYwOtf>ZLY^HdYN}n-7CW_nqXI_QU)MMkYroSVOoAfhI`G6aqd#8yTs6 z^Zx59F29PDHZvz_XMY3zexJOeS8?Q5%WbpfCNx8MLZPO|M`#aqbDxA{~m zUs@r2pA}dVP+U}*7i}~NRQ!WH8(}TNS;zyx!tegRm7E?hbSZ_At4XywKXWu44v8kH zUt37WQ8Rkq z`ZX`7$`iR>sgiJZI6X`G9eWUs@yG2XY%P>N4Yvz%1_z5wN$yF66QAX+Ldz z8{6Y~X>1H_&1;3$sWUsL%M1G6@ zYcqWB&e0kgz8Bp&U^~wa@cGjlNj#b*hoN;t1EX3Em77AA$F}}_Hs3Z9L)a&3Ap=w7 zj1)wsr@(PtwU5x5zD5PXJOj%hgH&V-=jKuN#u-srgj>y3z(v4+|6n(xT zjIvGw@QQ|x!nDWi?37c7w7XQ3CW&EB+y7;x&zL#WGty~=9h|6m^fKo;38oNkiAVge zejhYkr119Rh5=>uoXf%Du=_rypVtYSnhY{lQ^+JDHe;i7oou_OIm7{NJhD3g4B%>M zsp^2hEid0qr7X;&BdkfdUOs-xn0qOd&Sb>NDDBaB0CfNW6}$P|uusirrP(HZi0(6j z88Up7W0m637dy){TH+PyC=ESeR017Vs&@`S^N%NXAN4TS$?@1O7PbBO<4D*ZPodJ) z1yPa;hebLEc4Hd`r}ks5gw`^9%s#mDm_15TCaoSTDI|6p|gjA*NrKU@EYH z3o-x%3V+P>gG58Zj~M-0C&G-&hAP06Yd~9M-^O5EHeMtACl>1FnfTq+>c0-o;f7se zk%Cg=_v37h#6cRUXz7P9?77L?`K4{5e26ZKEemDTw9b^?y(N`w+PdazfIc$8nUaz$ z(R{6BT|yV&F}5&eCnOdZMZNv(7bXXv$9<@}X7^w>87Oe4q6e=xqlheH=axg_oNv@L z>ry9wb!Ah)NOd#Q2hP*a;veca*F5m$Syk#HPXA#Adzu^n*VLH3FyQ0%{crkWrt-@G zF|E?|!AIuH#_hBLuu;}ky7W(N@(pK8ve-GycxVqe1&N_GQ4vnTtonGafFQD=2KS`< zamBd`iJ*f9C}|k`7=CIe85w4>pLD|X7Thl`04m@B8toHC44`=gG3RGX9B=Vg7%2HS z1}J5VmmM5oU$5KhNABf`IMdeX0xOhIYc6(YB6ZvLmMN*aYUH&G}!K`-6nm47a_04XERe3k;LKBpX#Oz z&uuOZZCyt33OY5Tl=759PiwU;VkHurX*Vnsh^2**?ElWH?;zJ`H4EVJvWyFz0Z^0db>mTZvb69>K91fyjtySek2)x4zLS*@foVK2UZ%t@y>1VXH5r}1&Ab& zrmYMH6FY9P9k|%XzhmK60009300RIt`v%)S009!7qWA(Hy9%}+d47g22<5YAW-8JQ z(#;;+-qWO->*$_7qe)`_)+f(G866%AQm2ze_p=-%KnT);tzs-dwKLaszN{|1d=2yW$vxIaMEt%^`jICD~{_G@&1hNiukmi_p=^ zj$>L*rm>|X9tb6h`(z%5L|3#D^!iauZBj<+?p=Zyb>K(5d5yh*?8zL(K{${meQJTS z<~;OYCGpzn_j}myG}2?>^Z)<@00096=wvRy01A@JlUC6P{}pudacGs?jxH=Fh0(iG zcXd7S;QbEx-;;lQu@POa#R+#n{4_w_m17xewnq_HYH3raaXR{h&+2B@UNP2YlGj*E zSPLC$AAn?-7dCTr*trKjjd?CnoEC<}wqIOFq=%3Vu(0ykG4$`VFFv`*inp><>Y>)m zoj^mepZT=X2tT=yfn}QlP)yh5kLLlo+pX5B%upKO000aQhM52WQFxsoyue)=e`~q= zdSl@D#p%jIJ)H~y5api~45DwY>R}v#w>1`RGC(EWMJa!MjffMA*00^9EACSs4#Me1 zT8StO#GuBdLQ|b!>eJ6tY|%4#{C9SuRZ8j(4U=3(JC^zR+Fa5Xj^a*)%O~+m2X>pwO|qvV1mr#=+B9VRnf&IFjM008Tzp22_tis}_> zGB-h2wW;NcPSp$jVMw!RHh*7YFbke2l>+nu`0F#R5~>hG)hOl2lMI3YWAb;*V4Up| zRJhDIl)X~r>ThL(4Zt(KJaB?;A-W|MILD@ zAOZv$(WKC9WK`x4@Z2Yj6Y|O?EujyO+L&ZD-(p?deX(-OMgVp&^dPc;02MCkv;YP} z^G3X%;ZS}zlXFF)doQ9aOLl1J^&ybMkaVly?7101lfjkIvk|XtY;e955)r$N*LEtf z8jMYHPsjkeuq;+4>SVpM!67Zmg7q@yapMjTWLhqCIUYAO@+|*bft(_1WCejA4mG3F zA;%f4H2fgwJTt++V+QfTHdJ?$QX}s54X4~9i{)`u&4Ya>G4GR*4@_L85m+;12a%AXcmDozI2I@7nw@?>pBrJaf|} z=g0v{lhQRk000932D|G36&BJiw_llnxk*YnK0F=xRaK{z;^l-2IMbf)>R;P08OlD;@;^}KUgcl8 z1lzK)9e$*Mww5~^d^o0A7$kRWDp$&W8{3?@ZdZGc ze0^S|PEb`vv|+WB2m~6(Qb;d-lTg7}rTBf5gmcFmTYl-E$M%Z0-7PeC)-H@ecEud{ zpXIj)cFqW!)py)s)J?g-Bg5>?y z+)#SX*On0x-=yQwA{foE)k>#IkwrJEJc^eHM5$+2HG)%gMWYPDbO=|i*+g= zuxT}dObw`j(4b|N^{PCtiQIlTk?qUZ8v%;=UcPjBU;qF^zCfe_qAwLxw*0FGKvY&& zAEu9|<#nCr;ni3+P-&&ch~vuF)@N|7ix=T=M3)2Wi^%YZB39#eeA-01QAod+G=D5{ ziSu_;Cb>0MyI0EKFga?dUaTRUNY?voSOwS9D)WJ`<0M%@ZUCUpt`>iw z514q?ec)QPMMp5&vhll-dOl!%x1OTzXOiKIGdC3%)bUyeCF7eE$%7}P1b_hY&(%>_ zH@EzeSC1MraMwoR?5#IyYU@?^%d6L4K>9z_z^ooK=flvL00094vH%|P00IB&>pl59 zJ!>`o%*1x-NhvN!og4jQFEH=%7 zH4X%Jscqwy8fc$Re9A6>04X%xumA<=1WgN31z(EW)u9H7ToX2pjtfgaJsd_d4|@k8 zn}UXCuj+l%w-vgzum{YXu^R22ohf7zIni~_Ax7z?FYqCdgJVgDm3-6N4vLlceg<(vBVf`0 zioAT^5A-N?BcKdRy9WS=;JG&BbS&7L$rGZ2>1e}yAw=|VQeo!{qnRrSV;TRvl)|d* zlG1puV}|GE_1ufjir_S|kPOoLgRXh3edfrKy^wqs26D)vzy3O)7QOg(kQenb_wx9^99LpBj*_++*Uw(t#}5) z#j^a;C`-HTDA;@NO`qK??#(eUC&VF$YL_FSuGDJi;$J(eeFL5+ zXyim6PK%!NmkTU@nZ_7oNlG5mGEi)34&I$VkvjDq+C3o_c<&vaxULt`I{4!e#=q{?(Zzn1e_LN2xKhB+>SHw8N zv138?rCW+*VX9_HlkLnBG6%gz)q$RnOf{!n?Y-*qEKj4CW38@%m{L#qL7fj*Qpclv zuRJYBLgbo;e9E%BXCkX?WMt+%yr1D79TXk!E)~}Q|DW4EVSb@i`h11Af_V>fdn?mO zc_WXy7X|U=({U_0@_|O4_%6b99mJ1EL~9Z1>^2v(1SpkQn9E7fRWaSfb#(gnzz9KrFAU8M~~tOHb4 zdX3sg#BkItc_($}e+WP!RWXDZLBE0J?b`?kzgU)yn<%uoisI0iDiq-uTvO?1ul{)Lo)S;^AN{x|YgfvkWx(!* z7TAX?exM-Re>0Ex2Mdu(tD_^MEiN;Vw0d;CqZfe2xkge5Sfief^sHl^B=%y%Gl?zZ z+CTT2R;(#CQpq{2FeCbD?$~#{Vmx(({bREXL+n!QGTuL)!<~|g<0K2iAL#5NbC(I* zvW791Qk$cINhS<2NFv)4*L+Cc;cgBy@}FL`_pIxaN%`iZ-2s#DY0-q#j8b7oP($m5 z1b?obk0L?gimJ0o_mug}?-`|xk~!3kmtA<8T%-RP7{z}TL+6?-1p}wV`1}X%<^23N zu{-9>x``qHu%YN}LJ@b&l8rqq!pZLN%;Kplas5eoCj3U=2SH`!n4#Div0RkzE!THa zjAe32a-VUyqsJ%Ze|X>kJ???2oj!l)QPAy`bXm#~E}9sn82e2%*o2|a4?pNtd^&v? zb0)o9$9Uk49Gqd#PRl$zyZ<9Yz|2`-4C_~WcF`ZW-a7ql_n1LT836SR6lVud;4SVb z44y4~y!*9rtdhx0w$;`HdTBxhH=8JdGeToSn)^V0Ry@g`li>m{iOdT&_#S1gDAvIj zt4`(hzhAd=CymX?a*X~>MKyp@q+rU@?s`!Q{k-zG)NY9>9x~XBTB_ zr%J+%L7#F-d@&XpONXv#Q8&*|${DW709lZ22w=yD=o*wYzw6FW%oQ6$Mc6aVm>FCd zfBjtlqo<*Nm?kfoNCiF4mBdGTPg%nk^6chbk!M~EPUqN{yFqalnGx#IXKDuZBpBlz z*t`&D4TG`cdFG)Jh~Q#%7)U%EB$ zzr?e)8ry2Yeal-TF=gxk(VV06fN+8ugRI5;J;{8%yyt$Qhkg2iyU@U!!PyrHv>Zf> ziUpYyym;KS2xcve|d$=k)6BR}vui0<|x#XOg=)#lqHQ6w4x zF(~zY(lUB#V9(K-RxoQ<{B$|TlNI1+GG~Xj;C^hi zjc;QK;gGd%Y!VwotQChS_y7&=63;jQ0Ydc%jW4)OAGQ!SBIo1#BdT+4T;ad1GMGN5rn1&;x3zOChM+mEP1M<`sWm9$J4nYa_eYSPa3(Z7 zCkj4=h2ef!&5igDkwwE+Jm=p*whWeT&H*iUSlu}`?tM6JXR z>q3M^)2l3zBF4(ac4Z!B(MFZ%`ca|irc!X-Z?b9a{`N#wKmAr-T}`Pq;f*FuGfzf` z6$m4b_8j!IBM`3K!HtaWgi}z+k6A!#zp)D_bQf3(Q{3I|7wLp_y~aX;xlH&+b{pPT z%ehyHb824+_A+%3T3EWdTmG!_o8l%iK^!wb#X!q z`LDBc4v!6Zo}l@=n{2mYnp4ovR+EBh>e_Wa*0fe?q`J4uUf*>0%d6I*cw;Wv?L~#T z0+XS8po6Y1=%!hLyH+wvdVT8LbpoX01D=ElIaTs1-{Y=8 z|4z7406~}1DKt%fPLhRYlrsF==p!5UNm)aeH zj!!OJ%5qjI7%HO1LG4+rBT=WT2m>Fhzb-&-(S_fqeaCLNgt9X;wR-sgfp`otF_ejk z_d4yjt^4R77Tlzt!LBJD5{H+;RAo^h`T6UZP^1pF8atuKUM!8GQ9a)@m>pg(mM*FP z`U86S1F!%ai71ks000mAh1>`?VLH4)ppn`0h7RoR2_??m`}>cp=lmJaw5?Q%N^OEql8>yo!FoKBBBwFP(w(2V`#Y@X_Y0eT$zNtQ zdp`GowsptGZpV|SqW@~2FktY5*}a=TS|6+tv+J!*gy9ap=wz8){UVv4^i-ucp(d+# zIuUe{x8ArxOZFn{7rW&|`pGJzj&~_eGu7u>&V$2iq;qUJf(rCr$mZ<|C;0SPz-SaDox~N7__ps>ur*6_GAIA#xBQ1ACY)wo(n|#@4P^F8f45 z$=XJCHaBS7H&@By?z)icj3uDHB&i<7eZaYu$TL5|Rm*k>&u;hVhhXiWdK2!^K1|qx z7Xj=rWZZB%4T@WcAGihhaKeaQfK>Ay;$XDjr{MS#pVoZD9(Zh_U?&Y3^g<#d<&P`k ziqNl11IY;5wZsRwCR-bYSCutAmUyY9UM7spJkWGPsn+9X;M-w-JkB{Cl1LD09gXrk zO!!;mPeX|Z)1GKsgYdpHs@15)y?&|tP^Bmw8FD%QlIc}-QA=D!Z?_;eC44LbKw%dI zJvPD$3|C_XEdJY`ZZ=ShWNoR_>H4hOlo9k(aX)6){8-=K#P}8Kh{F$iw;7PWvX_Jv z*60AegLtIT_k-(2g*k@Ab~M%)+63#of-9yqIv(KWhtYRS{?iR@;ZvY}?TEh^?ds9m z8+*@bjdNfJoXeW*`GK~+EzgJQ}!i|{%Pz)Dnv z5ha`!;JlaIfJr#ktUp3SwYMCg#S1T~4GkNEZEzG#*`H>wul4<%dFvLBvd!P75$o`V z5jMS^X(V6E{q9a%!HT?U)lpe_hZ*-JecT3b#NNwz12Lh&boxd{)a>q4wl4X}JG{74 zdbRrKiDi)HZ+k3kXe53l#lNwg9(TFclWsJT=izWA+_XW&Jfw+Y$MbO5*8+KLf&8PKM*${9|}g4dNP2pD8h zUT$UCz1iARjPLLIW9^WF6t(2Z>|8#m!}LMsy8vwI`>hLwksSQr=2s_KLNZtwR}o)W zQDtC&nKx8Xo*GByzyNh#qS`gDDbHW~X%s?|b@S0B5`brZ zt{o`^f4adxZgi%3d$1PBUf(#^GG1(&3lMCLdQL(N4Rb!th=*Q{35xbYOP2r!+ytbw zBL;sQ85u;6xordC7GQQJ&TsIIuD$M_<{!c*vz`m3aPPWxdrQ3K0`5q?fCa}L&XgVb zXDzi`Vu>vy<69?%klNZ&Ov%=0F6-K$LB{tou?Fklw-0{;6Q{x<;oQhXK1tECsiik? z43A_?CmJ+Q`cHTL-91MK^HVYJGR=Ou`ZjK@$5k4QTUNPO*nsJdtsDwR8qE+B7ZC1@aCoh$s;t*&Cp>-=9q=+hr|ik1fhG z1}s?uGFpB zw;kV0%6%Z+#Zpw@S!mq;?gNF2)T@kP{fke%0An?b_Znj3xyxoLbY4x z9w~pdEJ1LsO@iny=m2g#LKvPSW7#=WA`TN;h|exh)>y=AAi8n4^jFMQB|! z`+;mk3?vB?U)o_f-!&);)5313;6zss@`(kB*5yV`&se8B4VP#x?3Uk z?3&>?iW_PGgof3z>Bm-f6kuLQ0_NRvyROg?yq4RM;wm0lt>1P6)zrcm9#WVW9y;C9 zQXdq~|8Cm@3?OUVyBA?!R$Hpi$#RgLAGEd)PyDu=&@l*dVzoGJigdgFouc)Q(x_xG zceY@M6$3RCDi7DFf8(CGK1G@2Bq(AtlI)}_CHAb!e}}(?p?i&7#&Mmp#*d;R2idH) zy&+-WT#qM*bWrQwU+f0X4TCjqdIbE$pvfOfz7A{DCOl)y{epNnr6o_ze)VQDuAWj! zmw&be2rH!$K5|_*EN$#L{zFalKY`UDJO)h4ek#>u9;17qO*#VZy*x7NMD;D#qdujf zToDG)xR4z1us_)MLy^x8TxO}oLJpIPmMQc%qX}%Kryim9J=LS}!h+^a-)dMeIhnO^ zabG8C<~(V1za)gfMw!}nYnFkX^!$uRe7yfa&j*3h>#Vmne40raQaK!2Mox+!0!D)l zMa@N{r6o8};we=p9u7;u+JDJ<(HF9T|y{^`0M`2~J5?Y%RE z+%^KOZeD!0&vbFHzqB4kz!5FvL8JY%tc70n1oI+%H$$k2hf5tUw0L`w?_Hw+?58G} znAUbqaN>_kyCLvk@%|jESSqM(7^z@39%BJrhnNsFfCmaT3T=WWD2&46WCcSPAjwSO z$0<%Vd<-`uhbt=xwO#L6D>_*+hP&#t9v;}5vSWwelYZi zI#DL8$Hglyt)=_VwkQ?Kq4A}n6SSntFTR--2YZubQVDS*d1?9Nw-coRx9|z)(G4?#tR9zA&4n`M=oFH21sVpDxwH1l-u|S1-!%h&=snORCc$ z|Lo(P!NG5p8xnR>a;r=z!WUjNV5#mqc&l3~IxK1Xq?0$ABCj6ktAjRD^byckusKmY&||CFDc004f<-YjtmogyXJk^(9P5|TBRtcmzo z-Uk-SChK>xliP665O-jShf%d#SoP>VZMd1Z>0wi$CCXZ_XXlWbPx|5q<%t-@aa4TM zof{PpS!HMjlWv`)g5a?;s%OBL`6w`w38OF|IE$(&ygj_TRM+DA*u`=t4a zN0(#ltzNkzmNR=iryj7}V_k89fG)xbpB4ZePKi$%yl#~AbjBNO0+POIsGEYt$lA2eI$(QpTkbH`OT!b2~8b~Hr4=Y5c*nIO78;t1X-Ls z%$M#2#5#w%5!LE2Xue%2JyD*mX!an(DZ!%*Xt~nFG;VD}cO}`Z&Lnc`@yMr2ZlJt* z#A&`BC%9wpu5D$|Z-X0a9nhc-jEo$v575mn_DEW?(5nWoEt+hM;?MfscPQNd2<~S5 zIHds1kOdC*)>fLeNi%}T;$UZSV0Bp}G5(&o#l+X(1fZCbeBMD;u4|`U6kFQI2k8T+ zEfaVw;+=QiY>p8D&xVjmfs=8IYqzO#mX68H^K0ik%7H-hwDWm_KA(($v<~tPShRec zF!Z_=pCanRJ0z%Y+(d1I8bSeIxn}D#39P$7V?BgRLFQtj&dwEQLUF^of2Va_kbn4dja#{2^3O9N4l)$v}>s`?0ZyBK)z0_njfy|r> zR1OE80mSr+2~8Y=$PxfOl-*MlNkBRB_y%Fk-*cbTYMaKt5|Q!-iyKczu9xY{g^hP+ zdnFOyC=-P)Z~miVx_6D{m&-_S1RryphTUK@Gu9>`6K$bp zOpGU}2XtsT7Nc_5v5LqsjeF=5sTnoxWV|o%{=t1+FH&Kxam>L8yb0z7(W;S|{8Op) zRhs3Be_Rmic=p?Pchc;iScE8yDhkuuek8`(Smuy?|AFrsIcQ7kFGGh=7*iWg+23SR zCFJ$Yjin?m(k%mOD8BPi4tV@Swa{_sP-R;}+~c*uXKVNH|1qw$@=f>Y#jtG)UyCoQ zkL4BvpM1{O4&4^*+C|tfZKw-E6qCq676!ftazDA8RCEWlpwIO7e9W?h2{A6&GkxD6 z1(eHWVA#eOs{l&uA(PysNdjj4#B&)l)>;JK<_+7+M_Bw6Oth`1nAoE0+pF2s^&4Xb z7cpQ8-@!thp)A^9g`&(!h>|J1sNem+2#>fns{`}=hCz4b zX~P)Ge&JXFH*%${>+XAB0SJ=${=U=aq;3)i!cPekbet&_9@16hmJvBAi*r6mQv;3$ z3l3za#G=qVe5zi6w=Ef^X{TBVCA2!{wg;5h3Jc&)F7&x@ZC8QpBlO# zOs@S+QhVT;FRPelEj&8=aLFq-Jw*1k*vWnzOy_=MhO+kn!$4K?((Q#1@DCxd21S$L zX`sJ?RZQVPysVER+86tV$B6J=>C|dY{Mo_r4$!M6x$o^ zgir4flnOL5jcqw-4iFYAcfNJWhom8d%POc(jX$3Bh^Pa z^(=yPVNDv!G#SGvcdg5e5y;)+bD>z*(xDCx7dw$%n@p(*fi_{@OLEojn}X>P);$i@ zxhfoo@lG-PI*pyS9||g+qVGCq#J3(MqLtOS9OU0g^Am|NKD5 zTuL`OIp%Zb6XmEutzoe1bn^W1?Ym}j0p;y(F8h?pa{UuFC6q77*R_d_aIi)Zvv1r> zlRi)Cc#*@vkLIPt_0*%@liU(Sxi^d>P)nYvz8nuR2YQL28^$7tiy19(ig$2&l73VQ^Q#=!5yg)29*E_^zS|ih4{d*t0xW6N1axOmPY+3xg=g|>bxWX;` zu(wyvT4`-TWOwX-wo{@nm5l9$A1c$Q<3SN>lU|>D(>y#I_~RYtkIyvxewaEp`>zzw z8uZU*j$*6B#N5WcI2|&0CIH&SQT1?w6n$?+&@G>{@;<=Ooj(TYz%Xuy<>UOCe!=e5 zG}VVVrz^9!Tg$T>lRruUwhkdSbPNS2WFuTJ+wA%5>RaNS6j!17Rg@I|s=1|Qv=!em z)Zt@DlMeYfq7=+<3BB+3$zs9pNv&Ou^BFl>GE7PovCrCv3&l*%6A3^}Gcu+?q{422 z)+#m0NshzanPC3_A9to+u1-(C6)F&rYZd6y4I7p9bQIh#hx`rR4y^)PvaO{x6=Te~ z!}@Tr+O(Y0?GgeE0hh49F@k+$L7}BJH(!kT`zWSw<*T+@C-$337ABna(=w3Bg~a2I zCCkTY5pyt(g&_@Lf1R=xw&J^Faql^a;+hr&C?S7xGY6AYGa#c~$UZLs&kF;@+f&<8 z<(ey?p4=WQ`?@)AKU(T+7MyVe!96qD2FPE5gR_zPrzNUxUX5H8Y)E;P1{ToGeKv{8 z(nxC;CHKh@ir?WzP?3o)*mej%>1Tt-Kh$L=bS5d(i7iPCVHWle8?nH+X{~P#seu}7 z&62zh6L^JtFK46&zOj4^@4M=4Q0{G1xOrbjjlbi6^I+X%`>i)8G?r00?3s`f4&+;d zy^G2dIz`b+N!3*oOICK0t#W@A1uLs4S74hW=;xf0z~t9lliI#zvaK_w=(^1;G|qv- z+z(g3#C=7~Nrr(eq|qu&R~Np1drD&l}D5$kXHK%dmy_Fq1ii==M;SZDTT z=KHp#UY|>VrP**SMix3qzzLL!FBL#|#7rz#?xEOtDJUX)ug`L*vAxQv3+&!I9@9LE z#vnpPh3HA&CJJ_owzbC5CF|*>z7AR{!79SE{tYKh#nv2z83~fF*lGq4g{zdk{}jOu9m92+s9C!chdR7Ju-TX6FpFrx_()fx@G*DXgyQ|)w+z5;-o z5ffD7UEnV#2JwsQho99)_WKtBxDbx z)0KE6`(1nr2w*BL6NMFwaJNTJLJKWk1Se(*AKN%H7mCYW6`2YkZYIYfQgf~wUDBYv zw&|JJPx%lol=nqy48@VI5WZi~zyJdC0qp;F00096g-4Vk207BcXycYiaz8i|1xu{_ z4(xNnO;ietZl}9d7*LV7v%(;m7tJP`80)8y!kCW}qbLo|PHF14=?DNeIC)}?#L@gn zDwiEE1>Q=kUmS+3*mgO!@(a`H~9Lq8x)RmLNJ8oew~%nFg^((Tdw!&1U)okO%3 z0eXNk5LofHxblZyDV`QuFaH(hay!qA>w~b)!P+BYM^cO@s<%Sn`rf+~R9h>W5{X@Q zk|vSYA#namKHeaROwUqNWxD#5Ho({v z?A}9t*k_LX)&=5DlZdsUh6J&+)roU&fh!h{fNWQ3#%prUQW#=g5o!^8YoFh7{(M8* zQ~F<|&IQ&=G5O|oa(bv_JnQ(x)d7uYt7zEOxpb7k%*`5LxzTv^`M~N7pqEhZe4(jD zNDf?}blD2}JSVYvvN)*~m`+GB)hPT%!6%f-ckH0Hr z<3MQ6QLf5M6GwkZkmbcrqI-f!YhJn9jA{cg6E}k1|r%Bnc9iB+NwV_H-SC6oW2Q+k7RnI z-I-sWUP@Zk7jO)a@{)66PBtZ(sw-A4gq2L>ZPU5wizD~x-k6aJJOUu$xr{e=`h`WH zWIe;MlIKsqV;)h9Ox`Gq;A>oZP+7a89AwT+GMP9MAMGP<$O67?!tZg(yw5v} znI-yg&6>X5!-+GY`tq^_v3TS3T#NKtT+#;c!3y!hTf=D?&^c14+erZIV__M}EZ-;O z9sjdIv4&ON1`O{T4VvivEo^qda)9+D+S@~b=fFQBYPIUL&_Aoi_4s4stdE+z08Mm zcJc2r#is|AY|e%EfQ~m_N}H{u4@HU>U5v_L{TaNgmf`5*?akFT^GvwYgvMFyaTDsu zxY1O7FaQ7p00Z7RFzVo#^ATdN#W?@iz9-J%!aLnVhRi!b96rTXv+Kjvx0lO@%$^i{x8?xG(o0}yA)ck|3|?`WYkx;PW4wHxeoeXk0dEGa^VNyrF4*uf`p!e}^SqOv-f zno@iprVaG~0bNNokS||Ws#oe1`8*LOE-aDTI*N46&rYnlA+1*|`s8F40JX%}p7#Ze ziD9GB%z181YQ!|xLkY&9*z{`4Q(h#5B-(1NW62)`DXE|-6ps=M+!5o(CH3=2a+{sS zn(98$w2H6PBGQKSU`6zB=10Cn3{^?1p90 z5&J$6v}~raA`)o21dv~fkNf?9$gn(d!hsX#XL-pIhM*I(VnS8te{k7kebGb?PK?%S zt@HZiFDDTRhh3G=z3m;br+qF_@TV6q?w4w<0q_C}1BFaCMSLLixoj$D#Ajv`Q#CXj zt~YukN3<2lEcb9qe^?%ebc5xtGS0pcO~nZ~QN;N4A`(8{57!VQZG=DdO4{lg&mjV?T(iaW_!+#i!_xP3`-QL_6AWcW=>5IJK*;YT~9dZ@Luo04lyE2+)Z{T}Xa5 z7|+DHO>>B6-IYRRQyT9VDyR37%SW~XbCQ%PaYUlU@PJo34y?H!V_78Wo!$?2cqwxY znbCE>&EiS6xP`%w=p97&IJlHg4caE=B8Ek>3sRS~>9L1+B}Lsy9PH1$ecwv+cm~$< ze3)%41uV~WeD%3OtDCEFB=&*IFVf>uX6%&1V)fK^*++2|Y&TW-L5OXee)5wiTh{$W z6x94#jC`SQzh-dMp?zAjoZ%X(5sJEw?n=_F)1@YZ=yyni@fmfEwYUKW#(41r_D`N- z-ie{p3;@osrOKm75+)~`?}Cs~@XVV$6}Z5Lo@+FZi)LB!D7Q9Iuf&geuoFJ>)Xi7y zs{LjFJ@~E)_|iD{<(UTQ;K~Gi*;+;!nSZjax)TYom@KVsRc9c$jalUY-raR^p4ofvTY9w&Xys+RRg-( z8!G-Ekl1{j*$mdvWS>L@g=dbyA72=Y%@1D0HsX#)irV-cB#ssz9;a*Pea(U>xzK>I|p`GZs?N>l*z+55p4H}_)ocA*yI!tr*jca`+s5KhN_X>+L zR_=JYE>nnqGF#(C2>*0oxKjd{DRgwNdtQdiDQE9;T$RmOFsyT61s=A})-L>@c0yeo z2HKqJ(W2YCxfE}ye@CQqBLeDwf{sbgKQkt$yY;YIr-u?gMTa8UGv0nC*4G5cMx-P4 z$;G;>P7@t%APpLoze5qqsN%B5Y(xXgxJU4(SF2mfwB7^nfmxd4f?zLi)vWkls`efl z@|-^`XWb3J2DQ0EY$idoG@y6(ud0JN~hU&hxl9+#7f*}Zr7?n>XNy>`C9$^a|4 z4oZ7#7=E>A_yY2NYpW5#ei_9{^|}urp;6yzeX&@vaAER~+r5<}MjrQoZZvvQ zxDu0S z`kN-0Y89L~(@w=w3q}HX^ub!|^n@X!Ucq_b5O!r8Wog=6yZNn%0aI1S9kgy;H#hCh zrvOv7*4@5XilQiQkAM#$HfM|?^;pL5xHKPwNmjez=?AK`35ms=_!`Yn_4~dE9WbT! z4M`YTp|D^NoD=_FjbP^TC2I6?aJ6Y}AxtoJgd;1`%r)MS12c(eVYpskCz^SaGctPh z%_@WJ`Br{(Z?2phM}D8Mi}^@R5MnaLWV6S@w}Kur0}Z_C2q8Qe&-Nh_WBzOjA42=o zHtU7#$8k37`@fx=Mp0&bC~pml(3R*<$MI@kxWBW3%-}?cNg?#6ufj5{v+{!OPCrtZ z4}(J@K33Fq;ftf4A7V?|Yy~LlAco`Uuz};&U$34kwDe@ShQSawd6-oY<|;U?DZ1hd zsdtO$MI#3aj2lEgMs?900ah1d7~{}ML^4PU2Mz>99qeDcA=RTWp_&@;n()oZRXn^i`?=00RI3 z0{{R602JETW>7(Hj%C_q?e}b*1-$+!?Hm{O!+Row@KXsLSK2=x$l(AVDxq;}U7bK0 z8lPn;0Ak5j{<(4u z0Xq^=4{EWhy)V+A^6UhYbjn=&p>}ky;g1_dtUcp~;IPj_kFNnyu62GHJMmF0%+G&f zN4Ps{a;DiE_0&iM!jaaZOm*a7!?MTY^%|8w=Ej>s*iO?Qx=Ai#6OOMAyS}c%o6`%4 zAN}OiYtyFYZLPfd54ft)KuZJ@_!|vt7K9(`_^pTrEKbjtqt;;58FA$M>@4q!uXe3_ zOTu(vAJ=zU=gWQt33$2>4|$3>SLjg=!;7u&7yI==a>^7|_y;A@JmiRT_kdAt4@uRu z?y8%5QUN2Z5!SQsUfC;h$B_M2$nm0y98rg=glHXkAu3W34`vr|=r?!~6c{Trz7ODi zl3)_z^-PA+?-PO0WkbHzNL+PZtVFs#0VK8!R(b8lO2bq6oB&?L-wWQ8Q?Bh9EL@Xp zjfu?-_p;m$Uoa{3oS&dl5R2<`dG1YUwG#RNJH0XE57pu6MGEwwiX?{h8`yL+eSrw@5;`Cl-Vtp3>ZCN)3 z+vnZ;VpCCvlMJ)ZCa3_JC<6a&z^u09ME)V5dyQux25ZuEq$PUuU32TcYJ|iAhU&=K z`FxdLfB*mk0009328JxXK)Nm6<>c@GH~=aV&1!m;FL5Rtf|A=bTOac3hMv#F8|b3l zM~iE_yV^dM)FDGUs1Kc}DRIh)lBjewYJ_ zWns3>@M&w3O+14;e{TveQ_*+$R?8%~w=c8UV8N(lVpsRA`Ehvv;^^Z>j#jsBO{Qzu z=+tYOBnH}=tWY@_2c93|df@`4o8;DviX$u91r#Y@;SXaIQ!ZKC%0z{JDL5cN)d_WP zb-&M7#do@67GB4Jv3Dw`VrsnjE=h~83>q755`-KaZLq#IIif+e7#uPEidOoZ7U+v{ z#6@H*6QOtilPNu`hN03gy^>N~OSxgniirYXA_W<)fBFpTn$05$jfgPAC`;rdBdU3@y}p62zMqpF zMBWIxn!h~07wV8BNGgXH^xbdoT0VMn6pL||PYCH3G_2;U`K_w38#@@b745)1nFe(o zJJ!Qc?%v~6<$vc|Ng%0AJoI(>Ju+6~vS)TGiOlkEe-Q9g2D*~;oJo7a`k$r}%Ilm5 zT>Dr|E=w#zVB7PBJ_EGD12^tbgJM<`M+Trs3X-dmS@K|HxfOhg+*>v)`Y!<*w5!qn zyFl5=!(u;bkW8{nVYS{HyJRHgW(@Hu_f}!Ny*SKJ|15mi6*-7JO~IB*(@!Unlu72k08ob6xDUj_0ZU$ZkaBL zYX<}y*JkO7OQ4kpnPeRW4&xd?ftiWo()BpxdlvD30#Jd$^*S~Hzto8E?5r*#?zw!a zn{A~kZe%)li>U=dbS!5{b&+Pu?hWQist(R4AK<4wzH|P8`V;>m5u(fnqr<~Ric3I0 z&q2P^TCXk7qvbT>oJX|!GM-by^JgS}LSO0-W zLIVEi76Mp@1qAQ2k!XX01dCi+H5DW?P~EsdgLYj-Cq4(lLQOq+fpNkejKJkkjyC;`gy2RW7wES(7Cr8fKH9( zi?X`wlXarxE+>J2hxn+)QHW3yf3xc#qsNe zPMpS6$>p4i!D)a50gzUkU+b1NFjLP+?nDhl+#ox-8io-zuO<|n3gXisj~1~rvU*{q zo^@@=Xj++asWeTY3CU;%m`taWziwJIKT^8v9TW^Lc!6Gm#Nb`L`di76cF36dxg8bk ze?L0n2|dnmxXMmGnfoqg1pGfDD3KvBqi_gs&7ffODKDiLpIFNYLoK8&mrQ6-LL5lB zn>SS6fVC49SA?XKIqwU_#Fg+Ja_UEftnmKhwyiwzM%4$40-$#lo1O~%EfhFKe5Cz| z`0&k;EQA@n+E)fR^THazl4bBAF62*yvUq9=*)qSRK7If7h>Tuk0Kc*vUFYX{ES6d< zTsIzk1ftJ9?mSCICn~>62W_Rzxy+z%+2lM+l9ST^?1}GM&1dSTBH1Cl_gUU}&it$^ zROt9HpP`XhU{Fv{*e`|#e{MA>fm9yXWNnADD>{$Fv+3B0tJ4g@#=JR_mqTdTEfw0#iw+i7Ai1-a6}7OZEe3K&G*1Ui6kG z({sMqv`*;8#5YW)IS%^~McCo)tHZ4|&`-o^V8GBkQaBVMD9AJ|#M%#+E+Hhq^$mD&#l|49; zTfr0Y-GaHY&-=c6*bR%nT45KTzEYcPTG4}(T>F-90puKTU$QAG7A4z zC7Xo5=5RQhnJ>ac$S9OfgeRJZ^xwPFWsAVSX@G>V0OSUU1M2&U&J9&PD>B;T05MmC zt^~*k0jDzlGq-YSZGd5bFTGixO!{K~*S6br7v#vk9L_9HR*y(5{hO{Bd*4SM`h8A) zk7-9-c4;T62%qucc*b5&KoFQ4|2`KXg*?B>3eBORYg2M8dL@!XpqJZgWYP@xLI2I; zY^6(w^*SoqQ=(@JD3$7LKE6RR1#0iIxGsgNP%*QzF6IT0wySTJdan!+iP3eOGynht z00qcZyseYsN?qJP0c>zEM(IF{vv{rnfB*mp^Tx8S=;TePbM%*7c?U+(tr9{$2G^06 z{w`B2vdr*vi%iz}3TM{DeX@Qm63^S@LJdM6HGd)j?*ooNU{s6;Qw^AcmRQU`dCc_1<<7?7=4!S5csRWA^Q+sL`5nnFE?PuSA}PP~+Qd&hSzJTOS-_)j|El z_X^uv9byZ;#>#`YZaapqu?ppU@kqke$w7t=KQFLV3(>%<9eo=Nax-9$IT1qbACyt$ zB#8~E8=*8{V3m$VZN!{O0P8}yQse$7Lx(CXBMSd`uE6qF0VAOA6(bd1^}Gvqou=MskIfnK3VhoFQ5 z#-r~ORR2tB(5=#^T*-@&S<@-q0J(v%rnSL1m>u*PVGLlK;o<{+3}qe4H1XaLGdTCX3}6Ivgy~`R=#qMi zKL(-2>Veki6*{qn9u*mv{A#@ns;P7|hlw<-%9rXr-?Re8pBVr?adJi$Bj_mjl6c$7Qd>|_N3c| z=l(?1@z+bZwyB+XwlOT}1@qV2Sk`n3%9pU$f##sdck(-3t`QHg+j60?Tj6BmCK7Hb ze+iJk@O8wgE3h1;2bQ33=zS}zu}XHNd@C|bqFmv=%bQ$AXPnk;(MKcl5XL)46m=*8 zQB+S0pQbC>2P{|+PvoHl%v;QvkRY6txma7A&n|!l4pN*d!UbB3# zU((X=YhJ$>hNPFlW9&oxGyd7}8Gv@+x;ViLQ52j4fyv8tnE6|#nn-b8ho+S;am~fj^6lB;+hn}_;;{e z51#ODy5;WQ0w6*!`&zeh*;b>L)@qT+ao=mWPNhxALB*$$lIz;o5JRxUp1B2jh~&gV z!6kn9M(TJaPS%wnlXktV2jSW$FXGUKC-i^toMzHS2+V6|`NiB}I@9(R0xoVWeUB!M zFvzJThbyO-3B10;tN8#WvteK6YH`S`U_f=;kp6*FsgdO4W1Uv5BT+eDHdsL&2;@xuTdHnCtb z`xvnOH-C+J&lNuB2POnE1q$OS?_f+i8<)wugC8Cv)!$egS^K_bk}jAln*z zAh_#8|GiM$=XbxXSpG2Cr@G|{DWO`=lTt0{AG4&D&!fGyf9%Rn$s0~- z==2y%3pwKWixQC9>!Z6DWbTNDd^Jrk1?5t!>gk_Rph?yL?lbm(lhr;Z#M2UJC)}yR z9G0$Rj-M_fLfzc>{EXeE8(W#o_RTnT?(7i1x&Kna`H?t4+$DMbTx%d?+xpuLC-k8a z!_QBE!pjh`P{OL=7_i43W=|#Y!iG_CSK|N&zAr<`J1r(tQd}Z)nD-wd6bkZtoV7yN zU~ghw!?~-0-2K`$%TG)hhEj=0Qet1E+Sr~#(nhv6r)z{Wx^OS$r+Tmf*1V;ye`pwe z=aUSsr~-`%YB$my%{|68(4TrSFH4ZhXoM3|a8-d)M^5EqZY9TO@8U}b=|baVnenB& zy0nbI0009300RI34`PaS%26?}NE62bv0v$Zw_O1nVmNsmro#SNpZUa(w}?PF(BPpY zi5Xuc2CKLIEU6_JtL%N}#dhu+D2Fp8youv%obXdFo-g-zYc*}LDx`1|5u!KF}%3q%Z9gFY9Rv4KmY&;$;S$B zf_GKtt(K6CfrRD1$h+iB7>^0GG^{U#LwJ>ny$|6AoRO7fH)Pusn1IZnlg`Ctp>~ua*bx1 z3=C?NjtdM)4i7pv4>n^CGu10JdPVw3hs`(V1)6R7(s)&yg0d+eQo<{S=vQH&vB#JPaPMMv=to`6{dK)b>8?8O9Uqfa zVWQlY6QY%2bCkt!5@LRO^m}Wqq=Ot`>*@gS(TV3+JD~ugtIM2Z(os-*i4eLVx>UhI(3CvKX~4B z1z0boEy88#kb+(UkiM>)$AvVktYc*Tvg-gdy_yH>ilFo9z<3>_a)UEdpa%qmoQkZe zs-z--sO}tET520`J`2JcUX?eqVu{0e;$gJ!7$kzHJiQ2IV zY}gH&N8<>Wkb$!|(-%Ul15F92P8`&>lsZ2VEce-#n6iQH1YY!iY7Yy4`3}ciYcCuP zwOq`r*CI+|(<=;?ul)}gNvr`QE$*8?>24}kVaprOpk6fN zC2L+^%Y|F~&7v@xH3S`0tdWo2O1{XFh4QHvd=W55Wyv&AOtEQXAGw_}2atjvgSv0C zOA0(=cs{DmI!^eGqSzya=Yamuh#2r6sfALkQ3nK*Kik{456b|ZeW%F1IC`!`m3$nu zq8u;0+(LftLomwj7SOtvW1=mQs!~fKka%|xofOp8#X^NlWDWt!8w+ETAELJPvO>p^ z!^1Ir#wyoW3XijgJFb+{WG;} z*@h7l_!TyF{9KX?21MtF765vA-ox)jGy|T$d}3P!DaeAT~(#z z=+Evm%fE)esjj#6k{oL=Qsr32CCWYm0V`5?%dyVld6~ELG*M0|5%s{)S9x!zR51pr z?;3RCG*m{ff(Hf|9*uNmHVh=cS`<2We4&?K93mGS66&Gdr$_h9HzQOt0TS#ED!I^2 zq?hN0xV%u8CjH}4RsGl=u+vD~2Sj5x%#ks=hjDPx6~`Z%h|8atp+Cv1b->~qUJgvW z*_!44b+qujT9=n*gkZCG)uSEoZF~L65+SZPT1@Oo_DDXG+5mxm0LsKxQux=tsHK8; zQq!%@gq&aFHEfgXYB)|&B_T-x%5`4vtko4@Ji-G(eQLnCVueG7^g9&!s9GbzvD~r% zXKc!8%<2K}c+Hx**c2U<-9G_KF+A zwo=`e8a&bf00RIEX@1=Fpy7F-pqmTsue<;E6$Yp=x3v9-2rR-RUA81E{LQmP!XbgS zu*|lE89E!maCFYv;GwpSMjFv*ZVr%hg zTjDTNM{woVJb`NO=TDo9F=JC5?{GZo5O^)gp+oqNX+bD;l=l33X~siA$iYN&*U^UIvEX_%xa zTD@yEbxm8P*56!NM2%EB20Y@+wDat7BHQL8Ha_d&8!9u{RjA%oi9>cZ6UG^A@k|cg z0^1}kBCcBTVA|X<=JCcKF^$im*%UwL$@^~CX}eTo(p3BV+oiA90n(&yvPfWWVSImg zD~dqaxE4CHma=a#O&pwXHwWT3GJAm@+saNyFy=|S^6cGDrdY~6u7I5uyz-L1148x0 z!d2ioC+XHa231!#wei}NNJvG;Q@Xi#2O?yK?yD3WuAYn56ZI-@0KcXB5|bgA-4LBH zSQMN3nT&(%v~4UGvPcT)W?a(=lkaSC7z{JJ_UI=Nie~$ew!_;A7okbx+9_#MBY{R| z;5{+LL&BIrrFv8r6yM`idc4E2S>fjni? zo2k6a!`xv^kBJvHyd(Vvx_1RyRZdR5p3^6bOERKr9KR@kCpIRs!q-PY@I3TGJbJVT ztXDO5mc{DSeD}Ph5SEZHS8{hv7tgG?gaC+o#Mz`Q^#8U_Tdjd3P*QIl*-@v~`)kxz z!u-i{f#D$`>C@=g;7!0k`}9%Zj!U>#PRz#Y7MI?{eYj&GQ2t{Zip=9jq5rg^HAlY+ zdL7$Y-*ghX>E*(u&5P+1*Ce8HnLkc`ZJpK6%1qnCcsdUf)XvmrK5}V196w~B?_>m< zB1_Y<$QhW7;e|;;5<`huD=gHSVGyV6D?kl?PL>VcZdWMf^=`jH2}t)(Bi~imC}n*( z$+k^|JVU+{4^g)XGp-2NZ5~~10_KbWSr`76I@|H`DI-pPl%(29Jy_QY_CvS&EjP)l zKzV1`wgA>Cfj3lEpp|}L4`pAYt|2)WTydiMnQ@UF$9VF(t8Q|7rl_$>{)?<%>qL@G zrc*19S_^0-I z1=I}UH>-PXVRvpVRRprx$zg!Sd67OAS}xn|z63rSJx$kP7VJ_}Zyu;0YQ=95<^39L z+4zw8=@x(UQ_62+!tUehE{TEUFB5=R;2dRba9S}Xt97sKYD}lhowro&;|FR!_ey0WJk71RT`~Bw9rcr@a={F zGg7APRb`c1c0O0@N&ubt+qUFJ190J-&UU17^eoIDP5@{sWfO$1@gE}zsmC;zx>E-A zw+O~MG;)9VdpXrzE+iG)AjGCTY{iST2Mb_hhMR=lD1Z0xT5n?FS*4A#9WXelP0-5v z_e9#Mz7dD?krN+b4!G%dLFIy$kF?5?F8y4YH)H|WSXg+cY(Y{=g>;?agPGOPzx6Ol zx(P3tYwxb(7?u<0U3hXGErJNVsHNSIZOX zS^I_MwwzM)H(~wL-~vb3@^C$*=mniR7;Fd=dIemCzka0ug<3LHGGb-fqQ@sQlvZG{ z6N03=`%L^!1_9+eRiyj=+P9YYuf2>mt}l;8Y|cO_HV2iI5#7CAvc;ZbfD*ovy{#ynrM_jbp255h(NWB>pI000930KC|*Z22BFbyT`l zAWBWa`9oq(4w2X+f0riEv$pPT`rg*)BDJW3xPj ze0VaOF@al(2hVXTOZlE{)vB?(%VA{J&w{2P&Icdt$kAvF-l`$Z*&oRts@EA1@(-d2 zZ!7~v*iqDUy`R|y6Zg+FX=C(HCNm(k`Zx+`gsgca8M;Q>70DGq1uf zJW68b&&GVDUAbp3CCju#X{fn5T?)@X(sU3k67Wzh zgnXc_;7Qx6l#i%m)6Y|smZGzGz2~J;g_ykbl1F(J#~eMf9$J1TxJ8-SxD|!xW~WUs z#kzV$qIXbbZp?TSVzrWAhf@ZkF2bQOAP5smv_u&c{7w#JjERTe_Ogv}%)8J=!RF|{ z*o^i|K+bPu<|A^Y_cC)JVXYleAu~A{$We#fJ%iClUlGlVferp?wmClWd<}Xnvg})N zzW2s%Ssnq+3`BbEZS;&ALY7wq>%5C(vJK{^9uObmbzW&52TMM8@3czAsr+c4E-$+8 zUI$&d?+}vz2sZ|*N!6iwj1B^EBQbuG)e6{3!!i?mx2iv|WkzHnLLn;FP z`8g2K?I5kiJ}+2(yb1N5Py*C$`?SExT_IljflusWpF_Cx4MZFRZ2tF4JMvv(`V0hH z4g)y&vF^(X+FRhWYf zg{CIZciPz9mLuhrs@qK5yJnf5D2k>{x&Y!#Z%^t5mT{`NFs;;;KPxJ}JpWIKRJMr`#|RtD>0cyZN1sqzOj@V} zu<_e(WwTpWpa1{^061UcE^qU@mM<7y@q6#3wl?Koy!sH9*boWF{JZBVk`K!pxuc;* z80srIk10A7xG84PipCCIvB_adkS7U%iA)YZLHePqn1d-sE;(@H2Y<4c?%j)g3^ID(CSF72nRA=2Ak6%@SDp}9_7**WWw z*2~$g9&YF~-CoR|ZV>t5a|DA^@%D)YRvJbEWlAz$0I-I&IY=+(o>MW9H4U$>IT*>lzjuzBYt)O4 zMaSM3{kbSKGLaW4BRP-`0!i>z4UpHYwVQ&(K+0QH7l0Xuz{8?gU3a(}=2uP+VST!Y5 zSt`o^64%Chccz=B@+|gKSQm}-c2;YIzv$6ZZV6Z`Z&x_lJVh>qlIveBMgUu_oOiWo zfFM_|;;aP`Yml%*L>9x)R$-MMKB4POK$sXt12U~lqG95oE)q|m6P`D3^h z@nIHTuN2a*WvaCVC94GRx@-|ba8YnYrERs#EwH`LYwXp1HgtmNaO<*gCfH5jZ#%wD zW)*q%g}$op9cBLDRPe=9536EtqUt{abEt%nbJ8D8lZq@_g`YUPtG1h@yFC;_%?T(r zZG8<0ot;VUQB>*)FFWf1JvQw>q<8~|P0^FIYJZ_p^^-x#PP&-HBi6jP&a^h|Zr`zhOpf@tO2X}YNEaNgvDYiL+* zP;ArKVC}?VXG0m1XnA+b4e@1;_~3;f|GY{-O1`vN)BZM9a3k6!2`!Is2&Q%4zf8)3 zQp4x#V|=J+DS*ac(C~A7a&qfc$AGVm)|}Q%yTnC`>i0pBpGf87aVKX&mR))B&qoE| zKyMdrqmm3-V|MiPC*VuK()|KV90u&am7tBZ=%Z|{R!4uDD_!-$tx88aXFPW9Lo4)Z zcS*pvOyo#4YZwuEkGgUxy@dL$)m zhtpk5A}F4n&Bi8o@5V#Ntb=}Op@f5n+bGUgO|n zGl)0QAonK1T56o5@yPc}fhUOl|kyuO= z004uT+@^oM=S0S0X_YQg)T0zL=oU|?C{FNt!>pCzG7511;@Ur#P|rN}(q6OJ4>T_q zB{a&nZ+Y9txz$^BevahpI4BsA#4Ea;5n>)+m`*VYb1gBe5$-V&c|qw9Z%OOZDlsj& z31*GR)VXwqY@D4poUGEFU+p)6Q~Lkq_$NO6bn~t#KW8+cFb-*;zaHtt|DyWIT-@3^ z0bH%M0GXQ@TDD8=_rJQG>XVX1-ueGAXhfjdl5-!>+Jwt(eUdn%feSt;b1K{sUkWUz zyE-C}?Fre=7B=x+jB_44HC zjGsx6+7;x!*D)wBuBAXawDio^AEC6|Lg-M)+qC6z)m>FHQhfkwK$X82mxvf$V~xwQ z?S*&G1AnwCKeT9{_>VDj{-?Nz^FOAXWB`LH-4i>NCX#H-+q zy&2wL>A|vW*<3p9h7(j?8LZbjo1HrT^5w5IKRQY-VuHIJbh=N&*=I9HYCp#4=v6vw z$pzK_gz1JCKG+uvAyi=_>uX;V9Q!kJyMr`e?XoNu;C55YTI{}&i&cFIS{DZACIV~% zLP8raHTRX77=W+scgLDhB3%~<5#hmQrXiP*MTOekQ|!SbzS~#5LVG0262FUKyl}lz z>KDm&402?2lk;Iv2)9v@DamU5=5nBa!mE5o7MvM%MK$bRlYCFJ((^oMi0n>0p29dR zcj8m743s;m7bxmxHtyovf8KO#Y9yFb zNM;TI|NSLRpP@`%M;rc2!|09`kGtEV$C9GdxgvoJPg&CSCM}1Wx8T>zz%gZ3Hz_E< zT8Y}pg}DUbs6}z-qe)TovCNanDmpnEH@#9ICRQLMfj5>(pyuL9H&Stf#hJ-M$*kllj62hCAHJwG z5_E)d+*(A%$sQw%vhk`WTJTo)sZ@$#TlQifV@7}m#|5tw%#NcUMu*Rp2x)_}<^@$9 z8f6f!za(-n2SUOTHqRd8#erWvb)oIGw9s7WBT8C?c{j*sPdo$>r}ygzt9O?XtM>3tkxnA}xcuo~OZ^w3oGgyvEqD+CA14q3#Zj9$|fgr!6HtY9iC3XXCHWG~E*bMY7 z`&{2gcYps$~$<}>T!iJ7qR-1JvFds z77MZMxVM9mim+6ar6ar1G<-xwY_`DJ9}g?5M$u*`kx$1=aw+fRHP-QA-fE9{KH!bT zTC0EuSkzKhb4db>W-tg`!w^ML&+XhDOqzhMx|K9hl(1;=W)Qqaft?Crr1#&wyDA%r zcKR`MmPyP6V&9dXu6?cHa{$=rz5JF}&6N8~Rjj|`=^Y0Lr~5cr~-J>23#8y#=z6=E%Xy zU5{T8Jssn~fclw~67P1uWG`-9anqVYKBG78%$jwP$VCd~-1>gJT61RL(2^G zQ~wXwK0jx>sEVxNz$Xhw4PNS@V!o)&y!yfzM(-O%CY2DVKQoHX;}SVw_p- zIcl?nj~`F$bJvcd3l|#>2Tm$0d zQe3R04sAm!Yg6gw*mQQaS_^6N`K%@H%^Ahdj_cRxYf>Z@xO1neAiOODIyxDNvf| zY1!8t-IeB4#Y*FBVS;s}BkkQ+se$`}XR#6*`#&wZ_q(7(4CAQ}ZZ!&1QTb;2&~Mm7 zU?XoDPVI&%rQ+^cd|2rnva`Yzlf)_U#x9YS%Z&tspZ#fOt$ID1o z_Thdz-{hc&8dZpOLO-5#*ahvKAW$SYpxc%-b$mvR{`%Qp6|3u@0uJ;^fm6M!ho@<* z^TkrTE}G^|LZIBAko$*s?Mp}Z!;~_a6+b4J!oYsZE6vOK*FkpaqnUq?NyV3JsBIJS z$7C0_?HoUwa4?RiKRbW5kTo69npZNu+S-8(9e623T&SH~`!^FYbuU zI_?7|e?Ik)Y@6bONQ;m0Ra^_k{^ltbVT|6Gb?VY7hbkb@VasAnC*7AHhWX zv~`OL1#sw^zD)#BNH2i&*dq;pGE4{|iY;uFRhe&8w2JbZ&B{8v(c^kkjV|2J8{?me zcg6kLyx-Cb^i_+~^+cq`W*0mrGoiN<17ry4nuvKYihh_GjFUB?x_BZUFuVycK z9;-Ysz#Nu-W3cT&)P_lu%t-on5&vTF(*qv10*Htmg6dAOmjq+aj&#U-8gN_BU5Y~) z?I^G5`ZtR&g_p@L4udYqtEBj4bFpqBR#`{Efda62C-AiSjR&R7vc0xG9ufFxP! zF@~fZceoDV?NA0;f1UEnabHLto8+**x5%FeUQNzzRsMGauUdT5KzQ$N%u?HPQ)T~Q zQ8h^fATgi1(ZY%>uJuB1e&x}*)4nOxnwG$O@n^zLw_gVxaT z$oOT12ilIvGF9)?H_?avU!^7qVp6E#%_ml#UqlyQKo%5t2T*1@J!X>d|HDdcre~&4 zGo!~@OXtrCEb756)l*{SU+tG(ZNna<7|;;30gktHDXGz?Y*dsZ6WpvZj*v(h+yOv( zzZ&;Pjpj=zivWlv0)dbIr0??iIP6Y~IG0(s3y^?!<;7yW>qkND!p`3hszBX;mq?Ko zV4!5A4;l*hemsYlqWH^~$pKXw2aJpc68C+45H{-@Fs}xc`5{btS}^NXt9}=6iG?5FQCT2~-g*;Q#;w00093B}q~BYRvO+CGsiNg>}h8`~5Qo zdn01v7a9U_B%4U8F0y5B_H+X(IlXZwNazwbZlrdNhWd*NB2Zf%g*Shmaug5P)p$6z zJ9(LZ^x+Rr3D|T}(g8U6M)Oyeg`>Y<79?r|XR1$fBj+q6`SKKFv_JcsN0nXNu(jLW z){`;zcB*H@N0`SPmQF8*jC~u>)qZUlcfW+-HUB}JI0ngEzSGKLWU;Pr|0Ma-VNqYV z<$XQGxKzor_9MmCQ+czU9u0qP7dskZS*#7G6;n% zE~hwO79ED8Aq4k8quTzDz>mNDGV1s)sA4wSAYP*Nb8?j2=gWi7wh1l>lz{*M9Gvgp zsHVg7#%K9?5l;G2Y|EGlnUs+@?qOC_{44bjQ}Lx^{HbX#dGZP)BsqM?XGK)y>W@3R zK*T`_oM9`=k55(6(arg!=nay6w;AU9ds3g0`}SnXy*HuyfKfrfep z#h`XgqSO)}XM~W6SyP0SQHu3{o{WA{5v9;Qb!+fJr8vq-V_o&KL&8^tGbyO|n!6tf zvq+VV1F;+Y!EgV2L+bs-{cN6dK7(@%B2?*2g5wzeqVvD;8LF=bbV z$xX{vA72c7G>;xo*9XX(yfz>w@ExsPz1)o77v`N$#p4e?(-MSt(=Msa#e1t6)rv>6 zFxXnHbfT;Ngy=iVh7o99SzVs&+G)VhFsLjnk7a)O{LlwKiZk#Ui~=88%L>#sB6h^a z5orf@`dmSdYM@hn(4|9r0iM9Ku80H{AGqz~=;v&9ia$S7{XM<&wfgu}#Mmp3&QTr*fLf}|gBk3x z-v^ufl*69WoO6m^4pi!Mxa?qeP$k08t6KsDi79CE6Ep+{AR-|kZh6Rjm85E7{D#21 znPA)@cLeHrBgrHx^?xjwqA*!8iB5R{nfmlerhmuzh8rND@iKzzWS7T$LxSMrmL`qx zp6bscP;eS6Y3ll6$J!F2;Q-0S7j49O0Reb<*PAMq#Z}*eKx|mnFbVo#nkH@aHZ@;s z>$~QXwm)>O28cs;*>(*cKwp1B!#@NyEJ8ivUTUE8?t?27exs#>$$Mnn9#Q}Ams!3WievG9=vGsqe1pLEh&+Ed8LX^1 zVhciRjN(}6fY(%PL3fE}ox?vI*5O~I_)%hEUVEc&!N|7_pKlORU-WIh(B87g10F!Ens4yRjf{REkpBAaiZmLVL?XMKZuJzr&0pFVbP8C3GpqnhxT2_GD$+kEEI?V zz0k>RyPQ);Ruo+RQRQ5@$W6o%ry-zhxH7?0goFe&yvXen@PRw zP213Cg?OiwnkW#0h##?g9vW(9E=)bvXm3H(V5vr~O`LZ@Spx)F&e^(0F#k`m*|o<1 zOTmUv3(3r4>7*Kk-lleh6(&L-wxlHB3pwd(7mw`&mS!1dE(P|lQ0w~c45b1}|tfJ7AYC!v=mMUrFa z{q{o8m-gJztKfNun|Wl(G<`v$^_^03Fh7?8yya1!75P`ro%Pv1!j>d7)_F}=dG=%)d+kA&aF*WII|*s_to{;!S38Ge7^ zMzL9!={eVtpw?w<9tE;LVr}6h)40Lk;Z_G%UJyrX zQT1V;rjzRMXRnK$O*dl9Y6H&CN5IgTSa*mTskZ8jotRWqK;@Dp)5NB+z=wIeF;VC7 z8w{ui0c`#)QlFwqM!Qh>)N?H&uGZS%zd#0>RatD|4d5s9CXK1}{$dO0SX;3nbOfQh zW|;}T0{Mcklf3uhLEQM`8?BLrba&-f0I~F{lT*0kL9rKm9LN4BKB|y@ifO zJPmB!+q9}PX%y=~C^0qe&DorRL`)$;2-7mQO0Xpo-9}qil1b-* z18SwKXD*%+bkDZ2f)7Ha;++k1t4GPVVhfJ03!v6GV%TCS_{-r9K(=EM0OuzJ{Dd{D z`E%3}TydY1A(YJn@T@%Fv8{-yJBLz~?QVqy6fE-dTH1Sz1aoBtOd|JR zIzA#zipAi<-4z>fBtJ?LxXmZK{6oU|t7l~_qUm=s_H-LUbuER^QQ>g-{HZElcCUIn#-Hd3^jt?060>UeA+ zHaWaY^Rjd!acpoFmS7GP0<>ifI}I$|$#j><`GOi#%_ab7|H1=9k9G&h5b(hplxW9? z2Crd(JfRwry=T$*EYSU8Cnugi zvHlhsVK$U9PH(A4&qSsh{6%dQ9^k50V-InA3dmPuBqCh74dTyUijBXG4l!*$uJ0yR^Y91q=j{3!g z=Z`qJU{<60H9*j;0;<1WK4BgOV=RbE{Hli$#w%2W3q9oG?D(?dt@Si}cMZf*3 z2GLeWo`9*USC6DS%UqMTf1#R0BBpK=IdGK@(m&eKE))`4qi0PFb!%%X2q2!Mmh9W^ z+mR!eOn!ur@9-U9biWJih-dx|+u4$NJGCybuZBPo+=(uN*8^vgVS74(T=%H|gdJ!o zPSvtHTbnfwKqJ%CD2>Aj2shW=2|~E{sGaMKn`@lkRFFeVq;u=ZaB0Axa+UX{RChr)(Moj(*r0&i^{T9n=9Q-x-Z@mWaf25vfgay z&LxP$!6Zk<5|r#|&LIg=VkW3tX45^x^!yUyFB-U(-s)v6gCEfrhc@Y`!))=_=sE289K0GB&EJi4TEzwqs z01dGyL_6cq2SvZ74nE>RuzQuVjEMY(e`Z*3EF^fM451|nH@zW)osHvF2>OUSD*`7} zs5STH<$wW34HTg{00094MdRqSj&ydio+9nkC0>uT4^%NoU++^Su>ckUJ3g^4VZQ}; zX+V7`&y?yBl^iZlWHW_iLC5?xuK1UMuRV=ne&1AIKwP~Q z8PS;$t2#sY4+g0 zmI#`U(oRvuzTHlY2^7>;Fvp#Mv&BI{pDg%JKVfsVRq*ubiRZf>Y*cQ$2Ss;05fqXe$(q~^W{*dOKe zn}1qbR>&A&U$^D*>q&>d%L`PEM!ro^oEW(&7k1%Bu&wmpq*-?|%Km)4DX6iHeDiBe ztg#MWN?2!w!#3)9vOjb&rM{1(JVw$q2%CjUYyv;3^ffen;+c@&Iv0b^-w^g}y077- zSu5(?++xv~XMAgl9&l;{Iqv#msI`0+;1ZwCM7`B;BURk@hvLHWuJ2a7|MPKmJ{o}U(M{d_M_Pr~Q?T%VyzYKR@%2>#;a=Q7 z--M9cXxmo4y~@3&7JtVUMXypj|Lrys@2dOxy5bpl$=ib`Xqb#e$L1xaV%fX_gNCy5 z`<=w(Uf_oig}pX&qJ*A3ZAdIoRv*<4)K3?Ng)QsF!E~#5%5Uy?XBGDGuGSzhsZRxN zKY|poKaTy7_B}bJd&*}$l-w#U+<$OKToQ2lGjjdo)J|@>0$$b3YpaW=G|4QO3O(?O z!5PO|1#K~?2Xh>9oJ6DeGtCI#fYU=Bj5mvZNOM`tl0YFAfbWcpDlbZZi_v#&QPxRj zJ+Ssm-|^de)%7&opW=ZPfZA7cdw3=D(;N>7kg=~MZ?(Z((s4PdL%Pv>HhjqglOtg? zT(Z-JFq+&B7yb#8(AlQBgeP_28NU`kt~hZs4)kA~cN1OSk}!VQ&M@%boDV0lAZdr) zssZI$zHb090V{JKB@{ECK}Qh|AtxNXhNlcd%yY+QvmeFV`X$dyeJF)m6ytowDt8Rz zHkQxa9J!=uT!{(Q*M5sz)%*mXVgc|h;zx#tshc+7cu2awR3T$3xIP3@=)8EtY>P>W z%pAZ(c!YW)o7JV=Q`0Qb{CqjDH|y@ljMvxt@a-tMUz0D!)CB8tN;elo;$MsDPfXs= zXZaf=L&r=(r1C5|9OH8*lod~DAaFq0<%|qE2=hp}pXunp9;f^>wRZ2lbkhIzAJ4Aw z!{ToJ-A9W}m!a?WWPVEI8Ax5{suC@TY_F>w?59HVv=iZkAD+h2yvbdU^lb=`M}~!v zo4C60m70~YnX%?S(RxTH5?f8heTnixLV5J2b+SLd`uAjJ3i5cn2}vN;gB^Hvmx#Vn zEd1cYcI=AmjDuJI2rI1pm2q4%VLZ@pMmZIuCPeEOcsoJ<%_e-29WF4iv5Zd4s8M}3 zKut|{|AsgK_!|d1@O(3W>B@G6&L9CYo$e!-djbv!^iwkEh<`_dwMFKC0@=+B--ug+ zi1`>KOjKpYFL;l*N?NHdje~XHil0I2b#k3R0@K?>6I0T~4b4~8i!a4u91UxQuF)C6 zn%Kq_SQFQS#EYAzY;8#@_y5Wlaq^wJg}qA1xF2n*SPRa>apXQ7H!LwwA8ut$>$}xB zc}?afDxHFqs}FBW_iU}yyg3fuNH;mg)lFK+Z$#+SC?QV`w_YmYnpcj%5qs7=Q}lBM zFtNf4egJjH4Gqz$0Z6FU26@2GVz z;78d4<)U=oO92N5JWeDAM^=ZEKoW)oOgnn-IYh1%SVV`e8d-2d{pOIp7xj+_9a9q} z@`nVQ7*AfwvEK|oz9%OZPh<$y@|n3;Z3E9{U?7YSzGcTS(Z9k9F^I=6`<#`kdGJ%J zYyt^0L@P#ZNtQQoY3WqC%>XzldM&W1ly0Skq2nB|-?8|K#Ai0sN3SCi$pr1hXWkB9 z^Fs*~{BUO`?&^ULm327H?+n7sxMoss$5WbfkNG;-SC8BJ#`~C2@UI#PM!l%v2JN70 zH^HJ0uCL_gdXyQwQ0d&DN8i~4M6(>TqhRDq0Y%A+m6F=h@U7Wp30M}geQwMI?v%+@ zI;vouYoSxC&pYw(ZX{iU#42Mi51zS-8-&-tCFfF0cEt!1`S9^V0ecU*_x=v)JTPNK z0gOGKe$ula1UFu-a#nWCG;8_D?kTzK?%B$6I49=8pvf|Kd@*G9d^H>u#U2X0yAvTq zny{ueV97r(3G@RXH)~7uW;X!fRW83P?kYrd>@IF2)2VZ< zYjff>r^wpcz>AxiMBmUK$0qQMFXSxYgT60n)H@&b1$S*oSD^6GGu(ZHtn}$g_}t+g zfS2r#WW#>Mw}EBSa^-hylErA^KaY^Uh%E93ZbHabZ-bgd;xlXUBp-GH5L$WHAKBNA zj+h_Bz+Z~rfP~{i3RuJ;2aLtRg%buc;|>zUD;a$$T=tE||6%J>CVUkp z-~f?R8Y)LM+;nXortn=$1cwnpk?gnBmLLEC0{}9)^>LEE^}!$?`h6J`D<1}({d!lK z>zb4=|8uO0Rd_xge#2Zojss}cNq?W?`3cu|vlyp`Pd#@E^|r>-Gu2%$;QG8F%8LM9 zHHL2Tbnw?+Spv}@?nJv9`0u>a1YAg52d5E3u0%4~$|A`St?m{@gvItCe8+tJ)7U8s z{%LSzIa~r_wTgGt+xA7wC(+M`Nt+Zkv++yxX;AeS&ApnBI>_~6;Hguwip|0otUx^8 z4;JP+h`q$aR(c?FK;$83n#)fQ0u#zuGXkZ-fdwVS*0f8Kv9I3j2IY^vs`fchi>`-` zN$1MFO^Y~k61r3XS)vMHfvMt#C31PL%ZrpHn;9AUmpf+#kMAU|m|l@3!PyE-oaYl% z)NaQ4W(BF11PuVW9#luMeH}lSB_c;u6k#xzU77?h>?Rky4R9E4zXjNR!)FBHz%bMT z;}d^BJIK*#yez=8&g8i@hQ#%&IX@Bkmhd)GYhT8x;tc6U#mtdV;6HE7HD3kXA&&K& z=jrbO##|u+58^!sQuqpy)bVw}(Di5bpNVN;KE$byGQub)<;|?v+U7OrFs|(iE&q{D zFluY;?qRyA7cl!(EQN!U160m6=hKWOd(hp4ZeexzdA~AK>iE_e&$rNPwDR*_-a;5! z7o?gO48Zg>=Q{Yo^OjayB)jFV5uu^}*MqF1LRR+J@eZoygUtoBS$YJAV=iHmt*9$< z&5Tnow&)P}nSLYf2z;~>b%mzI{QK@`Jg1NUKNs(fVvGNdZJ^-N>X~`T0|Z+ z5zZMcPMO-_G5p?6tcR$VK+Ws+cM{s+ULzfbi-jEW@^*0QvKP?WmP=O%@@i6q5U|Es`6mO(99z7958x=;>h9RsBomZ@M0&es z&bzw$mJXpkPRi*XFEBeL8Ml#gdJ+HVBrh!5i0Yem?tbW1&+7T9>J@7RMA?#Zy<{bNih>}yI=ZUZfFBVh9fFEkr5LYc z7w2Jk%;59HU(E+_B=pZ!%xFP27pPoz&AXXgCixQo?o}v`C(IX|)bi#3slT%q|3v!a zdIWfzG|G(NH&a5afm^aXxzm1#I1)Mvi49@Ypd_iL`up-9>AXC6#sBC6Pk)5unBr0} za#(O(tu>G80!h3I$W55-)JwXcU(w<1$!KaTNSKW@j9~!H>D1Kf8oD63C~aAL&0r61 z_b)zUCH3~S^f*|~yUyE2DL88ST81HZardYgBsPRQE2l7ba!k6-Av1QeEiPej*=Uyq zgk(vZY80;|G&A7J81GllJ}mmb8Pwfw%(ZAv6`Xf$K(2fz)LN>(NHTpP4i7Em)Yqp& zA0k}T?zu~|&X08f00RLT$QRI7yX*-X6kO=PmosKZXvxn$3}cK%PNJk7UqsK`q)d$_I4w#`DHj)pf~TTo^g)U4}e zCx6tN%~>V(ipppv>p0Dn-6nM%vT2~Y0OWLly6_qGyl}ExD@_O5}{q&twUUHs_|}R%YrX= zwZJPoWyl>P~I=986kTv_fRdH3*ooWpb=^&tG&kGjz}3R}|4-%h#w6kZBA1=$0Sf!sKN&Z3^U=y6j|bH;(_1V5tblDZdX^JO2Od9amg@ z2!Y?I{a@Pa`}H{UGOJcbN}m_N4j&G|-uO|Vg`oBsari9`X?6g&RWdi@Z;z+JOFX@DusU%D*_+vc}4rSf|DtBlNy0R0P5UF2lt16it{E-_-QfGkz(J<`|KXH#2SIYtt-=W1uOxK+jUI_Gz@a z_*l<_u322|hH6|9-~itq628d}zjfqmhezZ(te{EbEa8ft^Awi*$}Jojqex9Ip^zAU z&tl(`UC-lv79JN%)p_BwuSMGyWF=(*cOw2huP&+<7x@{*LxzPn*0$eUip;5b42U(hg^qvyYTnGnNfec^j z2L!)Ge)Tv24rJ)E+z;nb1)k@oe^dV~H-C`ZT(}>(e1-l6$cKOE!ND4`fEcqY)%CZ3 zZ;q^rRq?6=0oR+Mt*AhW&dlb0Z}0g0TlHW&;9-4jOVL%pI!7s{Te3xOS@CA<4Ml1Q zT9!e}_<%K0eO4-t3@c%SI7QtK^^{cr=^iZ5nF~+aH!biQ9sqi349v_PJMIva#{be{ zy|-#w#r49cJPZoK!2AFw6I1ev6R73er^*3yR+JgYuEp=nSas)L+Kqszj-QSiJdO^u zv}Zwf7q_KfNHI6;Cl+Eu6vSu@vw+Vi00093F5#b*fti9dn}(<78Hbl+VGwLJwpKS= zbZaC$Jcu3bUkK;IrmS$Q^PM~X4q5*J>yS_3xVpWr11OjKDmseMRT5lT+*ZVJY~cN1 zs*`tJ13SCJp)Z))nQvV)%1()ocf@G`mZkX{KTu z7Tk}u&k|FYvq1REDa?x&rpctBJIZ(|uo`y1@Ai|;I6jM5L?*%2MPJk;*^_M zm_AD?uYsnq4KexfK^X~+P!)ZaL>n@Bz-GYv%;~+ZWX4@!@EmU@ho8ZeIpvCbNR{^U zGu1k1H*tl?x}`uy+k4^Ydf53{stCd~`}eZg3`T~JfqR#<4pg*Rz*H8&38geDKazRH zi#gKc#J1{2v%qYe5ncRR;`jsg5t!u@lgT=2=I2QXJoj3BO(TYF_8UdsRDQ6g4&EL2 z^rx@(reNfcf7{aDtam3kePmCClK1*{KliaJSE*)@wN)qD)H(HDT9+OujdqPa*`fGgru*Ky!H{M~hQBR&k*2bepT z@t5Qd*H{XuYWUy~F+9$(Euu#Djfi^|trTK}*$IY;Ih08E@XS*Z4%!=`9etO~SiS(@k~tv)FT7WF!nH8&}2 zl8lecfxd%zRQ1jhJMk|GmyUgbKpQ!105MrYCtHe#?W zfM@s=a1PIeEUd46JgDl3n0M5zAZ!{;97S#J(Pby{?#Rilt5`Bz7uO9UMS0hF8xQ`|3~Rax|DrO_ znOn@JdbGLanFNo6>!NZIe>XgreX~i+2ty9A>)Jds&+0HnFl#fYm2MdV*j-acZr|W~ z$guZ27wG(>DGC_N%vH!)(&ZzOQI@kvKKh0vEKPdh>l&4}8(fBFL#d=nbOEZtcsPmB zdo1s^APyPzMZq+;F?ggv<3a_wki$*{(mgvLfpz4wsU|cjN^Ul@yvXP?AR?|EO8ova zBi&O&Pi-x)XI%|YJHGunCp-fy30Y0HQvX(O3S7+V$=b2N2SjfxfNvi?Ue58j_SrymQ%q>-uzx(rT)B4`ADlv3y58arBB z7=*=>6b1;;jtgCn#35#3#RYN-9fOlV<7$ysJ1rqj&zW)89t3oc#eOek!o3Tf!}&_J zZz|9SzXxQE*o3-K;#ryh)RBz4zLNU;SnwN+tR#;>2 zd%HChkPx}aPpPVxJG-p#FI6wW;d><+)s|?#S9YSv%DX}L!e--fb_5BGltXpDb|QqFoV)`l6P>oJ*LrEEgL$URhui@21@h)ESl7sfFaNe$kuG6Bi4V?j38C z7}2dKiide`*coz&Wwn)A8(kcu@3gYi8!&A5H{qr;bY@=DPJW6;K&H>KC=C%qZ&(T; z8;Zi?7gLn^k&Ax>jC{(yoU>2I<5qK87*Es4+^&s`z6X8<|B%BIE=6%tzS>n;{ShDL ztXWFX-*L^Ee=xxWZ;#pFJW-D1Rk+RVe+yS&;~;Z{uJ5DyEGvt;AkHt_hDRN`XQal& z7x6pLT5RzS-j&)BZ3%mO^CBa_8gg)$xMA6rMYO2$_qoo|u}FzfP6;+kT3lA%&j&yO zF+5E4Jw%v0XAz$479r9%cTFZ2mO|aEv4||hWY4IsqQ*fZ znB!`dv5)bsI27wRNqq3?p=wi5?qk4>z9t%wjg=5phN~3WD|9S?Y7gWai1d-84S{S( z=0Fn-eI+=f7OjIv3ugUP8rB=6%kG1iYj*2MPARJQco%U0hfX_@^X{{;mBUys!qaJo z!&R{CPD0NEhw%{aDwAykWZvS7fHCo^4}Ay}aTIBxjH7y0wZw(NLxM1fYu`zonVoFF z00096u+kFu)yPJfGXb4?kX3J)plWA7r;k`Ur5?V5hr( z#oAXaumRD*md`pAcI4Q}1sfpM-ZaZVi*1ScZ5vJDX&QLNBJbx>!pDMzc zskoWJXzeT2iN5x|Fg(}c>EwyB!T$rOl8`w=+_m8E=EPt{MAM)a=Qme0i>-sor<@JoI&W8rOp-=qdR)2{$koN&5#k(CEnr298pj$i+(bSTr79lV_;y?I{!mfX?Y*i)^$Zv(07*DB(zT!_4Yj{V~x`1+-T`K|56bM+r6v zK*UR`I`DEcdyXu=Lp+Q{GvETb$9!Ac5<;23<-^fnE=gH-YUNWuedhhkXZ`b07I9-) z-3nwIp5yw^LyLGxB`K4mScCjW!G&p-^V!?>1-n zY6~CBAO&*fZrP(SuFD{H=7F^?lrThPXhr54J0Oae)5v}6vLO-ieDcpUfTe32rFe`u58VYC&)3nsEVkD>YI4?wu_>@d+ZVhb7{Vd z3x8Ykf;$1y!@#t>^f28}w`j(?5SuVs9ly{bUJ6~)pA3d=AhEr-p*l*CB0nkglyTFg zTQDcI&{eu$d-hFZvMT$+M-p=p8gh2tgC`v*`%|2Rd3V?@Nx=}8*yjE&(^d|kk^l+9 z=tN_qYWoBXSi{l%t|wmVuTxxK2^hbIMc)J*Z_k&R6=!G@$SFmotmnAuI_6L# ziPnv&wtmbr1V~y#V7x&5GcE+C0(pP0(C}bNU`)4vNm>mZY`mr@@fUzT5~QfHf^k>u zsm~uVcxzUZJH}~GJbIWO=?$+_^c+p9oZla$C3)6xR;t08EI*e7tw{TJ*Yc)XxY^n~ zA=dkzEj{=U*_-P?YEYdSl)JvyS6m^6BRgqhL8sk+YtZUElZy{%^N%v{| zaEm_za83_%`_=!0l0BmPFXY~xMwFVW%wavK)^teFa9Hp zG-DQn_~N>44YpQA_ksvlw?3!D=I;xduaF8LC*Yjjre%A#r&U)~B&zY(lJ7VXIsd4Z zqLV6$O+^QU;qR*v&_WEBGMR~SQ{~=KEuUk2P!<9?Vk+^>`$UT{8%Zh=Y8Bx#f7 z{5&#KyZT6{l=Vqj5;o9I7HWPr>dC=yZKM33S_P-dSjxFp*E5nVVEh|KrZ;bWDJC&| zzWUl4nt#WP--XJ^3m-Zcb*>s`zEf@vXFu zpTJn!TF&hCgV7jwA($B2Y3ex%PH*rJ&X2ZWAv86y0A;dlR~2Mm)UuYx2YAly+J-h$ zoQjRq@i7EwS==(n@#e$Q+~Ta6hbz>g{P%MUAc)N2HchotkMT962D`PM$!?ypIJd!u zCG5#>AC9=}f5S+IOhzu2Zjq6m7?Z1fi}b~NCn)Zh;`OPg@kats7Q_z)&QG`m`q6Qn z+nnf5Laf(|T%F%u^O-N>av_Ht7M~q9A8L0Wv?%3uMz49ihg0dX=$AMVT(#w<7ah-u zZ`;#DfUElqTOrhAG!*Y}#q0cAMDh!&7dcYybdVuMHZVxM$46z@JC1!f>Ku|*-Aul? z4#9A`?{-+mpWDu8;qgEMmP|?t(lJS*fom4ALwo#G9FL4)0C|^ZhqTm<1+_)~{=Tx-z z00093V8^qabey#2w-ji7RV5x9$q!i!zezG0sVGKqL*R!t1p z`}rV1y^iBePj)svbiiV}>TdI}bd48(*X)qA*%G?162 z+TV{3_A#Ds0<$m56`5CRkLj3h>yqU?$(Kse)Ld@BCaG-wHWB}%B$4Z%ei z+!U<|9RvYOm?dv0009307%x?3XN`3 zLeEjDe8EsV^S}tWhw1-yY@lxAtzD{(T>OSnT_-3Vo0sca`V~+XF5anJr;sF(zzbYJ z9k_qC0@(K#LVkZ|QQhh`)T?9}Kn8FCL3@sco4_NRz&J+u6!fQTp`)0NmnW65xy44- zKUdTV3@uOQp2c(C(PjssT@f7RoM1_pLN(#SIPMBx&%`{oEO#istU|A87da^M0)~YR zucb!~e)$xUT7qCR0WWHXA96O|ms8>NDlE{OmWH%`=zCsw*pA4^-2)nZ?0QWZNP=oh zWo8Gmqo2-#Y}&dLIlnT<RiCLSr_%Qx#9-0EVN#<2>GjZcXq#W? z1|wxdMP;r-Rd@QT_K^?U1Sss)fZt&4&al&dAWhB_hgsjZnPGb|L|$!sfKu(Pu&797 zSpT$hU}}&+GfSF~9Bi6TWnt|Wdar_p#62OiOY#@n97@|@zsx184N2B3enQ+*U*}wd zZ+gUFQ9HIO6yJ~%UpXk?8KdHJtw0JURL|vY=@v+o`W3=hd!n%(A)~KpH)!8k4snuCY*fuv;J{C8Z60p~nK2EX!noOa=G4aTn z)e+l8LAG(|!jXWFS{qIrE17S7m7^)(ia9~Z2=8dKX>jS6;?J*+sD|`}&%Rmy1m=93 zkMW9nxW-Agmd_st3P&4E)LdvlfiT(1j{?_4?xfOU_4gQV3XmHu+O>shg_fJGW=7%| z$S^GVGR33O5;M3JW&HL}^(pN>@fBV};m3B;G~P3$1MD=l^KA869iY_$hBl4{SqZcX zZKxY_2=H*pe=9!V%&ej#3079&Omb}F?*tkv$khN$0FA#z%yp6kECv)cGMpgNlnu=v z@<>>7TRijx@PQ>o`_ah69m83d7!YHvLN=~%2^YOVCa2I7WH?T?4dt@{XcWO{Pm$|F zM7?yl7q%NVOgC@y@IurTo&`8e*e)s>jQcZXiNSnf3HL3az!S@HrIY0?L=ACV^2^J@ zry~PMrr|*)*_g01fL&+I(Qw4jIP43cl8`^zmH?mp>P)|(`sw3D_Bp5e7^8$*P_sh9 z=aAL9VE(Zr0%QUQ^C2{SFD&D?D-Mu0xzh8!V5g+ zri&6jL~v+i7tenroBcxkCUvxUe`q>-N0<7No+4$x}wW=t1;qT)P^WLujYMWX5Ez4wz6mu)0Vl>NcNviBkejq6r%H1H(dPyq9}ydjZ62vO6h9k`pova7tyDxd{0rVTjq9dx~y9H?q0c zy|IZ5&c|JdhBjAg@`>MgDB=cN+Y(0Tw?ZDVwSTk=%y_qF0^#nn+ zw7zgKPNnjntE{TA9gR`abo`0T&ab3-v60{%5>VN2Ak#Pl1kYQQ(HId__2V`l+qVcA z+q;)Ik^#be*)j?B|B*wdaeiS=3YT7zXRQc)kO*;W@9*=%vkyN`t1;~f8GvYn#w+}? zk73d$x`Riwkqmdtk-W_k8KuTEiZsoyq9K)C{t$tS4|&DF^7SCE+06|TI9Kv5%Q#k4 ztei95$BrG1w*q+$TJ=A^Am`L8DCLs8jKo7n+y9*t6cUCZk50WTYwzC?pz1(<<08A$5{0@=)~H|Qc*i5fvi zt`Pr0m(4zi$YmRPPi1EFVm5W0cs;$UV`_Laa;G;vinwbkVhiew@aS{}cZ z>`cwx+gYD+u+S67U=D)TE}J_6LO-|Nw-00fR|62hO`rvQ_Tr|NqW#Mo1q5cGb6@vr zpR`^w7vHD?g)a+Q5&!@L01@u|(+~g>3LP63^aAe=D!(1-P}!fsZ|CJ)sMu$wRA-?I zQ4x>gOVW`IwPkS5FpMnk6q#qHjYSRpI}N=+?@vN|58|w3@GNa^@u2_RUAGg5_c(0uMRFA5GnNP?}9@H6I<%0T(rlS7i@% zHjpTyQC)tLpOgUPuF|uN{%3MyGBjDwN63#Bo zuFURyD6+D;#gBU`%{-8~Zts3=3wR5yMt@q=pvm_XN>VP7lOer`FqY(nxXs*Qo()G2 zeJlkI%WCAV@BH9cTpi6-_G*8)CVyZ`z|C)v8txLw6nwt(R6GV-^)|O#P;m5#txZ5{ zSF1O}&|5$GNDR-c?a_=QK_?r#;cKDX5=T3!pA zYLq3e%B{Oi4tzz|0i>#mAvo!)EbIz}Ig7K1!>m3HhPZ-{@36khvq3~?`7LzWgTC=hUdxZrrl@++d z`z$;Cn<#H^)ws3EeQXBS7WRzGl!H{-%^{M!k~5&xK0p1e0|eg>O2WgTtf@0PB)$L; zKGY(*{@8|&02n&#C-7mMVR-{ipcn23Pd6ml0e{LxRpqji<~zt3Dj-t~GncZ1U2s3P ztBvRT^)KhFmy6IF&Dr!Z2>cJzUWVd8aPguX)l&zV=IaLcE`|W#S?L=U3D<9))=9KM zL-nBS3yK^9RIqp#p-ec`JgxAxgxxNAO*g-Png3Lh?ChhF`h3mp7=Ljo3tx6>j3vRb ze9nDU-XqsWqt2<312h4T7SK1-F8}}o00093BGnpU1rR4xAiOND$@vzhuY+pnHo^U! zEWY1Qo4kQQyPfrl-;QK@6&Hg>+w(lg^i}WKG%g{tZet^)rJ?>=RwZ=Z6hI>rnznz8HAXWcVHm6glpIphcBg#~4R!U?> zY6=Vfj48vFKzbWKnw($#7Q&0qccc1;J_o@837+l-=_z#=yK@@sF3+CqU^p%YZoGjj z>rj3^=Y7k_y*!XVOjKSl9{pRZ$p*0f(>}A>DSUeGj_%JI-Xb<}2DPT_26$G_($MY* z+~l~dyLDUxcvA*x=Zut9K#ut-ZNQ))xFHi4p5{kOujn2nTbvEje`)-3ik)THfyHf< zaqS_AAiY+6k|Kl?%AnwA&!>tcfAxmQyD+k<^xJq52SSQ1_v{%|{$c0+Bj459Qg-N+X_NDl|y(_PAU2oXO^I)~w2rgRSz=Zjc z=O};)cw%KTvNGJg$|CHJAf%bcIVNXYQk`n&C>|)4z}IP9Djb0o0o#gme0B92PW7*E zM54{zXJU_U{Xpbmn>!nef~5VI!wOyg8CYIXA4%jZx_rFt3o!*r6mPdj;qy%YMw}0> z84r@AYbqb;;$^CvXL14>>OJ3SsN(WBl_l*>BS}Y{Bg>o9w9J_T;;$Q&i89Ra-o@&n zUgk2epYHFJ9G0v=!g)@c z0R^G|1j6h2ITveN$Gp%CFk(Ko8Y7ygFUP@j3QDVJ;Zt8@kW$^k`s!?;X_tp`<1k)d zEd<~B)&g;l9W!PigWFf2w%^rR)5IhDKzJ~6x#0O(+-We?w^M(|^nb)kP1Efm)3EGU+6MG+g;mEy(azD9ufoivh#2Y}Q9u0Lqno_o z=5?26BRC%MUCHl|N%f!}K9er_hJNh9vu^l#3+WY6gGE{;bE0ks;tJxKxV4b@2l0ZHZInyazg63F7Gq-uVJ`5OF~nk2mJqQZ}!#wH%kbOx|~ zpl*a5J@tCguBLtYe5!g>gW_dv|K|a-4T`zvSh74G#K&JI^zAPk@T8@@qhGB|A|c8x zSE#9(U`)KXVL^GeLNP^jFnlY$UWQ1p00093t#sa$>eqeD638>9?xA>ikurE@Eu|%| zNH!J39d;*{>8COY9JY9%dpJ^%ZJJON1FNEgejL{+p0Ig?Azw2V7luDv!9}VRqTKm^ ze2FlOn*Qj1{Q+J8!XAA={lc-XM5mr%I$Ovi|EQ&&x}a`62#X4Eq<^gF!uP3jICNH@ z#aQ;GvWPySAoZnLvV#YY<84X|E2@5EU)!5@IglPaT>$Z3d)fh5qOqXrQ!J=&h*lM= zYz=;GGArGD{85Af`YKhlXza#IfZjsK{%id{HT`z)F^=4hQD{6SEf4twXK?noh%rqp z(Ul;lzVEMINDI`9~O zVG zIFfqm+?RI1Wq1y!Z3?4SlmgeMNNAo7W)Yz^_T*9Ux4{TRp@6?`>n6AG)0 z9zDUh-p58(#BRQtd{Q6nam*Dwf=6q5A?o+SH{guBw*m2?w5Ea`g+^{^lJcQW>Pykv zqPo31e2!Wtk!DY|Im4?b2c(}lUJ|_#NpwfO!lo9J#d$wJq6Gc%Mdh6~*-mYg%a8#I zh>u5YCJG3JZOMkNa(A5UIRINOY@sRkdv=4MI`r7__uIZT$QXx?oHZ+AAGc$sbo zyEQN|>Hh4_jBxJvw7E%48519Y!|Gt){a*2%w>(1&t)Z4X4JJP6$QitBJU46|Gjv)% z59n|wjx2p>&mW@PisgCotr3iMg_WN}b&-uRz$ED^{T^RLxV2?NWdeh_CcXnSUFzUp zGXlnss(8kV95Nubd&8u}FO%fs+R(T`EQT=awCBK3c{gw3W;Cyv12^u;1|m#Hx#xd{ zM=4oSqHm4{pv>QDVhJUPC4C|H83S&e@z6lyE=d2=7u;ddV`#_k3LvE(b&N#5a&Qo= zu?vPe+^3Rs!3wwRn+B+0Htpg=C=sDm?%P*skDY{kV~7%GkPe0 zp^gw;(V4G%z#X$-(l1){ciWZ4xaT&{1Cw zco@$^TT%e{n!cr3NtkGeX@HJj{Vx)&*{O(e9j)#jYu0$rEdatckC%skz~sgIV`nHs z(L#~?e_>d5FElm#1>t8rtjB8g^h~e%0u4l-o7$O$`V&%(WR6tgoXmaRO5gW;!u3Kq z62Kh!#LW1C^r)-*%r`HVvBEPOE1e$Y=Jv7~sW;jscWhvjWjTq-sqB5(#AxU_bVnYS zgB6ef01Dra0t%Bn669+#dmpXV5Dgw@Oq(bYU441EA#fv(oG%k|1<&18Z;@=4m>X)V zwereBHQX6ZGD>7)u^cwA@RhthVAL%pDe6i)Cs&tkw|F}^Ayv5}GodUakPNo{3O$Y~ zV-JVsQwj7(<0y_$01abalyus$^QS&v-VhHb7sl7-j|A1~=ypi0ID9NIUq!Y=?P zB}nZNx4ra=tBsH@VY{~+XYAbe-m0c1#VvJ9iC0g&SY=c#O_%@>m~Nf7U!CUm|eVd~Z-$S2e6n+@3b zyYBcRPpUz`%%c$e-g*$VUyRqq?6`SV+}|RRIyRRPh+I|bdMaLK@rCX^u%=6C)5G}y z00RI30|0JPP)PtJ8>$ivTtHez@&LD^h`H3zz*dRq+B*sEw#yvt~_(PHWdlq zmuYv#XC+`0^lOguf48}UZR4aQcL}(9*cIonhj7X!9M|{)?BOO zNE}YuDb+3pp{i4oTUN1gzXfE0ZJWd7#v<#9X0fcimvJq)Vq4NAhHKt-rYSO#SzHw& z@1!tMqqEAt^YH5rwz6oNFdVeR>5DXpKzWH)aBOiNce9;NJnYt_U@bR4+ zP~0|UUNe@nFYoG`hXvx+CZ!QwZ;w$CqWZL50{C!P3V0R%`N$3;KVG@R;9o zSU;VT*?I-9=&#>p80J7!^If%0XFs{?WzlQxhZuM|&9sCKeB5|1Lt^6H(De*k$mN+o z<(V(WeHXGd^y-d9<8TJJ5(Gq!C*py50=b)6D7+}O#=L21OJXH9 zsGCt*ep(us9@+EJ`xHVs9KMXz+4;5$lZ1`^RJBCE#S3>S8>g{?rd-jH-Q3HeEm{&Y za#-gdGd{Wo-U4@;0isv>#;$CqHQ~$eQ_ifv;w`cFAZXN{3BazM6UQ;OEy-%PIH`_^ z6miT1AQ5JJvkgqFz4TC#jFl1!2uf>HokfRn+fH~PJ%0mop6|dlSJNz0=DS8^5f(V> z)~OU*-N{q?8U0pj1#pjYn>Gh`iUi^!GRMnDry)Dubms5rrD(Vo<%8NiKEJmS(v+LB z&-{x=9N?57%9R>5WR_{)Fl`!%l*>0bt#Bv%zr9w-7)_QQ^T#NC-sTTZ5>bPf;Jc~U zX(?d*hw77nr8El#?38TphDU#3nbUp)tT!|K&4S|jN?kN6TvEf@lPw%f*n+!#L6^W# zfsFaH)41zsJn?m|j!Z)i+&+7~3i-W)!hl*)eZxD(fn*-DESCfsUH`gEdW&m!chy3F z48=#W6ImUm4SA8uB55g>0ZDegD|H!WySO&&PuRN|XD7pi)mk`HfX}1^3u-M@%+)OvumkiVqvc z&qcwKTtt^4o@&>y^03k2Er?cUvRjG8wVu#*QcI3SkBAOxkgYleTv_yHYPbf7O|F8H3%nhNZr zg-bS0kZ?&d0UNiZoS|E)F z!kEj`1D%h^_*1JBPqCrw4L~FT_&xyUhfCHwXi`1vjQ2b%mKePP7i9X?eto@TK3Sj= zl3{refLD+=%%SB{lC<${Z$!K-!6a+9BlG;G_pR|09hV7waYA+?SIAdas>Pv#DUtB& zjl&WT2FG z+jyE-Aa~*?-J3Rw!31Hrvpb3tCiz28URMQ16O0(|=Sg3GUXKlpyOm_W$sBW0Xos%n zt>@Bt=fE!d!Wt0m=nI<=i^8!Nxm%qTHB@p-=?C4G@G$vKW`h5o?*e7#hpS`?Mu9gX zrovX>yVz)se-qox1C+|z1`xTBXN-atWL!y9Z=Wwv*Jk+KH;YOftX!}W5a;L7kP-bg zfwC&IwY>RkVY`)PZ-0vKJyE2ZwOw-S&gIcanckiOo~#yia&Pc|XZD-8GX zmc9LTy^5X;bE&@~E6}@U^J8|+352$tUcKz99kBJ6ZC&lB4ppM6vq( z`5uDtaw@Eo)rMV4Zzztt000930=G(6!&oVHy5d=#7}Z5FRb@`}RufdzUMBovH!Xs& z5~o&K`_r3JvpOt+eyzunlxm<9(S}!aA1VB%)9!-R|HR$*F*J4js~^oRh*D+N1|Y+6 zu<3n!cTT3mgPEOMw6@~s15y19DYT9yO*8!!7@I1EB*g2z8s+-QHg@`eDs;pKDB@+{hC0I9R;&|(}WUdQdl%mT@$Mas*Q_f-+%fJMh;)bVM7Xt6WJ+EzUlwR>oL;eoe&-Qw{vS6{Xdj5 z(?m|S+W=&cO~8cP`AFf4^m2PFujm*Tx6Px+KByA>|C}nwS;MXdZYPPz8Y}rNJ0Bf* zduuQsLOzZ_QfFS4BliJO@$BB$1vmYhLUfzgG5G2)Py3aW1%+&(9V4d4xBaVRhBd$^`qLEBbNRC(E+k>o^xPt4VghT%nUm>ZV6Nc(D z`eJ}Vx)|BM8h&rd|D0>rKFyWtC?Ycj@Yz{zfQ+lveMKxSAZxoGOAo%MlR;x?8+E8KvW#X_P7tv;Ct6QTQ9Nzy}OnEC!EXJ97g1!d&KOv zcAobr{p5SwD;0{m^IhNOgP6}upz6&EVO_;Q0RsDIb3dax{mMwbRxE}PW-9LRr#q;I zRXu~Zdd%1kJ4Pp_DvY!4#W?V0mWwrw-wR$IKkoP(>*MOL2g8}!Zx|i%AgIfn_Bk{C zRq!JzlBz5-KEtk3k|pxEx?sid#R(<$a(;Uik{l|z?>KGebai4C9={T5`Y+}dI0J>) zxhlYu+j<0LaHad$uVA;S?xaoEcuxhe`B>|CVnKcrD2Nz%Kz5d8*~z!r=mjnyW3O0Z z`rUKj3-|JW`-=$;cDk!}M5r6n6L9RJzG&}JnxPXNR5EF9A&sQGy5yqvCPU!ie9rr&-_*^(xBA>`_TnCC)?!Fdpe-Exig`ynu!Y`WkNQRp;d6}Q z*X=<<&FK7Gvy#lMG~Sl0?cqAgXCSfLPiSG}t29>?WT|3mT2y_52S;E9GWRF5x4tQ@ zrH`v-vDkbOUHvW#L$15Em9(`Gf?~dTzGwKz9Zn%hXAp^b@)CiBj{i)8@KnwN>G=0x zS_e&5{yaBc-aXb>79Yhus4wZP6)Cx10a3ke;)xs+&AD)P*5{pAk~`|CX?TW;-12=A zUYomPT*jahYMVim!S@%@Er^DjIH)dq6Oat%1s?40O5j=bCAoD*GBEJW-CjZ3Z1162 z{A+SPOaxObjc4LUDQV_CLOj&WA?Ri~DhH2BnrO5a>yblM9*=nvolWK`ec5JHLY5Ve zw%8;dFbb1N$^c)3USJjG`V+4>+`s0t?z@v9&Trj&btj((2e}&pzi&ja(ReMbJJufp zn}?ZDM(E}m&j!dnUV`vJ2JN;unIIEZopE&ez8%~EyQYwm65Pllpi|$I2DXA24i|AX z02C-va|gEojIq}FCQK2*{uTMnt}{!==#37fZTW^25YH-fdh1ffKepY_~GTRdkCw-_3|NS;) zlg!2l;wHz@8l>d>P*`BP-X7TtJY095^Ou~f#C%$q1OiqZP3hg6XS3u)lY=f80Czhk zsRT4x>++qS@qUFxxX|^h@->G$YAZM6ZodtT9jJ)@*m!i$>#N2sv}UgtNDo`|Y+~GWP)#}OOta?R$#sGbv_2{g@&L1`QJg0SQzU=3{X__2R$%s2695_O5Ze)LQ?|conMwL2tdpe zJa^-C0YlFOlWe1D6|}Ip=aahnLIGcNq}XxOcMnWLd;dV#qRXCYBfA5|KUhT_(9H4dM~Qg(z=yo?jo<1Blm4fX0gS|!sz}exvs>HWD-UejbZI>#iat6h zwO~c(03H&P;Qx+gMAVpvN~a}bkS1xIia|9~ukMoc(rw~8yY2dGcODV=5g$e+TsfhV zQ|QS%PM{XKPLrti=@q>V*g}NYhXO;Nz`MvGSuUAv!AX)I1KCK0j}3~VZOb5kpG_9~ zl+1>R{ABp@=9rf_PBy$tDQsYu1zoVW`A{w!)TFChLH~t`_ za=I{c8`~PLUO4yU&tUM#Z}#454tR9Xc&!tnhtD*OfS7}|C5q?r^g&WNu<-Uu6ZeEC zZo*}>{a^q90{{zz{@S~LaE?v|bTCz}!O@!l1p6s$h-BdZ>WhW=@J^L5?37#hrhn3T z6W{8tF3j|H4Agu#xLr3|S}f$3>!Z65_|-SF3>q9e))UwiWpf3NhD6rk<55;|%-bYI zlu>xz{lKm%_-K5_2%IbcKI>4nHi&5!Dwp6hoD3 zYj2?oF~|#gt2)3#la^@gmxg-Y@`TEH-Q9)MC6y=7g_$Bcnwr-f=8Z5K=w&wu00093 z02<=9ECVWOp zPz^gT@)-PsH{eB=8qKWX<=bgIhNy!$`MVOW%8d*#E|dsJ4sp1 zM&uvs*_x2sZ?iPxktO?3>VV96-lJ=@A6sfKJUs3W$0#xM!mFeol9QSnZ5)sMD7<~! zyNgVweGU0{fXzqiHg~tqZ$)o!1$6rd>N7>S8@C*C1ka&u&ZA=L^PWC#0Vd`^s*9|9 z(gyV)x>ADgb+4HM3mXAIh2rGA$#;f`7CNzS#?Y=6M_eTuD;NGD*z@;i1_H#1*wbnx zhu}`03+nTdpLRY7Fe=a?{=a%&je-E(NH<$Lmw9UZJfgJ zdwo?lo-4WQuI9oo*Gnx51_2eD$6P#fNfhOWXAn2OsQOEvIV8aj>8#IB;;U|`@O4YPJB3Q)~;SL2K+ftmn z>!MY3v@bxd5pV9TqB5HvtxR=g67jt3 z?}H6EO%SaKQkiCP=s*mimvLA-3{<)LV8%o(il+dh7rlCYNv>s4QTXU2d3}6>dh7GI z$;dSSvZjjMbw!x=0THPhEuY_y3FPg$&SPEQC9iJMTp*hCI^TsmW540~e*Wm&$kkf} zlA&XSuuvY;oNybX+P+9VLvHv+dAkB8jCdJ+#FbnPyo`!ON#X{9GCjgH$N($p;;SsD z`9MJ6$|jp6^F+ATYSOO4_o(YDn_WwIx&?T9VQFsVHj)(_v!KjvujR6|0hjHtxz=JY z`Dck-E8%fs{ys6f`J`7mF9U6P`U0O3gvh^@yQ4PxP?4(~y8~xwlP&2foNo~bzl6Ne zl&FA(*uB?d(&t~-_oPgygI75PfSGq$+GFkK@ud#Mh-03Sz(z?ksJy@JxIXh|f8~-Q zTsn)2FV{47@8$Y>F|Is+I>Ov9VQ65d?y0cgT|@YzXqq;%7iyE+vkyuqiXM}=)&z|e zL{1@Y0`WPaBriw^K_05<3tWu_!RQu`nfXkN6;{d9MeXsAJ-MmUCSYg^GN#v^Y@*LWE+SW21S&Exb-?)9?-QjI|lU=AO%MR zM95Ypxbn)WYyihPAl6ZXqv6i41-MyW%Cr@rWir<1#5O<)ml(3Z3DKU}V?x3|cw0i? z_kH%EPP4?8`R?N%Xw)#y+IGiguM5b91-XqvVN=(I9};$NeZcdo_>XiD@`jBkXqAVNl%=&v5h~eRA9Lme~)$XC;$Kh0MHwMLgbCo*~bMyZRAl*@WMtP zWe@a*J6*Ug8a(+eN!zE4i-!M5`C5X!Mc>G}ZJ|mGiB35hqYleFJn<)Vg!Y*QT<7M} ziT{s*Op`dsW^5wY?xWD4sLS(P^vyIKum+`XVO*`zSh?%?7Cm$hn!>73Nd{ZNHkxf& z0Bd))oiCOnoQjT&=(FKlXWj5|ZQ;_lbIt3WH)-NsZ*4Z(ylA2|=)sx{&Din^AbcU>ZqG zn|EGSFSrCU>{+@c=c!S&I>yeXnKHLTX!iojyYgWtG8WH%(pj53S+-D(U64Ry!~-%t zb>cqu-qgPDXxZC|yjy8)j5$uMl=RQC*g1U=(uFld;5up3;j^efs&+8e28W_&40q7u z6JC<1h_PVo*P{B24N>3~B949J*?6vj-8(1Pwz*mXlMc*@FVn~U;Q$jhP>G!7f`16! z*^CA&7fF;SbA07W4{GN;W^!9al1iPprMVo%5uCVO=@YpO4WB5m^#lMN2X~P3bkajT zUG*Abm@X-%yO2~-=+$Sh0UDP8Q~+g5#okxa#riUO-Vt$KK(YwnR7CP1)jgXnSa!Oi z!P`%>IO5!rY$@-a?`xLJ>qWRnh~a?*>Sj}1VJ+zl=JP2O73&3{U+Wj}Ft-sP|H6T| zBab5uzp_b_iO5vt4-npQeO?mt(p_w>7gINeSDB(dW!*g=PL5aWq#Gaka!`t(_)Ajp zu_mYM{Xrz2r!*-e5>Si_3!qlH@l62HPsf8REc2~6?aM*t`+N4zPU8@UOa8sb0eszMjZrf@F4ooL)H4BP$mdW@VYC_e; zUt|Acfb7?OM$I4y{OF^{iGNMG&Un6k25bOgCg!X3+J{E}Mt*a7ovg1fe%o6*V|LYF8ly@SflRJ~r7m(q!AR0nM-Yq9{% z;pe(lDD%~43reu+z7-9EL<)Ph!?N3lK*!+YRLmRJw4UO$&pMPcTgn2*Z)9_?OdUux zPr8s#C*%nr*)nsiZg>3yuiJDup|#S4y0jg($D02ZQ$DX3=dKsI3ZSik3Xd_c;q zouSl-ye~#RN|k(s-Df+LON>$F*dL} ztFo;ji*QyljGVpFlUqbhY&fZ|G`g~R!=mP%y!0pH{#(ZbtrzN6wj+Nzo3mCq|`<{Z7{^I%_OC z3Z!zZPL7KA> zrw%`KV`q$GOC{s1$pm_OFe(@@Q8%}o2Vi*QD}nXC`N2TXM#67pJ7EHOeRSGS-}EWH zj6W(RN;EGZYnxz>?#$cQnJqzXO+D!AFvMUOfH#Z0N>+@?OY{dPJ$vN8v%ka$q1)0v zDby+E$OM^cA}BQ-Rx)Hk;L0^QLw;d4>1O;{9!(qm!|69h63w= zFSTR%fi?LA!CDb$mB|(Yt=99uUbXhA3T+zElEd&+lCRhu0J~GalNq4G&LMaH;2ncy z3t5KT?&71Ja6YWzsVNf)MoQDe6$Au#6~wqxG2Z|m>v)8Um)5+7>k*RqYTmetER zHM{aq+)PBgTD>PNf(Drd;OSNdx@*JBK;tQlM{>QC!Kzdn9PFhmV*~}jRB%}9k8-Tm zLzMUB);N5xBw*-?U7kY-fu=b=V)pUV!A$>g%f34d`M-`V)rA7E5_%z>e-wV=^KWGZ zuW#+xJ%hV;dltm(M~QbKePPL{Jr{s=LAVNMb}}hdd%pcT?j=a>skd}o2D&;wwH-d! zK)l+4U8^9Nm`p5q82`zWr)2w{iI2rupt*ZGwLBuE?^?t^+Q;C}xhfi7iLd|t|BDayqDs|{QfOV)6&+mP zgE{2_1byPT+kAv*&%Xd*>xicI!6;FtaW*XitTKQ?H>)>8_~(L1@XjK<#*f=t_->DV zXgG1GICarkhB!24l>ZiohQ4VGxc;R3Cn&4$k+tYwq8qEUYU@OyrnPjFuOt@B=!(rP zhtORryCoPLbgMNG5wpkrK@jA2000934kX0yP9^Zl8`<)J)DZ;zH_fZfDO&DarbUPtLBOL z2{6JLGz&Re2(Ju786#s-0+j~0&5cA#oF0c5CrVCUh#p3@>QplX3fw(Dw;c#^YMf7? zlI{yt=!QyOKlqkxquuXkw^)iEcDeCplJ&0i8i!`q3TWSLGb3|jfeQ-Qs03&=0di>P zTu{sef|Jg3POPtkfTK>p39>$*ZhVa zw7T3q@J!~{L}c*^sDfB0libBAM*=I;=X6hk-woOQ7@ks}MT_@!kr!Wcs1P0E0h7}D z93c{)wi@y(y3mIclcAmd$XEAb2&oLO4^R+p&pJy#)GFqe3K9}^S$3&V3E&4@!rZck z@H~UQcL(qecVdR1P%{!g&y^)?AO`3w*4R3~e!U=S94U=YWJ57{uBq}JxIB*zyxXs4 zG&g&nuCJAQrzg~!)=XG`6&=HRsin(*6*DIc^V8|}%gle&dG|T8xjj}RC9>cn-PV4= zO^r|{8PA<;4sk26KFr@3C!XIIO_`GMxUL<=+2kZ1)>F{kK*uXUGjXl8)Pcx{eRa?@ zwVh*^GS1O5>HKd_#*7i_G(@D?%^57L6%(}90IOqQ%A9%XR>Rz7cHFCy^X`Pwa+jaJ+R>Kay)47}2~$ff$WQ z=uK(m^)b)qLUI^b;uzG$Jh+nA!j1q1@g46pYIk*ETk6o3(&Xg0$yOp*NWEn+)fhT) z+yF0`jR?3c?m&XV!c+N&-yVIel7b0;IRwQghR@8l3RQikU^#OEe1yEt zQHZdV43QbaY+0##agei!O(rYit@06Cbtx53@aF+rR;g}4!fL2Rd7qs8Ifq~!sAG=s zriWN_m4P^T`$K~XPSz^m9Ld1@n#il6Q3z7 z)$W-}5Mi-fMauqD{G8EhL_DoWY5kE_#HvOR)%ZkI>-&yWL^=svn@Q``M(~DfM*>1e zsTQzeX)-`i5-od>nUxt$?DlRQI27}l?zF5Y#yg~Z4ir9&^y8b38PONNnf-#=O2!%_uMevRV15 z%aSREbr?+O3c8EyV*w#fun_)5K4@i#^&Pv!UTh8yNIs`UACVcGUKOT%Z8Gnf$SqXK$!BS0+NBTSYH=I?njo21dVa5hRSeG?_u{ zJzY0ViCbfig#Kx4_7hIlI&z98H5`e)0`bp>&7YmyCO?lTPwpMS&3uVu*b(&K11jg=1IL#}(~c zls^yKdlmH7?PLIL#t<%WnCa3^>ZdoH<;S%1h~RpdD(=dAuucy&lu%D`UeJk56i~Aii}tc9&&#AG^+>|SUR>YRl+h=?-8xC`md^AtKVWpd@=E_ z6Hq(}xCHB$+Os2WKU7^Z)pYu=U?Ev0@iHOAoBg?IwszMi{KBBIFhWTR7b=S{mO5ZZ zi&e^fLF~!sKZWUySXqPN*!qa)-bk1=`2<9Tb70{#n-}SCOoQw0%+Dx^f2iSHJX!kg zAw>ByB9ilozN0ZjF{=tpz2_gUgTGi9Atnx$ei4s*ttmw}l)=TQ9fc%8@6o}Lny^8y zZ6x#}=HzVlFS-p_@8{HR$N}R=bRf4r8D+~+gE;4VR*GcY5@D>~z@{{3&*F=X3E~Ac!=#vLT$m9rL_5zMttS@l%vcxlhSlp_$N(Y9 zf|yeB`EqL31NjS8Yzmaig_Xhj{^@SHxI=M*tqeQsU&Od@0h~ODM2h}2SD_&S<5#VB z?p&`Rrt#JQLpyh1Xxwgd0fzYw7_H4VUJMp}a9_5cbfpY<&xA z)*01aZYzhll7^O?}7~Kik@&f05Z5z zJ!3A+n<%XP2N7gjH!Y`_7ZMCu$;?^*EiKDD#u^lcB(-abnIyI6la659#s_dQJ|hni zlHQ@Q`xzk=?5qUg0Trq0=i)`IEdZN4bf-_UZs@D#CehV;@=fTcxB^7v)$HG_=SD%U z*$g?duvqUBdfLa_Ywdg?ikYs&*Ved%_48D+5I?wd)W);}D z!F^(sm>6c=T*Cx~xurIzk!AdQeE`_dE={G z6Z#E8&6OHFBoczP$nPuMb7@;FL&71Dp-tE7VtIB$YmoMLA{(; z|7PdReu)=(`u1bL!FFa@vZ<(FE6rRMNbr(Q4zBR+GhQCIe^^_7G+6yk4&=VHOX?`k z?^XAltZfXvSDEm-f{e-YXFfQ`Os6B`KC`h>x)GsuG?fYDts({mWi=y^t9=ilhX=)W z_7%!F2$YW((uP38pToty_8?W3a2e26~W3moXM>jRyP`c?&d+Ve{l~}xDGwB!R3_Qq0S8E!p2V0 zzB-KX5@m8pTvNJ5JG!yqN6@!rXOQrQdrk8X{koNLjXp<5i#BF^CD#eZXZM5lLC4~Q zvahvn`MX-c*^f3&;5MQ7Z(iW-IKE^)SW(j()}LwMX|V~cfzxFD4-vAzWO>4F?=(&{ zeaBPf?2)>mJK(d&sJCcLfryLd;k4;izob`n zAnDUH9L^YIz6C##74)n}|7blLPC%-fj&@={YqIAnRG*8x|3+6^RU`jbz_R;jP6L+G zyoQ+f2&~v+JuRK@K_$({hjGbyM#1!5N4DE>o|pU#n$LD)4WBoJh6s_>-CXi8ErR%V zt8BJoK#o77W_@Z$_o@Q;<>Z($ss9H-Yf-WJIJWvQo3Q#!KylrNI} zc8M%npytM)#IW+ZX~f%n+rsPI@a_09Jz3nPJ5|_)0gVC_v|Z0xtt3>f%Jz>o&8#z^ z!=6mv(~0BnxeBJm@hsCxPEi9pKAOi5G+%h6ZHm*sMddz~sooI)nZXn30(^ArFX5_3 zjAW+u^Xa^GKCalB_3aQ|wl1fuvAQftL)SsT74WKR#Q)!6rEEX+bCJu(kKGM!8siCr zrtzNMy6KkW0#+D!n4EC3fu`>DsJ~O+9e!vl)k}!#92+z*F-GrtMSBV^e%C%rB)IB6 zc;I51%zB{*JSqb@3sBO%oBX`Jk=@D{Q?cgYs5JN2qKU;1rT5vO{OCfQMmYOn+n2Cx?5<_z<`EzhV5@e+{5v4wNo-)8iE+0LtK~e zHm&<{*RG%e=dn)&_=|sTE|8hO|FkRjVDXTTp?uwMFS}SPrv`o)^8QgZcrr?h31k{w zQl{K1d=f2ZaAn; zVMr#=LvSln#fDsE%zuJ<(1ycIt~p?orlAY`B7!2Ah1epI_7)b8K)*L;H7#o0{pC(> zXLZww_sfVb^UPXskk(9`P>y4*F)4WCxMyD7#nZMK9o4_Wo&qR;Dlt^25AQnRE@T!c zb#gA>I~f@h@q*-{fQ4X1;KXxAA}@AZ6_bK{K^X_1LIm5ZY~!A9R)X`rg@3AbZ#MHI z-;n<%#&$)_{Bs)crR_Qf%m25zd`HL9<^?eGHm0$?udeWF_;qmt`EH8>8exb(7FFMo zil4?pZ`2lrDY2s*Vn0|-TvQ(`Hd^d=j1^s8VhtJl^jauZi4x?>bTRD|@Z%v2O@FO) zlA0ql(L#~sD%X#A>n_J>VCjukjdVcX^{RV%60YBtbK(n%FIj27F8syt7kRypD2Z-3 zYPo@wy#-WU&6+iQx^Z`xAi;vW26qS{xJw{7gdoA8aR~&1TX1)`1a}D@+#xuD;LhLh zzIW!%%$@n}zt&mZb*i3v_Ac9}j#jWi|H*a+5o;Da`2_U!lVA0d%g!jYNNfXXRqew< z{@zjA6JwJdp|HwXR|Ka{!%trxLC=uVnV0^&w!Do>Ym)Rm{c8djnPrIQxOO->{dM+C`Ox}HPsx@@US-W9&! zGiXedAn)zqtIY@D$Rdvp+_)h|wv27lD;8OZp*|%=j-DEE)iVaQq5D%($H52 zoHv*DY0M8Ob0#g6f9zY-=~@aqJNGu34O+5wYGYxWc2_-GUF|{GCM&I)6(CHzIDly4Nkt&BKw1xGrokOb`SbOXc zjrCrWMJk8EkuNaf3We%=TE>_J4h+0-jC=_xIdHmUx0Iee2fdJo>bmOTZDBbhVH#mk zGRN0>JB9vJFPI3HC<4_{Te%BB+uaX#U71`4FLYgD~|(!w;KI9 zUakZEDxB+lXFJH7LLq+&&iuhBF=v+RsqA3y)XVjvr8E~~2xS?~Wpu}dTZAqjtA)+m zF}a>~ACW1(_%g)nGw!kgpfyuqG%~jiYO3AybS7YhH`IRoHD>GhY8Mt@P zB;OotM{dkanNHb-lGE!sD+NwfdMxLsS;-@%59~#Uh+?&TcXDK7=4e44*dxwluuDv_ zd6svw5~|HoE{chJY4BNr)P0Nty}fYok4V@!=2TzLHy)vb5#*OPp-!Fc@!G1~e2f>3 z%LjqcE*T^^B9|r|&LK8aW}Gj-OJk z=HkF9Ve6!fAJa?rXeTiO!?Ukr+F9qPZfbAUPb53SRyf9v>|Qi^3|k$x)xQuytvA|{ zaHciYgsoiIh3nk;s!jKdWN3k}H00D&Zos8^H%^UU#T23ExBj~##EnuyEMnA$?hsXW z)_%%a3I?3zpJ+oGnv7LxDVYxvAEOATX@8uYTIOlmIEwv6X2#4^ZlgR=z2)^~#x7%x#Xlg~6D>YK+ti3iLl1)vKUQ#jl z`#Y~>lq&e*8@WFu{HWHvVn>Mc;twct791TEmDit#?Ms{Xv}?4}robK>bNvKf`7&51 zDu+KOTZO!KGic@j>-PEtolhqUl@sgxX7B3>M^Cf#zDUsq#`DV`b;9uD?Z#6x+~$Lg z*$aNor(vwCi-ab9DOk0z^N!UHg-WQ{9>T+`Gv#Yojveid1ItQPNR`>Cp`8jH^WElX zlOL2VMM}u*zY~vz!q1A8KQFu17RSK|n8W75yt+Q{F|cxA>|LuWvVFC%+NO!TcaJL> z3Mb9O;7Uz|PUm_77Z%OxuHPYclh3Slq^uE6M*w>YPaCRX7ewe5Y1j0A%XV8=ynTfs zIm(Zr_(2d4IUd9}KAo%n`niJN!i~g_B}1B&m#Fx-!tL=crJHm~5X;C}w@E=75t!>& zT}2XQ_aD}$$Vm*$vQ?UPB|Ii{QsPQg$D|u~f z3ZKUG85|wYx8LoRiMRPhbMgo4TJ$c+_Rld8Cv)6%4))+Pn_B~1qf5SxC38y7e%!DB zx)<@zbpAU-k|?{r0P;uta}H)sbGYl0I(J%qSqQo;a1BoEy(bQ}e8&YV!@dY27B^3L zUca%m@Y;F#Y|w^AoSteisiK*vFH$Q{P&0!}$teCX?EAB45TQn67%O;=As(9tSbnz* z5Dc5~v~VrICF8Y+nXVj%`}rTwSIV!}_^Vix@ViT<&$xvOFWSfRR#HBUu(z)T%W>U! zcW6y;`)Xa_W2=x&z9O6Ro*>S)=I;E!SDV5KaW!TRcyBm%mkVo42=m(=QjfQjDbm@F zXVWwS^UJK9E!X`$hXKW4IzzFdxfC+RjNk$OC6X=n+6jSx)q68!^IugsC&K(*Q?L1^ z))Gh&jIXY4REFe1W54NLyG+xzdommfX?=g_7Wf>ibVJ-EA5Zo%0>EC*XD`$fJV2jH z`VI0pW$OgL%`IHgC8gx%r>2BYk`z`-dth0IsvE@*e}B;w5Yz;$3`5s2E80UxRU#a@ zGWh%>Ct;=4O2vj+LFLWwf(5EIr1b+d{SAHZ(vEzX`V~9kE7F%p?wCYUm9gFMhvV<3yXZ|^j;N^bk{HtE+IRM;3{+Dup3=Js^Y5uw5wtm5ETLcWSXk{X=!f2>rmvgayd67 zO<&zj14l;5)}kQv`;*a5Z$|9AG8jWwH?J>j1IBMMnl4&p;=xNV=eEo;%FXTBH{L+X zwge@(c@)!@V`j!CEfG8_559dYh&4%fP(K);RAseFAvZ3l>#+~6XGM9f>y>=eq|oZ8 zL@SSEf)skEP${BvqKv=#wvvq;ejLN{3+HveEj_uF8si!jzsOmI=I5$c(hYi&MdR8W zwd$`L*220^=CY@B$SDjbUkGh246zi1R*ab>Ayn)iP+7k`!_hqMBReZj>O#W_!GW8P z7gg6mqH@Z4OIBC&P=YVkNnqYV5^2qu;sJ-e)Q(F1jdefo_q&>_7c_?izX6Dc_Y|hX z;)cLX#hYS>(ybXi%cbFn4|v`)iLJX3rMb6S!qGY95fJ@7%4;7WRd9*nN;rvoyw`7VYj0i%>p6`ZlU8}o>S@Xcb79#PD`6AK02ch5a7k^4h z-lIzocmGDrrBjuUIf4Dk`~yn>3?YMrzZz01*BpXFc5BN{j!mr);X?dOsr2weZo=wU z{@Ubh<^I(3{w`XgmU1B$B+ltwL%81Lp3fmwiO{td+(k;mIu7n_Q%r&?V@kNr@k*3- z@FsQttRjepCQehmYv?%>>OVJL`$OZP&4%}aH8dpbOKc&&%&zVyH#|^dS9Se;n`y#4 z-VmC%mr%mo3y<`#pClhn6hFp)v{J=^uEf>aFC`FEhR%OP{)Q)}gW=<-x@RO8JojK@ z-WFF)hjy3~A75@2^6{@Ex_UqDdGCVJsT-a0I>osu+c8k8 z|IMW#YVg#}^Hw)0{~q^3ojeJdAwwKeTZve5XDq?ZS~b?vQ7+J#xQ{^ka49&yR;B#+ z#gG_JT2h3S9i9|$;Ssn5F-<6czF-?x*t|T#G^m%hR zpDp5yetVflsf**8XliC{u>j%y z(q?5I@iN`ARZOX9;mfHnWTDe&8G<g!-(4F*LJ_*B4!)KAOnH%0U0n`>k*jday>ulgBWDLwP7$~ ze_Q=Px@O;``Gsw86wd+2oW1ml%fU}{Sx#76P`o2A{M?X=^FGbBgZFSe9f|N@I=$P+ z;=Nm(mf6E+n*fa3`mO?fn_suCZ)(#u+G`IZ{VM&Yog+5ba=3C9BD>I&{-jUGIV@mBWS?%gAvn1^^43yEYT;VP7@2}@y3j~p)BQAU?Rhd*kGr@|Q-<~n&TNZ+ImSbsR($Mbu*M(LvJG;J5* zDsVOG!18CZI0}0@tJZXHjk)*Y*?=g~8<6*kTTjnY@3!PITd}QD!&>^j2Q@#OBm^Yt zWUPEo=|f1u!Hi(C3*-W!H9WFiO5m0 zvk12Oq!w?Zesqk?y%DTI74?@>C8HTmp_GjqLQ6Kp@+oPuuLvdQm~l?D-Y=})!qvjd zr@`_5@_V4FS{)qQ>>4;De8S+8=~B*!Ui-#{)OVlcCN^owI<|b2Ippm(w&pNbH}I!3 z2lf4&0F%B0suTtGH<_qS{cQaa5g2Ia**)E-qYXzL{cYc%PrkjulQw(V=17q6F?ojX zJjH|3{q(KUYzE8n3kH@b2-?uh`vSONk`E$=MYinl)J7|0(xlPO_f3 zHpxygN}~>~PN~X>)+xo6K+^KZppjZcq$^cExF5eJre)!3*_aE@9IL{~b6L4AiSGwh zglp*Gr^JWM1U|7=mJO@@NgrQz{`}7DNLDVw5OOtnFY|+b8?6hKetpe9Je3E}4;D4i zeB&7q$#_s63zF1))yBB;eu<-CGJ_KKqLg4;C*UGNZKN@!pE8iHyJLM#AN9A+H@|t- z3-W7R98XD~#P5lXn#zg41&9LMlY8yoIkcp%20P52t3oyTCctB zzMm4EuuuPhWpLRVfE{%?iv6pWyd+oGEcWPiVbASoCQVl!u4jkG=Z=qMAI@Rn`#|UL zl>5Yrgr#3@gnJ4dlIwbP0<}9F>YvHrVwqOS^I?9G4G${gOd@n)IznV=|k#3$+o$ramk*BK5AYx>t*2eeF^>j0O z$0;vZsHT30-n%*0%Vro@*ECgJ@(aZa_?&1QZCZ~~fwaU^bk62dqKX4}W+$r!8{C|Q zy=(2rYH0)aUS_|K5b|{UIL=Dx9mi(?G{#S?SCSk!a-WGd6MaR(!n2jXtM|BY{q~m1 zd;X`09_<;EqpB3y#ToVKL)cVB>2vWJgXlXZ8nUmZrLt?h>Z2TD5CFjTYA#*XFZSNZ zGe&sTrQcu@1jgaYBiZx4AHOABY(=V3DMW-6>yVP_O)Q~h3^_fl1{tgP5aEZ5)8=g9 zGe^tSRlwr1ekF;p=6(I~Ju$!W_qQ@}(UzEz2C8aYT)8#NX4Q0&O-r<_YCml!v>(j$ zU&s4Qj|`lOsZ;-~I-Z^rd`6({h|R|z>epeEDW*EX``)m`2iEdrlSbt56Cl@8$|w&y zO{&zK@OWv57Y#=w!sTvavFE)vz91Zuy*0JQ6Ri3@e!8pmeY5KiGv;qWa^Xg3;WxJv zRYrp1u%`J7 zT7cki!;<>x#D{+`)@%4H2Wraa*Oh%Y(oW`iCaHJt$xT&6Sy{fb`Y1<7^7VaSb&hU^ ziEInaRHCnjIoI6eJ!0Gf`v=7@HL}jl*CUv|9X72+;|g!J3hGzx-;(s|b5TwB_$$#Z zS&>Acv;8pKpGFL`dN;X7hZsPVBp*^~Z9>U_T`&;&(i8IhN~WO}WKOHpvWCE{?B94n zpElQaQUMbiSP?WaAC>Wj*#DIT3{^%mm!82U@yUgH?@!qtdo`}IlFhyqrDd0}`i~48 zcyAWSh9-5(4f%&(SUm(Ukd|zrU8vlQiyS@O21eRqR&%Y&xcJle*&e-%;z4}^?pbHe zeG@vOFZWMSYf~E@{`RpKJ?XRW@NLZY%YSg~0zbd}_C~gPs$c5mz}@@EQf57Pc#rj( zopi_^8$Bw9ad&*`R(`aUz-=`ri+e;#r@PIzj!}F#VDox=_D;1^?<^MsKifW`cApQc zEJVc;e5TsvPu|5(ET!_%E>UR8cK6bfg6dmC&7h#US%+pt@XW2mcQk-+Uo_G7%V`67`#nZkirdfAnCM8q9kTF& z3DnccA2?N5qDhk8iW*}g4#~O1ijoaw9j0ryMq5Ltn7D-WdOt4pgDT+i%!&e+6J~sT zoG3pJ97Ymzb(>}EyEJ0$nG(o_UUv^z5A70B;V8WANkS0qZ046S4*MDGb;3ziX0al~ zQ}c4!?ptoOhwu3s1ECXY`*&a6mKWo((>~j;(1X`UY-ejq@wpDghDo##h*`!oAll3y zFEvwUkg>}dUmg7{tNg6)Uw_8fZydTy&Q+f3>}7Y$=rD%9fdOZ-cz}5xtgLpJsY|8) z`jd^9xpa5{>#OP#m+AAyDlduZ`PLvE^FioOp}7Nai{n9lGjRg&a=H5Z8)M?|jS~ zs->iIVy(I+Emz)(UfNjY-VXNooq$r!;wAesFs`nhTGsQq>enj2%5@Z)iEXBr+=OkN z3o6_*Z?@?|ISjgRQ!R*amZ>wx5v7d9-^S;v*va^^4qY}u#5>Gw8^ACW-5AL`T@S%5C@IR?0 zq}s4cbh5vfdvSfO{>|N)N1$;tJcQ5@Km5@Y(^3==_MY@y>5VT;L~6`S1wgMd&juwt z!W>_j{uWt(F^`pk zXMbVq{lN`$a*Fgi>@}`&V5Q_tvICEk-1`hW(yaNz6@gfoy6GmF)OMS24-kL#wVp z#90K*F)qbS;)`EoYuO!j^gQeena@jkcOBb`uOL1u92~XFI~(F@*XkP-R6zo30gL6Q zKL#qYUe>@PBKusgzm1n5V;#6x6Zaq~OS*FHPYCM?mHZuvdKH5m)-#Og6=e41SoEmG z8tVj0Viv#pffP%Qw!>i|?6b^giMQ6I!HbKP9UGVx<1~y);r!r=*Z6}sZ3Zgkd*#vs z%Q>v?%c`}X6cbueG>%SFr3z^Zx75x3tkuvDZ?MwY|KD`XWqI*P~cw$|qJ53{C~faEJW zm4x@I-q)E`o?_&(jqph+#e*!gv|^G$IqC47;z zyeOmD;SR?(UvyfxwbWYADupCECga32b+o^-Tl7=)o*7BMaz^)NI@$Zi#8WjnUV4r) z!MLGf$bF=YZ-RFF()E>&!AvlKA+2ltNZs+IF}MBR_AFZ%4yg$$C~4V{P9u7XqlR*^!PQFDb(kr#NK?S3T%e z?}LH)0OSXhm@GFE{-TUS6iPm^B`0>}TfI2E%q@@q`hX*-p0qIe|a8 zvt$~HcD4HCYgANqFNf7>#M_@V8r%0au{UFfJxiR-G0|9k;=~&957~@6>){Z{LsWvW z81B0W+My#0%;x3S+XCIjrqx$+0Sib3Sl`t0)fO8HcZ_?ZPsCakyz^irGOO(7PNK)# z#3{^hE=oTbz=-IjaDSRK6O`1wT!*>CV8|FgW-LISJJA!&Rroc5p(YHMrA>Fu!c@oB zYoYf;4xR`{t&iULPJAxOdOg+H0{W_DESF|oY(>i;uW3O2>=-9v<(ek#f-4TeAdP*$ zLA>eCB>1=oD->%@Z=LD}ndy06X`Ceg66?iU?WAJ5$PSXO-pqj8zBJr?=^#2fL&ZDY zkNq-R?>{Ps?|KRiHHNUdx>n>iDNQeo1~#mE7!64)VOnV8BNfeB#xtp-u4M>;V(Q!XkyLY5by|)(pLwpiW+*m;)jM zXWP~$gNSqN`Q2bu4>zguQ^E834Ic`$=pmw-9%~uzu=K>=EsWf-AFQiOKUOb6mw^u8 z8w!tNHo-wrX4S_h`P959$Ge&KU5tn^9;yPI?V-h#fqq&e`iwg!C1S5c7ZPOi53Kvl z{8OZ-UPlOCn9*hP?`O?hhtO7VoR!}6zw*;|3Uf;*j;rF9gT?hP4p>kndIPsj%(9Ut z^RB8q0agLn5suKU=&hBcZ8_`QD<5eX;R9NUxg4w;aoEv zZ|Y<)wlomd73yob{7rO6e{v;S+ZnjVNEyNe}kRq*4q9XP|gsuQB>={Ii73=E2-PP4w6O6l>s)JpFhxxYGYmW zw4k3l;-~wdW=81v(!$RJ$H8~@s2Ny7BmF3v{nrlg<+WW_@{B05qC-;e%!{)N)hAtq znYI1BUGN>ykuRk*#>!>yb=}y7-OI?Ybqg&Yv@0B43w7gZ>1{JN0PSDu0`?VxwjQsp zmltRh;Tzd-MCaU}-zIlX3^y_nxvzEX9Sa=V>)!)5U)LaNt1QH-JM{9E$&CEu&w?0W z37q^zK-MaVr?kCvJWXgsxO`@(YnUS*BJ_ zb)h;NCqz?`zcX#DxzM}ox{i+Yu>7(Ofw)?k=}n)bcUKKu#~-v{6*pElk0RU`BXOxk zTga(ZvbQYqBJNwxHP)O7ff=711+@BK+BOU_i&}W!5&+eI*pt`aYTSsZ65bEUf6oCN z(x07c41WaG*L2FU{S=(cB#oISiFdI6oIqLQ6&=@h!01Q0YFU#N5->R5wCGJCZzWB; zfQ#vesRxh0WNPgv5SfL6$x=x*Vai98-Q01;)U0C*r-#5)Pikq|ekQB_(elpfvXnm? zkrC0xsfL`ql%H+mL~dOUj|XvyoMT=V7FF>Nbyoz7knnq)_{^x@6tVndLtEZK^9iEh zwdvD8&zQq&vz3k3cm1V{S2=@QBUj=OTns*-31zpOW=SHy#@gs1E3`k?Dl`uqxJ*vH zmW;9+YBh0LuIldm*yv-fIktt7es z?mx$BlQ>`Y{QhWEEO@+Y!f%ysoqAX5g2^rTnT_VAz zPTUK_VRfa7)QF9r-nRCn@vR{8G*`Ovlum$z8M8+k>+(}MoX(=m5|B^F@u6#f#OeQB zS~+jso`1gFnuNX6cp0b{kYb~0)TnhOZ6}ZR)rA*%U^ELqa|0<(kd4}#9!+LY_ctsu z%G^6QcuDlR{n)9q%{m^%7V(=tjD=kBQu1o_=1b$)p6DywEj)y~Yeb&sZOJPiR>$*& zwiLXI@E9?bQ=EBA{fjP(pJy8Oo+WxI=}dbgpro_hY0;9>E~-o1@L`{S0+`T;L(LtM zH_(1rtn@`?b!wgu_Vppav-zNJC#W&re7-ZZLra?F;37+I`Bo#xj?|7>rkW(TU`qU! zi#)vA`OAEcx*!C}KJym+DvB8V^{sKz(a~$QAT(zzn4iZf?vXnYp}|TRAJj(bIC<>k zyx$pu3AG>|5(pmV2kH#B9R1e^8+`IhAKyQCb$JO%x?Ve1oUcaRzlW8|Zl=QdC25C| z?d)RJqx;~)fYYjWz1b^@kkSIl=X;*6zDL^DL!BD_^7G1UNFms?pAF>qo^$T54w z>98Wkw?>-7XO zKcfc5g@G%nloJJbM#ef+&fhmHwnbh%vHU9hnO-Ej}FK{EpcFWz$ z8@FF7nHd;6q<4DwH!<_#l%#08S+@x_{R>2Qa1;-y+x3s)Lwd{ zW7`n$h=(Fi=aHL$*XvMP{n$6R*x}|8AKa_YRDO6F*gq>GV0^h4<|~;&=}e~rh9s8jZ-4d=&jWo!-twJ@&jFG#O`bJn(V~H*s+X|&SV3||^fe?Srcf4hTN025i zIkfLZssDH06}>%g*Sd%_4d?LAd!)dkH78cl=q_iv<^%+eFU9Y=dID4rFB5*?x{a?H zj03w9%sv+%qkwdw&S19(H`ZoE%rdx`Kc4S?1msbbdCevG+K$}))cER;EQ;6MEmt)G zn-}zk_hWrW4@Zd`Ty^@&1=jnnMBa-o;}daTA2dVNzD=c_lsZ$dtJ+$ds3;xQ7Bm^; zQi`uQ!!j|cKb2qa)w`LklpvDO8$REb(OeziDHh-Uf{J}Vto(y4Di?o*uB^G6aJ&Fv z9J$CjmcF@XD6jHGgBNmSDK;0M+b&aoovU{Z8$wOxuAvzPuazabf^kxzUdbTGI58O~ zLy+j%a~Y^Mb4x6Cbx+*!iUQQ1=&yA%XN)@6WK0K?m9|zVF2M*yosDcA=}$(zHxBR+vm)Yk{3CrBw8uKh({XO= z!J0$nE+}iS{+x_Td$c_51~baZ>Nh^ang_qa>}vizQ;SV4!iHpWttBa;VvN8Kgsw69 zsvxWf(LMUZ*X3ePgCV%XEZ`XS$uAd+X6bJE``DGT$=sr`S`XC)J7QCb%CeEv?TI>^ z^ctCF>W;=3&yeod92NRxC{)HT5KauDdBbM7T~-+_8iEW+(!HS9jkxgX=j7oSnWHXE z%nB+R8h)%*e$g;tOs9wMKOHF1x!uM?3b|G*rtG2QU3b6PN7opWC zZY1!*n7@eBo$~cnM{_sMq9YEfs+$A4h(OR;3lYr@w$!V*1wRIL2cd-A_rZ1OabIPZ zR+HB}G|(*|_R%jQ&pZ?V5W=d8IIzZZJR`%K>q|0bBfk;(6}C@b5PiZg!6oe7|K%i~ zjez&fRz2^8f+d{2Og>#?1?pU8##fT>nXlC%CgN}J1RZX^`Jc%P4$E=pZQY7#dy4Gf z>Yg;}I3pCp#A=L*?h&{XZ=ZHp%ltv4Xx)=T3rqhQv*#%}9=XLwhiE2L_C>n8YmG9I zBWC-{xL`X`7yL~Syatao zWUEW&>4@*susoa^n?A&*>OzF=R8?cROGOFUNsYe#VAJHDw4LpCJkB}b@LikF>LvBM zeOb{R>_Q(gIskvQ&_y>d|7HC4r!RehXl($-@f)2~&VHtRzUr+OW1B@HnpO*h#z<2$ zTB~=+lgMHxu{C!?uFnn9{j5Ht0^~Bx{?z~_pk7xPlMFcJ#ViiqY^NdB=5;dj5CQ-yt%5mx62tpX#|{ICBWRLYZ7oT&<&K6m5rA0e zy6QUqH^0oLe!q4A04Iy3VX|Tw0)V(2DIzHZUZFy^Q~|cl&ujH zl{yxiFZKnFsewTv4sWtH#xWzphiF`bWBhY_aHMT?z0>JfJ=aZs~8+iyU!7#0OD%~aWlyUz?MoWN;ljZqmJEAJl6LBCWL z03)gmeYJT^Jsuo_(xj|6B+3-JstS|VQn`m;Y&hy%<^5g80sy+mC(BhCiG>+O8XVa` zS?H$kM8;-*@?PjDK_4P_h%bqYJ-+3ML}BDa=&%4q>e-LHa)$VEe4;|xjU-vQ$0jgo zvWs6hgm?;%dzmo7wyF&QHSz6!ZyW1~iYK<-{0!AE&*S>Yt=<+##6WxI5K=YWgOfep zh0miK^%~P!x@IM_{l`g}B%Ki}fO4kin9F%E8i3J6;{=cLX*~}y)m8J@HHL1(UmR|C zgEpBm5$oD}9OEXho+;pLsGBOvpZ40HTI#|@%ZcY1oz$ny`z)eF49cVia~v8IYvdEt ztN^Ao9>Ff`8ui?wc%He`grE1SCIXc1*=6?h7(ZbXF&OH!o{bv6+mki^Y`J)i=qKwH zj$%Z3Z}P!HalYx>UW&JO$@VE=z_7ZIOD@Bk)6;;(}i+90LqaZRRwcFV(&IstGIh6md1&+ zV-7viD@&)#XOr#8_;SRP06;%|?jQ9<-58Zx@=qL{GtXNUqX$|~1EYWnCY_ltKEa*} zLE>MPzY(%-bf!pR=_b$bhIB3EZiDjZqbG<53N;(*c2~DsQkSNAzwR?>ZBMf;eRb2n zt`fv2U>E$R`eISEnAw!&`De{#qoZJ>e39Rq+Bt*jVFGe zh^k%T0P*KaYEIp)^<^z1vgw7&s zyhn@zy;#qm@%rE1S>orUFig+VUWOgG+9v8}b0ZOeKzR@=QD{qei6s+-a)ZHR9Ek*v z7d=T9lbR|7xLQoymtxjNRm*|ExYp|RnoO*8yHFtwhWh-0iyx%$g|vYB29_!D}6{;j{%7l%|mNXOV3MG8D;X13d#AsmdqN9`s-BKZ&%&Oh6|fA z{=Rw+N1p$(8kdM~%3;YY2|14r@(f4wB_QU7ObHnq$|r+)rT&S2jnLHPmc20Cst_fD zkfuorOMWGu^A-QJiS#?-aZG1=NM@LseDwgj(<-HS}aQPenhKpTI zY?4Cp)WVQjU5CI)8?`aWXAs!6^8}5ZS0mRTnncg~f6<-_Q$|C(;vI!`4ngEN!qzJN z0boo~)Ihq*kyaQfldut^MY>>WBZ>PNbAZLR3f%fWj2Jg%yP8bnPB;Bwp|?7!+-(EC z&<0=@OQSgGN(TTQ2tAd)4M&g`bK8M54g>?K9acznL#i#B1OTXKZ;S4j);71PP1=$n zI7$i-)QjUJ{3Yud)YnGT-;pda4y=3Nf2h6Cj|T`nqJCG#WQ~-63I@r2WR7L)g$`4+ zE5r@6D6#yF%2gucmI^ld&&OtFH76P5d;10f5f1cqv$J_5vR_73Xml8nfw;Z_T&hIm zt3Xsg%fnVHeR^AtO;W*5zR#t8=onGkVt%!V)b$%m)BuPlku?Mt5*_V$H52!vWUBPW z2`uPo_LY<#!3UF$LV6{u$lLfcgH=$u7Tl6U-d$E?<}Qh_#1N2!3BBnIbb_FtGRb0u zc2*c*KXTxcCFYSVrUSil8sI1#0Or*&);fZ*o&>-~#1_dZp6I0OnBQVvF0cA9eHny-`2-2KEYf-UwJY znn3jPBmo!>OrEt+Ez=V~E_KjO*(>lIDZu&AVx&TgQTkttA)}cAi;5Zb)X_`WG=`y% ze8^5fcd^yF0B3OhpLgdu6o#SzYy}(>hyg(F1Ce540$_2VT0v@h1bRD{)_}hhf_Dqn9v(FE#rNJ^KVfhVCFL9dmJ1MX0MKmO+T65%`H$`dUZ0Fk8P?+_H||Jr=0-ae%ZSpvw^6|hXX z5cttM+2W@-q$N=Z1R4Sb>gz#jphsk=tCxjMz6@YLpbk1JfcKy@2Gr=k8d)fO^vM8f zV+#a9v#CGr{zv5hLc<7ZsoVBs`U1WMI=r5OD6aqT^-tLtSAnMjGcf%FvWjYk?;nQP zqK_d8ipO7pzr6fY-bdutorkQgJch(gpwq`j2*?j;wOGZrVp^98myluqiYQ zxIa1A+yJKK0-@!(fttZ^0s!C*EwJL>=!dwC^J2n9^oWm$04dbpUwB%gP^eK_2mtZ} zHXx6&gcLmhfHDKdP6-wQu%e=Zp6H|o7 zqR_)H920={M@JSwn3Pj80ssW)k~F|)CmoKb-dXN462eYu5zP%$wDGl2L3a{!19vj3XFE3N{-=Rg@{h$X)$tObMT zpa&CxhC|bP52YL#RLONQ3q^mb8?gS;z3AWJ#~8%L1pshiQxt^-sp=~QkHR*@ z4kSJ+0MOYdHBzB=pxWEq{^_DCXo>!EkUpDDA%~)RjQpl4|A_Ocw0|W${eqY8mQ~&# zZkadYZA6O#+nDWb0AK|L1bW5NI8ZC;9=)vK7x=HB6#O|dZ_I5Ilu`zOIXMSt)g9cY z2?KzFMHHX`m_z1<4BEgBu)Tus0RZWunaq{gG1(fc9bbK!LOArXj!=by)zW zhblv;9M-~n4>4GBoPuOEyH(3rMgdF;UPgr$(P|eqfT=CO-$Hodgc^bvX@Q*UMVi4Vd0~Yd0s!?VkEJtt`~fWkfV5cA0|3@SMxkE;V4S?z@J0ck z7C@%CdxwaO816e40FOc_&kqn~74b2Hpw$H5L5YN0@jd`I>7!zxa(I9mG!9R!v7?`< zO+mF70;jM7fD~X)0gNEtBLJfyz5~EC_zFQqgfjAiG8+0PMgZ~3Ba8pOp=CTq;oI^d zJq19SStZa;2-0eUAL}QgZ9^;o4_7>8qNM(VE=CdLj01@PWeC4|3}O+0Am8F0Z|)0S;vq=JHkI~-NN zj9i}qraJKDF#Y)#$|nQ?PB5?_fBWDg=K#1xc|~0lPXWv*iluor0MK*`H=6;6 z0|06TVBtc85=DIb!9ETE6!Ve9p1o&*5CezdEi+K9fdTxUuXIU@@gnVTR9o9nD$tB0 z4sP%PAS{%4D_o1xB}OK=VCwb&!0wwYfVl1M>v;;$4}>HF;CSLUeqb0LzwH2B=j6@N zXHZli1e7K}wEe#c+*56VmjJ-n55*9G;X>JBhR(G<;*63($ISwO>Y}=_f%94r0>F5s zLyz#VU7BrAWkhlP4l_sjy!!+dB#!JO3IJ@K=O-nAhVUE!mk0m^6@~zaK1mdsLqij= zGgStp+MryZ(<}M?f8z50N7@)>psIRJ3IM8YBw9v~wFEK)fOf2IE+XSjBz9$J3`h&W z8C;`yO6!M{1kmUjp#xqSr~p8kP;@&`ngZ(I=>PU$hw7Rx;-klZu^~Md1wIx1V`}!7 z38L}JlPTQ7--wEmf7SiJ$p0^$VnZwbUnQVr07{|&S~li?O9uZn;ehN;Xg`qv%^dZYw= zp}66H2M|K=jR0Pn5C9p|QjG$B1wd_pk_dy6DETK6|3$|B;=vBp zKp}!~S%A>!_3aMy$){gUq6Scp;5LBT7&hD$w;cokL(oA;;LCt_nDK}OUSb8#LyXxy zI(|!vzc7yi02+Uc)VF{vW;FnZ3&2Eki+%^d#sUx^F$fX>lw?`}HjnZiEtagfUHYh9 zPvQj_K05p74L3Z`&PsO-)fz?%^@=aqc$Tsm!S!L-hgn z769)QZU4iso4Zn*!dodwNbaAYKC}$nXJ$(c04QS#6^C9K9*TpX0Th+VeUe50)z=9C z+WXj@dY5p@939Q{%vz5=G{t%eDXjb{G`#tXhz1%u@pnGTNjxTO=5fzv5o=KF<3}s` zkb{_gv;Y)kFR`~T0qov&D8b%fGzrN2dK>m_067WD7b;)6`|?z+k9qh1$NUT$39Y36 zTfUH?!&gu+1Are@k~X$@^aFfH%Mk9^(A{XeN`SPklsv}i_dOrN#Pj8WKut zr@1SEFJW98NfIuA^#RHSI$O{~{UXKz;x0DG7E1qX3|Y3jhFG3g|%}))NX2Jvr24`WyV; z9@)^2{1=;l^?PCTl*+vFFN_eOtq9maA#K$D|H;?C0{V*s9JDz9YbuBrisuN$3;!GM z-!9^#cs=?JJb(QAlk*=S;5KjoI&_r{EeJFUgoSqWA1OfiW7OjYqXLD6YL{Ng-?0C; zcKL##&1S#_YyXtJy{HWFsXvh>@TrOdXYdPhVQo)dJsFI^NAj8w=e`i0-%u?0FW^sY zcr=8{kEx*dupt1dAQu4UAeadUBLlEsp(H|~B!>Qp#6PqPbMy%d%2reqDtm-45TWyQ z(Ty4ifB`R+!33RwVF740xobzT1>6|`S!%{L1m=j(q@VODn}dupwXYe|xV`%)R~7eT zC=(%5$8hLrXdt~P^k@mdBSJYTm}3Gsn4_2wyjW%cEfGqlNi5j_@yC;N{iR+1IrBn# zSnaEZfPfUgyOH@v^#Z*q9QD=v2g(1@z-ZZciJ>hY2^vNLG49V|00OamnD}hAE4rCr zI-jwM8%-;i>E3Sk=*a=be&8yAp&{7uG$i4R`4J2Ln`4+OREiThMgYLr;neEdi=WSO zVPEQ$^%IemFHy)a0Z%~LH;Sdbv(fuMB~Ja(E&sie5erFPhO~+j^xPh2Y!O;?I>96f zK@d3rKra?Bj>C3IB2{7=X+x^MV;Gm%Z+5j>0om|)3YBv;1h>0U&?DxN9qb0Kyz53x zk#@Sfc#)P+sCKvW+@CHZxZ7=>6$Gw0Y7+s-E4=5$We`sLLIBW$nf(7~dkf%5mSsz@ z#4ToKW@ct)sm07pEoNqB#uh`1Tg=SN%xW<+jP8ARXWus)+x_!qx2(*n$}=ncq({Wb zlV0T+P<(6MeprGS+kSu+uvkMs@r1g&l~-fr3!uNi#{uQoz-a!T@EyYR;nz$q8a*9^z-f&D&+4zfeVhR5OYO{g>A-$!HU0{GTwOf#1J5gwg-|Lq3bZ zzZw7C9|!=Hvo!DPD*%@-kCp#;{BIxU|Kz~Ol)oGZz5nCpOZ%$hYJQ&wK+BKV|79bO zPWWdNiUQ!TEEYV%m(;lmb^h`k^yPW{AJ2c$;1>hM$NaPRUmf#r&!jJ;Ab?k3fcf8M z_?-fTnZHcHmid6M^jsr^>hRwij6nMVa^j0n(0&V`i~@g|awN=wDB}Os(sr@JqSjEAIUG>c=nWRw1Q$GcaU22|H56 z{+Qg|UpTLmR^tFvfD^yJ1OyBM!&fG50^w`)W0L?lFiRos0V`j}1c(>Ru%kHt7Z?7E z48N*Y{%-QCRVeYc9xj>oz0Cj1@OO|z8&Ef~{)^=c0Z8d;yWUsCzsCP^6l}xi(LMUn*7xy- z`sh9*+{;M(I&#!a+m>*w~!Ppjaj1mVNED>sQG9t$L^(iECJG15**Mff( z``H*%RqIdd;a~=-11n2m#u^2K2Dp;(j^9qaVEy>^N-Grv{(;>NcSt1bC!ql>F%PHP z+?Qg%6^XiH6o}l(`m)1YB0H-6_!FU^a3onpe|MT={m-T(`kYL?26UUA$6B8Pw$~j5UUCTp>Pa&o}~)f@lZ0DQODSipuXhz zjTYTvrVFCEf{C*@Tp72mg8>Aq#*A41KK(`xYq($C1M z46r8n)}_yKYv>MqDv<@SQ}#Vc>WdUp*>3??**?7ekLin=WEXLIBBFW?G%FBgQSU!s zYQtQu<6|fpn@(FxU~Bf_@JONX%$0vm)ULX0GP29*YBu#NgDn-4{Vt3EONpJ&r_zdG zq0tQuK~1z2)jn4gwu&bCQ=I&28X%6XlO0wIDOSOAMJLVn;cqEhkwG9zPJ~h1tynHc z1GLngCeS~F`9UR!TT>~V@otk%fQJ~+dHD-TwRxH#dSnD1U-syEkb|9blao!wm{P44 zg!(Zh&`)i~w%q_|AluEP{A4IUlxBF~qd;DS*%;>hm@QI~z!(@;mN4QEf@o3@~P%paz*&u52W;=prguQ>|Y`*f+8 z5Eugz4q~FWEBx94;>1$p#0O%V3yyvTB75~Xhd3FK7U@H`7k>J;^z)yg+iM66KV1*u z@fbJZS2X75T80Xi7S2~sv5UQon;uxM=wt4zqO9oOR|c>b30u`mSo5PG=LAYdx2}v< zsF1~cUoQq%r_To#@tx^Fpkrq4Zn?bW)uL%pd#eTR5P5S?mW|9r2bKt>Vz>!KXf*7u z-EIl^BSVq=j)oNR&1iJoK1pCoCXf-GmC(mQf|sNdf!9RI5|Ek;oZ@NkP#;o^;3iL$ zCfXHaR|l-rw=qhPg8OO0SZG)s8nD|!-|{8W(M3QCV4)&jhye%3JDBcrt()xfHGWtd z=fd4w^p%Y?)*v`CYOQ0sr()i~MFN;xR10Xc28>#V#^DNeFHPK&dP~Qa--n_1py$bJ z=XZGDeO-j^$9~K{=4M>|%0MyxnXu(b7s(rc-1 zb1C)cxC_!&loSZuzy_Np7#KPe%?>V6fC8Jy>QnM?;;GYs@VBG6?z8&5EB-&@wst}a zdf$)t%{gNi2TMhEq3R6%W7kpF6FGeR+p&cAyI>y!LrJK9+%q%|NCbQv&KH_%@(V(7 zZs_QkFRLNlfg&+!cf+&3mGNlE6;cqgGsT8*r$mGLQ~l6K8*(`A5&lG; z$ZF?1OAZvF$sk_dq3hn>vO&3!i~M{Scjh+r@X0iyX9qN-O^+pyrmOa*s$s*^$Fh z{%IDkru3(X@_Xm^b{r{CSFk@-Tcqs9cdACio=caz-ku2gz|<@i3E=Y-sqvd*Pvwr=P_E9$Nz{j`kQit)WM(?pRRp z@AF|UfoOqPI@@!5xPd3+3Oej5{Ozw8y*FP45QQ59@SFuNPLqBN@e9T4oMstTs2ebt z!rEL5$W<=f1ZUJX>-33bpK&hMQ-*F#Pr_(5kQ55MCPrLDDy}R+OeCxfmQI*jWbp<)RX(CSNm$hF9Ia;7S z-UcV!1h8g@-YqikUi&H|QRNkBUM#>rs+32p88_dSa35RL4%PQ1!+!`hlPUzAetNTAEQk2%wrF^BzvVDh(@-FFlS z>6nPt)8Y&Rl~et!sfd+&M9BZlNWs>GjrVu-^EzFm@)uw>SHcznV_G^?w4VnHcT7$I zOYozsm#r2FwhV)LQnEbo!sL3T7Az?)@c=2fifHJ{suuU+j~}K7>vLb*%cTtYZjlvQ}R&{Ckw6+UqtsX#&?A(5p2XagG7ynENfKF_!&6lap=L6fdQB{NX7dkX7Td+ z2hHNuW->5fb}!H;!c$Qpnf3N=%M+v@Hv^iT4~fW+IA&IF2}>|~aY|qR=;y9=h8DM{ z4IW+RBJ$dx3RsNw`CN1rMGkJPl5?f9*2@{QSm7?FoR`nAApl0!6!+s^L$ZCabohg5 zX0fDuz!QbaEUM@IwN5R?032DDm0aSE6Il|~!8#0*8u zs<#lv$gpsb6S0w`3T!@a#L*cMm|+w0EFkqbb1G3+4oET5QMsJOA)Ltdc(HiZWCT9~ zL2@c7vF+}B*YEisJ{f9c-)1?*u8v9Ku3}szed4f!r0de<;2RMM;LZxajm5w4O^>Zq zv*A4()Z$h-$g#R9z_vXMK{72_t-O!99sOx1#g~%`^B0$kjJ>TgtsL&E#X8(@xKGq1 ztXixUjucCUeYiiO55_HW?q-q#;{J>d14pR z`zd|A9&A`3>!v6UWeg}gO7g|^g7Od@BbP21_|sv+H9(|(&|uJ-*n=|_JFV@j0oA~F zX+Ojlu7Wb3P@wSxIU?=LuN*u)GW-sp}xA=ECZ?G`k& znO1Cg3pu9oIGYN!u_96;+U7xs*aHI{T8rD?j=0h;`JCr|kG0xQ&K%T#7@|l7G{PKG zhmD<`tLt}Ww06!VME~i`E2%EjB zN_raTYv;PKne)AO|CtRNi;y3xs^`n~iarj?Q5#OuW+`E!SMdvp?}ryUz_J$?CQwuv zt}&tB+AuUNuD2BWJ&PuHz!tu(;_DvZOGMC;WyBZW*mFrp&onXd#)*l<&9D;}!{e6w zXE+j`SF`?Ie(p#ME<{dkc5-#PcVhmVBMae9q##D_^D@#q8^dFe?+H_Savj(}ha)u) zXK!#nyru@Zv=p-EK=xX{`J^2h*F{TSzFF3lZ1 zIPtNq+Ocy@$V#$=)xd(S#qdbOY}ucc<(o?M)b8-s2mpi2M?Z)r0#9~mkIs8Bcx#qG z6&A<$t{ZW&d*!RIlN4@8$ZI1HmWG6Mw;i5LIS$_JewB=2^*3G;G~C0z-{B z&ShNw>?A+0%7WcS1V4woSxSu`{6;0>5huMMe%qd;?^pdiO#lUWQo5y^}TDF!lnpvxX4Z^5N_79ky;RLcY+k zFdYzGTLy0Ouq1@@m~++6i6vq?R@~zYwgc6b{d_+7a(VGglZ!;rXfkc!ltUe7anePAR6MsINcis^V(W*3FLBC zxJ;UWB>MbeMwL;Oz>I<`DYoW`c>^(BUoH~K;YB+Hmrji+4UZ|^EW_*(!D?nbhMTZK z>i=oqalyuy{4#2rg~as5$Xe8QzYW zy^rJt>+Z#OD7hYi!9DuOrO_n6>GG*=ZC4^#CyaGzNZlrwI{%JF5eNslRmi%y43BO0;BBLZl*YdV-8!iz#_sGg zETFT=cnZLdA4duqr=eXl@)~TGRCx-}&fbe*%Rc4gH=XTL16P`);B%9D*ajm5c)z|NT zylZwH{%{d>d^Kh;yjM;Qg{rx54tD*sjHYcDDM!14>i3c>;UEqLhN%U9(MAPKv7PNl z*YKpKysNHnT=*DK}%ObJwDXjIgQP`X*?+UdWl`PjE!z|p?7u38F(r01wcN&i4i zBK@vj$0JuP$})<*o5Rl|EO5BxNLv!rcP_WLNrBH(0ePQU4I`CpuH1<^&c% zYkM?=wErCU{ukSi?UPLF?V_xf<;VME9Nm24JKgrlYj2=jqSzNfhUJCILQtmISS4sJ ziGH9=dyHc8U*-{@AHmWKbItplR()q~;h?qTX^{$kB_P0oT69Os^IFoH+a35J^=)%G zA;UHWso=+D7K!MPY$X}X2LaaH5BP%3WSI8J>&K*SNZoYiWxo{07Db!{by_G2X>YBo zlvGif;svNkS=%nsuK6fxE(wiY2=@bL4f3a*z}JUPT$*9}X2ap;JQ98H-CST3K4D~? zU<)<$pNxGtUj^DLClTs^4QRUti+Z2dsYboGJh+u^$<~YEW^Wy7>+mz$f#JF^_O^!b zM)m|sA7t;sYFAZ>nf4C2ehos0YEK9&cBjxNkD_4C`Prr#zA5s2|7H4tWwwg&FwE80 zrv0h?jKP?l7%$`v1Fron;8~KLM=Ud}o(dKaEqmp;^h4I-LK7k<-*3Kss|(Z7?E|>{ z&AHuOnstCPouBERE`-n!c^mFKNSoepQFA6XAajMg*eTzC|w&oc*+_Pc|#ig)% zgJv)91Ed?C-g7yr$rEl2uFc)NVY|Cd5DcKx{tDqEe_n>sQs96Q&pJC?3O>~g+QVMW ze-c?2NUFMDUrLZtYwJ>><{L|g?%X<0-2Gwuh&D6fb7YcN2grn|oRV_Z4aT1I2fPa} z>(5T!bKXeg`Yp>_dqH;Z)nUOk^~!aATbW>R@Rg$ZF!DGD7MdZP(CgE>q5M=}gC2Tr zwS8K<$ISU?FlF#nl%JNz8aw<51SOf*q}&LF$Ku`zF3s%=tS)@{$U2bkVpL6pC&VEs zvM_%ATs!m7?*&wl6G7Wg=~P97WQEqQ*5Q#$kT38?K;Y*VPYqVpm=NH|dbG(~C!79!^`G%N9* z@Zz_?$L)#JqiL0sQnljoR-D9z+cI9n)B^`y@@km92qy}RDZbIZcC|ayRWa)fSaH)} zEo1TPkOeZ7@~m}3onQktFJ*Vot9F&6NbN|2XJ=Nb;pFRP27;%=@=ow8R|gfN$K4^q z1M$oxQLXS$og&_Rglq09oMq~FzY-7ZStMTG_J6YYVl@(Wzj!Vgae@V4JQ`TLveznT zgjC8E%D!Z>px2`!k7%I#qpkIYn~SW<2&=@Vsx6LM%%2{LHNcr*TNyaLWFF*}dgD1k z$Zs47bU3OB9}H3&=?DIS06yfD7`Ir`a)w}kUoR+g0Ov{78sYHq>(kQLoW)KxgnCx| zkQElc4`FQu+g9$5XkL^`>U&%K-3I$(6w+ek$^g$upOTTw9!pIt?&&cP%Tv(zXRI$` z8OEki0l4y;nZzSlzgn5Iro2oekmU~8!@xWKYkj*MmQ+{wFi;(->{vp7i4MK_19CD! zs7Zr}TivX*k}&-yx8Y4+_e+)3z^f9cpfat+{Syc#foPpdU^Bp6@@wVz<1>`N~%z|b%=fq9iK9MX*RNY$x6A3?6 z9s1D_Fu!G#=NZl8j}=`q78yt?vOU=Kslmeq5(}hNxdl~P7E`b_z!eLV3{yz3>zkx> zq*vlOap;ji4_MYZBsi9OAg^LDZN8Sr_@UQ-=*0_g!oa#>ZMK6)`pKT8#CAQtYmy@> zS63e(k(n03%TutkDJU7F*Yj-ceyrY=rNqYM@6TR-H%V~8Naf24W)EO-$?lL=KOUn@-Gr1lr_wOD&Vj+sKn?i0NT0IJXph_nXGpas z0ZBTBnj9r?Thoe2%-gEowu0{lDHeAX4Ix!koQJ>UBYzt4lOYY%K?Gx&%|CueF~a<6 zO^5*P)eKi}*%s>10k`s6&gsoc|Sc`MgeRG$}ls9JXG}!#A%R0`odZ+vj=@MTrpA6r7xi2X#@1m`x2TC?Ef?gJmP#-hfPFnkBE`~Y23}hD z{yYD{I{+~{ghg={lZ{!PbikY#<#bPU@Bmx~x+zmq?z!!rNYI5r+hNf-j)=MMEb5MS zItHD@|4nzR{izzi_)7hV3r;u@YnjCCH|Od7w#R_^{uEtR^XJ<<=1wvjmEW z79lZJ5E~kiW^?Fl1LXI5!0d>g20lxO)Y1OBnfR!GC}ra%qBT0F>(-?@VhW34$U(3w zo;gBXnH8c~*o7KW*Gl>xj?H25YZ3x87;RP7rkCkSXvXikfMxrk#fI?JxpDK}_Y8LS z6eN74V<^@pPdIh_HNAtEugf>lBAfVBKkX(fsj|>-=}9?b*eR!MnXixEWPo}weP%$V zY1fX;INR^^WDe44)KJ}G(=csR$Azux0}9Pdgx1rreD*?+LnFY!ed@aqA+_&wdA8Ue zc)4avd7!&vmbUeFF?mbB;WfW$jc=zpLhHYDGgU(03#7`zzvMb$UAY*+@%v2FPjgIG zjdqmV)7cnS2V%<8=H;&0(f`3qQc=|am~VHSpARcKrOE@Mylx4 zlURNNCxN!3j?SQ0!Ml!ym+eJUqp1Ot+Qg0B5+AD666)|F9Wk(CIgc`4M7HJXx6Q#~ zG4`>Vpm@A)K8sC4$P#apyWj&hlMT^jl&}&G+>2#P(gu|!P^|kA(cUJmkUvsbzx!fS z*WRij@kLP@dk`!(J*WLEHS{`_;>g&{`AN~X0%gy{dGySe6fLE4A}yy9;cnTpaeR3%TLJW zkWF%-{3+AqTa1JOf&Ze97ATrg@&t_e8*ntvr8#o7D=Y2>5niDdby z4Nj9?hFZwTEIh5_Z6pw?pn|QS{3d}(KjShCm*qr=zPCPNVI(I7b#jf?w9_2_K7E^z z$A@=Pg1T0$fUg9cTI|Ev;hXi(r+w4=p1DWT_VqB9A3+1WS`=#C>yX7JPw>z#5vcvY z>W=Y6@>a}67HNd+3+JSY-!yA9pvDjiom z$F}^gghOA3bSDO@J!4b5!V%qrp24s(S%=7Zj!sgP<-n!6SmvHFLWqIeyBl0t0Or*4 z7^?zp9EzrkA$odLut6G5WZhNfX0uqTT&MK$bCFVBN0Yx}(&kIRG2maxjz^weG95AxGSwoUFbsY3e0^urj*f?| z-vs2ZyGgNp7wA2C#EUcCS?6$`fnc`k3$|z(YlsIU!rmj}NBuTq)_a_L;bwS2=t`qk zo;4pwS$7sVbq*JgKX{?!avUF~MZ*{!%Q^U(oKG*F^tCHt5JO-(9}vcY(_yjKWTn+I z+$)PFp86V-ws3Q1mMU-+@)g_^nO)|k<8wA*kSaxhzM~kkdZi}~s=u_oA*D~Nb zr8s)HUW9Y2kC@Q+S<28+@LwZ+IOTF}mpM#lv=GCKra%akXw6BD#biN=ZUuY~Qm(r- zbN6GgEN>?rZ}lHiDC}u&sD6v^5J4wzR&UiT5gDb#>UwN*+2qe5xjxU7rk<~GTwxkV zcu!;dGp)G1SNb5&X{^BU1RLvru9+yvfZ6r{X??*g8pfs$ruVZESefEXv#^?VNg&LB zzkhgTtdD{un%USolLgB$-rK6@`HyonZChW{F_H0_VlWL$*94jILMYO!{LdW*#QlJX zRMF+@nl_dO!*0S!W)r3muq$ImZv8Qb-{G&Vx$Oa=x2Dj(33+k}8N24G!k`xyJEy{VAG-bW6>M&;sGVT6VH9F-~SFCI2 z-~(^M_Z^4fc`rl{_7lZSoB69Z=blnBo=Ray285@=%C75!Ux-}ynrw24CO(aRH)FXW zehF5^a3?+~15}1>l{cZLe3b(Dr#20r!2&tHTzk~>EoV;5@W*va+r$Fx;UfFEI6sA! z5s3L2l%YGt>A@md2Rk4X97`KQQnZLt;MU%%>IX67kYa_xv+a&eij&aM7z;^Sc9;%A zBQ|EY2T#ZOGHK12SPW?l8|htjQ{pWLPBB<>Fw5C{t*Td=BoAvPr$98NRxKK=T!$yt z2vu^Sw=dDj;52EG*3H{{CE!fm4ByDzCL%_)b3)4$*AA;o+;I%M0yt)#VzqYV3owPd z$`kO}5zPxYw=!6yx`xbw1Q|0mG~lhfVny@M70R;|&`}gXStttm#K4oW@UzbG>vklg zFw>Fgqa~Q0pp`-RrJtTACc7;2$bsHspx(IPsGQVOsD2bL)h@>#wY2W-HnjvoR6y=0 zk=$7k*57y;)@#N=+-$U8bH}kaFWYGxW0Qt*-pl8vj|{Bb6cLP9Gs8-mq%QxYFmWXx zXfRA4CCWaOG7ESz0ReT|56Eyx7;9m5SXb+8!z6si2z{vN8JbcOSmfCIk&t+}w~*7= z9!>0sytH}6^W<9jcsgd3C8+2#W|7Ee8+)Y9QxpM0i~?z1V6f#Jk15lm1y92qV_*BH222@9)rDSe!9-vc(r z1~5++_+)?D$x$#(TZj}5BC>KgAm13b92gMZH)|=@iGjEyb@p**7x2=HrJa2!?s}2k zsdSqVXN_#^ONR*~l(HyiBx$J3`W}5T)SV-Vc06zO{!EZ|J-9+7;hFw#e!q{SCBGI2 z+Lnc_x8O)0BZBrXVQSZ)4W|S?eaaeB>|8s6B3o&(MoC$uXDzx2U5hs3m;4T*o@q}I z+YMrlY3Fjdpi@=z0fP^s1W}Dqt}f#Jkx@-P=fL9lrt=(MUe++Trg&4A)jwe|;8NqE zgaB@IBj&|&KJBS1A`jt1NnTkwU~*e`3>Px9vBVG_BDk&0j`54CO7AyEl`uOz!PcZT zgh)oTS7P-RA;@8!y~Qu~&|{H&m5O^YZI!d@J_E#YF`-!YWbF&)Z4*z;?z_R#qO8vNaBsaoc`A%jXfxV7$pMZu3weJez}-m zl=tba6??(rIQ1;jD(E_E8INsK&bj8)YH)OqR3b05J&@a?rKco|BrCSMXR%18&5UzBPJE4hqb3Ib;L3AJ285lFU zrNa_D}ikuz}GwLsUn(hA!m^2=Z54&s2081p+*R3 zs)r6b*aWQcf~(^aDPh?zNDCSE4)Co}b=mG!QvC(3l;iy=@n2BhLA2@dF-otq513_Z z(A7kH2<|AUcK zM{8jWHY2*7d05!vDPdlvl)BCbrE9P}JdZ?z9p{XSgFMqti{v?_l>{zp0Ral|M*fC4 ziW3MF?28$TosL)fLPC?I1n#3$iq@n1N?$>Sb!_Z*v@z)8usmqdR1MfPXOVVP$m+=s zJ4v}QE1oNnXT@MLkDq2#+Zv)wb8UYRHxZhm3cfRKw5aAbaCGXxjDpb)zt4oa5nyk~HX)|z_%V*`g ze@4Yf!B;X<82lCx^6NPH$7cws6>Y~%VG4#WnuHp@RE<$Qg3q}QUSN4LhK=wo`RmoS zx#n@A$L~TVrxYTpL;p2eVqhXv#n;CJFP4x7TU!gejSi! zFo*;kcP|*%H&zujbz6b-d$v7;F?+)P%ZIUNhGSDJSs7egD>)(!k&t?X4$)~kpPgHS;OGnSsjQJL>Ui1=1i*tD?^3^TC8 zlymDno_cIVJjZ~3V>Z3z9#jw*FY5fq+ysgD6D0KdBdo3n@BdLTdHjk-MM%OMy3p3KRgZ<`XFGEXI@*q!%IW@*}3~-MbkT z%f;*?GYLHv5(VvLs2Mc@S9o9@ KEUTDIb9?AJxv%5ddgxxqhb;~Wj%-Rkc{FcL>F7SH z&)lA46)93EcY<2F14p9H?WOdxK2)}*A=G`7!omexXaiqvCn8VkLA^F~TEJ1j^*F>l zw&ZUyX4>R!S&_5fZE#q>GuVGaz-C-|Z@pNX|EYKYQNXsdsOp?0Rvf||g4|Sw`Rp-s zR1UW1Ir4f6V>}t!Um4x^S;~Apq7hyQ`?$aqZd|w`Hk_f6-llp;m+ZA!x}@0Nj%M$a zNA(Gecwd87e{2-%AmS!z?cGqysyvWpTmLbG%L)#;6qdv44^@%D<*Mdw>zNePZ1;QL zcJQ$cJ?8h<$!dci^%Wyw-WD1U90%3mThHpFb_8&4bX@{04dPkRV8hpf3hB{7d}5U7 zfr3?hg+m0lemq~fiQt`*g@nzg1{sbE5iW@`D zR$C77y4(e7J;Q`J}dSdq| z-4nfJINYo~y(3iivIqLt(BI~dQebD*g-^2+@)pA!R#P%B65QD6RP$LovxTCBCqRVp zryyg^`SAGcqUoV$@Si&Sf$1b(b!XCC1!k9Q5YkSVit30?is9fTA#ptoWk|F|U#w8d zCgH`7(tFqDEU(!Ya#Ac8O9+qVGahExk9vN?HxU2k0I=vp{J?FUY; z7M1$2%IU1>2yW$Y7O0p|Q4C0>CRQ5=^H*MJ6{pjJ=RH24%$z2E@Q&)K*9{sc+;TDxOCN*SNzD?%oe2Y_G zUzPHrT4DKdr@nWfbspdGI_-HD`45$FeQTM8DX^#|n_d?FkPmrCKrXdz(fb&>KoLh* zPrViU+YLP$!OaDfEK@6*4JVo7E_Z8&_UgpR#)3>_;`embnBL%qt zH(}ppNFpd2bFGQhrSA~c+ArHuQ34N(hUIfqc7)tJfb@;jYGD(Vu>C>74O2dn?}rW3 zfhH2+cPZ;pkFUc{SuYtlh<6k@a0p?^%6oiCRCfp&$c?_`DKzs@KvBNhfDWnAF4*o6 z*aWA~TtUkY0=I8P`zSXT^WK0qd~^L`g-UsL1zf$knP*t3*ibN8bP7>^vvApZebS4G z-)+Z~lf|*pUzKG~Kp2pxIijx0tG}BY&J=5Z5i!)K0Vx>5WnKvVWF1^4Z%H&WmeIDd z462K{WHY>EbpFo0Y&Orq69Q4NwNJA8JY~4tMq{JxC@1GjvedIC6+naU{H$8#`rUHD zXC2hzhn?R71NySBD%{)e`Vjw}a(~3|F)qyuJ2B6VaZc>LbqY(rjKz%Gwmqr=E|da^ z7h=hTDCIlPKnYkLnQTtU=9wckOCMH9ImPAB{<(>wv~@EG8NHoLVr|Uy(z~vW%Vk15 z$tiKT#QkXYel&^rq;bhXD>4dgqQ(4q;6D6{^I{tc&&uW$GurY&;soTw4mhLZ9~bIF zjdlDSj5irLvKZ1P3u7^8o;(&czt_*HF6xnVNz5A*I2gA(M4ef63SP#4zzlTr+{{IV z@+MliR4YYZ-E6c_IbCFKnV-zqKQwV&1dg(CGIpqP2INFJ6(Ul82y2an^VS(j2D8lj zY7bWiSe1PQHryhRcdwfw5ukI;T`D%6BBfTY{ZWz?5Bz;`u#&dg+?jxVCyE;2xq|J9 zk<>1e2}{flc)xOy6vqu>f0!*IulyFJ$T=1hKDASy9TnEUC_22p8C4DLs~#R}ht$}d zPvnKTr5>gK+f^1>R=mmN1AYPtM--`BNw5LK&Q}UE z8ja=Wj~=c>KNIi+&4&PP&RWbK3D72cAEWLgd2fLn=cphUf?0UZVK1e!XiYSiQfIa< zeK%5HH@4i|LSnk1g~va2t2Ca^MJxOB3}`7}Jh~}zm;33>k{KT^(j+_17HP&yH6fur zPwiIPLYrxy`lw1*%DQU)DWwzX=a1Bh-0R|)g6FD3j1*g7zp^Ppy{$Ks=IErzc@+Xm zgnoy*l<*t0S&1pfRgc9Zoulx4PAnErqhh@BCo)u46Uvx;Wy_>8Ve=Y!48<@-$}j}i zDf1P?`j$%O#CMn(XrCHJi$eB9l zZQDaqBr13lGrQ?}wQ#GHT?Ym_%Z$V7Tt2De{EbZi$FZB+N1 zf>|KT#Nx;$?Mu=>n(M6T7xr4R=f(D|ibeP4n?veCcMBZ)3=atx8XE0bs<$ia6!00= zGAN+oB?&e8JciM-;WOFUG@3m?d1*G8Kg`8MU#0jlLVXZC-P?2nb@T?KvKit`7-QJsJ(nYWu|d7*OB)oWQLDD#fpIo)>bryp0KqlehxI zyOQWd+H7m>k8-4d$Yn(6{c$&`ZHu6=V*v(g^evpDJRM$7$~j3mYj!E^$MP(u+7NG_ zL4A1ZJ0bv`h=jvFsDXz3PMf%7U@zWlCu)emRX9*gx~(> zN`%iOpb0cv3Edqii%n6p<9l`dmd7JrzZD8P$IC5H-|k2d{R_)zB`*&xO6!|fWP`{L zy!yv(TWB<&AgJEhNW)E5zZ0hj1J)#qkuhhx#`)Ev1%GuEW4+q}Fa@OoxM{)}^rBcg znNUDY$($$jcas9vhS3qZjvrQTJ-gTzpcY=LP<`~~3gJ8Q)Oc~CbSavTOL-9dGo~@m zI#Rg35g7W`cx|*@H83=imx)?>aK*_SB>`l!HNX~n+|QdIbZ`!rWm1AjD(HDA$Y264 znFIRBzY$>Vala96Sx3pw?LP*tmDiFxxSi4`>O>+ONn?lKJNgQ;k{_~s_Oe`-lo2Ya zO0uwN^w#pG*Hn~oI!-a!xAY-1!sY`6&U>rD_lALL@$s!`1<*RB^G8tbEKDY2&;DpZ z6|bbm_CN7J*AX5!n1$ZS^y_}|nfpm9<8NDQ1!?~C<3k0IVvy- z4-Mc$#A%hhy@-A@^YoP#X zgRpn(YEG2SDH&ORlN+_SD+h=e;!83lth{`h$};E_mtzQhOJf|EL;{^;c5cDnttS4M zw_J1liKrc;05_LeX2vjg+p^)an!+tz2*U0WkBC6Kn@7JAKzqdW( zS@8h})xM*3uL_G&-v}DQ7l+IhtfVCfH$o_kZ3wBz#60x7>3yg?f%x;a$3_JQeSeLe zCuebXqGnCb@tu?{Mt{yo0ASDc8|)53DY`febkr7Q1N$?W4n5S?DOIWY zI%l#Zbu;@OAJ6x_u*zcm1Ba9m&cA8 zrA3N;#;T7XKoe`ER}bo_jRB?4&q`ox<%$Slue$fv6jzZ!{02|AdwT0u(~&&>CZ~6% zD+x4-$-U~r`$j-Y**2OQZf|Fb8W<`cCc_LlII+7}!p_BgbFdzTbBh}aiUnPbgrKOP zX5>OVb&QFfG0kI|8ru!h+kW?(_BqW*;VWFjU_;gcv@EzQcHT^~k=L3Y2KoY8O-xqE zimSV7AQb1QR-|~9*Hc!bTh^n*fUTgJ=48Oe_taVzZ;) zLqQADgUY7o(Qnu^d%N_H8Cjk#R58v84`m;ZcnnJq696;B0C<>FnS8yy9)=iUhSFY%_3rkB5#{e4&2!);#kAE z?E3RDJ8}Tp)^i1=rjdNXxJdyn-WHzeAb^9X3g%e+dND# z*x(|8E&Nc0vKm9I2+JDD?Yt;VvinA4V-=;UDV21(rT&P;9cl>q0_g^2)p{iQ}bj@KT;MrV6;KA%WwH@4%_!%Q24HhQaT%s^5>!9WpC24Qb?7`V9*ET^*qeGF-vPbR`L z&mD=5uLbiC+a&a@-=gkf_(AQSeq3iJDYVwjN<&^8#1^%zdm$2;*KtwniU{i6mTs?d+4Bjy#_ZX3J-;`?5 z-fn8o4A;=U{xdS^BgCdF5jFvo2Oj_cG%J`BTIrP+fSdSLqsglV;|IWW0yEPG0PEAH zl-)?01whF@^DE4Q%Gk+sn6-jz<6?dSW#YyVY&1+>g&bxJg`+6x`eC4td{ZH#l0&m? z*K&!+`nn|={Faym@Mt?B$F9=Q#h~>gvHo*myHkTr6AV6yZ3>O*QU6OXguUT&{D7Q6k7I^+2x6HXDVgEv&}eLmo_R*yd@`e5JtU{ zp}Ek!sPxscj`M}9dFj;m7#{@LKvw7a{XCy~qtV}j~&P35_$f%cs zeA6q5!P*~V6yRdz2#Dn1UxB|+fl}x4b35FG(x~55RK^l!Jl&1KPoB&(9}YbaMyZ4M z=?75X*Bks1cLu&*GgLC(=e3eJUu5PTaHR;B#Dk;~Q934=@c z!3mj|gf>*b|1qRTO(xy)`QQ*3!1=kAfF4kZf5`a}#l=VYdc4g_Xt42}fSVX`*1Y$c zT;u&&_+8%oAPz!uFH}54)R(^#g38g8(*A304@m4Ezb zZS4j?#Q`wQMbNro)8=NO5kL($iU`wg+rVfmV4nz7=>WlTI(u9uAj4{UPU(g=ClmNhaZAQ9&3t*`ebtaxQ&HE6uy$@9W z@PE+u7I0B@Yy0q?8M-?ah6d?w7#gKJm5>r7q@)>2kPbx&0coYXL}`!)0clC48$<;C z_V^snd7kGz=X>Apd;foao7t<^z3N)`+I!}@9fA*o@{FlJIz02U*B9o!bAn9;;H?@7 z7(iE#O4obQ!y`g4`f9a9)iy&RW7x4&I2tX}iW8Ct0=bQX&zN3D%%qHniPVRk;#~mf zPz1wlqH!f~+zUjobV(Z=jNu)A2tN)umM;mKZ;;2~GeF+OUQQA(LbsKegl4|Ss{N@c zfa8q%vA1j*T{Xm1(VZ+5D8DrZS6|{HerNL`l$J!`yT}sZJ-sgUDEMBr47TZqj>Be18Lk}gXY#+8 z1z__<-MUsC@%>ZVS@NrK90&n1hzCG69!v^Vi4;~oHb!JSXK zc*34XYIX#}QwuF`x-ot7Zx3(E4Xx_}`p zbpgA1Wp>svsMsEbuKwveyoL{4n2rRlRL?2T3z8x)xdyqAN>TNt6G9wO{MJr2qg<%LiiLj^+-^nlaFYF43a}g zbTNSCAk_h|Qbn^+$+X(N(9Evh)t1t z+5adNU|0ghcn^y4n?^yh+uHprNa9NZ^gGh#0{{UDQntan4Y<3-hho0tH5&@3Po;t>V#1gm-CDET*p ze#I-0+Iaox2?G+${8A12Oy<@`B%J@G;3ZvQwMn3VGG4#PN;N1Gx|nu(#-r3F-Ee&w zvK8nfDk6|W3kTUp(}M)0{6L!N#5&UstVW3OgKZpj1OUNC$%7A)tO2!re3g~Yd_OGpeG$x<_lgiSnpHSqwr zC&PoaI|_vELmBDbj()&pLBMh-M@SAjF8c0Qf}C#Z%18@wVpe6rVf|csyxVX#JXIt< z+<%zf3lW8s|D?MdbKworpT{#Pt3nufnt>Z^;6UKEy?p(`4WK!80cnqhuR%)Xuz;r_ z;3Bh&nbtKvu=49#_s#E+^-4Z&97r{%TU&Z(olZI^ZCsu*In>ERknu++_AQdU(4gU7XP~qZ2I#*>gLg%}^Z)tq@jE@OQyx zy)!nG69T8R;t4^s#O?z!JMR|eMzzfp%O}1(y79;`{dI={CE-^RhqyXyc!x+!Hi7G$ zuT@Z@eRrt5uRHLK>MCKNN2wLGB3(h;UMXhUTrT-$+^X%hLZ-DiXIuSsnx6<8v3txp zk4sC{N#c}ob6x;$j+M@IPvX>-^4>Y+mAME;knLNC-|tk3HMpE*^!e~jNw**ABYdyb zEL!r#yZSy0gnbrT2_YWQ;_E;zlY%;ge+}g{yE+ZlX0-U zSyCZLn0#dnP9O-?JAkPg31ona6=(*V`-gskYA#SxS*Q!3+2BnE;A(@@3Wu=aa_){nDu!R-a1ltMfMi z+U!ge67x1Y9|G-Z-;$acvwCzYN#S+E;CaT}Cjg`te`v_17=wpw#ZfuL2Ai7<5Aph&;QuZe@Xuw z3}XV*{#qu$jTq1i14JFjoC+n{euv&$S`u)!M3n%8r4fl7=qN)XoP4W)#gk@Ijogr@ zOGW`K0QO!v65s8Qd@y}g#P1R?sD8U-tbkwKZqI*jeb5`fqfjD1YEeGO+dqeaxasrD z&j!cRebt8Iu7UwQ0C0(o_t#{9wBg@<%2q12Y|K6JeEkWa2_v&ug$OYbh{bKvXwP^&;OD8H9;TXiu}U^K?Cm)HI#=i z4HTdNl9l#*cLKwJ3$muz9nY;_?Exa60O&^);4u(HtBINF9Fzm6_W-b~M{*_;y%HBf z7oL=s54IC!L_q1_z5r&drIaEl!&<#7bUhToUTf1F}#AyA%TXBh! z52Ct*2of2NdYadruOnS=Pth zhX05OKFk@#ik=9T0wdW03bWY(9O)*nQBbdG zz5nV$u2tLh%+YjDm)pE(kOm11#uqjCZ~*uC*Hd4BE5aya9a_v=a^xpnd43DI1gIC! z`+D+>YR1WXxCDb{4SWc~`J1x^Bg)kyjYlH5=K6f|B7Y`{Y#orZzyJnKg)NFp)eN-7O>l zH3l#ZTlWEsthA2YW@3AYqfeW1Czh?1??ZomP!cH5AQqg6d0z7ZQ(YUd=Y2f|g-m$L ze}Y`vp3vAmNC5alCiZf_6XH1{`?#sRBq|31%pM$L_rS>mL_(6v{y- z(uTTWfY^cVbXOpUv5hHukk}j4+x3EhtgCQTBsw#>DjB%fgB{e7HeFD7W_k0Mf(}OQ zguCW<>AQsDg#(T>`9yg+$M|G^~(Ci%++ zuCl-Q(Uk&RraWRCuc3mW1k=A_Nt=G95;Ljj_~l3As{Cgz$V?wv%+f!-D2F$q2~cPQ zez9V{`i-1_spW4%{PNN?iv6V&FaxzE0IuQxHs>D+oIn{-wC1n>43&Sbh`Sg0m$IOr z*ie3WDmZ@N9da)KZkKRW?eG`d47v%uhYt|`=j4Aw-mJ;fEIRLDhVGuTsYY8Y3fMSYpHp0*Vv>{N~ zJWyEmf50?KSil4MNG#&Fq*V9JRey<^1I{8#fWFO%0szJ$Iv);Dg|4w+W)39lp|=6F z%iwv4*# zd1)B&ON2(&$npL>`Z$px*+6-zg`mOx$>&6r09c&t?Yhy>SjI~HwpK`j6WYuqn!aVa zMZ79tm@iQgPoBfLwd1rj(j7Pme8N-FL<&rY)~cV5xjbXbj;fx4s+#8rPTfC5*z2CN zt67ApH3Apm`D#kmsx>Q#=nh)$HyttoocfpF285#ckqUIvRS2;|p9TcL$dFISxxTqN z&Dt=4L?=0tK;fMqf`pk1iL(9$R6(+uf8!mLIT7TJ#!?Sca9Mu*_}BDDvjK=@UN%2R zEl?Ohd#bPm+V*h(XibTz0Jbx9Z8;NhEyh>xfy!z0Ji=SX0OXXY8i0CV5)v(32Otx8 z&5c$e6_rc4e4BKmuuMVy(VO=T%x6vQl62MHE2V`HV2VK?*qbblp%_3@i!&Uo1m@m8 z0hks-K!Z7`*+$(DKygOY!KL~x7ibj%&{2CVXjG;7&!G4(kVdDlz4w^q?-PMvJnOsw z-7~^19c5?>5=VqefMHCcP2DvQ09zmdyDT)qnA-A@Cy_RQle6E7I0S?O!6v z1%FQUhnvI=tkD^g)$$)ul5zx0@TWrlliLA+LjOkzAu(WuAk$~dZ+QG$iIjZUtnhzR z68bRMkEpaaPEofT`_JKTiO|Ilz&`8{hDHIh%$C2RF()3j{mzcb2aYin$|sov0Kf~d z)_>w0iy{(YOf97G?MH|M0+j?-g#egYehmCmxV_rU!_YZeA&C8IHDdIh`M5)wg%Llwhq0xHurFKa=i4|st@ z_}#QGl22J0T4O$eZINihsOa+U$ziF&)apRM1vLk{}q5S`?_)fmN%PTVCR4xi19j3@t>MAD&SuiWI6M<7mxI} z>tE6TJ_P0hO0g%G)rI$GppApW_ynx4g78#=ileW@97f=%+%T;tT>x~NZ_Wr@^XP7m z#iaz@uYHebb8?c-RtJP=4dM}K19LCSYB6e$2@R^SYj~a&*kdxKP{}HUm3!!=+8?&2 zQdoFGh<(4?2EIY&hV_c&V`92VxkfZhbbA7H&c043mc!Vwxb6U^Hthi>TbGkpb0Mn+ zMHA<<;NsRi(rA$f_h}Dc4wRt=GQ;Pd>^qRv+B@CX^+CHZo~1bQ&iM@vE*uuQaC$%I_*@ydAA44m_dHR)> z57p%B2jD~^g9EB*C5k|x{2-OSfgSRrGZp|CqLm*2J7kyvG55i_Q{j1&WeLNW3qg`} zo4hg7m&RRUBP9|IqDJuYqrf;Z9AjfH8C9Ojy=G#f>#t0ZD9b!J8&8%H5S9u7Bmk>x z1l*61&_Yl)@G-!^pTX*1un7YxWl^O7?ucJE(Bxl) z{{Siv+u{MOr<{Vu3IN!mrb&();uNiL8o-7o1LKIDA0~7-)?F@g&F-+M;7lP|Z|m zm&--cjOHPg135O9nG9D-cZI;yC3ci;T>a|76Qo$C2p=c{WcHv`1rgfn0Z^tNfTJIh z1E8(+Aps0{KFIkR1q7qID_kypsOLX| z$nz?HJO5V9-@Lyb4(-TgO>+GU9>ESoyi&?e~?2AL}*(-BCfKgx{&H*XQZFzm0a;qyJxWOW6O;+%|oiNJQxlQP4M!0tu9N;b+(6u~G)`g|rw*gch zQ3D{geky&B+mZ$nGGjIc2Mu+U!!ay75Rgr<-@!RC|7QUDpM#_Evu2kFKTyBSqflx? zzwIEhh6`>LG7C^Een2S133whu?6RhIs`OL{eMnx;AAAh@)~|-a5_mLtcuQc4Z!jTXw*am7Sa~uFM_kIK#xCpUSK}Aqag&hDi z5NP25Hn@CH9PSHv|2u5_HAuw3eli3KE= z?*mca^~PzGu3t`$0?p)qa0?KrMFPM8415c8!UMkW zH=%-h2P{EaLBXQs(ii^|E<%4kqF@1VC2h)ODu-38L9kY3+d=h?ucI3jD;ISAzOp^0 ze>?vOi{H%wpu=wfg#*N2BmSA?pAJlska)-9cnC_vUX#oEto|o-#MdSpJwRWFG0-{O z0@_d|;nLMP0GKAW@2Z!;7Y3$WaatOLd@MD2T$K>@`}3mU^B?wHs=n)&RrZVDu_yDI z?`TJ^en`0Y(q8+A={;ENXrNB|zO^d=Q#Vtxr}LvJ{`YXb*v{UE(X-=No& zy#m2AzUsClnQQ|0-afx@15cWYfHNvU3;#N};&Dp}feq1c`7f1d^I$u{>9G4((a#^Vmn1pLDDpTC2A0t$Hf!Bkjrf(S^)raEAP1RsPwc0K?| zOqW5)B+Zbtjm=ZfZ~Qv>f%@X!pYiBFLLx5}C?P#p1LpcIaHJOja$^KaVzgRZnn7@? zf$tjbDvHd?{-9C{*10{{~a2YQPIS0M#S_ z8~W?^kHEjy``18F>-zPEYVXhZgeIT!TQ;=uUjzTIOmQwyJu)O14P6I&3@n-)LAFwi zauFwz6CtZQeucu`3Pr;i;TT9(7^$IP*NZT zZ13OE=uR{k0}h~0B_Ke9ZHYj6v{3eQ0GjII15mr?50UOXPhBjC22I}FphjSswW%oi z_W^)v6!fVQAlmK@L`4gyEkCp2JH%})0+1kIsLcb<Zl0Zp8$YA@>M_3;J7N3()M!V64}s470axn7dT0{Kfvcb<`q$3 z!b9zRht}s!1-c)@P>_9C3~xcjDw?3aHm7~m9m)t>Ipu3t%MxGi#B?SH<9BE#IF#?7 zdWPStOOSfEWSW2BqT7AzuxWm#R;sddRUh1)7)ywi} z7(vh0ZMrWM*7dx}O?QsXjeMtbgnCDUsmN1Q$6w_$-l_c>oEnun!5unp(p1E!en7rn z>PUO_-J%gdpKp{>T3dDh`6fr_{`SFv?8gYv=d^Q2Fa1PLB5LpI+;+QD-}+XPDePf3 z$KWJgV2R7-_Fb!r$)p)^=R2nuC9hO0QX1a(ey(n*%*@}q7PtO#GvISI3slCHJACit zIinY;ad1`fHy35mH%BO*hL8-)!?>U-m*m4cksH#q>a5bkcuK6FXF~1(*WnACedAj! zqd6K$%F*OknAYsnk>aCTInhf8hM2N@4HnJCuj(iHyYD!?^jP;J{yYZgBxX3STDe$1 zbG}}4o8^k$@^njy{Ds5^o#%2E;VaCH@fcNvgFP>*zpxySIg`gfwhu+zGnJXD^#xB9 zCF&ti6?N8vfSdleJLL$(uCZeUGti-3^jk`WL~hGDc9;71Rlhq}^X&^g>y;z2Mo%{# z@3}Ln7G)Tv@>M#c@XEWPgWL*QGY(UG&{h1(R8oDVvzmQn&+%lJJR${>K>m&(75!TO zBfmujSxqh?zI{fO6bnHwp(uusdNk*`lVWO;vDC4L{(OWl>h0r8f}*-2Tg4YsRBq3d zlUxr^n60DssW4xvyTSdswsbUTvLNYp(Mm;r=kwHAv#y2U6m|r)Vi#_-Q$4{lAGc&S zL2=@CE;?%lzjHSMCNA~p@=$?lDyI87RgvB6=kkjNNl_ty)5N5azgiqwccAhx20AmR z4)ewdoa`LC$7zM=3y6qhvIhIRZgS$9^7(WP>vq+b^C#Bt#OmDK9pQV~% z=P!vnk9}e}N$oUn&x1-?s+1wV3c^`z*mQkp>O)k^{hOK^V-p0DjSnPCiKRE>V@1|! zPst@TBs{BCZVla=)UWc+ez^jfM!$p%~(y}LgFLzV2Bp~HQpI+%5Efyv?n`LDd z4l1O#A#^R`E1z-o-Cl;QV+Hr6mrBS9*_CI%fqbuWH7Da*bbo<6q29t7&C4j{sLHYU z?vDDrNY{%=<^xmjMg@hUP<45CtJHa5i>=@1l!;wCuQY6eXR>mOz;z_{6&H5u>S4o< zMKZj`RnrC2Aju|rmxVRu69IoeFc50{C2IGcg0E#iyY9w1^UZ-qa{FFet>9_bS(|a_ zguhbSM$^Y7edl*c4`Qx35@u7SmPu4^bZfY^=@@MlRJI(Od%w%y*XZiJ8cFu_m951@m<8_lG9Kzmgj9o-d3Djd5HJZV#kHWH>dE; zb*JW>SNDaZ$Bk~`><3s_s?~thBR8n2XeZaHC&jsl&~f%LN82KqVsolN+wWXwtNv%%hDph0ItDj;HTt^n`{l&iuseLb+#pzGX`3kw$9W zdtynkN-5o1ANgVPVE=_97O& z=%)#f_@Nfrlg=iKUOs2^U9@+mSzA9&6x}X@xhP%~%r)Q5UJUu*FO>L`w|F}@?4ok{ zr^rt{vT6?z-Nu#omNDCe(XA)3hIE~A4_4ZI+G+mZ8J`l|LT3g&Y_gb#&r=T%TEi?sup&ozn@r7p0D;6=$}S(4zRyje$$#{pnnFKPc=pphU0jWUWGTf}Bxsh8)^2*Lc(F5JcVgaY z0`{Qt)|ZSYKTkG=Nls6NF<*KhTcne288eDJl#pXjZLE2`bF9M#eKHiH8p$2kti{f` zV@L40>zOdlZk|j9)$p(Tjv(%#h#t z-4ImTV6?oX>|NTAVTJttegSvJ&vcH=^F(O~>smUOFNU50p~coJq4_nG$^v04?{@=e zc*u(9l%v-b*K-T|9}KeJ-?1_3!=~%ygD$R4cz7+E;pM7(lsZauvWQ845)-s4 zvK~@%Am0BYQIR_@i{iShc(n>a zZ(esB)4^B!-Tt9uDxG_LxgkKO2B%l~kTvt&T3)lm2Th`8USvPtc9!ACY&?m6W5HN%T~H)Nz?Q)#iCvc%)b6{FMf2urm^UA;{;ru- z+EIF}@tLV};>V8sS9NAd>yn&1{Kr9fFJ2dX{dWDC3wf&3`Q49wHi%spFWsUd85ts# z^kLdCYguX+DYR^Q^27YcjLT#~)y0?tk`^3~BsLejQWK@i@HkBv0zK!4>t<#Hro`Ud zx7XJs%e*hvcL3a#BH+6$hV#7T7FYY=I$F0S*jzu9jeojYeD3U3M%zheVmQB=;6Y2H z?xGkp&*gEAt-<5aQlcTm885wjarkWViAL5}bwNKh0z5Jq@vSK$k?Ad(>z|!BbKkKu z7PMrsHDn(5j7ixaca58bR*P*xmuM2uS^2Ke_S?&%=#zv|$~9G<#8k2vo5eld$x^oX zmYtweYsRiI^s*aCi?mX~2E6w|7T*X%+@SPS#BQ2lpJmQURixx}xAk}{I`1AAZx`B! ziQqgqxg+ODU2kt=7L>s!Gc55HFYyuAUW^5rXwb;TP2~qokq^GzERPz5H)hi%R&u+q zTx_IZ@ZdtbYI^xH={=ntdFbWln4Xv0x*nSmt~G8=(Ain;dgE)+ zKGmSe?X+_E7azH<_K*BTXQ6`! z<=3lFzUl&Uk&i^!eIlhOrnB-_v(L-Y0~-q|jHVbylHI1hZsXAoFOfE)XE|dH9%vjX zjaDL)R4lt%kS5u0u&D>$d!34LK8kKCA#3zQ*NB3bH;BmMEtyK#=rb`~Cq9GC%FR&D zt_=k5<9rl75cqC-idowUi#O45;y^?w$!(lgwl; z(`41&LhqR+$!|0xP^G(g;1n-vB1|M#_L9v`h+H3AY4|6^v2BO}hcuq}n;uv7dJPNz zWkAz%J^l8m2Wi+!*s3$DfT{Dry`GoY0yDXqWiZxhrC~>|CX@Kj7Nq)eZHJ$F)C+na z?bUD8aDOG~KFO$cnCds}EV1xN3WhtqP$yHoR4J!seR?mf|BY2x`}KQhk`~g#6Ytq- z3ph!zq~kRGeZtho=RVrn8@kTdo!1pw?S6K>7lO5n!JC-snm4IiRNww{?wvCLo+ zG$Omzzw8TItiL3e{_W@2T@`v3sq#nKE$o+4t>^W;w6*n;I&&Of*+re~^1tZ%#zy9S zxf?}~eXZm{)FSho;1}iy6G8sX_s{QAPuduSFP9i$YY@m$^KM$;&2oeWjqK)M3;6ZP+XN23@%U$SdMU287v01io=1c?GZcfIiL)8Sf4(dsGqQ~crr~%;$ca`$e=!u8 zZc4VKc6}`7lzcqGuSy6D&{9-?d_Ez(JFl)JZAIm_PCW zuFlu{A#lQm@5T)^s!HzS-;x3sIGF-ASOuCt7tqle*Dy8M0~~H&<}_FhnM{z z`e!n)9J*~xsjoKoWj+|`@)EDIF&6XXKhkTG-Ef?IwYiAl=9VnOmT}ubOf$JeZjIbc zf{)67=OTE0;CP$T|=i@57QavWF)Gov^%4skg z{3*e2skfW&Ug`F9=#tLeF^~PqkaUz%R zs~;4bH9POZJG-m2p#lWMIdP0uQrh~7G?$PT2VWNAT-OodJ3rrAMHJPWczEVQ&p2OS zof;pUS;LHRm>ch7Zc8rvUEjD(5@o2qaEFcjOD|p8vF+o%M5*qdea90glR}G(YV%yP zJNQ!CM=s5xvfAM+rK5G1{a56k7ayLe=yf07k!eqQ5Rq1Z8|nPdy|_lD5+P)3LY z7fX>ZyuvLOuwPO?%tYT^FX~Q}vhl1USDM4yxcxx=L{5h8wrqXCxuNTOjw3AMPZoo# zE!c|tE@9uY@1D(&8Ai1;wmP7F%>8;W<|@rvfTkE(rC(q4!&0_kPcUqox#lY;>s!_9eFy|ez?(A(1ndu zg$ivqEjudtXyQ9@ht8>EW(ltLrgbhm1$2-m*q3?S>^&t85J&Amy70-el7Zzrc;*a(@3@C;gF4B*E;j6P351DH7>qLG$*vLuLKF9GsD~owUq(MqI zO>uabeD5$0e=j$6xz2^O{&?)^at2noin{F66tjs-AAC6$E6GrOG;3e|hmF_B+`JtJ_0IYiTm z?ZV#hEh^$-ltSmhr8(8t6-5P|u&i;`)7Wo&n>%MQKZeZx1|Ra4UlftQpGlw$o|0Yo zA-R4eA{dGGSx4{LdIzt60b8F$-$as-Rsfd(PK%*$?@kxQsMk@9qG88Ris)N%MG94d zEg4~1&O3rV%zCR~O%naspOGC6oM$qk^>l>7ao#45g1pH`JWM~QUQq|>Kj+q_7d(3_ zv}C`(cV}-@%*J?3Gz`J9p_80o`4oDY#5_o19i&V0%pfI5>C4(6^MrIBmUvVSG1G06 zpH_r?H<{9wm{MiXL~U{tT8M=87AISJ_{6tLM=VGQm2))tNc`7A3#Wg~eN|44GMXTR zv|_x8j7kYmx$rNQ9A>48xO43qmwY0Hf+uy?&G8GXT&kvOz`9?+Te{H7Aea^3l3POnM_i7E~;LP(B^} zwv?mN^tyoUp|Ec0!-`6JvCFa7JYKA0pK-50y43}&Mzvu$)tV3GT3i>yxF!0k1atZN zjM=t=XJh+e&n{(Nf~mwCTvg_hUUoDV*GP_&z$y;jBVV7JdkH=RoV-^VPap5g%BWT) zZS}5~3YTU%6D(bQTjl8bJfVYIkdRQwvEjCjup4+O7{;?ywBzd}Uh>WBqUCnZ3wMq) z%_@TZ`^Q+SdUIlaPKzTH^>tG7pH7V5{_NuFpJYwTjK(%X?-w~NI?28CrEzn51U*Qq zpk7owf5y4`ZMLteUED05isrroEz(12YWU~Y)@#=BHFvEPoO>5#tdyO{TT@EJYh%<0 z2JERHK0Fg{X0&2U`%)&9bX5zxRL1kHE+%e!h}*~;?wy(;lT-4PH7=#ZLp)NeOUHfb zlZ>3AgWgeZQ&{Q1hYHscg|x5G+5y|E+?!RE-NpVw7>9s)G>L}d%Gc}EUiMb)30-m; zLr!UK_M$FIF&<%;ElMM)(X-9-8!n@=C*O}V2pv5`Uz)7SkG<<)3xFN=9|Kttjz% zWYB?-s`0or$G>Dd8Rcg>a7fo2XD7k8?UPkxq9p8Co5(dXdLU+4PFXkR_+6VW;ze~b z7gGr|u)BNRw%2IC-IgvZ&OPBwN*=TA%W}6*!RG{O;uESN$+^t-pVy}vB?Vov%}_04sIk60NEL6l2LLrDDrd>UaZ zgjblVkZ5ogOZud;^a%Eke*T>fp+owVue|VzY|Vu{-zLqDGV5d#o|D4x7d8+BbP((q(%S-?Bp}2FdO^ z@fmz+Z_9P(P%|gQ3ubIIAb^|U6vVtv{(ArC#(8#LQNv*w0Ki{`%gcY zH>|jngw*q2klm!UXy0NENY#}U3-Qa(eYrxg;DjZx(dK}bPiy5tpk$J)a5+3Pj$bSC zlBeGER<_@(udAORq#Oc2mkdVoekdP4c(o&@r2d_K_wkKEw^#QjV`w?~9E!ulSt=k3 ztegA-B^P#2V-)VzJ2`y*-2ElcbrLsei{_!^(Y=<26H6ztK)GSP;PWW&JshR3kXcD@ zO{z3s(om+@d)?Pmf6UGeZ@PKaB$~P^Q%|k6J1O;MkF7PIQc+F0cK6%W^V|EVUy{ei zBw4LIOEn!5J|MX^^!QF#6Rr0y-jHi+$I+oq*3^yQ7_Y{HP~3%x1fP-OaOb)5*`vbr z>J0nA0LZd~PJ4(5RbF~|IV}68%rLgzPmSAD!x94{M8{|VCDrHcPTV(w2?BEmEryz1 zv69==H7QrF53&_^*d>`@%+1E|sjx7Yyh0tdpxT&*!^K(zmT$rRjO~I$10snWO4#s_6bC9dM*&my*&?BZ+C_fnURid zoom(CN||Hvhqhp5+`L6TQZmNqQWzb|SrATMUu`r68O-=hP{yC<_YXktEObXE%n&K>KOGxWPjrFOc^23LGf*3XXCx>Mt+wGQ^ z*W}{XR<7=4ML(|os6DE}s{{|*Tva(QISnlnp>xk~{z&Dbw{#vPYj2WZ&N_Wse!{ww zKX01bZ;O3jxM#K(Dm@C+J4#>82&FVnybEcebtEmuGsKeyy#fB!FpjFL#Nx; z`~lp^kBgFk=k|?8Zm*V>gNGRu7|)vTJ0U-IWX0W;ZlbSn5yooOE_&ZVQ@|Lb^l?eq zc$(prwCw`yi5J(GNvV?gOzaHAEps%yX?ptN8?i4d3geHzMr>YbnMPRtuu_CZOP?^*;E$kV=JWf|Qe%xOQ!^&cfp%+QFRtyW3Y{ zvRb37Yaj5Rh1FhrjB%5E1oCv@T3q9cciBuYc296uz6WaN-A&-o>9$JbrCxg?Z>JiI z?ro!ZTSc&r*~sG5?D!Hffm3nKIn!cE9q$&-!0KGQO-0?Rd)9C}b>}N*rZN-2>qSF4 zX#)}V=W(1BSoeZQg&|%xR`s#Zp-4{cApiLA^V0TPOH;0ic#f`z9W%Nz1T(iE%Q2Y3 zr#BQ2#G>TmwP{8m!5=Or*ADap5+ajt7rScidp*34{a#10;_1|}kLi=O@b%K~eduY< zR!koy2;?=o!t72@hI3fjf(Ux8`@Y>_Det{^|GQva5bLFn2{*B>pY&6z+swVrT5VO? z7mS_di%De!f`Q-Ay4q9KAHG=L@XM8UE7N}+TI8rswOI-kTY6?x@PvB%EG9Bse1D;~ zp)KtYOXiE!2JB*>r~0CjQIm`E35SuF->0{ILbJ#8T9W!R6rMYu?w!`k#eAL^8Dnlm zzomkaM@Y3brtscDz|>rW((4CBdiXFi)0!I<*C<1GQ2w_d)1o$Kx~i1{&XuFYz>s$O z+ll4~&!={r!YbtA(O7N~`qU#mZC<7iALxml_MUx2w-Rsq+W9VY#6P$AhBG!{=`56+ z`8`c8nk&BQm+v?eS-KBnO+H{S4h%yczO%FR4IbJycyaTZU2+N%LJFJ2e=n;zS)#-6 z;^Qu7<)eTl{*Q{VDn{v`9ZVnVya!p^x1Z$Ryi<|1$aR8Yb-j+%_~5NH4{_^$=g?pu zLp}D*WCykJw@tRUsr6h*&Ny>lecx}t3=;BwE$eX|Z>YaHOC-o9bJqx7o+F8rJlEvmn?w`ZhDC0!M24OXX5|KCzk&tuNowQ_R*@KWQbc z9Q*R!&_&HDsJQ5v3X!X(lq2>O)2MhpvjJx!g5c8Sx`a5crM{-gQ~6;8<>*H1vq4&p zRq=XCY$652J?0g7LN>=*o#;~D+tzeW$&7b9pUuzQ39*~M`z1X2UZ^3i@QJbey+)Ii z1a2cCvF!!vOqO=*!(z3*bviY;zxHc_;*clRm+1zpLbgxYCt~ajmPN?C{ni&9Qi3rC zafpjkowcy;0tf_5zS;AZo2S}t#(}B<DAMDt`hAy13)BxgSVLSRvwU81q6|1*!AOD*NM1^wj zA?KjEx1pPC3MP><=m(#_kf*;(^Sxi3rqq1+$)zJNXE_i3d-(dI>%&&vFSo?8iU;0Q znubu-=T{Pl6cEa6SuzR_+~lkked8Wu51#vglF6uvG1>Hy25% zPZYFl)Hq^sYCYWsv<5!*Dc8SWjSaIXk73<;67b=XeELA@0*&br*WljxyY4Svw%W~_ zxW9**U_Tz&YGT?6VE;jzr#`I94BT_KoW`;GkinuGyb~SLtD)sw?n%RMq@uU+lha^m zEngToREN(o4`8p(rMNd4)?39zF8h=^Y6gDz=6@pE-oe$9I(H?rn7&;;6_~nez2(T! zSWauUET;UGi6^i02kFmSg8g|%%AenIQ{j{JD`Lux&ApGj>FSiHW&A^zSb_mdTI^u+ zPGKExr!`DZ_rZ7!K91D2^-ne&v2{ObJV`7(Xzlb>NYMO8X4r&^-)tk4=uKOvWM@-c z*kU%nJoUeJ%m3_E{OgJrMPWd0nn$N1u*@`1-7kCl{Zdn#Xk6J^8-&qAKu7i@!K=zf z(2AMAUM47KN;Ur%gh7Qzp zmK!-!R3~-6=jidgBTmJo{25N{vxR$4K(@{AHJ+T=Jhb+yJf0`KhxCH#MGBTY{pDVF zNvn<*^*(-$knT|mX5y3Mf?{=Nd!C8YQO*Fd;5Q{?^h#DloMB@|nV-ZTU?sbK8q-~S z?i3Y3nml$$?MpEr02;5-zAN9X>RwF(q{=zaOOn5j*^p8r><}lsD|N!RR}-E?f2CRY zaZ%&_xu7fMfoS{^vEzPYD1O3Rw5xpScdaGvuzfrSax*kGp->I;u=v~ev**t2?0kDW zJx3~i%$Oo$uL_)|-QkduOXp@v$#~)O zdda!HtA!Q0ubW8!F8rqFhn_-(88KjVGAH{PI$>aW745^VjGP?Ph?GYI$pQrf<|Qvo zF@l{+>Q$vDBn+u#5Gi`htKTJUI9$WiLf zjmb*Ft*Lo+F`c9_C{v?#S)LI^R%`oXTC%6}5Ys^=H;mfZI2*N^mfJ)+%4@0h1V?kl z`8RC`#VOhN-r+78sDG&^@N+Ty?piT9YnUQ9VJ*9)=YfauK1Y){yY(%;vFcLB-rcE1 z-beiWJtwF9wrqBxs){kXo1cP57m|;;whYiA2W3}{DX~;jL1S+Z;BvS{!Caq{TZ$P~ zabJieH)UIQoQ1_lDMjCGO?@akapRN=m!vx`#$3|4k@j2vrc!O+@%;FwFz zg|qnJRm@#T!*_x!|3UadQW(kD=+ml#_@M(Mn+^%ZnyXPZ8$H8^?#x(DrcFxmX87NA zYP09oZD#{avz(}!vrprT>mS5>!l;aQ5|JiRz+L0Yu2}r8pQpvq%)UXmm(ixRCf-NS z@}y#jL>RMwN{^>>*g z{`NwyR8i8QLsil&Q?UKjnybh?8i-oJYCa&Uzuw&{-FiWiTN2OW2$vp;Vg&W$ckxVxV^6H=O|QOtom0_(rwcd4e|E z7F;vOeFX!h4Vwht@HhOUjZ?(+596;D^xmmgA6{XoT(%K19EiRhth&yWaU(u+=B;@K z=0g`Vd`-RcxaSv4A7=0jm6y!w%*@|kzK=K%ctfv{X&}l4K6(2*(n3fhfJ2A%R_lG< za361ha9#@QVV8IwbsK&lS)h^L`7+{QWdeCy z*|R${&z*bk#PgbYhTYdy|K576(rub`JE2XNa@ANli|JEDT163hsj|F#^hZtk^HhzA z(MQy;BQ9D#n^DQTgtPO*j!)=ry#~jVm4HOFu19;yS8s-$2o8m7(e9t^JGDdFuNdBBINkc+B^&qw7!YLPgrMsQ0d`sL^L4nd^K4C7hMLG7aV(cUS>zjE&?#f@!tm{?K6a@m& zuBphQ$02?4i9Li0RZ2H0H68Qq1WVGpW+SAYfO9T`GL29~3_{6;h?eNpzNrAWa5XB@ z*61=<=?dc(!B83ROFX#)~p^*PEl(bsg?k!}7o$X_)1b%(3lkNqZtIo=)p zcdwjt?+?=+*BIgK4%~BZ5wYT1nL_6zoZMJY?4ek1*V21nBBS6>6qz*S91}d^^hOC`znta1!NOy%ZB;toa`U#*>Wk7kK|bBPc9}rq1|{CQ#YI4 z{%u-o>9LgmJ8FjmKNb!#f(hEo*?xg)2gOnA#{m!Bvjn+`!63TnmByM8&V5Ezg-`zK z!kC_vIn)-5!JTFo$1+>qJWkzN^UKV4^ER4}M&qIQQlGzNo_!5}oNu6Cf(R^We>YJc zw;M5TVK>OyYmn}gurnka(O)9zvwQc#=IxDdw6KQR|o!<03n=`fk&N z-s4(I-9rZVWc%Nco=*&j@Dxn8!qK8EUn%c>9<%pFC&H85YT;bu%KFln>E-jT1s5Y| z=jHKArzu%NxrZf{wSsBSX3|Ro_m&zWmr}|H+{`&U&oT zqRYlDc+VWeYH~(CE%1J$a0H)+a}%MPwgAia^TXAv{F7UELKgANt$jy@k*2O=@q3zPbC@Z z21TzCUNk|JffcK5ZK_BWcqzVJ&hd|0Bb(WMkqt`UI^HdTgB)T$g$v&M=WB!P*b2v3 zH7a#i@rNXzz_JN#`?&La?^!jY{MmaEQK^CMnE=*H0&&r-C z@Z77L^H0AwV4iV8K$6-iqR_oI;kHwCq;PItPULR(m0RR)zSU18qmy53xjQhfe&>6@ z?R>(U%medJ*Bvq#;LvgziQmJMHn#Dm&(6&ujhNPx`q_2mL}~EXjT0GT`)`_f3^Qg^ zzO&bc%$ZEP#~c!-WxcG=3>^*o9;*!B;0iDDHy9Hvb1JsQ>n5P7cvtiD6V5#vz2l^F zE+1rVRs}2#T3=~5$%n^&(+-{JuhjLlx_yW0u0O@$orEo2v2FLF{CUo0?U(&;JFi`2 z9sC~cY7TzAn|{(Hv2iv8`ssjG$A|K}=&yJAns(T#PN?VEe)QpA>sxS<@J8mvTex}av(ky0TZ&He6Fyh{GRZ=Yta@H1-S1D_6*pyrw%!kG#$U%unwG5^n-A9}_v$V!why6@1qu#&kw zr%3v&C1DU)*mhjwAv`YQQQkvX)W5Nm4ANm7Ns<|cbf-rh^YPVNq$JPy$Z zi|vlf7@GA%@ApZHBkQBD4U_Ud$G*8MkZ*OKBsF|6&k`Ny(fq90E&uBazhAE5XIV8! zc?9OZc=*T$oxc>Hs5`NWvp-k~Clqciyc!jCKG%&GJ^QqT_n<7Kvt<`XhGf&*xKbYf zor>ml@CxPDW_6%o_&NJAdbS=}aY@NUw53o5<=x%grx~LFcmx5X$J(%v;_K7->Ls%hXGx7;(|Wz*b-4UIMTcHw;@p{O59+MpDd zeAi$1MkH~<=j4;G%&RJ#81@x<(XHPqFKNl_l$|g!*rhoyl~voHwEU=@pG!>JK7?~= zt?udDtUer|3=ZB&R>l~AbM;)^{(0}%;NarTft)iOgf-sYceMQ2`d^6}+XY-3r7(~( zzUoxwBrl|yv5?)>AZWQ|c>mj2+E#SjL*4!()NH#>itQS|Y4jUPaG`ceqEUo_HS9~P zj6|mC`;=+w)D-+tw!JQ0iv1G#g=2ip?@sTu<%K97jj3LL5zONJhTHkqY<>RoD>oV~ zE6i~MJNdsex%;M?_Y+j!?vQ)84~uAg7N>CYE1f9eR6ofV1%YLbrla#PB}Vh?uiRXH zpG>dUtV@e#)OGi#c~-#@lC)HoC? z6p^@eBZ#9yRoE#<)o|(|B3$PwWN8OD#tcn;2^w<_pu5vE@ll zerSR@UL^kH{r#bjyC<5$Lw)1d;ggTvY`(ih@~NVl1OiMMwk<rHZ!1I{%hqt9>c?wdAac9yILbuwfsKT z*L)ZzpN2ZHU06mM9-YwpbEpVzYr(iZ#8sy@q{ej?yf?>A7)>t?85$f4YHiBByPo~Q zyKiu2>6@GNu1iRbTCvR3t1~Sq+c_le#eL!*j$~gA zxARh97@wo6>B$$X_@v|qrX2D7@y!b5=_j_tQB8)*F2X-`Qg1L3y_6&Gt+8fKdb;$K zaJw{BZPf#T}9}3f1XSbP*a?Ey&up{NHkyFivHBqk8Lk@tI-c zjrES|%q~yCmRX#ae7zP-g~Bm?tp4KZM!Zx<0SgPBg`1UD8L080w24xD9pNs~Ew6gd zh$!9*!yQthVmVcPe2m0}ROfHcUZpBr^&s&;V!jyKz&cOt<;#RhUj^6^$2?Iof4>zj zxAvmFUN?wKeELG4>G^l+#>WA{1b*b&*Dg%G4rM@II6>`ehOs;p&Fzr9bG}^TyZKem z#+#2fZ;F_EwK=4|-DRdUyID`z9??Ly+hLAltdmQk)^a%J`TSwc6mxXzE9LHI?sHD` zA+Z`SSCFudaT0;TP-CmPzST$kzSDWt{b5HB^mavCo;i?)s+5;E36QJNzu4F&_v3Ad z`^Addk{GZYyfU)!<-~qX%KFN?I~=N|zNrkXii5L3~Liq zcqo!H^*w9KjO?`6pbYX{WD>&r#GS}vS+HS>biMHTP{%z>jT>!MZ}@!mhiykyCm1}{n<*(zIht;`_)|Uw?6Te?-1QuZ$8gt zbiiI5@q3CoVEoU{e~Tcz;(K4Z=6UpM3(5_?bB}P-XP)hzmGY=;YktO{=^VzZGF;+F zt#ye}GhQcSjQx^y59x>ZwBZ35g;)n!KNSbI7|VXXF9|l6^GE|>V zOOlShCa*WLA#&7D>up)ZM5XrL`t`%5&pzmVouj+AAle%xHKK-(o+cB<*9rEBsO$0i zANWSvW~_%0?!a?*Tbu8r(T|*!tc+)!hkJO3KFGX)W#p$v68h;4*ndb})#$$V%WLz} zr{oKxi;lWm*>>-8FGz`-E&J`9Q}J0~N2imdyxpD@p*JRwc&vmmrfDiToDTdUhwtS@ zy>uqYGPG^wASvV zr(Ya{Y}kj&h{0DtVy^!38O6y@y!-Y;`zABEYoc6rf@*M-)`y$4_W~Tg@6?SKPh@X0 zwQrI7dFn~CxlyVF-bi{!9ufblaf}+H>&jHhk;2GheidcX@WJ3)V=D7-U7jwLDz%Kgr?M z>n*_WG(v&XD3k85XT7}8os(h`ARng>6JWC#ozUECuIqfsUYwIeE4pj zub%#trub<0>5$ugyK=1kc39TX!6ROQGApvE8U3@0#&Wj=_a3{f%9VuVmTFiwJ~lm{ zsLaTd=~fG9C)^u|i7WIF6IQ6pR_Z#XMQn(jsDCW3>Zb7 zErQJ$a&mm$-n6#zjH8(HnBxHG6dX=)6Dfi}C5>k`-|AE%Ue0^smTdWk)sw&83f{H) zjjn&g?!n_TdU)E$4`w7NSGyf{8e77B8AN@b$PI3ceYq%M<9}0qiz7-lu?Jy#OPYL( z*qGprz_e3i#f;b$SNXc^mnX?n#)DkfChq;1%2xs8s4btHs6lwFSY<;+7`4c{a zILHeAnDKdT=YsERu{8b$qb{zV-74Ywtc~ZwVZS(xw2E9&Vj29Z;`YCM*Z3{mGrHaR z{i%8`f7{-x32Aa<`m*z*UHE=gNUr9>gA%Y%TAJli==e!pdXBt$D(ms; zx4kY}T8*M7HwAd~xj@(z%@$pw1&S^Gmv;qo<3t=(`nu%Q{5ZcRtUvMk5r*TYx9Dm8 z%D~N1_DQ>zljO_CuTRuGb3do3E>4wkA8l@C^LMvBj;h~Y2peB-GT_hddLqaa%j(`b zN-Z_$RkaY^iE3QmZ!5i5>n5g93H>4#W~rQa;vQVE!f_Y+Ijgdh0<|chC%9m6gTdyO zX=4CttuUFwX9K66D@{DABsqkxs*1nc_%#U)vumO9z@TeYZswpjX*a3*`G@VAqPEPW z-=c>0O@jfroSWa<*6?vP(yPTsdZal)_-$8J#3+YN(gowEQaUb6;jO|e+ll6cww$Hy zdj^2uJ#MjqFttH?BV$d~%7XZVZdPG9^LZX@kVZ+V# zTOQJTL6;g+buHxT-sIazsxQqX+ElV$BRXfu7o|{RSK~5x%v;*6M4XFm%OO}0|M?{6 zmvLle%uPBRr38#ZOXVmDAn;nHT&|ivr=CPXPNgNPyq$JWwHCJ|nUJfw5w(ONiR|XU z(ay!8T+ck@8LnelSSGZH8eqS534y2da&IX_&4lQCi&C%Ty2n{bG|X0V4iAq6HM`s% z={l>>%gC>Q0kC1HgB4);_`iQr4}}T2<+<_Ahm#MMo=X=qAX5I_F{kdlwTwNek%Z}7 zbXOa!`IR=}5m)Q3f%g+JFG==Ybgi?tDNFQqPGy~{VgnPzdfEPi&jff7wlG~t7Q5#Q zo-U}dqJg}GU-A3ag*1vjN;N<#;96{;$}Ilr5gH_!Fw*WnWlBcu7N!ppAl-PX2H8KI zm$->KQ>%HOY2YMSr&*TdXZt+235kXb6O!17R6&dI`J0-Ga0KVlCfBeJjJsoa@_w?6 zj+iw(NKH_}Uiqs~D;JvlZ0DioE3G-*h={1wtK|O6jQmGMin%}D^4zq+@d;3$-xYtL z;!UMW@%b_6eaeL4pOt+Je?Z!8eZ?qB^yvc)D_Z*)a9!_?=ujZxlfszyOW?Y6aHb8R zBZLwlZHxuY_?@lKnMLSG_dK2TMVcH;uDSMy#)f?!f6Niv7MXNdWh zg)P<+ur2r$h?+z*w_9i0?0c`^U=QijGnkXj5kuT zzqb**xyV~hz7pH@b7$~rEOYFU%-MLAPJ`O{SQdK~I{kY)gj$VL31fD${=MYy56t+& zilADEL>+Wnqw21uKO&XlQCqE*eW5tIwW%ia_E;Mt&QHoF&N-NiV`WWN}=8EbRH6^^J`y3 zgG+HE#{z?In`NK{=ww>m2MVb@ab;n4QSyv{s8xogIESLDi6@&?U#O6s#8EMCp2~h( z_K9YK*mAXZ?aUh~nPT4p6d=G-^xT2^@t=?kXHnrfsLok~dSbI7)E3p6osD<3?{X=sz z-~f9FK*xymU9k5qmUy11qih0FG7W30Xy@KUg$Di1`(_G)DK1Iv|cT1(}&v zG`6a4ix&1n%f_j{i*Qc?nz$mxG^`F(GBmGo|7peuYE%tbJ%!}hj$$nd}+ab(vfC3C7pWv4Hhlo}^ZN52jQ8&whtye{*!(7}=j)6~8B zOjIh~z+QAwlP+5L?%lonRDIGZyj`Wtl-}>9Hnt}Wf+a5E_2hy6SfTT;o=b_WdV-@0i~mdXSPc)UF=>hGt94xa})(vyaSk+FLqF>2b8i66D~UA z3S~`QfA+l?C$|0VEdGV5BzKxp=eXDCEBaQl^mo;-V*tX7qhtAr){Mc}Jgij+c4&-B z?=C(^Uu_%b9Ob6{%93R8nxF7fjU+v9JxQ|5nFLZ+#hI2h80MZRo8@$A2}H3>eVZul zOKrkJqdRNID!lf)FN%K6_f;1}jMfSQMx$(5&;ooF3U!?f+n63JJ@` z5Sij@0Ng__D>R-YQReT^6+dD56o2@CVE8NQodgIr5#DYJ;5v@R6o5=dUE~`Ka#<4K zd`Uze^`tab(fY5>?`=ISX0(;ZjwQl-4*o%-!JAB_o8Xe{cjiTBk62*}6P>mR`s7g> z&=h_bFXg2Ir+z!?gUm*Dgi-PrnH%+mk?rNefGpw7LMD*JHyuL{yna*ie0hV>Rs)$@ zOO7+bj(Ec{wCG>ZtF+kobI;#YQ_|yCG9d09yji8depXy;+a&=B1q^asG-f}8L@-D- z!&yESyWMxGMF~=3y|RryCaeI;)Hea1AO21ow7P)XsxE2JmFlo`K>RTsIHJH3R0=ww z_WxeE5itDaWL_k*{QFQj45E!5WTLuuPNyqwo>z6MWy4R8H!^{3guPjY;^Y6MdLRjiY(Agj@7f87v9~?qv5|4hRiA-mC#-G3~Kr@BzTl@ONjC02Za zSiYF!Yj_csu)lSS!(Uyb3En;xB4bLbAxRd(l>xP3Ud)@M-6+8hDd0s z(I0U3c;m+3)m>jHt(ZVTtJ+Z9NWK7I+6cBGVKPS#m7oy}1ZdHtBj+{zn8s+2AtG&v z@CF6OD*&n6Jfhx?%3lm7x0$Ef(3Q1z5NR8N2;1dmng{siwxal9!PMbSKn#_Mf&~lk z^!#eu14Tht-_B@Mq7WBE23(Kys) z-Vp651tfrgBkJ(RYJS?_WQP!<0PF_$RODLJG{wWiQZ6QXk9Lx5K!z4tU{Gcai4J9v7mze}11b zAiE|u7ve1w^q5l_&vQW_ZZAw7Vhn{I%Bc9&+!Lw!6{CO++G1N z4wyzVG{NZ8x9-^Nc$FLJOJ6;6N7qyNonRY@4uCNbr@YLn7hN#yz8nfvVwJ<>PzWU6 z!I@*{Ws{^xhWp=Fuc!{;rehGq-EiNF69D(d>&eF}q|KS5l?95OCO?8o12schLXi74>PkJa51z@r4(4LViau=HMY@uja#ytr12r{x_h+bkqDlGv3qY%+AMBGc56b`!^WdR#l z#OkwM00MmDNNf`KIqe`&wT9e7VY49^a0V`YOX84a``A&cFH$PK`oYoC}a$52!Q#g6@Bb{4)Vd>;6yO ze_kLC{NKyTjiC1YHHJ-`pZ}AGK}`m?AcKFw_4kw6e+hf?o(d8y(wqIQF=5+Moq@vU z5W<640%g)I8a}9%tj|ON4%Z(kZoX~~B>rOZX_k~#M)Wi>2)&;MgG8J@K1s1d#_M4D zoc{qx09Zr;j7tZxj07Mrr%nA)b5;yq5yH?5|FC2wN(w3+9ml)I^8kfQ9I^uMci9r{ zCIIi@DkR@F1!H13rMrtHw$Iu)Zyf`?77B3r1$Ha^c?E&FQrQ;Nu0p~>_=#BXec4K1^)}zA-Cmjp@5%r^gOimkp5&C>yXSvk&~-ITOQ)KJv|gp2v@kzQ*?K8 z7L&EFbOLJR1(;dQ10>fLQ#o0NNBX!A9jmMTA9EC|j=%%?FXfaHx4CK4 zh2Z*-n+MAI{JsCc^?s}*xilx#8ny?jJ_bMT&d_DcV*prUvoV|VB!A;xIwm3z5`X44 z7sAsr0cq^Ig&HV6_iNe}-F-_EC4QM?2wFVT$$6`iW8rZGAVe7#*Ank#J&AY?twDon zm}o71u-g9Xf|oXkeEGA0oWr^d;uG&@a{e@~W51(A<0VM-lxNtQNMW6F)>?K1Ulp1V zBg&X}Hh65LMZ)Lk$PM^=JJX!ZKyJL0q}Mk|;+cpwkc)!IS_zr_9Mgi%yxIk-1d;%5 zj&7%imfWZtXUld_Fue%Q?q(312*|YMD!#5M=2Ady?}g=y{~HE_0WriT&MvB726Y1h zUxm_L;R{uvcvbL=3yI)!QXKMZHwush(_0yk)QQ#y9n%}3sLpt6^iY80a7vuyiRE@H z?p|WNi~h+W46=bQWZyUa1ju{}{NT_PfV;)_N|K9X?ZG9tA7c#nW@>&_plwsmji&-w z#;jI1M7kRcbHWQBn1&)e6|vcHY#8C!8Rctf70#< zI{?cw1C~Z>T4wkMPsOAT8G z7=+sc9BFLwGGNGzoShdcfE@CN9IE(#g><)j7wS1&p>csQoge>HE9n*ht0- zevbh#*nijX_d2WzvKI);m-r{FVtxAa`u~UNo02xCdT1hx*|7cz zw#y;g|H4L5>?L|3=pFv!#Ujscga2CzJbQIw!+L-S-AU5hEX5Fa<%!}aCIp(1m%%6z ziWGMKft98bCwnYSD0iaMET-^lCniDai(BuWUGBrz#&Vb3T0)v2pQ$SIK zBo}OZi z=*hDV9V=@Jw=AwD@OBPD;fa!>rC^v9VaNUSH{xw#(KKD^J(uziw91~)H+!(Hivy~z zl@ADEAQFjM0bE4~FC?$!%RJ~-I*ugiUhdTM?Zrp;h`W5{o4k<*Ehjhl-vf&s0zEBU z0|rz56oeqK)eL)P@U18&3#U0Xb_5oB0`-OefrB@f>tN}9rNU&X$63T>h{#el=rNt) zCfGP%jbe-E*t~>5^vTW z$q9Uk=n8z9KDo^U zaE}3m=rV7C!wjQMn!8D5b!zH_(G%zVH}!sTqkx-GV-T3bMZveIKB}gGr>U&kAJ3Ag z1fXbPNGMdq9XIV2u+hi~&Z3|w*~%OM;aBz!1@c8u1l{0_802>> zWnz<5>19C076p5Xn@Kqc;86tW+ub(C#^eIy8@NVX>=a1o+(H!it0=iUV5@O$-c_hp|Df+=N`|{e#9> zSN<`{{-mKh=64DakXgUqv|4CD^3={GS5Y>F(rz*8XoL zi0hEi5Xk6XRQzv7KLnoYBM-7ZMM|jleUI<;1a%YJ{)4Aip65W3N`l@_)Sgs{cnJ_OT4Rfz~DY zpU~`seDRC?GQtX5iH$)^4T<>3XG1A+2h;gvtCr!#SsR60=M2s@OLQe_TMiw>>n24GbDiF}5sH)t>2#S6MXr2n+SpR9VvG z0ECXRP;5W56=+*ZDJ@?&Ym>j1le!dU!Dylx_FIzz?feYuzBC|WhdR{ z^8`Zk!$Fk6bXy2#4bR1%x#z_;xhM$}=&|ZPA^ACDLy3U=x3Enp=rY}&fiBcYPn-@C zGr%Gqc|ZW*KTMI7?I`#r)OP5p%;Yb)VS8+UEfe6V;VNJoJ$VnV=Bu!2Hrw93tECL- z#?h#lQeP1DfQdmz>qnLZ=#av;?%a z0270Hk8~Mf4&cG>QT!+niiA9d&Y4aAV&JLAQ0smVbz1*va!u<#5^>oVP$%m_J7k(_ zq4^9iUIF4^mvcC0ufcD9#6a>0C?taT8@8iw-(h?RJ4G7kZkL~dMp_!u;0(at6S^M+ z7tk~{NNC5=Zv%%vhwe+rh}P-)0NsT;(1p`*z|c9f$=5%K{Kt)d&pTN1U-w+=2qJX} zy>Ot0K$4PY=dmBBVX&kMY;oYqoo*-y z6$(+yB!uKgCGV>}J8nIhv;pQHNXkJu_AG{o0}zRH5~@hi4ec05Ae&Bd+Es|A+k=_mr;k^fKDh01Ndy10Qim)i;2#B|7jC%5S~N; z1y`U{jFAS?fCNPdp#u=aJVn8oK_qlS6}*L)j)Xyn&R|_R=gRNRF!m(lpWu7C8HQh) za<|B*8g{E@@ug%iR99F@WCz3)ZvifCH9g7!-;4kA#1?`)GhT8mlR7v}@ z_Jp~7VlqkwubNYu0gxhU+<7|Nk^On2-#+=TuNQ`E$wy!NzC2^st=WFi&bu73wmaXzU}I1Pao+RXFN zUf&ygIt8V-Q>OzvBF&*_~^ms;X@ z-~MXymA*j~hmq1(PQVkQvYXE+KL9_#jWBnXM}6aUCJu!l02PuoK2Z0v+)nNT{`B3?2DUV3zC3<_L*iGhM^ zhmQapD$!H`9FUM3r_paBA$R|GfJ8tz3LS}7SKtB1+~m^+K>vK$ii*{7Rfk3v+H2ue z*#NPROay@LF!?#d_;`9h45e+QlZ38IHIz#86-JrIJv zcQS(gXaj_0l?FgO4V#hEJma*hckoeIbxb?|v_!WWf>Dw|+#96$y#Smwu>r);0P@9h z0n&rFl&)}L@bVNlrAAR?{!>V-5||5486cU4lD`i?=zJhYG9X9(1*g!Ckqxf=)^Cyl zTjv(9&U+RVv>YaGi6M)wngXx!?&xqiz=TFB(>$bBQe&2NDY#7#{}Lx z9RSfV0fmLdZoq+bn{v+eKYK+8ul@s9q`fkk750x9=IW4#ALTB#WGB|AB_zya=Vv+gR6)!WiueFRtik z^S<^qwGizK<_=d<#f7tvNWxe9&d)4y4hA2gVJ^cygU9nF>DKnC#~#DCo5R->G6@i0 z58BU@y>D3Au%foqx>N&4q>~wmM0x`5n%6RC72lpGG0;$d^<<{3v^(N{yDp+%GwBO% z2dUZZOVJ3#_VVc9fX<$(_a|JqY387k{#Pr?GUAiDx_B3%@uAw{Rr|zP1}hyKzMXnE zYnx%dw~8@jAG~oR238Q!bd@*H%mz82S>`6ARRs30Z^3Z_KE1q191<_Zu**UbIi0&; zeK%^c<6G@#oMW11mi;RFLAs(vst*c}Jhhu&)riRJD=$f8Q;IHeObR}CcBt!UHIAP4K+Don)ALhy`4?u_Zu%?8(i$V z&6#i*Pqq3&FL9zqi8g}sbLxOC({-`QuGgdVg#<#G7CpzQaRju;T06(nmP1-=Vs9XLeo6-%Y zxPudF$`QVZxgsvdm8@nf=K~AO!^GPJ0(U?Mb$PhnOIdMg0f@E6R=~`Mg!-C$kILk?Pw!%WY z_JJ7tfHlv3M5M{l$Msgc&wO30Mdp+D^IwVt;JzYL5K>#Gi1={tSZ})i%V@+C<018q zPqm+F0_B|K14`BN#SDKHo!zoXx(BcD^D1ms6qsaQHlC8dexPx#GaT@}*!5Nyj2U_L ztS#;h#^`C#rZ9P%-Vuz8utp$T>3SvpPWSa@x0JJyFBpvryzK*yrMyWQ;%oCq=x+-h z<|~L)&)(67n^tI4iAM_PC1JA2DCB8{F5qu0?b3Y`v8$xY*53AHWp<(x+eixKdM1!M zynOZ}AL&@(OjpQq@NF?q%sJgLvwm0ZMvJw5{~teThni|F>zN!69=}VchdGPPzo+SL zrZu5iuD=s=ymARk=>Qo9hME!@LIBR7@ujr}+1Q@^G6sfIEds<}M7E%o80&%*VcPgQYsV_~YTENSMI7y)TP)mJJS zpI_{1$0ZUl7!wvb8MoWCUL{D#NN3*8X);3Lj2+jn92}5dP%HEBc$t&Izf{;}EG#&3 zoU39<^D5iT`5KXcaiHW?U7WGvE1cS*p#vflKV7==&mEfIx7r8}w{>~z$Q_ZFFNXJ8 z=S$;!|8O)_=L)?(Wj)>!TLk>F3F7ljMxU#Fvvev0-QvVN4D^zvMt&Dwu#4Z<6<;RF zNax@%=;1SEq!In8La7sk!LJB;n&buV=lVL*DqGifM%h6Y-|_2`2WE|8F(G@bDAeP% z)Wb?8G+N*y&-%VbOz@{OamboQs}9jyE1FuOFJTV*LOLcEp2UP-s&_fp+zY;^Tv6{U#g;2A+&IPR6i8r!KA8L@=KV3&erEaVfBo27Y%Wp zM1JLXj^Y@4A|Rme+{}o8%(6n*fSl)I+9*MFnen@#Els>Jrcou;bTaDf($cUnQDQB+ zsEbz~A+;Tx`PXUJTM~-$w2=#6+LG=cM+p`3gq^?pj6H?X{_$ngh3c2j;J#-hX;|NyGdmyjaOIBbRs4+Nu8GU*u_eK8!qw$wMPsJAzS^@;tG`#QiW1S2E9zjC zdu$Pd`SKxu_lazBhv0ZbcvIQDi?CVv*adWPHH}-Sl226$v%NYy4q?V1*d^@z{y^)( ziJ}pe)C$o`Q7DYfu>7?Oy-fL?+ePg!TyWqxrPi7!y=}eWw~G2&nIf8~66lx3wG$iP z4-?)yhHW%d3t1)W6T7&aeLZb^Wy-do^->FWQdm+7-h!4em!EQVX|dOX(c}w7f+V!n zEU>51&XMx*U5!sl$X+KSg;8z;Zo*03X2r!VzFo6Y>syA8E|Mj34H(*s@-gc_AX_PI zuF>BoyCIEJKb&QTC(E(Klcp8b{`PwZJOA7D!5DoKDY2JNnuKw{h#WgAT zP&VdO`DFO`%!Uoq=;Pqd3BB(__R~DNNp;`MSFhyVOnKEkEI_JOPob+cHzLo_6G!=nQySL0%SyrE2P8jnLtT6z1J-~_rmD*miSi%2$uarGnT6E!@@us)r-)DdNh?CmP@i2!c;6-R{ zvc~Kk4qTq2AUBSkq{{xCFUN0yE8OyFP2-y?Mc0_b;Y(4!`ooA}`+i#rT3^uLH?#UL z!wPbDR$#OWbpD!(LMAjRX4Rr@x{tS0!&a9&Rvcc!IhY2*B%R>4me$X6(p|*pWfoPP z4}?o~`1)I_53URFZ+Cn)defK0ZuG?o-DC9s5%w2QaV%TIKio5eySux)LvTxQw?J@* z;4Tx~CBdBpcL)x_Ef6F~kObFYL4rg059gk9?|q;5dB1P1X07h(l3liURWtS54t)Ht z_tHDXgpl&c4=StqMXL*~Wv&VnY@JV7BR1z!FSRVpN<+%BWuIZtV6qO$FyEU>(r-XQ zecH;hz?gL`asEm0U!g99Uvnm6OEu9+CO<k|zJ3sU3cv zC;mMia=b%7smx|-P^{8{eU}(?_R@8aDLuZI{1;) zUJ+MCdP{5G>|>xa(WHDu+Zda!J&`re!X&Z?ewo>!`62iVe^~71uLdZ}AiUr#w=lFx zEDSaBwJZHE?mQXRB4yN3kVIe-U#crxUXClXo97VHhaUD+?mOI0lvwiH7bWgIWi?>AzhA1@7;(D`NB2N=*5x8kd(`ZrB{*yx>8{*^UtRy z?8H#h2edjAZFA~9cw})1B}#H(&b(Kx_&MmTxrcN|SMM=fVTWZah=vt018c*_Y1p= zk6w7RP1=ZUqO+lW@kWO%du_raAk5xHc0G>Dv#<9C{KW%}xX2%|rnk$cW^{$I*k&S^ z`LDxsk0L?uQ^tr=s7gm~pxG-*Ool_USF)D`K)dL9!J*R3!T=E!%uRs#&S8u(%Zrf% zRLub6W_s+2RP89zE*q@`xX{se2B}apd=A#FNzZ}RE-7}x!N9ZFx7N4;m|V1Np8;q^ zmqy4>wb}^AiRc$-<;bB>_Y4?s68_GYRdl~4T44IEB6mxrQTUf-wwESn>s1@SDjMM7 zvh~*bfy9SvgCfeyh&$q4YlA>tA%Esv_GofsZed z7$)>9gWuxaWm2!idHzy=)+vW@@a9yfO*`F{mY5FlcppuyV^QKqKZX(UP;}S}m^A3orvuJJ~ zJ{@ATK0Kay%?y-Ny2@2^$&-u~c-YL$eW8v7S!sL;=|1UC zc{!Jg)$+BKXIuO%;}4B)`AwI&?_6x;y8g7~TQJpDaH)pug(ppE)tlv*4bkDbXXkfR z>B5_S%rykt*Pj47!LLpa=v?fr#;dL_2z+eBxv3h{Qa|O|EhwK?6d%y3S$pPO2T1uY z&>uD2ja~ZkqRs5D7><3-*Wf46Kug9{mX%o9oZ@OKG-Ji$igUx;O|uAv0t-rZ@%rW^MmWjxxjybTE|BTKDy znx3X_sRF5d_wxg!M#~F3gRmiR&}4E4&~`~=&o>aZB)0}Hl59uy;EqkW^LX~sA@r0gZIIWWhJH} zp^egIV58?nYGQqjbiA=mfu?R{8#Qymo}DRtLq7R0&9!zO(&%M>*ACgw)du>ig)KIR zP)?HgQxlcTFnmhU4Vo;)_v=0R&>(hW0c5gI(xylFHcj!15%>MF$HGA0C&V8L`5tKlSenv^bvX?6#?)rc(wo1!6cZvx zTpxOy?-$6_Fu%}dD@O8ByvOK%WXx62VccFv-zQCwBd9mPB8qXF8z16;La6yY9X7;_&rAi9-gLhD#llOmXJ$3RaeG_-Om^g!l7h)I; zkMqKk)Hjvzjl;z_abHZDfy^~s9bAT{dRfe;?3*_QIpWolU3&;SOPg2#5~uuNA`&*B zv#-XF{ka;yu*Z&as}3wwKg5+)r2@@R#kSBCOc+JjCcND%B0u}d&OxA}kEv@wF zvUrPH9?4GJUC&v$b?TDyS>?XT=&ni1Z0*~1&v^MYO3ryRTVI+gs5Z1ZbH<4|vXt0H zX0On>+lHY>6UuI=wu_glj68*kY#*Lzzak&@omt+dDOfPU8uB0R4z<=4mWq_v) zf03qN0M|f*O%95vAKuz5{WHz^Q=7LPCEIQR|C9fs5_s-=HQam0^F21)5I&x_5f0PR zE87^)snmq01JF#r3ruEkyzs4J+^kXwTewk^I3**WI3^15Y5kGHsP-YVzXr@HY@>gk zb5oH#J1Z)A^(r9g`~(G!KvV0j<+i5HYpPQ6J&R+V`NFGP?m9C^$aQS|b_|1pN@Ko8 zQ}%#B9c9x1a9n$=$2_PYg1c9tiQUj3f@ z09Fw#QP4rREmeG=$UGaur0De;yOC8tUSNT|>E0)Jff>vl0}{NX6hX;%hA%ax3tN@M zUc}WR-&4M$bh2)LW4S2bPEf=BLD~L!nO)wp(bw7WHLQp!@Z1ky9%Xm_H0O{s%jnw8 zBG()2yhn{6hbuywjER=AhFWXnK1s1*v-kbts)gbp_wO(C1{8Xgj9vyBsqH!@QjHfp_E!R&5Vxbz1xjgvpQ2b^nHwL81=@YMU9|({Ab{b3-B|P28VSAR+yW$ba(zNT9 za+j2UV=Ay*t7^`h{X5e|$aVGWjQR8e0j3zfQ^c^;l=;Z-+sHsZYjQutC|jw9ImB)* zf~2!W&*AsZ7r!PUh;@^6$`(UNTfE4cIckCy^dn1-CNKP7Q<|a8Y4(q^L0rFd-xvoK zVEc;oTJgm2W-nM<&HLV04(mETv##{p1N+CXWP=@Ru?hRVj}zg-2eME3iJOMW;L5}~{uFu2NYU(Z6zA_Bj3 zaq=#F{X$HY;p&Q~Tu~jq@p!S|6S~h&^V@#S031vlyHvyT#GlJegsj_N)r?WTu*O(+ zFX!BUavr4ghWAx)eR)Nf9_qh;@>5G6*G}H?!&^wz>z8-qxos4J`7(x*-4xf>0^*W% zv^8!v>eOIsMh-;MF{y}K4tW|C+dlZhe7KSKyIE_Xd*E#=w!;|eb0GGPdKpqoJHj0% z;=2D@dq+$3lz9AL*PVly)Uq@UPee5OHP$2D4j~RDj2YT&b3Lhv$T48xf&t&1C_sh# z`#1hIIt8|{}iq~{q`-O&ukc)(t;Wk<*5Jukxl?=;=O@#IqUwbt!Dzu?XlT3k%ZaqI}&#E zqdc#q=s2x@jX?9>vBS^#(=*y$myaIbD{}&pi6}Tzwc{}6Tb;rChGMO)FnELC^RMIz zdt%X0XF;A_qSd6jj!SE0qKBj=_g9PjvZH3 z!>aKWC-r?%vGEF(qJ&hFOt*>SxQ?YG$~XSqxM+!yb3{w}`~km0@)U)_H_rYJolKBh z4%1w!Ot<}uFXt@JTc_Ex>uW70F+Vh>ZBRLEB7b9!QG39@HAb35BY7@o(+Ga>-eQDK1*cPoiG%74&;HVcctsfJ%=!cfaw-D8vUpJu^p%+luAp-(TOA zbDW80FeN|@Dp{6uk4Grgg@^X7RU)uxb=_PLI6V*gR$77&1T3d75< zbHDrJ{U|IKk@tp@+l9j>C)yr5Dd=oimOs-%r~{AS+T zGOws~Tcq^oBIT21NE7LK5%|Nq*WWWeOW9UmO~Aj){!mmnva1^R<-)E}Ucf=JgxA{Q z+|}d-%NeJzJL}DegLL{>gkP)oSS-Bd=q#i!ddavxkZL<(4B@z?@Fl%JQ<t%Mt=3S2%gj2fM?)vN77<$m> zmy|#7zPO{3tdDLx-hVV5Ler0@;wILtWG?%0o*5hRNT&vPU=YMqsTa$V?i&aZAZFST zVEj(Ie{f)kmZ>t!VzeobLtgIkR9Bc+Iz41-FD}6x2r%b5xG2M5nyYwS*jMFPSLKrZ zd?PMS-g``zZzfq)9GXTzv=?)?qwzgt%?d2?E8S(mHt#z_xLslYN^FDx8{K&()%B}z z)*>34u$L*1+4?_*urj<|D$Y9S1mzZ{1Ue`+)p@dJ!_vQFj9-!)!uP426ri(4VJrMO=(^5aaR^`JM%18NX)n2 zwttq4KfP%+e7^fy)Km1MW!Hr8249O6zw>B_(aekm9zvz0yveUFz3Ro#lM8Dq1o12n z6mL5_RSjv6frTO2XLA{k9%y%kv@D5sN8xJ@1J&+<;Qs_RvA=#lln%f_A`ddkO95EU}7_!pNaM&-Q_?m%tN)2rhiV@qL)z#5S} zZS<}(yGta*!C+gJ&PU5m{K^ehIvR6)xnhR9&xo zc5$z;@Ffui91Ag%m?u76v=3t=mTQmCspi?3IKHM&J-ILQ7tNU8$`= z`nVd7#HGrK#A=iVU{2Oef_+>8!R3u(&>+&tp?_4}>6G}F)`VuW2gM(8`sXe4B zUEZA8u#RWdIBxf1#`&nEJnmYr$ySb7C)p5j1+k=O<&T^f8i*|g~Yus<*>sNHu z#?7;|C^akFn*()|`^W}+ms;afVm4H}o(*5c2bRmBFU7vWif+@C2Y=3K1_&YArHMgJ z#{K35-R-=cDjR=QVUiW=xH1uP*Of_gP@w)aMF}e#8KgNwP0l`>dU{bk)|P*W%*Kj7oRt5b0axFu%|J z6|7n`6ci$zTc+0gRN1Vtx-fPPefg0)C_5HbxI*fezD=|{T zV)v1pD?)R1_#dQe2#>#l(Q`j~J4s0R2D@-%m2AGEiE6At4z6)6;Fk^mjTn~a8EP3~ zr%mf-PIh?zg`JUT<>HT~*vB@M^3)LlF=i^Pn^0KF?`{Xr)$ zDi^Q}!ikjeWZ8w;1)u&;nt9?ypIQg=pGF|` z%`6eW3Oq->%dhnkB}A2}f`3gew9_^i?TR^;{|=4XYeVwGU>i#^;s?{1Wk?Hu214?; z6J^1K0FEfXyQ2zGC)}{%Y5ez$@JtI$v8VAGL1VS_c$&R@d-3M#U)}Z$`vvz#cPpt9 zINpkjBzoC(Dx71?7HQN!JlA=sROxwSk*ARzb3+> z;8i1p(ScI1SEOf)(sJnBE{|-U zV+XHi{T53Ub$X%{gTT6;l=}WhoD{aq8-^P2x?(7q%*^{T4Mg_eq9dD;GsYbIPNkk_ zz8{@kA2~($ON&m+EyYscsUf4;pUb1uLw#ikdSx|Aesen^coI@E&fAv()k>gO>K~^w`So%q#Ht6WcHUh78;Kk;7f6Joy zvhH6XY)*R>1|y1hy@@mH(Nx2U;F9LEMZzmwKSxsJ7<@@_ip)$p0BCHPAFMxEDv zS5!E7-|MBKLb$(WJ6X{e)aCD*LuS{Je0ko6DYZq^h{vx-m1P|(6Cw2lkJ_pWKkX{t zUHh08u0U&pn3Ra@`L!#gcNTsx=!cLqOioGmHnqwc;xd8T3&xQ-ISG)Y|d(u6Gr-1tK) zQ5(y!VPWV@@!3HCHYI_hOd}m%w2+y1fQOdFsaD64P&|>wp^KR>*T=2Zys4VXx!Ezj zN*j9&UuP3af9yORxq{Kdmg9o1F(Uti*+1RcMs_?A=;N*?bT>6z!E6L_r2CRYcwens z3@eIi>j=KR!f2EW8eum2Sb5Z>nb*IuJ|SpB^%mZWN0xW3c?h1?ME^FEoOj{35vQN9 zSKnI5is!xCp?Xa|ZE~?6r$q|yC58iXPcQ1R7K)eqSHdP!F)vm-Wzm?j%$J;~Oxv7^ z#O#UJzZu-X-W^1#Jof_@fs*@nqy}@?ROes7y z(~B!ba6FM1f3RuO*7R4x*=UO6dmhVtYcTli7xH+Y5VYN;>sXf1^@73YWn~mgljpww z<1CL<0Nt(fO_hm$b`YFW&hdr!F|XtKnaVsvoW_wUZqdVuB+EbJzpb|73nZ5#_3AFsTw*2s=>;aGv`*Cc zz3V_7^2yvJMj?S{U;CJT47He5t|%=|=t9Kx7+rdtvPG^Z_9jPBLWsiq1D&$k#{}%` z1+f)8^)V94e-7G(2@MdA{d!AsOeo{9)XNK&#ZOo(#a4)aE08%JU6-_gr)e)aAEIWY zkwx-OdXc#F-FPCdF}O0|b9aB^14X6hOPciMsiuo_1hJepmIZp1wMETQu9WJb7mMb% zv%L}HLUvIr1f>CP0?!)v6HQg`WlMXiT7t@1JX}c}_+l;+#EH9(Hik^qyoA%tyIUjK z`UBrxl1rUM=p(AldgoQ9s)deY#^8M>Gk`f3DVUZ0K};8b zcTKyz`>y?M%fshExLY0M4b6FVErzhlg~%{NNcnt0uKlc!6^8a%l?~UMYX0O(w^Nh* zt>IIQZzA_E64R^eNPZU=E4Of#0XAB7Wy>F}vp5JfjU(jY<>iTqw5xywrb$WB)^NIN0^z(T{s&wUaOMrjtHw?8pc$ zqJ$5J`!(inOiYevolr%m>haG8vxQ3R*Z9q&V1lE%+mhBOcd4LoR&#gx=jy*}*gh^4 zee5pbPFT60cvkZbTZ`$gqrcIN7yDR+^QVB(G*wQ}@x-$}e8)l%O_|g;iXfFV;w}^J zdDk~Dms>As9J-b=2M@21{S8&9Fh2Iia$6DQfzx>}@2I?jlPVbKPe^1KJ$H_yJU{jq z`U{m`I`PnG&lfZzQFrVsz=j}ViHfIS{W~BZ_I3~7)7H(Ph^cQE5z~{cdY0VVQ9BO zvurdiNC)H-$$G+k3*%F~i!J{E z$+6Jbn`c&n-?~Plw{Cu1SOgq3HO$1`HTJbOxYx1YmcJE2NcEnJd;ZNsEgH7bz-lD8 z_t2^SiP2Dd^r^Lvjd-OF{m|&lSSe{pr`cD#BNQw9?QMQk+1d*q#n6UWRqeRU*|a@F zC27a-p$%WJlkh5Qr}W|&75*)S0`^Svf<$tS0`2Ynb1n!$Q+vdDZ##~rHtMG-ZARHG zf5b0W>yAkxhaB$@=1*xHc-vKJgLsWc>|f}s5aLT}*nwAQZ7f!L=Io&|ltPWJ{Kc08 zlM7!NYYk2s5R=U8NO3x5z0FEed?JS^X)S-`vcX|U-mFypUPr}pgPR%%_(i}eAw~D; ztmk`(;+3HP*oSd!BYU0kCOYdJsetUTQ#fq7J1Adt>SMTliLomd3l# zeFW3F-0Ajv)zu8b#3>C6$yFN5k(AV9=joI2m`T2MTS}tMGfeak@iynIXbpboee{jJ zFT&3zi>x}b=7>X9xuzHJ(Ktyi$05{pRDMfq`SggT zEow*(v!g1l89a&Vg(6ADU6UC-5ZoN_z}YuQo%r~ex~R#vSSEyK$q`4TMCrzNCrd&1 zyZXR+v_eM$a?o*eyjY#E`BM75pm>Xij}fIT*#qonLJFzwlCrv%+iY3~*ydU`R~22( zy1tPefj1g@op4Cpl=Dj1qbVV~Q8z3FFBt=Eg|yp+Nryp$@V0_8=us6#yVwL z6o}!u*iDv(?XY9piSayKGc(ReIziQ*`b6ECDBn?;j@5E2s*66%u3L$=Z|uyw8Ckw3 zvpNdbUwl@oEUp#0r*4DErjp+Jin(VRUUd|yvFireESh)R|GX;Zuub2IJld#zd63 zquXWo``%?xR=?Dgl4B7l6ZM6CGt!7FkNu$^3kD%E3i-%_&hvBTd;S2O&V1j_=WJ0+ z;fbC{rpt2%f87;piK-&5QX+fUqko&^y^cP#68E7#!+`Y|^`g=PZS7}6Yf;@cf%1dm zKs!8_$?y=@;O2GZ>z)lzMYp&)DrQj-U`i0A^m6am&n?B!GCngRG>|w>MV-9 z(@gOoqq$fzfT$HsI?r`9(oFX}FczMA36(rfX}Io=FmS_BeR!Ka?oE|+e#1$qYqMun z*n#EHMfEz_S?h5L(DnA@7Zb@cz3GE*_OI5@VP%J+!wg|I+F?VK@>ER;T`fuu?Se8cEIhwsE6qR(iB5wCR9FWsU`6)6u=*omoc2q+& z4`>s@bDwwqta{G#;A>Wdh|>i2sR5KDJU%fCNhDLLbE@dt)SeC6CjC_F7>mPd3|*40x0Xj1uUt z58pXC=W1O0>FgYD&2UpVY+1+CiJy!by_brcskBXV*7aE(H36ywFr*=u`-4?+v$60$ z=sqc;Hd1e|Pdx$ov&}g+3i>L$g|8PkLtl|G#W=$Y| z2>ydH#5_T)-U1DqNA-b3?X1Jf1|ZVvtiG%Ug@P%_G{8nc8U8$@u8~A!4R*+$IwOdx zG*fE4Knq!qqNR=SXPQL?ow-=X{Ia$}%xlT|1QTgRqa-_)%rWb001<_bmO^ondSzY> z!!G-EVpc1Mkw$Kgi@i=lyIS&)&d!VZdh_$x?qNx|b9 z@G_Vs?}|=6;$7fD%y5ag&XB!)!hL@5&j{ZMMR|%%RQ*o1szs$hled^j7 zRjN{W10ANX;tw9@BMx9^292(1i2|?BD~%}cgR-gHx4-|Gvk^wj3v!M;)Nx5hP>665 zcjcif*ax4SHRCV)LV>+c%cli!T8zp^Wo?Uep_{%m49(^=2xS!_;`6@}?oi9wk~_7n z^?UB_WcvHF-NFZ+?T`+9CwtH;D1v~$Kk(?0kxk0)(Fw(D5!eie-6!-fZtTPLC#BWy z6V_+ue&60SKt}bjoK4>omqXTG;Gj;{7$Y@T@7Uf`a+H)hjZf0mFS>vpUcK)q?%gx! z!9k-Fs6O3Nyy#O_sW)tx_vy2RAN>=u`IvS5{#WFHcCnq`TQZnCbgQUx zMlhvR{%f>=f)Mg2w(v7UBSioe25NBWuW+eXt6;YlRrKzV8ghsobr#iMdBz|~83tcO zgEI8_8=gkY5qDYDn{u~t3$9>XTm&WqTjUEHarb88B{VUU3T9!KcD7NFV6YiO$sJ8r zuY|H^CHH<-0RW0Ae#=l2vAy#;Bj;v{K5xq!9@?r2QqD0&bXOM=oN&N&Df8Z+GE7a_ z;JiA2#U8%kst$m=2gBV~0uJ&(EqSlTk9`q`4`0OG+L0Gb+P#uucSUb6llhXO_)4sq z{VXr%<1?#-smjpIhm!=HG?~awB&l_vth&I$$A-C3$TAYN+VTFH@KGo3Znif$Sk5w@ zm!mpcUNuVm>Sgba_%cI=MtC)#mQx(rt z6twUvBh1?E&tP|EvC$?hntYH;E9|$?bVFpk@oa&Y2F0@=Wu1#uhcGk&e>6nCYX3Ht zr&B}g?uQ?q2U9Z}lF3-Qp*@ds{!nRVTQ1zq7M8@7XFC?c#Jg0B?P!jON%lVC!&Ia; zvd}|$(+3*0;1S7A?vlu%J~64f{bH4qR}$gAzZ4Tu8mzct73svHNQtf=bVX_v!CGzl zo2KY1>ySSv2-0R-Aci&Bb*&=QdUkdYB>;e6WG%0%zsLcSqK4CQSB|k58DK^3IeJH< zHd6<_<01b-Gpyfz{G!)>VEAtm9Z)AM_+Vz&*N-8!24&9&3Xu%k^NRN{1}oqYXHw9# z6dXQx>_hQ51dHhda#qM(igZ)HAnW{Y(-oCAq_h> zZ@rYW0nVd(jRXwE3aV75@Dj|0s;9`ny<9k>g8LyFc#N>gi>lpp%9FB3g>3F;+*h|T ziL!m!gZgH>UPy=vE~~Kk*be*z3xkj38HsZ^DP&B0fyn*kutzvbiKjVt@(23Ykf7m- z@E8{aeH!x@8+&Uq1?!?YfS&K-haQB4=~1$nJ||lMn1vl`1v$W4{$D4krS4z0N+#h( zmU7`fcc7*CP=8AJDT}UD-8M%j<{|X$9U@M)Uo{1dQx#oX0o-}Vy5`zg&bGG>I}s5X zFnWUmb&|GO07>L85fCIL8kYp%wkZ7@HYYU#mt$eahDT|SrvleyrTM>$ zYVOdu4?wtkDrnG!!5@gs=Rypk@>5SuyU#%2EZz8f+_h08V{B`^m{=;r&m{$5f9L#M zhwqBQCupta#3rPNWL;RqSz&fI2h!5i{^u&Q&?40js0jTnHW4+-7F|Brk#enbgwAQ9 z6}|rPR`gaoC#X*RG6DJaPz14j9e@BOrVK=pHk2`d%p3#-4bEJwL28qW?8Qt!%r=z- zU_+Uu-)phFGX--Kwv8i5f@9aoW><(G2W3ShfkUp~BO&nn(5pJ|b0!8E7K~ufAD2un z@F?Hn6(8^#-jkY%LMSfNN3G?8Fm_G;PM^*F&6^%dE?9Fr!eLfbyjyCf`S1LYOa|#f=C400UI&hAU$6 zLLOztJPs%#M?AancS^Z8#tW7?V=nrjVULMXC-g|AEQXFA7=ka(=j6QTH0<3i2Lpg` zDquk*Rr0+taIQ0|I^7gbXe>P#0+5*U*k^y^iGHmnANQPBh6`8DPUou5KHtf74wTD* z!-vXFg6)G&FYY0X$A`++M-F{6fh2)AIjwKG4?pGfzRQQ`t#CycvAs#1<;_3{P4uuX z@EPB89U{C*)H|?aO-mT0m01On4e?k@TL7S6Qz`(KH^%IqfQKYRfw=vX3}yNUF7_)V z=kMW|zf5?|JYl~Mlmy>@_L&0MkgRUC)<8L_=%^>i)D}umLh4DkDG-iK^%|(v(x!K# zbB`GKB?-B1jG{twti`kil>a!|@sR+pNL^ns0^O!Kr?AuA8K8Xc|MRdr>|+^#MeoZl zlcl#|NWVD?S~@5W^>8OVg^I$u2zE$Z$@M^D3hY5KWIS#$*j4cq2AGDN(q&kGDAZ9I z*{U0P3W67R5r87l9{lAHHoM8%ASHi-Z0tPVY2;m z1b!;!KQWEa)B?P_6Mrff;{eV2U8aPj>6)Ul82-9Yfa{6WBzmL$G9C3DoR0eP)d)eV z!@qDSw~=le+r!{Ov;YZij?}&HTfBc2bfu@d8I+dJE|wYMrJ4l31QapH zhAdvZ?=uIiLISFLU~oLY^d2oqoM)df$#P&Wk)-EH7}sR~l8Q^JtWA>SykLEr=Ijx%I{I*uVZZ~>q|7h{Jx0Q z2yO@Cs*Vt9A9G&AcsT?E%!cOg8{p{}yy}*_ypo6yD-{?e`Un+i=ue_%k=H~JqrsJ%V zU&pHh7)3(LWWz5A;N0Jh#y%Qei1?YHnh07&j%+yoXgSiOG1 z>J|5Iq~G85%4$3T!1i!1;EH-J$hSz&Wsl0Q>ImL!N>P1#c68@W=4#^?aEk2mp#+{i zVZWCU7WNS7C^~4?dNO?8nM&O6#X+Rw8o3&6exFCfSROD(9a49W<(Y&#we?@a?IQ6n z$j;PzM{3W}7-|8aI1CMV7EMkk$BH2$U?Q_SB{M+h3j&i@wXtUMjWpc3hJuAc=3;!( zPq7JqD#2~3$Z%?r2;LwAOfuiNo;maajZpqQH+iK30Phs$OM#&)ie3aZ5ugB=g_so! z*m(2HMG6Y=+PZ*h765fvcY$iRUMfG--#N9Jn61Ao5^S#!rE3BFyfZ&uVq<=k_ax7v#c| z0B#Bq;;%Tz9DCMEimUMph4yDy>XJX8SDWgR)mV?yMM{DUl0^=twZ0AinU z>QKR~vL*Q>nHmTo=k*6)9UtC=%kGl4Tb11iwkqdjIaMM6#`uMG+Fmp>A1n<7hJ!>9 zQir%(I>Q49jQ$3&Var4fYep5Rd>^)ef|$Qnx-hDE%P@c>un5l;h0Ic`P0&-BY=G`k zN;h%an!ZN%DyJ%1#%fEyX%#S55l-x(07PE&*2Arg^kNQns8{zpDq*1oP^Mlk!KG#? zrrzD?cGElA<$O{nR7s;XWt#U#DM}X2ua=`Sso!%A^Y`oI1kA-A>8aa~nE)gd)#ahFK(9>Xq3P`wG7l6G2>gzCDak+_sF|5Yt+lE%jBx?jwgh^#dt$`A-*&a z779gRi{OL7%0g`k)M|j;%Hm+G=t{GDSR0NHL%|3GfJgxVqmhB~BmcEJfdJ!Lk|3Y2 zZ?GX8AG%|BO(9*#Wr)Il-Hn@`SV+5}gEPgMD$q)%k&aq=(@VmnWBP9Bh%Kv^sMKxK zFX{=@lD4yNgt~BKgg$6@jizSeL=1WF5TJe6*++T3L1|xvV7&^8`ibUgn%hm^=M$!Z zD+P0#euDa$h0nm&sOQN^5sHBAGxfa3i1Xh#>&YZ}@X0I~;2)qI`!^%p-4yVdt2mG@ zob&T@)o$BkskS60X*ZGr%i&NM6f9OydxB>VUJ@+7{|50lm+&(H4eJP%1t2B>OM+Hm zWA9p%yd41Dp#cCLVj1X1C-7PdR`&^5-T$>z_^0kr1itpQr{M?6&9Fdt02q#t%8DC5 zL5SYH`MiSiBQy{+;GzySyQFJ7n1a!p+V!OZLek@>L<(2OY8P*H6n?<80L&QSXZDkQ zRp7r5WmgxzeDMml7lR4G5PNBy(blvN*1U0+Z~S)4qB#vj^1QS7^X!BKD)o7UIXfdF zJiEY_lj=Q;1t_KdOcEe}t62si01jRTEF!~<8fXh3+0T~zOFkv^s%$QR9~<`YFBcN@ z>#!Q-fbyYefAhiqi(v>M#=@T#A<|y#rG0~jT8epJ@a5(^l)@g3;kmV1J^z)ZHWYm|H*SjLPBpyq_af)%+u+f@x9g=RR23oupV|H<(FG1M{ex& zU-ksf^ZH+}KzzR;MjY@GEq+hw?a77)#$PdSs(vJGa!l@?Q>84Ia_OP_*>e;jqSz6i!#^M{iO`m1y}0c~64 z!D2hWGM`PL(+(62(l0fWWB_nr$_pkOs?UXJ&kn#pu=wR-Q)%*`EOYrGOGz2w1^61u#3ZBvDJ(bOPR$NdR%o&F7W8Z*N zsMD^LgfvrLZ;J1vEeSQgM)6$aM;kTw8GS+QWT#3cf;C&M_Fu>fvI+pjJ(bVW$nVZmgyjndd~POfYNCf&mxvVT zs6^VU$w4zMS9(WisrQj3Nv7boO3+gj_O=*VKE5e{FuDT$_05^3 zvxl~;1i5>Pj~z;&H!jgwts@GE?bKccnKVnWo)rTU@vegq`DJ+0&l3vD5-?oy;MX^N zHtEPL7N%XrJwQ%$WJn|$H$xz4&taN@+k3KDt{z6VaTF&~QFyY9)-nLz1GcCo<9jCU zRcb?+EVQ4~jl|6jb42#x{-$huHnPW}3ET`;QRQBEH-^aW!6_w}cyd>*w4RBtz6$w# zAhd>rv>KOGsYsOsaF*85$YM|cs8ZOAHqZA4cJGp?Vw<5Lau_QbNs$Z-kYhm?{jMkp zt|RHek}ZJ1R)bHfKItD-4`7VX!fm11jKNwNHs#Q4eAY-v46=lUMKy)2-4(&X>;aLiI2oQ601V)Ea^3T=u6nS)Q7VuA?r-WE^#ONfFNt~vn?K|0Dc^zu&X ziK_)(0pPPkENH2|Ld8?H$YFwUSU@pVQ|g|w07=8NJ~}HD0JdO%SWi2|AegLd{};9r z6Ro)?2EQO#W2BX>2|?xG<2rSC#0S+@8I~8QE;sF<^DFh=(*cxmk1)Fe%hae83L*U4 z7W^&s|Ckd0_4uT&fdH5U|F_1608aJ*?m?Gs!QZ)n8?SXnAaS}xNlyXT_$S0Q|7;o& zR_h8K;ui1!|CaYZBjmya29jXq|68H|d-h_Yt(QEem4_-ZV+2?Y)UW;{#*1AoZBXwq z#}SVyY?bltYrXWSKs`b?GLqEV-?_Ie-7kO#Vs<={NYxD`K_pQC+Fy+iz<1iG*BSTV zivML15vBk&CU@vlA{g8hz=l=pskb1YVc;*1ipl@2r~li?tl>)ShZ-OV<9;E7r9pTH z`=abasEEGatmj(nb%G@fQ|nti8!w`f{miIf4i^lP8o;tL>$mW|7F3Ida91$bGTcwa zs5_usA+}4`N%HVc+I^n`Msnf{5V-nV!0JhkpcNV__%MuXfcBZzfe$hg#1vd)3FCAh zCKrIrDgW9H0DM3vY}pnC0DOZzFfoi_Qjft}^2`6*x_pm-lM+?tUiO+b$eOrJRcHHU zieSEAm<7Z@lsdh{b_=a81>kiL4$l+?oH z7lIFnj^@*Oxf?PO#KVwo7B&Ok?V*@LXnz&}(vkp34qg_((u3Vh?g13)l21%M;GkvS2>O>OF0ggpTm!CzZ4CZWukI>j zU}Wb60ma)d_toHdz`}WMH?)jFTU=lBYP?(-nF{{4#!d!&(co{ITent$0>vl0KCZ_I zdJ{H8zPr62Y`~sS_QRoqi*>pIehR=%xDMO(V9Abn^`}QYSoM(I_^ei5kOgUP(6TPB zA77I+q*CPePIR9N08C+xAn5p=APLnudsKI6N^PN%bR-4J)0;l4!5^m@rpv<(vMxkY z2eFO6OTeJ!IiYlU=qq6g9#xNSHSd>1MK7`i(6}yqP-;G6!!X@#X1@)`v9)0vj09Sp zwqnuyHPX-2RKOSjm<(8=r}=sS61)hfb3XvU&;$#lVGgjG0RS)#%76dg%KE>}j~$n8 z&86iY8&=9?jvP=S3T@!286%h1X< zuyMrY0`AF&DBH?7DCBf@Nj#s{E5y!oqK!S41fCe05TKh`r=Ml<9U2y&k%E7(%}`}< zs3Q-nDGD=RA|@8Xk!er7dR#~iLMsTHN(?v96e$CuR6GDPKS-==`XG8O!@t(1CLn(R z4(6o>aKE5J9IFFAE#%8#75cYE|8MI90UvmEi~6uYpNdyZg#!H`&jvD7d|u@kwK5c0 z87a(wrdoyN9@t{wK5B1coX{g8gg8Zo8e}e3llS*fWM8wKm03W~APZ_VA!-Ogo?x;D zKnW}A>8o#k!lJ;~xCpb7DQ!~bfL9QLEUc~}hJe(Ir=1K;M@$jA0OBZ601l>0{`PkP z+jYEG{$I?`^^DCDI>AD|IMv?;1F=GD&w+zKbui}cW-&vH9Ow3kl*P1i{yz~ABThJb zXp9D);uFe^tN)XZ;-3hBU!>4Kfe_#|^zVC^!#v>0N#Ohc+Xlc4Cj5U=JXPVZ3*+(C ztZ$47 zkITY-Sp0m;-(q3yEYTNI3Oc4?S<9GV??>E#uurmJ+-~VztLY8NW$PU6L zQ-63aK%(GNoRgumdv|gx&o^X1W$u1pyTlx;_7>hz&Z%dfN&JL*tKkRC{FZ#Z6*5CB zD=QSnkj1>mL6R94*$Ks-p3e)s7FvoahQNin12D2lulqmMLm<+{{{Y*b@KH0c{9yh^ zO)`>bFfHIY_&8tiG2H+(c;WH;{VVVI|LA1EJWak^P>_hL;e#A&0DJ?0 zoWs}tu2R;n0hxqigPX&8177*%U1^)V-z&c_!a}0gVnWh^W+^I8MH1^m{X z7$OyzcJlzAH4X+HkUs#`2kvf{7Jb-}NeE)F@@>MO3*P(>mje0g&!heso_`F|@BgoT zjx_ZF0C!y7Dd$hV&u(<>An{M|@1~h52iSV^Kx*WK@yzW7a%N=WCFanJ4h%}NNHk4) zf_Q1KEg~$LHNmEF{iqMhe?!~{vS zfi2^O4PG>Wu!XbBBLCC1_<*->;wJkUhuSw$1A1*o8!qJ_c09EwqpY%n^R^hxJb_oS zAdm3C2*pH{M>rJ@IeHVKds@NgC2-V5K_4;owJeK0D}HY_Yi;*a2}aDjea!D%coF%0 z3Z7kCQhZfT-O9eYzZHs?d+6U6Nr_0r_FTXT@jmZ2KuoS=bsEl!p`2`lKK>5;_9pn! zOt^+Qsi#5fo2l+vJ$T#O&^6D$Zs<8#QBPHK;40YV{7_4T{9SCsNDN@)bFs+vnIKpZ zQH%-fAS=~9-|!Uoaq|G^-h~OV0MxX&gf}B4-*YUcl&26V<7+3FaN!UF{GkA)2I2{T z9FAIA2%G|m0O<6l-<@?uC6l~uzvTR}4NNqS=^^7M zP-fW{E+G}@h7b1~u$GP$@m_^P1CVwMSpjI*RogOBG{AJXRpob;bZbEPgWn(V@NndQ zfQ=*Ak*)vE>GTKw94TLC{a;=H>7x>;&Dw^rcIr<>aABl$=|2j9S#QIK5vcfE_5MnN zkO5eGPPfiK$sd4+5I_q?G_Y-R{o@w+>MYt0Fm?T_JhRZ>6(ayJZw0th{u_n=7xYI} zwWZ5+JRAO70=N~n1_S!PjF0&1aA7DnEP)PKU#(={8JKSWCh7z z31fCr(0;Tde_7vLtKZ)R7~OS*?9;3&%%Q4tKx)2)knsQnV=9;!L>UVC4uVq^>K_Fm zMBe87T?P6p*pDiJgpLS=ygGqDVYj+}N7etpelaKQSPiH3-*w&S{lHxAK~RH2`1OVO zIrzIKV*22PKY%F0Bk~zks_^IC0$dOz%Y|Sh5b_mCg0>4uny4?X1%TDVW5yt{1oPd1 zz`Vl8!$!3JG=MeW=O6@*OQGQb_&THDEAZQp7C}_^ZfxX~w7TbEH z{|)y2oQ*K#N)W?sb4fL-A>IR_IevgVJb0yc?__FcEQjKU`c`9Oz8lB0b3pJnQ&etw zxN~oUYta!Qb=Z1Ix z3*6yFV+bsv+j9l`r4uA>!T< zld9g&Wgh0ruprw1^m$NNbLXJCQ2&P%Pz8k$0GmwvCq-NV$65R@>HlozpBMNg>;K9| zqy}R=ig5PV^8dv6|M~jh2bhGQ<4A>BsFE+`6dQ!6Np?hGyOJsc-4ez%9#-0?Z zQ7%}T<~ERTRu6VQ2A>c6 zpXL$NRPJtHB=*96@>A^uT(x~-C)QyDz!Aq7#TlISMM!nrelW>4R{KGShR^6AvJj-* zgRm(8NI_o1vs16^6+t%DL;a4%ph%WN-~uoNlK`Nc8w+7~{u@aCm|pL{W9GksJ0u{R znk{o~k{S)Nh8Ud&Ky3A(Ygoc}F*{8X2=a)+^N1TvqF_1~%e!E-==7k6sI>;mvQOqG zPxYBcLqUAthgtjG{gb&t#Va1k`tMr;hlxdz9C%28A335>2pJrqgy=(o$56}yModOtqkO4-0zy~Z0K}iW{n+KRl!HTDYvU~pttN*`X zA9^7vq|=xf-1&R>ni!*Dd=a6MTya0QG0th))8EegODo zrk}d#A9{lSgTr8dfgQ@d%s=k}q$Gb`|6ww50Qb-T34H&3)t?K7D#qWH5San*+%6-9 ze+m1eBKWhFR_A}+`;VviSMHzKjvu(ye?slQ75r!!aP_aEe=p#fiuSR2uNtD`V7xc~ z$_0r}!n5B6UJ9XunbEe9*R=|%a{kJ?ezR@?pfUgQ`;&eZkoYfwB0}KcTqk&m5Cs50 zG}r_EJDUCz?g5^9h0f9>a1GQeeki_?h(9zC$$uV$-r z#rJx*VIp1LAu0?G0gy&`6aY!UDqs%603cz4jOa*d0Gq%>2XM<%gz*5rF1TrM#eV?& zTkvwZqT~0C5`VBpRbY+i{}+7MgV4Yt0vZKa0<_45ICI3nvzZXLlUk@WxMCeC-S|#c zH~?C9M-&6A8dQLmXOH2@Nz1+?q9$LDyN;j$;DFU7tAc>!%;3d84&n!p z1Rsz|%5q-kZIh7<1dsuCa+($%GQ`8v(N12a98!Us#hVL(X|c z;naW?E6y(=0KHTbz8J4nk@2U`NTN^Y$v!Dv4P+%QLO9H?Oqn)LvThyPI{-);t&9ew zTy0Eu6b9VPt;SdTs39BT!0QaK{VaZN_I_kC@cYI*&ePcq;l;?j4uDA;FzweFJ=Y(q zyPwE&fFr**1+X4=Jas`7ppxTw1n_bdzMN8E9dZVM14O~G%pNGjBYyzVl>{8N*${$F zU>z$AVsVd z^GPlN#qrVKhCKKcP*rU4`&|uD0USvW057DFn|~)C!8d}6F)}A z8y$*2t^Ixb_b|bra)d+NLLx?zSVfQt{gwUDo3;W`qokwx1GokNA)#5n$v-*lRRLtK zT`GV;xfCkcRYQU@btQ6|{2;mZ|73${wEh}-De#yAMPOA%|5gPRG36~Faq$L#P++bm z8wpmrrt*K^TN@R6ECh&d_yI7Lb`Y!3+sK$F=4@DF1nVsKJtr zc|86|hrq%@bzV5>-7Bc{yOXb{^zFfAWdO%{-v3$xAXoWFV2%o@NB~_icyeP5W*G7D z0q|5p%m(jmu$=zK;|qe|0Z2jcv#QF14FdseH|$lypJ)H)Oo9O0DN?HE4lhxY%>j$} z53{f+x|F8{$?}__9>Wqyj{~odKMPYoK2}N+T|DDF_B*D7ieLy_Zz>!*WL)U_F!;C? z=hT?xu&QAs$X;0TzdEPt?Izd0KzXLCMn{OwG=Y!zWR0M%9e37Wyxl#2$ZM2;B?MxW zkL#(D&bZ?q$j$6EoQ9|>#c5LJMkI+(rEL)n z6%eZu*1UwY$~692=6;bcljg7(LBg+`x*}p=!7=KppP_job$tA@s4fHI7xWLbsdvJ< z4tTN%^4i9BMuEOjI~*ej2H3LuQT%{~CdLgT{a^{iEpcZC6hvat#4IcVx^I^R#lg1* znH@w*zk)dFAE@1@dM2r!0%)a`Li%>0!Rq7~Zz48e=`9O#MPtWLtm;r%r96zqA~n}%5R#yoq2Y?xs{i5mKmfE{W>#{3K3yodPptRQsB6>3t#WS zJqlh%PueI+4_G|)KoeKbz~m-NfRt1ow)=s8$6J0X)UJpibZpKM@s7s>gFLsx(E!iZ zUp2xh6T|Pa?zl-(#uWqOsMTYruJj--nN}Jf&#K#d&kf%f;u@{MYrax?#>PIJ=dO<~ z1{EJP230K~E(iy5k0w8VI_yN?2txI66>!}Q5qKT3pZjsBwm|?SW<|RFqK?NB_T8r^ z6~lO1L~apl>B6sd@2#AAnlk-ExBmyv!J2+t+2uypgS30?z4nJb@aYNAjegz&aA@^6 zn<3RB{7|=oqPE3aX%_t2{n5qTw*$)sIyQlNJLEV(P6cKz!|BlVm1MH|K~H$u;2xLFj1T)NBUEaG1ElhC} zd7h@*?0H7>*i9#!pw==^p%yY6R!EiSickzf+|nztn?pZ~ zw)?OOk#H}Jlv9?jEU(1t_f7#yc;YTMoBKy8UL%ojIR$jcirA|it~kHQQL4)%lF7k0 zQc@&;acb0*K?~uzBuo|IS~FqdgEe&K(1YuarbMRxq3IVtWa1IZ5ZN=!#Jg$MoC2$f zmdC>v+ZL#8;n~nYuVNm+H|&3laE`_M#Tyii1QW()S|*ug?T^UD^lRsAf@Ly+krLTc ze^5%OZj36s@9A#;OuG5OZHg^2T`%`#a4fnFhWE25npu{&$iotKso*mTJzdj}sL21Zr4yDM>EW0X?v; z0g+D5nEN0HvY*&DY0E#ClI``_AiwGT9FYy$LLUE4XTN`phLL7OLX~=S;2oA6QkLUG zn>%hL^qz;yU+;jJi|oG0F8MSWHK>H1hm4BIbN7q{tHu-VO~{9R!zN@7rSi`COgU6JrEu!$Fqt zi$exMjX9ImXe}v=FQ4VzR7&*gtnB))gW!L--y8M_E0>{5Af=NIA@1dr0)dw1?QnC! zUxa&k#9J3zb8_1&6a4!ptdRJhRK!l~jcEi;m}=fT)>aHFLry2X6{_WYqq1NY|4mLG zsv3`I5nBqDEc2TzvPhSj8-e@HpcirG)ro9k`J`e3@McXya!Y#>&dRnkF!vx^!HI}S zs}9qFj1K}5q#CqL)tks2b&C|GV$L97qJPsKUE|x?PuIL!{yCmT`B7*a7HYT1LLq-7 z%{&urE7~S;M--RxHgq+yQ+<$MqvY{69?3WiCHg2z+7wMJf~i^j^CqEBEKJz#Rh2 z;5bf0S>kt}3+v#bWwH$G?8ohH{o_{(G9dbBqUz;Ly0T)g<{2f(-}P@V<~`O#am=%l zsY(amsqdv$X(@DPNZu{@6Cz#`3lZOpVRwm;s5R#&FkHJ|m&|l78fTlda%s_i zZw>op#{FDf@+i!jV|3UK_f@HeXL-ZPlfAD$}I!tk5QptY7l56@o*JA zNQ#L6n3#*CxZrc08H&|i0 zf^o^Ur;cXRQE;0RM@i^mWoI9*TNLxNjDFmD%+A(76o z>L`c1KP7+(@mk^7`U!`2-WKC6+SJ2MWc4?xo}D&Z<>WA12u)LskSw%JqT`R#=sBO! zhw)hURBHwRbdXhY&bIxN-@aREQ14=A^?V^qDc(Akq)E_p4CSsk+9j0Ug`Pc_8;fjb z$+f}hw&1Ky!8drGq-b%2Wt%nrYRJ!fLuh$PH*Bn$X77j`pOCFZZrRq~*8124QJ@|} zqWx`g_%&!&E+ zE#0c>Pg#;b_)O#*b)@nPawc%TA#rDLF&&{`o2eeg(euJq-`0k1PSmmFA&rnSe51Z9 zNJ8b7F14qaC*Fe6eV4R8I0j9YOj__*;v*dV@!7$|9XUOY67yTvOQiN&tL*#{N%z3p zBqe;zFDG{+Z(UY922E1O5-QCUq?t$umpR%mmtY*4F}~$X4X=>@y4XPd(rs8Raw+AL zKlLm}e_BzL^F68a{%p-=*vQc^qppzU4wAFWQvZ~L9o=Poi;_&NP)~+)=5;s z$$i=VxLZIsR%I)wLaR!&q?G>%ZB9lYVS6>j0G?m=mhmBBl~rNSj+sr*DXQUj6`o#Y z6Pzq6OGIhaE>PJE+Lznt3YHaAZ75;^^my*?JQdtX*%;}h`CG0F%L*?)nzgme_T8Cl zEsHr<^>vV3!_-_XJob`6`#~BUMwu@laJ#&GKh?$-K8LJ;B6QJ~7sG%svk=DHoheYK zs6|?vJ!#;^bFI&K2bz=tHD9~#=U#L-eE#U^LB2=G18w(8y2;h$mg{x4SFpNP&B2rQ z5!uOZpUiyl{h{?P`-0<*C#Lz2CiT81)rxYuZx>>5g2?v}JzqvM_AeSEL6B#|6f1d& z>@L_ZK^H``@dn|jYP#lmsga43C@2_x_S`R}=xgH#dL_>IY`fJcUHgPV6zaUNQVS<1 z?F49R9AQZQE6&sIYUUHk?>*0SRkRh<8v%QUiMSbFx}F=85my{Ml5uN^grADM4;8M{ zh((YVTGtq1IC+a@QTnZ@wNf^&q%G>&<7h=Sy0Q?ko=(Vw~( z<2qdU)~4sf+!3XtCY<}i4=Nn4%@oi3C&Z<|<*cP39-t7_9V36vh+nrAHQg? z%~$KpGV~AK_uSQ!y_LR4TyDI3ktB;fJ}?`lao|85m(Kc?oG|mgo~l@s^Ic2ciX@mq zp0vsNgJayc-1lOM$=gwOc2-ltK~Nz1ebk+nX_wCeAB0U8W%XpKNZz&wva7^HPP`mP zzOpYzaIv!g&SF@ODV_bYM0m?A&B-k9zdVz!0|VXI)ohCRUa!ep_o{ z2*>1LbZ;w-VYJJdsKWllZr%3vwU(%M10U*ld=Xc_=`HzRPI7U@a+wzUPWJ`EicuH? ztX`{%AxstMd4|wRxa+0)I`WeyvlS3xAp5 zw028IT(K<@QM{w>g#&-)ZdpQ9w^&@?+SFtGkb}7;2Xni4#j4n+*#zZAM$svyREBi&fom*4Y7fyebVF54W zB{4(kz%}Og_An~7m-!{%>0UAx^3%prs%yG2kd&6 z*fql>S03D)N{ny@Wg$PM4oYl1`KWq&ce{VY=fziN@#AI5b(#AwqAt~)I$)*>Sz#Y4 z1$-Z3a)h6^JJm(`l~{twc=`{+@X)d!5ey#Z$L*V$(o6|FD`5erSVV#ICAr4c)`n!v zj+eva&i6N8Zt^%8lcu=8mLyvst4(m_7DfgolJhG|#xXgaH})cb5_x|kn|7AQ>d=(j zla0F*Stu0ju&uXYQ^7}n%tKEYf{RD|OoF{HlPMl(u%!4pqq>un_|!OKZ1w)yp{Rfq zKoMVf`4I-9(4o*X*YEwPCVuIU8K16XQV$o7+y=)fJbSn6vG^I3U}d{ORw;s<&h%vi zjVm94o<9FI^u2EJq-E8oF-!Ld8=t0D#}Cwgl6`60u1rVWS|#DN<6m^D@m)Vh;oQe> zY-J2lXPbs@MCyEcY^I51ubqnSpVg(4t|y3Dz*=F}<;7r?dKaaphn@NLr~l>|Ki*<4 zIsq(n|BxT+M$C#TX(!|Xp$+36V@(vYS`Oovve&$<}h`QDx#o)t?{B)=Jz>L*4+5n(!w z8keSl>Zf=rn^D6;KY@iI3F!>CSH~xF5S$QHam-k@1R4||3;BLNsV9h&=F{kMv!<_M z@G2wqN~4$!j;j1FSMQ&%<8QG|Rnje3y}M>owkGTb#W8FK>=P`{pOo}-yOg;X$?xn| z^*Sb>1^P_YALm#SugKas?b1IcNT2pI!-NwPEosjRG_;bZFiw7QKE~pgT%g-|dGsz0 z)0C_WRtP&^GL1`r`_O zD5J4n3T!C}*%sszswURWAO0=F$ly>p%#oV3!XSuh@qD5pbQye z;TMn9uFX&|J4NUPW8k8X&dSRdYS&@cWS!^tenK%eW+38-$9w1--eWYl1smC_J{B?H zSUk0zemjvXes2nt=a$NseCM#zHl?D-A{NusUt3uYM4>P7cq#f&DDUJMfMSK47=m?C-=s|{y!YX1cZS-Ug5R*#+-GdD*Z`vf~5tm zY_u?aFy>U#`>R6?p*g4vrgG)@t3@iUKy;1Uxx}RFUt_$UfwxJCP4t4E;{=q$ zuZ=^Ph`&vTk`mx7V%zp$r#qS=A9;iuRE;bjA&7c~GG3)Frs=csFK?|+(w5T4!zMUR zBz+z+vD}<&iAnQZV5=WAI~_U94B|FtS%C&Rs6XUPzv&o%`%ZA#-D~Wd!cOmxIHI<& z zR1}MSz49hcJyAP1WJe z-iG~AL=n@xOMM@StGProP9NgB0KqB6y^af!C25usMMNVef zlPFO7Q)Wo%Gw!vwgco%7=3`3N=PPh5R`DKSzo`?~g0&_9)7RaQZ( z#HG}dWloBT_9FwHa=y@Z%6*Vzf{_M7imC=#eCmPS!39wkaqDVfT-MMOLmtMc@CVTw zRLdSDk|B(>eVyi?@I9d}*OhVVv52vCO-1#igpC~X`h9PF-wi|W`geI^aIkjX%ChM@ zn!^6Fj^X=xpIF7!5YIWXF11lmbDEWiaAjjN!qLNnC-9Z7Gq%|}BpVfzb|U+5)c3fa zyh?2w_-0`6UfXk5 zv$sszwczyqt;J+|qxqxvcfA^B=+R~jbT!ife@ok%xlDI64SsnpIfG*ri%5O`SEx5Q zP-5h=Z$rSlIt>k@d_qF3`o1)*T37&fSm%V)!`|-d;U)`o{fb1|b}((bU*1EZNq9xy zJi0oM`;~htVPmTGP~2Gv zYLm==F!G{Zixa)_NX5}#P%R2X5VQ8`Gmz!2TCNa9MCjsTihw8u81HC1;(5PjWqoNL zZLN39#=?vlDy~}hVfZ1KC%({!cyieG^zCv%+g#R){qBwB+Q29#$mio~@rnh@J?<2r zfK|%4MK?$55lKp}jWvkR9miViUfOmXWrGG=#iF}fn%1j|(Lq{G>n7jEp#SvQK2U{U zNtpie(<6b>9YaEw+9s2dm0#GlW05EGl%0_rh1G6k{>;`0ZGrs{5LTd9zko7vc?;_& z*R5~9PYshZ0L3T1$| zVKj9B5-)mCIo-+1ow2IYRr1iO-gwx&f9s@gpXBRAA$+m~_8bnE6oo@8z9%|{8j38rZ_pE^i%&&PHy3IbT?R_mf`A|Wlv};UP_B0i zQ3XnbSnyR&C@tJk%tMCKIVzNWB6P>s&m*&{6Ck2mEk`?8J%Y=p| zeppg`e`TzBW?X7+}hC|_vrc?1NB#v|&@3x6Rfnpl+lHPLjf zqxH2j#lO1hnGDAJ2CEFZ0%N>azS7=rDhMqTd$Z(&0o?UmsJ6oQkyiAd;3tgHAgVX~ zN-vm?8zLsWLf4^k$)b^5o8KGEKqn{sf|W2+8L8M*CGq z5K3^lc!>P&DcKcNwGM zhqVxx)8J|Fb=B)f%BZKb3vR7w`@5>l9U{0^^pJX!f;s!o8H`wd z!MKo(hxQ1ccP_gwuW`ZW@<^=Ok#-kal|`vh6?}=)JI``CeS1YMAF7T=e5~ZB1fWLF z8gdPle~b4FmRW(Z^i>DxrlzxD;SAMk*M?8sE}6K$jYYEv)XV6%uLv!_k0-7-i6KheEpqr+M$P z^9zm82J-u_2Fvd(a8s~IBT}6bA?qLta~Hy95=U6TLx@F^ z%x0s+D|a~^vABn!rf@LG+*m317cxsr_l;*bb*_~Vy_5m-UsD2kU(Fy^hpEXnN%KR0 zx535n;iI=3d<|ovH>6QGe=hw4L&l_Qt9FACk^h@Sgt!m(aPpaR$;q_W_$nwpTPM_+zx=6K(b^}qxAf2sloS^sF^MI?TlfGKXfPZ2C zzy__krRn_}jv149 zg_yy^lsI?UIW+0@s2F?`h!3lwT~&n*t&ozoB)rC(8MQb6ph?KmNfYT?P57d^vFBae zbmdc4EdEY-alWs?Q;DLnYE3Tk2LV;s2hoJ!TlDF@pA(BOy{lg%icZ8hf1h(8P`)5Y{r$-k z6-pc>Wgf3S^VL_MI$fmZ)#`Ir*de)sG}ik%!Gn0cr3hypcd8D*asp_LsBEGL?X^17 zQne|ruyJFxi3h277glzYLBr!66U)Xu9!nuGjt@ym7CV9*2)4;#jF=w0($-gr{u`u$ z6I|AU{TH_vVM85yDuHHVd@3U9B#m^N>M7iBli<;qY7I?Ge)ROl<8HY<(=KQ}=-T)_ zjF(b&U}JWoGq>q$TUaI@Mv!_l`;iWjuQgu1xy1Zru+1G@kKc3snBMheZpC!qWnWha z8a=};#*IRzf`lM9JKG3Ij|oG&jAL*4B@X5VUohyeYGB%pjmt}czV#uG%A(FL(2x;N zCnx3fhc;+AI&f%$8;k!Ev4|!!f*>h%wm8%X+4@0(AHYg`YMF$g=I9x6V?+%s?}5r+ zOYe+d$HszrmG~*Fr+0L$dxUbgjf99myKX*ChaGK)T-U)3KM7?5qXj}-YvijJ?S(f1 zLe6{1<=R8r=dYXP{aHq^3YP9X3C_|Qb)HmTKfm52=&hJIvWkZ6UKyM($})Ir6$q{F z;lQVh=vtZ^X{RAHC*u)v;6$x$#z4M7-*TQE*DY*Zz|(q_(k?xK@1HdJi6TxLjfb}` z&{XIv-05!F-sORb#b93^q(8rsg~Xx)kLUA+5g zB~jIGZ=>(^>h3=6q#>V0j~;;H1?ZzzC0~6MKOOxU`{b}Z#f|hvd2^&ZFF)XhnrSvk z3Xs_#)Jta`_p>Sf&>juC3@KZvH^7-D*qeimLF!JCH&7iL`HsW;lKff^X6%#-MP)$b zOd{JbE8IRHQbbKPw_p^T!*XC3rL57C_246gj;||i@(;|=$y%c`+{zPu+zPz%aFg4q zNE{==r}Sl)6U*a16ehiVsU%%mdR!JbsC+cB=GV~aog}pq1aB_XpPTej%2qONr(o-& zKx&GyZ}|9SpS1dm=n37_1KkAP5>Qm~4>$I{@eWI(8un*(iLXvDh-VJ%fU-$ar^UYg=yR?K>vSek$Qo=ZXMO0i?_n~xZFV4y0i*#-# z?jx5%H}^NMw%}+pZ!(bCnGx)j4e2OKGBB4LSZAMUqE;sz*n*u(VrwkvxJpw9KvS+9;$Qc)Klsfqk{-r=ZEtv=4@FNfQ?OG2O&>7xadzWE zA}i4jPfCjRu913%Hredw98=xM-B;V{1+kqE7Z7W!OWx+)>|*n|kvX@az7LTF{xPEj zZW<4P&>HYj)>QW8Vpmyg>$VL%=k46`UXDM;T10EPS_9&EGXrhWZqOcU%a68R!K0P4 zHiuR{J(_h9$=uEy9m}Qy7w?83UarUMhc1G!L?B&3S_6Y_}ct@Y~0t1xUmZq4G}Yi9LxD3+DN5v(H5 zL4+~lXlU7kSrtzn43-F5KdFJfO3c zd{k^TKK+556QzK@PnP1K<-4hxn^ZbLT^8BhqhOjFZ|bUbnUlutC$v)#a`$;iC74y) zlE8d>hg6IoE1#oqC_E$U{Dazpk&|cF7yfz4k0pIW+kK?gQcYh<#Djl!QLytSL{0^D zRr~O3`TgFEsT%mUq@=rx`PRY9}%nb}s3i0}n&3GbXH@h{L3$-V5=VzkmQB&bvO0l;xbienR zrAeP6e`{~hS~9pc8t*KEJ@}-DeNHlTdS&B29xs@-&sA@oqk} ze*5AJT@#E7rrV)eJ;EZ6W$vqlyj?D`z}pyeR#mK$fhtd9-B$-Wucl}ERIe35AA*Sz zCAtLmTRjU1>K@3tI2y!Nr193eOf+*;QDDM`b@Hb~cRFLvV;p9zx3mI+($~v2pZ9gXt8~`yKS`EdqkQel zehJGdYVnaXDk(UAf$R2eTS_nMi3^S|n{i_LK8iSb*Ny8GN;lI)VwhKWlq5?qH~8tv zE9~d+EzEYLU7YI)Us<1w3#s!bUnwg6i~HiIK3o4~nIAf&o6LmQ#5+du?Cqv^C5e)F zgg5tJ=wcHO2KWpFFLLrAX8~Dlgslo9cFG{?6?U}-U zG~oc%F~W>y8vetQxgS?U0gEHaR*F8!2=*=9qpcfyZGgwBkF$KNy-vK#dVBGJt>vJD z{`Qo}>cbl;e3eF2ro3a%25KD(L)e~WVQ`GH?Jh%zSw}alnf01QNzb(t3Il~xs1fBKjCEQCjyOEZ z=C8j5$y-U!n2h65QI|C7xCSnZ?C2+?Sw&*Lx;R{2eqo+S>~z}UX82#7C`E zDzDMYuLzU9NzL-sW7-c!J{Oa-wm!`%LCxj^~W1} z-Kdy}9BL>9@sk{jMV|&Esu zV>m#9|SX-z0bWXl@)eP0n%n>|m z>*S$ZX~;(9`K}9D_ezhyzUu6B=rJ{T(Kqb(L$%s{O4Tu)ET&JSd3cqzhY^h&eWq?{ zoj0pUx|1{b9)kh>XP>{xk@OD~Db*p9H(g*051r(ixl91zm>kECh3PNJ7Sm+b{ag}= z#%+44Rv_eQw56|o3?X@0mCkwgKNOQKt9IztdNRKDP$Ci8PkW8lMeqRuTB6s{d4U7V z_h=6DH%6gPEw=zjd+*tl@cX`Z6l8*FkHfnq5(?eZU|| z{ka2G^v!BU!xcBe%Is>h=vylC3CmSJG&OFHY9=VXI`BytRn-H>Qq#3*XY!=M5?HP^ zdmnL(1vsRXK&#&9)bi7&{)dboF)ytQ4G8g^0k~n~_slYsoLH{Ja?MxXvPNl9ATk+C z-RsAnrq`id(n0wtM;yfrPYE>)UrRS>P6N9_`G+WhYnjyq%M^4=oCCMuY#Our8ca~$ zq}YZATZx^G1h(R9a?Rp#VFj|KA6qhp$X%2?udMzK0dae zce&_&c;`tmVPe$Vs5Ye-Ueo(kgdmjylK>PhdFK49dF8OaS9=fEQX89a8~M8CpOgD) z`Am(2YQXfzB}@x+EoSR|aQnVi@~i_chP8Zl$U=z`VsL;+O@BpZ5Q3Oow4=Fp=vPhqahX^=Ly zKYn*)ID&x^LPY2Y{NP4+s6V+zGxE<#`ji=$hxbBovmV%{-0M63fH7X(is+)5TqYhl zhKf>rVnx|a!>g8~B%=u38!J(mtx>N=YOSvnu);=TNJpPg272bJ(ZOeK%812m%tsxJ z7~tv1D6}QdhE7`!ccWdcdp;7C30)UyrSw>eb@#t6Wpi!_dZ>!LQ4Ta>izeAb+|u@I z%f~DJMk#?LV4ehPr-}weIf4^t7xsOtJ%P<@1XzVU!D%B`)GrUW?+n>&+Sub?5l3?s zK=%TecM`VLb0W^j^>;qaF2K+LXC}~_P?8^mFW8E91pug@+3GsoNN<|8H|CGpEWupB z!DvX-l6k(CKbS)_CU{LFlA?BPN{Fc5MnQ*KO<$DlY`rXs3vI20GiSg>$+U@7@pkx1 zoi?9np5lxu-NW7Q_i%?`FO*GtnlP81VBfpd2e}NGT?sPzC|~AoXPa~pr3{$UU!ro| zgj|?QlJ};+=kX7-PfSKeL1EU2$bIMbvaa@~>ON-J>aNrDlm;7-nFtC8GCwFXue@ta<#Pj>UmTa!Y! z0(vYQz3URl-nEXxw)ZsbJe=K+;G=>-`X0Zz$-ep>9!t6O+=_qGFUhzN3BG6r| z=V}+SX0@%wX_-*))Fn)i3OC@m3$~6DlVdfBtF*^J~Vc z^CK5`R`9P5NVt?-F!T4N9if5A`I0}AXl{~UE25M-#@39GYw+I-s@+HDr$S2+^RUQo z_he(ql{yR@laE`+U0%O}@y{;`{Y-)cFlHO9|8(+YLv7VuMvW<9b=GMW=Q*%Y00D1d8%8bklDk^0N zZiwPMp!FG#sP<>*6P#d9$_UJ(fQSKIl62eGyBhT9kGXyk+(C{?AG_k(8#C3dw;fKK z*Fm@atp6Wb?;M>;(0+@)v2EM7ZA@%TY}?5j+qP{d6Kj%8Y)>$;ZQOjnbG~!#x_7Pm zz=q>EmSE0m$wVyA9Y3rpn6vfF>uj zMqWOv^VwVp+6#M2Ps}d>SgB<+Wkb}f>u`AwxOUEzgmSHNsHbX8zBH8g-(tlWVt?_; zsl0=_US-KEB%8a`uL|ofH0MF2a3rOlfHPRZ)o2KbgW#Gn9$Z8i{v!r}Vv9l_*(t2X z|I0_E?djmFDERkPi*YcKH->`!$M3WY+yz_vte{6DvG%w5)nLo{-YSJ^Ic1wd&Gjt) zX8+cRXdIn+T@c&~Oo(GY9p?~i?mwj6D)#k!?5GCXW&p?s-&@vMO%WoP{P_5x z3Nh(JUKU3oDHEI@sV;AcNVi=-6MV{1K64-IBBmffxqU{(d0%guQi$R~X{ku-i{fEa z>AI7`@vxv<930`)8x#oEIMVv}x8FNQAt=?cTuK*RhHJ4?@R`n$mKwKGe&<~#svEE= zbtEt1&U{kY$6^lyi&?pdpbhgfMr@(&4848P0vUdMMhHl0RUbI_?BQx7usXq{7}bFY z%d)GJ{Q`0%ElbsG1ltgyySYm*F#`hf3K?j-hznKw*2|lSsP&2wMa<=e{9I0$XgQwG z5ad;AK#DtG~Tsr}D#sRW(}udgxz6sk{G@|2hLr)4?*7B1rU+5q)4n7D$U1;CYF6_OSJ zSit{>=?L-II?#AQJcd(gm>6V)YPM5TL1?ZjuJaI+6)EmCdhgS z%L@a%MZN>c`W;C6{}V{X;9Y3)=2}|JAu!h2;@?C=aLn9r{qi4la1-K{i4os2Mb%0Y zIEEcPvTwfNM#gfyKaFc3@l;IvE5vmjMWE%F;hnz|bobTeuArYf|1Jv@Qj516}?@-zd$hP!~E6>~c6Tj?VM09D_NToC#1sLB7Y zsBr}kOASFTF5(f@SEu8yO8_u7`cM_B>`!~fBTwLepA zgetHl#za2h>p+0M^aC~#Vw#=dF?23l5wS5<9>Lv&n8lVxb;E9q;LOl;wLAL<`F<7! zi&|uArTNNMu1M=%LD8eWf}r%cf!A@H(|t;Ra;5CP62NT^Y9b4)l_@NJwy%+w$oVeA z0gQ0|{8UflpWY|+L_J>dZa+0w2^;t@Yydq}ZcPvaMtc2P0DpL43hASWL01)VbiUA2t^}v1t z)HoM_08smHDsRenJY)V#<^4bOVI%{ieE?W{&VQ~A^4_cZgAxD)zZA;@Vx^f@S~&vv zc^3V_`MAG@M)S%ecpz2#hvU3$vU1vM4WWx;Vu2#UZUBgjr~(Hd)Kyvy5RfzofH(Y4 zTVO5`0R2D6ATb!z|MQtiM)&F|+P48R#&nQ zn;CtWl83kRpBnU&!2Tju#W81Mdhi9z@mv0)rw~HM0hVtO0K=dCnJGCo6oXJTlJ?VF7@@jJ&iPHUTUTR_t3A1HuRha=--+VEdn2_+BNhzwwa)zY&4{`^JCs zjsL$CX)urk0HKUm;vf+FbJ5mD0SE(U`VfqduM4Nz;Df8C?s^$Ge6EAF-N>X*aTd80OC4{ zrXhd};@?|OsXZ%3L~}+g%3XiRCh@L zNSx~b!HaD;3t)7G;|4&v@dC_%AXwiw9V3!`MEU=bEr0-LG5F8_zY7tg>Hh=^gnr;Z zar)oIUOh-k)BmqP-hboS z0m;9D|G$GG8-4%)SK{ZO5#%d_a3r2w9aRz{?$54oQLCq1EdakM zDE%FZc0p+uaJd74U`SL8B2d$#SZ4(3?__1MAI_Pt~ApjDq->k5I3BZ@&N+|W+*=BwK(7_dQz&B;$8y#)|fS2ie>=_3G zgrorQmETI;re+a9Ak-Hc@avtvshiBj^M8k;-qAlMR+kBVe$>TcJ3-d=(il zsby#%wf|VExeHsMQcMO7y4%R`lr4Uy>c~TuGGHQ90q|`e{OyWJ0;QprlSw}_H^N6N ztsDT>q!SQiaL|9X1Jn!zHl-vvdQnx}U@2eh6z7!nf8zvM@I~BD+=5TCg{QInxgkAD z-JiXMMak;a(jABfLmiZvjy|Mem_s63`3ddExu3&PHuf?n%X4xn(y7Ea0dDrcM-k{x zEzIrkK-fx>;02S>hNBl+a@L0HPb|E78oCPyzNBIz;r+}(lZn@*$2ZnIWaxBTx=prS z0G2~0>}=8?E3jrj)(p`v%8aQ_pwNUSAqPecA3-KM7gvl4>*YS1*Ip0tJ ztDpPb|}BmCQl>Nz@MFp24%!qZ2AM ztYt)-PAZAmH3V}D@<%y6Sr!GSr{r@vq0Pm7uJh#YQO)cZb3Sk=ej zeA($#4Es6UiIRO@YyDWzOL*Y7|29KXMHIzZLw*UdG9#~dt!i-u1uf1FZ66?8nP&!o zCJ8*zknSXip%iIA!=I2R=q-#X0a%e#__kIaZP>_yl1p_l=phx-_2C)J+%9^Sw#vsy zHZI;TNP6uMU(z(=_^7Y`(DV#8e>t=?L^)_WV@j?gc=E=Xe8F%aR*2vb!NK7HyJb0d zsGpda4RwetEMzzCC$;%6bSV_Y8`V?#gUuOz>-=2Cd17FZFV*wAbn;Q>qmEjfl_ zNbKChi1@U~lu~x86_@2H*Lri;_~U3(0-Hv`kLxQoE2fM-jSsocf8{s_)g%-Dpjpz+GMuOm1oa}zVIml5MA6>6 z4)eWr0vd)^g2e)D(dL@h%RS(lFdGyr{cVqv{7UecSN#**ea6*{y}t38Aa za%z#1s$TEH3>=3eKTY|$(;Sa5qV!84o|mQfdD_Q(IpA|rsgGFb%jE*7_GI?>P`?s% z5oPuHpMSmwjjT-CSOGhN&Q?V1csU_)((ceFB4@bQ7ayWk-czy811xN=^Co`vDs)+~mus>O%8OVPcs=G`($7U<8T3a8>k|Ept$jN6}kH>M;H>MEt0uW`Kmw zLR^cQS;SAg-=yWUwJoKWU>pmCod25EH?;aA#r{J6opEDAh4u%)(e27d=!ip;4tZIz zyYTSd2K{Q(N#`39sIN(MRTHdM4w9S&oT#tox``zmx;eKJH!Z)?ejAeRr-LAm_hro< zZS(Ua{JnZ<9zPE8BL@jOs+_EZ`hfnI4=GdRrsyRMn2$9QMP!5Hk~rWj3q;a%l`}ac zo&lMr6DLGNp4ek7vsUGl!KTJvK2j zQx3{kPq?Edvlwq7N%6_=j!ZnxGWc&^(dcVzE>tzU_+pJ778Gk^t%qd4Gp%ZCsYfbI zl8OUTfJ0)}=apg%IA;z;gvjl;N;fsK^N3SDp><-%TbdUWR+_vTubtSw#K$Zz0Nim_ z=@)XcF1#-po&9^v`9{)ezLV&(r)me;_cH|+-NQT9Zky9iT~Pkcu>(!LV_NQvhsR%a zBHyWPuyLJ9WQ)qRbl#udF;&I;A(JG-Ln?uh$x)r(nh|C=ca>@)UYzcjI>sL=dEZWo zKm#`v^GIjI;1X+CT%<4YsYhX=@$V<}}W%6VN=0AyE_5}yK zSldbR2b0-Zw@fNy%}g$MV47aRn=8KGUsYzd1{BV^*~!~5Q21TV$HvoaTjGg|5_YuI z=+(S~kbch|-^;|T^^ER4s|f{p+Oohf-Gq7RUwn}QC;X(YZ7dMsf@9=I==)UfFj^+) zPpR1YF6HwqUEkiX&tG5!!7cXfp#c~8CNwj64XjUu0#zrtaeQs=vn{vRpaIq{Hi_g4 ziX!}kUJvm@#(o$NDu%9;iRcNhVDR3L-CR^iA4Fzu45G6PH*$@D12;oZB#3fxO3xWi zZrDOt!R8mM3t1G{-I>Zs?Ps7EQLuAUS|VklYE~;@a3iM%m@8GOorF#_ z`!UG|g#X(4C5CNc66c2s(=&ucZlho9F5xS{O5?moX+pDitn^+x zn5KTLhzr=Dm`GG3Qua0ud9shs8M1sd;YDWvCOS8~+Yk|bH-9MSNL0t?(G$fK1EcOw zsFixv7wz^jf|U_`m<@dd?DPdjnjRC=D7$p;s9QrCF5k^&A=x%+!>Gl;L{E$KI3_oB)UYuYKB z4E4r|YnFZPvaJwCs$UoaALZWx5m-RG78&#H=R+Dc;n6q$v|&NS~5Oak~P)F~SqA<;ql0H2{UM(Cr8*PNV`z^>bmlBxG$>MXXu-qML& z^fZVP=r#Lr(++tShYK9?RKle0qY!l)H?O6gIX`y8k+Oi95B_1o?GXxV#7{d)mOcROU13K4)7Agj zMA{q84ro)_K~Wxm#zU%q-+|Z;=l_e!DJ991Ur$Wb7iTrz0vTO;I$rZ$QGt7Q`=}jL z3Y5%LN%IuCYfwVPe(P|OP4ULYj{uKFS9HpPh?$Ac2;wKPjpDiW-c6p)OQ<`i$=`{< zew#8e5Jdn8+UK9nIKL`u7+LA>mz|f~=fBY-Irqo=z%m}@zrH^ze3txP+$Pru4ot-H z$ZrE|qL%qo!`7@97J7JSp;3F>R&5F8FLv=)59`MBL&7J&_vXQJyV3g= zg%X^%*^f*?Ms`On6xq%p4z(JgE~k;I8?@$|Vef8UHb$a^X;W0OGk#hm@0A~^sAY9x zuUyxMDt~{|Yau$#@nbX?I>2Xs+^XOJGWM_VX{_pLQ)2~{W5 zjCSx$bSe>$anxM0Rmv%pC0w=$=on@0uo_%pT8mZ%64Del$ zsr3gPY}+0KAb2?w@|hS3>X(dvGG3qhF~77hh#54a3b!?;AAUH`JVNHU&q@e`(3LUes={+e( z^{AE3Wz%3Q3_KD6C7Y;ETT0x+hSxBjQ6e($ykk&&=FJeR2|4aXUb2Xm(#I!%sSc9Q z)^Ri2K{1rw8a}|d^)_SnMG&>2M+wwrgsfC;AaD)M#pY;XIWNJqn;@Kk1qWf~PPALk z-2A|k+wUhYcH9(6NCz}DiI z@+8XuOiN~p+KL&UpM*C*i+ zHc0jSbi;r4mRG&0$jkr$cUErnQJG+)TWK`PD%E1k8oSxD;!hb|LA6_?7L`*R+S#hN zmL`uLrUOH8(6R(jaC23Dy`w!z#jY^4ZM)|-L;s24I=9+5qR%9Qx8BaLWz-U?<%f6d z*zj&;|4=A;g}6Fv&JBU{m>ne;95He^f%>BYfJ}h9&|p6tbg?jMRxKjuRJ?!CJGkFk z#@JE;ru5=51me%6XE1n4og&zwMLN9>EG0}wv5m-9WhznL3@KvNob*z>=`)kCIkjM+ zcD&bCA-H8nx|_JFg@j_7-|%!R>#+Ay2a2=vOhXI552AE zA^BE^q=HYyUf2c^t*s@vu&()#I$2l0CqZ;=`)dG{;L@Ait;AJzzlre~h4%Q4O_q@; z!#w^+fFZ$)sO<<#1@{*x8z!xPbun38n?h{4JXRjr{?3yy(Xf(GW2;DyB3J09OVooAH zhvLO@S82YPmc*yB6s32B)% z_dSTV*QCv89NUr^T>_%QWYBRFdxK~COUw@^@Q?3!qT(ZjoJPX%db76aVq&|x3F1qn zgCQB%ttV}ny1bCo3Ls0;qtx#-H-F8sO^-qA1-3VhlS04Fl&BO>`wB7l-W|hC$~JwA zTiW}@LIYs5m#0(n)BUN{m@hWAzWUPgKmC{Aw}SJ@;`aMPRZJigVz_x8tS=NA2OQ9- zW@Nrh{!Io4sggi;U!l)};bGflFFh@Ubx9a_XFEd)4|~QzUEx6P^&Ud3*5#R)of2-u!b=vU)wD}x)-JbC8aDT)-S1cd-Nd~M z%p2SW42<^LPope8#$&uP@ZX}=G*lG2vtWt&pWtTV#x%`i>UL2O)89T?7`$r$u!Rp8 zbH@5n^MF@QE-Cqg;iXOMk&#WuKY5yiIc+7@pbT$a4ATpA#nph-X*dr_`jBe;$J>^$ zIUd0l0Ql}Cv1k30r0NNIMs}r4i^^=o5=VVZXcfhF?E!W0dFyi_&~KH=hG&$06jN$0 zW-CJ4Yauru9?!2?fsp$TpR0K>m|s}yZix;gor;W)^4x5c{e3vJO%UKvAjD>DnrKMC z#I&yFQN1}0H;{Q8ao_Dk%OD;jBlmKD;cO-q0SG{!3+7@5$PM!bv-aHhJjy|1ZnLQH zQKGRg!`}5G$$mK9&h#LgMxi82$RQUF2`r}jer}EUD#U_N$Yu?2P#RfMLC=BgMS&)( z6`b;|V@sW8u1Ja6A~sGOne`_42Z*L@;Y*Dw@4C%i7N74@RB0aYpu@PVsaQ|c4=q?7 z#yMDuVZ9h6^n)oUspVy_vd^Watl(XT)6WGo?Wl(FR+)nGyUSTrOUnI1DAoVF zHH0?4;onKzDJ0S@QP&4Q1LIoT0Khi7`4)xe5&A7K$EQ?$ofa6yU3`ml)n?+eFm}1VrNYP@@Kk1UWtqC=~3Z%@Ix!?*v$u z4f^2#c1Rzrlm`>*H8|tGhzCl2_2kCH=Lz$5w{C&zi?o2Jp3(UhgG=BVx0Ftm;t+r7 z7o4y^cJXKihK@NXwCbh$ON*X}vZ_w=TJ}mEIyVDez2aXx@jxHOjfM3~XK}!YsS_k8 z7pF2}yw}1Uf_imWXma>!)mi?8{(+RH;(U4hlkF@=6_bu-J8jd^2ufQCaj#2y=9;Q_ zbae!DE;Rtl)|Rgm>SI_)BU{wy1MB@2DeQKZQ);Q`TB~y_sHPoOe-2;Kf|CQbCo8A8 zFS4P*$}VEj9o2uVe8_iEkp@w|{WpoVVfhxF%G3<38}^oypVr!qtXCg|B+MI|0wM)` ziHeMb5taXKSyac4KZKoZqllhG`!%9|$|)Q-Rz=6=O}JR8%yts#AYm*8wKPsfL#D@Q z|HBmhld zOXWd@sK$W1So~G?w`Pqq^?qFeG<9UwcTeC*nrC^`EId0H=Kds&$+x85*YF9XlmMbZ zF2Kq3*rg`|7A9BZ7Lkcxakdhm_~E{NL@27&k2 zS4H)51f<7LwSEBTE<|^p4Z)qxT^O8I3r%Z2>I$0mL96mLj0B&p<@8Cij|O>GnrFB- z)S%;{-37mh#7GgJ{fRk{L&v>);I!zuIs%(qQnPn~UKDx<`DV#~y9N{SID>IFu;0tx z#LF7063VxHo&Z_!#@cKCyabUn&1_t?F3b7SOy>RTWT7!9#c!h(ApiPo+uVaPbTsh(9^tHUktB9sNC&KUazLi0P~PTG z|Hx)ja;g+J(%H$3W;rF1UwOE{zrxlmw?i5AO-Lv)q{cfnM+jT901hLnzKuXW?&w1U zw>a|xD-YZ~ScPYDNy5@G>8%Xk@}Nke21wNoC@bHAIVE&w;&;@Pjy z=RA+PhcjOlGqfr5-OoaGH&u2EK(8ZIhp|Qc%pX=A2#)=WmS$j6=P(5R90u0_dfVoJ z+-@>nW7T-Q%-7ZAs%XmxzCk@VlMf)q7aAlIrP@ykj8V_5K9z~xix(Wib%7+vsBCs+ zTBS~r%3GE&!{*J|`3|a>BvmHZ0{9>w;bS>Gm^fP4TY>v@JsTd|%Fz7!%r+0%=lbi@dB@Tv~ za!%0Nmwt0?jy>{HV&`l)<+!EHYNt{;dFbc80 z)sAT_`_C9DlqY1C{EW;@JQLyIPkTLxQkU73Z_#%do&WS!be`YZhsp2|S``g%^ERrz zi&FxKzpq(u#^&S`BmC_cJL42gX(aWt;f%C?qWSeiACmLjr%*IrhJs%$L`MlOJ1zdQ z7t+)xoNP1h%05`OXf13+TeIxHjbS#CHK{O#i`2S-GJ=Zf)(H_A1Whzr+SStZRA_x) z=ocn!&)UKZm*2)Ve@7_?kNAR@caLUPwOqy9(G9CK?4oNDqhxH+jt25K?YQ0Ybm4TM zT1>BCuCi?KSyRhn5SCcO6Jd~-#TFD*TqHi$p{Ku`8S@t2E#zcb38(gI>LW0>DkP-b zF%{G9Y>C1ca3lelFNrI4FjE5u?h!-(SYOVHFtPxD-KSN&;zLg|AC=`NuR(S3{n;bm zxW3j(JUe`$@tw5_1h(iCZ4sukRh-KNsQhGCuemP9dtm+)fHo=tV%xq-kpTcS6XN%< zQ5p&5nQD|Z(aSdMuhyroPDF8Eo+(^-S5-3J90smILapPz>xm_Li}K^dri<=u?y(qo zS?ui{;{BS=L7XxC;6qdT9uWva@Sz-eJ`+IeMyzo9S_j4RNUdAfN)5KpiLP*DTO5J_ z(Tk25M3Jt-=D3%Se(8DD}?hG;R5C71bOU7HIh!SGQ>CGX|&iV+9S|D7Kkuq%ZgSsNzS7DTMp48As z1S|9zD_)zjVU<(+^p7FMXO&t5{5)-FI}=F`YIxB{r5{{rrsZ6?MoB+=t5#rglTaG~ z5Vj--r88W0$IZ&7^McDmB8=U|f&Y=H|sIb)2y@SbMSC+ps6GdsthX%M+X%N6%H1#jq zqMltXxolg&Q@S>>kDJZ<$Z!PtE%hKVGSL(Q105Q`U$jOg!=RUKc6T$0l)pMIDutCj zXeLC;EtpSORMrvnm$b}g`toS(VX3nWlY&||O>0hu7~KPsIYFI3<~t9NX-%D3%@wh~ zFtaWUHHs0>_2}~QXGk@I?59!Lq$1?VsHVgpi?0F)qg(Epm;i#XV$9M(JXMBdXsBAq zQ5w1x)k+APm>UXggqNy>8+uq1HzLXi0+J+DY@!#=yg&80Pm$i)4_ul0TxE;nkzZ;_ zjo!l*rAZ&0Fp{UkeBf(FAB7lL^7+4=Ib1aNjbT;nl6)`&<#!|ZnN`=X;eDocWPl># z8`Slx@Ipfr*kfu1$In41pgekilvIg?LAneM5;4Zp)sT3luj?Zdz1aFX^29%v6L zy@e|17REtE+EcviOV@XD?N^qU2cY;W3=A$>_3ndVghwJVz`3s^^LQtVE1MVHxBB}f zvrP&$e^kMPpJuM`Q*uwBJroY@$O-wnJ-$TCA?M~EYGkBW-?4^js_^-qJ>~F1zGM8! zou6$}XJe)%K$dWhkdWN9O_={*9NXe4Lelv`$h#>%y6=h}Vg(w9d6vE%zHa@If0hz_ zkLmgk3*wCJA79M~RnFP&Q)LxEM5ds>e!50P=D3QIsnI61?sJdrfYi$5>e8D#5DReGHD+a`1}4! z%?(LmFPEf=B!HbZ{C;+yN~0r_P-8V|O&zQVcbV|P_(H67@Gp)v+bK1ch670l;s(eo z&}{q{E+VU@U3rz3SR_89`Mf@(4w+8)8@Bb4NDc_GP6%0$>33{@DvzDWs)1R`PULX- z*vHDH)2lMHr)LO6#rQuw_a>B(%|jDpi_|Cz&ak@GT1pz@e=rz}gavUC*n1W9rr5xJ zJK{GkU?V>{(vM^37_pp30)f!0SwK}|@nSt9%k7}IC58P;4B zq+}wtBa`dOq56{_Tb>%n_qwDy%Xd_WhDH0jmqKmj^ejCLI=y0KgWm4-MCfaK{jG?+ zQQgW$o+SJG(sy*i5srzU9hhbSb)3C6d-PFfD=3x6*xjEH{(LvAN;&zYTEE7mPUGZ) zO%w?OGAtMtKDLbmI}o%C@(kRFR);~(=|G3BP-@xzb?q5>7*b}KvAc(RbF6!o*|n!2 z=3P_hUjNYf-u*S@+>ckoGdQ?7jMyOiMRIS-I63Q^h~iR@Ot;NvAQXm~jfB_#4jQ~- zHR3MT9Bs}PeF;VLu_Bc-?w%kzU79cMkwIo)*0`w)L6~)x?*Y-3!^{d-RHrSan&s6^ zwVR}TSmA;(HLdtn+bQ*W>dbX#zKs?kOJ)Fq0E>9@&@!dxz*E5gIc=$w?Pr33i_YW& zk~fv?FzSK9apxS1`JK!SeG>Maq>_3!^{2f-OIV;20!*gj3b}8rXJw12f{j<16EW-O zzyTT&mcdA`*<)2&A+-mUONrgX#L_;C#7t`JECq>y*7fQ zn2G9LW8!-_HCM6lz1GM_0Y~T1BN3kvkG~sDJb#5kDQth(EgSP8ufb&qLB)9SFC18~ zss|zTV-X3U8f?-1+lYe)Ol|l6<=GCylN01trWBT5R>C(RfC@m_e`x`&#}eKV(e7gJ zl!r7Vg}l~tAb6Fu?Ri&qJs275hI+hx&h%K9-l*uhd@Z+FcBOA`>7}$O!(%LUbmC>v zC5;fUFHKA!N0UZv!Y3Lwv2kIHHswX7SuOAcKs4tobya@Rv&Fl&h|;$ za?RdT_?Jba+^u;2SCVc^{L(;Z@UFod3F_fwUb`5y7kOW5O+cl^WP*X%bH?X%gbmNq zwoKt~%=E6=ySRJsVB5#099^=FoMBakC2U?h(TQj*ihG0T5e*H&vp|*P^=aZ9_^gi~ zSw@{9rdp+hY?bR}?#?02aL$!vEk8nbhy(kgu5BXCfb=lxuxeU%_L$~=`*dG6nmr1q z`R<_Bihj@}l5qge7}r-1L<^BIQmex@o4CA7W$kK#xEh!=*>c1%@osleyoh@ds*D_gZlpt;*Pg1lj6#93*0g+ax1GDN zbGa|D9`p{wWmdNn0yP$#6Ma;djhwU5vpji~4qG%@tE-Csl9*CJ;+O z#1_y+#J$BX5Kp*=l)cPvf8Mij#-nZ`udx8-QKcim&}qalOytSYHG#aV$j)2zRV`GG zjTX^K!WjG?ANsT9i{VW!Y3+D{!5c;X4gXIQ>?R;UQ}8<#MDgf|JX<<_OQw`i^C;B$ z2O^*yZw#+w^4y^7i{ri5T3g~k_EFbY6M^X(_c1ZWy8gwcs%VzMqj#1Zgf|*C&5g8r zmRaEUL`Ss(Crd0<`GOh-s<^ChKh8f>tWTgUOZNbWf<7p-E9fL8Wwc1Uk~2f_qSrin zkvfKJmspPcZ=P{wipVvi%kv5Z5~DM4;Glp>~YR6e*2>JWA{ibgx9M>van^I~mszyFV?93_4pL)Cxa=*boM(i0hWTfau zviA-&|D2@Hbi`Ks0POLLpwGFZ`y%CcQuy7}K-y9Rj%Tid2 zCY5EASc>ntmy{^X_`xz-AU8(#{hju1X6t>QTs!o%`r)#2Nv@$gA<*VvPcMn+JwK)V zn)XTuk6yrZN-^rs{!U9$mR%}tNgpR8vheFAOmJD`+?cnLa&f(_)qhlUZ+Y!x%Hj0W zZ)P!$;^GXWwr*11)Ooq7yY0^~{_5iD4h4JhMUqQs(^Kj2(`i5wokeQ+ts7i4TD5T5 z4{$ONAWHF_eTuELV5o!L58SE3Fm}w5(_}w(BeLp|4im2Q>2VOH{8$gSesYMERJ~R` zzp03Prr2b4@g-6T2CYKv-)m2^(7$&aJ>cG`c(*bYG1AgtYGZZFQgZU`32h`BXYXhW zE%kA^o>e8_d&EHE7wgrn_&RH6^4iN^nv7Z5J7a{L|AbRYlzouPnX)51e+}KOQLDR?26P&QP);g?dQU~n z?)Vla&pgY3qPFw%(3S(Bj%4^7`2zd)g!W1NP#sG24pvB>XiR#{z#KLpsh+$EF#7qI4yd<-%-4t zu)z*%SO-XpkoGysu}XKyqe1Qe&HrMSKt!JL+OJ^zMb(NV-tsjcKT!ge#!ouC<1^By zcODsmEo(s+1Hl)QA9gTMHG2awQ#*DW%g4bz!gkLprxT7%$)hybYU#E`!LeTSdPHUz z%jGKTyI-xPnm1k2FnTj@zNeTLIUsx`WC#F;*S z+&#w9isFI1*S&GR|9<<+sMoE{5Yn9+ymLL{s(3nb-HM@YjZ^m{hFaUSl{`?FNQbWx zEV~9fZffC|ZHm_@-YN?$Ytcmk{)KT{ihZ1SpvLq?wK?t)TPahbGxx`S-eZaj?@j&? z{{EkW2Bn#G9+~CUI=TlBSGEQ%z#1!Kva=F8kA%Fhn8tfcLdaXXy0|PC%F3t(Eig2Y zb!KEA=D3xF&%O9XZOIHPH;TvF+txOE!no@Py`F&__qJ3f=hS`zYh3;mBaW$Y37VB% zq4d*k20a9bd_uv$b5&TJ1Z7`{Jw1yKsJ}%b3o%N)kg4cA$DkT9mREn!faWXNDNz`o z;GtMy8Gux>5p7em&qM_$>0=4U=(UOHM{vye*8Q#t<~p9(wj+QPW~Zry=?LKv-$GXzq)pxyll=?SMk}MCa69@F0)Tf~ zMe*A4mIo4^>a>`nq%vKgN*|}6xkq06P$3eO1af6lXW(h0SKAyGdx|y6{cSDJ??y<5 zl8OFei74#%8e+gEiuX2^XdNQ_`k`RL5|lC9RZ*6U^T;ZR`2MBsetmKJ(dhf3R&R@$B!)?&M4$4YXB+!hhK?~( z3)eQ7WYgZ+$5L!Tp>l&@>67C|*kcdjuh7r2%&~yM`IwGHM5=zo89>rG_r9@~WDYK2%PIAktowd6gg9oNjPqz_NmGi`~EVhAT2p3ug<%sQN zw&By8q73?QEg`pI4~1Bf0wY{mNu;sQ9Ov6QD(*hY;oAZ(oV`fgg7but1$$iDh9PUE zObfDo2Ud*a38peYLx0wxyPHn#Z^ofor&~7Qwxb!j{#ox@a_@}TrhLZt1IJaFS0x9T zSRNt%UdWrj@?{HdK`A`InLtV|BFY0AbQY?Oh$aFIn7_+T{TE1XTJ^VByDKi zc57aae1}ICI>e@J<%s&!ru0_)m!F~F{|;JPdPQ9z9GA-%?_;*&v9ABNs%<#p6`B3; zA8vN72je-`AG#|nBl%6?!3u9mz~68)rJvK4O;W%qtOG%b_Qb@UcO1!fTaFkqyK}K( zivKqLn%_4~isfU`u&*|CitCll9%9$EbJ8lCk|;kbWuz(X`m&bkYqLD9q{5!?42>$BP$mTwEu}LT$O{)#_OORtWDGSk8%}d$ zgrSNFYUj>Knae+Z0ogi6jtfCnS%sYCad#QvtlZ(}t~Fwp63;Rd1Y&GAITrt{Jc3wn zia=XnTptriEJG;5Z@=IVe$(Iez_i_n-zGk6md4=Opy|s$^tILsI$qVe>lDCKd3IkM z4j_^0|E@(-?VlaQr_oKu{;N(`DMGD=3tNw0$IHcq-iL9drO}pxGC}}#Zo->>ft7{r zNJJl?2N0MMH!XW&_EB+%Zk#^y!uWfd$kx=ji{S)V9$6wQu2NlwaTR9LQ^+2*79&Kg z#;#skcqMNJKw~9L(?kq_rg>u%Kuzc)o%$V-cw^pxSasi`5Fo7`KC29GZ-EZX%A?{_ zo$i?gQQ7>F?`Lx(>a2u^9>{5=FL`d2RG4d-&NOnjsAi;}Og_{$6u$aYL&IQGJ?&>D z?$Dy^J9?m7GLe#QePy9C3r$4x0j6Y~bxLdft#x6mdXuXBR!xnvt`wOUaOo3GwBkSZ zV73HD1I;|sfI(cqtJl+;Q@;8eSF%J1D}S1EkM4-aU;T+M{&wAbvW4cg=lP6^!7LNC zXT&>CdBUv!lc4}>Y9CKFo908*}U)1QwyO0j%}JC5@! zq0^}a#a9@#E;IqNjGUqkx&B;KeW&y{_?J@$c-V*W&WJeyVOc}TGYjZMcWm5UY#lw% zFs;Eoi@oVbqXK~O8lKC$Q*c1_57)15M@+BBsb4sk2OPh?O!S7a&l^}jeF-c z^50G)ipds_p^m`;ubL--U&B2bhHa|C#EgXf;m(zDjX!T`fe#vwEEmzvK!7c=D=IMn z5a~}WY|d+vs4$5c9N*xNNO|~L- z;P5Ia2{)8FE1lt)TD%bQY`SWQXBIijEe)Da`SWuv0C5J^yxL^wr(7@xhopGlFK|a; z>X_R??cm+WvPY^ATHE+jf7fmm5^g6N_bB3Xq9a#{kR`{F2oio_QGuB%ZEPS(IvuyN z$vRLUs?`ac`>eSJG%*J~)NM0j*YDi-aL_=KI0DWFED|o$cW3n@VD^BVG*XKfF?DWm zOFXL_&qLM&rjITvI6^!3_kGhidR{_5mIk82X{X$`^OT zPc9A9CKVebfu*?izSH&ihr!Crcu7xAzx0BZUq^w4Xrnhzhp#FNKUz2GP2{@ZL;S30 z7MuMgxH7yOQv2h~?uMAD%Dky^NDvg|2sh4HpP=;~gSyb!#VLM^JuYPUT%c=5<#DbAm3|ZtZ|I*l9Xq+4Y30uLCB&StajYN|1J9A!l^gM1WyKi$~qjz zMEX$9|Ebu4LDe(FT9y{Na^7DBN|kFh^cXO5p7nTiH76%99Z09Wm})r}{$Q9IFXJnt z{cJAsN5^^$B(`E+r@zr{lnn>G?kB0wFFouE|QlIyF4rFm{mVorP45~?xWZz)cP*LKEF zAm`NuuZ6AzNey-5z7bk{c04aR0)E@>YH7S}0^th5ImHb5LE8PYqMOP>#z8-2t~>ni z$_rV-kbzZ&Ec9R;sxVa;p%cB1;O>^?=6i$>D^Hq(&mqL-f9rJw1m>9h<)h|aJ~Gnk zAKz*>gx8M(Sj98bLl%9?XQ_mCgnVIgW`kD(wB$sMpRQ~H=jbR)HIYY6S6Uw2mZyom)^{CQ!|WGKz_QHuOu}Ej7rz^dCoJ1P4a~&-J>`*lJ4iXf#7V= zzg`k_>^>ndpKy!{<9hMZf1g2MlBt`OXk*BuKlF2i!R|Z(0KM zhr)b(vluW5TYsKv$zE+tmzlFf2p(sR*7;?x+hxr(hTm_78bgyLGv01Yp~Vl_PQ$u< z`$$&>NSwcLW8EU12?Gw~Z2Wwqn;_jowRl^o{#Uvlq{q#nyGqQ`=tjrF!tf`=*aV_G z1!2zy83xf?_^VIls$fLUWM|WPEAfbY|KR#6tzDSD#GIwsgs*1%z=Xrd#slRR!w=B1 zB@9eD_92f}c{aP3NaFa7y1b)E7OW!oSB>KCo*hjY;x0;Ip~-FauKx#IK%>8{TdWnI z`$Z$f_g(>~HDj}|X9ghWBY7fo=AS`rAdd3dvI<}Q&`OLsF2DiWHc`21w#L3)-Nx5&{qODeT0 zrR&Ir+L*W)`Cu{oJU30S&w&xE@Ef!}wDQG%>Vqw|J6|zzQu+?0th?=}E+*SPMg^W~ zILh4e^{Y|99X}yaWH%JqNjh%I>BdAtlYY%D(tMv?6e>wu1v@T4>*PZ=N1@xGpbcZR zq-EY|N|Kk<8ivY8l$L=EpkHbBl*Wt&7b^j)L5(p>6 zv^b@EgGBEI21gYSZvA&7`UYxs?R2V#r0pq?SN4ez5OHxJ_U{9q7~lEttKah+Wv*Vd zt#>K9n)sjw06p7T&Y~vwlc39%D7_hKTpM8W?+cWMhD!$s6}#k0&6!gMpdwIBfPHvV zHn~$V(`C%(5K?J@6=0B4*aBWy9aVC8rJ&o{nj$CM0Km5~7Au^9_P@)TeOHgWf1H%f z$-^_QuL|oVyjcfRo#4Nd?Y+H~mXBZ6k6rO^NbCxg2f6s;@YyWoVhK%m5Ne_3B>Zkx zod%2>Y=#m%EsM>*U=aS^?vuXAUCzQ$gIv5Dw_H`9e+Q9<4Z&>?rTLO9>YgQ_IaPsK z4eoh}CHR;SmPXOz@=j}piz4}FphSb4;H(<6qyRljn&#r( z(5ZF|8nBh}G9~Gs_;ML=J!YHnqv?^o$V&mY=u^o(R(bzZt4hND(CT+tWO;*vf{0?7 z*8;(4OR_9n^SM*nM>^_fHO#JI@FL1Dvt~s z@=XwL_fc9AAvverthsEfsnWlJ<2SoSt{=m-T{y=xuIS063OPJE^Cpt^b^x`#y5c;a z;x!d9`Gujj;W+^H=bPvx>W$|CFbV8A5*c_XG=4D<-2F)jbd>#}Jq8HgFV$A}W3vSh zAUri!7-ElzIew;V7nAH>hT<;VTc5t=JARl6Z^7$M97+~c(qeYZ zl)6iWIl`!&E&CcXxy;f5P)&Hk43^hR2n2CZl;RBfF4BZ1rr!9tcN%PVR?+?=hymyy zH;d2-zwI0U!J3 zh(HqR5vgfJI-`PNZ;tp4ZJ@bxA8o7RMe3J4C2j8S^s0vchFfCz`i6{VWVdn^A@tcB zvh?gDI0O($?ntQ!jN&I0Ftm(?c>;99xBwT1I{HArp{^41T3=H9hEx~m`{h_0&$%Yf zn;d+f=FAdnj#E}7n&rNNizaG#h8-3l0$`--x`@y~IL1%)b}WU!Z?;Pqi41dBU43hEu?r9(MG=Eoc(7gu$+M-NODRv5vtX^lG@L^$uQHjjZ?N#LBDX`7af}e zdr@$oB0Oxcg|K=*JmifyHBXig#MJosEIg^$7-@}pg)O(sUUz08Em!a|oQ2+67j$N9 zIkoCua6W9#tOQQu?8{db5^0BaU;xiD)%uuWaM>Dx)WX3qE{Alv>ioqB*C0T#KwKK} z)dtf=s5QX?Y+M^hPYd=b<4i!?hI*ApT_ZDV5e}LXOHiS>(jTroCjX#6rZG9>Zc7;j zc5JdUmJ=uZJ%hakn9>U1>YaiDNY#c2ly&iasScrc`~-NKYcHKps4Q7EP&n7|SGQNk zCKBt(h(kzn>pO@ltObk(PavAyNeDM2dyFLej9v-WyNz(eQ#4__8_)4+*T$(R=C4_Uaxu5^kCJ9x!_(qeROk;?cE~K8clY|`DpWY3 z-FU^#Kn!EDIo0L& zyDB({!43|boNXsD{0AT3J>AJ+m9;(jz%?T6{T&=|DCj%YtkpxA;Vh0{n{!b||DFB< z+kKK*ngpyanh_yt_!}v==51q%VTpIUMl7E1%!>;eN&9ab+s?9oW^R5pfh2jYFg}U~ zu6{&@GI`XVxzG^^u<04PG+x$GkDZNI;Wl`otxmyFpcs#{eTa1AX2ibV&3i}2QQ*?v z!8ryt04!U#Xkid48t+@woBVj~)V6JZ)~}aGvub`@?ik{DpTR8S!Q+GWj2P1`J2}NJ z0pR2dKeMNhpV&_u>_Q#sW&Duacsu$AjgS)6;LzwRgPL}mQ_;%*9(RaFJ%{8eC&o>}vPBCkBy!_Tlk%pa4I?^; ztqnfJ&jUc(!3}c&5{6kHB*-Z#LPbpse#=46NT;@NW4y1YLXfdK!l4fM|J-GNzLTW1 z(JI#48&f3Wlle;x;@3&nimdr+v@{KoF?pwa$^c*U8#w;Yw7O)^Dl7q8IwfSGivu`? zYoQe9a3l}uPUm5bVMX&P3M9ag;6HL$9`Tf zeMkyn60I$2pc&enWlqMTiGVW@@RluEE@ z-}e7~=`-k~zzg?{8A&<2tmkZtky5jmUd%SYYVJjIgfjz=INP>mk+wbp6iA3R|DPnO z>~V~gzvy2BHK36Xc~NZz%}}Dzb~rnkLg=@z!-~>Pa~ZGgv|bTt&!-x$Z+lWouk*&0 zfo6qL1Aqn>6sx=xuDyWO;Zb~TmJ9Hf#Cy>h+{9?WBA^z-c4hIRZ`a@rg~UxZKC)Ua zZ94UrF<=xxfreQ0k70!LAdvl%Awz9YusgsBIr)1k#w9{%C3tLAc#2oV{=kC$L8CHW zc)|AWi z=3u!qRK%kJyljUq+pvgz7gkT{dRdEO=?2pBBykZ)0L%7Ry)KP~>_ScOo#?VHW&ea# z*nT2UKT*>)bD$%>q!FUqj@05mpZa;kfk|Tw#R4hDn-{A7IoZn4rxWSxWZqhtNhsvC z5$9!~b$$5%g0a0CN-q_c1~HZX^D8dPJrAQ^eBOBUmQe1a4X&3S>&#yvu2Q*IDEaXo ziFTE^ReI~vG@TXm5|PgQEgk_pr6VXmRDj2-8uoi((+y! z(HmR87Vv1Yi-UQ9{}E@sY|QcqJ2@W~x~FUarK!F6nhbKaqAMuQb>wx-m(6pQI&mbh zEmr}o1wtRL@X zEC2ul0B28oa}wlP>f|++v!q!mY~gJgX-^lZT7qd|ii8 z(hT?7ht$2-hsyD2Ox_Sbc2ZV(Huv;}aQ3@W?%q9Jj_%ShDk^GXxv9CW#mGS6QsTyd|hr(mJ!E7Xt^syrRZvX1gzFJo{f~M)ZwBN=# zP5!-@04WAUIj)Ky!Q7f>uu z887pYpM`!;d|-D00}#}c$|p1YKENy1nql8KlBb`kUaS4=^tu;d`vF~8<<_%Sox4n? z?m+Gh?y(Yuzj30nFw@6$>MDZhdw56dA197Bj!kmsRl}n@-_&k9uJ8Efb;&4r=7u$D zGuS4ccrt!lTCLqK%J)HcLE=ies!$Mre*z!D(lQGHuLVZW)g#d{*X7rD=&-K^CS!l= z#b;d#arIlo`(rFC(fUL>o5#tPO2*Kvz~id|-7*uBCG6Zzyh0uOB6(iCxySR-(j-n( zkBV-69Dyqa5iIqF1TAsS9od4C(NR*+F z7h=;!7k(1%S4~5&SS(KEG9RA-^yCbAMKr`RchKZluF*-Mm4agNf}T)AO^3tp;#JDJ zaV^CTh{r_$ddc%f{_YnB@Grhg)k@sPG)RsUSmmxE5RY*nZ4)yGwNBa%BYs^I>22@{ zeFx)9yy-%Trvr=!G=D2gTRQd+RkOk|EtY=04L?P3HevBGAdA`)$|L(u4ZlHis3>>W zpE9`bTk6lBPmFCsD#nJh=KxNk;gQNNv7yJ%3&+ZmYO;2zN-O?j56it>nl_qKF2G&o z_n0e9GWaVe_1gyvHXPgEnzN#vC{MxRqrF8GL&ua~yR4y9^M+tZ{9;JqEGdJ&3C*%vHvKvT(nB$Bp1aGLPS$C z8Y*k?h&gr0NE|DJa0dqAv}4^e!I`4N8^hV?@ln{-4ITH-Lm?qm&m!@fJ%v57V2aQ% z_Ao$%(mo^=OYt3|}&&j)ZARPpWHqchXp5$J$(e>Z0`koaP!!`2#zglBR7!CM*#?sMSV zq!u0+W!CMw%Yee`t-|&4D^s$cxJ)UQir1l-GPx%~zA?5tr2}&nqMhZDH?a0`8U`h7 zboSqoV%F@&m-3QjQH;fxVCkWl>S~qtb*6klVgo$RMO-?5e41>^_MFB-`jomJ)wcL* z0}TZ6jo*6N968QE${_WB4k75mM=t} zEY8{B4fN3TKtJ2KWMD0S5;!`zi%8)fi8eZp93cFZ$>Ox#NFL}m7`7VQfDXH8XR5&W z=4jN;H!FRCsp*8)E>;SKan6xEk8=jwR;h0)$RJ)$QTZM9v*AneWJUnR2aWGpcP@4> zv`ujxUegkqP)t-1M>TSh%U zBd-9x(OiEZIm>ULa;Jufay~-e7`_lPfB*mr-Mj>7IV%r#gDxt`l;=RWAtELs@4fkI z+9WGrP)_mGD0r!%%0XUhQ9Bs8r!pp@o-ZcIvx;bmpMb0vRM7Z#K^GnZUOABn^~msq z&g8F+*fZ}445>RK4#&e+*^MXjCG&k3)9qMdY3t8~RiyF;kuu^^QS<$nL}*iT z#VOeJZjXIMT+nUpCkZqDCCJcZD>+@>-KT)m}K_aRSyzkST2 z?-b%%jhcuo$fhm%=Dg#&L<8|4MWaOT27owsbO+zCqGNGt3z`Xq<9uDe<{^2>*pWNX zNkYtm6LE-l2rMrdGinZ>3DZW11(zGG&2&*`+Lzs@0u)uFg|HnTHNkYIvU7eX1298o z{VirJo0ISBN#&=M&g;1EV24aQma9MYbL;?KOr#`^c$vM##I6LM=Ay=}$RZ0j-#a)Q z8Wf3Y?%!000930h&k!-1(bq#lHYZ6D8vT@CN-Z#B0;**IKrrnx4PBC4OsA zd*0R^!=FoQxXoHfd`Nl;nj7oOw7QDsr3i8Wl`^TR&11Ur5A$;)*)H| znRI6FJ#Af70glwY*U&NuYO-N0+n z%_z7=*~)7`|4Rhc=(=>_=VR%iyr8-%2s|we*s8^$G<}9yDSJFQA?zbV@g*zJW4+>` ztcv`ITMGzZ;ms1e^*np+T`QyrWUH2GrIZvU1K<527Ar_~f}gw-Y<%(U_7H%c+lT6g z@p&fnhZP&|*4R^cHLB|PJoV>8gWY~LAJYos@NR8pIA9#0=oK@3gd)3CNZb^gA}=yQ zuO2%yv|SyWgYuH6Q`HRD@x5RPxvRm%f%G7}+9j#!Vs6(xC1D$~@;;7Agah`D1|u0O zI4}ngH6gFRBycK_*D|`LY97kMzvT(<9*{$8BvXFgYF?Efz>Q7Ebs-BWZfJy1RmS zlbn@3=)(3G2o@>gg|V zVaMD<8mU@+i zxel(Xwn{=qs^~TOSx!7WTM)v}*j%!>EbFOv{!1se;on0L@CGN(hhAn>F!gDoFB|qX zHYNv-O&wsZ*X2U|0o8pum5DGyFPiWHr$Y{}w;ss$Ro(Jh00yv%)i`@(^oNliScdKP z9?LG0*$BOG+i3e*>-Ljtmz6XArfs@NkonUINZDFU@B`I@#RCm9=xNT}kCM_M*h$1& zBBw3W5`i1M@ZWBs7ZBU{CsVj-V7Dwm_jfm^r$G7dY0*3}2OBjz|ALt5u*2=n`wM@+ z-#Q=iudKf*?7y%&ySY=f?GOy=}I%p@Gp-?2#)XH3#I`Kr&&Z7n=*MEm->d1tmY5mG?$fI+6BZ@m( zqZ;w&#g~(7l9&E%G0y@Ky0=Y@E-1RT*{~37+S%AzO+96rw|RSM4YWUkeq&Q&$9eG+ z6XHYpmI4!N0x8k#s&)~rak`HWD&&V?{!(?yniwpAkK`A?DCT5?6A?go73TrDs*&->)cxp&0_V!RJnGeBGL!TB&HEsYcN{Ye!s9 zz9rgZ86Onw2hffCo;V>gWTll3S{5_Om@f$T{r;Zs-j7VftB{~w@a^MT^4vyzIg5U} zv+zJg^*g+dZr6nk36`;WgoD5l_!bYrVE`f5lz)JoS+e$q3&|K$^{$mSdbcjLPO|V2 zqDw4Ikq(MY!(@JI%F2;s z)W`_lDS3n-b1+`-lZcn~y>5zs1-cQS%KGzNCWPjIXa4Sdus25?ls+3d;o=>qK>_a} zmj)Hu)SA9`2xQeWkZYEji@x}!s$vPbYS7H06ElAnU-NS?00093y#&eix2$`{<)<`N$FhTm0?DY6(9K^S66k#HRWr4MY{D8B;i7p2 zE;Xf+3X{#Suq(<4o0ymOdGOaCDDg9dU-_N6r62@-P-FH5dkaXE*2B6C z_uf)Qv*S^CGVY2?m4lc4P7Sw)1cDf}5d6T3lp$1nF zsff8Nm@uS$o5V|wkzky!Bi04wdFL**hm$B%gDzp6`~RSvGG&CUOsAlL=6pNTFH-E} zhZ)UkrQyME*gse-w?J_rfzKPB{3vxhJ|EV16Uj=_yB?2Hda?gH(YT67WiX8}dlKey z`EFcK->&yUWGo)$7N6w7W_jF#tYF>vFgO8&`u!{)iD6s--^@ADdip)0K6xg*Iq2jb z@grxSSxuT1e+dXo zA!`1m$im0ur)-iCO_$9GW}tJP%EB5$H$?|TEdVyI4&AIH=ZrilkAa(NL8{TonTujs zk1~Lm_wWV7n-p?HU{a{F?Xgz*GEOn!QpxI@S=oI|$EPNHR0rrXgCrQ?)&JY>xS2oR`) z9$3r7F!(P7v^KAp@eNB*oyxB%u`e?d>eC=tig0U6TY@a2N?x2Gv!QFiLzti?z1?6H z%^XuG*(H^gb%MeLlCt~BRvDkPaL)GHB0Ps;(Va%Gf2Q1Yb_qSYpzO-Zb@LKK+SPOa zUA&>I5_>iCiJ=>(&tjyIs<8j|c0%(U0XB(tnq5RoU#pvvJFtkZ&z6==D2E0A6W_$< zS%CPe24qPyhf_<*VBo24g8DYQdGj=`Ipq1M4NA{|s|{!{ z`T|F>UB*==Tc)7?ny$sJ9iU1zaLc&~RoL^LoRCc%hgY3~wzlaz#%9!1AfLU#CF8P= zig)1?H~g&^mD|ep=(Qs&`iR<{+tiU}H9Va)EFA84WL5VD6^AB64OiZtpPexZ|mQnCx1jvLBDtiCa5K?!j<7p|ywjHlb5We7sq1~3UU zf#^g+0EyoMnTQV^lb+XjS%D-pslbfUB5`E?T;*f6A1-l`)4xG>+|uY)&nr#x8Q-nl zve17=L}yHS=JdJ$t}CTc|94WaSfKl6%&T-2fhf^t?zh>QKagKSCWE^z2P+)^j8hbg z7!6^*fQ$e%E(c=D@L@<1M+o>oJy#Fq^t5hZ3^yV`LnXn#UfED8YiY%=FM%vGdMOXu z%q7B!_+X^q*URj}fvWUjq00HwkhPhWcT{+$oyh7)mL{9vJ#8tiKOMyt(azyas;Q}X zrAPXF*KbBuSb_zg(oKUvp?eP`jb^4i`CPy_z39@~VfR2A23Hw(w_YN6dSKQyx>TX~ zkM88dn-)j*?BFRu+N+_{c8PBpYjtW6V6(k>ii$ido)G0xG2_e+bp;Wz+25 zGmS^-s;vS2&19EQEy=*Hqom~fjcnLOcFr!!7?Md?}a*=6K$_tx^5v@KRBjaAM1)h-IR4C$YZL|Wpxm;uBN3+k z_#lQn3j=juNjyL);n9;#4=}@y(I$0I0zKQ1xK-{q|Tv3ceB27h3cZ}I3U9R zwVd7<&^_voe+6O`d;0vy@L%uBba7>525;-4Yq9^BnC|GYGo$(0)2w-_$^S9zo5pLq zT6Zh}01e>imh#$@r0ou5tUy5@S{g2^WI!*x2K&3U;S>-hwLg)Ev>02`U#)vT{?mr! z_QHlM_X>f`pfRpp`<7L(j;dI@P7_(zN~UyA`74xvRTvZTeL@Z?w33iNuy>pZut>{` z66el?jg<^u5BE(Y8VkA@6iB|nWRzGY@mZdL7j}YpV2`6c7Q-fOE$a-Kv{${g3^R6a#W_@08+%(&LWqbzpxj zT6@gOPimJ#r8 zd-Hnj2l*f%S&MffPcf-oe;pl6OS+`kFw9^E@SUTe^9NU;IJ%rOznevjlX8~@qlgIw zE7l3zY%O?T)E(p;z50&i*ynI>F7i_T(nu(Vy-bmmBdlIS2zzo_p@e<)3*)}97yqB_ zM!!)`y}SzUGN*!=x)k@PucGe<_HsPBP8AAplq3V$4bD~NaK<__AMr z>KvyKUW$Ld7UhY#Q}XT-nnO}Zc}jlax0m2VZ)(PuQw)p^7_>T|JqqSE1>b5Lt(znc z`yY16?ACz>w6yM+`RzGV9VzQaS+o)qqRuR^C{x*7X*+NDY9;-ClvtL5J8c7ntxq>U zY%*}KDeVR4Tp49vuL_aDAoOr8{`~_kK?pFebw;{bX11E7wK)jS!0ON_*M3J|;)y>6 zuQZIsDsooc|7RppR2B_wsd(cT(o_dE%tQS!amVl5*8}Ztz=)r>o!d&@xQsrTWw(|> zhQyU*@IIwyZM0hKNNhKA`yN0KpT6P8(H0o=_YTh?gYZ=S4HPqBx}^u%awJ~EiBVPQ zA%*V42N%zkBU6MJBz6000J%xZ?SmI_#G6eWLLMt-!&^k~H;3-d$FNh8&Hl zcB07?{u)8HxF)MwBhQyE?gt~eNbN-2-ED7m{Olug#|1T&SRZ$`@=u#XG zOBr7XD8;7Qgy@vZ{ZYefy7Do;=c18=CzE{d=X5hnZRi1;X%e~6D`2;^+-@d)y?Cck zhR>#slC=fPlfO68iywXs{f8 zV~~vXS4v`K*upHa{BsRJx4&b^m@)`fVKt#~znoXJy0bjtbBwkY;bk%2g#D)RT^b7$Il$`pNQ-9Ss%} z_HY`1kvbzlq#nvC1S}mnflSCg4AL$>FwiQeU z%;3$pRqZ2~o?y}vDq3LB+zGO>1Wyw>jQYI z^t0>7GEt0Y>`UfS19r3?wz@{0vG}LJ2v?7vi*anz3*WmWb1k`rizQ9s-U_vLINMUF zX{=dO$2IxEzv<*EU9L5;cr`7i}>^^&l1wW1a*fhBC7F8vu7<5mtH z65q&Xn3(M1uaSQIUkT8c!%l0ucX90g*sQtW5IEWnM#&a!XjwGI;PK(%oh?-7aADxL z7youdlW}IU6Jh7+SjRk+EO@C>t2EjFe8MqhmM_=WKwd|oGJRJwx;q|2B&`H4CLzv4 zKuq|D3H6oMflVm#Vd(4pk1bEQC~Hj-A>d)yD1$w5QR@zgvkL~`oJ3f!{I^EKSAMJFUDpz}&h z?!!P$jdjgEYm?T1Qv?&-0V!*F2%;rAB&H1Impy`_@{nq&mQsd6X5Lld&`8qbX#bYa zNQ_N21yVpoua-#|1C2XS+QOuX4n2<48A<>ug$3SSQ5<=M0FbtNIdgWrxjL1A_L0GD z-dZ=?4p!oBh8Jj0z4CV85#~vtd&!$7;FKDRxaBkCK zbUm{6wx6Or#w-_+CjKl6yAUxdYgAImdWEdz z6X5J8bu}jPoeC8A?17Nw;&Ez&Nf}phgVE94NQ;6UGo0O^G>K1M`3Z$y(X%CwSW`lx zcKqws6qGNS^7pD@Mb479GXe5x#tFq*AWxjQ2=A za2-{X9!s(~^^*-o%yJK*QI3Zcb9priCt85vYOF6RuJ%y{%hO{rBqLv_TqlJ=0v(kt z|Hcnjw`gDZH|w~|ckpI1lc=kPg>>>5ed|^DUqK5h?QWhV?loMTF{-M05@vTwqd!cn z_E~wVStp_Jkj_I+hGo9h?TIi(Pbb^2H5uJ6OYc>9w6+@atRw!6NKF84sP^0pm(bT* zX5UKO9zBHP)Qpp8-2ToO4-gbdlzJOV895e*2ohKn00094kGsyyh7_Lse1GtCjZ^Eq zQ5*!tlpB$eIx5ATS>as9Xo|Gob1kC7>Miux0)7HN6d8^t41~~0g2{!^K~vZHCITEp ztp-$Q?TL$km{sXu0ob$`Ww?Y^UlByEDk;gktyX#DKFq6uR0gRwbjZHo`_dubD7*=+ zlK1Mj^`P^PASI2`PoZTav!uxY*U(`9>J2rKmH;CUN8SA1qgK^>JThH zhdtjpb|^uVo)|)QjoI;{Ra-NScfQ!(IA1%E#2?zn)R+6llF`B>b~e!jM0#aiS!U<( zf@2A>_A9<^^cd|#SNFdGyMG^ZC;Qkw#sC1uz%1n&or_&7ndPru^Z)<@04mDs$KStE z^Qm;{@(-L26Pp+DF$1#GIzqNy4|Gr{W? zREs}8Yk?M?Fwx2U&O%L4$ewtY({O!@uQa;afR-5LT++M&-OzgMM|_6rg~~Dm{lzu( zDZDsGwauk_=uHWaISD|1-Hgv z4jA~SwafxeO1L^&Od9rw{+w4r;{zoRLehP*`#gL`&NfetU(Cd0CsM6x!)ZbUn%ji)H>W?-9xQHfwRxH99=?ut(6s-IQJ~hxnmB4(N-3ZV-m_*R#)qx37 zp&aOkHEgWAlv>X#vvhBWV607!Lg(aOARZ_n6M#+Y=HiB({}h9C5+#S^=hW@2Fp6WF z!s`Xp)h~%ir#TZ+eBmy{2Yhb7|NOvD8a(EPj9w}=lhgZR^lu?oOE%hK(H^21V+o#! z#o31OA`Pl+8yvxg)bagS^DJf5=ty;~H%&(?X8v$XJJZLRo90K0M&PGH7skrhFRQ}E zscg9QzW_>#AGK>@JrP`8veSecKOi+*H=!m~T}oZaOJ2C4j#0rJBORH-2XaejK_yAZ zeEJ$`c>92Yg|g&yoi**R1Zr}KG18d}kvK~ampzgTV{y-ZhTQe`)7(zP0PryRp&{Wa zf9CeJ-Cm3BK&UJ6>sGd;JPKK+ufb{ybf;*)z4h^%qfipgac7$-l@6ams!!hf62PLO=SQoOc} z$`B1BE)GhjUg>tUu-@!xqiQ~~rv%`yj;7Wnp&zXnM-%f~B32P3QfrLaFJkrUExf4= zszA6~C83GDfED@S-qP*4HA>TEPC(uc8wbZwudtT->d+z`v%j=e4| zUo9^j9Ix8;&I;9s+9g8Mt=@!8!Y+{Ni_yYSrE%W62X-Y-lQJ)`(&#E+#NV?ZC=sAbs72Q2%b5MUr?g+R-R_#FY zbqpFKhb_EYZGg(y67d@;Pr)NM)4z$1A)-%=<)Y!c^@XAJbKM} zrr%4Pi2DGD%ZK9Ed7x#khmJD>RxY$sc>nQ*t<0VYPg&R7^0U7>)z)CV)9ZqA4|DEW z>hK4F2cU=2V;fJ`U{!p|ePL3*q+&-Q<#=d#<0y6iB0+XEhbJ~GOCQcZlAxhL|Fdn4 zE&qvXB7@c3V)V#iSUwsct~|oa)n!{6T_2w_z^7sRM`d#Q)n9>IWB~jtag=X+gdJUw z(|^1g>z%^7Y#gsm*MkAgwujBU^3-=cMs=T@H971_xF_+t{BUE?qIIkU`se`kkx>CS~wgA?mT_KpVeAog+DZ>~D zqlu&@fr-~+B!G`i1icNO$ZU!R+hLF$L5SNT|AlLX>KW=tV#g->p6hwC6@;p#kGIAZ z*Ut8zu0RQAf2e}kkKAID|Fv*0D2?08X`yIlZ)D0$I|<+N>M>B6mdL@Gfq&3am4mFe z;KF(Isk?DCz|(#fFGd@mGDz;Q;9cY~InbGcTp&BGfp9lQvZh~$NTdoESE<+=vH&~= zo@}k5*l^aXT@!c*eLc&dAM9WilaQ=5EfYWoIpiS50018gdkp;_hqKp2u@8{F z9w5*JFb({j>9)ctOM+Up>ZlU>o=bg5)Uls~XP|+@kd#b%RUIgydf&q|xice(80Ep{ zEB2a8vQgz32zhEN#YO?@2DzTA_6$Ah{D2z{v{W6-HmfZ4)Xt?!gVDF}04qAZ8x%`p z$_1dK-te+enAKR6^9jNS^Yp5Dr>!D7t`$7$<@-CnfZ>B4cCfCGy%@A6NH*1l(=R;v z>u9!ShtO>S{&Q8J*WWtR^sSNx7oKw-M1lJ!;-M2klBQq^m&XDR=7X#CSV~E`cBdbW zBZH(ObCw}}57VWsBm-iQQ8nAgy1S*u2~a+#n59gk(=!#$!m$o8=pbe`I9O`{}-p4#xM0_@y!9_5@l6pxj}2 z8VL-p{`TR)_{BLn6e@H1{SJk_kV-525Bms8I5R}Vwp-z*m#of-jwkOwE}(s%61QhA zc5K5NSUurBNbb)8bg!X#%WfXPgpjyCGQaObjN=x5;3E?4%-@xh_Qd8V+lO*4mVJTT zvc#Cm>9{q#O!1;mrT%L&fyY`4$XFys>(EuY()GTSD7d`WzV-IMxJ%H7DY4XfNkcJ`Q*X^=HV;_?mC${GRKs%DpS1nPr`j{3yg ze>i^iu~{=(pD~A(Yi^FvgB6l-czHS0s_gFsA|~7^i{^nSN|dGUXW_ZpUj>vf2#)J^ zo>70u4?D@39U}tk`e*<8kRX^|UU{?-V537neA?4K4M_lAGqTrnvXsM2=;D#XQZ1$* z@?wt|XP33)B~T&>CYHH+INlk7DeO&^X>Ad#h=%PK_ zzZE=3Cuvjn`ZqL+Cd-W=$CoAO)%l%A`Yv;;!-=hm*&fFqYqqE^Y-m}+$~1~ zLm8Tav6RyWxnaU76V4>ySPnbZm{`1Tbj-#HG#kY8?M+nptDb7^P0gp1T-dZk zgNcoPNdqBV9iI8I8%rR>?o6}N0rR5|hS?7)a0jzfBKUcn{d@xeY(SI0;3q3Z54R_G z*e@R$qHk$HZN$J8ur>JyF7KuesXl!0rRJZC6H#=D7UD_s{WX^7tY=SNv!{O6_9?a~ z*7u0&>Yy-T{(#f}_NgPhjhQHsnYnUOP&>1>cf`r*09lj8TB5<9 z)S^4@XLd>h-Aicf!l_kV%ryfkEZ`kV+~WIZ>)>q^{ay&t(u(}Of9HZN_Qt*2d7ZK9 zfaz=nd#aI^phAx0F@2fjTwLzEY6-qA-->h&#e9rU7M*c+C8J<^vt;#&ZT zN^aVU3}Y94fw`rLVmEadaRRj$yPuus;sh9ccee8gvmNomMUvck00zavtpD9_dKV|3 zBY~qr;Ev6Y&cvjIz|(zNAv&n`&Ri)GH}x6tK8S5bQ`L5;DQmX_0S2JgCTb>CjThte z$V#+8O^G!&-PiWDI}L{*ij%Yzo~DV4Y9zMSqG=emv~-cL;J!D%u~EACeSXa_8#fGO z1?FDHck4mdKfJj#sV?5}@Ms>iFAj>ItCbdU*Wu>pt?&&=yEwMoR?i04_82v2dJ8 zN!jpZ2Vs*d#7-$lkmL_pqH;MhWJ)o|D4UQ94lxKYG8$7glYsfck|_HZsapBOD!zSF zX2^{qXUU>~000F(y3@iW9xBg>WcS_|^cFgklHo)O;{5SCcyyg{7u`OU>_zw*!5{)b z+%MhAL*-xq(Wg<1njme>nGv;Gcc9|6OBBCQ>h1F*Y;>Y~VXM-OX(hvUE zcPWPE^EbX|K(xV=R_s~}D??Yg2bstQ=@xoIVmdoYpLHUP_5B8U^&|JHZWt<-+X?Ed zd^_EQSfH69o9XBgI4BkEA0PhqOtJCYrI5-?bVcx=W_YW&Rrz4&R*l)^?qcsw zco>(KJ^X{ctt85v6W1iRCYNW>>g4GdWhuC6c!3PdmltjUJcQv`(bs|f$@g;7*|K$OMKOPwA+PwTrdhz5xaC$@rKZ8uTE~Uv!8DDqMOq`q6w`-L9FE!B8u*Cl3>EK4Mdj&wmghQ~a zD;ynTiH>xIyM*N(yf3INAC`OIu46y^n%6M@j06@gbQ~}RFc@;j$9vzU+h@*efftku zylEUw&c;_Rs+1J^lvD!RgXBv)9%Pmr{ud**FmBuC($`7fv7>(=p9Z`;;3s}c>Ut5A z>AMdF&eo3p+uR9&A?@QfV1X73Wf z%bzD#Bv<+`#XTQCs;9(o6k{UAgxo=x)0o!`ORH*B17JBCIi7QanV{lR57rh3*oA>C zl8y?~Go>KE_sTUqd>NmcC@S38{P&Jd`y5&oO!){yhHj);dA}_#^*&hRlnq88qJoBE z@+6LrIEHgdBNVEHtZ2L~JDj<))7%UMzoJ11sedFC$JVhWxzr!9^=JMZiKAm+5B|zD z7Nzy-E~fe%d+Taykn1lJY>*DTGXYR|*h^ed;ABktmP-mPA8#5NW_12(-aq^#?>dPt zF{AL|P&soVvDCnz`ck7o8jTDRof1_@pAN$;s;KQ!fLAAu(9FNVJV_@+cn(@4et>f6 zh;9l+VmFrlydQT`9V|ZQHP-e9V3I}5gqP2zmBaDTxKtiAq3_Rc3odcC2*E_9lUma9 zE>8NjB!9_Yt=zc?!7RR)(GJy`GM^qg_gWoZ6JkHTn#DblU|{!|_B=Tl34*e`?-xnh zb8OHm%62D3bs?hBw;$p*4JSDb@kBPzo0znTR~>tp-EaNNaMfF+xq*k>Wrrv;g_-ydtXU13LCCqy z8iViSwlB&QoO1Y!@1g5>YG+>S1?l#-8Mf`{@9OE^CzSuG&vg979DwfwJ)UDVMvL1x zfb%e}=x}9|m-ql!?ree>@#4!}<1`s)$)U`wS9@h#hKHr^OBt+zHr%CWk~iQPcWVu( zyi+2~O7?12Hxguwe~g_Fg0Yh%{l`3aA7?P}srTVElK?^!lhBD}0Z+Y9o6!C%DnerU z*uJ;ndX)|{vYkF+8+_P-VU0ot6|^`mOe%F_``Wn3sspI`Tu zOqlDwGfnox(CQ!TN!9~z>65-dEgQ;rys9 z>VfD|f2Y~4fmxkS1C%%#{RPI-pHg9{rJCB2s;USl*J(XIS|N6P$`GLNg z-CDFbqIx{gSvQlSghZQYB0TANi&)!L*)hTX)Jz}ASmk472c&;1^51+afxm+ zg%VBh9+s<`Ap!Y0xoHD#!ixT|ej;rGlst70Eym=llE{|Qqp@4M<>79tz&4JKzJ|Rc zo@=00m-$bo3oI(2cd_t17V;F@U^T$4?JZT+r#lTjc2wcu|vRyleAVHjq&ds;LhJFkEPOO$xjXy6 zxL{6?i(?dHLn2;HkC?IJ)R*jC9c6RXUMO2CD4Y(KR4X1NRm&d7DQXWTloKXn4Vtib zZKcx(V6k176pvu&QQ4iw4;&l7;M7?#0J-e>`L@?uZ8NT6K|(yLdRP|ds>^l`siLce zn7#8f-ck29ca94}A|m&v-PG!7%e}mIY2Y~!mA)2tDE$SUi5}gb)&29{7l3l&wKB}R zhCSv25jQRew6Kf-t4mQc+>d^ILu@bun=lub5`%Y96@QmU(myEiTc~4=8Hm|=#MSC5 zv_tY>e*kM+%LT0Ix^jwIarNXaXr7z{xu{vtHebx#mc8qI1FmHrVNsa?hZ$`*uit@^ zzT*z_aHs(SXoSXrV3ya|&J^@t+`jD({`&X;(pS}}=1aoI+T0VqZrs#3mGE7`ALSwz zkJmlx>9>JS%GFCL5lo;7Y`4qU8B;dwoHyYfN~&6d6wZ;}z!}vAPmOOlxg=})E=;I| zqUC-@I z4BUs`*ibf7aF{MhUQ&v5>FwRylYp@&&!hL+^jRb9+jiY;zp;$LrB`Xyw&I&J66>E@ zS*HepCIRL&YyMOELGPbCOEt)?2$6~<5aefioR0Fbw;=Gq>@xeTe_8HuW#2P!H8iN-K~zF6aUQl{U4Js26=Hf|@67i9wLZd+FGQb)V}n zLAmdnn>6((=Yfkm#G(EdE7q89bO0~mgligCB!9jL*{6F=aUlH+S<6QnSFXO~?>(oq zIipXhN-C2o;d>F3^e9$1D8x%wLmN{rCeSRsX90r+M<`__VZ9!V}FPy2VxA?IY&m^8n_t;<+E2HGg$b;%%amIz! zfBQ{+Fsq8()YND@K4`g}wvyt=G|i`dsjVB**1m&DFvP>G`#j<#h5w}^$}1q>TIMBo z1w1Hs;;_u3LB5B}!NyvnqOHp*&XDAY6ZD$F#Vc5&K9iBy)w;(aF2DT$o&0{&=9mXu zwtR262g_|V3I7$u?4r(%IA(H;2JN19QnI6=Fm>5ba*jicAE)_jMzLvq%BZNB~-GKhvG>{6|^-o;$< z@^kj5hZ)ROjepD{t=o;G#;Xqu-e-FS`3;Mv(Rm$k#B4>V2z6r;6qSu(^7L5Kwsp_PAg|F=O0|0}M zNZ2?5q^)UB^`{Kv3Tde2v;0)i!n~wdXeT=Id$D2@G&Dhx9LFY<^O~w6n_h#A(s>7XQgp<*&J=?3Gye(3z5>c2zOBSj3)wvQI=fqDEXZPy zLRES6MHlj-xcH?PIAZwC3iY39EgO|$J+1NFiQeFB_O7`eIfUDZGFBM2cM*}HL;_CF zyl)=!a@G#?q!#uIAfC=ts(g2iX z63yBN1%ncl8jr+!R-gxwKmY&(0DymfOznLAnNIv}p{3D0Y&PzOp+v_&4yb>|g1Wl> zF`PYr^84_kMTSqt6xRQN#Y!h6Q32vXJ(|na?X3qg(PP-V>7IHIcVKNr^q6)5)ibgO zi>Q_*TAQJF9QG7a^5NlHqjmDf7v(9t=Xss|SynTe{s*I$5t&3`vZwH)4CTeyN~&3P z*@0Mf#-nylcQhD9E!QU?)K{yHxzA(;FNO5M^wNO90Wul73aELu6?mW>E{vV_;Fp|c znZX4ZKa?b^zj9xd`$_280=mo^E!P9YM8G9b$5)w4vo@n51@g-LMR|}?+6`?NXs!O4 za1#|09fye(w)n*B>-bYDNy^ZW#uqVt^dU`-f2H{dz+)FUP?R($wgG8#QDPquB4;~M z4UUC$o)>;^Uo%>`rSkjh~5j-%jhqzcoDEA)yRk?_GO_z)2r`Gx*oOn8K zi@6IGs&2NLY?8t$IdMtcK~CQU2V>M&JgE6=WJX?}fmTBpoBP|Ru)R>$du-AVk4p<6 zx?w!tQ8{s1td43V>SuzTicQf=DJ=IuN1-T4yYEC}u;WJQd!qIFi zW~^T70rf+9s;46R_j0FPHazdJxymbhlY+<d-N=zLn|BUI*h>3lm{7s7$O*7|%j2^Z9-gBc##?agNN_^jd?=$1v zmAlI<2i8i2%V)!#4P6zoHorRUz;#TO|Ez&9Qmj+S0eC4Q1Aw-OLrr+A&V~~uj1jE&il+jpMg9Mh&lGCW zD9KU2<7Bfz5p8rw3-R&{KsPXsD!w>g^=v(2A zaW@%aPAVFrgB;paA(GxV#_w<`rMnrrQg3u8pLBD>Iyg<^^OW+;cwr%M$JS9Fq|(k_ zLL#?>DHJv3d;=#D``#CiuDap;m8kJl{Nlc=dEzC!w?ngQnKZg_4WBp1k8r$?6h6UA z0o*LSPW>j`T=)Rku}E5k7%;&M#8y0Tf^~=wOIM(fuhZs>z8Bu8i6OWm^mmZm#XpGk z_pq58N8TQ8^|`XdiWSI)-YZ{nJ@aF9SSnn{yOcY1a;89|$3BEPn!Y~e18^im98x4% zduh*Z3mt(KunPN_F#aRQZO$5hpLD|;_i~^AxIbrI{kKwl>4+*edH%wLgAd;7nE8Zc z{c6gWk3g*9;F`E^fI+uoxs;rjy2uc2(X_~94)usALX6!{lPJ1#R+Y%Xj`Eo zR(37dxy8UzA=p2!`Al|s*sVu7f{0xz8ZjUqw$@7`DM=>|cqn0#*PM>Pkfu4mjo-yK zH&zcevk$J`nw~$Mtfp<28lDr3?gItTd4K(msl;gPhg2|5@**~C`oCblLDW0D77(nC zC+WEFd;wK&;z_cQR?k>>L)T)Xv6W!w=Qta|4yRM3glI5`gZBC6Jf5C9;-$55=l_|V9R%1CA#nMCC0S&+nid7!iP9zWT7 zov<1Th7kHKyICm5=Rvo&r}lABJaxh#{hM}Cg&s{6LUeGerMODzRnFJOUuhSyQm|19 zFrSVVscXtwpVE`G5cOAJHp!s!*4~R}7`egQ0S5~3xJ$2w?lO)WP78mr$!REI#01KB z*LU%D3{*)JKfZ*XB)q>vOk`WA=S?TprjyIn4LG-7fzNGpoUEbsm#SXxrOwcl$1@2a zLdNYvGc1;$7=0n6slNX{`Yf-`2yo9=e}GFLL(vGw?SY^E$d9(M3xCC3ReRZhwiEno zmwuyAzb3wRCt-T&iW&^W-h*yGPAPp%345~Wc<=xK0{~S%E*BNEM^s?;|9U$h^{_*I z9VCje00&Cc*%K(LI@y_7S12E%d71H?+XY{;Ey*S&w?L3agAq#y6=|bumLB$23d}sN zw1GfjMKaj-7AhurHU#9N;Sp)grFbk?P>{Tnu*2%nyd|^USq$#s2@#%!ii7UG3jUQv z+95-2o?SEtrle`@$D1r7UWxap$w+~y@tW-&O|jDFb%{XJZ8s<|T`V!DQmjroqgw4kg5S3X|UbDd(G?|~UzRM6qe(TYspg*uwXLZ}}}b+tpKc%DnN`%xIJ1}@4X z!=hC@BtuBZY%VCWOq21x+rePE#3Uqe<(;i@OU8em{Wru-<%h80J63d#l+9C0G0jnr zr8ia~A%FR2{18*9bIHi_PgX9>>PNIPjEIs7%Y$1`1ojd|4bMDlEXGM3S?wc=9)U#; zasHc?l#iiHuPRm({CEs6PGJ^8h*-dGRJEc0g|Ti+uR{*4a5Qs~nbN+ib}d*R8wld5~;yLx@v%uRqbGF9n$Kzi%va_v!2mJsq;i3Kcm|wE>muVRWAKf>(Y4_Rw~%# zVA(z?T-5LPC)!kKBznDWvb6J$4zqmAu&OAzriE;iYFo4Q{+v?D0aatVDz*P7T)vyI zPxanjPg+FnmU{i?4G9)W>4@< zM*N!^j$x736WYu|gyJ?@A}|3z@|H)eRjt#u32TRUOP?8VCt+-~zSU^^eUcKMnnGV3j9mlGro9K5KB&*8#T#L}2oeteE4g(n*Q|S|j#j0%oDIP78 z7Q3m3%Lw9MK_>NQx~8?LS#hr^In0iK}X`sNN|D*4T*d=Xz(iI$C!#e*S*)3 ziG!SZX||!*OjRyMXv|(s-n3y%e=n<$tfOG;jh&oS$|6O)(N$3w5f0xK-DjC{&ZY>= zuY$-#y}x-M?s(8?bMAx6$;d3uIozq$@2Lh8NVHzy$6sx@1a+o(kYGe2aB2RqQehFc zEbhfH5RxyWD+eQU?$8)Uod)G$i9O2zFogrF2BfiQm+VHnG1UJi;v04Ts5*Beq!9b` zkEXu@pClE z2PZ-;9w5n+$^er{sHB8^8`2HWqNm#p!{5~p|B39V@gI!v`9>BnIhY6#8>ga0l`r_Lw-jfMRJ-*;@Z2s5w*1 zb_kv!W{-1eA7zLsoidXdkw zOLSRV;5;kF4Us9!&$LyPZ7b%PjRO%r9Efv|-CP*WbwzuX3iop#`|w|o*uF4Un32@` z16#BZg?WF=>9~sc78S3~PGml@po>+AWASOn?fN|XcTb}8eKgN6a|QaYnjaV2pxdIp zZo8-2GSE({`CL9+90&~7#bC3xK^oQcO6L1oi}9hx)qT-)_S*GVNC4&om=%Bk05qRH z@Ii{*!=7Z9**}jJ%qA>CAiwHSMPE1FXxSro!oca*NP?CL0~TCjhV^sFEoGP2pxY*g zAk7sTivaA40B~Dfl-{uu>VZs=SSM^LGM&K&#mH{zas|AG2KLVcPdO&54*g2YGMKY{h?!8%4c5Iit$TBfYWHk$q8xO z{nB%v5z5))kwMw@cVTEkD)?x13A)EdF41f3mgNKyIUlkgI6YT)|90XjTx~Vc_$NJ5 z3L(KvAQT=L(rV$>ZA~%C7kK!uciS&!5XzKi?lBBx4fSiVcUqkIUb{-^o*c zh5?f0a`)-oicnd3Td0SOmm8y5OeO7YEWvuICv?i<95C(%ouOe!l4hxXm@qdi5<2FBc-4k}YWHiNMQg^I&S{(nv1 z&dJXVNO4%>{1HgCt*`5$2!!Sus=e^pw=6>j~kJGd=SOpqKbX zDp5-F_@t@BkTa7WdIN4?WH8~b5k>;{#g)5DMg^e9qA3i@98D%nHrmaNV{haA1`G4V zS5dlz|69UVe;G#H<8H^IF~}MzB4!1KyGGSBYnN_)e@;6Mqsk$O_4XwP3>vrN9z{`x zBLxG)tHMzYx(@?(?W;Wd)f5YiZh-Nx(oiCMMU))pfenEJBqKOc#qD5|MunCRV<+SP zCy&kac3ug7t}_G;c!N5J74N7{<`fe}(a~yZID-@_L$`{JemwY1z0f#pqjH+K=C^F6 zQan|-UXb=7hvoXqR3N;XeG(1P(iqq);6nb!L@jA@afO$EF=RSk_VS+mXKp8y&nXe5r(!wcOo^~&jEir zxIKfqbD(V|+X{!TPiK=OB&dU1%~?2^P1-$Nl17h9-jONpDy>~6ZOZCKhZ<983cHo+ zg7E#KXmbYwc^lW0Nuktqa&)xsIc}(!xtWBZVf~qaf-suvh~GIOGdF0&yUVzEu?px3 zoSS!2=41Ingsp2gdF~%Q*u9vjv>rXfs^@@DK)KI6qMF}nxu;Ku0xXVpHNp!-25Fl<7@%jPqOaYIfbWtAi&C1D@kOs z%?2HN%NVqKIEdGFA?cWK{Vim_aw(HUr(Si)xx><6Nf1#_rc+YqD&<26@hlcldJ9ai zW3IIwF>y?o=EkR*b6mjm9p>m?mm#VcYSQ(W*Ld?N1Np+fXav{lnu0`d@UWyN-C&sD zTz-ID0W#G|%Ww00>l=olO;&fJWqFK$VsMP>W6`E;xZILUe9Vca3M~eI6GwQQ;789G zwo@!+SZLxAaej@7VN>IL5(t&6qS1-8Vj7Oj{rf=yngcla$jM#VWzNEN3+D}lGL*O6 z_UXRQLYiAGgV^LQIp`3(D$VIUJZ74+VSO&qHL-ESLWM|vu(Bc+i_?4>MI37Dy513Q z+q9Yxjk?4*mXAKRp!{(Qu|k?vyk`^AxR;{KV@Y>|f$E$baWP2cV<1}*QT4K%lPyCk zsl6YG5fLounQ%axZ zAkjCChpZg(%(@j;tW-Y_q9JzH3QZu3qT59_2q?rkM!K1hOW~dSdxDbL>kn|@x5HFi z>nKv1go$hIp-Nb9u1ND9K&3k~fGDRB2L&CsDsG`m3g$Vz71~OFJ+J#y1SRL2ys46= z{!vF%uD6lG@}LAR?b2vY4t(b1;uVKbDIL)-Oh$o!4QgaAiw(QnJqf&z9_9;CeiNa< zx!4gxUFMus^4b{FG9;&TG2cc%7@Ohwm+^~}C8HTnMumg?vE5U5?qDTCG6v{7+@>74 zgE^r3Q^AYlRu)ACS*Cc|Xnc?E55ViZy%fl3Yta<+>A6k>~5$400RK|@@y8gDP2>7E621(m2Rwd!hz>o+x$DmbOQE$ z$fjYGa=sUyT?Rb|cC1Kl{vo=q9=kS#E2HSE3>cJ)bXUCmOVaoN0()~Ry48|{Kwjr= zi6u7k(%$5bo44>IjT$yVG*KeNqrBi#aYnKEU9c8Lr=Qm7e~(E#-qF&6==yo-QtO5a z(d1N{3u>b5^BZ*+VD4qF2j^r{?IpjZM#FVFpcNp}@~5K%p;&!?S?Mr2mn)#pxVzmD zN9gBp_L0Ce9y4l*r*mcNWLlep&kH)IN6}}D{p0>bc(=wWaVeU##aRoM9$^dXved~t zX@4MY!-!D>5+7WX6^pMDa=b@n03s594$(}z2d&MppA>N~YhpASE^3kzp>a&Vs)0>Q zXJ-8sx!3H_B_ezCAlQ&~c5jr1Wk?%p?Uu;^l{Ut?O5hl)`tk3KeR{Pl3A|Cb_2s`&PR9 z3L&9ATUDjKB(y&Z7F3%dzh*1s?&r_h@LBz>w#azPOdQ5ON$Ja5bGYo)=jKqQS5xvm zp^k0c6&fBL;t*vAp9lj2pHX}y5l<3(1~LF_8yXy z!IQ74uDMD`iTvz%c~&aC%gTPClk6S{aM7ZH2>y$;55J7He}a9Mez=tnMA zBz)UQ)CIsb7!iRY-&@hM{fu~!0padRi@>CqXW3b6Rw$CD9aqu!&jd{_x^Fatdi1TK z#57(DM#)ei?twTJdwUl$yp^o2u=6$B!)bJtE4;ix2F8?#sT#5!&XvgMw4Mf`J{_en z;ZG8)xIvNy+l0J|HTk^Fml)-Ah58jSs8v5MxcD#LBUJ2J9cA=n3GB5S{~t#L{3dDL zT;PvPYs-33t|qeQ6Wl*%>4DuWtQU0%*(7QnG)I zj}YGXA!p<^+vQc5R2l77&kuu)Z^G}fZf$YFc6vsXq6u8YrQ)~^BWG=)4j1cS%P>Xi=Mpcl{Gfk({!ker|WcHfYUT^y92U?hy}ux1<)nrwHJKYhc89Q z?6dNq0pU=K7@Bg)0KMkG2Ht5VMevFA48Gu@MJX=Ggd(9w{ycEiu*-9h`Ycr*b~BrU zIzlzgkkPLGH)CSC9jhV}=wp5|&=Kd}(90TO8!Z(r&y`PdAJoA(z-{zkQ1hKZS<7pC zH7JO9ygQ=S)YSkqX}17@04Vl)I(NwM1zzO33uG0jOaur(H-m9t#Ek{*VL~z;x>&$lM*I;?G7)L%z-<%16$sa-~?PXBih^iHt<2ZM85=Uhh0jj%sg^yS|s zHAIVdd4rDC9v)=${p0QMGC<0BS_rs8PN@iCc&l8%$J$Dk9f?3`A=A734$earehLE1P!Y5f50}M>Sh$Mo7b#M`kv#ca zGA3A$4R_m*RRRUb&>y`YuO2(TI>DJvLdG$Qm?&#Gus0-TmiV<; zobCUQK2Ss$n(NXx-pcvi34f4vQAcLdRYjnAeKpc^jAw|b$AP4=$+PYzd8|)t<4#HW z365~|YTIN}h~Z=`rPip;-=(Go|D0thw~?DV<*$%KCAyO9(zWX`hj@2mL3JSK5dfXv zzC$7|+E*a-XV685Mbh4iY|pkmU}ZE01#d1)9PYGWOEdgUl|`<_%+cFMHVrf3XR?Sv z^UWw3=IGqyK?$zNOR!b$pod@J-Rg>>B)lC0!jdA>zU7I5{=8`glcjj4hikH6$EGs5!pa8jzQ>$N9AmhSvzZ5cdaZy16G0009300RI31b5F4id@``bSK{tq)nstm^6iEvONB90vZt?_kRC9 z0J5M2{dv`!g~fPbe9$NpY54LowT&HJ;r1S7l4ltqXyVn{UKHH#VrbYNF@TULR zu$fHEaXODzN=QO!Pu%xVpUzVlnL5A8vZH*jB_Rrv%;Zsh*ujpwN!Wy4=$~zMP3MwS z$`4%sM_lSa%J$BqtK(wHsQI&bYos98*k(bnMbk)i9Md7|HJvvg`%AOX)G49m`bC%I zP`^;qj8hGQ%J!S_alZVbo)Oisv(Y#1jtgvQzRazGtJZxT>eJ4b7Rb(kA`a1E;2WEJ z%~H`H3LSONRNjO6+k!HhSjd%U(>PhT|H={NDzcB}`~I4o0009300$yw*&^=Np9~ci zK2(w@Ik+h?7+>euB308U_Xbw^m=}nT%0~ zI`a_nlYr8pI4?3eT(CP7O~Q;{oe(>=_9TTFt;-zM4W6YtME9 zT)z9;T5y^&Yired`zzFeL2K%QT+0<9^qu|6 zXB?jLt!%_DR(zXtQ^n->T11TSMBHnA#mE5Et~5m)B^vH`Qee$boZwVRQ*Icr-df{em#-YVPpRWf#Ol^gzG3>yyKUgMkC1GWzo+GoZNs|2qA%_a+2Q*6tHZHxtV z4E*x^4vi2`-3ri%8d4FU;pJGbMTv=c4=_?R?dNA&^xWcl|1b=)zj398d^pz=A4RAV z0Cy|F`g@n>3;xi41!e`xcZIvq>9ggBucs$9raPL9mfL%faoOS#(1pLUyV~iFj$U(j ztqcKzB)zlP4m}AsBmHpw{EYmXqy&pW>}lsIPMkaN{f>j}te-*)&PW*8?|Fb+i!j<* zf5|AUtOEm>I5lD6$l}pl6V82vz@lH3d8Gwsll$Ix_Nww{;RJ}FGxuwq?u+|Dbx-s| zo(LvuW%X@M9&a0_#2e+)QeYtJZ$Yr3FZBFFDRJF_~W1qliimxUIDTuf!E z|43DkcTNlt69TTHkRl6s8EN1>96Q@OvolIP;`+eGg14#@y2F}A4^F^o3laa&_Qo`K zXSZNN&P!I#`8$2>+zKM#Wy>beN|SpS7uel0r)s1Fqwa3_8QfqV^T5lH>#KM1o}SqD zxq&khrR{{@tbISU`tH)M@5Gzc%EyS?#|G})o|{byl64~{L7Wh@x=?Yb=!6yDG0?ft1&qCeBH$ zW!5YVFNSsDh2h=t{W=KySDeEa$I)9c*bdxU!RQVG0vpczJyi=`b*I*Yzq4Y2Kz1)Z z7z>z==YICU-%`ceEacy{6qxJ|db}@woDc|}-t@(0<&R5zFYkY~zza%jM~Pstkf_9X zH|ERa5u9URn2cuhn{r$lIwNxTF379{1CJjk}{QihD>{=N^k&?U2Mdk+^pn`z%NmdbFpE(Bj1<|7KljaPCUJ)4ahD6A5$r zfhxQq%B7MbP+5R|Fc6_~b;F6K+D2a9i^2P>Vt9jb5V&cL_%1rD1;|QS@86|1d#X*@VKsdVh9 z(IriC??3lC_y~WE=XHeTR21usNjgWXb|Hx8uGF)FTNcG zUGZNFI2vRndM9b%-P3NXH(vl5emk}2P3wr}c+=ix(G<|a{6bQN{S}jf zdDkWn`~?VY&Yg^{-l9OjFTvebnEL=S%0}^Z%yN94?Gs)wg3gSy^lPclaQnD+0tAr7%~T1$FRe_ek;W!-A7c z>h!%k)Fq9+6M^oI)A{9uMGr(ke~_QQUAkQyHI_U;dw&=3^abia(Hqr!l@iwecu*Ko zYgu4L(T@(&d1T7CBiE-hr|@g3W#~!z+qQK_mjW#Ritzg}lo(Npond>OEw+Lh!j?Dt z#yS{^w;op1>VI&9o7QDz)tmHV+%E z&@Al5iC68qinDe|x8-wlQv@j?wZ&m>$Ks7{^j=Ax1O$;@cR8&X7!*6bBR20G)y2wu zGwR6~Xm}EilV}V)r~aR1>NA0#*(S=2P4|+QprET!pD3vL5rr{m5Hg@nS`t}U4%Lhj zZ_AUYRlCKFXl$1kF!I`d8#Q9j6zflOFxTg`?>`I%8ZO(#{RZFiUNCTJyCdV2H&m2) z@;6TV+|iBiWG^lY+)8`;i4&Kkk|iyS>5p$tn)mEI(yO;y;T>Um1W`*W zArWh#Mv@Pw?JCvi@7t^iOZldREP-J*mD)LP*kZ_hrKPw>VOnI0UMm;*RpfyXhT>2B zPRx?#xuqK&eRHTv3Y{rj*V3TI6>NQ z>>wv++8^ISab&EpU{OWSqTMJPdvaB*q^a|#vqyTE z%QtR+Y?jEuXrnen2LqC+Ik!M#h_emBteh;X1x8Tl)X>=!j1d_yHmM?pJj0M$z#{G; zj6*LSi|XaQ^Gi*otg{^}olvsFktjFUq8D=G&Hw-d004%u{9L_{5CZJ4oE}RDdK!!T z`%q82-;1MAUr@!1DC);=K8dGS{D=q;SiSv7HnKm_Q$Fy;B2x^|lko}zA2j@xr-S)oudSNzo@(z-1_D~kF&lM`+X+Un|cQ#qaiPrk! z5^8$Nuw-=?_A)hDRaGwMwzW}%G+5E0U*m0P?7RwT6sN2e*GBfwji(65ksR&Uf3mbO zKw7IFX^eI5H5ds9H5Kn&NN5NRCDNG!jo-x`v_Bh&LuL5GZ}UY1rY!HmCrBv&VXR$PnJDR=TQbJWmJZHy9` zYiVsSLPi26GE&e>u~&m$^43FM04dD-bTx;UZq&qM+pgUzp7*Dfu5|?}jRe{)2}_kK zED4#`LpN?&@N@$?N#1iyl$f|Q+{aty41tI-0Te zS*-q?qJ8Y&esFG>#(mfDibyrE8BtRE0olnFr?ld1dg(!;OrRl)jvJlHk-32b!)@e) z83R|S!5u0F)wTY!eK&-SLJmO5m%w*QFlDT^>N$NrO5d7XT5k53tEyH%^digC zsBuLmbbaeLL^@rfV#YX1magNu>tu0x2Xk92QHT@FCe1HxD9|*X8BOc@AJ~>-pvTk| zh0~Y|L{eS#zZ+E6iniC%Fz%$UoMq(;1KArdS5@hxRoxPm@s7EIrrl874=vc>8VgM1 zY*Y;zpwFuS@`R6Fh3BX3qjL=p)J%Sn#0~+1`_`MSjS{iMO%AU_@J}kGQ+3tUegHws zoS$qgvq>dB>Q>0y-P%m;VEheSprxy%Cid3`ZB(X_H}}JMn|oPMF!0+tx3=Ay<%Ech zmiRqXOYjf0T`~C+$r_Cg48zbN!%2KH_?`z43yEq~ejzMu(2S@yubhGv9;Z*hpFT65{(IlHCTJ`Od~>-|A3Flw9DAC;Z5UDjz}<@xC%{=;E?{GS z)}yrl{cIOoxb8s&L{9?;qBb40bqWIhzSq*3;A6#K>9a7-47bG+w|qiuRCAX_YR+Vc zFr@TDEc2_jTIw|QFX)XVs+sTL#Zy-@Y?Ts`syIdTm43j#s#I=3 z3B{UADR9kPDqanuQP@u96bDX@Z8Q`v&v0iyYb15g8JU2BOAGS*cggoV?xtPvUVW({ z0Cqr$zf(J3VKXePnTQ=Gy#q6z3Z5}z`eoVSm|s;H)!1_RY$>r>yI?U8%g1*R&6lR1 zqpf`1;J1D2d#StpW1bcEg97jt_(vSWl?N-&82fSi>O35MC&nA%l@Hf(Mgr!YL-I!2 z3Sm}Lj*;ms5OJ`!w@}2%xpqyTs4>U16uGyzqtEph|0gpPiyO*gG4$qfYa=y#v_knJ z{VRwM+>VMge|Ezhzd2}M8t3zL(RJIk?Pw(gq)M zYWGEI>}aCUs!^Una=vj9Ms)TJZlnjK2VpDm)EwmKf4ah%z4Gb2F~lu3TJakFEpAKv z;z+bQ%}tLo(19NC#pbg?YN#!*0XlOw|zr~@bIhkeBr=~n)Q2CS7&B*BoQqLqzrOYjXs+jUD^vbqME(29WXeTH`E9E z#4o2pcL96>@5fcZYy!J{Iw7r$_89ENeC5^pfm)VO819#| z-mCLrm=;91j5drp{w!o-*J3XLCD!b4oXp0X;x88y-a?3r#Y>v_luGcEjGfv)qi#c> zRQxt|D;JGWf`NufpN)#=xC6?bCV?D(3~gcPuuJg-m&f|%ln{L^8>D9%fl|o5O71sR zY^o@kH*+*!WXl*}zm_TAa%AQ1nrv6uO&5K|QJtm;(u&GtbMldSrZqakVr|m@)dGoXqLLe~s)c`*^oiXES^&;183o?AuPM`Io zyw9pJGHnHl$yxdqzmC*1?amDdqNoHm;ByX!%O*m?zW3n9;_n5vd7`-7jGCU<*&P?C zOL{vmz*WOkdU~0Hk-h0%nvw?rTpiHBAsfU%6*@F91jCaP2;X#+`%I@*b`gpI00RI3 z0{{k=Sq^>ZEmu_}l~*heetx|!527acdKaeGlbj4rABZ7E+tx9Vr-Tu#Z=uxuS6do0 zM-rkyMOFF}zIF5IZC^|cazqgicJi0sXgr~Voq3KUt5a8eso|gl{~Muba%v=n`TJ3N z%;+%*%1_@lD+hs7v!os;?JL){<$eJYS#S^zI&9Cg3N}xuheO3b0ezmxcw~xE(^)uF zgF1uw<(>fW&E(%b=x0}2wZQmoVh_%>yJ;vsnrN}$IJ);e&k;faAd43WfmNO9kK13HDLLP!;!TbuG|Dud{^QW5D7oWg zhLbAWV$go!K=d^xf5Y`CC|4UXkN1+f+k&Iqe*MleivDLo*t;hncygeA!sEcYHPand zeuPg{oQPwt#oiy%H7G@1>e+k8ib=s0`d8JHH`l@5)!yyuq0(31&+-&Svic=}KFOG# zVP)8x9KEe6{E^qt+S|cLQSYC1OZm`$1xQBOHg*}@&EBudmWih{g?8?7I|x8R_Bk4W za*^(SPW2JE`FO^5Cj21(a&pz*k-ho~b75?KTL|%oaC=FzR>V_ft*~MnKI8oNJW8z{ ze|%AatXV%&1cb_2>$m3nJ8GbEP)=zB1jd2U-EmijiUsuCIPEW-*CFs3ed8nS$PZRq zFK=BB@dQ$#Pk(iOO)vGn)#r@kmj;|sL=o+HCTC9$Pe(2-cD?R{HXQde6BM9<_uHRH zZEQxQW;thza~F|$_m4%yv+Cp0=a$Z>$Q-0ehZ@!#%?R!=Srs3GH6GJUC$V+My$8pw7QTgf3HLx#%lpbUkUc0b4{=wRbE#nyJ=Dq`>-5Gcv|SD2R{pdP*pSWfv*n*Z#kmB##(Xz^bN-ztcvj z<>~tD=`G_Lf#UwUb}`_qbV?n6g5J|h;zYMfhmMI%?JZfOvF}&(6=424v^udcvK$Xu z!y7*R06uY}F(qy?mO35Y9?6YB8GsfRvw)%gL`NxBtkLa3C?(=)%0Q4&e_W~Ne=ZF$-LMi8R!wE86Z2rg3{7ip7EQ0}Z zK2s&LMw9TO;mp|w2HDx?JjW1ZM~2L{t6nNU_`5a&W|mKJBa{fv(YFNU(RQollFbTB zqz3Xhzc`K;$gfJ9Qmz048CH?FJ~`aX+TC5ka;K&p_X^ogV`W_3m09edFYukNq+=~VWIlcmP;*wF8a{1j<(je2nr zyppQhHCHEnH6+zUfSH%ZWMBUa^&1qfQUJ0b1%37UX-wI8$ASdrx@W}5}Xpa9y|{mfy$%uE4mmkMN!Ow0iHd{D;Pzv#7K0u2`(zgcEyM09D6o!qntguF43*-c z&dQ7R=DR`mj*4Ac@TazNpTvv7k=2}Qj?+!cg@En$cqaO9!snYX)b0ka-Z+X~=N zVU|Xaq?*tgV+>0PD+NAYpHFs$(qn=K$+V~7Z;J){HfU&91LsKM!3<1fq{k4J{i7U$ z%yqT~U<>F7G4Q_Fp+&u;<&Z0X&V2=Y>3*sy8*;-tc7g4C->8U)yz``>^SpfYnqkwh zr5Jf9@vDsMZ2tkdz;cjYdQrT`6(APBCDYo&>_2n5ZZ(^?Utl)N?=XiSLC6mQKIeqq z=TTwKxM4YT0DtY2Vcik^|9AkOq(ee)=WS11gZ~eKtlQN-GStoNgWEo!Sh*cTPW;u( zG4T{19+rpb^hBFurvpuNlTe-n)Qq#RohYg(2dL=iA+(S67fCEAfqn0J450%xs+JjVo$WcebKYzAoD3`ndpUB_YC7{kTb3p@k&Jkn2RO|7NMR&|dC;d!W zcfMu;)MmY*^SUH&$Av*9Fg;;9ccTOhWXK&5_tPaHs47b<(6Rzve6dnAmi00093 z28<320@sWH00RI39CzFHxafwjp0IWZ$AWptz+@>d9WS`NDsUAOpn5E&AA{BHO(a}|Xgqe|ZL zlbgf?ZXorewUgOZaK4rzxTB3=JTxT2QIEw25-P*$|G#C&qZLgVk%@z{lPt&BkwrOz zAFN@~ z62FS0_2wbd-C^V-`lJ%=H<{R46G{8HX_OQMgKgv1DB{rGPV@=OFp^CHka3P>IQv3F z`E&)8or&|%9r{TqLGz^wkh5OPN=2)^8%%M%^JHu#aQp2X%n>uK77tur1!o5l6J)qJJ5d^IWkD83$i_0C8E|ig&tI@iJ#FGhDhp%to zn$G!tLgFg+m!eUUh8427x1=8ElkdLV>7M|(h-LcxL7`;yDbt4|$rKxZ{qE`IdQu6s zgg!s<{lEG$bM=K-%0OHqAI^ye79O)$dI0h;GG>l8!u?vl zm@FD-SYO=r87YIq9V<^P9O`-RB@w?S1jJ7VMu#DFDv%pBQK|1aN)o}+Pu_u{04l4K zBXpwqyHANKNU7NxbC5r;!+PU2`kv9Jg`3#}s){vI@4pOoSP}pcVtee%1V`k#1}SMt6&eEazJ5ykc^o05BXJjmtjSm(;X-0Fhvq?{*8di}zsOUwW!M z&{uuacm0cko=8C<)MPoo_vz9QDNbU+)N;^`XjZTRE@|izbYSkA2rMvsWM8)`0$*)8 z6x}}m9`wRv{DiingmJVoK_@A7o(h8wIc#u!1t;&n=gxX6iE7WnZP>d}EY&||Lji^A zEYS&budyL}))*=lG(z0qNEhCyUQj#eW3xEMU(0rU#RCIKYb8|5DkAO2k%7xiyYv!C z>Y+Z#_*n1YX)t=kex8{%T6XkE-&70={JCLzX_%}_y`?LjG5LK0kd(mL>3cbL4rC#= z+W^j{f1+C9o0S^r}QSQ3aVeoaZ>*S z$&J!EU9F)3=vi6r_I<0bU=KC(6 ztXTBWysLzduoBdZtIP>eSaLI25uS%*$i?&SN zM2C=2lp`fy5N1=Vyo8T2!LoYlWn_uIv!(kNbUm9O$Pw+2&xvsm-8%sB1FTEjiWnt$ zBKNT1-i4=clc={(^Ct_SoG|(0?lR}wO>HyTZk;S9R)8D0#JUhpNFNDvOIyV>tA|hA zAT9}B3EKQX=R%f7C;&LW!LsZ~@$0@wfs!QLbBK7uK}(PXc^J!?Xnt=BL(j)-3?|2g zmd~*uPf-v#ln!wT+IkC`awBhm=lKA@1b^tdDRQTC;Jxc|^>_I`YLHgIsJ;pSn$Kf1 zc=byCmilg9VC-~aYe6SUlk!t-@aU9mI!}92RE{H==HiP|^VA|$ewbG=?T*oqO4fGD zSBc9pD|oour*xADSg_so~$NB|>d_0z0MUE6uyXiZSzM|@JedvZM; zSN{O2ksy$ZSF$yad&U`;SX1os#gYKbveKRCh_2ZP9yNS=#ohsywTibH~T zjQWXh9^XPog*QV;jn8e}qLO2CEgY0PE{TkOib9%5K~SX$F|Fo)*`Pc!ekYLx*8!cb z{CuMzz7g)}o{6vjjCP(b zWY^nSc!(5q8nywXXl^ik=0R!cu@d{=RIUV5Z>%I_fB*mk000O7S0tJA{x{8m#rVyO zRD=LD6TWffV7#>34G#AgSk+wje|C{-*Ss=XCfV@#K(`j75y02vmsx#j}aC zvDyRP^bERM1qF^%SQJMH75O*q0?oU$x6#l}14FnVyBIW_)PKJFa>^K6wFFr}jSbrT z#xB7ayUAXV(}sg2fe8!`L26LWY@f9rk`kZ=ds0-AtLgIG4>y)|8fF85Jo5!bv1 z*9YLlV6>xlBunlEN7Ll(U%%uqLEiE(EOF3ZbC6Td1cwrg2S2Axx$XX3V!J{6<33*v ze^Enfb)nq!=cs?DA6qh6NdMDbK_;XTou{)j1mkFfcHWQ*)~p9yDDweF=;O&Xx(?lL z@I&DMgr@Q&H+|=@aT@BFMMcn?DaupMaX>Xt4wE4+ye|sTry zffKT$~>_fC42; zyJb?V3tC7U%Y@EmZ@}L#+u;bRWX$a5Zb&GOXq@dYIC$(Dq10$*Y_ib^^LP{5c@71< zC`Bt*)z+=BD@%lG!6qKydcvV^#2im`Vc&;7`EAP?#g|$Ry>RVaE8{t7RhIn_=@~xDk?q$)c&!!xtFs5-TJu2vbkd$Wy zUZee!Ve?gQX#mV~idE^r9zr^9Wg~g6`o-F&aV?#Y67b-jhVlSsB1SVeqddb3Q=1Dy z=3$=qPs6=Listu?@N+v7h5`wFiUC+)`=D-4V}o+G^j}PlM0#8q>E2vX=Q>Hc#Hes- zveM)iJ@j|=T5@Pwg)gB-k_tyxytuh~mo;1u& z8JsJb*w{L57*j4!!yR)pbM+cxSZw1yU+DO*2_+WZ?k@rMfLh(x;`LK}T&3{MW(~Fd zL5&HMMY`AfwrVCn&Me)ul1$XgDBgkh3V2(;Zd58XT4YAO$pkWrKGU&o>6on z+xXwK<6|kM9QVo=A%yVDDSb@B3xbm6ijKWJaRS2+)VvwltWf@)0kj0`G^q3=yvm_+`9x> zQ-{O65f24ZtBtiSF6oN$w;TnNEINyHV?LV?TDc7ux1byFrrEg=kNk7>%kCF4gAElQ zFAZkGOgYdcoV-Ymi8iEp?4F371d0w;!6%pMAl&R{VdXr~Co5CIX6OJvjnQx-{bEBw zDJ4EB6&*|C9h0uzivM9QLN{>1fr-%cb);sU?{q@M)q4qs#KSOaK?>YJaIkmEf=_vP zkdToQ=96?#MNI`2nQhwP)#lKUw~vOp1ApS(VacGZjVE~WtBXL#MJQPG_!}%&z0rJ8 zOtE(URl22#eLqNpr3){6N>U5$e#R50h75~3e`^a2i(aWr3FO%ee2e7X)w$m#BTGvv z5v)ClGZg7n*##I-tR_?R!XJGE8Z;0bo`3)VG@I}X*)VsYdN!R9by*5m-9Z2|FnpUO zqW6c=xJRAkz(r;s+aE0cxe&YM>+BoW)G;ZbC|e2b844bURO5NEKwuZ)^Q*#X8KDNh@CWB^Dr$JqF6@?b#G^?S~(CQnKKj6a%eecnVV z7@cz(7N7JvXWsc73$pq6jFDQ-&tdx&NGtyBC25@*vO&Ztzr3gmAO+J;emWsQhLt{% zLvyH78t-+SfL`F^LUC>%r~cW@oF@`Y7C^&ZU{&n195q|Cb8N5Te0-rS7)8!(S9+aoj80Ev;7kV{5SV|KGsiF*fC8?Ag}~iaR!u{MWDpw;W)G3GhtvGF-Y14 zP{*ApIWh>DB|w~D30fE4O-;GPO86kV(z&^oD{FPnuV1gZVM5_iE93n^A~&E;oTWs# z-s7+z>8u_o)Iig0KM20hGvBAwp|Pi7m!YdnJDRAL$M40G7_R zmjE=i04XStv>FH0?K6m6Iu~~UJ+@w_i$~#HBr78L8gah<(xPOTN8M&%H>+hR#}d!O ziurpUd5{bqY8-vM->8w**>#I*dn0A`fA=eRzeA^{oYf{yoc+y<+6c-EzU+GHtz z{DJxbW|1*UqR2{-9^=JndR$Q%{b@~xPEYc07}Sp@h5MG!O4-?lSp@Z<000dvN!A=rh-|Y{fOHMp*}FVj$EkAk z`>$kilvQTC_TKuB0bpkmU@b+N#7dh+>WrWw(hDrjGC#U6up{n=2LfGXsK2;^6`O|o zo{l-z+p#mAxskqVUasCP(e=O@|57jh>%Ej|;+RTOWZ0cux%3#_R}})% zUWT}+@C*LglnCygk1HUzH-lc1tUDu$e$_|?XcGn!16%|_;|P*ZCh z?0`sWF!`#n*7N-_mEqs(K0}Y0AklGYKATzRyQ*C!+r)Q_ioxyJhEiPBYCtBY1?pPW z)n$xvje0SJ*{#Ipua0z~O@SY_#g?P!u^yL$9G`k0VH_^dtSd|aipNYB&+&@a@Me5` zkzYt?P|uX|<~OD!l9U7ZArt+%1yn0Yt}&D7uVGAjT)@q{k2puVOH`6*E8eR~gzOzI|mW0ilw1I)(D zwZ4HF@cbY%XHWo}E*4DOpoEdc7J+x)7*Y?@Vwp`#SO%*UC|vS%;3&GdNB^FMfgYhv zMx9H4lJ0)khwJ5Bgf!X(4;b*@uYLet73{GyA_yC=v;#x5!E(TTuMoizuT-x-7Q6)L zD|nCeNd|2Ix4Oy%x@|H$Y=izbu;Slb_brC*uEuLgV3VZ6x#aR?U0yF7=k+bU(7gTq z;7>ukw%xtGNP}J|0009300RI30{{SoP{?f+UIO_A`jI(MbLy4e(r)(h^A`9XfRxXu zR6&%5mYbF!+K|k5;KJ9o8#%K%H?dGMpm6S^(b(v6h+~a?C=q8_w7xjDVxJX!)$sm@!6BRa9QW&C;f#dD9bF@G{6163~l82{B~Hu}>1ZQj^Kz*JZV zIqE-!u73vgVv0*@@cE3q`Je=tSV2r&#Fg+>AuC=-XG=*!OH*yIw1M$Q0q_UJtgjzkD+WmwX!SEOufBg zyr61&Cz+VOyV#9Kz^g&Ztc_yt-<|jsu~y!!$&m(kMP+{|J)+RjuQ%1Ick!Truyui|;Z)5+w!VP!jY(sY$x_^l94Lc6!5)JRJ) zJ@|e0)YHkcxb1th-jE>Dr{3PGOH!UrQ>S|!P z%d`l1>3VTJ+_9gIW&<+!$UH&F4@#_uqYJT22L+!N4Vqrkz(<%d?SYoFz8EjIj@L@D zP=~?PLFe`>8ZCotF5>uC-mCNG`ju~YldRYryPwdj<%y$-K#gI8QfQ@yFd3Cxi%s}@ z?6SxAwI!ipgk%8s(qlq4W)Gl-*yfee-V6t#Zoi%bp5=PB$6H!&OTBDA?BEFHmKdM3 zks}ZY%fQovxcuJ2qsd+#0K{uW9g*xMzeURj89}IfLWbb~U+q`=w}CFeO`+3-FqE;5 zy~o3DYQo0@s4_S5n!uHCiL&y5{4iqbLw8g8C4Q(E9-nny;V*b4v_31DNKJ=0?txP+ z^pd*XGwDPw7YnspUscN?vl|5ZPc=u|+u)h`i3BquJEfA@z^3hc*d~Dwky@!u7?78R zPyj=8`R+Y`2>D=6`gdDFd8ZOHxFA@uENK5O95>toN0)7iOVcbs5hf>!cO@XmubH2T zQ)ObgmVowQSkAtbcMzlxso2I7;+)*k7m*?^#6@Q)o$~2QHSoAWzGQo#m8g9_AJ@&k zX4z*NW4LXt)G>oT2+AZ{hU;JF(h|W@inSW1XJE;)T^R}xvthdlx)9=p8fqluR_K=` zRs9z0w6J@%S?G~5#ZeRJF}fOIT*Ud361$$Dis885WH`F>IHc(_!Lc%S|IfF~A4XdY z>vme#uZZvqAZuCYmmFYvZpPkd9!Ly<*pAv)Zb+jaY+n`dW9IIu7w2FdvtYIM)*MnY zKh3QWXxiB)Cu6?Wpcbk9#1h`9A8QIUCEu`Gk}!EI>q^}G9|o=T_*RbKT3|)^Ws8I4 zFbH_wl-h&ih(GR9?K)hTDKL5*l%;9X2-Wgzk(6QHd5_# zSZd}|pvgzW{AXXWJQzyZ9O`Le;z40a$0{r&X_D-K@{ShA9L8y(ry;V< zP$DQ299fH#?}V(uW*Sn;(FRec;94a@jC9y zJQUrQ?ybfoqsXFQI6YO8dHrZD-^Oz!IodSW&G)E&1Ml7McsE!jVO)msgL20vZv9^{72P1i`9xh0MyXz7&*niglS# z2y~jdj*@4byqO^WSwL+-3&899CEWZS1k^5PD*6?B51O0{UFJ|}$(!Jxjy!CU7t`Sx z+Z(GtJ96Hhroi@IO@bh-mb+j*9$Y;OLbo}goPfNAVD*CRG+qa65C8xO#H*Plig@b= zKkuxkGL!y3pa8Ni22}sCuS4%FMt`jd)n+C(gbN}m<(mvEPsPl$E{541V}H6%>zRNb zE$r8y1k`R|5LQpcyed(u84oPtub2mJcdQE+HvZ$~ebZ_!?0@T0MtDk%{`d|P60{~~Uj6CV)pk7WC|0T2Dtxo5rZ#Tl- zuRoOlGgrIWhzt4Oc&VmeqTEkuR6r7%4Zq{W?QAR7anC4jE`W`l(O22nWq!@JDnEr@ z2Bkr(un0oqVzUj#-6Zj5W7ul-AI~H{Y4`|;dVH(?w@8LH9cSMl-&B5j{Q)^ z?9DY{4Ns~In)d*X2Brj4Y6)Mtwet_DLOcp0M&;7ca-zH;5EyuM=4vOEDB80VofZ1@ zT|GZE6x&I42AK)$a81GyR@LC{hYy00otQ#m>jA+wcon=h=-41!jpyO}*fB;`@$_e?7VP>YnK`Cr zdwZHPcH*!D{8x~l~xw}U@i^>di`@KyOZrYnXhNdANjru4mZIdCAc zA}Xo|*MUZRq3gp?ho~}Pm!rB35={Z(?%DfyHmwH) zmRGf;#L7!I<@Z0`P{KF5w{ziJ_rwB^D3v%*%d92^PA%hpwL9v=zX9|1lpDU#`(LEs zh!pL~GU{|N4+QZ8qq68x@MB;{pmCbKfd+3WNm?F70HqmTIzV7xQrbEHT~|!P)?UR_ zhOPNCP1X3SSwwHv_ zt%V}GE5M%>mlPmYGtv5nQZ@3pl^(-4cqvSAImwj(^)$zo&m(Y~;wl2on_x4+#d+qt z78Ix`j6k^V)(6a)tE7CR?_6rYF{kdwH!CZU>}Of6D5FL;RVx5~qw8WPuypMs$Urjd zR|m=@OPiNJ#8qGISUnr)llIu$C$v&Ttdb54j^tFhvGO+ zd#=BF^^?P_9C)w?@G?C~Lf;TQ1oifDzs+;4{SzHTHj-_%QryYvC2rUJz)MyT;%0PPv5@XdpK5n1QWR+Bo`~eeW)_G>H$H!|0 zwW+7Y^GITi)^9$w=0nK4WO8QHFm|iMOk>V~W4x4CU36OP;tCbETmcESPI%wHWBZTC zT1U;5B(#F#UUIRBi)KzwjF|UhRk%mBHfiE8=7^)edm4>kjhNd1!)GW!pc8+b52AjO zuln{_u(Y3bfS>^|0#d`jne|fuU8Kzj^)Cp$RHoH{K)bJHNcv_=h70A)T<_2N+7nou z%Y6b@KV=>8Ub)ZU^%N!9ev<{GA19q6Is-{plVMcLo^Zm$pQcusVcM*4oHNlaBH4PLbX{7Z_H-O=4E8sMB8NCpCNx3o^^HI(R%rUvIwUQvUfnPM;! z*Kp3mV+|iZ9{pja%Ha^_c!j)WAIyaYSFT}t(jY?_iy!t>D^bZ<+)2!f@?)D6nFaxn zNWz_uAW%GoSydxZsA6ClrDz!2XRGN}A>$so&5fnN{ug|yfUE5y4mMYy+Id(_@rL~! zWa`Tk)&&WrZx2}^f*dOOflVWAm4sIiWy%Xi4Y?*5so{z#BA#e&8rGF zrMduojbgwsZJsM{sR9JGQ+CFcWog7+yH{#_HrsN%F}Wg5Mt?- z70Ch9TY`O|Bm);=Y{zZHbM$9)T|V1GNEO;_fV|0r)j;1zaQP;%MXe2lgOplgS&RFV zpjoAdO5}mLOM>3B-VgDP*Eo^OY{lu)66nH}^BGSR@HaEjvxoi*z`MIM(td@=_;3#Z zEESKdTNlxtR8eu42e&>E6bxbxtJ-`h7|K>Is5UbE@QN)i^YYjYLBlfgNUAu1t$jwr z`J0tcD+w?%7S{+$MjoW33NA1QogEbm zJ70WY=EQi$JPa3Ik`kvXbHh6RY0NZMdS0@&ZH7rpaiAWq5YLE2xPj<>#MXfhY6(_i zgT}g*ZVuXtsKpO&Goj7oeuVI)#ARw^Sk;8E(tWI~9n@HF^yTK_t1d!gw*+&b3L3>ht z(Mu=*00RI33HWdReBFY=I02UtG2WZAGus%58t?~W3IcMo>uoG-q8BoP_uJ*MPT2gp z^bc>o9AuW^8w?iV4F{vRb8J?2r7O8~c4rz0P}i7Y9Ac zn7vTU@XcQbhE0EU>sbn_;?tNAd6qSId0SP-1~y9|0027urI&J>neYGr0|QpFEJ=?P z=XO`MK^FEFHb@RetKsh;&Tn+saV(63D@AAX2zU4|>&Hc$LKp78$L0Hz^Ofd;b(F8= zycj%kz+iob=l{D?6aRJcWpF&K^@u;_n%bPILMPvyK-lg< zXv^3Wl03Lan^Q+Bl%5NIFKmQOgULm_s+851T$%(OvkIj}iucbgcAg{ft*!#_SP<&l zh?;!7`G;KAXAn1-Jmj(^jDS(=jPEBlLU`6Wve)WE9>}k8#J@%GYMm2OFV^}Tz997{ zjH_A5f2MJXhE(>GW6S0zO28%ID}P40O3eiYv`eip#^>ECQ=&=(58?(h6KALP8k`cu zz7#0`q}Y0@Qv=5^n<76Kc{-5sdH@X%huR;(kOB%B7GGK>8{Q3tVH%`R43+NCx^%B` zAVAcUzn@GCQuC8vRvx3-;6lXH-S|SP7zvKaxKrtUdu-0ykQKuT5rPy;)+UG6w}T!3 zoxi>))PUhc=p}JLRDzzc*!+@}!}h21W-D-}XBt&0jjlZ=?Mn{7%?PcLf_NzVR)(k6 z`s-vx(akce&hbDH)@qp*P%@tCt#~lNsb`3p(=4EJh;o;X?fEam&^-8C#)$~74%HyB zcK=RHLJ@d+A#7<1d?yRe%f$LypF4@<5&ELDc>#m0mo*ZXlVd|+Gj&uV&^4b(c=w^q z%|_9!rYgNI@Pa*%ZWLlZ$I_a0IT9p_1!j0%l-nZn>)PPJSK%^g(Y*T3?e3u&TJ+?m z!(dt`2nUTs?x2?D_=s+9f|Qz8Gv>}n8?v|O4J_-ZZU3eqC**(1CF|asTMV6SPAfr! zLJR62Rg`w1pku7cqf1QxstMax-V2wyf8^gT@EuVt_3>Ik@$p58wLx7yDL120(IIuW zv0qy(U__!T%I9@svv+%EgX72^WUdfqXTb6fX3TK-?U`y@SS%jDD9t$_(tZQQN)~;R zVmF)ETz}VjzDXoclI0s6c9uDa`=T%1fb^|8%K7;Dsbdfuf4{ zq3Rv`JCK8SF#4qu@$$2w+*KR@#1!2&s|{?-558O&m1%l$;;$7#PrRtCIz zrtU}GB1hyEAjk4W5}X=%dBWE~STS3uQx-LnFr>-<0Usa3YOgK9N_Ye)%h~|5&sZrw;N<;jHr>nS4uj! zsM^Oi?po~EvYNg=wm&58PGOb4G|Gsp;^|xd4r;y8$;u}q?zi~k46%nZUp=FNJUjO49yQ0s@JAVD@!JQ{GH32!D!JY!1Gz*AEE9=a!Sb)L zQe-XV`>Yc*JJy#HGTKE>#wqZ-bS z&jwNFW&teMQAa|TOx4<{l`tu9lO1JIhagX*kh;;V#VWxM9Sr3Tn&^I)2*o+bcnCE# zI7Al+Ynx(cdSH-2mtFp=h0rO000093UaI7+UAYs3rBORdcYbO@uE@)9$a&2-wzc$g zC+rNx=Pi&}5xhE(5i1`5@kUwk8qIwxJ#JGHWrkl;GSaYwL~&mR(Tft46t$9y&B$51z?G+-_L+x z()pkfwIn4~U*+%Zfuq$RX~JJ#7tGwcD(5itFDP^87^1b&6w57lZ zgrI1B<3kcWLaEmSGt2kbrAo=A0LW9;>J0BkTp(CSM@t3ZnEMqy@9yqz?waJX%jf1W z$b`Qpi1Un`9kn@UVxBoJU{1x_=g|ua--Fu?wbQ-Ugi)m^ngKzr?oJv(Kb*SLURQ+*@ix--8-ZjoZ{EB=%9os-V zIF0WNQEp7`Q26hKbgM&bM(701zE%jg6NtsNirK^kYsv_1*7y4&%TnI~xTYwg=%yA! znJJPkmQ5OAkRZLWDSxc~wzz7Q-bfZAT(X1f{c9g1ph@aG;?pt7HB6V-tFsDO(o_F7 z-H4IB33v_z34OtQ!t-mimY9!9RI{lkOCGhj3OpgvFq27N(W%s1V&dJbnd_ajUGCZW zDOU08O5icE{*{RarKSN7DHp-H+UWr$kE};N5WbDmX@HaM9tZ=(=um0$%h)aC4zC^j zJY~F}6eTdO+xH*J2NJ8C88;LU9Ht0AD@6LsbU#O5{AeI&X7gr07GN(ys8>oxM9y4# zE3kn+jqqSF1nQFbZni=+JEHU22D}4ZE<06a@w;cK$1}<#y%{QTMqkkWdmr&Jb*4qV zRT3pdnMr{&?3-F#(IYYu_23hSjEcx@7-6!1#p3svO^a2U-7yRctsn&-p^Qc`IG}6# zTbmZm8}2Vr^Ay|~i?ASS{H)Ju98d~i3?J?BOKV3}$i`oNc-%u>L6!XqKR8X#=eQg8WG-}G@({-Cy_;uTPaXs*^$paU#phEP=*Co5uJGsEN4N!j_2$+TaHA*0=j*(vKywoxR zj;>CzQi+OXn{9e*1DZ#{BLA?FGd7z5dJNYACrBiTl4PK+6s7kt3#e?Pap%OYGLAb_ zT>QVMQZbuC!!EKWGVf5o>-idtQCha2N~MBxs49*Ic07>lE0FO%RDSF zg1Gre%IBV$DD2cdg3x9{7HaDp`S8?(p|&vJH{t$W7vp5+k{+}-ylXHyHF4Le-} zfxI!Xze!plBEAT;Qo5tU7cW2wa$C&Hl%h!KXNzHI?Vi2J7#LY_mvE6|TRyY8KF334bsx7dMU+4>mfZksqN ztI;I>{;RM_OhxbBYi;~yNJ8S*IhFh_C*3@yuaAR4iEC)r{dZe&F6}*b)Zhx(iwoXO zO|p7m_7e`jbtD9>3%7^dNBE`9Mm*}N@_gi(IYWG3#Ycl0u20lCH^TOSjw^O6cp`m( zzYfY^x_QpNWPAA_ev*lX1oEQAYmlf2@QhRax;@lxUFqIjEhYq1@#Bi~=Pv+yUo^17 z7t24=o?}8cq&;@yMYTRHemQ+eZ%I6SMUmVIZ3sd+Ch;g*m{>-o|2WsuWg}~t@`*_8 z2Hf)8pSX;~Y>;C9F#wcv?%HerZm7d~Hfq@QS8`^FNE4JmlI6-0E zjasyAcUX!Xak*Q0_Fr*Xkn`mQAVdlePcS!`p5KS+&bzs;k5>Uh+-YaxpNnpq#iPU( z@0%iy8}&XuHCZzv|~L2W;J{bB1>IuOT0(`54u zA$SDwxAF}Ct9fz3H3QahSOy%fu#jcFz;RjEdNY&N)2&%ddF4_L7tMjtJ z-tBhoTMskv;lW6>in$)c3MC^+);mp3=!koBDh%&yrpn2~qm?-tL%~us4a4W9#l$Lh zY$xA|mk?|z=d6VH;|Fj6O+Ln)C;DLfyjOH<kK7{%L7b9ogkI-ML|fdd__`$lAyDv-Xf0HD;EA74$+Q`z-a^jB+D7CB+ViS*? zO_e)9=!G!UdpEi>Y>C%vh#p^&TpZl|LaXwJggPxFwgUTsJV*E2KVX+72TgOUa-z63 zyOn4kVmnQZ{nUUcDTKaape0(u^Mvuwz%m3S~?+!?b;M{{nS$I9ZsI@Mo0|gt?S+`$3^XR^5J+?JR$0k#JIix z+;4{!CK>)+VsRLjQ!*AM?;~HrN=)s_e(F6aIF)$BW~wWshSY;mE&O_4P(b6e$la$# zV8zr#I>@dkC=;asb!pBC#r7g`F#KN;W{a^u>w=$1d~V;}!Aur3=|Y<1?_$;fx@^ay zT-tHdE>MK*XmEiF?Apn};c+C0iC)Uth)DNPe+{9@!YINTv~5iM$c8{^?yOai&_a0g zt?rk#A_XA}J`H1$aN99rE-`@0I&VDTlI&1AtE9fr0cRP(L!PRf5D|BQIQ5K+M45A} zs8ZG(xbp^DHe6VeqMQZ~sqnam*t;r~+U3uqpBMnIzHo?WZkI{0Ya&4i8vWWohX)^6ub#VsYEnP%^x@tI| zZg3{&v%mlV0{{R6046FKoMXnrP4t zY}zv>4Rj=uDY?3c*m*Rz3?@g;^@PWJ+3NR%oVrl0w*CNHean2^S-6OKr3G)^-Z<_| zkt&u%=Dq6}4!f;G@A@?xFH!IWA9iP-<7y=}LE+x!YmY_wcEO82_MnK>R8R{IH&?~R zX;8vQ3KRs%jq3_igZH4q0F48MAeQlfPkYSZu@Ibhsr>UDv&@99jlc;|eZ4W&)eeoO zJlgMlMmMcNpYfXFn%_FS?Nw+!eco*ZI`#2)-JYPh}Ipqw~P)?SoHK3eQm%15WL@4d;ws^EU*emeWM57fhF{!WVbFvg)H=dwt2 z>E$-M8pPT|JY*dVCLMVjMhubRc9Rjz!g$_%^Hg552_q&4a8DrvR{2{iQnvDsoBop^<3w_^$7jFaW@p z<4^)w%X_YHaqw16dG;@m5j}udzp&ZxpD_ySOBLnk_L$@oFHeWA5SciF1Yb~Geh|df zCmzdKV>(G$X>@r;`zqeYoQg$Snn)cKf`7g86guswz+qUUk}t$GnhAR?yozaZ40R@h zYk81$dw$uz%c-p;Idjx7s3-bQM|ySdMnA8g4?V!b!JrOn6Xo-@^6q!PGBJEHlMQ}OGhH~j3DkT{d_nXW1q)(ndpfM?$40h{<7cz_h zh4SdHHX2catA;1 zVnJBi#?HHNp1s(Xm*&zx4mYXCjF@XT*V|00;P4Bg$UMVg)nTU{U>kvAqO4jAMWMZk zJcn;b>*^)ou7Vg%lEVX~&J+*c?|~xdRHgKx6<;%p9u9~RN}-=irOJ^#!yB`eTyR1H zx#Pr?4-f${*vg-EfCcUVRT*i$(7)H~EdpMtj0~@Ic>JI^U7j|R!_mDx@}+9-__@9I ztwT7o?oM*cGKiwet*%o*FIfTo(8sA2w45p`;uxYYYcFCkca z+f^5tXGY{eQ#ApLgUj#GPanv%hdamv0vjU(6u(tcp{&_FNMxZ?&N!^mEFCSec zNZBhn@Q#ecc?SvbRnCbNffy|S00RJz#h2in>EG|-g3p=6UFCXOOX~VAGGcZ-YU4NJ z2MhaBQ~S?yiO?~-=rit^Wgm-G}2x&DA#hkhole~Vl0@P;i1^3ttUus z$ZlP;_Fy%&)C!b*FLX_}q@13Pj9)^qOv2h-x~{5bia}p&=m3tT=^g_Ul*?ExV9FS;wb8WKz#v#u0<$;dlsFy3|`)?MN1GCS#^_^er>jm|+b%%A4 z{aD-j*_mnTWlMfjGWt>Jy&7o;7?>9op%Xx~>0nLLNRd=q;S! z&tUG!nY>M=!xT%@eC@z#KG%8+ADzDR&P2@zzx0v-oZAR+X|s4u{Sko7Htwov;lRJs zoyagw?uCjQw>$ZO5P!G>2&6tlT1Q(m+6}<-Xp|*RykQfgE5^O`1oNWZQUsfXyD~F~ zx@$;)LCdojJEn`|+>XM*vcj4G5ppQ?-PU=I?MFYJ`poz&F|9H;pCFz?3Hvc;kE&1Lzo`A>G1@)rdyIXknBP7g30Y?R&W{{_aX}b@eF96-yR+4OWZN zSt0ueZxJDJKPuqC91dv;;#r;Fe8GK}Ud7^kCK@Y{gqBq+F~?K+g3NT)9}8~%6t&*3 zV`-i3rzwWdv-v>KC4x@ev!P-$}P|TD=Lhx@ozP?%6r)8+{4P z{xDKNROZj&*+9IDUkJ&6QH_|A5>7h6z^{k38X7b&rnpg- z(mt^|hFGv@-aYOeh==BOq5sxE&-j+)%mp+xs9B+-d*JMMjt!7$eCW2&2DX891~|CI zd#%DPSrXCBMzCey;@h;Uf8^`A=?FRfuq8US+`tZAc^ElIKx9x6i7f`lmlJ5nFA!P* z+}4z$*3L07U&n`^CE7d8Yo0Czng0%Qt84Si0qA#Wwls44R;>Rh%&no22yLfhQAEvz zdbZgnuA)HkWZmgwSxVqpZBlr)W7K<~d$ zO;t8*i67XhojEUAqtY0_N?_ojkw zKWk@Ee3*64(d)LKZsSMz=WXAl!8?K$gZu<&Y%uB3#_m;gAOIW)5v7$Zk)7Y^MTqi% zrC_=C|Lu8uRtd>!V9gQu&KTpTC|7;5f76kc|GY>v+Z|1E^zfzt;8=^NsM8N1Dv8_5bJIvWG)6 z(352G$q4INM`tyI{5H<$(+unVT~OI4B;Nw}&peojr+kyLIRUny1 zoI2d?5vv2Z&PN}Ea{UJ~>{b|3N+q|{QgqK{#s$3iI|0VuhZt3?yfLe~3LTHqr-SR3w zn4V<(OM)tYA4?ytzKLGfe(nJw<^^%l!k zo!tA~uz3|%7jGbZJ?{=mq(XsZHe=!7j3p6UX5C&l<3A9O<(6qz^46AkRkNxZ;HxVs z${p0RK35huY4EFD3ec7n*v(Yu3}@YodPgX`iI!fK!wjj8>4fENx)6D$;UNZ{rf)SO zB~)jClc^?}vv|3;mMW{Ux5Rf|ra9JPngG#8Vj7^J%_5%Rbnh22N9V8(ATrRT@O{PG|uReJ8|;gX+oMDT$PNB^;N76sixX zfb+a3PE&n=Ezz{|ET(^R1#9DUclt{8&v4u$qYg00RI3 z0{{R7m2?XF&saeHuov`hmny&cmj1gp5n~6*+mHHPr$0E0-mwTIW2K2sk=p!ut@~Ov z_(JlMFl+1SU`sZ(kc7oYB4Vk4=HA#7vb<5+2l5f?B~P&Q+?-s%g7FBqeIk^wY9872 zGj}n>O+{0jBHg;Z5Shk>Bclu+8W-(nar6jXD=~>1S)LJG1-FqVtf^y*#>eNYcbSo9 zaLjE|SWq;EmZ3TTMggwr05un#p_ji;^)RL#pa43+H!!HNR_kD(00095J~ajyTy!6l z7Ae9ac_INp+B_*xB=~TjMY=EsyuUZuq??}$)HUf6pqhltWg6l=?Km=aoPL!1Pra9~ z7Or9NX9y9biTolS=v<66aQf?_#jEd1_v#27uYue$)LWOs6JjcaZ-~5Lb*zY6%f$ zp35Vm&8k)6Jk;*r7{YtVej3w}AsKN(rnuSguzTGFFIbV4#B>3qd!|Yv`%J&DK}dI5 zNzz{2gRY#UQKfX~S7&hcyB`P($*I=_W2s?;5YG}jbtq`820KMkY7omFv*^;}VgJ}> z@BkP=RqK?{YWX2Fu!9QcRPUtyqN;$?yY%%sIAFzA*tyR^iZ%;Qn1v&|CApGnLK7@F z0z{ysk_F&)SoXkIASa| z=cxb|8*vZ0MOi>hof#m841qZQ#@MzlogiM&qZ^0@?@GYnzD3Sn1YlDNkbI+)slf$N zIoi8J2b54Z_WP7V&4OOS1wuOsTxxxKDtCcl@Y3nP`BSNqEO@#wyMMa^Q~~21+K){Q zif$w4Sf(y82lbKpAWFjNKf`$v9x_P?l>49X5??V`(Ob#3Mk~Ov8Qk0-NBCRQ!Qn;` zbe_#!Xw21GjR&PsoGZ;HTeXJWCx{nzh##utnfZe*NQ;*|3e{7IxZ3VECWx{_ zM`17Ua%i@){+%vrSAS!ckoMpd-Wk;a8E@QlraXN(Nxu;pZ@#E#Xra;9#E6Zp>eKSz zzNH6G7lvSO+hM$!UbpdTp{#HJTyaKkkFc)tVtAFzFln2a(jb)evP99Mcc#1-S$J9QIIJUwXC*zLa7 z?O(t1*B6?V3>cnBc)HCAS{)*!!M#rcIE*cHUPfYVt6}T}vlTyP^E4aX9-X&kHM4TL zO+G^)j}egnjxrn4BiH!=PAi)d2~R$RqPtrU%WN*CLKwH`7;OiL7SttSNcquaS1!}& zRR;JXTYn(DcQc}0)O(*MKa7-M)*+{#^_|SO7;WwHp@6U+bbV$=ihnd2eF9?Ete`s7 z@gxzXFqZn?2Wjc?W$qXxWfPE8g8uZYL1gmE2m^;-?tcXu7tH*;SY4N`T@XQ0MeTdC z1vS_k+*NRDH+?}4mH+PH$UVzF!(J)s25;5nc-P537nS_rj6jx{C;N}hLeiWd3CzzP zz6;=$Lz{p2D0gSN{R>B4S;I9zk%a$p)Z+wIy_beZIze@g2JHYN43g=Qg9wByd%%rQ6w1#VlsD?6`!~no9UDTk<6if_viH8Wwmgr ze@-ZSVQ^2MX2G0=`K;p*N!|7pVvrTsart8 zOYvrmNp)C-kJ#bkJs=avOkyaqVerN{bMK)fZ=P|7@jvn3Do(UCWd*5v0P4(v$4T~w zYXT_3cpfFnZ>`EHge=S^dpG^MRzw7VR&>!2WI-@)Bfw0%rE5T_p6K*g=2Hv9Dr^2` zWGOEEj!IaVwDj3Uy6U=TpOs?ocUiYn`6?vfTVE2gLWM%juJod&9Ku4Bs;kREw~aP! zMx(+cDfBro!_>#fa%<~y*SEpXU|lJ~5J3Blsm6~#jPbjBsQbGsSh}of%Ov8Ll8_sK zl%i_<7?q_rm6OctkI*?CW*ExT@Iq5e+O<@HnsOxdH|t9iDkB1yAWhhVu_4Y?`*ic$ zbvro&h5jc8@(f|{*Zt+%TJ40cCthAN<^GTlQqWir*~95ZV^oenGs*-@8wFp|dCwjc zFD3#200RIh9oTJ@STZ%v6qDKFL0d7}%h4YLaepM=&cpH)T;ciDmoh|RrE3JpvM;3? z!vr;m$@%$EnoG>goy79ivN0V~UAg4ck3pc{9PO{%g!BFsTUt6$4%c>51T-@rwyP4Z z$FY4MMKa~Y&Cqt<*|SS%d)AY}5^mlf-DPK-W<|afMfmSAyPoS=C-H?r<2lIA!OrgF z`ae7ginqz4`h&~TIk)TET#sl|`{pVQD9CnWv|K~UCnd&p?ZX15vd86vsJUM#o zL{nFw*JVmehXKbALj;-t;LNQM&+@u6iYSvK?#$*0Wb`)Ed&zadB}dRigw&mHtm}93 zXF32y`e2Q+Iw}Ug@Df~+ONT@{*N}Lo4-04$Zly5miN*+(NcV z_ED`xAj;t52Bh_g#s_bJu2!qpJ(l|Ca_({(zE66jg(v)X&uR*^x^VF_(V_Lcb|ut> z22>MGr=I<}nYG5t2|d2uHo|}a00RITuF*=qEa9qC)}pFKYnImC!_N>g+IinL08Qu^ zHf?@#jKE} z+-|6iy(lVHUJV$L2TEEJJXT<}8D8feM$n{3TKdzsGOt)w#7$>0)p^(nrjeYoc!GP3 zRuFFWl2lpeqS(N%+1YD(of#+aD^~+5*0>^atvEb{K_gLXvBV0$jI4KM6ycxiY))&b zAMDmHcwOeAsAe=nqVZTx zJibWctQN$4p(V+g5>ilE_Bp^Fa?UD4OA95ieX(ivLa@=0Acl^7D;9JLVG!l#Sx@G? z=pOCGMu5Ig^N11z{ND(k8tf z0Iae#GXfu?_kTp;_(ZE#q%=9|`ah*k@llU|X+eH!pFVOv%MT>s(&E!DQQNeFq%tr# zr9;iKxn;LVpvr(H4WVqGwO&*{q;tamjiPu#tYcQC3e!arT%a1%aS~RJjB~v*m`r?- z29vEh{nj0x3tSrHdfckQm4}XHliqDjEy>cGA$aV?5&&`z_V5_Guu0g_TG-oCa7-qy zEUm3vxKPuBf6IKCt81D;2l%ZYaps19K_M*|DU=O{vr1KO?&WwnCD zc8D(}1wss0!ttqJ>gTU+aa3O=FC&^Nbt`S4;PXP9t@+z+VlT${_6x_nwhlQiT&w)P zG#*~CX$%eS$XQRiwZ|`=RyxpwAiF|-=PGj$CfHIOTRNn6$*BAcy_8>nEQ%z7ktQOF z6g4aSNOW+mpwb5>23)R2aCnEQ%Qni7UzPSJ1@03SjymHnFSk?dqwt@{+#{kBE;tQ2M)`hvN3qOaxM0SvQLv$6PW9+UjDVmv#zc+? zgT6gV?CSc(gVZAA;WF6EQKJ=HuxwP#aypzXc`xv3EU18vkes*BG6Y>&`p0GHpuCKt|X)<#vw` zy;~pk$VNtUL#gKY;ozG8V ztFu#XZ_LaUDTjoP&e;NNiq}?jL#XU!Hgy0xqPK&)2w956N@NZ!z?Ap^v%Ir|qis9A z6?U5O6V5T;(lI|ns(SdPO~wQ&D2#@JkOINJ(rP%}Xx;!-mc!UI3v# zkV&e{s&Hz1Q;>HDfs-|vYKrkbhuy^!%cTs`O6O56n=TNRtYai;6sJrGnPr2Oi~s-w z0CaSuOQ_D^|7OX&gD~p6!1#T-UuD*zu*@C=q0=5AWbV4W3Kb?B^$e9GbutkE=f7J1 zQ6xVopTlO=m{;$EcJdqTP3M7X@E7tzWPVEcLQG%G0;Et58LaPJSi9=1JQ~ znXMthS5CTNGFmH8cJ~Y`D&gNxFmJc_cTWJjQ#o)%@j;vo(0Oa3M)V?9Oe13-Wt%F0 zV{hUZdw|}>U~0Q(;>zUObhjOvfn;{)r)oHv*^N`V6@l={=#l)@l~uDQ_}RXVk^0~BR^&7Xz0Qp z6YnR96p-j1FnKyL7kpO=Prx0|BFrz2(x!hSEjN0WI?t+p(N1dUz$gXwqgri35+kK(o6{4vaF=P@oy&wMiK*UAJB(Bzgo)b?$U<&GrU z28~4EaH>~GsO6zl@FAmP4ZUgbEP%y}l+Ow3{U~*Na0em&R0 z#)Lpue?E;BW%+{`H>%Cr8*!+Ajt^4I^9cU~etuPL;0q>}6-tp<9T?Uid!nrPKepiq z)uiN^o({x&wNM#u$J@Dwj9o z4|FL%5ur|39`hnuu24{y15&4?@d~Rb`2T2sL(V#K0}#km*|Z|}o_+MyvB$tlKzGfb zz-G(gf6OEJ$^*`}fM$(~nuLGMiOzrO&kp6=QbdNi7Sj6r?AeEU90o<&19C z!p|Kkwz%>7LQnHQmJ9hxn10Ew$R>;Y_x;|^tE#K3e$j?+7-na6GB#&8!c{mE7d38g z6k|yB5nqgq-(uZbF)>AMZ~g{coH%=uWLjulFo>ZAHjS_#OWbN2oSc4CI$3*OBs0qo2 zCLejE;+;|BN;=7ps-%HrA$cFL@V(YNY4EQ4<8}?W4|=1uL3sJ51-WbH!oL^DaWrqW zM&#ZCrVyhq7xv116>cI5ox>-*@ai1^UjZvn>OV$SnXU5>V!`+AyQ z921`vR<#XK3Q)#bR>pi4(!2{hXCwkO6Z`J@Lfjnx;0GLiFXxqVU-!1y>YCugE}6mn z&yyqzEgf(b9Yl8(uF5)rIjc&C+{?4iDiQ|BW?X&5|3weMbiIUe;J%s7otw>t1J7aR`-f_>>b z;l)zm-=ei>w39kA&KU`qymIm(A{mr3LDhcTzNN)lFG<6}jQXxn*(qNn+;A(7_8g;x z;JzmS6NgQ&y1)dMW8UQVfjvGKo#YvMy{gdvk|N{gx)Ap*BqhvTSeUB8X2QX&gN@l@ zV!es2AbYNJsk=|=8WqGIQq4Z_mdZ7Bjz0-VxHq=$3v#9jUO`R(00RI30{{R?ZxE zpV9}?KLc=@9|%1lD|Q;+wJqeMVHwCY?iIc^=ft`B`!9nXa#f)7C^?Bo`Bh>iy`a99 zaZB0_L!u(fw}DLlg8NvPTQD>2_iA3}?B%EF9D`ME)kA$lX=tf@_s^LFoWh#v-VcyIfblC(=0Pz=*( zC>n)vJpUz>#xJvXqqCVwK?%zbvnLMe*WlLcmKdQ+-(uWkH-l2<_s<{5ABlc%?QH_@ zpo6AigOzK^-LNfw9F1+S>l0ooAz92`Z=Gvi=NAf_w`XMlQjK^T63V*{Q{0^(aNPbtL6Z2H_3!89!D)g~<(H95@XxLIJ4FUR?VNvk0{@IqVsAxjDz@fZgo^WT2 zf4c(m&YOia3sIXqhsv$nPUJ1M2}YgoxNgW!N{9%yHZYc`IL9+9M{F%x z(|d|d|LUVg{F5BIs{{MYw0t4CS7vc>qCrgGjuyhtv zR~xu3WH=#d=t@s|t!ya6zMUmIjs$+KT>tfyl%<`cC)J8tCFO)cpI)C7GerJ=11=O2$dx{%LTo95DE^i6;lv^P2aK2Y|~@t z;MZi$l+uf2M8cpF!OSC~RM*4q_|+IkjTP+FUUzy4Y58F+=How4aqQ}U4)m^?gaW^_Bi0*lSm2Od+YbZO? zQNS%<7LaDu>96d!BoTOjC14?6c~smK))={PjWrcEo&TN%1O?UZ-Z)6%BvGeOU`p`+ ztnNAR4Zc-l7moPmvr~7bq(k8~SEEr0;x+V6?tNw!CF8y!?}vS4vrf3IhJO%6bez8! zeYBa|qR`Cnk1f>i?Jax3jtQAVpgVkUIyt5PlWUeIeD`i;5sC}U|b0{loEX0=k|O9v}o;sUET9Rj!-s*T|Wm$cF=8&+aZ;i_M}WJhs;C_pZ>4!g#p z*tL@{Q?1G6MlV@B&?eeoSGpiO3UTyl+iO*HRhEqV4PON%R&#}f;-<0OT?>1Bjmwsv&G+YML5p712T z;vyDb8&X6#B0@hDZlVP1>hbgBTye|YMj6Tk1y8|`wTE{pmwGAboZXDB81th5rQ{qA z`6T(am@^0770Q*^llzGW$nSb!y~3xW43_3Jynod^H1}Q?V*PZI5|Fpk6KfVgPaOaN z0{{>%2Ya6bHuYm`C{7{8ivL_~qG{mp;s`%KE5L|WIxEA$7KW|qFV5;zE?)_wY=W&lybu*&9?;a700Z=rzV?W-Bme*d09&OIHAuNL ziw{uOw%Imh?jqS}3Wew^T>ZZ&JvTcO%c1n%oIU3<=)v30f~!& z&ZEar51`GMa@FV>b$UsLFt9JZ?ijw!$qQjg4vtDdVa}Jif#MbHNRks633(1_c>wro zuVH;(lux(0Jo7Wqa6PaXTv=R6)9w*D7~r~^uewVJ!#~lc)=Q-=TFcz5QY9Bn{-8mM zKt~TLyJ7-%9npw~#YS!5zm;um=?(P${gezt)$`^3t0)4AB?*Wh4ka(`h=F#Ll@=S` zP!7Bz+S3%shi~F0-~2aX_gBuac+0zW_@QQ7J{{)o{1idP z639M)M8(88i5_Doj`dE2h|Qlhp(WTZP56gv3dGT=?v>(-CivcxVseYb$X023s?-Tg zU_%M*zE!E1Az@I6Y%y@UB^v%}ZW{hxs}A1_xI#kegZf7p`u)~r_=ja_&0T3b)*b=hK zX6rb=LB!Vyo$gOe_Rw@)LB?>5?|Tbcvw#E=z6Ezp+ODbj%@@_wcI*)OLD_65?>pG+prTUunojdwa`ijZReo*NBy*gZlhv*w@{bXHCv zZ21v>_{hatdecC~>ozJ^+uR92hG|w=4u%R?u6_S2m{%pDq!kBYmVt{ z@*vAl^?M{ugr+P^B%)hWW*le&QTrrhTEgm+g(?1IXbYvN1N=Q$>1)?}Yq9bIOyVMT zwQJu~=5mUKM^m7Ag+!67wR_>8OQ^7r2Qz35OlA=ND0vzF=mlT<-lVuX>S@6;x6+_Ya-Pi zQGTs8&O($YC^;n+$P_pGoh7o@c&nE$YBT|{yx_}7ai@I)5Oq>quzd*|PlEHB$8*M! z5?(fiYF|lnXqBo=u;=b2VY}{8&`4z?zm!tGLA0CmiyK+jMYb(J%&=5hrLjr zlI|t;N1t=iIb<4GvbJBB2=$b~FBxFEy9eBEw8`z!gd>yTT6#TmpSl!uQP`Lb!!+VN zHkI%m8f~M=EHcCI-1a_tR(o*wXdaSXl)u&`9@cc5I*;q@1R8$D#Zy08cO=Ybb4i}C z(JO|SAV#Sh5Arha2)g%#4awu()uk!~F>H_~#QO~q_l%O~GPX6J*5Y>!)7Pu+c3In} znaPk`!=r(>fl03_ecz}0n&u7PxmEF5kggL)qM0yRktW4#)=4BJB2n-JB5AMGdau4X zxqW&?t=xeeAFaHD4fOZi*m1g1AevcM!Lxnc_pWY*HN2byDw6|l2oXncrgCYOYgNfT zHmVmN{9PqgOk{|S^Ht5jK{rA8hNB=03J{@SnxQllLyz#{I@$WRU#P3b^CzKs|C$f-FYWPoCL8HjOxf7y=ZnLX_Y6p?!M2rs@y?Ccw%eO9DbnZiN)_ zu4{Oo;x1!?vYzl{OoNro12q)8a#QSipM(J1q{#d~a1v3#3KuoSR>5%mNJk^gGKWk4%Rb`S$m6zkirFSZ-E@3*-updK!iM zcfefWV_WiH;UJkgoG`ex-61>AMv_bS=hAJ+ko`1Hme|k7Qs%KvL+W|k(7^vz&Nj0n zI7*e3xN9p9;twMW{79WP1AS`zDvFi{iH4nEA_A7~?81X5I$EoxIK}0>=q@9L08r`c zAPvoL5GdJG48Tja~lO8~NU=91H7cA9o)`_~QAH6zB z%00DMw+TMe3MT+pn~L~jyY;R-1q+(s%fX69UGh%!j0_kq(z4xsP(?9?K0{{R6000952?rWGZ|;Rm zxli-6_^Z+&CdK16jfchYekcpA~b41q}&LA5@` zy?xB4JVk%*M8uSGHtSDD$B`-3LIZm;fDWHNN+Vm0T6vY-BD%~VS};L4xMIu-9ulL6 z4}8ZsH{|b9vqa1-MdM{)m-^dY~Eci>Mljqt^T< zJS$uSCwzg8k0PpMFb;U!yOt()1%sXRA}MyZghZ<7HixqOhB|;mrJ4~CCOW`dOqY$P zO0CS=Y_tDDV?3s2zQ}(h@g_IJ>Uz^A>xZSetLl+Z=R$oP@qZp z$kQLaZ11YJ%ZrY=7tXU%M&u+3eK#3V+l;=uabb#^HL`4Gcbec;_3rt`o4l^U z4WDDRkN}!i4P*C*-3>Lse4k|m9i2y+aUw1tlaxmnv_s69&mu2xMM7(YovAp4#|F>CD?@lr*#g(l`Ru*#^s_s)Ys ziDq!Fruv$2S~lSv8imEc=E)(}w98BfO9;epQonwW(YJr&S;As_-pk<+gD9ma9E#hi z2<~cSt;E;`@$Za8veuz29*K`bVO5E>;)L1l|v{OkOUwnn@|zZHG#uF$;;{y zQ?t(?&XFl9&UJcUEyY4xxgPO+YHp(p7MqCfYaP?TL@hp&q#3XIVIrHM*%6~SNd-39 z^qaw6^yxJJc1;bez)5ST3kZQ|E4E&oUpWgVw5x<+^Del3#kJ8`U>Kmzb#&?80XVaT zIbbpdK+5M9c2g3X})i zU}rzMqlTis=#!|X&+WS1=cUXi{(8f+RqwX- zT<_6qkQ5~_S(>y-{^b60S!zGRXUB->yo||naR`nSvJVRAsI0P?S7VRi7L!gPSe6ge zwGP#aD<6U51`r+Bb1x!UvZ&H9X8cpW1vrh%vc;{umrI7K<&8#X8rF)K+UVG_8^msj zu^2v$|0ANnkx$?*^FhN0@DcNTqsENPelAo%*&Imn))R0}e*Zvb)ufK&^;f+`;QxQp;dnU{AGOZr zo_69#tO1PQEj#pVLU7{G7ppSn+A0xKIE(Y;2UweHTy)}I$WBS8hRvs+@I7Wl_P8rg z3$*O(ufy9N*kj-AX!LS)dPxC^5*OROIP}jf8H@NZybIx*JkJGR%0h0DF+DxO>gy6k zFd0_NLDDemiE=r`1D%h$D zUu;xkNb+p|7S7K=mHcd&_acd{gX}MDTge9GG~Jr`)Wy2d%|hjEI!ko7H0_r(esu_G z#uWNURW6qbg2AH4uVV85+Ep_8ySHFWK9z|y4OYbKH&ahJPgC+xAQ#g^i2$VzyuAff z9m}>Z+-u?P1b4UKu0ex41PSi$?gV!T?!gHm5ZnnQxVr=ou0cW)Aa6l-&e`YO{odL4 z-tqrq^y*c!YR>t6Rb4%+x<_}l5yEJKrhiJ@Hl82ck232N%afxCzQYoAmjmi;3%;Y< zqx@8`4(6^+_fSIV&zb&@u+4MlT#yXs_+{E#i25#(6WSv9QSH$_6m%RV?w$a3}Vb&tP( z^Zpr^;DyIb1}b(w0@0P5So4DZhsU3_vs|9-g#xE6a=<&5w&KqiR_KYHuArXvG$1@cRhw_tMq=&zkKXzQ-lV985Yo4L*W?gLhAD|{m3m$oPV z#f#f*86DsxzwS7!`K(jLV3(21C=1Hd)HfX?$B?(%bS{Z`u%O^80(%T?;Q3WD;bt=1 zoTvmXSA(;8x@z%YC+e8zj&0C=M#ctJVT;O=M$o-2^+ zzq`;kpYQB$!raCn5|Ma4CCg#~l~Vr=i%q(cmg($$Vi;c;3;{MN>6?y_0_RzB&&pc_Lc z`iXzOgh}IXC&!xIEOne10dqW`cCK{oGemEW~hn9}jO0DQ&~w@!#dl zRXK>rV#=rxC^E+=?cu<`fHnHeEYMojEOZQl)5S`=`YDG4pGkg(EXy0`bU14ov=BAK z5}E%(;APF;?8PQ%(TGE zx#cUh^Yd4OKbJ;u7`|k5;_HYMV3+an3TpOvg}gapBgyDa zkK${?Wm21_7##2f+YWDu%~u*WT6=R|Wf|*e+D}i~FD;rizRQe~sMmpnRL1TUMsL z7t!WHzo4NW9kO|y8T0Yir-aXrY(6-ao^d;xf?c@;kvkC3V-*?c888~hUt&WP1tP~5hdu5EIWFY@U0M-xW`3uVQqE@ zTY`6nRfBKdVXI-t!lvNvE8ohf35cJyG%2;}DmoOc({p9g=wz|at5_D3WDP*Rba{Lf zomwX1XKrnc)Is?)--svLlkCEEnV;7R+-CZb6iH9hYTc#w`VL)>@D}0qkfz0G+iQXk z>JpX4;$WgO=)5oZjgi@tSY?sEZX_A!)AGIMNV4psClrpS7*(PvYLwx$y3f7e>2Tj= z5-4owp!-N^-h5chb1yZw@g*-o4o5*8rj6X{gPF`|9HV6H+0hP+0klD>sd$8I51fa{D%ch-+*=^l9aO2*Uf}>TG;CnenQVB8e{qn9S9o z!a-ukwU}Sk5&1d1vx6hO=hsG4stRdc{E(n|?~J54txS6o>U&=$+RtXh%ao~Ve(}$W zp?YyrozHW?B~2GM<}G%@{IS4r+<$Bl_MHVR+bt|06qqm=>a1nGY%lGExPSI8a$d9j z2lJ|k3MX{DnqRW8phuyB+`_?UyH^zvA2XsFL*PAwj5QA)e~dp4$t8h_+>%lfjXxq1 zRX4=;H?;rgw!^nq*czaZmP2Lsquv?)J$lXQvm@}HjM@yJUv=Hgg={yN6{)(pGfsG@ zYO!e;zR!PE2+nqNC!5x;zRB%P4UKjtQQ(_uiRTQJ_STx%K^qGxMmm$&;GZT?5trIJ z{+XPeZ}^QxrXsq$xhr}OZZ+GYBUrNet@x(FPC+JyTJSD`kZ;Ld(-5mjYI>aXRwXr= zqvq^mC=yYQCGx;-N9CmIoNLG0*07q_mM1=gXYH$OzSF{J;m>dK+gQ>zX#W&^;trS8 zB6ont^3q#;&ZgF=UE^+`KETSwH3grkB<95~G{az5FuQRjAWoV}{Uddh<-G7r%KD>jwBYMsi0!7NasMq9M=laf^a# zYBRJTV=0|uii2m$ry7P8ZTs0u52jS8JyW#ykr#~{v3#bJ*LQ%sF`v6&Xyh1|i5$q$ z0Uey_3H>D=fs%98UXDpeRgR`pTP?0rV?6|IHKt#Tl30UVy9&shGJd5}CW<=apk3v# zL6Pfug}~BdwdOs&6`1uU`w#7x++EJs+JI1ym+QM1OD90TKQzHO6M(WL=G%`$z7V4kXpSpg*tPj6m7Wf zdy$b!$yS)$H^=MUJRg?^P~0xshN+S9f0X!B-!N#rx?{qGEVb>jH(J~-Y~|(Z|09Qr z7lUVZ*3}fzK(=87u0p?KdGcMI=}mrkYu1~bC}j}^qgS3P<2yg)JvUHb%;6p0SgfpY zhT!)|op^ggJx1f(itHHO7_U1aCkv2W_J^G*9w0_5!fi-9sa`42>@tPPL2q%CZjhGN zf4Zm`#!2rpNd8kx{{Q%@QT2P<{CL_A{#QUV_e@v?k|Ik|d0=j;$Uo zj&7t_WZ%Gefgj!3tr;{TS+vtIkr9k`xXASmfTncku*z&iwBD_MZ~fv8LdiTk@6}Zr zdTzJw=;mrQ)Hq|SX|VX4gw6B@26(inIc<)XaJw5=bMHX}6}QBW0^^vTgOhP~uFi}4 z!1Hon93BnLqpg>Ft{3(pFMi^I2U1%jcYv--3dfq3HcW{RY%N7U6d0{YRlKOHKje$) z2P?tr?7VP%g_&;ogSU=lyYG?=RQtiYYGO$-^nH4MfQQ$`yP}rz3HGT7P(IY5L)f$L zTQ*Gfd-x)eQI>EUpH`V*8oob@eB8Pyk)y)`%$E|(4va1M#BQkX&X7&Fz55snei`-# zo0k-kN$`?F=zOxZ6x}S5S5x5Z)0t$lGKTXfPI}zyM?;@{X=N-rYJ}1dnVN~VB$ngA3t)8?7Zae}G z_0_)pk3o~!$Ug1P>rWT^p|S$|syu8mtBn?Yawg6DnmePG!&XhXJ0C~RcZZ!-@Y$2| z(;D;PjySK(dO8l5g#tMPonUc~=SjW?yR1$8oH3eyq&lDDhAVPuHEID1ttZFz>E$Yv zXSv46)`e_Up<`9k(EQgmVhpw_1x4=XUuNGnl3(;oDP1QZeza0?L|@ zr4jII^0re+#4)`nMjy3S7c<;(V8xGmv(mqyW0KS}+ngOWs$b2USYEBC{C;WjmA zodm=cI2`uCi_fm^hqT1}Fdhmk z!S5JUk>V+1!>VB+uC#kUN;y(x(2elr)Qm)2M!B^35Ez}uwr@p3U~VP6`}ZLF{rXgAUezFrW9;|DU!&yGP~rppE@ zlj#ip-LT%3S|;cI*SS@BK#h;JaO^Xc&IoUod#hLH6VT7bw63pN`yDn z7qe@cBKy1-lg&vY15Ze2p?286LrmU zm`MVPP=}1PPpbhROyuZ?1X9w}D)f0b@KhELV+_@yk!32EXeXrz8E?W*x=&Yzs2krG zJnT*fXswy~+nW{7`E{q}#|PD&G4IaxK2pM$bSrOlI|a!`Tjq>8Y6*$f9cGae*G&`L zrW!Vs`WaBZ<>mhR1nMdC$87}uZObTTmv*E|WQm?puYmZsvT7zjx7Q zoVL4NhOV9I*{#0k?^yViIZgl%`%yw8Z7ki=kMB<#$y_{9+e)!^!+nC{c%$o_w$jgj zXj+0}OvKH!=6hkk@IoGu+w`-XM?bo=DqKB58~mc-fP^3%4OP5-X-})&_%Xx?F5!&c zJ_@o}eE)ZYZ_O`Y*@@GngkqQ zc@?5a!Z1A-L6RQ6z7}ge)+tyXfNH2{;r_g)`v|_Z2SsJ#rYQA(O~?B!w=B+VOc^Ga z*fna08%0HO_O#pFw()ANp>(wGNgCM0j}Oj{15y1>G%F>^^2V5OG{!dsD%on=^vYE$ zKq0X`$6_4~*Ep-bm6D1yXAtVB@hR53&;;z#4!X*(_|JM|?gLPuXS&wVjZC z{#4s|9*q=>#^iJT;LR!IJ3eyaomI4W(E~QkjU2Tdo9#~x-TaMU#M)dr&AWI^wy`~k z`_pjs+JBm_nwxv4Y6C|c&2PQo*g`O4(C?pzIK) z=|SJKPHoV+D=Ox?7-gA6z*4DKh9!IFGmFq3%t`jHlvtDZ-KJH(^(TAkn7LYC-(o4~ z$DuR~lI!b!q{YN})K#eZG%&;qB$VlM0!V1)gUMQPAx-+RlgxBQFOp0 zYh&B}9Y{v*z0RN{U%wghUBRWdAM1*-3ZG*x z)6c|$(QWW$Kw9MD0-V%)eKHM=ux(m}AM;;rU6sRfb}ZM<-XawpyWb%9%5M0YM}1gh zJvZ)F_HDng8uEP>;l;;POQ!B+)*CDN$QZBRHZ=IFO#$SBELrFr1I$(e)mm>Ngp`sX ztE=d1K`kQMVU0rCQdXB2=sW-EYcSub_yyzF!mlTx*_z)ypD{B9Qgzfj?8YPZUM=GJek;|hB6A{d(=beffWmi!~x;s?2&?^T`Nsn_-Xz((T zQzUXnF!cDoh_sfHmY5F<%v$c>w$I+wBGo%90B!xKMzz^{d%}{4Ta)KR zQ+l1^HiX>9x+SJB-;3WtzR^`EtHY7%oVo$f2)&gn3GnA#0^<}jOUqn2y6G$S_ULdO ziXcDHximOa5XpYdpU&v7p8JX5(9{>f zJ#uuvW8;Hc7I+oI+woR}>xCM#JbEe#{{#g~Tl1avgmPZ$`*qI|+D)SPeTGl~M1Xt={yjFBp0M<3!a^c4+t*KVX zTNjUNi9ebsTtXmxOd+U4m(9=U^Eu{PQeN~XTjM{qwn3DYj06BLTnvcZTR+hj*t%EjaL zslOW{1gkIrp;HXNSawEEGkI^{O7iTDm68nX+ht$;<&FfnH&_TvUN!KpDf5sOw#xdy z^YF?L4mBxqd`@*~(LhG36vplLC&nSSL9TvGjVo(^B^aHVXgDtkm&{|wYB=-yV)E;# ztySOL__Z7KC@-wwDi8b&#zK@5peF&fSHdM{;yuFsvTY!nvwE@+dv2k_q9j8a%4VkF zL%rNQ6oY=14saPN>L6 z*rpQgkJCO#5oUZRSrO>bn6weeIy-$Ie+3Ph$UNxwvja`P@>8iYJ8dzW159rgp>sch zwjYK3W+B{lN}P+;)Z5^?MP}Ck09R1n_kxb#RDPtH775SF;%fD>*xoS!W7u}(JulCI zskS~Z)j7k#_?k^A%#=}}`nvQFv*4+ZTOjLOV)uatZMa7E2@AM>#;=1dG#PXfRn=or zK7AG1d(<(?-uz6&9I)6wzg@h*={b=xqpmTyw!ph#N386DAx=3a`zl+y1+$M$=1@Ii z{@L9cFF@|&{PRQ4c6r!22sh~8^me?pI2$D+@;;t@x9s@=pbZwUK&{9d;?cOY-; z`qhmdEMYtHe6U=gOUaXPCC?DYhkl83-&|l^?ZA+>gia;xjzG?j!<+roa#9Y*GFCM> z*u0#Y+>&&h_09@egYw0kUHnJ17@CRv?gCxkFRIYAVCR1ZV+%B%@j6L>q~LEh_G| z){m8AeXSLs-P;YqBQTtlF-eb0XMf9_eT>8wHrp~?!ng9Yz^Pt4xk5V^EN@iZtQ+zc zCvW8YDO9fTuy}9Lr&kTAb}Rq`CgpA;pW<^kskCRK;`(30)lx4odFb6Odn~J$>4MDL zjOI{8q#1(Ed5YscRC`B0{*=G;=EZo3+TZHeiBTZ0TG!Rm%+Cj z*qMyyrN<%&x2+D0@P3pSxSVZ-t2;NKKB3pbR_< zF$W%f3&ej%NJHpRH5p}lwGT$JE`1*ed4`^g?G)sDwQ9RG{VMih_DcAqc^VDc1UlDU zPj_b>kU}YAxWJQ_5e0r&!~U!b0Vqr?&hrfc@WH!UcfLaa3af=pQxs+m(7}V;?rAS? zB)f+P9QheYR~ouJdVMz>*h~=WkV;DU6Li^?Nf!)3D-y6dH^AG@a{{5bY3<^aLGXXdN zH3xz`p@ErRdZGJ#d_%LkWo1xW)dhew4^A@zsGI{I|KWl%T9n2j@DBkx@e%-e0`Hjj zqY^7w_y7R#1LfkeL{$G#{twjungIWNpdeQVECRT&qAZj4B%pl&c5UA76onSzpD2N2 zHxSJ_%|2cfKu-XzLOg;pe!E4O`kjITOsJob0R;J=U;z9DLcj+?K=BU(Xd+$z)cbb| z_}TY`P)O*=hM;3s=(i?Ac?l@_fPlA*BRl=QnHw<035a24vsD5>dLViNBq~CFzuM9J z4npxE38P{U0B!dI1{(xE0s?RUck3Tu382K8s;P;z03ed-I;hho0AN@^ewtUT?<#Ze zQu~p55dffAMaL%qnCKuT#7zmxoN1#|#3^u4Gm3gO}i;Zh~@ zcaFvNZx;e<_o-jrVefN6PXIu*3r-~vK#L@UmiVnlmj64oEYJl2uo={xK>2+ad;!56 z`J0$f>Hx@XKFZp%Hjwx+I29lk1$&FaR#OIu8Qyzm+>=%(;T zME&qP^@qYA;;$z9Z3RH#LF+*=Kmd!xG70Fpz~Bk?^hfuB=>NWv_>2R8)# zp0e9O(|da+$A=#M+tqIZ&VtK@IEsY7^{iRF^V_U8RogSI^Df~2AN-~j;t zRX!vMLYW2tq4n}-tbyO`MFEXHQR>A8%=;2BRH^~HDzwi;wMyXOJOIV=Y^Z$b#VMf6 zl`oVALuWdjCsKFsz^yYOOM!7N96+TzDfnQ*K?KQ!+#Jt%t`jxgZV0K#jO0r9=W+k^ zDzAr5Cu2^KsgYS1^PI2 zvq!K3V4(w`B2RbKAixd)CkieN-K%5SjR!)S4ujtJUKIeU{ESV3$s*$)}Nm=GtE zJxJv6c<2BCI6zn^{56YvC;!;QM1KpC4+);GKV+2qfA^H%r4I)00D$rr%0KLXCDQIs zBO3^$-QR%xH{1V#2-6FJvxUIDPWsDs{%7?B{*5l;?!Q#%pNjtv7Fg&M>wn-4|0lfv z;)bj1zYhonf(%@MKcs$#e*^CcFvES>d$5EQ7(l4=_-=Z{d==KWg3=!e5Pp z*Z}}lwK(uWm!$3C=)$Z4ZXm;loL{_QG=2w5v@-|;NGxVR{%Zz=Ousxm*uf$H_5pMD z0PQFWQ+#@#N1G3T>S_NdeRgjGA_oBR-|7$6i%EZoARY*2iC8A%(|Ry?5fYL>0l!M1 z1l)0{f7>91Mn$Ra|CSy+*uR^qp=mw((IDDEJ=5g!mJGAjO#7c2aG$K6J{|NbN8Xuy zUzk;peflTr|L6dyZO<$wBf}W)&9Llv-u~14A1cs`r+|0~V{euSecA)lT=v&Bzbgm) zDJDVr!f!rcaHEL=$eeFZ;ZU`!3;`T;05NblhR{J!U7+dSKgD8A1huu59yyKDa(Ez! z5E(#V$QD^)cUc1~N38OeCdS4F93ILJZFpv@K-W2L6KI=Y(jv2@w82u~n*B&%z z*ngjb+ZbmpfN+5fas0M_$>q;h03h~&a_{^v3Tbus_Gt$$Bp4Nt6ySuiZ0X6$K{g)P$=Y?*(uRWDiQ*+!;KbFv14tMA)!6r)9Blks`r`nAeEysP6~6q3 z_%K)M6U!8|j1>)RXsDAf0bm}^ChGQqFvV!6=9tfz=#JP&dGx<69y8(27Apg$Q&&)m zCV>wlHsHpdK&20F`=2J0C;&7 zm0GoP;Xd&!^D^eL2)Pl2KIt)S~z~jSsn(kzD--;l&#edZ>6?{NMdV>dV=!6Hvka+6imN2#8U>UM(-1EhV$tS z1ODV2jCJ~lXIOOz2T0VCi}{1Y{|)wE^Fc)q_75|-`w|*50L1o(%YSHw{t59PnV?t* zAS7zZz5Z_j{=4sg`1=nDm=6#*NYs)$l=!O=;@{muIfnh}P5;5|zxB{Ri}x3}_lWYy z|GyzZj`@8*l4tr`h`*|a>ld0@lBg16CI~>+-8Tc&K7c&M49kqMb}vD$-2nofColfg zKrj^z-Ez=>%76@rq`&(SD>;M%WL7RO|KH$%@bTIZ73ba~+{eIQjzKRD0Ti--0Rdpj z{v^Z4Ku+<8_J)J>L10TPQz4@2K5RY2Ex_QukXlUA=bSP4iMdq`bRYU}%7|nFlR^xE zP@|4yoLgZi$^djI!MG(yIVa}NrkBzZ;av-X0MxJ8B2v9rfqd@?#`1gItunchKnjoP zc{JG%ch1F{N{NPp!h8Tg5*vqE$AxHt2CgQYP_dR|i)$Sg_8*;%VAZN5?yyzG(V*Y^ zxZkd~y8cKq?pv)z+d!7V1z_eZ9`fKPO-&yXsEe-Z@B^mTkT3>64^1%*Sm`<)T`JQ+ z&N84{ELZ(d{^>(l22f=nGfBknVhv|4|m>@ zt^COYAoKK@nG+$+k}!x55CD(;8Bz}t{4$j9eflkdpvJWa;-Xgw7NiuR_bOlFtDP{) z97G|M13-! z|22hQ27m0uMDNY+xBuC63`_?AYGM#TNMO?&{u_Y5!2UP;-_tRDWc9xj*uXLFe`=?H zsr>(&1thXVv<(!bOcvlE6@*O3^qKw^;(r6$2!AqZV*5rZRYZ1mB5pA_{Krv&H+pM5 zr0@9M$~%$SP#dd}TM`RuNQ>Mv(09V?2e#Ful+VXcFwrT>1jBtq3ona9EXTGeQVoUa1*} z>J_E7v^G>w4Yc8B!9)kjHSNroqF}s&W(DdD9&gcxa~96BM)N#h?x5#di68jwT{=kK zkVUkKdB1Al49N1Gey=KJHP+IL>$zg~!t(tQjq95dcym;tE$F(Wj1x_grNoAk*4tCe zLcLLNBr0#`S6{A^^Q#H_h&Q!SsQNbw2W0IPR`EZ_J$i+^td+bCSU*LeG%nbahI%h! zkG+I_7NyxYe%v;%zjqEpI{B=>@pLda1Gu`&;wctK{NYgVfS6`XdqVcv&8Y<`>BYCl zbNv`0ceox1!H5|8CGw=XM#Hfrt6x4Gl9{o|bM4t6`p{d%>RAoU^I#8Y4R9Lodmmq_ z^{I;bc0yL!GJMmFK3hiR@Mm9LYK5c#?Xsq2+jJfNJ?NT6Nc$)6>bEGP@h&&DaH=AHkPGQzD#GAN&Ltjk_@S zm}JR(*Vbjr*9qzX6scBsx~@gW7oR3JsKx~tI+e+3-J4T4LNfB&1v9f$8aj4aa)j@g z?(U;TED1}@R}DIW;8J&)slzG8ht6Rx1P^*nhsr9zRb;4!jOYY0$37ET|Cu0a5Wr8ViJS{$wbCo5u z={)uy+NE#2vrwNRq@a_c_~tNHv`r6~EOSIB=&u2~91+mBMO7&PlJ3%Xk5G~L?&NL- z4+vtvro7-6p_#q72U6mD_YTBS39y2&Z@-MuoG0Q%Oc9edMwf+4%vYv=nief>Bz z%V{^cKb#NdV?FgAVa~5P#){h2;MZ@yZ=ae}yh{+J$~ijL+Xhu~ezF9;lUhJo;36TK z+Gu@7IVc~Wufx@l2F+ePdSv5Q9h5IEY&kZ;AVYbwa?#;=XgykacQyU`rx~{rXrPqK~C?H^;h(#|f zswYl2YC-j?_S4E{RI4!KdQdS&=u>@&XYwok~*PzOUo_31m7L1gq2rbq-a!eduW&uk6sk9ITHJx*e;D* z#5LzitD}pU$XzNqC{{Kuj%K!=3dpH?IH6##W8q2I^lguAu5YYxLpdK~9=J;tnTG++ zg!|WsqsE-@WO0vA>~@!4q+6#;x3UlTO6ivyZgY<^2pOc+xnoZ#`DH>(j@tU zJ#ndwFB*njKYZ3TBUNl=L~VOJe~fKPKQ@Jd;%ic3m3jW*4raLuDJNQnCSHF0GAwg$ z-p((`#V~K34ellL()%LpKm~nGd3KWt(~p&tNxOpldBZGgfCsm2-1UhBL>2+cI$6P$yk&m3o(C|p}txa z8>!G1lYmZ(;T;E^zt37vcs+2(_o$6T8Zq7t|MBzFa7ElC&z6Q5Z3Phy^=C3UzLx&< zA9OcS{0to$!!MxHr|Y+zf5e1^xNc&+%nskJdp^AIx~a`YpodQFj%rbdDOnFkooh<# zF}!C$5eIy%bry7g2_;6JdcJR%4|eFr9xg^n;xd0hoW<0SB(_^W?MP@27g=V-9||L7 z>+%88b0AZ*_7OU2#Pt)>mpfz`MtEM|JaE6fPb|6IiX<-k9J~UThoh|6@=}{(dl8A= z?0UJzeMuygbMTd25+5=9$7e<8Kvzc?c(5%=^06G&KE5PKUaMW*lCVi|750eyF^c$G zS0^7r8V{#l&_|<|J=VRAM7+UM&=r<}4;n}N3U|peX4;jE2uZnyCVq2mc;-BJh_QyT zgTOu>r;NaLiVLYeHtiD!iYI-oYmO;&aIu1WXA`V?kMl!hsjP;UmV?GX3?FWs8?o;m zIRgR*?VX!Q20N14LsDh~dyK9e0quKr%`|r6Noh72=#=N$6X)`}ym{jKh~6EPKcu?6 z%B}{qBfcE_Kg&Q@zQZyY!SwPp-Ye|UVJy>>PHxq~8mxxSd*_EFtEa=X{4 znx(Pa+32max8HVku4FnEgnu~O%b}GZ<$scQrB14q%s9kBkM()=D0Q1;(7I>X*>b_< z6Sk;L5zwygj^V_$(1j^n*FX!Rf4Y}|FCRfug!C;-%L{b<<%_wMVVq$!?Dn(u*tyMQ z{fSh6GybT|8*cB#Eq@P*!tzVqB|+*z|K8y4MVNL1G5oi;9mbM~L`{1#-@gaBoR90# zrZ+1%xKfc5gHYSkL%w4^Mu8hPwy zx00F3AVY1l(s?P(;w5c1f0>8NrQlUFV%)-D(fT~maZd`q)PV+_u|@tV$-9|uB5R(~ z1>AZ;(o4r+UABuXsrB#8QbGPA-^WekqK?dM0t%ZQ+C&XYcjCYgguHFgJR#jtv( zj%5QF)!<{IDpoaAvdt+&vdUB?cNl`3B$4u4)()<_^}`~^>GJr{=;OIEWk;#%+J!YT z1&`-cS;PmXq)Vg&+Z9CWJJ+i^FzQ|2{W<~f&$iPrpiP1c0`w0<_%H^dtsWtZ6m4P+S;@$YF`Mcw4(4Ih{Ss|yAf=wrt=2(B5w-c?g2hPEt9k`zc6BNMPC zRX|YJ?(>A|t8c17JR#hX(~P;gXEuSYj}Yax=u-_x z1x2*iqDd?t7h$6l?^fay1Ds2^zM|X$aebR^kR_b$5~!8TUcU%M7Jfe20K>umdTF1G zswBQz@=|uBU5%th;YnpySk*^$~DR}XFWty|q1T1--X&G^cs{Gu$p3Z)Fu z0jdNef@XB4?~y;<3iEjLzl9GMn^NJfNy|h|7w#q?Jx4DuE<-(sx5hOwcl4-OLly{T zQs||xj-6y4d?nF(o~^Pfc$T>{8f&+@ieUCFsLn^5rFfbM2j*N5o}{L~uuX@YEo`q} z*#-^tbK4I;FZy7M$(e-o=3IdHWfB#z1V@(`UU8Grsh3ACwNYUVobpH5B_d$(;aZvP z_T=2;7|1h*`a4dtYGW?6N%^;=D-F%d63q{3?6qMIeJf~FF3W~hF*Fw!WKan$UZk*# z4}AQI8srYT^5fR?1;00`KEp*QPKEw{7sKCVqn>>8B}$8BI^{FEB^JNZmjSmE4D8UK z-h@3|juG2tsCLPd^yTG~U$}eMKrchkJ6HSy(gf%U(Y;^G+?gj|Oq+Zo?pm;%DPPKu z$m4K(EQUUeH>tWzHZ}NN^es_bS#dAsSQydF)EWok^x06(j|AG3+LBx19 zMmz>~N85{lJ1<-PX_e>6PMo_YA&mj93_(v=UXZT4b0v&`3LfJb`1$nyK}6Srq8_+IWNN-yJZFAM_u2o-5V#C9+Y zj!U^Z@mImMDm9Xi9p5(LoSgaDQFZWl8fctIi#PO?k3D?z?0Jf(e5L;9Fiy*!s+7DR%`{Cy z=y=IT?8gj6Cyz=P32$*WRqRC7s#Aw_lH5d;y`kr1AqS1|jFXT{9;&Aj)5TWrYph!P(?eKiu91P8sm6?++FC2)(puqy;%PF*$W^@J5 zS+wW2J%Jr^$))VZpY1y9Ts%2Uw+D;U^U@RK5%>SL}KqHOH(s{kiZ67jOohes4^UC>zp1qI03dNDx>ad zu9DOs<-O*oK1Gjp-?u5MkgwCA`re_nm*<-8O7cizSUx|__mfl!gCd<$fFD8X*X3X*OAEcZede(uFokKQvFwP(9D7 z?=k<8u$h)((rZ&G7w>mMrZQd|qX`7Xi^9V>th=!^DF_`29Z+VmV&`2h9;MfN`D2^z z_y@tx0THof%r#p5_9J{|PTp}sU#M|wIMZmZpl#jX!YTH|96sGmA!3`)@b?JRA`qSO@v#O ztea16ey$~=qmI*he{V|eBj2CLFRpun1D5n<)daM;Q}b-_%0eaRuGhbe{5T-L)(j;B z1hix@V!;n9V4)YYG}oW)|@0G5D=oAyZDOZdLU{U z^YdACv5P*&Yc3srTh#Lcv^CQbV)}M6b#1EDF`^$URJM;f#I_9i70bO(dTe|x3;e=) z<5aRrSC)r&Nr`H3hBy~i53D3#R_;ikvS2fVCM$6Fwzs<@T_Sx;UN^EZm)+>qEh1S} zVvgy?zFXa1tqW30;Qf4>S^sK3k~Eb5@St{yMaWK$GXKsCA72y!fzE>ilc^{D7?=O1 z53SO@;-l@INgTd>2!d||+uT5cqHB0{;(WOe15W4dRBOhuDEkq?zS?kX0#Uk<9K*!> zp^W*u3fv7)4F7dSgxc1e%NX?RjVAw%>0safNrNu_!N~_iJLFa+Jjn=i%x~95-m6uQ{5hhl{2*Yl;k-=<|e+o^B%nn5mt3}r*e(C6a7`* z!8a_OUpMNm{J?adx5>FSzfRcT#T5(GF$LhOX)cqEu_lu2kA2N4`Wm4Vmq|r{wkA-N zr4$1ir^b9TI-`NnL_ zwB#DBDe37~rOEs{7vF-PRGU4a^s@*$W*65Vf)UVL|LmIkXq$qZOsK%Db>HiiOLgrU z1~E)v%$SXW_|-x>idc0kEgz=L`^#)c1lVVcd9q$-M&fmi+ISQ(DH7yf*Mk<?Z`=Z?}XnR#>ES4f>^1)|w@493bTVa`>W znv`~Vam~f_pGzkSufapI8G%lo9~%n%b*CwErjBNBssVThs{CagKG?)CecHxH1Kw=` zw}lhAd0bw~(!1GV&8pQw-x`9kqnoF3PZ(o!2k{2i-&!N8!Hx*gd&w|IWb-bX%0})S zDZXx0pW;M)8H88`BU02$_d%&sU+xlN79mVffRogmxC2YoE5)!EB<0(LVbM7%ml6Uk zjg3XGxiP96zg4n}itDx2f=s(Zff~bdJbje@)l2`ep7G`3z_XT29>ykG>__ZvKgegB!HrG~9d7~OU z$~oh-;c=;eGtBe}bPkD1Pb!pmp{3yGvq&E*s^xg^(j^bo&62gEwPEiU{jJ988^s|7 zSjNg5`Q*fhz^hVW*JOY7{h&@ytFGnqT{`b}_^q2B7R_m04%rfe!4&&t)vx810Z-w1 zUfSvgcJg${)CZbNOZ7K&Q5W46~Ux%l`4slnYqmXj)|RmkixOx-8j_j*7L7ru-zEwP9Y+eO71`83z^!d6jv)>7!-bE z`!-UBLyLuTB(fKjM3O$mdnIok{lQ3W7}eq9W<n*s{z(@57#Y8~~t(;A{dT*LQsO7Z$thYIL7-aVW^#$E}yu=pu z+DN*KqM^69jwt)H3W>cycKphH(wOJt>n>ZgABz!qpVA!Yt2(x8R$X9@qfdVVSVyi< z;Q&Hv>c}7PyO%P_R3=cdx$I5jm1at-jh31E?N*I1C%^IC3I;dV>!1>+m8XF_n`%6Y zC06gvVeAIN*~=*jtL~NC!XZ zU#&-vr?195_5;(`^N1h|Kb1Um*?UZ)cV26rr2q{&?^&^n!lubF!k7@eRKTJ?vC|M_ z%v2SzLWgd6V#xc6ombskp-Jx;mcFc`tWK0$DJA(V@bG(qva3u^W^@G&^WpQyHXW)O zvuB-2^>6LOYz)o8Y;;1$inlHMR>GHv2Z%r0z6jL7s1Y@GT2PaSFhpk#1ituy>R}on zVXX?YRK1Lj%0Z`F>XnQaNrodN~O=~aGSxy(t6HMni4@>ZTigQ zbC8wTM=$&e{2J}>oaCd#@bGhh^ zw$Y80TU|1*1|`BK?%Cxm;p4b=6ZsEJ+eHk&yqQWSK3L~ns5As8MW}FhP+XGPN8xf! zdE*z!v99Qs5Nhze51V@YdIaSt_S^V{8#Nz`CKu)7koDn;!@eYvZu94jp1BdacoH)8ndmi{ZHX-F%C z#R z#Hx#X>=AL}sG9XVZ_F9!Y0Ttz0Hvcmo>t3<_r}%EnfKy0QljHG3nKecYt{s&Tv-g- zu=F331Yt=8kQJ>bG4PYJ8ia-$a*wEB_doA)dwp+IxxH7mw~@{ zhLKGyFd*oIOP) zSgPm3q~g&UGjiCk-6Xt-RyFAq#d4XMnkNYnc=(74T|&m-3YtPa`bzW2Sv z?3LC6a^A{LT=zlI#@c!oCnAv(yVbI;R`L4t_KJ4(Q*@7$CdDutXE_baa>Mo5*>Ig| z?ACfnXDy3Rne0m#x?s>erP{I_;a1_lhh~Lhx1u=&0++|?$<5oOU|Px zQA5&NzCJIiUoHqyyH>L?xJ|au9ygD@&JZo#gR=0V(8-n-oAia-wN8fbZ-*kZA)PWLWol^s+;758a5Akbe8@t4?g>%0A!x%_sv}gM^w}5Q>zT zJDil)P@`7!Kd0`h=YRR^QQzaQdNIZK1!L|V>}`l3gG}#epYE$gSAE2l^>G*H3`*RM z$(KbQYWuL=4{@F~*rhRAwm+ zQ+c{bhi48me(Fd@)ZG>JR`l3xLub!lAy3UJ1ySl9cVkx?gX&SvD3>wt*x7{-9g!tzh$lh0>w_^gMxAV!y7yaSBkE&rM8lykzR!+C z*Jm+{mTR<)T2$c^(%3~*~i2eL z)bGo@-m{FqJ{`(bPTxC=bwjF2jEzEi>j@F%hH#G>{qtBgM;MB4yqj;~+iS)dW0h&I zi^TiY~pXr;EiK9#A(&^&hI4u55 zGJbk-M=-^E%9bRT zk8~$QFL5uL3=uIY_g1{%KDsRxLvKPZza1ZL z&r-fdcC!R$(PC3j>n)Q4iixt~$+|?2t*>VH9{RIxOMP>GZ?CfZ<;k1MI*nf9!!pXQ zY^U8&YzKHb{jlru63! zGlsLb8y2PZC{#Yz8%BPmOl6kJj_C7*!qtba1Ix1XkqVKJ-A7HYI~t1ePZ>MD1>P|< zTf|i|$?0<~^>s5-f=}Yautx^HvY{22<_wQx&hSHBIw}q2n{<>xvtb+vW8vn^7~~YS z5Xh{Wupf-T3+hN$kDJ}@UFZDadZ(xdLVH~w|qr!XKUMiC`d)+lmSPA4??G^VO1 zck7LI17G~jC$P^VaGYe^*Y%c-Yn4gSU#G88XzP(-PZ<>R+jTcXoYim8xgFS2KkM6Q zjNXYCU*5Gi`s#1k-_<@LuPU*ewf|zttdi-*#x;8-OeN{^Ta3i2EzLk5CMs&7(?!T( z$qcE&gMGi6H_KM@O-Y|QY7g%4i$DW15JHmu=WRMPx7=T54!v0Ck~WkQ)Kxr4KV8xN zl1FUk9X@35=64gXW~{}!Ge)B`6nAYglEXys3qcWvaB=G$ay-k(Ey75X>W5EN0t%Rt zpKIvr2IDdUOj1)=n#<>c%W=zNj>NNw#3W2WJq)yc)JDurZ0iSOIgd)QJP|{ zN4#tTGwDQa;n8LL9K?O^NzSyI_6%|g|5PL4cjwa0um{3IuD3%J*7~Y9+J#@CzNu|5 z7N%(H(Jz{Hec7kz3)xDRyUZYT*gOu2_rPPSvz<0<6unbak z)&N@HZrf51G7XQ}UA*$ZH=Xka4UTrkn@=fjC-Ho%?LUs2o-p7KeZ7@lhmXk0{YGX! z3Vtte9Pz8Xu%;*7dK${uSc}Y%4gr*5#}nO*aE8Ic#+=|ustrYT=0joL{J4r|1P{AX zqH*k*^kPp23{-Y9*bWSOaVe_BwY`iJ`uM{6fjY#+TIu5 z?CQ#5w;@P3jLmBciBt79mlm%#(3qqdOn$HV+DeQwt&#aCxI{xrKVQ`iSIPkQWjS~0R# zo|WA*mUq>7#LP@S*q6Dj)s8kml&Mv5z7wSEeN(eW{JZjbb%)#nyQyIzCpTOD$MhlG z>Sb@j-f#5_4~~o;+{K~c*>Q}D@8+ZC6)CS5K-a-Q=9F3ZHj2v+wxtx9LHzWg?`>MJ zp&9cxe=aTldxfOy=?!STDn_nYw1dXE8&hUs;ue?;*VmD0J_RW`sbsGv-7P#NzxPfJ zS(RPwdDZCR9RxN%xv;t1vmTy%)75JURB9`qQQb>*-@TE!gZh2@y;Qj&uU_d>uO1y6 z58biV7c>nilv?}bwB{6$VP%WbtPFR$vGmG`<9??hX-Rz3y<1PrqJraV{7$u^OEFeQ zBj9*v1mGJ~O_hBuW4H#HSNj%%WUu-_MT*3&OS)*gp{ zLPAv&aV@z1aqzj;mg@`c%E{HLq5TPkRgc0U^5ujO>%Gj?7+Fbyp{2)t_=zVjI8VCu zJ2v&}pKk6I5X#BPuu0iUB`sEmvAudwNJ_)@`142*(Z(n4I=k0JP4W1+;xuGpq*1TBua)PISQR|_I5Ey6e*1)_FzG zX0c(fA8(h-@cQT)G1OqAB;UG+<@7#W65abA#QV(Z`TD|bczVnXXPJ>jG5BWo5bbB* zZV!97F;dBf2Foox8aRr2cJ#$Tm`9qcA>e2r5pcp<%(c!l{1oEPO(eQ^Lk4@a$GXNz ztaj*|l;;!CftpNov+A3T2n)M#WXVA+qk8=~)s7)TzkdZ5SQmXM7^M8`4`7||> zJL!puzhX;S>*>>buH{%UMSCO*SJ0eiBdFsrRTPOf8xYuSg&5Ckm|tkD?8=tMqV_|* z8=b~w+i*#ebl$T*ud1hOcO5_!Q04NT?*VjEXo9mu&JR_|)Gp2y*)P^7mwCTL-6fjw zM^8SGu7f2Q*pz*Y0p4x6+pO|vqZ%vS&7;*ivT&;5R8sqTv430rnayhg0Zu>vf;VR4 zc6fPnf?vmzr@am}d=GU!91ig#m-1mHc}QJh5mn!(Nr?;|JVZ+MWekI0HjTJA-q~4Q zTHV1SoSmd)PAm`3aKFb=HI08=H{|m=vP0L3d&$b}eU7kf7b|Oo2GwupE@cbRUj8Ks zjBA0fM+bedL`E1mw7S0Inh6$S8a&QIUv;M*_4 z;vT`mHaZj8oixffu5aJdr7^&$h%;$!)P@J2xD~O^i4EUL^yXixm)R!6p;0rdf*?;H z3vkE5GU@rH)G9j;6j8|{AAQr1x`FHvquLg#ar?C6;h2h!p6yOnR)%wFY5B!44bohi z?0oIe@<|b1ntE?xkU0G2gYUYQQx=8WB(EeoquUQm!j2O7o7P)T(V4?SYUU0%(M->$ zzQ7#Odh2hrME9EVXc-BbFS6ft?N^>3u6*O(^E$1F{)`-<==)cN5~$~AE>|hiKxB=; zd^XumXZwqZ{nt|OoZU$L2UGYJtKQe68lP!!Pw91q1j;ILD8}hoRgA61p5hKSqdtp7 zGPjr!l{u63SCc`V?aa8f@!i4@vuD779CZY8mocXo3;sYM1K}DfQ_!(T^`zWo?ekHdZja8aE;gS^LC@ux_C`+eza zs2(AngUW!4h`>l;a5GBqv*-}=YaO2(lB6^0`lO`4qdhY_{$dlzzOQ0!sPn{W zPIxCL(viDw>V$rP?en?pd7iBm)gy1>jwL@3=vx@VI8KHAuHAJ7S;&lZg zNq~2UwZ5F~g|syz4;H?s-|hG8N_zkk=~6=V&cmv z*TN=i%-QNVR(R_HmY%jEtFx%C;s{b{NQ|Uc6| zR;9t}IoC>dG-so3x?#rOS$p*zKVqL?JT1t{fg%w?f9=)9rfONm>z>^uyInC>SNHTf z@nc#AZUxfgYx{J~%=__J?zg-wP(rY`iP&NhUH4MM)s5*ZmSUzRn3s7bU2djp_`Bhs z3=c%r(009iQav{{p3o}Fp0wUSLndx+K$hP@6Wcdwh)$U%}<2FW@uO^(JV*VnOTzGe5L}<#f~dc1Q#e= zTZd*OTh!Ea0@Lz)wfsK2R?j&rFq}>d-pMvBTvI;68M7KEi0BrO7J&<`vwOYsn2IwT z#%*ZbNvtluw@^(-dRuQLveBgvUvO@8-pl9C0qnH3u3MDE{y?l>D=f*HzDu_Y$7whG zQ!xByzj8qrnvW|g8N0{5vtrLhQF4a9?v}6uwPec|p!te@t#R%6#@E(mZxwSZD2zU`L7&gA*VpW+;F+AND zS~h-%mboiZpk=_*%OH8<`b!6{L#m}a0fhL>(r>c3s&K~89@d^oBc5FFev4T35a+qe z$gJwjNX9m~+O#A@pZBVu(R2Cu#mTg5nWO#g!3fbay%7Z^*^(LS!Fr}L$t{en+}Z#i zUzwYPHw--qg6igSHJWQ)H;45@Ul2#bS#T5FaE=B`tHO1TjJ=;kWP5xSnYELZt!=?T zeu2ra8L1jXHx{LSoPka)Tt#ju>HV`%my|{=DJfa|ay+ts> z%6Suv)coL8pNMyRG*K;vAKgD>z-7QEknRrK#dE&PF+qM;^k@@tWMU^T^~USXu-CAL zuE=Yz$0qvhGa1$q<&$_A2gGv%Q^*yxWgM#cSv={Snp6j71SnMYug9)Y#_@#@2}IUR zu{k8JvQz}5WsK1I^hBK8^enGD4@Ng7nu;v8@~8|ND?oo(;6Tf&rf7CgkpzyCgP|Q| zW3&CaeS@>^<0BfEv>~VDGFi=FOfscwk4%QEvvWIP4w`_t!F+kZ3={Ojf-rj7)^dO< zw~Ru=>lGj1 z@#86@=?IV#m5)BBv*1zV^FVpBzbpV*lVe+7b-o_%_0`LWu)erXX9ht(5;h|CRXuc# zB!At*uW`3Lue?a1V7ugt>}}@vXI+Pz-}S$*GC;|a32dJ9@x4WU)Q_NK|Cp#Ce_!<2 zYwUx!vb`XqF5#x865YWK<4J=3}U&Q;fNfzDGve9ER11LJJ1U8`J27=-*(Ol$s)j4Z{qCn2y--VtAuYH3i`Zd z&^Wp|zR^pZH3)dkv5Sz_C&bpgx zAo&(hBGjg>U>eRZ}Nw&IOKX8+{KD-uM!r`DeUcubA=5(Dk~w{HWxp@k*>-hg#%s1^VLf z(ib|{`I-Ygonz_Rn0ttdhhl5Qx+fohqfy!|s4I*%!n1y>DYKB#Ug+8Ob(_VLEWiI& zCD!g4bAstdO?SlQ&ahm1)rC^>0cHbUW=CA4QL zCOdW)eR3~|S#2k4FPK%m7=aS+2?3foiGDy{Q&+&UqTD;4f^)hFaI9Z*^JJf%jlWhsrB^(S7r zuFF8NdCIkj6!0hm@yoly(dUwfEsz2|x~1YNsqfOqM` z3wY!1=8ogR%T#canj?!pIfzu*&MXf=YyTq!l>T5_%}d_19i&L zNqU*L<2>8?xO|o&wo$LdH~W*StKu~&tlw)w^Z*^F>8;E@ChHY z&A94B4NbLOZ=m)Fs+~+_iBy>1A7wxeu6uT#RwvyS);d`}&*8Bz7TcTW_Z)Xn1-))5 zWWJ+`g9KZrAuuPrgZGf-)O^tudnH8O^sZ4xBbSFa78uuctp?^I3we5iN?%*fE+^5ZqG4Q*(Q5D?_P>k%bX|;>&zhWJE5+V*EjV z@}b+bXZ%v1thbTq85g0*^gANmSHwanUkS~yq;gab=L&>}*NtaBEwD{e+nfv1i3^F? zFe=7uF4cTrG{? zbB{)(R7h9S@T_L;OY4u5zG-3qXk)v;hbL)bNYGxa=G|FDBcxQLchr=ESuPsDhpHK~ z3L{sXOdu{Eo@GOespc9U;r@{=oaM&e ziDaWSpFPw1njs1QX6P=Z424AQuKQCL0B~_?br2&#z|y0M(~6H>1LOSoe|Y`Dijpqd zWlwHzEMUn*n5b9jn8&;G!J-4XRD7esnGkI^(YKj03|1c9 z?dR;K*UxC^v(V(HcgXs!bYu1P3kJl9V5_mPlX8YbwziIXsSP1N@h=Iu$|~r5_iZOB zEuQ0U;``vjBazc-EzUnwH>|n7$KQTza9mojWF)euMSZTQv_Ac$f}^{EjHyo|F=&3^ z`2rG;amACa3EyE_Ul#H503(1lsx5K-&9HMzFLe<0L}bj=&eDYn1vQt25&0LMx!79? zbOGDIDEiyLW3HJ>DQGqT$X>=}h=-)v73utV3Vw72fRbfEEmAI@bamEn2LK(*J^!mm z-$|X}dNq6ifUOL03P0w%&Ghnv-&?yPXy}J>G6F%F%(z~%!4+;&;JSK0aXa{QFsd0s zMYcuwr6RhC6Bbe<042)v1wJ^^NSFVQ0q8Vf(q#Sfky<1zAh#VGv*Bmf<OdmIq(;)9+g3x{RNyei!{A!DsVZ2ucAWZbQ=S zSxheQGwRPL+jX5Y;eKD$SfV?h zN8Ko9M!Bkh4;bL$w3rgWa!@1_65|xzrLQG~rsgu%!q$<0^g1UAweBAl- zZE=8)@U0q6cZ9sfzFEZRUDd|UurAJ;`?%y3P_0!N93_Sx$GEry4E%lp4!yoUS`Pau zU61#ozV>2W`(^5{&GRGA>IFlo0CxMQ{RuD!QDVO0Zpx@I-TBkY)5~ATqzXjm#fR^)NHQ`k$GvZWCOzu(F+QFf-cMq zY$(;k>7wSb;E061ElpF+RcQQ{7>RrODdV%J+v@%Rt0-! z8w=JF9G|8{KQka%FPhPMna{EA-0^E5tc>&8%#lop*qzjQuaw^L6#y_32YZ`HJlO$d z^G95QAAt$L@DKn@%lINQq!Be;qqG!%mAJ)XEa(W|kV9#6WexRSNppQ}x1NE3`izV< zMG*ktSx1Hg)YZJ5NRy-hd~w5+g6wk}Q&e;e0MPOq53rxtsAs&Rg+KjHg?45o4&Y31 zKMHLCa`T-5rgf69zd@knM8 zQYe5MQcjNBi(Tst)8TvBeb3YdzW8lr`et%7a^8rz+Z^4#DECryrjntA*9*LEE?Ei^ zgXg&)oPcc9aG9@!|18z)0!Xq8;l>W(R|OtxWq#tqrx9SIhu?|u!63q-VgLYA3{Wec z_NdEN+V@HfyANX)5H>ajGmuIEckM#)_TGk_i)o&YCCW-GO18j962Ltu{WigiEc(<SuiOwkP0=PAjcOih<5r~0l z5CbX!QY2RTH_5az-KaiS4GX7qIK-Ca&&exAl*~urs^>G~woNwEvNSnis+WnpWEXQ4G1z z0;7$Au|j||@wDJ@?+kykXIIv|UcZ97v@1Zv$V?woXdZgb(HRs>Th_Ju45{!z~%MuJ%dvuL#_}(3~Vdu5e-S>b@v>31JS2pf%RS&H2 zHv7^>3 zQH-w-+AR;@JZr&2WEBIDRXKNE!~~OUK@G%UD8{Pb1m9WKKvBwugWbK^3>^QW_RFz@ z6!iMHU6*TTj8Ty9gf`7AOFc%b2Ag0jgBLV@rsJ={&?rf*xqlUJ+Dq(L8F&eE{2DD% zQ1UVcca-A)v=AU@pzdh+-3F%q{Ox6C8xB;%%a9#sI2 z-~{+A$_Vjnxh#QRgVcdj?O&w-oJC6e?*6NWI2y!t2XTx3aN+(<*}vdIpFhWQp57w; zr3405sV(}Q`L_uqC1}|%0oqv*+YQ9-`Y*5{^NPO)4f#Vkyq^8t3o-aFjsMnpWEfQJ zmmsMV2pt1L|C6r>G2%k=1#TnkZNMRGVq!U^vj76szE}jj&4T)}xttgfY^MSss5r;5 z+R(yu-!uTgnyOeU0@@@7LwBhqww3vIh0LX-gg8iOS^_JSKT+}D2-<^j0P_F@DFEuf z0k*rcH{R-J0s-tp;3*_61mhq5ab=WX4Vn~i-&hP1F6(EL0``6*08>f@sUHR*y^3LJ z>r$d?zknR-$Z7-@LiYmE^Bm*yn-VZbk%%AXU5&Z6zZw{Z4*nAngZ(l-IAY?@?4>;% z)ITes)u1)8;>n>hzsOYgk7RmmuT3bL1fX4O|C^S};|Fb;%g+)`fBrf^%cIv6%tKgN zY);3)Tcx@t|04gRFRs2JcGM|@$?T&N=lfxm2IOeIq%9K zfWri#@eABrQ~3C~nH{=Pjn{C~{@!dJu=wHK#=M++g;gK2Gg-L*kR2pLgclVW0)PYI z{b~7XW_2Ib_m^X+PQvo>YUm7K4CbF<}e_abR%&A`3U$*fzqiufl zRurXx+Wgs+X~5p@OO@npp^e(Fe&$yl&b9ho2>@=KA7m!${BnxYb%66EmJ;9_30^^g zpn|9U8r7#)mBa|UkgR(jY#Xj}2q48>&eFtxvJxSOWbB6#Fp@c&xaAGiZ(P~mSUc1-?<;~qEd!B;^1gWdT@n^Vv$R*^J*)Dm`DN6 zOXFX|1t8@CFiHRl^6u3Hz5K>w2Rr{N*Xsuw1u{nBKbeYcXYReMw*PY!KG`d2h%neaeZNG&Mj&CLHT;zy{et~F0|O)ZU7m>(!~YwW{N)8i z6Pop6F7t1?f7Sd3_)`Mma`6V^izWVdG$rv<*AN(6)}00OPnxg#^MA7eq6xx+?3nmZ ziu#v!|H90W`QNaJ!Vw$l$F>HA z*tE{eU?@P4f8YQ~y^aAiv^a zx;21nGyqvb&U4v@5M3(5Azfj8@QBNu8WD3Rd=tw4%(P8SEqg>>lytWb;2WV|Qx^7bz?eOy54xjK1uJ zE!B)@0HLql?nYdz{o_mql8+>>M`6V+e%Igt%9}3ZGCi&P*Y2R3JJa(CdMa`<`o~d8 z=jWrQ`@onqr^}r<)1KxizsPd!|1leU)5UrWn7MKe7Jwd@1psOfwc2JOg8*QR zL3vd(gWresW4RJ?ixGQ;2CQCkjvpi~|DT)#ZqJzSAXDPoi~=v2Aq0=XojoM}2LQNh zwFUr;q|dgfD3^L)CP0J8IV{AnR&AvwTJgad1%vRTi2=~Et7=dJ%B==K8vy9Tp9Wr< zN#b&)?S|u31ZI$Y^8ZOb1Py;{aOE1NC4lm`1+nq=EHAw81AOf1%9W%HxWo1STbt`; zU^vmg<*#&HqDwS_o`XT~^NapHYoa5lnDWBaK#6_LD+w? z3L!?=C^!=+`(3mt04Vhj-Qb%8AgSGHmv7lYcfTxBqA|KB{^`bi;C1Ckd3n4T zfEoh6>Ib}!3;w?vDM;Q2@yxYzYIh8ZOQFtKho>;0wd zN6Wu|)Ab+!Quy~`W5Wgj7`~*0FXCwx8-HXx7*yYtV#pztSeqjsT5(Kcd_-1zXwe5p zVh>_2j2ZP*mqGV7<$&Pcx~Fy`k2nN$&dxo(gNTNoEiezwk6Hm>$KJ90nQ&luo+O13 zu4z&o@I6h^f=rC%p(VhT5rD2Sp4IGS%5?uTwKex6dT7B!>B~1$@Q2hIA8(P9kNZgL z&au%O<<+m*!;uR>AF$^7Zj=EKjSJ=9vs7!jQRPJjAgoa@76Qri21MS1UV)uw)cYPO ztd#O+zue9MuGYQUf07Oiuz8h%ok+{w1wf)rAQ?@5PXIdAu-MVL;053ZKenRDE*uEKSBbH zms1+--*^9HqyMYzFB05an*6VEk@i7Y@Qn)Z{z*dM)~e$p_*0W$PaFh5K-~GE8@dF* zB9g%AWA@|iW)SlTKmNSn7UFoc04$VTo2E-KWOmvN0BNf1r#X-g004Kw{_wxdL+Bj+ znc)Px5C{M*u>A)O{@C2vYjpv;8;%lcJLKOPAwRabNN=412m)vvH_nSWPgJ8zU5STH zv^*S$o2q$@)FvBOMc0*|!2wESv7b;_82~u({$=eI>;G8?dk&hBE1vxR)t{IUDWbv+ z^;(4{O+p7fk>TB63SpiaRS(nvAP0`V)&~H*4G1j&)j&<6>kk2h+ zcn@|DO+txkHYFf>TPmNw<4}8LrJbP4s6p1z5de_k?6f+-M+<}rV|>*okC$@pb4DlR zH0$tdLxSG~5Kdn_xNCv@@iXdn_@&iQ>Jd5@@U$rU%LPm!Z6$g*!1-qL%PepJ0DMAV zpMjJ6wizFiRNzl3G;m%3fsnM$Kk>}}!g=7LXHH9bd1nJ=zoiCgzEnk-L0Qg&-6_C| z?)>_eZ~$mM_}-6~aPZ*rdkNDM2hUgy;6(lj4NAavm49Y&X&zVuMH;d0_#rha^g`~GEv_*aEQ1BeR7MDN`Af1o?KlIAaf-$?&gf^O~yVAp?4 zI}q?h{7Wn7*YEUym{4m30YPr<`V-;&QO9pU+#Ytmkyqe|{ZZ`S6b8dVOmL^y^+$^N zMRJ3O00PK{m%f3^(Vs}J)mU2DEZB%@<5J21iUI%ze=`P(cJ)q%Uws3h9sii#Fu+J0 z#0M#^EByZ#io3xKHsGI~5G_y<>mz3-i)77;()N)K9Nq zfK%1qtN%)0+t^_(Fas1WCmMJv9%A`lSd#2bRYhmaY$o9iJO!VvWr>VpVDAGz!JyeS z`7G2{Q5;s50E1)nf$Ini=wCb8I>p8xRde|?pD2Oq#v9aXI4#09V&V51N#sVkEOK+-%OCw? zc`rK*Jg3fUi2d{cN%(1d+I#Q^3EM5Hvde?9?(K}LD)npckw-N^M!gznmY1M=L6Ee` zKk?H8I1Sv86$AWPAOZ^A_Dch3Ie#|Wjw=IX!~n**!c$H)EThZPy@r72ruQ|dy}1My zK4zViU6wUHnFN2oIRDuQLRW@NWjbNr)r4) z?C#!%ZS{8R*fjfKG=&-b1hf0w&N(&|&brcWrZ941jpM!B4>= zbY2$HgWYG`k~mpQ%I%LYWzZYI6$<{~2f0)_hx_{aS)u^f!5Zw1wr}*w?Mx3aXhwoi=bHKWk zSgeK1lU7QT%5>Ro(0ht~QWK>CVg2H1Gqt)TubD50S^5}D-C7K;LsPc+rW5e_W(@A) zVyGIi`hL++jcY@l_BJ=*UX3=|ow~9gNh6KXB;k{>0dnotNI;Oub}7tePufj$WDASo z=_Karw^$||WoVxca5XpR>H4CnejNzg=cRB^f7uk7wDhL8ya`q(?Cq-o@QBaQoH-uYOtM=*%pA zBX$D5qOYBsOLo1yiVt;GEDo(xN&M!E3_VO9#j0LMHTZ zxzmJ z0yA=yA0=5H8SBT6cPXlWBMw7-P-wc5A?hd2Cgfvv$gsZ+{T8*F%A3zZ{z~_?C5o|t zq(hv@$)XY|xdpmD;+O=F3(c;4va=S40&JJB_a?njIbw#9lMN~+yY_iXlvK{WRx3+g z@nwbQ$F|NK55*?$s?7;v%FqxT0WaA*2Ew@jR!6a$ub zc^G1qDw4(STaU>1eu$}%dn|*I970?-+Si{jT}L7Z1k9>g`sG3Nfmk)~Aoh>NjX%O4T--UO;A%o!!Z zDj2vQ$pbLV2A{7TFySrLPx@7oU+2&nJ$=@aP0@~|P}OH;b!+4sA_3gdFu@+gr3Yu^ z6DZGfCf4@l&CMzlbk+$T?DgVI?eRfG(D4U9zaX86M*mQ2%G9V4KKNLjMUf~8o0UZ) z=3!;^TOe;!PZfM7K5Ml^!Ro6c<*ko)j>`)RwnZ*u$2Db=YBKwXNXqUeAruVz#f(#h z1*WDFUueesy-{2PXx9V~WMk5Y&&{ENH<%UXn6Y&xEkn>bm&R|!IXR6B%=V!x&AVVK z2dRfzkJ_qEQLw(}*3igV$}N4UqhDUu_CkEZWzAnhun1wXNAXC*FJCaxbVDC;LHM&M zO9i%rgb@PSu(UR=zJJPD%==KOx2AVL35yz-s-3g$EJ)F9TDNfVX$WcDE(?0h8d{<(U=lyBw zdc9#S#5_Ic@sXPq&F&_26k|i|smRMZ`g5b9`ChX+UQiw!sBMd4Ejc|lmMxrE%E}$p zqR~07S{U}MRo%X&lDo2VE|{WOeFS9&Q~OiDQzc2qD#EEocb()i?k&x_S2%I;ab?*! z2dC&Iy@Z#C|gq#9*ZQRsoDd0=eOmzR%( zDVlEMdBP;M&PreRmidwrBu!cC^#o4o@NZ!>zmr2X;<>$IK*;lUo9@j!zh-ojn`X_- zRi^uWRg(t30z+tuFW!n33Cr_;Oo>etdTAteph1AJ(i^A@3dAJ6U_G|+MTdt9p#BPx~l&Y8i?yy+xz;937sO;cL1 z+{8}a{V_)DXv+zPtoj7S9d{%ZiB$T9mD?VuH}wl)ebIex#YExBCo^n*Iw+j3Z{x%a zxza)!mC*7Yoe^latE_njry-}~Q9Ml|3-Xb-SquL>5xg20toKe&F+n{mmTNV@fsI&q zZS1VIZBr=EA@b(tZ2bKyfAw;xjE)Q27y_kM;zRM*BSpH~c^P1s~m-ashox{Q)# zvwOo4ONgPBa{|*dC8uq+X2v-wA^mbz(a3ezbZQj+@173m>l^L;O_^mc3smn&knVFy zJSRHJbxRcJHF`NLKN8 zp1R8)AGDUwwA~Ta$1)JvBCW{@tIurIL^>Q~iOE78=W?X0zu5vl@oKj1rE1FH^m4Ig zn-rVAsXfLDqpqhjNLVs=(AcCT!>T9G#7mg$23soHQ~KVIvd@Ej+UG2ro4DAv%sbst zTwnN?%H};*z_F6RSL?UoJQ}mB$wXv*>Zyw*zKWlEO||x(dt953OZ&aNvj&&CYKn!H z9f5+?X_p~Oz9Q9f#8vrs+K>`ef$jw?_lKOYk&6Cpj^M} z&=b`2@x`KF5$@y1&ggmA?ORIV($)no&mpTein-idpiu{vFce%(dS&nKPgoPD@B_Bp}_3Tf#k@z*UUAo0D&>zd}> zxJ|s;bnza|cHfS=0-~P{oUUG19E~QTmW|FoIGM>@r`y2MWo*XxQ5=fGdji<731*@S zvHLuNuhg%a%n}#gICWW1eRi%}k3E2^>L$vgrfc%tipilsRD@$EkK!(2MeS6{Jhj}D z9Z9%85@$z-_ATKDxZ}a^sERK7^CU|0<{-bGyd92y%TA#O!^a|h)2_JQ)&ZZH z@MMuZto4@S2-zrtjTje9{G-*QJ<-%oj5(#%h^iVCVQK+)grgwSr7Gqu>I!2?+=(Fn z5(iScA)B|SZ!&0ydun(}a?bnZX#HBl8B^XzKISj2LCRkrd8VYPg*(sS=iD%H4})4N z5UsGmT3N5o@-D}Hiw7+oDgHwbL;2iVfe-t}n4)r);eyfROC7b|4`%L~c;J4&3qJjp z^Z!xy7Eo1vTOa5?=g{4q(%nc&H%dx}bVy1!hYpcWmF^T!Qc79@NofQTDFNw{cpKy1 z`+wj4zBk?&dmL8I`I~d^HP_mQvwn-wGdDUDqGKCEg^J>$brhtI=&vN!=Gb@|Y68)w ztbY2Sf0ZWl27VIug;ViW1`FrsQa+ktJKXrMq-s)C+k3{cDb#doaOgcqSn&+Tg)WxAc@dSfH~nxNgHdU(?WUaNwZ!9W_-}Uc_nT z&+q1%TRfYh&P)$7Y^|NrY~jSl3f+Mh!|% zL?tt|>8l?`bVMTvSE$3@g}2`4D&exx3PE`FRdeiXhm*da^(YU9`Vak>d<;0(0LR4g zYN+0q*usFVf>WFnbwR%~s=0Oprj^QcTvf?$Us89FdwF*l*(#uq&q!&4lXqm!b)4RQ z;Lo<39N%|e*G#tx{Gd%_)^rmWG$ZqMkfdPX^uxIzXRHg&crW%qMf228#?L5YR;4dQ z52LP-QLdlSD8U_s_#?Z7n3cLHb3OMJpjxAni#ColX5-u~`U|X%J31AGU#T{`UL6{5 z<*pN%V3Y4x<9i+7Q7WLlVe#$G4~^GR-n3wicTi}5rK)=(v>!rU89@0SMWQ~Cot^!w z(8*7QMJzeo++B4m`Zqs6pJ%OotIv|BS3pcFcy~>TLR(@|6R-3jUoM?PvBn4Uk=B7q zQ_x+eLA`GMC~}XDJb&q(^8`Be;VHR{4kb6D{cS9PN)=$CqF{6*Qk8LLl9J^fvTT9{ zW@dM=``hiM-VWnPwvoNbMR~faR+2UUQR|tI!Y1!aCbfd2rx=Yo=ZolQ@6fa)Sv9u> zA=1#EQo#_Ba-|xxZ-%@3QBLPK@#GO>pLWYOlMxP{AW-yQF5O*xI-kSA%_j9JFU&Yl zZ$M|qde|3-u*?=oD$$eyq5k3r6kF>Oes}8$b*e=KS86Kl2}UAeUBQHc6RS$OjAAqW zPu?GKAq*B1LHrzdEE5~&mCM%v`!Wpt`+0s2*ps{JNBoZAMp!35$O%pN*G;*`M+GSw zETx8A8pv!D@6SOw+pf8kWNs=J=j$!rYfN=?nEy?>O{WdflT&!n~8YGl04@u`MluTlh$6WT5 z=dYY?kzrpYGMG#(eu`ub9bBrmLo?TF30y^G;+ys(+wk0A#She8JM^G>?avOpnjF0;T|=uSX$(-2`K{r|5sZ!q4t2r=*e=! z8^nkNQGVYC)1z9a*9~3Xmt>5Kw=P zaHX}ppZ0uAhNFvG&Wk##0@=hFi(b6i~Pme7{-$A$`df8z*l3SVMNqgxP+k>{XBQW@XZY%))FA zTwMPT#s?8;sH+d1gc` zv&$dF%`))bAzRgY#UY8_(1E7A&BK|cct5`59;K3l(ol5FPECzu=e~rky1PCx)@7DW zuv>oT$O>t}yNnJvp>EMTFC4Av@Mz*R0}mzVOey6T_N3VMn^i{mwC&Rt4E>1JUVFS@ z^+?Ea8OTa9(yeH@4;0UH&>sI47)bWiu|0mwSi23qM+8G_a&q<%}wN zeD|h_eJs$EvLF|a$JjXQm+%qUneVzCB67iSk%-`V$Ywx&;E)(S6*cyj;FLWx94vzfbUJ?Cl zeHCV*pcyNmUGc!E`0a6HNAEhVRXXZVFNZ^ClVtjg4N^`xfdwm%(yZW+qdlTkvFT|k z;PHCn*av@ve2uUkgHNnd>uKuB#`7eoa2H1Qz_g}-^&?^wZ(?(ApP|)zfJ9cGXSr(O zF(buje(8mMx+J%dhcSaT4yg{Xr*dc1fLEHkQva~*KK)ynaFiGK(%|AjDbXDMVaM8W zlEgw9aO2PkbE$rP{WXFy!6%;X0?5Fi%SqWpqo?(=f}1hM^^z}@{pYm-Z}Ek(-Cj={ zyTj$gO!S3t)}pU6uBJ|cNV}*pnM4!9A4XbhO2i~lu%Ho01VXy2KF%2i!dM-p^K?u~ z%lE|!-OSU8sU_7nhNWdwYCpzuDUZ*br9QY1Oh4{V-3gKwQLi)XW=a|-K65a8NNU|?0@HfQEfq?~$x%PFDi@OxkIQ1o z5y6EhD9lJs$W^$ps;G_R_fSo(Pr0#ho4cL;O{?%1&v6szo=bq5IRmr#iehn*NWl6Y zI=0G2Q0F-zod9nmVJ)TkQQ&r3bKNIu=A+ES!_0lF_|*qLc*xuxW*9dxmA=M&WT-}c z@K#E7JJ2ivQ^jrns^DyY6t#g7Tv%l>)NHK`KO%0&lsrgV;9+e^?O?huJuO4ri}`r$ z$qyZN1%3A~k~)E?BxzhhJgg*srAm>9X)iyQ-bH1Z(F}RNm)NJ^^{W1X^>)a;pca6x zmeJtkFh&`{jufk z>%!P^SbVFh5=&$hULs0TT0Sxo8d_;BLXmWY51zMn?$oTgvj}d{V(%B?Tv-nvgw8&F zgU#B2HwO{cQ;d$6G|h8s-aOT&Z@jW6Gt9TkzLVZxomowPJz*fd_SRfbO2*J&T>&HG zLL{fepyQIH(@89y3TKOOmeq|(4zrL_J+$7q&Vr&+lFscaC}f)EXoq#DeW00KKysW4 zr{Ru%bu;Sz^K(*qC7h}+9&d2E7P@QNLE5Br$rT2-?dFlU94{~n5pw#EXHCT}>A2@# zzm*hK_*RwwA^A?ErwGX;zy4)@w6(qg&QW=fvYlU2UJG~T1DdZ?F~tXNv1z;%KhOOw zeK0K>*v&_5WGFuqT1W;;JW77EFt)xSj8d#sby}^x+ddJ_DZRl*iH?TvRU#0r+BS@d z;~gyJN1~;_F>_IH-P3EBshg_cmp^k!eflB`Yw6>l`rHRX(ziccEVkY{j`NFBbr5>C zU7=mif6t_eR>NCQx$T{LjJZoMys0ns7m4v6Dqq zmA_R>TonOa?kX%1D_TZ^tz6}(vq8g}Z>aR`yKi)ABtIh2d+(j7CBHlKblU(f4;ED> zIyCx<&qWGtQ95_&_mMsxlH4n*jWN1m>$gq0^7ev8WxcN3(yr(8f7H>N#ta+A&uozw zq^CKx@Eemgm+Wk55th(T-zwM@LYu5B$qr(p=M~(Sl~2FlQ8Kdgqt>KZlKErgGGWRc zZ{8!OnC_3pu2cyT2y-@ZxUi8ujXnxw>im&fxQ19vKRenzJy`C(RIkoe=U0q91qACJ z+J#cbJ^dLh4W&c#Y`z|(1M1+2#Zj3Tr1I1S-;=gq_XNwpmGE|OTbw==eAx0-Q|@Jr z8}uqUEn2b{JAv#W4iG+ALHzmJ%x3fAw9D=Mu~s?uGW<4gCK)XPoG!9#tI+RdWT~< zaK*9Ow2|eknE1(hKFdb~zVkKlCuKKhiV}-SP7~B_;dOiYsX`Q0EL84n8@03O@TI)< zL%}Z_HnK|+_+AictKL_erC13+pjvgg`*k4dZE5P7IDd9~DX``qE{rNi{b}?48k?Ii z+t|G?rv`T_5Zh@JPiQv2$=}_i=C>EJxklCK{wBELHo>+!*_5+0wiJ!v^L9l3jT4<% z#o#2r5D7NAi^lRm`B=sayouhyg^iz&aFOt~)2T08pe{(=%gpLoV+tSgX@hjrgN}>?+FWpb+r6E@W7Anf;Rd2}Qc{&QYv+ z%l=bqa^%OoabGsk2u`PDFSMxGT=o2Fsv4r6os&3AG0ePS6f86$8F*!5o^IpamZVi1 zSk7LQX@Ro8++|woe%EKx3VUMI2HD5iZ&Ru4@F$It#o1b@zvQLysT-`P;A^r;49%mP zYy0k0+>}z@lyMElcslj{xL2cM6SRl2+@Fghm1x^u%{a8o-XxG-sCo9EkGQhz_O`gj z5OvTRJ@B&{i^k2Q|1(ADRS5?{VZPN#XP zi(r(#ySS;%Sw$PgX`(&7=?@k;4a%Vx-!b^&-NZmA)`5SGQ6*KBBDmE zZA~V*iLq&9BW=}&Tdq(0H#YruS2 zE$TB)D4CPAo<*|y!|8j={L3=o?rY89Z>jFo#-)LsHLOWolgBrdETMJhuGolQg;oNk zBF_nYcX_NSUQ#GgS$&1+JH;Yn`W)Ck%zyOUHXs684Qw}f*Iq4)mXQha<|6Ymisy%Q z%D}4>B3tcM1l0ze*QoXa^13cmo+UilYkGj(8X0o{?2FO%&G;`EdQ_0IJ!&o3(`|EX zK>f(lqh%lKj1|x5ezJVW!u3tA=Irc9J|7nOVLqjCdN0>M-LVOY6d2&l_v9_-;=aE* ztfu+$P0&k*wU%!J*avw_O9A4k5sITpQIrYlGndS-M(UqA&~gUG1zkg8KbvLRNC;%? zsCVx6<4$n9+-tv5E({2^c(;!cSA_XBOj?AQ7e3C z?&x%s1+~Ih@wVssdC>CI=};8u`|=uZz_ED`M=!tgiE^GQXf`-%n&` z3f2~^uv|!d!xXFSCLKde#^rv^yOpg_{Kk;gFQq7IW~H~Z=JoWr%>?2ZDmjwV^3qpV z=K+=ZkBR&XVSLR-idJKCX5}=c6?r=R+ZdX5afj0jMd;nVi^5TLL-{-j_d49!z4W4|{j$|MUEhrf zoMLjZ%u5IEe;!kfLMSQVDj#l{ADhe)6Rp$`{$OB?R`rNkA5mXB)>EvtRytQ>`EK=% zW8HY5&#F za7-CgCpFht#K(dG_l<=(6Z~I2X%?OJmKRME%c<@0<(Cu@lps}`{fS>6n?dao6Iy{h z;UgM3VCYOUC||6Ju;i(3{?cFWoA3)ZDlg)Qx|bzBkIFAzj&muT<<1@)BnRi6N>yLC zjF_(WvvWG0ObK>(eD3iz7wPp8@7^D6Fr%SWfx<0HO1gzRgX=ApP{HFp$L5ilzQ6Le z@bH?fWax=E$~}EN%*biogNpMGHOP`nU|M#F;*pV*X|Yd$Oaf}&Tz?p;kDhzlD5|h5 zxvLa+thm{Cvzt_|^~-2E)fzg$i9gDQepjNn$HRxhzd^XLQQ|t);||MaT>%~KT1n^T zMQ7W-z}?~-9u8+k66Lx0nw$hvGFkMmK9>hYjpBKO`HxK;0w1puO<`}!kxQRX#NyA{ zM-PZ?#4R~|mpz=ls8;X6{}`zrzQ4q( z=PBZ0_wTL3za8ol>S3{m7jDy(vTp2=+@b2uOwqyk+(bMN-+hPe;KEofUMZJB#Y_06 zsY0ACrEr8$sVnQAUHRZ(%kpr5pusxQwe^v+%FE7x9_lM?PsQeOylQXHwWg0MGZc@! zVy60VcRktJLkVr(=k8FdkVM25cbm!;wi;US5iNdDM(cXKZ61IfTQob9Ro^#JqrN2R z@m+!~tA8d3MaIi9UWC36WcW+2XjZN2J>XY=slH1x-}j-fZgUoGiO1Fb!`!>+_L<$R;5gq8j_So8e0Gu4k8fm^mi7 zPng-#rvsm?2@?#V&OG^Cvqcr>Z+31F9hQX63{h9h$-ItLRRhT3^!`Nn=aK^^GMr4)Bjqm3ng4*qnZ-&XLbU9?|m_p9L0Td!IMdE&11H~HlyZp(4+ez-8lsTiR68M~QSa=h;Pj200?$p4Jaq@W)HDt^ zk*cmV(!{Vf7#o(VY#cn;?p6Eol?3x%WNBR$R}Ra~&VMSd%~rq1)+veTx@tr8bIcKc ziZiN5(yYClytZ~;%Qs<&@nmL`E6sGpcNa*lX84kCYWD^S%5O3mf__Kn=pf1#wvK*x z`Sr0r?7PbcLnSxiJ+*n+>oC=$q$Gp4erIoJXpK5;zP^Z54JBDqPUxOe~Rql6*M5WjRnPQ?Ld#@?C#>CL+{7hMrG&&)4F(xSu?wS;$ZmL@?vF|@*WE(Oi2*=qK6%vEAshdy-JOK$fN0LO-uLNZ#(3iJq5}Xyt=489;2}-z ziP6h;yU}oYs1ISlB!9g?|I*sc+&$Zn?7&P1$GPskZuOI;1o`=w3^#UF;$s(0S*YG4 zojMKn%Z#tbZ6%nWzZGyBS^s=ASvHjw6v^cu5LmL&+yJ+J+#?{!Z#3iLDCe(<)rOQK z+m45>uk3qmxx5I`7yG7y8-wBW{k! zCgC|>6IkjJW+CT!jgtc#gzGyNyUsNeh|SuSN~Lqn{&h6Qs|Qx>=V zdLvOKoHseDnL4Ds8-DUYS9&QgNV{>JgvSC}tv2kWb!vn!5Khgs=1!a^Xs^(9@pp9s zsxMI(nL`7JkM-^DhG>q2bfFda2rvqt>~_B{uA}pPZWMTKY$IiA-!i7qOyH zNiT+b=vaL)2s7c5FeqvOC7&z4A=F`;tr05K*S?#8fh0y{SXydFLPrxU!O6G zp5$a$4(s@MAk8e%)_Hflrd5(Yim_NGFC3%k>VC{V4)wUPetNf_hl_Q30|85R);xF8 z!m>F*hqf~K6_QvTq&Pu;go?Ft=AEqg@VjL5{edL&Gn4}jht@Jf@OLxY zC~y3lmfMv-BiN)b85xVFXNX^rq%S}Inqo14J3~*PoN3Cwt7An~dMR8r$z>xys1>IQ zx8l4j_BD$)0)6Rb^x;}G{)(vIPi@tLEz-$41(!17=*P%3lv#tH?$DkX5!O-GLoJJ? zFJ9BTOB$vUaCZ;V;+;29Qt#0(zZ91kB4?2!XGZ)NYqJ3Ok`J@>?YD%QSsPK z-Td{2ls=_fl(mb8h0qEr3hABvhgPL=RvBMrBM0hE&flh&FG1H}E8UmTL*tU@D%LYD zR!+||9BXhbv~c$G$M53Cn1$g)YQ`+z96@5}BvHe->kOVvhpzh>GzJJ-`MXJVUFtOE zxmD;sKW4&F4*qgaV9X;(%?wjH=dcy=rg_zr+-5`Kd6^+sE~)va3!q*G<466(Cu-Ig zy)UBFbp(&0(MUugZZRjttZ$w*P=5AA;y`pRh>-Dry}5XlDQdvlc=t8x%iiL5nWI65 z1xVldEYopOpg!Lze9xTS9~x&Gv%OGpk%*&bB_k3%qkTNB&g>Rs?&s~+H)7`NVdQUP zcb}`_OVrWBBA*eIbM#dTJ{)-npU&7TV`??IzIQKD(obwZ3_YJIH_GdusFHot{#?`~j(a}S6swLSPpKtT(M%&2ns9bgWU!ioqxG6z zQ*Q0+(scCJJ$u&|ewE#4oHnhrCe4b%Bj1HzJixqDy@K+AVfDZ&RwAI;19L)P@Ga4+ z!gMb(j@}PzW@`=^j1Tq%65XVAzg0Okt5`*9U7kJ6)|kbqt`b_jD9a?kzd$CUR-bL3 zy_d;a{wANNG2)n7U*rs{&xF{>qXISFmxleSZ6qbBkKttOvw#h&zi5OH-()yn+#_L5 zWodH_l8K#{!#I2h!Ml%e(0*Wvn{2iT#IGrSBqd*;i5hT(R2ly89!Kq1N*x;t%5Qq% zw1$FFT=Mv!m<%Q+WpUv zw2A~i!tgT(=s#-E7tkKBDwI%DqE^YbJ)ruLrW!(npc;xcw80$NQQ*e?CBH*VJaxak z!mk~zG7ch2Ru#{FjAACFI+cL&N-TOCNh>bblTs()+~lULIjEfd$5I z(|D7yy)~n6GKFbLe3#8%LP?jENILSc+E{j@-dj3pyyQPSq;jf*G!E`!Yr{2Hr=6IK zWWMb*Tf8_lA0ngb6EoTxx*U1x=k^(=_-6z=YQFl9#_1ngpV|fUbj}#bZ@zwPiuQ>b zKHx_3QhQl%#N2Ng_$tV6Z2l^wTJ+kXbQehJN?aL>qd9uI0B zmp$n=Iwkz)`qodVDad=0fChzQnm}iA$$TNXNX%QXN4QTmuYZt5COggV8 z{L1fVKCrZ~W^;{`ToxI@`#LSesK^F~G-N#0Kd|h0THrexT+(WeLyCD`bAt!ro(bK*qOubc^=+GGl=k%h*iLTBq zrghZ@jJqG1#AOQXE|p?gdSkGTDN7TqM^Pqx@VnkVBTtbOzzpm~?xmWM$V8p((Qo)r z(PZU(z2yHyEOFld;+Z5s$yLlD9($}x_QYb<@!B^18#5HDH)oOVE#}jjh&V4; zU%#ULB&J{O(*qvay7%K#{C38~Bc&ZF6EMqTcQ1x$Zfs%0rbu~INTg=_hp+pixS~&a zwP%~WCnBCYC}aW|TS<6*6}8!)=)7O_>*_NJQP~+!;P<+J-z~%o9zgfDKb*4SR6AZ^ z)4d!_`NaE*aB(z+V{UE6;Rj-3kw7NFB=BgFYkMh}*?$B3B?a~mt*{9*P2P%wETXc^ zhP;#|A@}*?C|R%WwAP%pl^97D&W;p-r0xMjyVIQ^s|n{Jhjbo$iAXU7llTDh#TT1% z9;T{;yDf2=PiA5i&Xin)tY=2{Uyt3mWMUYiJ@YYlQ z0lo|&Rjb|z^IXY?j2Lm1nNNOX4&DBESP-?0i5Q-Ruh%n=V|BX;WBLtNv}}|3|8Ftbx^HS{j$nE>)XEQXF#4bVL{&ra;kb1Em#|q8TRX* zzX_2>zZb5@NhRoC8ca4y_?bE-@es(kwM4l1=it>Dp4MoxYKyUZ_dQ1_$ZE?qQFTL~RV*Ah zkD`qG?gd(L)RuFn9@PYbzr!!G&}bSdtjDj0ghLuPiDp{E?L{QkKEPjsZwxOgd}hDZ7pX7k``PF~favJ0UFFYPv|H?%UE`^D zSB^`Qe#k$Jp%uZvYfq!- z`r{dnU9Hp!?)ytG6$+M!=fWMIELuF*#95Ifl4&LrzM?bc^uo}WdOkLw5k^9XrvLfo zOHE4M(3thZ+@c_Y4W%E?qEEnTR!TlNt-PtfVRnyn>HNP1r zAuEwrCn%g;$n2Al;q{~Xg_uV>rLLzm7eeG$qeBXU)pt$2>E+Q z-h;-8H96jOZ8}y!QArHJBdCOKK8qrH(W8irijjdK9n0mSTzpzlpHQG)RX^${Yz*7N zkNX}*?D1JSin}#kB5~pN1?l$enzm9P?9pgx=ykAR*}Ktg_fDo=rmVp z;5*~~v7|mGg-xVzf+q{VcX?-)*}D-e48XuFDOTk$Z~$X0<&d=P10k;yfwBFwBA(qu zzF607BqR!I3cLd>B91F$iU%zPrfMo`$v>@G7EagY)S&_@bQZ=dDUIK%rxt$7St7*( zS^LkS6inaP5-s~AXLPUIc$_90P4EXY$WjYcr-{zDE{}D>tyT9ZE^bP0KCQb;8J@gN zdGMq3bu0bzeII-YxjYfQIjhB{ZgDv$wU+^9t&wNTC{y;9Qtr;+8@X3CCWS(G=mR2$ob7w0eZ22_J0?A3?E6qDy##Hc zuecvXPD8rIc`-MD(j0M-jQwQM@xCBY%{! zo=PM+&^uvk`pJ=!&p?veyR!*dV#95-kLIXTB0B#Qjt%J;lGKP^D1TOxbb`^o@2g}q z%{#Nm+QWqFM*M+kK--PWP)9-D5p3DFU$<9x-ZOOHZCnLyg%JyJ#zR5xy`73t`f*&f z7W_W#wj*~l110rKZ_(AtQr@2oIxJ-2q)SKj3l}cpb~(X!J-6WnTf&fr*W0qM6G-03 zN2y_KN}fT?D5NPd$yWv3Xn!mVbrfyTLn5ft%mb|`Sc~| zsR^^9iVjO4E=!bDoXbEVr@r1!G6ZgM(fj%sUF8x1NqpXcy~-N=dQ0(!bQYOrMt?>$ zZ{@XN*8ruBDD=maGu;SINNe}!VahNcyEk1WC<`w6mMI7y-#$DzTdct_+BX+wP)}o9 zn;~OouQ2v+bLqPhBv%|^`@y^g*-BNjDWG`2RpCf9fggF_Z+7YPW8YK`iOo+k57wQo zV@JMg_@JQlf5Qnt&CRlklAbzu9hZ+lG*#r-Cu^xS4B2|OU^AYCVLu%y^vZrLE##!+ z(0+R;7rS-{!qC`wcz^h-UU=jovCH-Vt*$`AfY4=%*C(7oHJ%ap+Ud7S;PC98ELPba zh!}%`g0Ps5X7rDPHKZKu8G^Wd&#SY8+$HzBQEdTwN@_N?E;5SJsA))W)OE3+uc;p@(lr zqUtr60?=!%S8S@wy`DI!OkNL_@3p)B6v;6FNCGM4$U?#%lZc&+=wJtU`W(G|gFuvJ zR^1f?&?3(-mr5m-*!eM2_MR;R36z@d!L*i)4kIKlFUfnaKeh}P0@SD$C$9MKr>d~v z4vbZ&pPIvn_qUu1+Hg=;JFy5H8k!kEdM-*mrfdw&N>%t}bR}Fvb%02S} z^=diRT-5p*e@zPp54$sOiT=)0p66$7Ow(G6c~8HYK(IMx0X3@Zl2pbIA54TVM=>`-gDtXz`Dc*fLan(2t-8N^%FQoPR$lu zCLlTL4n$@n&_zmS;Y_cY_5769?f_<^qS2se+?YzB@5v$AJHK}jOYw`~J--7k7t8#^DHfA~VD1e;aKM=iXbpE6iL-*911%YR08Gv{;TGAk2)YzvU zhl}xh98Va1sv2`0Mi45u|KU$D7s1pkUzgN}UVN{t5cp6asa4|sa)T7R%qpXx!F!Y> z|L7$EG=@5NQD~$q55#3u#(W@RC%Knv@34U=Ofd{_h4R#ia~uC80hi}x#TzGeo%B%_`wHv^c)mq zE<}u|UNmL_5XG}1WIXm;$PNy!0k^9|d|}h=5jczQr1ei6OpGrGehJqtozNE>Cka%j zQq$_eAHp+AV!mi1w6%O}lJk^=tXN6|NcYr3)AI&|bah?2E#)ic8sXFlXHoz`7_u|c z0<`R^nuo_~zuP@_yDs*%Ks<78_5vPsKkklaIjQTw)(ikxbb`*31)atIYg@RKUN7Gs zP`A*ih!DDG_kK{6|1v%aEvHL@(i)v!Wkol&WQD}z^fND~NO64BH}Tc2Es{iA;>c_Q zD%5UTjroMCDrs#5`MSoT$LqCj~vM zU!%_xrs%xw#zBBsUT=82Z46f-ABXu#`01C56%t6S_VV$K-wt-C7Ggr7nF=8=3X|R3 zr6J;6p4wAq*78-yqeCW%LN}aBdT$@b^6fb9ej1!WP3|l$sY_4tT?~%83wLKMifF?8 z6BRfr=ZieX61+l8WM>EDOH5d4`|2i4; z#0#=!Y=Jq5_|BUS8<-gbc%y#RDqGzqVC{gkByx@IZQ26doei;3Q~cGy zq7w~4us#E%z3Cz1X;Q!4g#R3b^>=Uj{|?K=nO_!CimK!YKn-ps5j?9M-r#LTwOdh+ zDElQE#QHTL0$&n%b(fV>6F@DZ0T712i*1zFn=}7vVCnXkEJjHIy3S1bI2Uxn8MwP# zbx_5VmvLTrc)W59n{ncZwwP z72|mb08k`!)$uMjW=X9G3uKV{I?Ty+4TBu1>IAsPcmwzAao z4W$3F6(3z(0Iiu$;-r(`Lx1PlHG9l63&mxEh9&Mbp{Ij~@8&`et^h78v`c#WIS*}g zfwQlN5;-W`$0XB0Q2WVyDIvodKSKONi-!US>YQF`Gm(r=n7DV#_z-`hVz*bbQ! zATWtG=&k880ZwIjGOLe84ca)PzKmbjeI5F?nNC>&8}5rDdh+X$1IN;%a{wTT1Me9O zAbS1H9uC-}9vDsmFriYwEC%+|Ik54UbKg)BHi2y*jb{ONUU8K?@%%qbjxZ|a9S%8P4v>B10pt932 z&d&>y`dw_!W2+QOu}UrnSXx*`P{M0eF}dS7ii>zE$qu=YdP8{5@EM;aBbky@Dy3@g z?lZG$-h0j0VHfqM9@&KdGknEekWF#;e zs4a9W99@%M{h}xV%Enb_!c!re?ct&`>|1XE(2e$DYMSy0x85-|IES5u>yg*&K8%lf zNIevQ282*6ObrFZ0#L0rd$YOO9%vB?gvttvpl->ujHiw_Juze{7jeh$W#*G{2IS#V)17sqtAoH_eioLPvpBkXWzPNkfPeu$Z1xi6Pe^0Jp)CSFjP*>=s z`$%%)KIFZxq1Z3iSkS-(nT3mmLm&&&f*r=Rzwt>im_&Mgg&cr&8S9|H}`90Y~JtbDDcsY(^Bjv6TOU zF#!GfGJrK?H0>01-)9l_*z{LN1O^<0!e1#uPIZ7BsguGrX!-Zl_Af1n5x)ZV?|c~i zS8D>AUw{4r`CW$%2D4jooSVP%6#@bDpam~!PL~YvwmFgMf9V94LuLjb<^R3vx8Q$$ zzWlBIpK4!#g@7NZ_U}Y=tG225Vd-%ql6j=;1vn^TJlRNcN!Wh-750aL7Ig!v37%18 zp`H@XQ3a5w-y#6dhoZ{;1%-s>zaS!|>HHt1*tVeh5>WlWW)X~H8GN?WEc;0= zqavGwF8wFl#9Q+aX>exu3&5yl9O5bL8Rh`_R$yQt0vVzRvvIw`02Wi&b{IZ4NEIUx z8A@4))P#(>yZ4cn$Kt~tV$Wz4G7Jt7aN~l_!r)lvq{))ESddDkC1D_Q(r=%{!U0)u z?1MZm$`pUgPF6t={Hhi)1EFSsP`Ce1c>jiqS=g66zVqD}iw0yVpH;0SM;)MAo0J4_ zama3sPJBHodS{CluyGh8ur^_y0M4)>r4|rcfTD{y z>{cffN@@zR{tE=efIf4Zft@V>DTAI|{z-|L0^kdV)bn%3|1#sDmd-vNOc5Qjdo6bq zsNkbhpc{rHk%g~p3Lx3NhYez1aq6Q0)Sn*r>rH7>lJ{s?huBG$9**pV88G7j2*OZW zg-*Oj%bDwdT%we~W6vDn4WRY{KrRz9Y6Z-?AXUB~2nfal0J^s(_y^A)hyLqPn@*K*wDb&cv?4qRBjr(vjsm`Hgm3(rs6QfVBR30? z&jw;ZUx=Mg2mF*bns8&0=LlsjR^s=?HkX$nb$<{r5QVyrseOhApiYZ*pg28o69ep6 zArG1|km?O|;neE*8fay>Mjfdwez~=F{LE1&z>!+Bci}Q=+s7ey9aQ=x0AQd2m}tT6 z-g&6QzBXgrzu?D)9XrlooNoTLg;u?28Tj}mvNDy20EzAcKw1~S+7CvPUk1V|(Z)vq zq_cuSBRe2DD1XBta2sMi5s6a2N_+@>ri~9?2=XL39VRo$yeAIb zs#zWvxVROg@elyaT?}G9L(pE13du!e9Kl|ZS$h&=33r#`k=qKUjW!zU_$Gw!6TbFj zVj+GA!6KSQyiv#+;#>r~-;SQg@F7S7s=c!MtvCofLb?(?Le)#UKNx{l@Z1C%@Vp{$ zSyuJ(Z=v_!VGk(-O^5(Z_(znyHQ^z&Ql>S`zXqT#ZFohJ-0}$F71Q4_h4|*UP_hNPi0gq@AI~#0Yt3jjoku(D8~LA@BJ1en2zd^sqKzlP-X~tB437sXAB&sY{ccz+u#Sw%aG{fI+?9pF&tvg!i8$RtAXm86*c4vUlCXs6mB?5`T&Vn=)*znT+ zg#@@mTMmBFDS4|2r00Yg3;oe~OMJWp0DXV5w>KBL;db2IUXQ`{K%3MHH2MD$icuP6 z_m*FC^BXap;hL{Mu#iOaOK?2kx%wGueMF65bWWtlQf%!Tbklrk=@IN~IkK65^`Pad}QUCdD zxC;kReLw^DrE+j9{|00x8ekAeWl@?pfu~E({POh=vw^CWLk>duY2O!jR|ZkXId`00(N`uMo%1Dt>Af@Y+$|NAO#Ksh z?3v;ogq3x>bjz|aoreHH zvviwpt;yYb4}iQue&GiAG5i5_ds7e|0?+Q&g7^Dh zx6r~71aX^#fN>oN0x|z14)U##+*ZQ`<1^v)2#jO5u@!O~kZu_we+l^khhbnfnA#GP zE~{A-ccKvfezXW^Am!kJFt>gG-_Hg#?H@r7!2a7nXc>e6hGNp#{|v=^U@3T%j0Zpr z|D*D^;y<5c|0?`VIsT8zf0_BeCD6`6l@6fFzhM!;D3<&svHHJi0~f4Ck_hzw()s^4 z0aXL_xq3Z`^&=kpC+UHb>@E- z0zzLvwRw;nvVX=kgXrh%kqU-;iZmE+Ex5opPZ(hJ`WZty6tm#~pM&j>LJ02@W#Q`I z8K?+=QbNxm9*Fe)S6#$sVMfHUFu0+^-H;xd62KKTQ%{ zMnlv8_($?BMofa=#=rpocOb|}5G4CQg6}QJ2>wKS&@d9+wn}tU_4Xn-Ko4hoEeQa{ z7b93OY z-nT%&`hLAXm70b zUz*t1qY?NY3H^X-I!u&syLs3qby9#!X2BEZ-t3a90GTg3*$@5SJVB05j}QQu6@Yzc zKE#Y*daI{_sYf2I_*5GHs7}e5IbC#(|-4vc5(&6KKfG$^~qauW(7TsL*5l-%4h~!`T~-}`p-}`5T^rA|L|hE_0l*I z4gePS*I0$_=T~hVTHH!`MGbnl()Jq-yA&-A0OJL~Gq6gK4+cz=1&h$h{mOInPlk3G z0GFE}ynlwVfrwxAgLaaNQfX7SffO+61mhk2SFtD!&yVl75x_QU_p<-javj0{MLzg0gN?5Gw#&ErHrA|09TkORIs~rxDWrxB0*N z{pz#&w^*3wZ|WZn{?EdO;6EDwGo}HMlK-pIsrtWb|3QrZ|Eadww%kGeb^FO#eeONyt^3w`AJa=!r7EeatJG>uOM3PNK*6~nR13@7{nG%7ivG{NqyB&4 zg3uw`|GPV=%IlC7RUr)h2_K!Zi)@W zH3V(hDFA@PprUNo`tM<(U;sqgmpj3_tSAi@H@ei-Kmgv(Qo*E;wO#n;-x#~T$i>62 zZgjqXm58!IG20DE{+A=r3kR?6oYVhS0H~~mK`JAzF}oeYBj9iKl}`S@BzEBp#@>-2Q=u&kT`9NPKv`U1eB3inej-YJN7K~@mJMbOSGS%DcPk`QJ$${Ykt zr>M#!tuOk{(s?XZ{BCpMUD!vH?IHYhP%JPucQfB;o;z?!RZG|C$JdDOSB$ zG|c(m=U;aY08j(vmud?FlkE4ff(Sy)W`+^%%TBMFyO-E za-{C{4jpJ5`P0>#`cz~9%k0TRpIRfkzo|a^qV}-QP0#;bAXeVt>!ukN2Av!q-@j@= zxz)r)R*~F5!~V6sKw4~=@;@M*A>c22V;0|k3Ol0pVSrgU0C*8OV932?d;0fYO$QD2 z0Q!NtNBe>~Ai)6p@$=G+Nl*`e$Dhl(oMh+J7PbiyG)klnuZX{)gm0JpA1T zqyzk|J@SqJm#qC86A9-3=m0?cpGu(H|A7C$fxnY=egkIl|CikRPmcb9F{=L=6PEJ- z;`{&T@jr9@4*&{eD*j7Z<^NBK_xHe=;lTKc@c-bOhXer435spKX(uTXF6jGD3s*PL z{~vJbKal@T;$IKef0zD;shGdET{?*De@iiim9wwmt44L;Vi70b_DuUhM0iPunSh7z zKD!p6mv0aS*eA_tlH-3-0^0x}v~?TM6zJYiCyMNDwfG!IK{U>IK{dP>~t` zP1GBt;zs|Q9}E%zk|D^*_aE$d*!)v~x&r{%=|$26{x4M((W4-Z^~q7lavU4@?XB1KGdJD)x% zUi@lRC{s#3<+$eHIPu7dTZ8O>n5Qyxv9EdXi7*TV{kLg*>L-!%iOT@X?dlEYs7?0E zdL8&4qEuT3z@=DF4ziWTI1>o7Mk(a;>e>XUQE*|Em(TAaezigHJUKUg&}Q)dTtu4`;frfnZ`|E@JIi+1FS=W4xQ+R8sf^>f zA9!sJDxS!NNG3;355nv>tdwC(MGT&b7uv=pH7)Z@RMCF*q4RGQ3={C2rAH?)R>oWT z{YRAdBQ%vBVzL7+Pt4mt##Y!b^#~9Lu-8h7(FKYM*M+h19i0UG{Z4c{`&hRlr5D?~ zvC%N_6+>Y;OhVJ3#=Bi~xEP2e`Ingbr348t^(<#HW-D1muw3-XD;TF7 zW*SB;`S6~}^(lC9D=o%(S}fuZCq07XwkM+jfme;+?NA3Hce#Yr{E)7>I@W!PAjc{n z&OecGun6f2HX(;cLU zcT&B57l7{vo@F_0F;>t-R7hIfeqBIiU!I}2B>{t-9s!(M)|yYuY-Lw^xBu{g(a>~O zwPARQ#7CYTf@RA(uZUXb|pi`iVV zEaabJ)$!|l+JjCnt!2)<{f7B_Ff>J!^zoaqacxH^?2}L$YrAORUST(Bo{sfi)&Vif zI~nt+515-N%|Cba5GR8H3H9rEgQNRgo|hIV1}$;L8zflX8mr^q;Xu zb=G#N>3I;e*f6(Y0xxN?3M{I4YxrQPagMcG@6&YoGx`G@#wsWoAG6i1xwo2vwVE*@ zZ?cm!UBjG0jPUwTi)=;xDg8>X^5mNNXq!eUqx7~D-W&d9@;U#(YG&KKsd?K7@8%x^ zK{I-7KqXih(p7G^u8mSe_(SC#`d6ibc>#66u%`DCwH{E~`J}ELy#v&V-~hK0!68&t0XnlyrzSdZwc-lAoa!9!6m~&D1qD!^ z{QU0WV&PZI;{hK2C5n%iaM+s=&cCu0O#(LS_#~Ab&D;emED}q zVZ@$63F5>Q2c4Q+@aNp5O#f2Bp!d7^^S55cx-)MXze2>?jMBQBT^Wi3T83rsOmbP= zD~>r@oVpCKu*1*xZaAw?9lBr|QkwR56rV!dG;|w6Om54nbZ@$ph=>bX;0YjMmB&C1IXUXhR!1j=IiNF_w3B0-mtp9$vGNF9;)v1 z_VM2&ld>@F_Agx*ene_>#>w@xHV8DQ&S-S;^LYGZPH59j?EERkUCmw0Bk!#+cc+x; zMuDb$!>+xYnyWMRX0E<$Xb@#g6lU=?H&!w<1<%(gD{j+z)uyG#VT8roJO(<5C#E-^ zrRkCp0r!&5P!@wT_An$6Zam!&Tuo7^%SJo`rsq*;J^FIc2W&c#JrCP0hW&S2YX4US z>0c5Ti73xFeAzOYd{m*iQRhl9zJP&gJ13OuxYzwqvG59s*bh+~*>9m8B8XcpEl(jb zeH7*P>0$62=;kojSl_7oqr@OggC7_@clIuLRHIXhDRNS*rLic8biRA@48+{X9$=p+ zKKL7}sCIrq48s{}qm;9c_}Y+v`E3r33cGWhAZ27LN2MN4`X$SR*R#5NnFy*(0a2rIjvm7>e2LFbpM6Q0nq}IPp?1+R_QQ&0`pYA-!$WQ44IKmmznNIRiccOwoL+}FmOpmd4pNFRqlR5YzcPe=66 zyt1KVT^tx}4PEs2nEYr1(8`q@DZ1+~QunG6H*}R<-`A6$+Jh0PQH`D0yAOZ-@FP*@ zmkdO3G0ax<(b_Pi!TfOvMvdB(+pN(<9iCXWZL{@6VrK!2h zZkJiyj0nMySnbFHqPBs&Z06W6j`p~RPgX|;o1y9l&*=5x=Yz8)v`Qb}e!^=TvzgcH zVul0lSXL22q|zVFHdFm#Nn0=8-v<>lC>YyaReR=lIy+NdM%faaM%Kw~m*M#RxT(P& zr6oKxkBnU^>xnHB=QF~A4%v3LqH1@JZ*Sb(VrTyG27)p24M}8_4cGIe*g4*&6yppb zcJ_E_*P&oeli5G&w7`!O?zK1j7xB34BJ1U=X7tiy$FQkA3j6FpaeJ_-i-N&O%fIA4 z)O)ym>Bw{B8f0FdoT0%^hHlacjM9{NX);H6J9@_~!RC^njxijhYC76YYLdRAP2aIO zJxm4{u9qsAPNg7CrcDH&zmghoAK;{4Tm2b0z6T%s^47&u$)6%#LOaR%hP55I;W+5O zdnQiKzH3L(PA++6Im(8JMwC`SQz8uUYcRuxa6U5&7pWYsSF(ezNS5)<5MDG;()qzK z+&$<_J6hCoHrp6p@Dbu|@sm}$Y}hAewJ^n*_i)|s2H1WN=Y!o0aDT)5Coip@dm?*Z6Qgby#z7%>iHx=hls>@Mo#-NAw~slg`U``b<5rLQh5E@(-2 zK97%unhh_j^#2|?vR%CnIi?rLsF{pM4vYGBRXa7;kpfrgf5TACBCn8IcnngH;U@IL zJTKyzQ&7}MK3~zmof%h}&;ZhC=5>oK<<(>I8(RM$6%}IS2qS^P>&*&6<&0Uf(Gu9a zJE=WlVOwULS1RvOM=vjM5mWVzJ)teG9m+Hz7MVm*n8p1Zr|URKgzJVyj!TR%M9=qYwROb6z0Xb`A|J{)FTRX^EaFgTxE@gVj_A6Z8sm+M3FC$O;Lll{I=Dt7Sa(uG7VtEUAdYa+ zNOhAZ8eRPvuSn5X`5+7~VHcmdE^81rS=gx1)<_GkQE(2Bk1h6~z2AU(+k9zm^3U`S zdf=n~b{u(iD`eSRakN(!u)x^C1@>ob0k9S!5iZpI5j7@mhd4MpUs@6Pdyv{xeP}`a z7C{|v^`%3em2=N~mLqwU&S^P!nfWx`_{H*raAo;@Hi+kFxK8xU4wQL~LV9zNbpJZ? zC_J7J+G*cXg?aK2z4!xy2H|>Vdc9AqDq&B*(h`|*dp>M~;(LUD1RT zIK(D*h)hmk#Hqa?z~&K!5{ zAtT*w%ucvo-`29-?a$QTv@*aOCm&o=BvQYU>Q>QD*VEeK>sZ`F33Y3=VRx7JS@?tu zwXnP$pR8_-0fYUb#$)8I!uvn>aaG?Z&X1l~VE~0HSt_Rse{OR9zAoS)#DB>KGYSW{ zsT~-+)%BPYSgmLpa4uLOudMik=yMa;keKZqLB|W`Ew@Bot%|N!2s47?id@3DE|W zEI_OMYE+_F92TqKbfjEjW`MvL#xs~7+jsRFkVZG4NZ1vht)^>`Sv0q1pl>OoZS4E{ zZu;oV)mn{gYN(ZMzL7X6OHo30WU|m*hFM0eG(jWZ-^->SO(0pgSBgi?g0WAjE0GZ+_zT?v1n^#v4C>8QwO|-!Z*FddM_|-gvz1k$ytYv;ez{%z2^{~WrTGDPkoV32Kz!`yS)bV{J8W4{-YPmGhyT(43G55`g@!PBe>iG2#2 zc`vgo#QP~}6ugBJhz(sO=VzJJ-L&pXo(}BZW=lwREUVsep!Km zn&R8C4VAQy^eo0h=xouv5O5%JFMn`CU|Eivz=3q z>L5Zbo{%=G7o-#*eT*06^_&S_6_mc>K0hq#6^3&vma+FOj=?19s?0)F-}PY)4)8EK z@99UmRzHI)Y!BrSyC_aD-$XRaheb&Fn%5!S>Qe=_(bB2(c~AYrdbLSq zvS35SJCJ)}=%Fu^#ijf0TpcP^JTXPMj8moP1_y7Fur*8&oudbBA0XJcxp7sP_=B?FQdAj zfeP;(68YGT>|ZGw^7;9C#7#z z6qKJZ81YXb1>Q9xSc4R*i~bKbqClUK8El>XAx<$mMm@F%@iT6wkucOY4zw*PIaBR- zN@*SQQ8^E7~pJnGSpcU&+8%H7M=P3l!WyT33n?ks)NP+5-haEPm*%5Bs8ZZlWFV zTS|771{Zf~kT0rJnDytdV8e$CCOHF36^hQLL=f=Ne&C$N75f4kVDI$gN5gl&0gXd^ zw}~J<-{*pKhP*!Ps=g zoR8DTvu{jU%xu!lYxa-Tz6(N8P|Wx#X7~=s>kMC7+@>p42Mi6G?^3TylYjDcbRROB#ZKiEP&n7A1DdrL)QYqx0CoiI#h<10tj_&;VzGFE0hlTR;oxSkaYFuP~;w1(kFgB{ZTrg$C+NZ0haqZ zBkq)uq(gO1;G67WX8ZOmV9BvtkZk+}RgHeg^N2@+cQ#ioDx96*<$|TY$7Cpmt>?p) zxO7QT@@I8_D5?Bn54VK8v*{G~roF*aCEL7-uqhuCmW)A{E2wFY;#@<-EUyJ4~2zh6reEB*6%#CJR4 zYpctEvhl6Hv}CxNbTPv``EyZa+*1xkdiYf>mTG=l!ouQ<GB22-NGs%PVRMAEg^+5xCzhHr=DfMcgDPo9L(HI0WxWu48~9a$ zk?*C0knv}&oZ@GJgE7zOD@6k0L8`X$)>&+;8|zelDk0y75muphY#jl(l1_H{i( zYRf_hpMz}A-;Zm0g*pjTDT*n@0++i!G5U@;Q}tqq*Qv1onTF4pBIVYsyIxwOm$!+~ zBOl6xsUP&mj<~_Yi85u_N)J%S{G~lXw3;W&sM^DQsIuqwqsAF(U<}4P!p9~2gb>Hq zk(_PDm1}*jhhB-B%i_>^G2+LHmm9nL1R4KxF^lqX*H`F9D97)P$W!{0G4?GejNg>a zZaEby%@|RP3l1$+Ph#P#4Gcus$yE9R6N2Idkcm8O=CCKHl73aA}{oK3~|>>1{;63`dAOhnVD?yP;H7 zIZ)oFetmNle!Klv*GT>*sFuqYs~P6&60wH)0}-p_rXEG3kB7SS$S>QZg%c$f7;OoO zUwJMOnpHlm@H=1-g2B!q<9UtKj3>r-hx0rUo9A&JOpDSGrUK$z)Ca-;D`fG(eu{O@ zBxh3J?RJa5u%n;h8h8R>ASr8-61bkJcZ_0pi)vHd#mOBohxt7_ z*wT>r7q6e0PEm6tf#w;)lwes>>yq7K#VYazytIQk7>C>N4;f<=DAd_g5aIzm(u0D#_}E?9XQ5DhevI!w zI-Cc%)4TG1?8mG;=6@-JJeY35JxSD|L9#x0zP%{Lg|i4667#0D+3owWMFg4Jh;M*o z(BbEP?D#d?u~WOl#B2Ic*i-x`k{yD>#?3=|JZ?n1VZ~t;=0XIkfUAeyGCn7j?)vu&JZah2oIL@X= z4rpPLDN7C~^ZZVs3vbo~D@N{O7DuFq20Vy|NkcZwGv5m!D37<;TMPB^lN!|ol6kDKoi42; z=?DypH}^t=e;iiR%Rb+V8=Nl@oAgkH#88iozdm?-DM3VE=Fe@VTs}A=!Zj0FzzF_+ zS7qszrdJU=DvhmY^knZ+nRb;XSoX`izWp^I z=`L&aog{T#k$v)y->{hiEE@sfR;YD51zutv6l}e*?$IN8i@pyzsCA}GN%O#q8Od8! z$r0|Z&}w$bu&3@ztxBp#DHfD^p4(=~N%?MCYJM&$ypHJ@{_YU7w_ohaidS<)g2E9v z25ziXCuiN#;?V#}6iO7+6!McOZXJHGBxTDaq$7dBJ&=f?&Ql+}PWvEtiPhe!6TT-R zu_>0dl{e&Qq%xa!0!p)E=`4_?0a;%ThrP#Z&;Zj!I(IxBf=V$ zWuMXcLR@IPMcrgov7D{A6v&TMU|~5mEK9lMn>5g$$9ywJn|zt+Ou9>OBV`-=`dC5CT`gq=$tMf>-BB_F14ny%N5Xo5( zjh;tNmw+;;5`FH8dr4+|y3g^$%?Xg-a&bFQ%sHBat--^1RGf<{*9%$GPHbiLeM^@w z8UY^m1Kg?OiPgHNq<>zBispGH$)J=h6HTU^X{bCuW@Z9)-ajAAJnur0F$z}H9Qi>U zx|YAhRVOMMf63opusVRdy96oFe{ByFd&uX)CRmW-F}-)*TS56e# zDm>CoecE(HNs(BTTfMfyl}B8jE<4lR#O+8R+x4WJB_zRB_PNh|PC~=NqWys$rr1JN zQ}{3~)>ud3X-a3 zii<2;=da&x)$x*82zKUFT%wWHt2P6KD-!KTH!EWOu+fR$yiBuaJ{{CDhm%9E%wmx7 z3uQO@7oem*R7O)D)k|JfGuM*K3w+4J2!!7^3ZytEi4iH^y_9ZC%`{RD*Sj8kKi04~ zVz^Nrp91e#`(XM~fyhoN59|9~=5tlBn_QEmkV>1=l`PTyu5(C6JfasbTd2~Rj98q+hA}pXA-Kk9LFnu9U>I8GE!UQ}zK@OL8PNv*N8R9B@&9p-c^)cf?6 z5V~!_hbWR(%3+$9tQb*(^19OG8!E$dexN~M0)+eR){W#3OIyBeAEz?bVv(GTZv7FJ z9LJYX!VDQ8B_&n8*+=(q*Qb*w_%`L1PfytdSw!<|)jib7xRUA|a9@(tWnP+phxI17 z>=V6Jkym`#M@Qk=)2!@wQ-am?Ikr>ED7(!~&7LH;r8hc^FVdUX=kJOC22EkQ>tMno zUAJgRIJp8a{o<_fnW044+haFIwU4d2TXr+1&6uj zLZzD@9a>aZ>|Nmwhg+o?+fWY#D(37zsxkp5`-rlXwKjK};I;fYJZ;K`?L^ohkC3!^RCdN9hX z8|;~Vt{KknHg)dXHa#2}oN)M>p?2magFggyKhLV*OQPO@pOx%rMYg8>T*VZiKn{1( zQn@=4_#O8*&H8XugCDT|)E* zt|IjF{8Xr~czym(C#sE)cCpCmB;ss!Ekf9{%qRT5qG!S{x62ghBM`bX-Omoi>@49A zz6zr4@C}|Kh#CB0+YMaLx1?$?5Rc*n)X-FkRq=iy3+rygt>b4(PkObh($fUS_E|J3 za7{U;<<$)_0h^p?vH+_3qan4oTz2K^VWa2bDG9v6o3@!PwFQ~w)VS12yBJ^gx`~6* z>8PoWex7%2yJ6Kw>=6G%O;Nk%A#B-8hFr*B^LvQZ_67wcK*B5osFT`WV(h|FD5VGH zlCOzt-~k%Jz|r5AbGWHLXumXOs_7+)4qr4b7!^gH=$I%X+_Py+%bN!?I;9yQ^=B{J z|EbIXNb9+UBYt+hv+SO2Z?C2KXtr=Fw+-i)q5OnTiE6VNyG4TIt2ZFDku!u)JrcclwZ2%&D!RymS z;g+}m(RiSeB3T%n-5;ID`(gUcERUO~%<4|ieDcJ>TFpV3EVVWOGphMxpG_35>)zmW zkzsYaRuOhl+K>bqTs@+23`NQ*hqN(bFc^~sa?tGw=%6D~)V@q{uvpq{?&O zI3=B~qdbn2;j&Vi?jkq-RK`w9FxiovsC45>zg}kkobDs}xozXX_$RA%=Xb+U2h{|V zVgI!L{I6S?dQAM?zgreYYPlznInnCTOv`HQClXbQO_t5PZXuG+y=BWd%e8a16wI z!=hlbM}B-KS)E^blKA4Avk$Gfm%&c{Mp5EF3;s}9Yn{JpDVQA|e}*ctc$O`d=52j# zW)@XYr`DF&rc-T(!-FOOF~!-5&(=vpuS*3b39)>;@w84$6(a-%Sofv$Cw+gsj5m-{-T9ylA0}e!2C6&Tl+v8 z;a%YtF(z|f;=$LOOj3sW{{8=G_Ff@pe&ILBPC+U(iTlq0nD#<*P<5mz}x z+!fUX zLS!YFWb-x3(re98Or2Ea-jxR83k3G;es0H-y1uK<7z~PheST=|1<$9;7U>A~(Puu_ zNbW`^E9pK-0>-p0mx|8(h^PI0Lz~(s3{cCGN30Pbq9X|rd$E#eccRkXW55x-H4Rrn z+}VA&i`7cDn6lu#2clUd>y;=iAk0_h-VtN9Ibn7O_6gusG7 zQ8OOE)FL#%|E8$Oa7FpL|K;lX6_SEji^0bsiaOd!GJ<;mkgz%4l>M3VB5 zIy6zTvwFI&YKPd>$09?mS>Ygb3Jb5^-}A&OWI2Wr-lnyj*ZZ)SPV27w%8B3`2ju23 z$yd@{#^VuSEeSeqU&#^oP8mt*lv^?A#4_>zj96K(cZEG4slhPz3yQ;J@$6fLlw#fJ z*YC31eV}Zh22KCoCnW14p$sBpqG&ohh9=`u%QS>L%g}0>9ny%F+PdZ&w{6Jj)U>4YvSL%nXAQ7s}N%up(_lu9Re? z8#*#8CRM#atLshh^kq=MH!LtfQF%NqZ7gY%LoHQ$A2>1>s+njf~$OJ75B^&|bRh{n6__$z@J z`k;dKeL+hrX=SMFQpYN;6hRybws~xOL}NzYY$0*=$~ruy#m1G*jk)*&Uh2ie-Nu?n zSGIwvGNXk%UY0Zj)c)p&UQ`8i#UP!We1o;l(V(WuzNtVtO1L)#dFdalr(3>&Lwg>b zFN4=zoX9I|=>25E<>n@zx5pKCU=VV~?~Q2TB$GgPrsMP)c2^o;a)Kk;oeI}JE5OXs6~P2W_?%y$x`<@6*x?EGwz_PN36x;!-CPd$YmH3}!qJde^0q3Ej4oAkg544nMEmu$+<>%T6Jhj~tnHZgPrPgCe2Jd*b(bituN7os$CqOB1b zhm(g+n%+%KM$9wkUb^==%)1pADUy&103E{Db4tt)!1h`< zY*zBvGl~j4ck=;_^4u=k%wM>K906)qN{l3qDV~dflOA!ok##ZFTn*7OozV?34a59! zavbf-vjDv`yv0F*3vN;uH6a0}{DOma4Eb&itXBH?h0t>jWq=j7g&tMtNM?#>00jP> zVpqC1i=BdE3oa8uf(i2tV0^H`-0*#+j&Us8#+c%Wjp41A%5JXNQ4pUAMywwu{RUO| zEB&vVnmeN~QGTM;vv%E|X}$vz-H&>+V?i(TV^Cl&;j9>WSmXiIYbksQe&q@r5vCM- ztCjC0s>)1?4Pl8NQ4=`IBA4vEex9yBzR@S|Kz#CJC*@U>uFCjPRDhET?!F?sJv))& zR*SqJNGmC2O*2E2!~f9$Kf?0x8SHb{lB^bI5WRR{c;ooRbyhY!+fIHs#3!_0D1Ic; zPnM@dMiI62US$1?4NhLqZ#46>XQ66vnfuOtP^)@83nxBlpF+I&4%soaF!gc!P+Uf7 zE~#LB;UA%KBKBI$@tQWFhEQAX7V`yuhv>Gvin<}<_Q~{udw2%(pUq{}U9NL7rMS#U zIo4P7D1KfNEb%i2pK$6Yfj<11jkIi~lkZrod!Z6gBizG-0EOG_8wInXoMX>uHYLNT z*BCh^RDvlcORn`1<=oV)th5OIt!ZI*+l4QcGwj>+~B^QPGKyI$%y7AiCe^&W5n zO|r484r~fLf7!L1Y1E~RIs1Wzv1r4e<&guw54IhwUcCGNbm9q2`T%|%Cm8b+&fTG-eKMM+P?rea zRwvJPyw#cDiTd}Si5PpoZ(7Lem73t)9_-vdK6z2^`(`6~~so;m;w~WvQH0>vhzv zIu~INV}7p+736flK(=3qxtCPgb00Mp6tRs*Y$gU% z65v%Wr>x+=6+Qr0SrDNDIlUJf^3DP7T#BNDww_`N9{rVv`3mYatO;1uzK_`gaQt_(?Q4F&zg3HsMna2B#*V-yCz-TO z2=4PrZETYiXz|KX#rw|`5PNyr%%K$rK5InnV>nvSto!R!a;h^y~@h33+)$qPM4)mT*di0`tPG(PRu37uq1~hee|`2J7k(+Wj_SK) z@I>Uq(b=pJyq{OaOz595q7#tBJMfUsi^0*R`SU`jJmI!F^-O02Dae-xwTyQ9uz9D_ zf^^}jcT3FFRK)TSbYSo9IY)r@}=lS>Gj?GxTvXLmSzQnaiYAm@uf8Izq#7OtD&$fRISB5}=@9%o`By3?G z{f0*eQJfp@=gfPWP(!x-GPs0_4^F^GVXiyYmBTSN1$8&nOyi#)F%^|>Q_@HKqGuw~k7r5UIsS0bF|0tu0 z_hIiE&B-^^uAD|-BzRFA+c3&~ca^AXsdXW{yM%2V4M)jcR&nm1q$*kprNpYv4TL9_!zTTVJMz7n?L-?S%eU@S6^!MK@4d_3(R?cNxpXKIw(WiayQ+3wO%SY9u%A*Iw)bzR$OEFx*Sv8^zTq`}#waGQR{z=*UP5##A&% zs>+c4cguW{KN2+ofVD`+SlE0Oc}#OEPs{5Z6>_oYErlL8;d3>rfD7hvxp8V9ky;s7Djh5Gb;~+0G zj!>*P%;<97Y|Uy6MAHO3qK#KWibMz=;bW4qd5n#djK4ha(7-!$N@up+05#N_=r5pE zgJ9{dP6DZC{`2CxOorUufWRq0Y3M7@A}A;s2p<%2)z=pf0MYRM@NWmcKLE@t002-4 zTD|{rA`J_6_5e9l0{wxgkVR47e=^AR+az)b1Hi{eVM`-~L4CpNx&Z(zr|dC1`0i5Y zufv^bmj_r@#oT6Iu24D}BVXcpek#OK7s3w|GFme}%H4mB5DKXmM<1gGu^_SRYzW3m zKJ731HxuCC#T3)S{{sKx+Vj6KTQVpB*gu|?0A~3@VO2&Y zpoMk-&dDvV6Iesia~#UclIM~UK>UL3(e}5<9#qnxtC-pp&}&wSQDnpreNQ3WxEUNP zt(Q=wxEfVq(XsZNF03&u;#Wd^X>qM~eXnp%Hvo4nu;w^H7+_qT1JMnoBy`%D^s}QU z$74J-&dpP++H2Fkwb;!44&SBqe)JwE1HER|iijxqwqqw>54f@YDGBLp$sD9_1 z&P?lH>l6P|-S;>f3iD>bGqW4Q5#{GG7~UKzn_9Lyd0sFgX*RjA@reL60QfzZg9HFz zj8~RGat96OX=X^ikDAQ_tt+RPeg})S631nzN!XnTRm_h|G&_aT4UIBI`OR`B0Ykbp z!th($I8(SYHeMCEpda)ifGZdQZ|5=Gg3Tw)Hz#yO>}z(0JD`?N)tb(iw6ZMO+doHm zZqk&_MIWI#G%Rq`y|70g;uoR^33`1X|I<><3E8o-n04vn(7M>#T|) zn<}m(%qk0~CrraYQ2;1bKOEC93scMF;CiPjH40V_sU$9mPS=~b%pJo4Fna7?-?g%2 zf~Q?w^HEgaJEI4V3KY}*3$>p++X<<n=nY%(NZ#t3Bvst`g<{4ZRzKUz}Z_~Z;B%Os6a0FJXQtw5Du4PQ{O za0>ky>v4tKy0IrCEC6`6LGh0g`)YpGayp{dn)RFTs_WGdbf~Fc^cUi=x}EM)?hgxG zLfP`O!NO+`NdVs#+9ddK7vdS1DPEZY4|B!9=V4Jmu%|f^-NBF!OOpo_r!NrXYYP+s zEwlXpxy+DH%)V!b^8FSS_CLQG0o~J>pmIk^?00NU4SmrBzSY9K1KtSl zmUyXcHSf#gOE;HYB_H$#rO@(sT2Qj{TUN}Vd`a$pFoI%Zx^IV?(%Y_e;rGxZNlL)% zhM*9n``97DGJvoV1ifQ6LwT`-#Toek5u5#yK<654U@8)pox~bGLHS$E>rjOEFQxD; z8s5|XIRL`8tAy^a+}%l&0#)q7M{QhR21y@7B#166xu0ngo4L=8P0pWzW}@h+0JO1$ z2V`aNdkMqTk-jL5i0xWGh!;C>q$zqC8NSHFs8RG)EZ4Rd&0>%wTLw@8}e|K+C) z4q){Zxicurf2AO1Wsj)&NALg{*-wHQ9q-fDZ_j{ zpHSpVThgIR4-5gouDHzo!SgNT>aG?wO8FMZpgHRD-Xc4?h`|RiEOWj8hqAW-tE%bR z$M@mTosyE$A>DE4l#mb!2?0q-0RiD4-616{-62RfN+=~=k`mG_0>XcT`aIA3e$Vgv zzW;Td>#%2L&01?_&)l>2Y|cGxuQ${wZNJg>>oMtD$VLy?Wzo{T>GRrA^dcsfYdO@i z_f+BlCj26Wc%?xGgB0#Y1CYuG*88>@?NUJpj;DTk|*Ze117n&31j zU}W~sbsBnj`lP-ESx$|(cr8sMnG?Ev-2l{jnxPR+fWPir<8=};9n~y2!kW!d?to|p zK*CPqVUP#ja?B9`Dku2Ua_woDAsY6VgULT_N9PBxAnuFt)qpIB#1LA^4DEkVPs{@j z4389*i*SZcKiOWMaJs`FFKhC$g(XW_(xWzN3BND5k)yP6!tO~jcM2Tb736H-*~^>6 z-737AF0ewg%;wWHO8z*(Yel;#EbQZ7Mpk_#k3qXU1OBp|5TkoeEg;uhoI$`Bt z4X+N7FF@r00KhmT!!Z0e8^ewlxv)xj-9e+Ng>JAg{<|E6?~h;2K+elcB%XsyCznLr z^aFm=%#q&1*4a8fmE(8sqqfq&D6YPA2lv7D_F2XN=^lW=@6DnB$eyS;Uj){nZv)sI zo?PX}blnPhq|5|cEhf@Xh+iqZSWoB{A2P(>q(Vmk`Sf(vSjvh^k6vfd>`=%Ux83(+ zLs2)6eh89pfNTe;a6qk;7a$}31_y}%QC?-wU=3f>0C9H+Qj-Km{l5PICWV9B5F7w7 zWvPj-sYj~7mi-B^5C-htj?UT>T2KZG1PltG>M>jSKCK3Me^M>Dn7xE56+K&^LCK#Y zVCZ!mA1&`5UGqkA*LV1%t`=Is+dS`2wOw1`R4*9bBZH`RR-*}I*G*7TrX`ja;VqOD z0P)zYdAOTB0d#%mWGIF>X*c4SJ=9PobSD5}433h%GC(6p9d@k-E#o~5x+ifXbKSmz z+?(t!;D+QAWPUXK6WJgPgal_Vh~0Z#kU-Zqe2PrIV}=3_eXtJrLDI@4-~d$OG|gfo zk4Gr?ZZdi5&*9*R1acGsfYXYKGw>%HJ`AC`+Hm(i93-w$BV~E_z78O11CZC={!vsi z{Zq%d4e;j2z0N^uU8ipYxb+;a69jDIA{TNc;Uza7f*J0s*V(yn;F~W1a)v@O9{q}G zKt88I=Ao~5y51j=9mZ4YIu;1EfduB)8X++=foy{S657Tj$93hu=({>U^v9v#CEw2Y z=2wAA2-nU78pnn?P|Q27bs4;_i`vqV@JtHg&z6M&p*eQr=2Nv4qU$1=U~Dc;nQ}J& zn^Y8$fL(sVs1mEOA6Yc$*_%-$COH^DhL!ob0A!xl|B#z_;~EznB+_^usy){Bo8(XR zrnk_*fa6a?0IsT~->K{S4wQh-{#qQbon^OdMAP4J^Cx*=47tVj>TI)6=vtU%T4AoL zN1f>wwz%{Q{h~5o>S#2Xe!jJ<&Ae%){iMlha+1O9&$fu@nl9V36M zC8_{GQX9z>qriWqBm(XW1(s z0}r({yjP3Ei?^28(H&bEuj=2j#N!t36z38QXb|zgis8Z*E~5SVNzw^p-Wn5lFa_ys zmpK03b8+NdoMZW#|8)$lI5Qj*ca41>zt`wz3;iPi2{|m`83*}A5V5Lm68RoFRy~z- z6OKPI4^BwHg`NT`Q!pG5r9Fx%aqoO4#dk9Ak52szB1G`kSkz_iQQi%k7H%|vh8u&h zc^iW zy!zA4T^NoeNQC==_ZDb}WIX)?^-vmaa!MQ3qIh**%LzxyAl_g!ihWLIzwHJyTyP!5 zeMHYTsnHXn0Y4yMczb(4UDRfQ(vFk*!NTc*1N#@+RB;p{1tR6P2GQyUI)^$q(!#ZE z$Q}Co+pj6R((j6LEYB)-5LkIr5JBW`fr}LXZSg$6*`45=w))^6$}9#diks%N0Km54 z0Dzu(ok9Si5=9O`lmVc~SAQlCBGy^W=8bj$O%QB^AJ~XLs1DX)d1pWfmcn3CXu$yU zvlqX+fZ6yS!TinW24!gD@e>amJLQJ4-{5pF;l&U^-N7kKK!2%djKK*^quq=@1X^$< zmj<9-HyY*vz-StP1Ok846;rhR*6nwVd`_Sne^B~wH=qza2>3*M2f{PO`B zcEC%-rA)y5UrPTH`}d0*qVDIA4EsNLdu_EQ2K4%u0Sr|?a>)-wzmgC^#6S7qn6Yk~ zf0TZmh7kUp`@7oT-u){2<>NmKkr0tZZ#eRZvR6y z-Ys3=A$&<$)b!L8xb8hhYTylkl=MpwN`3S9?#(yIAO|w91J4k(K(T+igse-tfT98b zKqYAWZ@{#sVV~E#U`0YRobDWIF{nW7K{weh-^THP14!!V4-Jq}(KMzK!>|=5e7H}M z`Yi(+0GGiFW)0sJOkD^7*+3@8fz$kQfb+?|%~6q0G;I!k?B462Ats0<+HC*}K-Z&$ z>x*)PzZ+fgW8vB&?$$G$Km!pX6MOslUksxG9G#{h6>gCLjG z*odS8_y;S{(4pVl=j#!j>k6`oU3&-V1NW!A07S$;BOD5z=)jYAU8EqD0Oa_B?siC~ zSmymJ$Wt}~b=J4aYr}3g+Bg@WUJCY=SrN>jW9+i_Du$Fq(JC zz{Oq-mRX>@i%ku%W}--&{@M>YZMCzqOC0>_cXa~Jl?PJq@+P)TW+QE1ISzHQp%b)S4FC)e*}=O zNGD(6ReFa@G4_x~BRMn@y?Z%gkM^XN$sVZ*C82{sP-G$Cz3Hd{fIRk`M*41^T0gR; z1HY+=auOuz@lCjNeFlM=$>TJJXnGwPNYU8zmH#yi z5og@n2xwW54*rZvFR*8TE=Y#YAJ_!3UvOk)VdLt4(%vaEqJ+}WE#LYNM1;BqY|U^0 zcw4)=43hj*g^ zh!li@ff~piJGv1BBUE3`z)sljL_e7hOXZ>c#_S!_&tKm1Nqkm6@qJB54WMXl^Z^^d z9~L_%7=VWQD`o`{`~e8&Edcs!$o|(z`_gHR@r}}5{|K*z85wr{PJ-h#b;Tx{ZUp2AGIz|7}AQa*Lb;j;y z#`Pa0ga0c1za=pXe>K(p5BUBziA~nq(#?Qyx47*;_29OteZ~dEU|LZ~0E#;J4|EFv z6YQF?{l?4A{}cwX2L_ND|99rK>{~c!7i0u?|AU_hgRajiTUU1KY8bw}e+hNX=Mf^2 z1#2SsBf`Dfiy&26;vezwObDDfpaz+*xJo@FBX*W^;3q8X3*e(50u|C^+iyFn&ijNP z$o$bb=L9Y=ZB1g^1Uh2@NCeTTn1vKb6qy=fkz?*~Eel3z^aFl@J-=fwlsf=|d@4v< z4?w*qZa@{3f!^K*kAV8sx)0YN8VC9u{ukyGQo!@1^uXJO;f{j#0LJthxhi8S1a8nrFzf+P9S5I1N81fRu+aVh*<&MTb4Wo^k4*&-m3dS|4)kD5 z_o1g!l8AWG*A@|Z0f;E@`;o)54d4T3#~B>Rhu^r91Q!(l?H3{i=vS3w%JZ&&2lu8A zD)uZU6;RayiQ%%}b#7V&!A=BpTZoD+;@Y?oL7L4VYrcMpUAR*8JP!1;FyEae6lLGTfvB=bLV z0i;V3urq#uXpSkF;mh_PXilyUP)mH$)Bg5N&V!mpBKo5*HFl)6EetOan*?Q^UO@As z$P6xo5=HI4lG!Zh$@8tLEAFQ+5kz_(Yn`}q><5QUxdcO6MeP+dLa~hJtuPB|=V6gE z#)qR%K$G+gRK$i*FD$fK_q_Da&_;E%rT}@cy+`mL z^aF8RjQ0a0E;O1?2LO(*fN0+o%?^C%WL&xv7^N`hJllAMP5FW3y!JzD3t06`?-pHY znFkyU?{NWuRuPr+VlNPQq29=7kDpz%;$itbzk<`v7KIbsTjBJ@kk}^r94Y}p#ldCk zl)Z`CAVoN;0LC`E@ih@R=s6e?p+AEGRB+&yW9Dy|H8=| z6aYlw3}8@4wq>wzBS#Ut8a|F<07O`9zlc;4?9*prB{1-~ z4=~!fQF0czo(YEh;0H`!KdyhV0GEG;XW0uMC+D8j(;_p3hvB$pdkRAIk8f^2}u z23q(ZEk%3*ntctL{eyW3gDz>dFp|saEo&Kc6c$~u4&)e$tJQ|ED$oUL72%!r&+1uq zXzx|c1c0wESLoV)t0g}gNN=xQz(UhFFryrU!C+s(-9BW4aFQYLpaN~=svGmyJHb*S zmH;}_bu9#U079$-GWG&cGH`_d@@~BR3j*~`0tH<2Zk#Lm3y>w-k&M@e?2JI8RO-BW zxMTqN>n<)~Ch4~TbGA3F6g5DuHHVmaFvfqa0y+u+C_)TF?11F9vGpLAu`Rj-1zS3% zbQfhbAo#3)`7JGgNC@{qRiO5}+3NxjK;U`<0K4#O2gEZ0vRwc?tnZpa_?L5-Z0f%+ zZ#K}TB~wCI{{@v%o;t>L$7b@~TSW}Ngzu%i!#rcl3a+PTiY3tn=Pn2uV~g)pDnLe8 z2KC+N9~)O*ko?g4VFR}6mzkSytUz7>@ixbueHb^EFX2(mkDoF3*ZZ~}0m#8U08+&o z_1MZi|AbzeQaiE*xsHZXaJHgjEsLr$J{7!iA6VvE_*)^%ue`tX@9+W8GJrPnmk4-x z=UOw}jkIhLD0zK00R&GnBUa@8PM;U=7roj3rVFum7=_WBn*%+EVQQ~FjUTA zU?!pzX-J`SA{Ui-B`VWM9>mh?EAx~47p`!a*0Y{BkeF%Re%`yP_kzmu} z5X~;4)Amyy5e}fV zq;YQc1nR%$Hxy?I6y6fbDcvN)CNGF%~~~l zx+#YO_a#A(y&)ONe__e|&-*ve<1#Xm55jo#N5p~ncN{8~Vy&#yc74^5anynqn3 zp&a#-z&&u{>R!j$?!SEm(fS{f;I$?kxD9sXe`a1MyWyZ=@MwtSKM)DxH=B9+NquY3 zDtwrI0ep)9Q&C6)R6N31!IuWMq*I)!uW^Dm8u$!`!1Wd_wY)J8Cseg8iZ{EePupJ^r-Rhxm&AW+DMm@^b%zf`})AayIs-Ur_# z-6_Gb@A^iD)d-=$bP|)P_N6K3n;ZKy;1t0Hz(@mh4}AQClR$nS)iPD`#`#$_d!euSy7VsZ|8vh(z7vd|B8vKo-B~ z`KT_m>bJ&UdR-`j0T1d~#581pjl3!j!0E++V+jTkek#*C#XDelHpOz|3q%CoaLzw;w)!DH_UdQ>T9}+dCFv)Oc+Yh`8w192&nbmnxOO6K6x*{}+%1JF2=JzI9qV3%v9QijEC0OsvyvF{zxT$sgUTj6%?Ns>8t zK{`J0!BKaVwL|DkwbBR*N0>xz_Avt z69}{bCG20c{%+_$?EFX0TVK#92+76&4UpHW{t3z84(DGLhyK3&EARhwff9>C0XYOM zf&q2$A7uQ0L-OyS8POC6AaY>JK!wTN0jD@BxZ(X5B7Sx}lUCm5R{r!5!)<0H+WG^G2`<0C?-A;1JcDlnM;E9SH{yrv$`@{@fQFB6+la zVz3xtj%Wd`9_$AYf{VBQpAZc2S&HGpq-CoC5f?>zSSCQ~+~{BTjOX1oKp}v`1=&Mh zye=x=#2>Mq@~y*jEat%HCe3uz06`U%De31<<7@?-MKnZQ6L8FdEs+MUr}6E*>jVhB zP(yGA7yN!l1ZF`3La$36L%o1Ouva;WBvVQm{sn@uK9!^}d~I)jCUo(!v8|E24Wr-z z&iQAl#Bht24SfE1OM4kvnK?RSoo~4>+;Rfznym54-qT^Y%r1EO)Yb89BcWlDv`5Ua zoj7(*-$`>0&TtS>rglZS%;8}uTCpjuq&$0sFf2tho*>a>QBC4BcKQ@4yP=1P$Aoj> z9_yuehQm|r>C!CyBnt1l%teDsf{s^qO0+4*`8X6<Mk{Ocr?jyu=b}nog%cM&CHvOm*SnK|i-NkFE@~o5(yq10y21V=lZ8i3UU8w2 zG~E2XYkHg@L3^%1owFJghR(;%HYSXcY3a)P?rqV=_pDzu3Ln z5%!GRk3Ml>fZ->4)9MG=W0|s~acii z?yj0P_SE{QD~3*fqsR=I%xa{?ju)Wzm~?Acm8RrO*Yz+f-Cn9E2wv1^S`Hc2$B`7e@u1@c{W8hDK#AO3Ej)BB!!`n6n{>%jX8*t@ou=fpZVh}-pi&f zCT-@{6DsyF+n+%q3&+;#Va4kUUlUh}WyCFP47bE1(`C%Kx`~_6);Qwk3nY0NA>?aS zRU!Aj&LVFr1?S9%ZYmaAe>l41!16Pnw>9Ysl}uaap7j;En;@AfOf+_9;evev+86or z=bR+;iHcj)A}-^W1IMTQbDJKRenn8`MsHoP3zyU|J16XXjk<-%irW zUn5EPV`o%Z-a7Tm=y>u5f&3e}4z3of^hY8ap?U1eg(>X?r9{I4+N-L`jvY0QtUwzC z14G28;CMqtuTVi^C zEx4>U#yz~j73z-r=w9aCKi(Xh%=YQTk%tmVJe%-CnIlfxJurB1*w|OrkBdq!#zp5@ z)E*1G#2t9=Kv^DeE}XIeeGIi&p-@g-Q)$2B5>`OW^>~%7@R6(77-pz)WN|mwxMhKt zJL{v;+ZwbsV}WZvjc=tow1N5-UA2Ie&3hFs?no#ZbeuvQ+b?)x>pnVJCWj{Sy(^o!i%O8B!l;ql!8)_~LB_8Q<1#=aA#iBfU9%4*g9+1DwrnjoowmL|&@N%#+z_+K-IR{~^}HI8ADl>ih^rS7hc*S2pd*H*UkjZos94&n90ofM46E%2zf) z7a!Q{yTuA+_->zV6Z>QP6C`r(RfR@75Uyh7gy&JXBSMesI+r+eLDh*BNRTI6@Z-~C z9`ST3sgWST?OWyJD+G(ri??HnRgy0-P%*psjMKK$7BsND46c@yy5BA}Cxpwly$STU zR3ALhGWSB-9bcxdbt=8hzG}2p!C5Id%?YdI`Ig(@)YbG7daLZ)o~2W(y#K_=WPy#0 zYmYL{Qouvh&y%|NZ;4UjH#k|JpwjpiXJwv^*r|Ab=F@hAG4AkT%%G(7Gqy*+A>v6Z z=K8UkSyyYF*pjOBB%jWS)e7n9%I53A*UGJM8T%YVp@xBbZ_{jyFjXMqTtXw31y54v zWq!IrlC((VH*)?C#&whwL$ zDUSKy>n^R0)gqg$gjv@QC1RRoFKVl`9TA_t{)o#IC3rlaIcCeBs)$K%)A%_q89St_ zS2*Pd$^DpT<|T2)Xllx@Cu6uoF7JuE*3=CzD|xFEw>iL6wSI=2`T5tb0ZN+pOw&~N zg)>ERt}1(^SuVywQi!sR{mfUp6SK<28Yi{sYyx8DeHDve9CaAB5CP44d1L$-I~g+O ztH;hUd9~}b1;Q=VU!R^9X7w)Uj$p~U#Hhck!OgzcJe{Whx^RLsu@u?dLZYpRN3sEx z8D4XE*%-pudY=h;f&sC&*FX34+1J1p&w`ij;&rG&6o5p9(_E`?SZc**4T?Z;Il z3C@|>8}m9X17TTaFUI_wSCRN_)@tlayIj8g!cOb25prxM>f*h7yKLz5mGD=xWEjqq zV%|X~W^nKJmW+z&jPpg=H}bow2FEcua#d(n3&V%&57yKpcdf8mC%yPEZsmj=z;zl9 zmJ5?IxjVB<`>6?S)&nXGf|&#pRA0~|ur4uh>^(>&B#)>@korU%CYs6x{#zJUs07n1 zyr-jY@H^Z-Hv86-P|73RGx~^FRr=m3=Hsyu;d4pGX!q|sO5BdeTLUE}QJ8wT6-#J7 zHS#JyLTB3t?#a)!pyBr05NRW-8yGrUAI0n4PvcVVl1~%ki?yi==!Fklw9f}u281N7 zs^rDX`<~nhUB#k(P;6xWBvrRC1##=Op7tG$B~v-^s`$^k9r7&kn1t0b%f>QK7(IA1 zkhS>5t2Srof$qM5l9yrxQ54Aw0_J%grBV38TsUDoQc@%t$;i+gS!yZuj<~=JG9ma2 zhy3V|*5SRCro=U3O6c8!L;P9R4oBtKw2vyQKYZBL^j~vy|By~*jla3?Yet+k`%EQM z3bw!Q9go2%F6VXf%A&N|Ldw3~>BA$lwHo1WE|M9{m2}RElqiLVA!k`62%gmmhoqJ3 z;R}9p`ULQLJssolTlTY9Sf3EHNpIC@SgrCKG1&DAX53+M?>OuY=qd&@+~okFwYO+* zRW}PSMTbMuwYAbP9Mc|)=Qg$Da2cw5oxIO_kYW8`YrxKQhZr?U@7U$*0McGon5BLq zn{|+ntE3_QN1n2NZmed-ttwjFPpjYOyH#I?P?=(Gp?Z%`e%U}PE+8&jWnX*1!%4g; z2Cuf==|)xHEI8&kQDaVSIji0tc;`sOft>RyKoj;TcUT(N6Jp@aZSSNQ?%JeZumsSa zay8#mGdX!?!Ov@P->+T4(A>wWN=<0rYqWSScyRbc6n_Qtm_5bv!LCeY@(8h_S2QQr zlE5;}#RHwkcMj@4yToi0V)b}dMr+OLxxuSh;{J2wuz_b zx`=zjk2t##^KuIp2Z+A*dPk~BV&hRI30s`YNL=uq&}3RqKRhXmTX$ccyh#oS~NoPivZK%yCq4J77~oQiI4^Tk@1gDsm(wYf>| z1{OM-PBP=NWF)RUgX1B;Mx$P{9Wmt$f>k?G+apYMEks&8QSRt%CR^eX^GkOs(a#p~ zC)Jf!G7s-PAB5Qzo7QQa8ZrW&=TYpb+OEO0=x5&SK}BRPW963;Bp2R>5?1Fj_&rgS3^YGjhR~_`d{~Mg zqUT>W563XJ{O8ToPQuLX@)5P7jz<(wOBr?WiHbOa?SYM=F2?Nf?RUFIJt_vu2%DZj zBva*__WPRDCN|~|TM4ErHN2@7#xwm)i0EHOCf?(dh4jb8e;-zeA@t+jz6FeWjswMV zeT&@FT;o6o;gZ-`)k0_4X?b~WW}O#?aUY8zOXSK)pY9XE8qHu|)Ob8o2j=$YY_(Az zO`^g*`?9h`7sMV9=E%jx?_ohtm>uD3EmnuBZ`z=*6E0zpQz`eo-?_SYt8xbu#eq$)8yo=GaP~X zpMJw@Cw6xs8iEKvpVxLIMvRF}-7(#yseg}t)Q0&t5{+G8^ZTV@sX&E(G3MBuLj*izhIS4 zRhA8K`pfef?SS;k)o5tD6AXi zIV17e#jf-^1&-bM?9D{N1|2q}pI%jTX0Q8GbcXUN1G0`ETPiqz_AB{jaFB&s!D9_Zcr1`(^bGSw3! zpFdcvEJsFUji*Ih;|lqD`cpoLM?@I(!M@#U!zdriGdnN9IpAVUO{O}#tBr=TFNNoQ z;jH!w;jska{sIo$D;vqz@yY%i_MM`lLvd&ya`y!(g2zs}_NpNn;mw&0FDcWLTpwy? zEYTAeibT+&rk;$9X=Y^8h;vS98RosXUst2q6(!i6U641@I4!Y=ypn+W>PLUnMr`Dl zS``Kkfkiv#^1)AEM~eD0Y3O&UntVfj%U!e7 z+eiQb>4B48d8AjL9L@7&t1CqZ#IJia#nJcl^0hN2(0kq3zZS3+Y#|-aM#P`7-A9*9 zX`=aNxtoXKlO?W5+?|=e3R7R;{TTy)^(ETONGzXpzRnT#Qzb#`v|jR&Q!>xSL4G7A zslkL_iu0`JNoin?L#T_X?c2}jNyum+DG@V_;dUSFwPr@dqepYDJOry}Q$60_X`1?G zOPLL?_dZwXH5WfzCuT9ILP99=f5jeW_x_vWzEjhL8||CUVY;Wqs-o6Ee{L64Z-* z`SGS^3sp#H;VFX;=5+dy@i9EPnFFci1a3*WAnpfYjIQc6b$x(-{}iKXE=-tKrf)xu z;W(X|L_T7}^I+z#8L|p?*)l_)~!teqL5)RX0PK>x==a3C1y(gBrl)DKO8v~a%hYEjtP^r zXe;BzqRmG;`cE`aEa7kmdv+Bin}uTZAtJ}Fn)gQ1l)C{MORwD^o4J^Q_xotblGG)> zsK2clv^XZqA|j@HoF>*FZQ6Lcd~Qg5j88$=3S1O2*)ApC&x!7!zCTV-fa!#s0~-uG#Q3PbOem?JZGvwz4V?{Jh^twJ8JhH z6s@bKV`^K}dq`m`sq22RSZ6pi{z1DJ>FMJN<2lk`Xay9JpY}fa#6!xId9HEq4MeIE z8?&%bl=duKQf^DeBN@JkSdS>iKpT*)&@7k_S$Wj9GQwbP&^7`&KR4lCAOwR+0*JKHmM!Vy-Wy zXX6t&Y}&fzCj;c5CG&YIX))~`v8Gg+QNf+=((+W8)*Ok{l|$udnu|C-$x!`PN$P6( zL*-8|UvNx~oMjOZU@9~ktgo+%31AxjaFTy`aEIO)uO>{G0Bz!2Yvk0_GGp(#{27Lb z7hF+H39s8Pz&&B$;_L0yC0f5ht4Y;OIk$2{2cC;JHHeH4_^LW*M=Mriq~H7?jq;tA z8g~y&{AubMGJ!h(cHX&55pm}3l&p@?XV&NBS8)Th*vk)vs4Sk$#L36Ju!>uN0nZf& z5wG;?%7^p@S1vc!b+F#wBa~`!?=cWummm7l(JcTq>(<;>MHY&JVGPO{eTHi7bu4cHMr=?YX ztG-0nmHBa0E30`+Jf{%nDDuv+WTRv=^1IeJqx)*ks#`G%KAF9JrAwk-bP8`CefA;m zTMB&93e6sr7tXb#quD7UeU5)7P-jW^aI{*fLo%SXplJ`&Y1H{kADjIZ=a#RE|;cLa>R(lO)-P&`_JPMRJjSQI}0B4o&wRprTqVmcSsRl;rKMjGdrnM?kTBO+)x z-1olSOD5a$08yW-rQA-7P=DttF|&9z_ixDa6X%rxCnBxzazg|He3^kHnl6H`YBgW~Pd-6z0bo zef-ovylS{to@P?A85I!h=S+LKUF z$%+}d2{B##5I1+bkED~lu%JuJuIsoQPlfT+zU3+t%{jXysbuss6O>b+si%U1^;->r znzFT{)jd%U951_Do~#TS)^Jf}8;Vj2x}lP=0b06-!}ZBcN&eGC-4tpJyu7x2yo6|1 z!2e6os4V}5k+_Rygmh)g1!a331m|lse&R}bs#s#w3_k(39&BnY7mB^COF z8@ATR2tDkoC*pcKi>oECa_%f%3|BwN5%{6pE_EnqG6{yOK5V$;WFON%ca0^m3@TXYB175#84`&k_`J@yzCm2%%Y(IG zp~aBT^>K){aW>X&E4NPaHzh{86mTAni-5A67B_jA2qjv$W;q`* zs<|cy&lfGI)r%nuby2<}&F1|4y}QcK81xS1&qvPX$HDj|+HFv2{_P^qI^wo%Poi?S zLw(Gt58DzajmZ{tCB_6Z#hXr%ZvDE^W&p;?IKm7kGg)RljWlIoptkbIEK=5$K%w(` zGLC}NgihAS0zLPPG9F$vIE1OlMYSyQjGy%dzH?7P5t@~i3-HC-wu{d;Ie9Q|d^=+< zI$LFtwk+F@d}Qj`e(-up35p=aX6g$UdCtaEhpz;0A@T7x@lTDcab-9*D=~wUWh$PR zYSoCFW}dmJN~t<~$Q0=$I#o8VQb-{iuclyx+h&@QKss$6re-SjDk-|sV&Ou*+@_T( zmc^Hmqq*2DVdccEh>JaOSe0IM!qfTDYe#K!Xz!|)USbS zZ<&+u|=Od9a3Gn%C}5ZdZenj|uCHZeSTx1h3fB^I_KrJ7Xf1 zy3C>FchekIf(2O53ND>bL%zLOrOii*ZNCWOB!6@}MW>dPd3v&z#;6yIM-%VGC}*0C z!*|lL?9-TNH5Z1Dap-dHj20YD?J1DNce=~vM5hyqB@RgY4~f$V35{b$q~)|{=v_yc;Q2{ zlhqP&Oz|D}G+&lZRL?efpW8Hk;%0iYiSU@pLS#JQPMd3qQC&?h(Y&UcVQi*)D^sGj zCOjzKn#$U3;+tB+YRXaSX~O+IlCHDUdbnhdQV$+J%TAd6(4H$&h`C7b%%$^yI%o2w zbI09pR*gdSPilDPswf|!s*3OGu{$Nza2)&yVo>>5FIK{#CH2%Ug@ZClZkHk>GqUoQ z9?Rk8t@bEE_Gjj!VrqTOsRxN%)q%0>EK7N|V^OZpD_-4&j+=$BJ#q|7`n}Fs z4}DC7Vby&4Q=3uFm@$uds~s34@vBvPt=A-EwWqM%J;oJ-QiUMf#Jk;}V9;9(Pe?@q zkmieD)Lo3BBy(4$EuR z+wR6~Z(IemeF9%d^0!rv=uh&T7-2t6LoZ2@NW9=3#GPyiAO&ojk7zw2U6>q}G3X}L-iJ_D&X^ef7Y{3_eude&V+B^{a# zU9e8eZL^n?8x+~*`qSS%Qy6){C@qcyH@P2Cl2SCO{v(ut858AT!k545vrD~VOqA=( zyUHX5T$ZmxQccROD=Ke)IvQ^(YYgIZe5U3~T?->3J{S zYFmD@37aRPIu~;}%XPnMt{~oIz%- zh&@ryEP>O@4mav6EllFIbfQmTPmFw>63c2XMd)>xlbWd1zVy^-Fg%gTF{_c{p z{Az-sx&s}y;#Iquy`!{ds}X8!?ct^G+EKFjmAJ%DPX<+pm#}8)EdS0E^*tr!>xQw^7}>CZF8@apW7Gv|P}j&+?*X z_09LmP{l>T7|5pWe85n*kGvXd*HC)n=k@f$yhmZ~2EgjH7$ar8AH5afpN z;@f3EO5}`Fni#&Oh+Pg%97RJytNoT=o{bRqk%X2ts|t1xeoTzncAGOpNCZt?$H`;H zxB?&f6n`!SBI+1BTE)xIC%7tj@3fW@q%9(tCG;olR-ZV(@bI+~^?AcBV?|tE2xore zNX43IlxvEiBSl4-l=j-0%Y5R9{aDe{r}AmOUfu%$V$-@|xfU^Ae5r5BQeSj3Pc|T= zgJ&X*ncfP`;plCMAo$XD{VzqLRHwxe%**bNM~8{Lp;`UFH5E zwU2B^T^xNgUfoFwB8qrF6zJl2_%T}LewY@gVSe)ICqGwEhrL)Z(Y7QQp>ep#&+a;? zDu`Qr(0NH%CNL8(CVf||cW35}T`ez#c^GWk0lF$S@6;5S#FlkpqJ}+Jb{3JfFX8C; z4wcjA=vC7C191b*Et7ySx}~@d{<`9gv_29XWk?E_CBX~*kaHJX0;X7^2D04{qR%$? zQ)-3hx!M&Ingy_XI3~%0lTvR}#1d7+i2ZPPrbJ44Z8fowZBeU%g6I2l z@14>9ww)G5Gb>7#ArU*)i$t2*7ou{6{X9)VRN1q~9+T2e1L==>%+|jwg*l_ww>#!r z+d1HRr0L(m6McA&U;|ke9=e|)1qr!Q%OFp(+LR?$J|Q0>)5~wEHRC(N;y|S|XyUIe zJSK^c5`Jjjn#yY^-sMjBnNGjP=AEb1rH==4LI;`Jr}U8LJDHOlWt8?PLIXg}i%MHA z(izWg>}(Y|d7Z`_VcbFi!Ul8`+{g6wDwCYL14)Z$tMcjAS_szXbY5TTC?zWlJ#n*M zM{o#N*Au&p9S^%YsLk;sS8ZFXJwp)JMog zxigNwbg+sI1S%+Ds-yB(2$p-5_nnQKm4+=vQC9PaG@;mhyZ7mRNY+x{iO_nam+BR} z_lgfqJ0yFu>}TTT=9>kLuI5jVU&sZ`-LDflNuR2)5i}om>1Ny~x8XvX z*MobeoK9Epj-K4%?0m2q`SD{Tw$}+Bf*5OknX6F|cpnNo5^!ao$j=ke;9$2Ly|!mk z;wn^W9|%{ZIIe&uoUv`+p&sea80M$6W=?9>`69u__UNlhskj9ND_uJODpJh0JZs$Z zd5!8jrH>t>(3=sl?66fnnb;oF%wBP}92;oyDH4*2U6{!o*C4a(uTtcEDx3t0e(;B% zU_MI8d-_$!S=ny+J#F>fHS=gn-FRSlb;O@+E#m1{@kM3Igz)B*lhtW6%*BX+>dn>O z488}^j|_YL266)=$9eKsX%)`dqSGChZ1;X(wttnXM@Dn6?cU^T>)OM4-kg&EdR39A zas|Uhn~-}EkF5REa^;UYU6{aAo=-!1D(0k@Kl8V5TiM4A3P9!~G`W})L&!Q?orvP? zrMPIB)%6A8cZN4JtZ3dp3N;Q)o1o)BXVCG4U)L5ET3?8Is68~CneON-PxL2eTtq$^j zR-1?Y|FQKJU~%=_8tBH|DaGAgio3g0thl?o4(_f+i@Oyq?pCZ6cX#*F7Vfm)_n-6M zbMN!)XC|3sCu=3yYm)4|?}Dh7aLTf;Ea24W^J>#ucCSBYO20yj5s9Cs`j9AvSFrZg z3G7ti(g#CD<?&hTM%LJ!meI4@%s;IzsqUEDG4Be& z>)ki53)&Z<4X^UY_MT-FgYl ziM{y&S4hvLz4>-fgDRt5BUG0?RByiwoM6V79XgP!cLDEdBDf2PX1$Y_EIC6jtu1y! zDlTPEqA(gmC;=)_%$MULwXDHnseU68J;!@g_LOKSm+ff*a&gJe9xD+rgCtgbS1?uB zZIN`5!dyJ^j{JTM^k^BcW^DeJUm0IsCyaHL z+7e?7??}F6roe(w7XH1yi%UyABQ;(*B}a${E=PD4O5rg7#~$?0OD0i4!%nBqU*@MA zG)(13Tln7Q^StI!XgRJBYBG1D=x!CJsYjva#egvPW zYsYb7e4vCz<5o%Sh0*x#9z%8|Eh%tJyY6S!kqM7~=Q@#yBkzq`NCqGJ&S;pU`{?{i zJu{yw*hJd@XJ|;B3N~a$=#)rWVFKIbwUjezN|J!M=gc{wFmF~w3H*7W{Ko^ z6s?V)8qr{$ygJ9?x4wqgkU@ywU|&~zTg(CR=Ayo&_u?`qOYF?CS~?B1MF#_Q;r%8{ z1F{Di`MDW@&(7+o#XsFVJ@RqCI^zfo+Zy_Q0MS-#f<5-ugr{3l3uBIN_XitEo&~#j z`qxWJp%wSpe56}>>;bHB2K?B5^+uIAq&$rfhO zW|~{19nc+Goj;}jSVHP6Oxw9V=)JJoS1$_&yxN_M)tRl)a45K`0%MZfIhP&I%$sCD z;$Qt&`1T!te=gYvoKk$ zCw0<5infYRApAC?cVAkkT!L8QibvY(~hDYf-JfycCoZ8+4SmWJMzJ(Svzg;M@=UlnvNT)x&5&13_sS@ zi^4C)s4GWEeRb4wr4D+LG8kSuq1^i6)jO z-9rY~Ig|Z~>3r7}S{*+jQ#7sq)fIPyGXPq;Mk!kL>&d6r5&kl^%x_HQUfHc=#j9T{ zEwrW~wi+K|4y&|0>O7}c;R|5|1IFDZOm!cRMK zk55pwgx_-&@5C^(HwG|&bTavK_D(tJw_YTX*hzP=_D-fQIfbCUy2JApPk#{``KefV z^7~LDM)Q+h6|QAmqd)?S9`QXz*mQ}V6wzKb*0aDKJ)4%lL;Tzc77WqRGBiO)WkoL- z#z3|W0Fb7l`AxC^0X7M$y`Twgvj_T}?pM@CU(e||R(H+Qc``u1}(<#+A#&F7%-sDW>W z;((k4J4Wx?0DxIv2JwxK%cO*t0+al8`ucpsO?m0Aaf&VB47u0a`&*efR|aX2RxHJZ zOS8cT6ro!9<<>pjW93PbNvO!so@@1DSc<_6OFF6d#C@RndaV2DSu4 z$NKE7Gv=85u)&x##{$zmckAeIqg)v@Vk)<~VM3l{5=)UN4eKEuX`!Z4E<~6+24qQ= zGNw2cimW7Jze$TK)APHpB0{z%0;dwZGt<-cyQHv-KYmL?cer5@hLJIW*TiVBfAPHH zm9@`esF*py{>4Gwrf#D;fg_KNnu#r;%3^!}mcEqUxoE)&PpHiKBUif7xVANLi*Iri z!c*bU)ghkBIRm3A;&bE~~R5F(532 zcbiL37E*RiwlEtVAsf>~BoK*|Niwg87xRcfc~@gU{zP>=z4rny{NsF8f&o{5#Bmg} z0;LrTO%Tu{UC|9D0kvyV9d|nDS3c|0odCXYODqA1OnMYu+g!dhnX1ZKnt0b^r+K;(D+gT)e+ zR{@ArjXYC_Qy`J!3&iNK+N4+SNSm=iVPkWc`U3poqVfGm8@et`o(a!=AgT>ZP&;M&{j=W3YD7v;-g>bW1fTY%mWv`!KdnfRZo^5T?#4t_48BK8Sz{_MvUwz z=2axwGhM5Loh4#-ui&6YCXC#YCu9dHp9u7zz8UBb6ch|O#!sUIpukTM6qtSm48_3$ z{oxdeLj4Du36lx2_%Fs648Q^B0_MQV|APY)6#>i!KQ;0~w1W)1djr6J-KAU@g8({T zd+0?Mc5+O%y3N&5`1iBEBlQHL9VTv>MdvSmy%=1G&#d)i;RMzBo3F*Rglx&%E#JU2 z7*G&o2p>LY09aObTlio+kaRz?2aFE#Eb>jG#9Irh7o*r|nN{TFhx4ETCdo|v-Fby0 zoxQ{z%c#c=#Kj2CN?u_Grl~z3HxrNx=>4mWDFEP-0$|uDST#6S0E#RVK$ZEM0#^0E zuiZaTvlOsicK_nrAPq-Ma;dw58zGPNDiTA;d%y*TZ5Y+FIs&U09HS@zRAxKY%-=$8 z{Gc9-{?-R6$DK^Um}q7u{ak%tx}RF6m-L92Ywz`}-xc21>+u-u@n+yMI(Z*NI0X?^*OJu9FA z0v_d%o)bO+C{LA)6<4Kn?>e8qvO52SrJ})dWUPLY`ij`rIiXpLg|7!;#=GDX4WVun zq!uf#QSr{axyh*%L68N6QqYYQAiiFM*Chd#9WtJOp)b@`!e`+f@9<$`m*52@u-*P2 z{r=Hgya=bTTLy570AQ?Ua$o5%RHp&T!bkwckMR~4fd~hVouZ^b#Nh}Ejjy*C0zz0= z1S$V3xwJs66VM%LT^krf>ir8HM*c@4x8<~z0EfrOU(Mt(HH);`fk-BCpyh-4_<>IZEOP9S1L7r-j zeJ5hDUI3fenS~ga9x)?XU?T$Stzwp|dfqHo*$d!YO5{F#O4*6g9gg7cqrXb~5z^U>&sc4(_VmQh#9rXfU&dM@9Sl z#7b3&^vs_^P%MNZmQ~j1WIxWQj^%-Xnrn|MHkVa;v^xFf7ql3vt27?UUPi^J^ z961o=M2$KlK$11qy6?$PmZ7s#GvWnPjh{L7n}W$JV*UgspU~p`>tTi4CP*775;lVR z5UW{ShD>R~YDCN-;6;>_-gyN;E0ti0K<&xl!40W?(@bd6BpCQFpbR#cvG-*Sc`y!MnV%AO5Iki67S0d z5S6lWhh&m+)#H>fsFG_i(JecDh$VKveSLV}QI$|H=H`-sfBu<5-8jQlWK065_7^O4 zQeW1`cWx`CPX-1nKg8LicqQ(=Nl5`hE6TfX1!T_#y`B_-$%sc07NQ2w_ImKJ2$}6~ z{N=}uvp!wixKIJ`C*lVp0(_uVcV*NzLT`-dfNB(1baEM_oR2F8QaQLKs?go&M;#8A zj&x`H71APOeAj8C`ObW_XW*-yIHJvS7{YY;=dl*oR zHu<%0_$W2O+5V-|aW~z^ZyM|~<1iS~QtM|vdUp0_WcT47L*Vrn&7#M2A##w2_vjaXGTBrW{$xLj=CGI6y^5B1@Ufia@51a zdX-4(Tl7LmFk{b?AohZBz)(@)1gQH;MMgfPl`7pJqfWF0t%G~Exhp{0_aXa1TIznW zQG-h#1gY8wFRwOhir+9K-&+bMFT#h=wbA`6w)2HE!pk&($-a=NzNyEWs}TqQ*jl}B zXkaB#ff)@3Rf`u9DCR98Je}iKZ>X`ioEUNnxgkZY0F{U_bygUEo3yt9GXe$~2!bfC z`$?7+_kGAHf(ihN2ysS41JiiI7&MX!V#Aix#C$^pK|lbc8TDd3@GPsVvzZJx03e(I z=B>k-?}ZuRy5d56M*mk&7DyzMhhgijf1`nadJa7Enf#xbk6R)DrGby9nMKtL9?fHE z5BK)xxa~;Ot>pLH_f?(%RLhqP(tqy;aIn17l4Q0B{=^|*U{eydAdH>0@Xl}}djAqi zjaCBmi+>XTWtW12_yUHo%Vnar>4AaV8HnI2z>MRpM*o)Q8eGfzH~5!KlzgkWndo1Z|JS*A8W7G3o{4>*%48cM+HHK4v@F5gt4y*6WsmH<`SQY zB?cmtNlGFo{xEX6_yC?f0P34$*bqeWdRSfn0%Pw`>@k8Rc9q9Z5CC;X@E2tcAvyZc z0Rk5QW@+OCA<`r{AA{vgcYvL<0%p6m5Zy62JC^t0d!f*+aKZ9ZOi#c6Qycg~C|5sL zVg5G)3;q>|2CMMTjO1?y;G^na1&FV|I848vk-*r3SEjWFlV<&U4@t&XpJ@QSB?tg8vMB##sygOLmC>xsLvccq_yL1KlK!<&Jl__8W#lGT8%Rt^}D4@ktmfymnd_XsrWKfMCxqXCx&VVemadw=Z(?bRd*V)MV` zK=|};gxnYafC|y<>Hj|vKbXvi6ielGH^o9HTbB)FCISF-k-x@34N6qvM7E*m=??m_TjFf0EEUY zH4MlJWkL2nxgb)EADtuT&BpFP^@bitS97kWKj~pyQP4ISY77`LiwSwVbR_Bk8l8jd zL{ar6!HvO+h9xnri6-|Im(!ylfnAUUG$*QF%`ld(x0DP%ft7PV10l}Z2nYIhu~ivq zT}w%V*zex3JbWroY19po+05+0J-PO1o9=2gmu$8ByU(KcvAb@{xfM1T19|*4XfGfvN6B0nFlh__sFo z6frLtfZ6Y|UI0B2dc47{bf*_R@i(-Fl*pgjz=W1yCreT0HFDw@E=(qC;pA0 z9D#)bfra|V9)r`6!4?>e01yE`U@#uk==r@!yrUFLkU=Yd+(rQMz$5veTX{*rWE{|u zQ)dy8FQ_8$s!xA@jGg1{#Yu!n$NbwiU^=e=Z%-e`WZO zmHd+gWArB(>csXS9D}D9D40`hNm~K0H~;rGTLtNe-Kf|q0eTh3oOu0Q|)*n!*OKPK`2r2pS2k_vn+>HjU{|7Q9h z4gbFZsx5GR;o$oI$9^G~iu^54HN5bGIx@|3a`;MZg(dmyS`+lY^+4(EO9N0=t8-zK zK|)0vD4z4AaOGJ3;J!i^0aQUyxR`%i7(B}WqI+}G!Mw2mV1~2>wnmkmpZ>Qi{#zc{ zKZJvRU`hV5UH_E?Iqv7enx(P8lRQH(^fE?;QG@b@;8zH&fDp2!&w0y z4PcfN2P7%t5)WpC`BnHvNTl*01G#$U%;zVFtb`O z;L=KkSuc-3jkD8>tb(@%KyCnyPxXo3qE4_Xx}tK}^?&k#iKiff0Z7dM$VCp`!}uQ| z!J6&&|C@qx40ghGWgZy>ki24nUVkxu?xb+_`Zv+hTxe2)-MN+a-MIZTF-+|6jzMz1 zjkpTd@ak_lt-utai{FQ_^*x1)WCZDNWI8lAUsDaU%7uE^=8@~1?z_jV#Y!jWQ9Y|{w-Bj&_e5PXj&t7=|2nunP+ z^K^DF1yG}w^P^_r9IESx!)k5o{*#@&Lq^PuC&s>Q=pd&sKV)MEPJoI4`d=;KQ&oA?#;9 z_LtQoj5UhFGaGj#8}g!#@H=jhqP~>}rKyL-PlFbEv>4NUB2yy7uF0Hb?mIiZ zfOA9bVS{&?W85fj>{yIK z(EIk*u5MnCxp3J8UtE5H$i&F$N89`{>;Pm<9e>4(y$a(OzX`~$Lw&&9tm%P7#2EUS z3Q)Tqc)v|@gj-zyojM~`9I9tA1txYtF!1Wu(Z7hFJTD9H;ZV{gMui%6}mBXV# zlp7DS6S&_mZ@fQCx=UUAhFFE`OEk`E=XHttk1%+fu}P2Rq-2+Cl;St}1x)@$mVn01{==f!o< z4}`zmQ-X3lGNo_tA8t4qr*-@TsE|Xma`H7f4 z(K(;OB$M#2-N}e}+H`RC%dQ2M5^lqEM7>o)(Gh0XZrU^Jybe0n91 z`$>|iGnsJz%5r5oE2k;W>WUI!!)40*=2p3ZHnD4r$(#q0YcTe6(YPIF)qe5t+ozd? zilhLOtLU#~^!r+_RegihQo|wqcD^j^Mp75UgOk`|a^7LCAzyurpp}BKBN=fDe(ewy z>V>rGn@;n-=Xy;%u!T9A;3(;CE+k>SL{iOr#QzK(_MYFm2|8Zus(i#{41eB?Hd9$C zf@)*Lx{{Zq8iJU3cD-dsPjshMCEl;~*fZ{`a95s0@!c=3wbxbaF$ULCa05;1z0SNN zMB-_P`nlyIi(m}5cY#?!fm7!N7r*^iCUpdR>piWMjjOkUjloER1~J4PNG zhq`SJMC;Kf2X&Vjt~i13wuECI(00hTm?|sOb)@`m#9_?KkF|5x$Fb1tjJw)tpZ*$` zI~W6rM*6_8eG7T*%_2PKaN-`*<+-BXbCcYTY!}kPOnc7PFrSe#AyH5UTI9&=0Tm>r z|Gv?(FK6n}E)wk*xHdJMXxbLxPflMVAY3fob`lFZdGsWee5#)8`v9F6rU6xKdHxwn zU6-Cuq;9})T%CS+Q0`N_Zy1!#q6NR?_VK2;pKT>x&FxzBiuN39 zOMVGsGshuM9skxM<;XF_1goOJ`eXFbg3=TmP!wimvDQ4nQ0VgU<6-&DBNb`|s;Z3bey&P#bb&9?uh+1dI+Ekcd)5sNVLtV^k6={8TU2A= z!CP(c3{UbDo;?YaPRFh_|A4pPQ}C&}8gEzvQLtm$ut79Uqd8FairgSRcLG{z`?a{j zh<=wScgYy(PV+`^zj#zmvOFl0m%p01*EceZcjTiMzV<3hyTdiHIE)0fmAAawsu`pi z=Eb%3_uuOVPq4y!q^f=BU3nO8^`RoZKPwnszF*RP;s(e@oO7- z7z!j6h|mAJwWF@j9*V^eKzNq%?ds&SGGEvBdNGLhnW(Oc@5DSJFbat4VBt*3($H@pzvxR~bdJw8VY^InO`e zxN%-P=%3fGrMY;Wi>}0NGzI8&df9uZlgdCr@_&wBSY3;hh4B<99=GOT6_T|*;PAeQxI*=+c#bDy4Yb0ch zs%?R0#v|#v|Ih^Y>ub+;;5)5OiWAOlJFBLsAFV7@T8>Ldku7Oe&!WN)WOst5uek+Q z!n@b5{-RybD`;jI7Ts~XP!VKn@2(w--@A61tY}X#R^vu8|DJ9Y&@;nNxyQhKZcXtj z`KXTQ%cj|!;*yDumUeIlkWHe0+?nFMw$<{q!xengK`<*gj>Yr!5yx7`(EVy}@=(x} zpzOH72oZ^I$bm^=ujdppC@AbHg#Ic#jLxV1-$!hYDP+rcHt*qX-hXu?KrY`*`SzRLV?E}2nxJ82ewU5>%EL$gu1y$HvnLyBPnm{3&wF8>!5e~2(; zrvq#}WA}0@>X#0N9e%}z4*Y!!JN;B5G>oZOD~M$tzBe|luy7O*?`Y5p6eaBm36FkD zfTD%Zv7+a8CR|?2YjoZ>{>b={%r{0j|3T8++oPt0BW=n7*=muZde>a@DtD*+6 zl^W3{bK(pIadQxUaO>JLM2-KLgisV94n=`iC&5oEmK^F#@$=FX;?ii+4*r;VHt|7E zLlJ~>4Lwfd7I~}Q=Zr+4LOS%+)AL2@rd}|2wE=#EjW&{Lt5Q1H-DkqeSVmZtc|XCU zmgBc{j8CPwH51%(hE`#7^f5w(Sz|$Xj{3JT>$;gbA{XISa>7!iKtwxLT2IF zLoBY}gAc541y_z-VA~cEJJ|UmD4i>vh&9Y<7j_9;Jz7r_@sWZoBqhGsjG>$2L`p`4 zXzsDaIM%IXB&rn6h42s;Iw2GEdFiA=$6|!tTusu@F?7G&K<|!9i; zL?zySNZZXefEI2h@(&cqCoxE|lr%~+YuX>`^q7(=$deL03c<0$#io=Dum*>9PU1fEA)S~#3PWb)PGr~*J0hPIAx2j(A-Doq^rQ+`IF1;=bi`8Y> z$HNKvTUWJXf1!B38BD8R1IBUyy^>{0Z_~JJx}=JrvITa>1j(n4nAgX&g^>rZk>&?0 z6w{KJ!HI%C>1Yx-nlDaQ&$vGm!Yy(;nK+Q?PhBh0?{veh4nSu0pM(PmRII7^GT&z8 zi2vT&^)%Z2rNu*git$G*K^Wze2fw>VnAF5YvyU%x z?h<>t-X7D3z&3=J)<5ctkmH1H&wWqxHf&#m)y|aC42Haw3k;1v{#<#{5cq!POOP{9 zNwu!nNa4968VQD^mu+c&%mZbtrs@?uzA0X|e-bq41B zKJmUms_;r9@RK+SkMTAcad0wz%NE!2RJn>u%x6~Tm;uJ_5#rUWg6M&W@4{uMTRJWy zA)(5!(N^*D3ctZOv$I0a3jqZ=n3WbUzrp8fxokL*D`=!^JR09M4?_XL=*L9|HB!H} zM~w=H6=;%2{U*r(PTiM``qTK{HUUkaW^F2wUabg-6vo&iJZhms|G>J$H7}g{!foY*!TB_$w-WP4mQ5)vB4`H^dS)!IJ5h7&Ce^kesoiod zx=!BIOkDgSF`!VV{lluqX4qxQ+btrlts#1vK>Km`RVuauGF?l6Fza5g5C>@kJ{4mZG zakskuD7gCBZUbM2i}+{6Lrw!kzgTa2WQWe6Q+R<|l1CZd?=>|%Z}B(_VkoT{2RKsC zxNZRyF~fEF3pCBs8JVvT#^SJE*b(}x^C7V`i8zn0VMGhdSUpWnscI)xr^57h6Y#MY z&aciPbII$Pj|W1G9HJ5GYBJcLAbePdtQ7#Jz$8&-`z1b!T~V@NtxfvYgMYUL0AV_1 zIZsVH>LZ;gvUebM>b1Bm@wS2{U)GiEwZ+@t+aDwMwKnr&Pg+90e;sy)bPqGoW4`ny+%XFU147wDyAaVt&Yn-@rH^ zTKqBd9}a#t*Ve|?^zBYcV(pv zEN}3^Scz2rf?~6B9;&?!vO^Ev)2o@-Fl~~1(YZhJBTw}seJWA^9zoTtZ*5T9&7QOD zidMTF{GnI%tSxGCY@Z=S5N29PjwdCt$Xd#~(5N@|HWi?w!^6G+0g|E5>Xc;YMnDSXRs5X9v5g0b^K*bnWCW`z zfq@`*@DY>&JaTJ(uI2oi8rJx)Z*M*{4?p{6gsn^pbXs)9_-B(jtr`M(Iac;`8kxr# zv(aKE`(aj$Jh-8j2h6F>iG9^^jl@rL!Ii&`fID8vscf0xc&E!Pclq)I)SN`c=dcM* zSkzAQd+ryxM1l-`{OiTfRSjEB=|LKGWKZ4wf48Tq$XzrnceUE)qdg6N-nfaUI@Z^^ zuWHBfONp}Wzv?>>-RQO=AKERGGI<*o|3-5)Ny}>&{QlTjqD$1lFpN$a+%j*Y>s&^s zI|~?&llB?O18A)|9efOrhJ2tsqif`oUYK>Q^x@9z$T$MC-t|-wIS2d+!^P z?dX?@e56u)YC4V`bwa*wI3Dr`NwyA{?<^%(ddl2z)Lf9O0QC~rDavesJG87lDVFsw z+z-eFy<-;zj^(nJ17SteadkmDHMuMrURZ#BFx`rjC~E?FU=&uNWT@){*W{IVs`nwb z5l`fyV!mrlbuB8n8JewTt$Ii%Q^`s{)AYotCv%+TP6T1_r-(ew&S7YAx=Ga>MT-L2 zWW&X~m75z)W}?sE^bB6UpjY`4Vm{6D<82v1aFG> zWC+c`VVmH5Gen$LspQV8fVav%ySu=dORrza9XuQQvU>Ktn`ZfYLKE8r!^)kzSC1^3 z^^kFvr!PuVed}h&-c5aXBbkTZ-~nVvdeBrdRCO$T8zm>CqeAxe$PunpOJ6-kN$ona zr8}D=)EH52m6Lpw_uTG7n!mqJ!ZIia?Ntg55~1;%pzxSTe>>lnfyO}uSF2}jzj<`# zeAestTeL|YhsKnJDpSo7;rz4b}=W*e@{gnVnIG2Q1yGLk9G?m=s^?SbdmS*r>}v9;-xi@;;cxDCDgj zMw%f4W`!(r=)X~2>a0m~zy9Ool4F6o3H)Z_XxLBd-BFEl^HKhRtF@0aRdcB_GUT^) z%x^1I=xW$zK4Fq;GryvbepZAY+e>=?^zZhw?JUq>dHNnX zmSkCtm^Z2c#mbw^{q?JACG3gDPq>rCi@S_y4@8m}^Y{HhCaMlbo9r9Z4EKdz8edq9 zvUS_AWXtB}<(SZKW>*s5F;-8EIs!2CAHdEh*+2d|n3AvvGa=}*Fpo#J6YBL#hD5({ zB{^^t6SX-D%VTv7m1Zy+uT6ISW=z11yRf{do^?Q=gLsLA7M62XSASV_9_<_5meL*1 z;OF^y+~I)d)2r;HU}rm~j69=mn9TXzws?OQ3cAuR)9Ohu;o_ta5;oo-+J*{jEUbQF zOD%;%5+z1sz;$u0tsh8P89|XW`S=@UH2dp$x?>u_V zw-9dQAuoPcl}k@OUSgR!(&=b$88^fQ=3DHNoH$eyCrMy7aM9*0R!m2>+&*bE5>=M1 z`t?#f8l;++Lfxw|2uU4qZ3J6Gz$+f~3kkfk;3I{$5^+o1WwWwu%uS0eVQ35mwLQbx zKcBS72<}F{`-l~^+OB&NJF%bT6D^Dk)dDYn@4}o)FqzlE`u%8HLZL0Mv_ViJYJo`p zRY2i~L?U&5>4_m7{1UfAFcW>L|I;k=x^Pxt$?flQrnA_t!2AZDee(qhGV1RUvs>zR zLeXhJ>@?>=SEysU)(iw<-xo%y!d^JfqEz>^htzPb4ggNq!8_flWi_}8NHQ?$DIn>A4oo45^m8+LcguPE+jM=`Aw#$dz7UGpn^MC4{%{FpP)yY1ryyheci6IWmOS z=egDvN@kkbDASGSWqq|I+4GACdw?rP)kh=eXv~XKH_oL(hT!IQi4IxJ zV1A|8T5;#+RMKQ$hVP}CPrL!T%?mygX;?em@`~673_i-QWu!>)t1>vltfe zd{MB~j`+6CC5vy(lEG-=muZhZu$M-AOS@khB-pQ$uvc6ERNmi`d^w)P!5H^j7UJh>|yK zdvOOazx#B3^y$1@BtHP-B@i}rGM&w+%W&tTER~?rT{DYg3+R#s=g%w*uRR$2iYoVz z&$pn>E!(qi&-nFx?~{zD(lWldD>GtOaIB%iPlp?a36}^3ySwEhPXjDoQ#wZ4ukM%2 zc;zrM-1CV2>_e4wH9?_)S`DNka=OW|$96&=RIQJYECh71s&{=dck!El{9@UAg}X^f zac5{i&bhI~DA*>=m=cWnDWuw=ilhR`+;Oc`$R|^FeXY~C{Y2h+3wNP;IL9jbQGLeG zq}okVh?{{Y@VM2pp0yI~E4`PBb;+pglo(Iw_4%SqNFgmDcum!1RH zc`&r7T%Eqle<$uDEaowUmQ?O3kg8U@zR>VI1XasZxXt^x^C2E(rdKfE##MKTr%d3W z=P*V4<<#mRo@H+-lMSV6%Vo@*Bda6dD`JA0Fyhk!d<+~(S(?~pe1K!LFA<+-?BbTV4CySimU!R<$8%-RKfxB`!hIakfwS4%jK(d`p9+`{9G zil#4z{?gd^P#BfbWvwF2!qHM((Ni?_;gJHjk@kX-`Qk=!B8T}x_k(T-{ z_N!_osr#2c7^BCfBcFETwct1cebboHUQs?McJ?buW@}Z}+=#0S6Z%QW{MZmXWiqh3 z#rZT=DiW9AiO$4Xg);^lymOIzh6O%@&|_jTL$~K`8*dtMe2gqm;aPoa z&`IWHj@tCbMX%f*%%Ae%bgJiz!1v+-V<+Vtb%?nd+%VR?Ctna@_xLlgr;1}P7y~13 zk!`Ls4Kq&XY6oI6Dnqx`*Z9h6jR2J;mp@r3=`V_tAWO7kb=1H*Ats zHaqic&JD*@VlBG97uD!)b7|graeZs)KC)x|wDm9iRhuv~o4Y3A3G5BK`qIpJoSV5G z?GZG@G_>Cpcdq)`!-tGY;;L5|CSemT)$UYMLpbeM9WtC&h}W=OaBYv6Qk_evFmxa@ zwco@++NKU(P#jO$MchJ~@4VtL{cRpkv%Pz6*fMW01D|V-L%mpvgEdl!hHcpNBb%RZ zMLJ8#;}+a{#$V4U&;^k0Md@|ku#>yqX-#-|<@80?i4aRl#LQREGTrvW*}-Qf7l%?ghWr#seYu|~eBMg- z^N=+!Y+B*FjH=J6;&G4tG4BD=z}|fX?!JN3SF;QwmT1wR*|yp5m)?L6U=P_m=Sz5x zu9h%_Dd(`)6n-m9my*c7Z+G`--xC^=f}dJMu!XoYjcdY6|6GF5P5Z?a*m014R0#b@R)ucW!&pTRhi2@YoPGS%*F-+*j73BPn_?zbTT@`t%11g73tB+Ml zmOWc!R1iHnn}|Q(X(y~%K47A6*{xxtCEUXY+0zAKUNY}oum|D2^`4?HKu(w&AgLYE zW#hpA9x;Ylc2*w1K`6(?LXh71td}oMC%Z?5fay7I>t)kleLH_nA~i}bP`q+ZU5#``)4u9ATttbBL$eA19}N@qYQ{n ziFF6t6TgcTZU@OzX?nK>}Wh%ADG^{D^dP=>#Ps<>GEoh8SooZGNQu9OH79e*!yJ8e=piN<7 zgxZ(UTh_3a&K9jRa_{T!q50Jx%}d3vSH?Jd?OzPrHp#}LX#ZaI)^9h8RD~C}t^X~N z=hDsmps-PO^#D)DQJxrg7wxoAqsfESn+|b19QwYqx(NEKD41qI7q}0QtK%9K$5H4@ ze;SGQGxl|H#E7(n4=JH5bd{)%A0rkV<3z38*L=tteT&89uAeq)$AA`rY~;9pYC0q8 z`z&6jYCf~%c4-wTR_%`%v`)$=zqqi|(lvy^{LmQjd0C;!aJi@ylN`po4f)LMEj9b$ zaKUrUW+KD3i(AU8#2(#SGMbdSlR}Ip2W(864kf1`J%fc0HwdWQTg}jkEpzbl-?CJiu?^JS@Qlm^N zUSq~y{_ydcu#buVG#1n&rLUfm?^(OvxM_ExVOlw2#__%C>}cz64sL_H(}I;>ao_C* z&IN4fS{2>csmvzfvfmV{$(I_VnUp#?cmy|Y#*1Ra-S{ym4-9@fGR0!-K-*+C z!w9El9_aeLZ}w}_9h zI=EpSfiFXXpm_|BZ;w>5_oSK&rO1{H33$~FYczWl2qsl6b*^{B;~%T5+@x$$T_z|p zetceb45_`!*-*=^+wBHMfKM4JoF@ zPSXSZx4jc@8FNNR!x_GPeE*Y$u5i~M@(J62HjqB?OA^`-m#+j=ha?4$@m4lw z#mMS<#uyu~troBdhkye(5wnjhYB(($~8J9b`O%!Ug!G%Un|ndd*jJ;>|hI zPHNYd40fYo8sRA%h^uZ@7z)D^e^MwlyzMn3ga`y7BhMHnx+0jG$wUg=8po$=82gAM z=LvIt!3=aOd0@OPP`Il2_4V+>A%8Z?_r0O)eVQyAMzQs^FVTBpESf~cp~WuxgHG$m z`bo3Z`Zar@n}?LY8ox^YdT`G2ea{DF`&(dCBk~ME7btQf_kTsz#4~r6APDzRX{86y z3)(afZp4(Hgm6+9>~cJ|Nc^g~GM#BBze8f<_>F2Y$-IWLN;`*7D)_&X(Y>nc)A?!3 zdE}%01L<9M08!OiW%4D-Kj6)tDrDzc6<`zWjkb!-gY$%BrTT$FA{T4 zmA=Cx41sZ~dQTo5z;&d*B*87jljDLHWXBG)I_Ap3Tg_`Wb{~uW(kt9t_sN|IAe!a< zoyYL_$zI+CQVc8U*RG6mgcY0=#Y{Vz7?-CfBa}uw#KB38B0c?hiug>3B)+bdy@rlN z!&(JA?y%5KuBMjog-GHlUvnSHo5o48w$Pry1?vE2Zp1__ZAaZ-$(*%O;(>D0R6U{? znDIip>ks#qIWzKeQIS)$1=6S*DEf%o3knsI+q#;lp$-q(N{y|S&P7EjBoQiGG^Jdp z@HK`M!Hw(PTg?qkGI6R@HRpY-iqunk#!D2o7Ob2RAy@TT_hn~$LFY2+tIm;`)Uj>)#Nd6kmvFTWO*x=DCoCwb_pt|6-fPm0AfI$ zzx^;1n#i4qy+)8$*$xMvV^L0C`TdV|;x4{o4Mb|=uH3hSWSl-VAyj3`Ld^mgtP2QV z4?b3OHQDoto(e%)U@j6F1h=S+?)M^d^4e`M!-P$bmbA?&cxEC8raN{|vn>ot2`$?` zt3V8>q-q-HWzO2qlL#InyS{0l`@Xv4ih2DdQW_?I(?VUaKJO?Q>2B%Dsl4QNm&48A zj=OwA2NCU=-abh1tA>(oMP}5-RdsMEyPa#3Nsq6Qi?eYB50<#0qJ;$hEibB!7#kcuxbs)mMwFW0%!dR?VS#{HUZSpc>s7pAXZ&8!xQ^5Hjvtp#S(xB$ZBj}H^`Q+Em}EOVpNN2Nz+iJ&_#f~&Z9#luLx{sGm z#p=A4I$JoTajr;f!Mek@Mbt~t{2%r=mqSZ`Pm<+6BZ>-@}SOJO>q3Ni{1I*>JD;@Z4P^Fpycv{YvE55z*;tR9S3_UD(S|0;-s~l z2NgtKzRD?0&6CN1@bMaI_u|CKL;lCnD6~`G9E=$Ep5NT@msH#$3Tx*7{DZrH-1R>h z|7MH7va_AlH*<(~ZL0}iS1Y><@gSrSlQW5u{WAnU>|K8G{ipYJxFBd$OCEWQbLVBt zvYM`bauQ>-3s>6-lZV?+5e-^1^ib)Z?CBzmP19m<{WUJ4w*t z^0l{GTsd|tfAr02^hbytwt>@i%8NH4`3e69WL{5`L`;|*$A{oIhQeiTxP)QtT7qK} zN48u500RI6Hn*;d|35i8#dm)6d_45Gj3u-!rdNhG5$RtlER6)bqW)wf6!>L)Wn)nK z&4)L5N#w$`E}-cF-L&-=0QQN$+NX;S7KNFkG$iLC;fGB#+{)nGro3aF;o`yp;%Bq_-u?*JD<^`dP8&Lg@mA^!FDgtQ3_&q+F zzi4D6cKHu?tfcD3R^7aeMTI~9Z8=+3q>YFSh@CB|M>Rh}$<)=avY-}Uj7tqYj`tdl z#X2gUTBWJyt1#Wg1E-jl-YUGY?262C0O(CF!qrvQqxth@MAvpvX6m#Bw!^d}7XpoerwOp&wPA_rdrjrO!R*rYD&HZNzwNl0e1M9^+Cv#LVCIj-i( z_bhA>K4G8vGC?@cfCs@vP4LgttC)SN&r2+OIisp2z&tURTR|`!>?GP{DvXea+lse! zOQ^l!xmq`wY`1B}kWxI$%on4krA6W(IV-^acn}&~1!k?`ssSV74aOLiH?;5rB5drn zuw`MXQT1rPOaZ9XgMm6ClpDvTUAAaQf2?12s$u;EEnkfpX@-74s7^cvYz&a>cQ>PF z-F_$SXCywF0*8@Jk-PVi@{3x!O5|XpF!`&ckKf10@1xb3&w;KQMdfOk6VDGW$6P{6 zqOYFl!5aaxq*>xBpS`(Oyz~@g2LfeN3i-rrUbwgRgt*x12INhvd4a~#=o8s2k;noz zZs=g0NnUL%ko%GvcUv>e3t>;N1~tMi*wG2jmoSS8Zm&Pk6ow`GDbS<}CA6Iql-z<3 zceJRJlq}Ai#cN2Z?urOp)^&i7XV&=C6Y=l=Dy@(@bXy*MNK`YBOkp$$LfE)N zS_S%^1qP|c{$4Uvuc{uYtPlltpw>-@Yw?~vka~uMof>)M)!e0yBVn{ZzcwfwYtmQG zqV|NE(Iv#&U>YZZxqNSbxu6Ow4zHGuoqtfxQ`HFzVLi!PVy7n@-EqbI^g57EKdZQ7 zSWMm?$Q`yhZT}L+0=WH?TT0xeJQgIm1 zapoc1BzApJ>9odYx-o2t0r&fn(5Sexq@Q+c7pJtUa^SoM#G?!AZkM9IAZ!C=K6NEC z5LQrJ+!4Pr{=d0R<_XR z-Yfiu5X)|<0*{JHf+N*cPU8CPJyie!s&WR0zsm&oMGcY$si$Vqh;TACV&fIpwT5dQ zjyr)BTmAPMnP*CtkqO2BVmV{s(W?Y-z8cKn%5ol!t6Bs5PN04z6}s zTqi*^Vd~l{nvPn4S}8VWKyst=jzV`q>Y`!I9aE!aF0zO*c5Cd5ey<9#># z1_uY2u4l=8Mw9~Z{W{T8>i;9;8(TVHeDPw!o#N}l&kTFfb?evBIzn`ofzUfTej!?Q z$bR3dQ3HeW#p}Yys}Xon^~qyd@2f~D64MN&w*lNgXS4;=%znj{bbRF;_S9K$sS|iC3kSXY znFwg0{`9#GwVLbk+hVcSdb2F&^==axaF};(WWOlupp!vELu; zIEV!i4B*=1C)=KIa=hMy^*+tFv4rpLKcMLzdJmxVj^Ii3fPXo)Kt6Fob-Gkn$MQgd zL*#bEavXf;U`dgX2jue5W?raNZLnTzD(K(T`+Kq)BR2tiOfPKAu~9#~Z>J4m_QZHIxtoA^bqPC_Hg)Sb zI%XpWpU#M&@Bu8Ikcsr&(FWP;@>+x(N^Kj`Dq6apjdVKPnJo`>*8s>-`2%yCm?GGR z9R>V|`vz%;P{c8y)7;q6kGg3+2;!$iqTJ=cZnEWM#Vk#!mer)8l?yjRy5bc=en<%z zNSw&FEvU0rw6ImLP)~ji2Pu86)b{G6nn-CauDkMs3^KAHrz%HHeTW50m~)IRNKi0z zMmoHgmG`tp?E2zq(U-vU1;3NOzb_55U=TCU++IOi5joEZ6Q7etw$(WVw)j;$?v3+t zvpF9?-;$-=vjhMD0|9Heq+~{Wn)R2H=|JdI)U*!`S&N1lL2lEsb)z+fFO}ijxAxk; z!xLN|Mb^z`?e_@#K3*OMNIz(*_p}b}re$qiqIuf#k);FsgLGHsu41L=Wzwk#2N!jn zKC+IIWGx4MAyW^Xfqp#9{5$!eCCHP@s++)Y8BRq0EAY=y(zYsd%;fFS*E_QY=pBt^ z+*;y$$V41|9+{vw=NmbqUU0m%wF2ai{>KwOSSc9rY!?hS%)><%z{5tAHOlnd(OBRh zaprCH`(yUqrGnAAd&P{qYgwjdD_sU3e^`QPf@6a)_PivQEF&IQFgpA^m5+d4Y~L<@ z6CoCpR~R}0t}}v_#h(>|jq%f|vfq*S!G?@fg@_RC9bscfv}@qKHGV6cZy>&Z-Fpg3 zIri)Iud$*i!5IR6rgTO`(BfCfHE^D&6d?F(@i5-vMTva=YU7N1w2`|hxAd96^CQj} zDg2F33%%oDhvN^!JJ^30f6C-1g!4V*>7cZkh(exIXtk2xeO)5WM)w$x_NlJ^l}l=g z=vMBny~ko%>IMgpdJl^^eE|MW&`s@&9p(>xR7Qek#PNWp(;mxhK?-{GVpMf~-Rq-m zGoTliys5oS8l6=w-O^(m?^US^q7dIWKF%i-*ltz*R&cBoLfsxbMn(|dDMy%#@ zhxO?Z8svzZ*bIln7I2^n_m`=l)VU`K9mc?3OPw;-Im(|s+z2t2mgeeVq|}H`LHiL$ zw!+|VvP+Of7=l>^1^YOx$x|eH*s+yh6S)E$Y+BnqJzbFF6@Nj5YhF#D!Y@GY+cca1 zdhNcow6I&(*GGzrX2t@wRR^n_~1n&|0MB$87w_ z%qP*zgn)GNxH+ zNj=!MR?$T2ahr@DG`SYGl!|$tenzqke2v>FNKTE&fTsXlbbhy`Uu}u&asx<#CE5h= zuZ(xSXY)87ks6Im(N8qF$%Hh$npcgaoVREt(jh(Z#9Hy7$(MGY?^8Y24E^I56K2v} z3$E~+D=kQ-e9IC&nqG`z#Fsq>VB*7H148E2I8*x|t46w7QDvGoN58|`mHWiqpIXCz z3!?rfGm61GV%?(Uc){K`Qpd~dZmoa9cp=Ak2)eI{MA&svd=qMh>NKh%N+{0+*XB=V zoMEadAj=s){}iV|_=6aYxKb`hNmaG?h1^J1$oAA_Sl2e59##A{dt3}cGJ7yx`^UlA zQxq7LnhhPx=U48`VC(^!_+Yt`Ms|V0B!C4KyfRqfq~;yO8m!Kq%Y`dN2AcMr)Z1ZL zj~PfONhxhTF;g3pYEI*;QjgBYM9a}Dh_J&Bzd-IBoLceTFfGyJ5>9SYA_2ppV=;&k zamuiyCc)d)ZUL}BM>7KA!X7+eO*z_qm(!`VqyeB%1#1WZ00RIHgb#@fYV;Yf@OAyj zJ~(Y+fG6bZ`j7+Pd6WR6IDsdwVu(j(Qr_qYXWG@umK7CcX&WjtvwPM!^6daGn1ju# zUIoZ^SwhVjL$+gNfc=^lx`=B(iuIX!ADEK-FCe7S4K^`+9eOJQCXw- zkK_f2M|+U26y@@(gqtJeH3u&(>Hg$F^%A~mXL~f z=+*DB5T-hB-%2a){J3NTJd5jDr2(qbW&YBIVu6Y9wxE0^3$K3w`J6Z;%i)LPrId(Rreuga=eIl-#oEoMxg zp~5~t0Av4o(?Vn=q_&TkzVV(b><0lQ7_)^t%7;~1j=*2of`Mc&AnWQq4|gdPt%_J! z7w->a1Sl4vh;M@<1ty_hiFB`BeUy?k#`V7ARa%_C0%fdU_`k_q0aXF$QMlp^bZ)2Z z7+B^42y!@sk752x9PJ5X3`(0{yAtko(P3LnKePME-ji`7mhC5n+AHb9b-_}+1PRWV zwfy<10>Q;GL^`h66p{@~8v1>F;$Eh;coiP$Jf9TBMcQ5Nh`h+=&hwQC{>>I8j)x2}AWp4jR@TqfQQ*%U#9Wgyt}{QF%HBrUcdSMGLFt?d)@ zt)t`#wT#8OBAr^EP&Uk8(YutFqVBqr+bDu;iaa;>Lh0fkXvor#a#HHBgIyFnWp#M6 z=#r)`n)2_Bm9f-RB>w?l_+q8?m*@jvbWQXj|5^i}n)s-NVI7zai7mJO(kiYFtw59q zp?)di zizrcs5M$C6joVVKAjIhwU=@!0fXIaSSElsz@OiZRkTF7QD!;~2j)aq|D25ju-r70r{U2{UxhI5D$Q8=XJHw8eh() za4`&fXoh#fmw|vaf9ar^nploLO{vnUz+j1Xfd*Y_(K76P{%-Wpn($}deD-5z2Z9z>`~-CAPJ& zXa@7DKIWT;p^JrjAen}kVP@&z^LmtP_EFnW=RuK^Dgy6W{yWkmStd!z9{^Co|1(vO zzAe^ko#kzqtK9PHGQJPehs1uW)x-Iy-1Ys|l+ zZbfaeCyWil_Z%BO&|h~ryNcs5MFwxOR9t>d{>jUwUgS`5 z+E@P*>U1kp_p~@S7&ZMiP+nRJaSc|%4UvdNlJC8i+6)T>Bve7Rs+;>QZ}`OvI#=Fq zxPSsr+B&nhmmB$a{~n1VxSq6Ev`~rcMiZZkyFTlPOm?(50}CT^1auzU{5M!!defob zlo~pZW_oT)kkv}W822DHf{>B>Ar`n&or_7=+}qXArx@fD?23?y40}0y&4u$nRG=r`iXz=C2!;$_+FQk{e0S<3TDdo6hh0O zjB&N&vG?eT$Ik(|7f&O+K^R~F016B1(iT`F;Ku+3CVSud{w6ZT6$aLN-_un(>S~*? z2BJNB4=)4ILB~k22zK|<@M-F<_6N88t>LAgnWM?0F_Kz?y)_pn(~{P>lco4u(cHB- zs7@J4FYW2+4#3SHsU5q1K#5{T@8}_Lv@l)6XEP4yKp+$A2#p%^5X$HJr&)z$=?X0@ zOZw=6H*%JzTs79Yd-<>XV&dm%ic!PmGCo0K1Qo>zKoCXWa3+hI+)X7oU^ngux z4NR>A)+^^d1i$-^8jzi)S#|QrJ&3R+Y#X(oRq&{JMlJJ|K|E)bdb$5n&*X7Eft(C!mhs-(p zo>_J)K^#vg^c^sHt=Z>ScN~})HcP&O?n<~d`_X@PX}i$fwV28cLne?A00093111zK z^&>2*@*~0l2A}IxVFPiosdNch@+Dj3bm~<;6Jindn>Vet`miQml7wJ_JXYR#dRi zm&+J|+Fqn>n9!=sBeh^dHfV4ef6@RA1Ri9)?0mABZh0KN28U|{09!sY5Rq_x5{6cn zKsa8*g-8XEgMH%4R9^gB=y4X%6A@Q4VXL*OAMZV0*{crJTenm|`{{pF}V6g(mthF9RZqgmn0hK~{l;2RUPbyQpq~6w2A)aiG04I%b>u z%2%$D04iC#g@xdd9)Yd(WP)4>zoKA|Wf|pH&R&*xb$9 z(uUYV*b-HSa?i<|=Lj-+Se=rbk+$UjhPV?i?GJm#HrK-jt!KUR-0sRMUbT+e&3wDb zIBFE@{P^3Rpo>w8Qq+Z=tU~-+3DZ2`F=h9EoE#!1htO~xZsK&oJ^jV(v370VaVLqp ze6S~&ti@%ZD3Y(GmrPQa@lC6P;@NVj&Svsho8EE+4}9q|WHq}b5;`^SXJC(g2j@hz zpWlolMp9eo+6jN=0LYlopl~Et%cArDMCoOJ{A9ya(1LrpjXO809fH;W^B64(s60nV z#~#t(si$6!fK<7$5hI7wt5KjE8BOu$rS%PMQ9CZ3kv9Gxk&-BF9$8c6#%y2zQs3xP z)Zu*G&9yZ`I;I<=j5fxb&rf;a^C-@14?I>}HF4MyWqlu9T$D!4a zox%mTIwStRcR>VumS!0$TRAE5PST~L@`}Hi_g4DdiStkvpx3m`SoQ#cpTRGk*Njrg zDsO+7Py>WP48<5v&j8=iLqo}5`eBr?Au7TFb~02QHr%12Xmsk5hANXKr=iK4*jy*W zLW3LZSH}lfy_v7VtaZDD$au0El#dz0lHgaR5W<=m%b#pAYy)+Tw+Li-wEmqOPNN-q zN_EWi0^Hi&BcLnWz*?N&pJ|fl0^l%R8+He{ocxPoILOj`hpFu zcjs&k*T45#Qr`kVTCvhFJK>qsUhvPx4}||;pc;n-nUJLg7vgZX zrK;-(&3#_T$I+}dr{Kl5;iG{Tm^k`n-8q3F?eRx`Z6&UCibLQxkShdXY*dQ&R$OM5 zFgQ;lQ8UGZnsmqm3m6f}D=}t0V<(4@cqe&n2x)YF@rDtSMOkZA1B5ZjDkHA=`RmaF zKKnS#gKvj?CVLpN&HI;57oYOk!|nu2io>5^?|QXrtaH(eo?jH^52~+DF(22kL)5Mn zgri40>B=pMZR$kz^-VxK=lb_#$mls{;(R+pONnLiAedGoSoD>k$Ge||Sxx%vq=Ul3 z3eg5fzmn-ddJb`8EB#?=u>P;lgFcCXA&a8v1YigmC}!skq0M?Ij1G|)S^p4sg_P7EcKQ#?eYDIqR{oUI#D z!#rR?TlV+n!f;-+1*BFDo#taw!~F*X<|D?`VHwyS_sGv?DB{qLMA{~>Anh0yLJG94 z8t061_l5yL=J_biC{{D5Zakd6Jm@l7H3}Jwpw~+*8$$iAOOE6O*}qVj|9U57?qic8L-2ncH8uT+40d5xV8OD8nu-R$`LRUsc&w)8Gpw z=V!qehojnsA*L4G!1lvBI-ToxY>u^l=qWQ#Q(Qau)}A-EJzu>^@er$kcN4!3=7g+) zEgla#`v$5a*z(d^?-XXit*4-x`qH`pBkt)h?FI}Yf8x-c!ag9O9l^-da9}+2a;qKr zl44<7bl`~?wGj4turNI%ltkuFI)ltqABA)gaB&m%$*1j(u`Kpb*9o$jRq<|!LV6DT zEQ|!x3POaN5YxK|te24-z;YAYm#vN&=;8qms9fX^Ii^zan|dj3O0Fxa5RudbDw&VOtM-?SFt?p(yvuZ>ioqL! zzUAgquf((?kM%w(;CoN*9AN5*djP#FtOt^2v`%@(G_@7dl6vep!*1rSZjm@zxD)WW z6;fdpwoc{q?i%2P3E$gj5-Hr+CW#ovl6rrnSH7CzY5eByia8O;& z6kEc-aXo-A@8Ia_;W2NYXD3-DYPA$efHfa_dEkJfkV;WskAF$*aNBLvS*1m-u5J7Qg6I zv|WoD{E}n8Z_{W;tkubE_5@IxIzE-oJQTbgufFnF1J{@6YPeXt4o4K6Iib4Wge>s>ShIMShK@V@qDR&jFg8Gb2V#H+sLwWr3)gZ3LdFs#M({FDji^oA6_k#z_z@PXr_yQaHbex|g(JxM4P>SqL8w5633 zh`Pk_ZX;!jP;CfpV3qP>sQyLLiQR^%UB~p7RtL-u0p*`m@(4;?x{!z0^i=l#xa~;>mqK%skK&tIJZp5xkm~L58n(&Pl;_OY2 zO68cV&|vt%4F=#}%1F+y4hMQJ zhh9%1P;5ZHKAv-pow+oxFh2XaS;iX8d3nEfWD0&t^1eaI^+0ad9zEG4Lf?)vn4LtP zJem8Ezb}@VH0ZfY!)0K(?%p~9$OcvmCop1&6ffCe4od*I-$-E=m)BpUz8aNZ##3q%#@tG4il< zZ5E^DvS8O6C|?uu?(MHkJ988)1aUKFDo#MVffElFlkXDzHh`S1LubK ziI#&{Vdtj#!KQYCc+kDr!Zt6#Fp^4o#~Fw~eCmfA(ApRU%ro=ALbT)l;Kth193I`{ z6V?EqCovVT$*SD0hZA^mZvumjI5a9k;f;kk$29KqbEhVc{8T4c(qfa|L;GJ-1&sT{ zE6DrmxS&)Jz6Y561~yS(9c*j$_)dBR>}MAI5WO4;vLC6(Q4g2ZKX-@L%F=;WxRP!P zGpo4v3+|H&*CSlhr^sL+C5%$l`x#qA8_<5dC4sA4&3@;yg# z#EdPD>L(>hY2x#OFfrc23RNv4K+byQzymng>$0U+N(RHGqln%;0yFES<(ek)ma>WU z3xASvT-1$dL1X5@a7&+aZ6xek$(X&3Jvan?=U;n{w(!e28EduJ?e*(Wfb2C>x#S!^ zs;-~N6!uSRi`$!MVG1;ea6^!O@NWh)%N5GEB!coI68(!Lf;P$1Rk}8wOQzR-#yeXv z0k6zU0$oc6+n1_E;jkd*wD#7ipV8CCNyjQ)yC@!CvXVNU(;V-BGL}Frau3CB2A1;8 zxSZHB4ioTN@R0a}DH0w)&{^NK&G5ZfkIiaqE1h^dvb|uea%*igF-Em}4@z@2Be|v1 z>5Z8rG93W(0D|k8Dil`4l%V#sG?*l!Nf&JKy+o$ye`E>2GW&@{b zg9hUB4?t`3)9pXES^Sb0_5N|hkQZ@<$YGtA>!~dR)Y>T$o<0Bo0{{kv$%*P^`iYK< z+yG)o-jY=&{%9Nib11?en`MXPD7zq`XNp^IP zh}J=Xq9~q%38`52UHdoSE_lS9igr;dm zwpdSC(PSEhvny+ik)qE?Y61sJUou!wPRY<|2>h_;3G#m zlRy+Fr46R@T4*B)uxl*ZH`ks+T)urLNtcyF?%+3Zxs|AO1rVLA^W~ zp=PKJYNQXhOq2k@vnQsopy`VIjF{iFyPtNu_h*>tx~D)wEa&`&HK_+Trp8) zI{4DkIyGb)8_@Z706*$E9bO6bm}Sftv~$?!j!N^2>b%U@e+bSAT(zEFWd)KG1MpV2 z@wMl5)qq`h1uj>TrPkAuf=P*#eV4MKwp$CUC@W@f^u}utaR6k}o`Ow6x%Kz@T*D>; z1D*(DKy2#XvXbR)Xe$8=oDe@H@XG7EycnE{gmI$On8oQwE!130$c)3)b3$9h5dfV` z#Tw1Dq&6b&#g_QP(ZQ>-oE5ghc0izlh$5j>$L?o4Y1lD1q+M5b8Zz=>Om+t(pY=1p z$Lk8fIO$E4`E3(3X0?P#5M5_Q@^RNrc9`Xu4(GzS7J%PL; zi(EFF71d1x=gc(P3EqD1Eo%G~A;b^Vj33=cwsM;Q+37=)Azl`Nt^Ly)lVaWMn~m#> za9+LIo)p;{CEYaW2)T9X*+)==nk_J&xC(;nrHREKjuO`w)Yv^szJqDwin@d{yHoUsf$lSK|YCmyij|1ThKCIhh% z69B%80)?(f`&cL-G+!Fl(sp|WB4iHKe0b&G(Ya_4&U$kI00RI3bv8E~2!S&5rZ!AF zg74)w$q!B{DzB@r?v@n4e31KcH?U3}N{4>H(nN6|bm6j%9MRQr=XiU7kba~IHutvO zEYtn@EY#=YYH0Lp0(#oaJ!PXkGjpLe9OAJebF+N2*^B$HX^2b?U!}^o8j<`+cEc_R z9CFCdQX7*R8<;Kk7awn)^p_s|)vj`Jd(hceN|9NivyUR3n*byo=3!Psxf_^K-OjQw zAQ)WuYjS4m;v7ym##XzwriuoMjpRs`aaX@k4!5w{Y z%&OX4_~N2x$N;f(y9PX}Q<`EoKU2S$^1pLI=8h9elH-QuS|t@{fP#W)_s7qlNJ!xR zwh$5Nl)xX@t*D|n0J*4wq^;Kg=*CrTsX9xRZkRXr(z=tI<#X!|HoQa7l5)Gng%Wf3Ri?tU8`bFE)7Ej4)I2@c#;A=tT>!H9nr%D( z&4*BbW)~LNXkFft9$L?98tz74@?gk-$$IA+B`|nE(9m?dB)TQVS(NZ-A zOfh5cR7STwxWEtil5B7s<50hithku7i)3bCutu`(4}M_CKBX#FgQ4`9YYmH%ttt{8 zzoSQV&22Scbb3$nnb(7YK3~BC)zL6Qx9kQnDSO1N7PaCle3)QRBEhmD+n^qA~6;dnh8|Z@Q!tJ$cU} zWKUQ%Wu_bMC&q9LU#F=P_0C+%M2utocYlN6;fkdT*=kmNBf$7I2C#Cwh-dmN1r)dF z_E$x4IOcL=605;g8u;OFCK&3P8dUlQY@1Abf~2DEs~?K;TO|-qXHc;IX9E*eiXj-5 zYVPel_M1=zBGSht80vKC{;6bml5~ZtTcpLvTYnsU@G?}M~K71$kF}0*s-LHV39bWqV^FUTu6`gZ;gquh1;4-Y1;IY42t#u zcGB1XqLMa7Yn2KYbfZ%>1Cb7H*s@o~! z-|X8De&f{sJlt+UH0&NQ>4P`;KD~L@f?7qBcRAXG1a#@j4InEqR0fUQZ^$&F+>o!*#ob6MA%ud$iJT3Snr- zEv2p;-pb7_-n_qOWk4*ky__y7?P6*!lVr@D%`mNn*sEJhS`C8=p1&6h3#K=%yPp7h zTKUR$nqr6o?_DT;ON2qNeGN0ZDpc=pd{M|s{OTAskDqo@Qx^oIwU@wch5)6E^J2ag zATsQL!0;K98^#m&aCTx0!xtW}1Bgq*$w$xI0e_ipLullMqqYj*o&B5UfOQQ}UZLXy z?s^%d+c&%bIo5$#Dn5$2#o57^H$w&E3v;%7&xUL6qVU%;c@7uL2wcD??aK7yIfkF#$%gr#d=b}qZm!RD zs&BeYVvi!SYfo2s(W+zFTCD@8evC;?>w?I36)%kqa=hX)hG;J@#ko&q-WN}^oxM22 z9mXz>a{emcxS5_%Z=f7o4kGYCyO7Wc86KzDKjl&n&3)*DSzD08={OOY9OMVDxijCB z`JOd}$Bzf5c5bSkj&!#y)<&9VZ2}9eCRom7 z$;GvdNZB;aRS?A(5OWovWWgL9j4BkxTobg*r&i|oX^a=Wp(=5f1`t9`rW!%?VgEF~M+T~why=cjJlw=-wfKU)*;e^RvGh|2|FJf+ zr&Ygx<6e8g(y>I%TZ7B_sZB|D+D{^ng%iz%<{IRt4>v$6?AsO%;WkqMkCBoWRXo1c znw&R&vLI^ylug&e(I%wIF21C)tI_gBh~2@NVbYrs;*eculpFjqDafIq!jP&sn8mWO z?B*^`>}~e~c>KoqP42kJJ#nIW^ z6l1v}Iluc$e`fl+b3*I=H|PCaI>d%bud#F|2)>Zp7VVLIZ`}m+uSt`pyg+qn@*^tg ziUgn%(<&EPoqh^lX~_hw{8$EC=Fu2nmMRsTeEIL{xU#(eRcb1n_jGTuAAAr100RI3 z0|Do$s#42y_JZk21f{qo@wBUx?ToVz$%i^&F^Hm{ZrzR)Wiphu+^F>E91tz3+m4)6 z?K}`7sQ*7altddkD%pRkv;`j!&Otf@{HJ=2o|-S}cbTa+U56nVzffQF8d;K&a(c1& z8_T6@zrJf}QyxNaFXyf=!LpkpA0hSiX@&m4@Pm_<3?qM8%XRJjk2M}4PU^CU?X$wnV5{K)s zfAj3CCaGhfBa$4#On4~UaF-nCzPst{(%ZxCk$KusSJQ+z6NBpvx9$e0>E{1DHgVQL zETJ6cjvD6o9b7p48gggFxOl$=FbU6{TrorjRT4uto|5Q#Uu7igpl_2b;fWU4;TU&% ze2^qH?`EPq{)6>5o)sF_oE`T_MGKwEMm6S2Mn&PqM*< zu5htGgVyAbD6f%Qnz>rz{MfGOuHvb3LrQ#0aTTE!%B3LV*-YC=h>L?7q3e@O{asQR zowCB^gp60p$s3TxCd(p?oRiatanRYXQX7h6dH(Eh0o2QNBQ^@sh9QX~7<2C$X)>u2 zAG4vk|0$HtDg63;u$f!@9c=8uK@r%$$0R72h%A96F7$XaS7ef!X^`%bK8nW#6m=ak z%C2F{Hd)P()6Y^cu0KmF&#iz%U*%w24}eY2p|?6;OqBGTJEq4#stQN4iOj|Wh1DX; zi%Uhd@EOWehIE*##1Q_A`+OPQk>t5R^<2O{A+JLe62Ln*_IK^OFi&QklPqeCHN1U= zs452VsiA40SxUD1XWmGPuF+E{F7R+8DWXyhvZiB^N#xTO2!&RP>8WlzwhH@liUk#; zc}q1nJ^UMI@s{|ipCZ=Z57cjKXn$-(;eeSoHH~FiBp7m1^t;D+f!Uh%`)2Ml{f9JB8zA@Sk$rJOhJxFVm0-%F_m^z&EkAc|_8Bvca*fh4 z2A?MIzUi4QhQ?97dr#vK!%QhGXWAi0DkY6OAWqLPB|OfxgiEaO-jGJblD9m%Aw} zaNd|@<{8vLWm~kw@+Pc{MD6hx;5e^T^ikwj%VB#$yX}x94QZh$H^TQ@Dl(au2hqOi zR?VNHP&^jd^Pb%&8$nW=n_|NZr10tf(tCD5_(-nT&Lf-W8(>zC5!s@v{o>p&wZV_G zYlV((1Uw|Z>rkj%)C1dc+w5FjcA`p&9c@99O^h=UwuqQxFJZUy_!X35&pE-VOq`(! zD@>7h->d2eaB{io`hO&N4~E_g$7J0f%b(a;2loC}4eU79FHJyHI*YNeAPrA9#Oqc7 zU>3pVR&A5!v!4w9-a;=NAOnw)Ebj;a>bl$7Rh%6}a*C0$u=@&ae}+h30(F3e*8QZ}?fk-u*zOzQ?_Y6g?W3-{mo^^JY(Qck6n`Kcy zFsA6P4#MA+a$iu{cSp5ZkIOMt|4a+M@K$1`(Fmsl1fV!Y-ebrG%@jo9)+;PQHHV=H zNH>MpJN)B|jMqxg6*LPe6fMXfc2xbtiwHpmQ-yTE^!B__^)S|PA|LnC3wKq#D%-3x zeY-eXUhwLsx8TLyqhbHi0#yBNxW$+7%1D(vdiU^SRgam!uzx57GPVg%!VYdx#L75J z?~d*8;Va{#n^A}?&F6miTO7|$HSqzV$Qj=yb)Kxp2F(A+6tx^VKatUU{S*Rs*TnP3woyYXx!Etx_ssO_3=8&W`^9B*yrxYy5#ws^S`xifz z%|Y%@)NfOLJjzp~B7sQ)S|9)c{zB+X(3o4;P3{xP1 zYuq+A#3tK&7l}~VU#%2WrUEgis?b%8Ig~=5BCevS&lVuzXN^5XV90(J$zbu$#fDa~TKf7lQAr39F7x2XMtP}H%GJiq#)MX3TvEU4pHDxTr!c-N@=zlb`@>k#eo&Yh0Llh(>;XMJv=t38m7EN z72-UHgTY*K)tiV3;-xS7QuAH+CswCC` zSU{)0LNyFlbt@XS4KNwaneua}l37nwhU6}#x3VRGA#zu~p-|268)i(->68jjZ?YL? zU9dbhjEl!xpUisebbV)TMfR7_)C-Bh+wmun zxu!lA!TPZE$;26EZS1WRZ|5cDZ6(Lh&Z3}OviQ#9;fQ+4Q~H6&%@2>ck@?-kmck<4 zAX52Rxi=~~SfHl-sNMKO5R-PT8Ug?ue?Z6a~}{m!tuC>!rzyzBhqi8-%i~jV=;I8 zaiq@FlnI4Fq;#Ch#lJ02LhPfeEOa7Y$eP}*qQmNhKb=kIX^RK5l6oof#I%16iX)_b z$VNxcC<>Dhm_Ek}%>7IY7zwE$FgUl9=r_vsCGk8RZQV}K73doX@yPJ1*Ha~KkcA~c zNVsKy>&Zx;&5u6dQ~WD@K_C78E99!ATg;_?gb-KRdB=N1mP&;NKmhKlNEy_pt4XMl+yTm0I-F557m6aMk?JTZ+Obh?I!ZzP`U~pl^Gb?0oDz zCLg%Shh#bxcE{y9^mL@-8|)h6bQ^y*%>^1r%MQcp9=wz16j_=r68NNufZeg2D9DC5 zi0uzyB<(2_svPfCc-W36jXZ^8x|;&(&D(_OWAjcAk4<4TEN4f0u51MCyl~7TqSWNO zWq8D{5OT`N}0T^F8rlO>%0QOr!qtQr4Ve z{;S{PEQvY8$OIeBFcQ#_u^)>!Q~=2nIQA5~wz2q;Kl0^L3ArR6^0YW&P2tq&XcpJs zu?LVN18)Rf33!G#*=#r10xC^L7>6<{+^2uW+(XgU&+j`mNz(u{XxAg|2AQH z=;#sNOZC+Y7$2rIcdyv@(D_%1WG0LKCm_$tCB39(fb%46>HgvsqTv!1I4$xWE>QCrx&UfJF=mmn(=JU;++As&9*#e77lrvRa{x-7zOg0 zBn&Y9x6gl%N|UvlA%4O|esr0*K{+ySma?L|;@qXE3SW4+1H_Amm3Tz6_!(rsxH|I5 zX{9NDzg_}%QM>kfhb?JO^t5`3*yvrDfrf+vuQVkUu**a|y5AK2Ed+(Z2@; zR8u&W24lg^sCa$(%xBy&=oVO0ZYjNZu|LhFYnt*BQ z5Ka%#gfDhK@VGa)CdtDf?j4#}H&n@P9R)`WZ8$S0i^)_1=`8zs<2KMWc_EzUl1yS) z_`~zP`8=8=V~}wFs-|H5-!uXZIzS^QR*;$Qw<^Kwo$|1OxHH-j&`Ka6r^RuiHmN4l zgbAQ2{B7v%{^It5Sn;6k6*3`Z)kLE9aN& zN*2FAxVsc3{eX)Gkv8Q~Q~k>(Ln5IO$YT_eIkX;86=@u!8KGl_ciaQlc8n?C?m3*1 z^(Xr#nPNxqTX7^I!tx^#k1hwaBLXV33&I>sBAV=AWU?F!beaEYqCRXWjv>FMqlVFS zZKr?$00RIfAURXrlL5)sw@`KdZJpfzo2E^35GD>iM2%Z_Tu$o!7c#QYqO*XPtw$pK z^x4-vCUBx7yp=(AxX!|H&k+F$BR{pWe5HFW$~&;EOB>vmZ#dHv2pmDbRD2KHhPsri z6<>#ZlV?ZGWv|RJmNuQawU4Mg@WG{zrrm$ry+(W|=P!V@chOb`ZlgXI*s+Iu0J$5rd3P%x`HwzaLK zDVtWWG@+S_U23AN8^<3$qZdvWIXa{fWpb340w6ZYg?zD*FVG);o2bQ&jfQ&*YvOg) zQEF))dbp3ta{bQ%sAvtU_9JaLgb3_{Cu%n!O;o%b?tS+a)$lstH9>|eVP9GRtivyf=qbY z*ST1tDdsPeFE$K6ew8Ov7P67b+(M1>P-H1N5()(9r9v(9W{70X~-9)$esS(Y$X;l?bCs ze)wcFWj{`JWUVI;N8=S>T9eXJO8wkU^KTa5mb?U-4p2*}$qEd;8bH{NA4;otzP8r(oJ|bdhGAph z8XJwChCF^mCJ?$IcS4IMxk0r#<$biLSY zR-lw@1xj8H%|Zrid0UQ?k}|!5p^k^`Y+t6}as;PFsF2w-i{i`{s=@?Pmr?Uv-^bRkAIKd5*zY{HUgGnFZ1q;oIh zxsA)UWOMe1Kri{8bMjCGz3Q&mBGt&}4`WDAx8U-UUX8Nz6{$F#shT4lmkKN`BaL+Y z`++k5Tcv(^@YQK_#zFx|)OPV9)PH%7+L^0#usUdGl!#c1MrtsKD!wi2| zp-Q+Eh5IS z@d4K$Ry#k6-pT2*fwc?RFH6YS0h)hWFDaCpBqvMx+xhiTDL($N{p5#Qv&-dX z5!uYBNW5-zv$f}lNZvRMVeI!(`U9$1fxTo;Re8GW7*Kc~JiGH;HHjdi+>kUlpadLG z@se6YG^*TnR47RvH^JiCQ!c6GBEfo`OM7kk_GjLSKZCK$g3M}ZmChm5 zDtZ|R_$}m43Y4{JH^$wUtNS@vYtb*GdFD2@-(hsV|slKO|Nh5aRM!JxMyS~rM4P2V#0}hbPB29gZPW}>bt0Ts5KxGksP!f!~%)S8MOkD0> zi&%zTexQx0K=58`m3j^oWww~B3p0?fg*yF%wJq}q#I45O(c`8-SlZr ziR9{gD}(+U3i&3n)4rjfIU_!UluN4}1K)nWa6a_Dvar?)-N;(R$$y{JXQYO0)C+sX z2b9Chk|QU0yywTDm<%KgoXTPbvDP|ed_~G+C7PsV%$qTr+VZdpdSj>2xVRrlqk-4e zC3rq%Ey?A8pTJkr8^=9ht#{^YRMn^~b6)&FP)QMT#a7`o-$|`5`4H|^Ng7~mrX{5IiL;o?5c^Uca<6H?>e^@qR7~vxr zLJ0UBXvE0hbGeyXi^Pu*2GO~#N1RCTM9q z0%CrQ)wQrbtSk{I68>^w@?Zb}0{}K3gJ*--r0LXz=;MQEiS(77Oa}UUhhulE(NHFbc=MvFmX z8;U)QIFF5CkLf}b8U!*%45PQ%7GfPOk+lYM=$=S-i3En$mX^oj{YAxl+4K~DFStOR zff^f*7eKsD3l;h1Yqh69je^h}SgD*dN zDr0m06PP@uNk4#aUg;fnK4*^byPc6Mr6t%GIE~1NG-XnGYtN|a%WZvwGvQBNSS-<% z|GfxLO`cLlW?~@&-9X=0f7Mm6n1YSM5W}ri=hDP;N}|&D@K0S0VW3n*kY<*vm(rWsS0CtGyVqXP-n4wivXAS?vx zk4&%b<;ksm*O+0@7aBl#F@=r)xssBuDx22^*`f3!XlNN6z@ogK--26$w5+8?;21!0y!8k1yi|Bv2uBfo{ zs(XdnRT$}xh47YSpT&aJj*1CkB9t-4MZ8q!Kos9m!FE~_{gx-FlPx53`<-7JrvPNU zkeAhkIgrCR>NR0^*(RsycZFMN{Be_Qt6EG=TGxUyS&>CKhb*-0lb-*Yp_%0=PV}qw z7dd-h68Urii5$(svY0~9dK9xjJS*@pnQ2YSpS7JDqP3y9!+8A=mMtu^*j?t^Y}9Sy zsBg;MmlkbMf<}_+u{s(t3oF_RPEW@<#o-hf8p^NOOS4H|;jZ?zt<~=NsM`^734-LF zF&;vXj^($r9Pq_N=Qt_VaBQ&e@kX!wtT*V6~!_2!#z?O?c#A$ z@FE6z04Obd2CvJLoutv-P>22sJi7U@ zE~zrDk(76|Siu~DZGI5-(xPeW{=}$Sfnc_r$HOu4RDWv|5(qy#lJB&kuKVOg*hvau zB=0De(;dhKE;0%T0quTP4ZYDC-A7)^R=;8WI8f)ouVcam2B|1kWaxP z@L622iX8_UBs3S;{LMY;UE?qGqz9?Bl4MdDEB@Q4LLLl^% zGdbDf$VE_FXN0JoBs>g@p-ECbXR!j^R10$j{HS`5%ES2R#$|H2r0yvE%>LW@Q^bws zv0=jG7hIz8hgT=fNAXiR$g<2Q{HmjaKHvWq1M=PKRcsE7@sC$>JBTLPs0e3I6!Chc zg&WMqdVP~ypJ5*<*!@09IHs5Cof8{SOB?!6Rvae8gSEt$yPz+x(;DKubAy3H{Qehq zFKRk52&rI1$!$KTb1!!b>;Df77(P>5Uf*xuCZ73iN1E_}9i|2(Acl9gF<1 z(paxS!#j|yWDC+e_g2FRyI<-@z`8R+HcA_~{P2@>j-0mmM8?8I75R<}j-w&ezI-WE zC}v8uNeyPW@RUwp=gW9yVuK*NzAq=<* zKY~A`2F5Vc+1i1PLzRSEssB*rGh<;QAr%G=C}*PfxL{OPoHqgtZh?;*jF20(FG1hc z5a$|{YJtQ9$K#_z zoien4=GRY|3)C1dHD8cJ+{4`BhnLmxDwuARL){JYCLxHevix5SnT{`d=W7uVdiibB zPflk2-23=h@yf?*92lRBp}?<$ED2UopW(f!NPxGVa5oQYQl=%FZfHtI=${Dc$z-$> z;{FF@io#B&qSbPm=l#+!xZNnk?@*cW$>$zoBJRLibG>6l9XzsLUek84ds@?`niBUPUB zPXC)sI5IfyGyPNxl0QjEFl}?=#KENuoS?(SK#1HD>;0I&4<)1tnaIY^hPDqlz_b5f zbn_L78cvk7@L|jir%UBhwmJO+NrIeF`jY;fFBn*-r>@Jnnw!9?LE3LkCEBIGhwz4q zYY=8@V>t6^zDm7wl??F2^&CWqw(JPX`q;5PbJmI7l*&7k?2`GsQA>>VU(7pp9Hz#c z#bPYj++24gaY!FU$IVqy=qgr^WSE!5pqZauH!^9Y|FxA^tNbR=uyG~`b!iljI*u}< zm&+XCiC>epvJO4FzrniJJgyRxT(*=o*E^r(mISY7s}(js9se!2(tVbsnQB^cc7ODqdDVm)7JON*jYmI2MXK+9~)5=`X^I?g?igFbn-7m#*uz#yx2;#m^l$n_3s+8 zn(Yr&SymyQP0u8r#sSLCy|Y(eyHKH)v&Z>roxYSNP*AJ!I^9%E-%diATKl|*T~&7a zVZ!x)H`R9g^X_*FLrEk8rSiL=+$qYngGNdu6@l*>{zi8^4qqB`+S z9z+fjUL7`<3EkkMf{m`e?m=aq&zX-Yxap7qdF6c~l+5>*YgkYi!!^!SI`Kj%gcFLM zjGM*c%l--j6AiBV+z!}6%6?t_p%K*-M%&TqW|zqY=_VD-iJxlIpW%x2OG27xR zpE_~8=BHdM{6v>A)CI_CMx0jwQq=|ZOy_C5St6BIqE48=m5>ps*@$-J?YGlT1`i0l znZ})vm~T`+p(fBv{IB2k`Widq7R-Kc^_h)v$5?o;Ma;QfS6)$XA^XZv8~|B(x7%vD zM+RIpja=Ir@{y;zvpcG=T(%iWTK)dSyD&Z;zjNb;Ogc*sA`WnnMy-H4W}o38!v7Me zc8Szm@RO;cc>g~$M`7zq?^0igqWzEm`5mcz{!#g%$G|1iTe-|RO!H!d#D5r7;IPoQ z0ItTx<_pgJ*Ot~R?V&1c7p!B}%nzAB000N|EIhznGXK}Ml=LnzSeBnj6+Pyis$_zs z+4R6?F0OEukwRv1aDTB7n^<7Np#yysiFrlY?L*gXYQDo;-&<6pKdemACa6d>ou#?J~Ag)W>u zbjB_sO@=``B^ zgZ6y_)f!c$Ub4U0$U?K*S>~eF08aOX3jgQ;04(01-vXaoysE^2000EO#3Esx(JE#x z_fklQxVVLr5I~C9Zz+?QWz~2@je;q?Y9Ekf3gDQzJhZL+0lb7d7G^Z$9c;SNfF-P5 zwq4(7vA%Z8r|>L5q6p$l)Zr0lE_ICZ)RB?`AFv2`R?p?O)F|9w^ ze67+X7mjoeM;~&#H+b%aNPu5-1rAd8SqLgLk1jhrv|S-<(2h+_3pkza)q2Xbzf#jAaPlF0GRYessEa#nPR_NpEeo zfYj^6*_M2J&6f9qkb5s;IH~uBa)0Q>Id`o6=5Y-PhZZr!1aFO=!zDyEfVj$)VgRen z@5CGvBJfl*2tyXya=ZHv@x8aKIdBnDTCQkv6@IhBKrA1o0JY?qWp{Of^<(i&0vEhu zMo>757I&MKyL8g@5dqd1YxSVtEBM>T24hqaDB(D)=x*n0I3WCjaxF_ZF4IZl^`N>z zuvj<*2Fp@cq>8jgiP^(@z=nt1#J|R-u0Pq|L`v-=8obhUDAm7J;`rtmq7>J5fS}Ni zj*7x>REv!pjt3aq z-U&f!RKM->wRS#-IOqBWHotg1C7O01tcM!vByCkXHfF=bqYC|h^*Fr;of;M5ozfpe6q;wTId?he6j#H%y4b31 z!{PIrkV=~&fFFHnB-{9&cRcS2a76V&%0ME7bc zwej(+tje-HklA^R;VDxO;8-Jh-+(&!zM^fYY;n!Bn_P#`48H0~e>7g5`W}mIN~B6b zzs^gomD^U7B}Ui?s_rgT%0CjRDwU6PT>uetq)qU&mC~(*1Vg8V44(j3#?lueaDrdH}TIdj!4u= zC<=!b#2_>n3c+Y5b_aZJt}vIP0`{VC?CDX8=4qP`)-HTkU8LVj0^ctrH!g2MS1Jk7 zr*$?DVu=mi6iz_Y3&FzZaFg%R zxzY>pP}>j+2EMSXt_Btr>v{k{KrpH>L=xY+qoCpz&15X`H|r&`xLlY~F@P>Xo#?!9 z(5%)~DMSM5RJ;rjO9f1h)P0ez^zzk2KQDsc$pE*l{nY($0 zKhX9A=OOpzwtcXk*pp?W_{RFm>@eMBp=gE2Vkb;&;n0Upv%yEqY6;gH_-_d_sNM5?qlOSM&LKmJ2y*}P3^>9c zy}#D_{WgZOK5+!$WG&sHfM44%O+WjoLMcwRtEmnonZ_}_5tFq84|?$VKfSqudBMdm zizdf6uZA6BWlP{X-I>5En{u}Egf0R<`8cyEs_{1yd+@HSr^ za&rBCIKTdGn1a*#IJ6PRMo}v05Xn&NxHGv-W#f}M+yQV*gbsEPPYdd6&ikd&C17WT z-2$lwYtyPJc1gz4`tEM+|8ZHbD=*nN_7W?!MIu8Ux;{?&EpL(fyvjw2=+lu`6v~~Y z%)ev;Oaoa1w0Hah6^3;=u4~CYUVebzOdKFm%B`m0{80gV>a0EDkpaBHg^QmTi}MGi5Av&URA&RXq~fcdd96edhS9Vf^odYF93D4<6~t zasfvD%2gW6{D)f_;HOXVH)=l^E~JUHeS(c8z;tkiM+&7yWpo+uZ4EJ}RM&bli@)?J zo-n~rF@&b6?r|4{)AEHM*>07Td_dWM+c1F4R*yzSX}{EwnUV8(-HpAtFcIS;qj+tj z6E_l@Ub`apaqx_$v3G}SnNsuqGgSUSiH9#jf4ZDSbPl;mZj#e%bZqtN>{Aske?7;%1Q8Z^-^=b)%H z??_hEAt_suOQGGUto>=m07_*MxIamNSdf-y?2uw>7dw!$3VF^upe$>Ct zm7{|(tGF*xmfrB0qqDqZRyqTH*0??&)fLe{?QvL*5?y!pXhqJ5z%qF?*hL^PA+`etlitFL$2)#BbL zz^=?9|Hjp(jUfrG8&J3yg@44?+WVgrgyF8BbBNkz32b_1j~c>`p!{JMWjlFacBf+0 zE415{xiSLt)LC)rChS`6EXPWjuC!Vk0I_lgW-=*J@8-R~A{!3m-7w(~0`Z0rf^ISQ9JlTfZ0)m=StaXdQJm=1(v=nbB(V zIm`&l+m~qT4~&Vht$ZaV;q7*>SH}8hQss<}Vq3)p-kw&rYak&MX%-Q2on8XW;?S!6 zTT6`LwQCHiQiWtkqC+-5c)BTs0-9wV_bS@0YhDrZ5 z#|S0&Ay%!1IWg8tqHOxG$n#R-CasTiznPC+C#=jiMK&&?%UE769Wg`r!WXO9Es?9Z zuH^IkgLi91W%_Dz`%BN>B71N<;gcsE)}#0M7J3Dhcn>M^w=253F@k*BjcI#>Fas_K ze%#dZH>&X)nzG;r^RVF)w$_^GHpS#Th(te!uPAt8u`B=#>LS`FJ5?v>g0n|=WpUkNd*rJaR zsg`TZ49XuvPa`q&c=)eNAtO8D+EC&h%q6uBM;+tmtwj*&@2^@Xo}=T%_HM9Y!rh7-`|ZN%}2|{G+kKzQF8M5IVnp=UF4w+gO2fg8D|Qe$ z#Oj0nVvvq<9~Ybx6y^^Q_#k*Up+1Na@mh`2nm%U51>&_pan{a{>Rt@VAz{7TWccC* zTer2x&F-Z>`t}*u;b~^QO(XtJhpEznNpwuc|N)@x1KHByegtFnA}v zyUuh54kzDyh72LQorhp2-#JZSXM#B^9mgC;yPU_N8XS{U> ztz^+4eK(wMx@$Y2f3ibk-nN9prnwxJxhz_U&BaFXb5@gD?KIbH%@AoPNqCJuwN)`# z5^fkzn^ZWrm!cCQ3Lc;uMJJk|?)^W-6&T#a^kQ;(S*2dlro_i5jX>X?r zkWw_POKFnl2%Pq&ol0pzYN&HMV3crY6WeFM!C|W}pxW!;hE$l_kpL5W(I5@=I}>_< zv_f&SThXFOyAXa3P|Eou+fC2a*R6L z^Fms*v-+=sLS2=53W{8gzf$StFP>73o$3sJ&Wn-;D||&!m_{}q4_)1!r1w~hv=z+L zbYJS>k6ACCP?%!Npn@}5N8aVv9z@Nh=AkYx(lUDKoV6EF2_+&7(afDlxK-sN1iamU zeEwc;BvO|@tXOJ(4bP`ZP_iLZav9kbyPFUMF+A=b$ z2~G(yD}w}%P#racdK={MR?S&%s?JaqQi~n|lRi>!y;)+xiQwTK%K7&#Z0+H%*q_Au zWVWx~6C-#dRf^uISk?dAIMX4ShGk_g0|FR{=B{4Zn!#pXBDh$Wbf77ZMc6sQ+G*f? zcz#qU=hgA%f+3>RPnFUE56N5(2jA%^}xyM$mCev`m7Lz za&@|1&^?&^6zoM#oNDK}6C63;5lXtRRSz*M@RXnQCIVx=yof)uS~ew@1!fZpVzEB# zqWI15GSR4Sf#vckChe&0c^c^^q=bjJY6nb_a<|`fJpR;rWaOpu3mKxD4Www&6ZzNAOpy}lDQskrnr-EK=RF4Tin5O)Lv_LIrx0{hyp)4a*dQkT2X+5 zQP5Uj@kS%K+m)%mQx>OAI;bxLBJKTd&J9e|efAv&@h{8a`X%gVGff2R-{Y`obIH~W z&z*E!h@q(qIRcEoQYT~Y-7VzmOXQFgYGA2*Iv2-GDMTYdsJ%Qxx@zJU9U%mWw4r6< z>uGhyX0hJ>1_@RE%Qe!Zk|i*voP1KKsjc+tUp#Ltd%syp!u7`-%yW-M-IE2PA-O>QK(~F@U z2e)Em8_1H5WA+Ng6LItD9oWE~&O>MbsiAn!k8Sgih*@q3;HyJu84E3fM6EO34w>>2 zXt>tf^un*&dTbT_vqh`)vs4qWR{~!6#uDmd4fP|gTeG>p)BAt|2tyX($q17DcuJNs z+{k*eYVQK^w2+N^Ho~@TzUO)~RuHD#=r85VNE*ky4}(9`jH`NfJi~`kEMhfm>jc42 z>7{=SaGfhJ=+>LCmeMn*sYOBisrzgLM{wKxSlNZ=!d=4eq-u(3*8I~5)>gNd9X7cX zdlirbWZdjO<|rfIwZH%X0{}CuVT6HnpSKLT3y#=Sv1UInvo+K^YiFiY2rbW?iw~3w z7Iwtbx?n+Qj?D$Kk~Pgmczu12cl4Rjsfh#4&NtqE{IKQ1RNx1wyPxnijr4nGUSsgI zLIQ0`EuYW~H~!|#-lhl-sv%Zkkz_^@my8L-dLRihN&l z?^rd@Vs8uAukz9yPf+kb3iwBnYB{|n&yY5ObT@ihIZ*sCAEEB{b5MdS;0O*o?WYSpRn31K6R5k83$PRPkgj^1CL_rt zwjLaq0Si&w?GMFOr%oMkdGGmCaJme}E7zeEcIOw-W1c@H)N|hGdAwFmkVZ3EHNAh7 z4K7Vh^T${SQ!C@AjKVgAV<{J8%-Ol#CW3~fBQz~SL9B`o zc*16pMaBXFPq#0c1ETKI$*Sl?gXbj z0STf2pNBQ4@koHLC?Ug1cTc06NFwxWTW!$vx>FPSLmm8VBHXdD^MWI z?1C9iYRHRv-(V;qj7uSb;^^o5@}cPyAkFB${X3S2@nT1{H)K2jjJ6-F@WsJvi=rj26HjxV9UKM!bt z{yc?}Th%+NjcaqD%O=6`0C>m1BSF>*yAv%u`_BVptdD)tG*$U7vHx`sRHE^{l8T+e z+Vy$#qP6?O8aJ4j?V9Ruu&km5vqT7!2OpFsK`G<9GO~f4;@Vzc$-*%_7nlgWNGar2 zqj&Od1n$481BiR#N!kCFaT0kZ?Dw5ND6CcxJ@b`p0~b(P0yYns1-kMxe1wh z!&m!j6mrQD>v+maXDajx{>tk^1M7Gd84eM$3bT$K@x_kLUqAW$8oe%MezxCk@F>=# z9BwB?EJN`y#OG^DJ)=zWwMu=-cRZg&&6m*MrDgTUTbGEIDx^}9V4d;>!an6%AL-E9 z;A1xO2=1%@KNoE}i@zz#I*{j<+~zBl59jLEy7Qx{{!ALy_NmDsKs)Z&SRefq@h8ti z9VwtEwV=1-<2Ikr!`~Dq_OcYp1)N&4BmpC^-pH6Lo83vA$~Y|tP96nbIH=6a-pGTH zY(kh3cXNL+Os|W-ht_%x-b4{cv7Y#+wXNaM4Yxyvyo}R48j+WfFhdm^p+I#@>UEmN zC#a-v$ZDQ=7NT+{p#Sxy#2mq19nN+-S|)X%TLB5EiVuG>OaOYOkia7shrVkPvHk{K zV)){dZOIztH9}31<|%^mSJsl*%R?7wvPw{6Brz(0Fj8}X002&Sw+n#HnVN(_z$l3J z!rhry7iVruF@dnrbqo^tQWdgWH|)$}_ETz93}~#PqCIMt(4~p(jw-wk#TPR0;TcK; z+&MQK6%g@4o)F{Wf|hDPgO%zgjL9=RQQqRV01HhnLWJFH74}2Xan|nB)69P@ z68W=?K2vPb6gJhj`nhz+6I9cq>*`Qjtm5@$1nVdJi^xGTeK!YYchfpyK$4##2e|dj zRm1`|5DRg=J`N-#juMm{hNRE>-2L?ifsd3N1QPy7_oj&7N2N=Rm@1}qr-ps4TQPTY zMT$s|6=<6y4g)F=D6Z>PkkgAOB@tr+k{p)x=^8im2M8Pv#2hV0=~G~uB@sEWOG6+U zthNLMdwXRQJ^Re2fUlC!OC@9 zg!U}rrMud3>vVm0HEz+l2q-yqkUbE(g_2TC z^Td13vU{22Jx_wUK<`|Uor3H2&?YEkdc6TJWvVXQdsyz}a|D0ip*0*cqm$V!G!D2Q zY2#`POYWs928=kaI5W74g`P=^K~Sa&n~9_-j6;pT$33|5Q8Ya%XT3(dVMGAIXPpA$ zY?>ksaxAHs08Ehm+LyX{ki>*pmdCk9Q=shQ?hf9pNdG3swb!H>jH!7GCE>ei~$1?>qG51gpSMHz#Gc(szJ z33_}Gji@yF9=LCOb8lE;X3GXj!k@ETe$qlNGbLTjgTME3;oO!9UjSlSY3{g-dnZco ze?My>W{x~A##!Sv9}JxsB`5=!eAP=8S-G!_ba$U6l)BnmTsWb8_%~vp!#)s_NXhzV zu~U6&z?MXMaj+;5Q?!|6CK$2}eFLM&2(2|}&9mQ)`o{#kd3Ky>9UFd^5b+VhPy^P1 z<=7eSltwy68`b?)HaITdqVz->;1>isNLXGV);1-sP!Sv&?sFHqGoNZQ#VnCHkB;qc z|BOFZM}^gVbynfI(Dpac$8=5Aps{<^a->MQ%j^@rhKFEVj~JL%`P&7I>XpqaB>5f2 zz_=x-(7>wSo+(N8o(@_!qe~%89J3Pr-u$9;2`9KDsjgQo0L2Q9gKR&6xN43uLH{rh z1+CijfG{bGT5q9ynND)(f$831I$kTz_4hK(2DGO?fm2L)9`K25KZvX%T z0A9N;30ji~ylNgrq~#&Ixy`EmWzy()>-oAN03NHed<_J3sA?f#AXHnb$QZ- zj4*)`&sXZvG6m??D}wa&JLx^_(SH3bAC9MRh%vok`bLPuJqjqQ-el_@JKP zu>+MMz0=(jJ!$67nnBA@an>iuWih>GL9K2^O&QVRll+X+VNL=x`H&8m$t44L(=(E+ zk{8y9cqFM%7TpZ3x#Xc(g}UXSEY=Fog$oo9TzVw)$=K`{HB!T19G8*N3gV(r-xS?i?PpMHKi%`VGvNxnhs`zK zeBoS&SsGuCo*D<~D>%_;3DYHpQLyQEd{O}17#T997p&V3;fLp+_MRISpLT!w2yjc# zfK(q*Yp{nE8LHkKsBu=d7NvMXhUSSvjYNZ#jmg)^dH46PD^Un>WE1~G^LUd=y{mp0CYf$zjHE0 zbNTJEK3Hr2@aByO%xze`J0G)Ej*&_aF+di$z{8f_ZY{=g83GOFh@AaiKnGPl!#vNc zJEbz(>e7%QqY&~zQ6IE0Rly)DmDnLT?3wUkE)`O9ZzQ6TXiswcRj;ZEM9CZmRkmVGODeFrp|~#qNiz~am$W?Ee&Fm8n&)ZN_E#>ke+S}sr zs*`zYm)pdve{K#ETosmjZ(30$j=Y99#yRrAcFMLT(&a=|9!%`MMFB=@&1~UEUTLtg z(q-&qa+1V|28=H=&I&kFS?ZkW{J2ouF7^{MUA908Yy8<`#*PZ^UzKxbT;#7^ePh58 z?V7U{$j_c|Ol`+`1TB-2ijHlzh;fjeD)Ppzvh#S@ppFE>tfxW6hO5kKj+Sy=!`qh{ z(m%}Raq(+@P?cFXud*eEEzqPlK#{Uj&US!iNh&;lU@~VQvLega04Q-G5`T;XVj>BD z!z0HA6E0Eb)d|^|TMc6l7M%sgty8LJ^e_%lCc`OK?6z~GokkbJoV@ud{g*zzI@<8- z!;0_SW_Q~WHnO>nM#Mou`VoF-NS+$!{}8q>--Ui@kG6L}O`9(E0t;3!zC~;3;+hnp zRHpIMKSs%CS2R)fen7TXC7vw^JJXgG@ourtme&-+DVQSHp~&y~u%Tn6Mvb+H%%z0E zrr*J9I*w}4WiK3`vFq?G)}z*B9Ei@ zCC;J=c<&=?R&MI!la%J@?`MD=CBYO4G#&DX?F1VXZhjt713uuKG$4-~BN`l6AxnqV zUf_tOIB&8Wc}kC{qMl7ISsbEp5Ruk=Zs%P-X##8MqpjF3?=qt(IRZ>hDX8XBYhN5T zX;7Czbju;s{0rc0DV4=KpkeP-#<7rqW>MK|hxeg|lY1G@QN71@+8r41Id$fs_q=% zhY%zC9aS|EWwT9qqQeO*q28>SDdT^Z%XkV8k@!mubwQB*JPfPYmARNR-}@IATn;1{ zzMTCXvl^V8}=iU z>&Mr`noYDBwf5Yv8gwS(Cfn#ev3V?%dD5X1o^gKzOw5zQWmI~lXSiY9Y~<2EgN69` zNX0ls87oL}@y(e-7aA}5C4OOoSk?L~h~O__G7}|(SIVO&Uv2#lNx_2WCxh>%bqPA7 zjCe!Tc16-K9XQaS=@#SzGYg5}6`&FPY}6$U7o?F9zKSN;QvveD7bA#1-Lp&wf6ZW2_^X9LJ_rFjLb}(f|^VXlNOQB}#0)Rps1$q=|5V8PyRl z8HnVpHx_YQ<82Q=k$pG3HkW&u82k}Li=x@gr1ks-;ND`Det+ogT1WEM7S(Id^VLMd5u)-1@ zO+nSBgdd41^TK+?jL$-iCNNommxyMki9F7SL*S^MXg3##dkA2zoX7*kbf~DI?a0UMT3I8WHv=rSw9%sd43EtDwuVFL zl{z4Bz#?DfdQmvmoWKA820dIpxoGd=Y<$@D*}U~f>+u@a*|!`6P;uCvlkIxtIO-t< zs>6DgxxuT}Tm-%;o{HwWs&z5Ocn4u`@pH1&}lOvpyGLe-hmWeIWM- z3bL09V{f^ZX~)EAc-8;&6Uv)4t@j6b;R+DY=@Js<8L99HRvo9{hYnhKL5U$S1&Wfl z>0X=$n&~U0NA7{D$VK7w)|%E;rZs0a_m`@@1a>U$n66G_q?@L~@vi<5&HemKscO9% zAYw0D+R?vzt!GSeH*IhM{zU*#T(4((@!+1l=-R50i`X4* zF{R=NtB`gq?<8M@y(JHD{EqEQd*3V)-l6avPEJK6hU@;U1CeS>*O*iyXR^JfB(&{I zb_PVVy4?Z^xPWiJh?^>9Nt1)?5ihEb_| zk>O8|AeFXvhM%RQBK<76YRO0cGDo|hi`ea#_G$_{WC0>t27VN$)~R@dXs;m4r&3H`_Wj=o%NhlkW_Qj)a1Lx_(EB;!~LUe9+E-dZ{1Z^l=fisVOy zLR9`E>teny z##h|FT*?Wgcb@M>7cY;xK7q{1gH%nu+qPLCzjGST?%Kka`ZAz8lT}7E|DglclaTdZ z?);iK*3iccZ5S_CL4q-*5)_emb`mQr!o#^>dF5CP5xkLeg{jwp*mUg+Ga!G?Nx7|D zYmH}IoU@};fl4X)KF>DBjS#Hdq19($3HZ<&qTa5AAHaSp3I6Rt+X~n(NjA?u+?X!b zo7FecOwO6ZN~C@hpGE6KCRwZhXXcyn7I0I6wGt-AVq8Z@HBwW3!e`qMTwKafny`xWVzU?KU&T((U8@HtdMDDjiorxJI8@||c0+-f9Ny>8L)=|y10hJU! zLLc#;1t-QM)$jRteB$M5!^|XxOAZ9Kdc#efD(pe8dehZu@Tt|E2UxHiJ}vVEk_Pv& z-`3fi{gj1)(xz0mAAC3;W*W{`1oRPj2ex0L!@U z0=MwEyV_Mt%$+#q=wRgldZHL)Awf3BY}kWy8^0%Hb<%Znz^eq0a0u6@Hzm@08&|wj zU$2P1Q(FvNa@zo{Q@e1}9MqR$(6ONYdV;)Jch=uYAt>&{W|Mu<-~}%|eMDZTB+=Y^ zDf^!v$ZuH6U$Qv1=WTFOgD%RGKXA$t(7kTi%5D~{EWO&70a-|!m6=}IvK)=$s+N4z z{}LRFK-l?MAi-(X$7YG6gicv5z@~>?@m=O`e2@^w#e_qt=Qyjr^@Y-91>YvAy%Cb> zi-$Cuv>XxZZ{ujCFKh$)OfMlpr*DimDGPd?2vmi0xBo$e$2~@kW)L= zP)U-F)rj%LN*7R+IUuerk9@QJul?_VK)E0Xql`SC6l44bYG{`ATSN!^)1A*o-pM}> z38gSO`Tulj%wTB=E#CKN&Fct5FNaPp?ExZqzz_Qhe0%; z8J_wd0hcRTH>cWW(s-Q#rFrp>FD&tG0S|*tI&dGO0pS4x8m6lEAHO>eu*KA_O9CMo zl>}_xy&613g$-5|cdj`RDy|@&CpcVlyE0QDE6YSr^?=CUwC|w~95(l#=EG;DR0z8! zr%Ga{rJ5o{4h2;~+gxkYy}f}h>XYr#O|;&Q4yUfa=8^tIoH&P|;CpdbhVq*Y#)!*k z000931!2|lzwmYpS7%=E3DVF18*7t2GrzBiIEmPNoJXn>*pMd1FjJaQ1Fn1{L+n4#|d82I`+cSJNXMszCF>{G-3qB5_#py`a`#qSD6112$n1oqQn{g`xcy<=L zO!hK3<+;E2gnAM%C(o>JSieN)(ZVfAjVMg=b8~6UT`-iwr?cPcF6p^ul1Zz2ZtQh- z%s2F3>?&BDOo4PTf-`u6pKBU^00NGWD8E{zQ^QFKpydn1yIasTx_)A12&J(`Gbl)C zd;zkoD+_h~NB{r>0B-qr5o(5giN)PR(Zs8SYW!HD0! zxEv6H0S^7>1E)=}Kz4ITN)zm1rz6QhV<2s~+fO9(dy8 z2#*Tbf0o%y6wr{};f_f(!>sile7tHHGpj)(>!_CkILI>{kOM3cGY@C|7kjGAw8*Ke zeB&(G-J^3m0J zLMmd<8vs`OigIZrk`28yJpzuiUGi%B5;Pr;!m6{5v}O+ipN&kuoD-1E1|!tCGac6Y zBBp&dvt_I+nxUx{>rrS3u9dEB9J5Oc32bRF@k%T{Iwao`$ZX2bmB<_SKQyqH%9$>P z9#_NE@LS?*5$aice0)-_+dI9OvcDAlS`~!ghvfUN@=bZjIEQQo;fmy@ARDU8!YpkU zf}%ART8ij>1tbp-F218WfA5B)oREO`Dt^%L3zhJ$I@xQT9nW$jYJ@Mzbs78R@m}xb z70YBDC}uQe7>_HUr~JCJOOVs)>=BMzcvG{85YuPxnU?8_bBKc{`#9VAFyZ<~1o&Zr z*NFKBDy+$}k0vTdy@#P8aD#cVe)qy6=XI|Z$k#^A4))W-p-fa~kmh1t6~9ajQ|5^I zgI)Al?#Pjmwb7%Y*O{sme5)Vmli>iJ;zK|LPl4dzxE^& z_(9q{63Io1?;bx1npbV?CQ{y87G0_NRZEEzvJk`=pC7=+37tAm*SOT9S)102bwjJsqRhvD-FYHiPt zgSCT}*ID--VrMGoBs@d=7Tmypkt-Z4Uh7GkECl72G7Dt{xzsdeUZo7ts+<9g?L7w5 zSo^UXx(?^H@ObV+KmJ7jVyj=4?*&eV!Jaa=X&X5=X^*BUYaQ27U2}>A({eu&rH#A~ zslPks;Q%^_b{(uG$-h56pGvuJU){pvh*obZ4TwTeEdg)iy5Io7y0vo5OwbWJ>N>k0 z&eV#uw-UF69-Yl0$L!eP7(WocP-7xViLMR(OTaYzR!oMS6RCU5?!-AHotr3lDT+fT z@(ik{C8YjZ1l@z)8E9w(6W5;M&~Z@7k_4Rh0lM4fI?ktlLk;$w)6LYH+&~!Z5h&!+ zXzjiat@<;vo^CR=J*~Zw@bXIZj3e?e>w2pNfK^O&SUWttya;J*^KqA|stk43W8zfBO9e z9UQ_4No14hLQ5`He)l{6OSf!5^jrEYx_pGGWS+ye&%_*AP{G91=h&v<-;W+Jm;d$V zrS*3`j~RCCPJ%f1m#>Yt`Ommc#mF|09Qu2)Ip2mzaCv#z9Gsez*?pE!eI?$V(vFdzmq_Qm=AS2BuIpa=mec zFBt1=v5X_eiTZDLwWJkjcol2S>oGE^6lmRVDwoxe5xsK2sMlA5zKx7tE~}Vw!Z%pP zn`#x$)CY3qaB+^$Vh?B{z&Yg2svjH|~=O4tSFLe7UpXog-#3NIzr+~g)4-Vpo^1BY>fq7(o-Wn+C#06B zuy!O<%irw_2U?&yLh|&14g-f0VkydLL*SRTJH9lo5K+eo?+_;yA7SyP?h5;RHk;-! zevGSbuWc|(5wb=tk**mWzwLD1C<#M*Tla}OREaluNoVIDBFnzn88ob90EqFK3k=AHhch^!t%7XPz> zR?Zk+p{Od-gs6ecDI~krw4o}+1Fw;*C-M>Nefe)gqg{ImobNTI+AY0hihL2kn)nV9nI3z>4;|2T^7c14UaYrTKA3oPNwC<74e`SPev)ioEQ`tDG0Z%hXpLLA zxBd}|#QJ|pb_KF@kw^h~zqrCVsKi@zU62%C322#_x$I^dA4;e?Uv4dkyj5Xz%}454 z+l?1aYT1X`l9;5M+I>L*q5;`3R^JaS8js!8o3is|&)>JsKUCT|3(NF`5bw%Knw8ni z2=4h909JxVc+z%vLd|lrB-{iXcj&0We}|uO(S*QyzH#bPHL_=EjgVS+XD#|67~i&B zFieaR{FTd7Q3kkdp@EDfGqh**y}*W`(`OvwXtx{!Egv;@Z-L(6aaM7JJ*SRcPm2Z= zu^I^rz8o<8eqs!+1a@-Yp}DxVU8`!HC~5|hwVyi`)Ea$UmXyI(M777B&j>n@no@>uIVW9li38Z{Q{&{KwCgr=Jv0h|& z#@%s~bh~m2qQP_ixmE@Wrb=yRMAWigFwQ5Jj?x_sFj&tE;OX`I_dU$)d_3nw$ee!~e(=REl7+QzeS-{X zfHLQfcciiJq{%{D{X`;!|03ZEf(y+J)heGzdR{`iis{)1)FCGL*cN+hitN+iO#IO{ zWBD|%&i4{=3`hq0C3s1#{81Qu0dHr4N75JYsacB9RN4K1z#o`Sqi0C?B2FN<;*nD_ z0BK+`cjP>B3m~)?hVtPJzZph}Kr+N~qHI_4_c|0ew3Kebt)#qU$qG)&a84~lg_WHL z1(j!zKd>5c_ub!I{RVQdzJeG)qJKVuM289kZb2?tAK4{N&sF&BYM`{5Z7lgjUjfj% z`ypeEq&f3!#U2<)*Sz>=m`(-mi)=RmyZ?N$0dGuUkRaS&Vf341J6FmUZqkQwK>G52 zepYh5-yCiA?YM+q1g7t{(@0(-k5)=IYNZufFkef%5Chj$RdF(+90H2-1_h*ebsP1d zrg?2}Tc_KqtsD4YD=srbQZ@Zw!|5*WAH%yTxKY{Q1-v=Rzo%qD-Z6GHdIWn8SoQSC zS<*q%aU+Z+=WwM4XlLar3_9duDp&|jtiM!`7sYjna4I7sYZn_KdZWxcs&>3x@`sM) z#VnoXzdY}f56yl08u_5+=WJHh?AQz})l6mbMkM+*)-6 z!z~QOI2cygNgXte(c+dQide=@N#EUWs}1*$ojXnF5-wPs7BpCdUiyT|nEXhIFVDDp z+>&donDdW`6480*QtN^=(j#l!R;{{?j^*4yinQBK%z|)y0)i%zAdbwI@Ki!f>5{V= zsZ^3=hypCX)zSXCe+ljUI!S91u2B?6z6VwVUq6yjYr}W#*u=g^8uw=}oH!d#95?>f zQ=Xn}$tZ9tp$8GS)kj=XSi8WDBnMvkhzG{cr``sw;xh_P9g>ItXYGjSl?u@|68IK94)9F~hFRMdhr+Ft+GvNYMCer=P~j&-$63v0iMjA=Qr?X_wZ2t z(c7a~BTv^hyFveO000GhqE)ahs-h@|8r<;xSwFG=-1jWeHP$V+K7hZK-06T93Dk6R zHz)+AQ(mk$MR-3e@IxKVLjD)bD!(zQ(N3AW*XVL&o^;zIGuoXoxRJ6J;w8tmcub40IlGiz&Vv z&gA&Nt+j?Wdg{T!cpUmr%~$_igb!Wx>8PZ82j8X)yJTeKBhaYX4x7;LgVJ1BDMZwFTf({FDvS}w_d}2q>MlZ> z3K9kG8?;I*s308d#WP*eWjKWGAaB7kw9DMCp0v=Ru-g@Se%Auugf({Cx350L)`Mfv zl-0iVl`zk18aiIQdFX$y`(?+qL?a@;RjEV`zV@P_u>QKW_q7JUf(~kTOP1Sygv(`( z3RRL%M~6_QtD}JEJZYehf5h;OVIUv=^;yrPn}&Eh6iEa}j}HbDX+=pX;;(pAWdGlLNl}YAaV=IiQShinOp)|*c@5B{`GVeJ$Raw{oMG#S zx;%10#-+FPGEf;KnQWEdCxAoi1qD?RXo?RJf8tD|@fm-QK5E~escc1yBrrStTAdQ^ zfjHaF-`|3-$xhNkC}{09R{1@LibLu{0H?}ocYh6NrIo@Sg_Aw*QAB#GPbAcPpv^wj z+hr%iKa9+)>b&A?un&pNGex~`z1Xb`WOb1;u*Z*ua_1C(vY{Y%-S`XMF8@~E2H?9n z>Om8~u1{%@vhivJ=^b?!+4JBGnQv_)0vkZe&a}r>^jk$8LX4R7*QZyFTd}7 z+R|)v;G7|B`k3-hu6YqTSAwe1-F5Cog1z_>g3}7Kdm-^2`XNEfiig=rL-8n+e4Z4y z)k*>0#MQ-1db*fxvtjm%d<{0S4a)tr^`s};N#pgnWKYoDD2QjB7aOhKR{kBd8}%xxZXPRrb-2W}5?+h;((Z&` za@adeeeR1K!~`q9rP_%d$FXk(KLpB(7r5w0AM|U9Hw18x3N^5+TunTSmHQa=Y>K07 znWX{3`&XL3OjmFoCapNc0qP(51C#v3Kl47_Pxv$#6lj4;1OxaML|stl{Xg%<2C&fl zK7X{01w-ITk~n7I`wAEJR*^y#SClVc=H2>#MxWDV#Znd3Y1;NN*iv{8`?M%~uX z@1?Vc15h%^1mVtE6|*i%smZ=C;quy z__?hO5ZjXzl9k*)PJgIj8ag0j6_oJSun2ImU}WK5FJ_CogIdQ{6T`THX9)xXS>6IT zuSL~|uN_UHU$j)Yt!}?eFZHN^#@ImV5g@c$Ix7G7HM&-b6$^se*yRKE3dN(%Q>dX( zslZf^eRzsR-p`kSR@j)QEcaH5v{+G;{8;s9rmB>ekInee4=E|Ty5va!BU_NSyuqY$}*uTgC?sm3CdQDR3DElmms6)6l{zbdU> z^a!uxg3GEFvvk!5j`B_|6vbL7}(x7AuYY zSx@Rs#ilumpQV`}tU|P29@!cB0VmW?9mKe~+fK^&m$M_a zbz|rs4mtg`G@Cs!R*&rTB9my7OA|n^kUkQtYt#KF ziT5XwLrU*4(IAig&hJg1o0LdIN!Jce^Dyc=%rQEA!Ly$^&0x>rynyzqL^Ky@?YGoH z1Md0)5P0I@{_}#*QjQd3G3rk`Gx!7Y$#q|B?%u-J(UjH(L9p^0)Y&4d1N^{?)|j|h z!mYv1@Qm*^QjAiGJsXBhMxThm?aP`;RZwe{pzw=V+C)O8AJg+=;M>81jGB4&z#D{> zE5otgk5d>2&EqxE9jLs2L*^v-BnJdrG$VvEHSyw^`4ICHnRyD*d!n|%Q@rnK zkmBKhzi&7PIrl+)Hjue57%j$cD_}mWhEoM%P-Y4O;I|22*XMS7E!copR4TV!YOh{5wk2jn z%+daU%cNaqiO^|@1F@ZYB5I$ARZ414gK!OAba#HPbfiHH~ z`vhmWzP+Fk>Mw)$z`2!k{$2yo})~nQ4>fR>jYpDa_$_*uHt>XqOg|Em#Ly zK)Epjk8ywGS-3dnKdrE660fM*%kO0YgpZSyt0sH~9_w9V>u zfVP1$B?xdO)g;liD$EBW@O&(Rld{ezLuAK(PvI#}dA=%;>i0pjHW$nfH;MdX;IcKf zFas~4cV21}74rXyvnCY1wP&rW?e_jgHbsygABiK4*m(a2b-i6R9q$I7X=vx68uqC~`n}mM8 zb?uhcSH5dh=%u|&uAz!QN6_;RrQi?oNZCGcI`rGC8iLt9e`wRpf-!3xNH5BijWk0E z2c$s_G{c($T);1&cqsRGL@QrGp<=a;8F|1VhKXKcyPrNOPNQ;fY(@|D)0!-MQ=C&F z4s~i|bh!Vj{UT&rZ5&cGm!bL3GGvYc5!3PH8l~kGAnsEZaPrPcH|{4UqlqWfxa$8* zUrrl|`ala|I^~*9l}NUeg&Pm;iJ1vwgAb}zfCh;QHz{er3JOwMg}W42a4w_Kyoxw? zr8iN8?reKRx@G$0Ac0VwL%ClX9x-3RHHfkjNNcmm)>gRBVm;vg`;|wsF@)20lI+T{ zW7!^|bvrvOV8_6-G4*ykFB{3ZLShJi^f6=741)R1B}N^yuQk3l$elHYvi~%B5~DEZ z`s3olyQMSQ{TSyq(gXXu#~RVkweVH*U~gktMPFt*(Ly(UR?oGz2qC!bM|*6H$^cx= z+!SxGE3ywfn$bUF4f8PxP<=`*gm2tFpPW!!VY9av zb7`#CF44G1lPIVW|Bdu^rBiu;Q#!(&D9O58ThO>VTD3Hu%-*lY>%)|gv*(Bs=owql z&mvpb9twJd4HDS89~QjN>X){v4QT6Em_>-oE;E0=e!C|aJ5KYnu>oa1n}AKHPBc;A zxmS4eP>L=l9GHtt>d*jBgP3dmb9zlzgKA`ZA9p0vGD|o3%;rR`tt^p8?!(cLFG1O+ zcJ*`-eRs3#i}gTfdla=kSZ*#xi#vE1|@Ni2U#5fgL)F zYqq)b0aUQLfr&eyHkxYc=_@!kiLo1|{&PQXUZ{OS zgkDKe6tHNMvIeloGYKUA%V2F*75S5%K}Od_-gD7l)u&Bt&H62hQWa`nlxt-N%B|}*eZIi-qY5a+0FRU7-sTrl5Kd`?8zrBQ7bL zL}3xP3k*o~WOk&@ce|0Ij=avH#HEh+ayAEp{TDmCB+mY!-My#T#Z07;nBTX|*n={? z%6}HbTHYDRe$BdtQWz`HuP3T^qNcV6cUTf99?*Hr_bqiIj+hFC%DW2!Ar$)}sNR9gnZ?T2qYyy^WKj2F#ef}s%% ztC-tib)I?D;D8eQ&hQ$8Jqs?#i+ zxN)>Q)6qbYq3NYm_&kKW{@GUY_Err^rS47!>PWeWk9%*HxraM|S#ll`V0&v)Ct_%1 zlzY^%Ve?FX`M}hT7(6D9iUT(voWXBciqu2gwM06N>oQfkYgxQI8Nj^(&eJFs|U^Xg?wg;8s`*u~SKHEtSQYFon%a2aW&&x6a; zNbo7p>~JQ*`S;C|%;Uam$|zn@;*m--?pAd%#X{Jn#Uz262U(k5JZ=>KrdLrz1Q6Wy zYV?2E!0Ys_z8!r8TAInc*XSyB3J{r|Mp#Q~=K0LIybxRCVAJQxyw7xUgPyaIfAzJl z<6q;1JyDo7>1+v;hRW%Gs>q=WkJ(P0z&5$B0Y7*s*Kx4yZL{G!+)2fUwfYTTk|Kc5 z?+^wQx*rk`Tw&q?TeKi+5e4uO*|KwleStXs)Hj!EdexLT1YD_=|9Fw6DS6U8LJ}*t zT(9#rhUq(1|j zD2Su6fdN$KZ#J>_bswEIyEAtb!6&APv4k3BvF7#rWN%(i7z zb}G!}^t&yP(!ZQHPi=T-S-Ns}l#nL@`|ZAz{+EVjkgR6BywOxHFBbD>&EbFB%}_6& zO?}OB_d}uftCPz<`W%5K5;9AKVG7hI16G!K*)jW2anbY>D;5j9jJ0yFMpb}hTf!R@ z0>mx{C{*_~?VNhJKs&s$eil`d+Evdm@PIa)PWLGa*=^iN^GK4Nqj2Vdc+TDnu?&AJ zMSK+;igfxP*0vkMZMM7rqM^6B6nNM(usStEPH0%Y^y>@ODlTSq#jl{?kO0_BonQ$u z@e~3YLH%_|pDxNsc|A@oCXYCM4&=4Pn%5!z`~FH5sRSw5I7P@JYFl283#2ubFnxmq!c?9RrE=Pj2{H5l^uxkPI^xj45dE$=v@%|(s+vdQsZJPCZWR|S z1e@nLY8AIvYB{mFX|!M9AC0<)w~u8DR1TLGkPYIS(D!>Ef7MAz#BZsY+EKx)LeqWa zEC2ul001FWxzoS-#5)uwBs%TDuRnP6DMDw4H`wkt+!L0%2GcwM)Bzx9LC6g~xbReW z(H5c)qoqJU@+%<^@U>2v77m$>Emp#O&U7Al^_R$oV_TB{0h8NqkSi@&S>5-yG?r0t zcdC++%}0#w$}UvHZBO=#(>s9fi=BmbXPv-sAnzlR4bnO7S8dzkL4MRzO)HXb!m%&` z`YxWKbI3|_FA)7eEiwRza-bfFlEXAl1YO{J&CN%-{&%>&8GEc zPsGx5hl}B1mzAqZ2DIi?c&^iROm*5JN>5YB5i$jE!ZAUbDd)rT!*gJf`v(jqo^8D8 zZPA5b0A`AcI)|%5eaUGJO5fb@e(vK5yn3Ii^BSh172lCh#myjcl4?b`n&hlTw5W`= zPk?xn2id$Ealw*z6=q06s}6q!mICZ* zQfgeNLE(}U>rr0XVY&*yB{&8fijeC|W$(OoBTB$P&`I@$5u$>xnY(f_(<74l4 ziLOI=BnhIA0evm*!Yb=Yb1J8dC7gIi#(%}aj9i5NSyfMstz205<%su>JvvVVIX&hE z0f#OXV$FU2X~lT338VwF7|RN~X}4sm4W`S9*uJ zYKy-!!C;iN+>2_^5(y`ETldxa!do`Xth?FjXD-3a(BY~LRYl(|-NJ-oQ_cmF5nxzOlEddhV!=hVeh3y*DI?_<;Vat-umOHf&HHV{$lIIfdO~%UE7zR0_ z<~!^RpRs)RN#l63AnI+r>{p99Zl!Q2#3l+yif0#8c^{ox;mSS4(e)bH*3)UC*wtFa z!s~q)*XrxCuhheKO-;scI)Wi-nPV7q{bbWHF~2hv)G@XUKRPXh#KF^M8C?J8?#_EzUKnF^1O!!V&yCN*Xh#6zaR%$Oe{ICS z$%;HK(nF8O-k4XLk{`(9rXFWltL5MdrzDe`SwwAQ#@v!XP!udh;@L)=dqPWBcyqVO zqeym1oYisQssqif$DW4r&~@qZ?J>EK$3AWRpYoCS#WMlnLuF2AXImnt6CAE4#|1 zFRIi?m_B+NhF1Wx^Ib1(gK(kHTbu3{=pY4xsfDNE%YNXVjc`6D*C&mUNZe{5^z?u5 z;c6{KXF__aW1WbUIDvZQ*lSi;)RpWe#!}E6UQnhZdZP{DLK&?iQF&2rF=N7tfkBj% zm!f%VKbx;on*pTi#G>lZxj^(1& z@dDSp#iv+(8gqkhykatGwMio4!7=DjNrigTsAmQs8Z>y}&!k^0()|E9Z=Z;Wc+WpmlE5m809f68)kQI0D`g~IhbOb27DQ{Ef^cLNf7t# zC<+W)anbQY%zytH28Z2eLQ37tx|sJTN43I3u+fb8G^I5pHmyl-{6|_5n^#{{-Pr3J zaW)#VMT?CD)-=SEyAHf7dWL z%z2y?EX$H)N?+sT;BS89SNFp(=2$iHd!97X>fedn)p$USeAf`WJa{9$3{XMWSxv(K zzMcI?-SOQJ4a2ZlwuAmxz-4mU4fXF`?3`-%u5$=r^0MvAWMGsRbMCa3a46ukjY)fY zeYV$IwKXEZ_VlCzAXgSI)%v?mn#ZO<9OLUWXY~Uy$=tPFqECzz;Bu--7k6$*vW{qT z*2Id^$9L=cECa%1@kN}y727RxBkKaZFo3cs0k_!?T}d2s@>F;iEfg3Sd$%@+W7nXj z>M~@M9Sp8;;T^SGb9mAzIVRqs*FfnYk}d_xD5YUH zi6L(}(!?Yfk03Y1)wjAJ0L!lY3DcIq@k{iccq;r%00093HGCmB6Nkj0eMrN^5~h~5 zX}~VGu67Z}4nS+?52fy%S)?#E-zJu2z|gT@VtQ@;IoqQ0ogse3}Y3MXSHR^6O z(9lh{99Aei?i6vR;RU+~&{}yN&i~wg#E&2LF!lt>N-Bobp_WE;Xuv*%*uMk@WrK=0 zo+?Dwu+Ml&{5E<5^HaopxNrLu>6*aFUt0 zRwRzbX5;s}2mYM#KYL~ca96Qq`4aS+Z#PeQc2%10tA%jvA(^6Vk|Tb5jZypRKmZJn zIXRRDPVg&jwLZLSYrp9v=U-$X$RuQ3%h#ZCs6IFTclI-H0-b@O%TosY4hg#&V6NLp z=EZ&0yH%5ra~6J!FZlj#>S5mxw_}3xQ4ast z8|`H3gsA)q)c>tRHSP73TKpg=_JS%Qn>0L7AEkuyI7GU%akg~0RZkM@Bp(xK#iNg1 zovp|u3yxS%?&L%m_^<*fV)0|SrXB3k^*G6uQYE`3A^|}x#Q}gL*4vb(^fv4whEI=s z|0umQ3brIv(jmcw`188kl?w@83#l_se)oVz;DOB534#D+4lP{6kBDvh-IT{;7yX;vG;A83wGNdG!HH*NVUra{y>j#G*wt|^Eg=6vy25w zX4yJQLz)|Jm}XGdr=WzGB9jprtT|_K0yM?IKXhT^3A3CExWULM;+k2xLW>k^v|8I z@3$i1PTZ6_&ak}useYQZWcJr3wAL^Sm!k2=f!13lbdV@v)Wimf%8&<3V=TRrxZ$S1 zx665H@MmPDzSN9ydjNMph`;7F0FrIwesNfJ6R(~G@<7v~ia}=|ynBFd{oHN~Kvse5 z{{r#(^@tgG64b!xySuCVJtl`?lG5H2rxWu3U zL2j8)fY+{!dJLlT-a;0)6etv%`~l}>Ra!22B{|nX^CdaTU9#M_hTvYqA%%Ol(I9Rv zr*;5lvLHdcia~_Vf({>mgg$p(DCMl`f&L?)d>rw)1|-!X@hpj(z-1?k0HOU7+{>lG zMe*g3AgR@gf%(a`mi1rc`Bl<-b?*AS6QfN0q8OUw&VAG>7*yg+#O!kKBaCc-FX^d> zSAUWTPlEl!9G9aAI8d>AagUuR<1wl2RT^jCb3Z<%D|}Koa6MI_oMxsdQQX0& zmTj5C6RYpX`*kU?F<|NKApV}FM$!e^dVD!~i!&JwBmYc4S(~YIiBWUIHE{l=aq~v* zYfhFEQ$lGDit%a2ask@{I8jdNRf(&&0-jXUf-^cs)bwUd;!qR9B;h1U)_Gj+M)tyBdef?LK&`e*@U6{ zt;AOwO4Q(D;?E*5P)-r}sy1b3#dUZ(FM$LccS6@N>Qy`xzbX# zNA7FH*Xhx-S~e(()~PC2#LyACHcdIAY;0|~2rXvgTT58Q1VoK z5^O*K00rX1QQWsDHblq&#H!2>;DJzz0N7U*U5+bqq4O8z^cvcqokMzAqZ4q z*k6A#ES?nl;Zsbg25)y+1O-mq`{fk8IUsBM`Mn?h(HK(ZHp9c)jcEA;Y46_I@RqtO zvrYaBF_J7cWRUW6V<<_p2KwUbZCXzT_So&gZ*~?aHs;ai`L^Ha;C!Cg$kmS>j`PTc z`_rKW?nl9cVta<=pk8@qCcrkg0Uk1+G}(_@Jm)2d39YemQ(5#>-2Ni*)MKnBsvHb# zd7zA`o;^c-uoTqg>AMX!Nwp&y)}>{$DBuIQ4X;vURmGzUVX6z#L9*yzl)4MqMdJ2_ru%F;Ly_f;6&|&fFYKbQp5MZ8m3Nc~<@Fqis2<*AuMeAtoZ{_-gc=;jV+z==K(DH`5(9PSA3o*i3SnEj|v1 zz++b*qD`D~noeZUs72d3qjw*}ZVkgmh;8mC%)i?4ISG5qDn+GMu{26n$zhTGhF+2>|SU@%w6s+HWP^uz)4;>QH-FmMq4xr@ug}ahaS1H;e7Xm zFOw3xgSgOLWJBdC6@@j&0|#`6Hn$7GSZ$KExSi~Gbng8iQ8>Ao61%$VP1*5E1QT=! zhc9cPqB3)5y&r8__6wj%Qii$<`6>sF(F9^{seyRxCw?1LPn-c1{sm z!K0ISP5t?3zXVuvge`%(uhrHGptulqjB>JeJTJwt@0KSRZync&xw~`u(FBfU4(^rP zRL9tTo7Wq6^=K1P#!AN>V5XVhsv2>jpaw?G>b_=_qXWY7G$Sxsy3JIIjW#LaFi8kL zB(lT`Q(1_eQ$q#&U{}sa7kYP%uZ}7#Yt;Hib40enlCvA$A$MIAZveJJYyEO;VrTXflP>c#iJy@J?615(3~xZ+&VfxORmbB3U(y! ztm-;@(ea(}xu%TuN_S-@Jn?gdfn!m#;cwI8&#(99i{X=5}2v$(EOQ`p8lkJgn_@ITK60!-%2 zgWowh%pEC#g2IzPq)8Qje?aUm2cGXYM~NfNXAwE`2pK+BwUV?>wpcx9HH z0009309u(C$Xr;38_~9b0bkreX8ArX2Bd03DH@#g9b=}Agmg=z!(`qMuJDN1KSo4P1cL|+qX zC$r})vcTLJQVVO&9qzcA7T#d`8}wmHJJ%j@yVyFbkGAmBV%d0|xdZ9XDbkQPdAdV) zY97jkGGrkSqmFe2vM@A|aYAH5W(VoHOBsosFc66Xn_a70kk{A+a93R0>TR8Ht&f=8 zs%umymcE#XER7jUP0Ii=jGQLMZ^W}af}UTBOru&kB;z9LrK9QuZ(Q<0009300RJkeyYFG0O3lwp$diqCV4#= zeCK`afbZ|s80Xx75&bWQW@F4c{Ha+ z#NN}wM6#QEs0gK&pb%E*=dh}b=~jXILfI}b4!UEAT>L)a5r<2|Pr(e|j!(R7p~--P zaoJzu)GSA_gQ>E3O$KOy3^8y1l|Cf)a@4esr^;4|N2!kE`Q;H_0sFtk?@t;tr*C=<@< z^R5bX8_~QGu?~p4JT5P#rC(5({i%I2;4&E^g0jJmOiQV7X_%v?MqF|B$22wcio(^@ z;Vzgbu#2NokR?m2rMFMVKc+wGO}9veix6tf3Ct~H{wttQ8~#9jyX@Oc*~M zwL-v0kEC4jBQS@`$2it;cO*(K4oi!AWd&xi?v4UW!J+4PT8iL>n1hGfl~emfXYWG_ z;-&P(BIZRU?K0zv1$?FI$~Gn-GpXRuLFz1uk_7MKlF(3(m_vxWEd+ZK6SYE}NW+xe z7H|He)7n!$BTH0=RulNasn^$SXB>KDDfufn7`94y7o80xLCwl0>vf9BZ z&xb+y9NY{ioP4k3DftfE)W0ea`vYS!!{~4((S15s%RvbGPbXYw8O^yoXrWCJG|0DH zC?qk=V@++iYMC(!e@k!?RRdtiwxAc^e`NhQhkMJwE!%Yv-D71=FF`MBs8-cW@_dt+ zeS7Mwup4OE6Jk&q@_qUfXVW_&i|_bP>f^GlV(_uJmKVa)>j`WpbC>Ui*0L2@)b4^e zP0}SYC=EM$n%q5m9C#Vqbp1&XAZy;o8bCI6A-~}VTX0$rU5uHs9?IA3t0?v~Q3-&! z7lNLFp`U1<=|w0&&sh4AVBD_-$FqiOskda;w&E2sN;bNj_SqUoC=vkFI&MNEJ++vS zKco9&YJhI>8ZmfNw-?;RUm>2)W)!UbB~`XxerjFRIq z>HY_l?3Nl|3+F0`4&Ll1j7#oek1mE8>)v97zfRqINm@H4EHRM{_Wcs?JonVRyu&qnc!&L=r^wdPLYJO&8dJSvV5%|}Uxzro|N7_*T*M46j1A9?QZ+Y0y zYx9(jPZ^2)X?hxzl5z)t-E-SDBZE4Lo2*jHfotx;j*u`kFo$ljmADwc#$IM?+fMDB zl3u>6l=Jb`1egXOoMC<%wx_`*R`4y3gTUm&#|ZUUfk2A);=d0GdmB`*nWJ}tz_^W= zejrRqNQyG;?EF?bz*>rNKarsGDzUuXSu!QAoM(p1)HZMQh<+r8}(% zPt~c-02pC8x;)JzP?U2YKy7EObxzD|2zI^sfPp6Cjv8NG{una9^FFm>1?vC+0{{R6 z001hd@4}u^A6NB!O}=M$>F5y~AJ2I58m0i7-tVu$i3VELhRgtvXtt<^;+tM^VGz@f zV4o!8woHug;7&_H6T?7XhuQq76gUXO;-(v1a8eZg)tndI^9f$ThUoKOvkX1~FKTPU zC+Wed5TApgjaY z8``c5)#!9Nqw>s+hjMUF$tR6Ezoy4HNI>5lKmZ=VOl9740CmJkGx31rhv^Q0000SV z5bk=yB-v~VBuWh+WP-yCGBcbf`vC^A3gp3WpG@V)CD6PozMaS%hsp z@AvqybjP_^B5 zII9P6>QS^(>T+~W<*Edkhx2~U$VwQ?QkCb+S@u0yG6~!) ze_?sgyqgb3*^0`Qgrd8%Gkd(Cz0xxCSDQ`;R>U1!isMpWKb-42AH83AiFS+AeyzK8 zci}Zc>j7I644+WmLbBp{%&=er(IEI<>epRNjpOTiUJ_$E_bCi8kzwswNEBDt%nP8v zR%8vryWJSQrhIB*yVUW*R+~Pv3D!fOFfpKc>r?*q_tI7XY_=J1&6%KG*+s(@ z`d$KsG_@X?)2tz|cLYI&9%o=Bk^D#-@n&S)^W(>nH-4@kmUXIjZSS}kg}CX>W<3-u zac9ih38RZu0_|QXWwB(JTSc)N0}zViUnOc5%X|yI@vtThzNce1Bn`}Q5^~U)luSQ& zlZOfKA_>Ijdo$bxN;x)NoKGlzsgT59@Ha|QWI8VFOh{LQV8fYJpr!>6evVFq?!Aoq z6ar-Nh|cPKahIw6On?&ZyDtz}eH`IjxDJ@UcjLTSFHM=kqPo?ufjj0ftOKQF;^mfE zmRX~_wTOvY+lG-{DXPd z$7;!mE|%s2Qwcmt(r($kN3n^ps!j4ZEqq8T%xySgFDf37$lVnRO%eR zU{$2cisZc2BHz=r4SbF%c*b1eW>7GoF-ntR7Qo??AkXyHr*D=l?s|JCzR<~EWx zstys_YvWUZZ|`KuA`Q*#`#y}>7b5eWgI@YeT*UPIcTAMz)}WyU0P=CSF=F1dN?!i3 zEq{6YLlna`Y6;H)+M@lQi-iV1okt2D*~k#0JiA~)K{;5lnrApFfX&au)b<7AAB5BH|&IIpL8XxKG*raFklZe)c z8qFP7;E=P@$Z$!Ll(5DuQ^iuFLJN?okTIA=er2zt#n z^e#6gy2CmOg}EYkeJd~xLD=lw5>}1qRu|?SQ=;=A=sFIQ9Q8@{S()F>-NB6Ld$rzB z4KQTl^m?Ok@>gdz2FYOXEr!8A>z8FdmUm!JR_0cffyk*+k@$ld-4_8*Zp}^JI-}oC zsD~B(A{I$-uhr~Os|}Wt^2EnXTD-AMjzLP%0H9@}&S>UitBnCDG==rLs%ICtyhPNL zJtuE`sc|(Vr^XD@h`9d?N~5S;T?H;w`iG|CGBiVf`E)mde7QqCqE1)CA@h@V!am=C zFZ|~Jz7A^3C*%7!&|i6Niw~fyKS@q5ebDV_tlrqrR&h^#Pk=J@mZorEu{HO%2-)(M_UH@%00RI30{{&L(XqDPoFpLbt60ZIoX`=a z;Qv4&bZ>9FDA(G!`Q1ry&h10H@Lf+U9@b3MOSy{a#8me(iaA#+Avet3$&Z8dVRf5B zplk)M?N=93b4O2FU|^D>=JcZj5Vo9B1*L>*e#(V5skZkEfyC5^pGa2SOf}PWzX~h3 z{5FiIGVkp&?*}V}rI40of8%0XSl+cn5sY?jbE8HfkkMW-{(^?JU`+wo zGtmrbu=G3;n^3(_wq6$=?49>aSrjttiGw>%rsQWHnOh)%ek*3d!_xK~vE?<$eG&4w zl+E8A70l+l#l=ryr#mry)}h+AL*{zy|iA(6jyc0=eqN4EiCCp8TC>G!H}5 zueUigzbq^pG&INx!*;u@6Gp%TJMo`ld_|PP2$1h*Cm}a zs0=uW@`xnz%B_QYsA>SDH`DEq=c{{(ixi%X(GvAbr+m!v0Lb01XbV!3wGD+2T@OUP zH!WqE#cl=|+r!Rfjo1?uO9mKK1x6q+3>l#wGtsd5s-`;~&RrL%1a4it87mr`)`nfL zb@UX6MSiu`rci}PwwI2r<2@FfX(I|sqdgq-{+Woqd5;2|U>}@=2^)6dbwu|`Z}R$1 zm0i?kH8H9g8YgE%{m?p>Kg^VrNZSwe`wGpz_m2xm>!=HgoD4UR@TVVn2YLZb0UxM+ zJ(w~XsNyOP2Be>8c@X6Q3;_?M8;1BNm<#;FF+Ry8 zTCWU*-z2WY9)bl}#|zfkb;Y;eLYC5X+gn}6Flku&o0yJe_~pBtb)&tjQaU=%`Atr_ zUpsV-V{$Pp+u{O|NT+09{GhD?waTv(RVfhPy{-m-n2$r?T3rRpnu5xN@T;hUK z6YBZA@iv8v4;$%7^-Bt|GM#>8K4Gn-fUEc<;Z^6|*J3WQGV8OE<%pE{psib%fU*4D z8M;_*NvllTd;{+&MK=`BU8yxV*}QVuLJh~vh_MSa!oEZHKzq}62=%brZlY?gi+}vE zg|r?65$(egQfRRr8`-JLNig#}^|rkEe@k_7;^6cY6S+CA9V)j6v*2+%t_ZNQ1;Hr8y0&Kj298OtR2JFKv;eiSnj%mAMfN)n70$t_Ay@?spO6m^$gvo*?;kg{ z6#>dRR{v;#Xb27_#}^X8_xzlbNW>oE9J*$Vicl&oXtIL1s&;+I0eScDn>MXhwRtV| z`2Y9^>zPbx=FtO%XcZR;j($s*cthKwMhwlSBkpH*u-(KNf=_4^1-FE@zToty!^8C1 zJeNpmG*8O)164ba(n$F+;gE;~rKj1QFacJ*`s0ufzZ39?hNz4}3Ei7VfOn{-5)ZGmAoHmc3mzGm0PQ>Spb1+mXoGx5A@t3a~ z8ol!m_reN1b4P^NFi*58P?#z>lP91TeXq;hSbSS?*%-dm+TSkRK~ai5h641_V#k(c z1E1>?r2w3npgjDmYzCL|L8wQ9uBYN;G4QKfrlO3mkoS}m#se?Psk$Wxxidl=9l2~i z!9dz4vF*8Tr>KV9Y6H|>J@-s5K>b2NNue zW?=-fGV&En*`r&p7Zycij6595Aia8HC~)*TM@v{}O+DTPmohzYZvI@EHPg8;&eed2 zjmCj~(m~Mm$~^bi9(1Mxr&Ii;S>T_9%M8u@?0Bu}0#$RiQW1NCVXve2bk?*E6ap)y zv>z==xo;YWfTtrnWQu^{)^Yuf&hhb2zp^w>RaLCF?;!AH5v{1LCcE>}~tE0}B%1Qq+7steoPG#Nu zw_0#W+kze(T%kecYT~V9{lJGavZy4JC;Hvm>H+_Db;L69ti#qFtcwZb$! zl{3}SO`NTv=MD#i5pkOAwR{}-URB4L(LhVVfr3>rTu@bwKY@@Om%$O~h-2#JUV5Y9 z`71Q(DPkGQwK%BlCiumeS@)5jhit}E5r@A@L};`S*5w*R|cM30=$j9 zAou-j6Bo^-3Q<-APamxE-d^X-QGhsSe5Q(`U=d*beWT%?8$hBq3B-<`FZ~y=U000FxWDUP|Tu5`WfheW- zeikU-5XT9U2ZuLVIA77?g;fZgZkoKzC9O(>+@h6IEX;YCfnD_Ltc&2j7BdILJU~ps zN;mxd=g3+C%mk)wy+85V(Yv>HQjsvin(Sq;i~46)M}!b+w~!rO)=ix^D}T$ zEI)Loyuao1;RhS-%y+-cOBFzVSh+S?26_C#IN*S!C(%{IHb;IM_E}hRGwVM?G-h^&Wr#Mct1m^|n)iUUy4>k5^D% z?XQ(yRF~gMHzjUBr#ze4fmp{BTk@?<@D@(*P^*nhm#&Ug4#yUFAsV+1XiNl%!Zxi_ z6#SF7w=<67cOZ#yJ2yofYk;6{&U2O z2_+geJ$*wqxt&pnWB0jko+ysXfvM^1Se+Q?hA}T-8dCD6}-IQW`sptOVsbXqzOKOvt$F_?kr9!o4t`?4f3p5(19 z%E%e=XN@lj2|st{UfgIut%uYf80=g5GyH9TTxN&@-oG+BLNty!JL-?Vu@W3;wxs{N zc^$cRyWx-&nHmTGpA8to(rcaJhUv7mJIBDiLaH&(Jdh;2gg&id==;&T{ zH%QqYXJu(JzN&NvdlVDI^AJhPC}Ei_YHN{_ugPF^bDGm>r(N${Qt30m|@fn zcBM=O$Vw{a3eduj;((sSTQn{(I_g{-szRSJ^GDzpU9jKj8^(2^&sV^iqB`}<2_!9) zn}|fD%@M%S17I{9Ad^vH*<0?^msz>D%2xc^58OL>{$8TAj6oi6nh#wb-JPa|LCw&) zdQX~N`V(KY1X^Yn=ta@hm%Kg|aoY1*0!!6uj_aqRt3qfxxhEM?%mA z?K=kE;)4H#^65)XQ(cV3jW@#EBAf!Fb=3FexPHCmjk9|lG)p^cIrPMZ`c#p7z2@`Qj2MoTj40nKQbfP?okZyKz&MhEpnVEUN4_;FWu} zu{tI8C*V5^I3P=^K^`irp&NOud;h+RkGp%<#|Nl`s`vWFo}+&mW%&9EW3Vj#A{oqc zOVHVEue?rV>;<&6upQQsvV_kngPdC2KCqH=+bUHEvx{o`hEX_GsAn3cj;*9a5^lC> z1qK^(TRzhjM@V-cTgPehm;=M4bLPYb89g%hSl3&UwRp`ipeoesaWxjEDfz*XS`}dG zm%L9~f&Kfdi{k6lJ^}0^SPeQ{Wd!QddEE+SuZnmgn+~f# zeoP7phPzP)aYJltDoXc_3FL;=6ZyyFGt@n%Zn03<8^MFvGL8kTfPQ3yg5jY9m+PTD zucaimds`|QG7^Zx!_+N#2fqwI?Xl84GBmn-K$Sxj>Ps(=Ozd$94yk9d-69as*Q7nNUX=`;9~l4u z0|5;4LldxaA>FfIIvp~RL8;mob?K;`5utP4GnEs-%oYp?BC`5)AI5+bt>3n);4*{3 z_iny;k?2Is-Vlq88$;}lB*#M7Ir8)pP{tUQSvsr{(>W5(M#*Ar+T+<*JKZ3M!=VnT z7)n7J%%1yY5a!#iHl|X%zi&R!=3nGYl~(EX7Tcqrn$|?`HzdMzKs*C|+Qe{^OC+Y0 zHA7hICc+ol_3<`IFOg?-txJ(V_P$6oMONZa@vlAl7s3i5cK*wwkff2yvaFOrvDP$-AK`-K@Z4^ELWZg2%A z>h@NUkDRkr4eG`r=OIW+v44@3=8V;zeuI?YQW7V4#7A;J`pl42vz8gR40DoEQ%m*e~Gc(jYUJv)%7^WTQknD zfw>=GzQrRBO06HUnN>xDytqr$3r%nNs{>m42TfS5RgCr4U~l}tNZq%i$Nfl~7iR}Q zH99f%+Q)ZwYkyH1k2?)@miXGZe52go?X600+1|uO~c3w#lpYR@O-XC3&#ffsl zUV-ITm5G%GZ=j7*K~A-?R-CO@tbj?abMU`=_FHnb{<4XbWJ^?5=U6y{sfsg$p1wku zVrgM_4!WvrrhN{WorwY;`V8D@tFm*Rmvw9y#)3-`7@n;#4k zEKF-*_Lw1_H7h(1E@7*2L8!+AgVu&=PQxq^2kus!Rn|e;cq|o0y^p05*~~10?$0wR zr!>eZ@TTS&ONax4Aj?)DEi}HeiCm8EF1PqD(c$51luj z@W!bu4YzWnt*x4QVYs6y3k2D@ zkmL~j)U7l9P$){H%0Bp~%t!D)-AW-IG%#hgtB?7sWe;>Nw^dxID!G60e>c(YBpZPW z5ug;(*4sk`Qhemh&`(1p$F~s3x178oxvob?^`8X*SV+Mbw>ABUYe+&5^-Y7wN*aFa ztA@51*ONR2X@TjHGQl+7q|@HsXvK@<`0V6ALmyv~1OSEBl|qp>+$YMwL%CkmGm z!NE`;PkpffybanQ000Tr1d_{bS_+P+7cex80{YHKL22hf^HGhl{jrgL1`(|-$!kq7CC3kL*5g#B*19xrnLM$Vx{M4k2>#~GD zx!^CT5qv|J%^8#B>N|^Zs0qLl38u>J@(VJ&{2v-pL_ODlXLb(^vpmZaJYIjuO6gTgcoU zki*6aWZfbHi@X{D)6h}&X&2TPcZ>Y~+a&|E{_SQ!_l^i9w#;krC90j!R9{b4qu+-w zWI<40)jP6>!~h{F%8HY!u_WfeKn^k^$csn@&!{Q*8iPP^18kcD@2N|#Eu-QYL_fAo zi?kFBL%|In(BBvPU?I~M@InFZrsjeW5JS}aN%diTQsVc#at6C$I;wleEuk_Cr1op_ zc1_m3F{cLo{bZhb9lz+_!NOz#is8IG!2bF@{%KUiV!nCsoD=n_xNXmtf0i1$q0VGLe`Lm^_Go#ZgZmDKY(AI305mU&zFmSUy`G>&dNzExHYWI zm&s~EA0g)t@$HZ7cVdiMX?%9e{ui-0{{R8 zt}Jphlo=SF?H6YqUuwU%|MGTeo5#E&9Ra)gU-%B1l(IE_qd}wACnzbM6&-h4HEunn zVR{w{E@*7<)OlXJ%@=){hthKGwzyAuHQs&A${z&OsBl&m!B@)iw{P46*}Y<79V#|9 z`hJAcP6G0j*_TV2!+}ujM<6w7jpHg~U9RT8;WU++saI9Br5(t#k^!1fTzc{7aU}>5 z>+cG4ld#tBV_C>2`f-z(O3?>Cp9~^wIEKLe4b$q%E(j|5E54CFPHpt53y3_1c!AYn zL#9=b2QDtISwlKF<;KbhnakjOC567TG!xrSY-XSnthS=%DSJ9!Jq(~O>5;+J$%2Ir zuf<}%Vn1rOU#YzhiZ$=aeP6az3HDQJ^U}0DyYq*YnHp&0=kLB2td_)4HKv~qCL2Rx zsr9+CZjAaLgH{g15E=r^9{O^f7~txBk8BxHLSz4fH0PW+xSWQ12EKXjZINM5t%!4d ztGOmo|^PR!d zE2B%CqInOo9_#TCNm+uH%Z3!=Br<&Y85JeKR9`IANO_HB>mAYhyu48#!kexOUR&y& zFP$XJ8nzFU#G>g85jdCtP=C&}Rqt157q>=R;mjbYA#yIw#1l4&d(mkmh9-Jb=PjV+ z!29Kt(Mlypy^!@`4fjqeQjTdWlI|o$aE`5&TJI)Uo4a%>rGegQgt|D-7SEakxa|`w zzLv1WRLRWfVwmqM566%txhZKK_HOxCRo&=!Qz+-Bk!6Bmok z4Ov8?T!y!!hzf&W?vPl8y+)$arLmgDOmHkpxHoJN2xIZz(Oa)Ffvk#+6Sm(i16_=~ zAe{Jf{|6`lK`KJ!*xjBC9q**7W~_$HRNxWBu9MPhNnFboR~gULxy=Yh#U>q}^5QJu0leF%v-DJKZrvn&e1L{#_i-BtdF!QYqf*>ff zQ`FqejhBN8!8T#NU5Xb`w|K6rYNEu4>rUvNzn-t0nT6uGA)i^zF%3?I&9A}<4&{5m z)11=Ae`9|>ytgMvRj^{MyntD!M?AlpWT4qSI_T-GZs>*p9BC4F$c$X(X;ss?f4LPR zriuDp^9~jj`?nOl$Tsi_g30?j-{;yrpbD4>(VW|m+H}?Hth{VZc3$K7VcN!UY%35A zl2RTK#IMX0`DJ^%cHh!r5`If-n`Wyy9iV?qpgl}3hW^qXNd$3@A>{6R)`C;F-U`L1 zYhVjs3?ek**jXVGg799lG_ns*&(+^H0azXkb*;R% z!XwA?SgG^0Gvu#8%YX!GtB33J`!+4;NG=DtR2}wjov027FBB*>2)ajP_{VIFXV{_!v*fA z0*zwZaVa3VKx&B72VINf03XIN;!m;BA+%@RcVP>Zk#C`?HERA&_!fpr1GI1oJ!=1( z7x_P>>gsfYA~r$w3JC8e<16371MflN3mYX(2WU&x?zU=|yVcEDZPO7We4a>f){SpGdfiMS@NfKzCpuVi~iy*~&;ZD2)>mf?*8Cp~=-Jt!;355DT_b?g&00RI30{|7bv&j6S zj&?!tUcXLbI|P#Gcv4CHRc}zh0b<~IP}vOY0%PiH{XxzubNO?^ z+kaBLEN|(Bp!Z!FxH!KmmdvJh2Uj-e_anC8S{#@Hh~E{>6m70w%%@ z;PybQry8073Bt>*U;^w+LcQb#XaE2M004~hoW>%6|AzXALS|7g$vY9GqL2riB^_Dr zfG!%F*0;4Fqndk3vsd%_t!gN3kcS#T z-011_LDLR(0a&Q=EwiDfY%KAY&Cpp}<+lfynHSe@6b4Af`}bnd6Tr@vx<^6J@&q2K zq}7Zs|58N6AD|KqIOn%lRl8BLqa48vq#|rb>NrBHZox75GTW@c2B2E#!JQljTB6Tj zuksCmaX8w7^3H8KIbYDkE3dtF-JmZKAFe*owDh|uqO~=G7}8ay79nU^%aysqyWIR| ziWNl}=xaY0sDRGr2+pkb?&NIcF%ZjQLlr#SQE#)r`>pKy$TVe_u52YKEQ_h7WEdI6)4q)k0WfPP2m^FQA)dx6&3tG+g zUq!2!l<>*1<^P-X)EbX_9rSnGCviwbTc_FxQJWrbFKF6T%62`)Adl*(9=5@nrD~9U zxN?D5I)TfNut9{JBSWqM8|NJVxOG8EwV^pFnH?ZPl=jE|6}->y`@&PRtb!ZtSbSh- zcf2qAvuE^XAwDSGDQ}F>bB%=+RMdFGU;s@SRQr#Q+Z4%|U?q9k?IuIxrZN zb1~vMHT4kt{dwfrllwat#8+^7;#C-2Uz*?bOoXU{RJYL=N+S5K%%CC`3Lia@`Y%n+ zF-@4M_wzfnM^^Qt@!97kg@lb2j}Hnu*(sQRX-RdE70WPiCS*Bwzepw~L7elJVsaGNO?+vCvbK-e3g_s}(_ zPZOy+tq7e$EsLQfnxN{7Z$b0_`g9b+d7C&J7SfMi{I*+(`|i4==9kx~g;7$*Pb}tB zsc>e}|1V7&*HOb*3c&s3?bOt%tqKCq0W*l5Ir@brFo#n}HD?ptakPzrg_VH-;UbDL zqD7zjsx@gP6S!?8bbJwEhcmza)9!|rW(TI-jdYrXxkXy=dFR8x`5Sqa=m3jCZ#}C^ zz1KeD;&*L)MP;mF+LGggbY`}+mhh4$Sj(8a*q;W9RJRLtM)RFn0oMs z+s?K9hqsQBu*~6~MP_zr5gx{Yvte@jv-P-JMEibQQ1k(6vefA7AEWj|iK@u5n&c%7 z0%_2vj0py(y&w^l=#xh`SyOXa;h4iR9j01%`ptt2? z3eP?T?y4%Y_}Jrq=s-Ps6#l=fC@@LE;>bcAG=J+Sc8|-}ZYng428-d2OK!a=z~@yd zF>C%RXYke$?R1UQB;3Z31@|AE6a6XqFY$ZnHO=#uqprH00$Y8p+<`UW;!IOv2%(U* zO2Rm#)^idTbekjLvoRElfcwYP1mmvn|1gk@Pm|);c5$?#+Q^loai)P+d_H>w&jL000T8WSiNLWFCMra1pP(o@0$s z205ML!JIP}FUAJyn*O@=LWLidGBzEqmYT|J@`Aw3CgYRN%Xti1xK& zt1DG3MydzJFo5!)aA_?3cR&Vmf6nK)>^T4a_IEHKSb4t=Up#TVim#VXC= zb1Q63J%L2sDB__;{2wSK6HcsTaIio3_Qa}!GNa@Ea7du&z zL#lS4k`E2G6BQ3Uc6q=RPzgdiwhMtshC#|%L#H?M`~%>j&aS3KUY4cghye480tc2w zA4yNAtb36N+s>R1jC;{sN$o>xw09A|yu?Pwz~$PdpezU-umEpBkiVIB-7JiKH(+M) zulT2-nXiSN8#YmeO3}V_TO?GTIk56M5>BuSS_54nVpH&zeXjgYsc!-vpBgjK&u#a! z+G5o=q~lUJ>+uo=;ZxUyx0N=ohCBZ_)<$z)$`4`SlUG`%F_L9|}5yH`LZ zRD;=bk(0KQjj;u;`b2cW5%;_ClI$^a9vx<(kcreGLv}%}gr8`RquvJVvEXf0-+O`q zZ#$_}h53(uvnp}0e)KK8Ryl`S<>7scJOkz4PzC0B2XgD4Ks+F-$@I6nY_J{vPEdd| z`SaOGyYvG{6@uI!0V1)#=g$V*fzKZBaAb2mDaV48U5?K%#N)9q?Ac@5*Z0+AeFO7< z!DHuQB;PjS?ACL*hR5Nn%OYy&F}x8-e!osYXwN#mwvGPf1Eis9PR%N>tl3xS*=%R| z%<|mXu}!!r0!SPB;joEQzUR)Fw>~rt9A-5!x~f@W*9s8p$9B=#DV_zfq^@w`BG=mEoKosLw< zUW=l|sCrPAyC-$XZ{&YlplED1sox}RF^<4UFT$DKKKR36Qu@JefjJP*<&u)F^4 z6dBcptsBPP_48#R>_0ZO8YPSlmRA@{(f?7%JVz7^!>a8VjD~IzhZ(Qo4zR~@7%^p) z{wNRwTQ)R6%eZ7{QT(D5Y8LIC#-Z4UZJHd)TYcyQihWXUoS-8=p&R>RA^Qo^R%PH6 zV3c&WE)X_4B^Jb$fAS?)D>_l&Ku(%hR5(EgjU6CGzGAjec7=voT}VC;@0l&X-!nVK ze=U;D-iI=gbks0s<|Z`HeLcnZX$%3WHZB);pGIqng_cQM=iw@|%&H3JnQv!R#34+H zJ#bJ_jw=&KWFCpX)~7YK26&N6L9||iQ#R18n8e(WoBvmuPi;?v1X!6IH({LN6X?{VBRoQ`+Puy3Ls0bSd_=O*-r1izX(q$o zbiTRmr{rC#0~V3!F3P?1KQ7?d3^F3I%t%}y3>=bKX+Q-8!ScS@U4&n)Twl-~?RfBl z%c9_2vLdEPn8P9f%`Tfb@sLwJ3xxP`C3d_4*c$n6@)988CT1+KGmz;jTrG@T?^ z#e&quL;b)LLVktLTJb-{%#@z*{BFHUwIk_zW+9TNg#{{|1!g;?r^V8h zdToRzLl=%g!{jFtwyBbJ!jx?j-+EW|AWSPa=od+vOo-q0>p7_Pa=3}HAscde1Cwlz zBJDhZ>XIe%eDAU$D0Av*j@Am6^WCqw;g$&jC`1PO%igg2 zu1l_a$LPEEXxdGK{hUoSaMEaEhl97fECv~@=0>m17|M%$tjIk`O;m(xt2*{3eHu6@ zswRH&8moq6&%8eQCdq|u>dq36J-hbz?l0_mEfRT$QgDNYkalFROy@9O<=Q8 z0009300RI&u9$T*eyFM?gNTM2Z#Qp5`Bw)~0mn)3>6c5^3pj3123XkP_>9Zx9dGzB%7{2miX z)xPw=gS-w`O)tb=L4Qj(z>Y|Hm59a7%1O*(Mhll!mCk@Jr7jVC+5}EY4i%dmq44SpIwI>CnDZZbWLk)da z38fe`-58D{1wO1D*pt;D+Ci1Dnb;EaO*%kK00VQ87sDB9P_Is*Ho_eHw$7z8@<%!1 z1x$bd00RIFoo7By)?u|s`m#8rE%X?<+ePCxaJ9P`4-T=sl+`RG>m8o_40Fas@NjiE zYo?z-a6In&J;Pq>BjE|%9Ld8S9G+Ix5@%H-New8mYo(sAVQxNm)yHx3F_Gb$dkWcg zj4HYJFo|;mp>`;SEc%cAiUF7OfQItgZ%y7tUF3!onq`NUPW+iZf1ka>0eZ=AnGa?- zA0Sn8)|EW4gm8l$#z-S&5A}9N6kb7XlpZuDC?9FC45f1P7ryf9+HZhCSee;aeT#}? zUrN&On~1$|LXdZ@WNYf!bwTCbL#~~K_vQ2QEbJ$wo?8GEZLBSqTp*JlGMadax5$f3 zqsu4FKWw@X$xqu1PH*g7YRu{WiaEB!9zr%87AH-wmNSx)!b{@tyOlI?!Z=0_Cj+A3W@_y zIe(O*+MPb#EPsUy@sdzZ^pA$Rg0N&*!mgOlI@f)+&6*B8i~QNIA#%-ZC$`o5j46d7 z!Qo^;6mU`s;YQ3Cq)F7>C-m+zdHZ|GL;N#R9l%E5^32w5Kd0r_b+IW*)QYwd@1)s` z(XhV5Th*w;tujb`p9N?>hU@7eVz|_?vQn}Olm^3_p`it-aAUCYEVLDhE%clW!uaKu zThpv7DT{ntP{NwM%#4t{T6$+-I8}bNRevN5(SM}=nzn`joWB|HzoTokuPbD#}j2H*3 z7seQp@4k~nf$=ui@zq5ClfMl_^FIp56kl$hF8kxeeR!;zOWX8)DqsIVJ`iVT@iW># zTY^uPmNRrDA{u<~e-ogNZZ^$h4?pDTJPRnrMi*#PXvC&c2F$UJxSE<1&d81FT!3Aq zTgCJWuwoJJKlj0FKm_qp!00=ap^gyi2BYzO$BJN{mxIuiw{y1${-GJB)cK#6hSxNq zXT`H`>>zXpMob<;h{~J0qkZl?sT&_!)z??s z=x$OkLZCQ&X~BZZkJRvoSy5G0#>%~k*rjJ6)BC_4RtYM@$664_VuAZyXWs07x`47e z&-mtiv&;fM{LQh&F&~m2;Axfq9%LP94v!R0Nn+EC$M1z)Y>luDL3J2AUb`i}g}CM~ zDoN!TI==G#IswY#USPELy{Z;;+G1>eTuybZnhIMgS0@B=Z;mt%Om@x zKPrZJrT@}BfC{&*7=Xf!O%?zf@3}!c9~YLjZ9m2C2*(vtMv%RLS@uQ#=tER}6yB&y zQbdb@lwstd74YYj^$DQ1abf6-yfK<@)Zbb8(?aEJx{0fZn+G8UWL(cmRMSekoAJW2 zOS@^VIG6amEs&@yf?IqoiHx=UVWqfx<8-vP(k?LIaxAI*LbEA0kCrVfe&I>Tt|yl* zQ7=cZQ7JoMnG9Jw86!-ZFXAsJ=?;UPj03jeAh-SJ4sd&5^hBplpu0sP^{jKonYwQr zKBPK-kSCrm)y(E%Jk9ueoo8R3hwM(D4b)ren0d4T=l}o%1IfwEMe0OmL|5FKQm>1D zjQ2^#Rhn)i1piaz8z28VOT+L)8j!5~@TTeaNz*X2L36eFiaVTcnszluHSL7L;e~r{;x>c)(rn-0xLecI%=F#CPHB&9q$8>lkvbi1YcwT^P_YD*> z&&QQZ$++2gM}KMdW~bxt=ainR@TcwX{|eWOS=@F{_8GetHS~BaXgKECCc;+-||K}1)s;a z!MdfmuMDj7`CQYMpe97d$VV-Ol~>i=q0l-+cD zbZrCC-Z^dX`-B96Tgy2yU(Lle3qNouvCVv~a!kV`1_>H2Pxn@}YNpbqL52MMR4K5& z0c-R#xyEM0R57Xf-1~-n&$vXj`M1ovkTc8~m>RoCh2GJ`m^B`pB;foCCE@AMnEs}8 zA;~B&`+6AsFQgkl2W~vhn78p|vHwkj0rx1GQ8rRDOs`n4RX0ljLc3PD)tkGknG710C4%MK(& zw`y!=$(Q+5Qw{Rk1|{IEgG=>v7TOt21W?!T&0h}}ZLby(w!2B2gt8Rga+|4oSTFZ1 zZ%SOU5JCLSUP*oM!Bo9Id`SGm-}*RKiMLK?2F_AZierAgMbURzg=L#P)pZmTK8SX| zIJ+yxI9v#`CzG(NEePk_(?(`G_}WyiVQbq^6xm!M(Pm>bbl%DNiF=!7SA_hnO7=g+B0Fg3rosjWYJ~YQ%x-_V@6Q_qZq!(ZUJHl- z=vEffSxR4NP-3#*-H{o&#h$dfND6t#nG*id z=53}T!H9GF5N#UwUK>@EOdMESa=(f#uo4x;qrP>J84QCqlY9AlR@Ly%%%Pa@SdUTC zB!O$T*attbX`vQ3?gRZBIe}{(sx&b&eSB0B&Wm!YGUtnvG3h<--#EI6-@{cWT9IeA zX=4gmWu{B+mB4GY5gNle5pSplZo%kJq5Y5l0cj(t@^z?!6ZmRXpuu?SXYe|vfZ`0) zg2Wc&6|>7eknYKkmnlgUBt*P3L(797_=c)RZC?~{i66~D^B;6DD7kQ#(%VKk-?ThX zYE*WlJzm$QNR0*6)u4)R{kUeg;KTwrIcr-Stc%}Ao>H$<^2`w?6B))_j#yjUj{CO= z-{sss5klM$2~dK<>%EX(5togOpyG9nvKDDWslrDd-M2<^i z|5G37lfVN0J=yfgk;e@LMw6{*Im9;(7IsJIcqTV#yb;yh$2F}%T1iIF>>ZlXOP1Y3 zxFSheGR^phY}?xk;yqSD3OIrA+`(x|F9*HqEiJzkoQ57}t>ugk653vYVzp?3A3Bc!%cXoBUgo8m1FL!z+49Xn}<66$XRUa zcMej&=;`hU@V&agcVN(`qU$ z-S@Kqb5O@$cZNdFejiwmt#XXQA-SU|AnJnN|6r2GOX3$S5BA{KjO?b{)}9rdx5-+L zV##8`ds%AME2nbRAaKvr9y}wJ22s5{en?FCviB1^3lQ!?aH01cP;`9ZMUc>dAdwwx zyW6QdKs$xmGtYIR6&B#FXq(7AqKRgFw`&$StH&zoUt)7yf{~tc0sXe;S193 zo7P=T7K>LG?`>+Rv*kUb9${g>J5C(hD*oeFgp>)RsR%LrD44&{A4gTX4sajUOpT7B zp6aQx9)$D^Br|(*pSCk2^;q=60yUG~m2Plrpp5Xu4RDH@>y1ZSLUGO{&1nS0f6qVi zIbCL3L3ChkE%bQ_0@*2ko4#UETSpL-xE7r?+~tWv!g0hFFwX%il(#PUS33RmLx4oa zB%|VvtNNl>_4aB}g#sHD;>bmQS|<2PnGkaUd7g)5hOzHP@|6-m7N}$|V6Z=Sy}yye z&7>6_WI_k;wn)F0+gvZZS*wB84^(^K2wOwQdg{AwEALu{vJ%)IoRb9B%0YoO7s~rA zJf9B+0n5uVRFW(q_&HZU?iS+Jl6Lg!4R?+<%3iG>E@dKMGo(kNWTfp{V1h#WFW;(a zk@Fh}&s7Vc@UI_tEl+J@)8gt2fw~pc_(O;J0i2u>?xZ66)m|}lG3IK(+>mx~r>tYJ z2RU$N$;F5sFTWC)G=-CJ`WFDmCo%Mp&!s9D({Fio(J%yB0ZVqJmR+889YOq1_H-u6 ze!4r(wk7tOgPmM$r>v5B6M_slyWPBIRV2i{5^cb*GYwWK+Yi;_v6~2U$sx9HtgPi% zGIonad~_|+Ced7|id-z}%bT{QZs=K76$|^fIr=iBhu{rxfEU{VORM&pu*uuL@-}WN zL}!2`5zty~>JnFD5n12$e;#Y;53IRa>k;raSHE)V-b$cW#Euas_xXlq3vG|>S>B|? zcm*G1NM)FC!QK+l96Dz>D?BbH#&#G-8#>V^bKjBHRj z+HG?!2>0{@+HtNoO*Anpz4tA`^!{RycO>ib2Szs+k$BU8nqJ+ z0osBx+lE`a`Hyfef;bHz^(niGt{NCA6U9b?$5rq6hL_mmmwD%>4GzZYpg?{RUg9+vDz6)ynU4Zo^e(Y`?rgK#;1m;3*N?) z51dD1#_!yOfebp9ivO}R0^Tl7#-6qIyV}lu_iNj!12%Sa?G}EL)@1>o(BM`R1VV@) zJda)R>@L->)Y5lWmU2D=1jRgWpJ?hp0F=}5Ny ziI->3tC27`e=r?40Vtco$HULtPE+R5sufcD{0-REy>Zt0fFS`c-TY;ua$=L_nqB zoN_~UYN0!b>2>0+FlZ!!>=96I|Lj?Gmtb??P1fEaRjK*jFZCv01RvYyBXDsdtsW(N z#9T(-wV{9+6?yJy)5V^S80Nh3(aj}_Gx_@6m`-3?&?wb3EPe>NhuQ8|H6o$NP`EzN9fabw`_i7EqFSW< zr{j6GVs!Y!z4H{Zv%m(8@JXT+nN`6dZ46gZ{LTj}V;UOW!ZYTNKn;>55u&|r7$fRb zh@}z9f}t#pcCB1>fk16E?GVa6@5f6zCF zxTf(BQv(@)NAo8q0Cw0e@)p8CTDc!QA9z`N6=>fkG_MY?5=B6$?rVWSr=cUO!f`s! zQblnnLsR_59uYf=D?j>tbBNlmRRWm7BQZK0J^YijG*-jQL!cX^9JFmfIdx$Rfk2SW z$#=zQXdu*o8=@4D@p%(u`%D2rU53{Y4j`{vaHvyc{O?@9YugW;pyobZMh$OgrC)dp z;KcOtbFnm`tPuNSiuV#&`enB1L09!IKW?8Dka+zNx5d7%Y+my_i`S|&dh!VRmS&=C z3ofp_%Au!1O}Zh6)1Tbct?A*-y^Th?`GtkP6lG`W={uD<9@5pxAAdc%2!$YSGm3;- zm#wgezZYZx8o@3n3sRkTI87BBwdw57OI$A$gXr@N%wnwAty+l@uxd5X0i+@udJ zV@@`<8d^HF>>V5dKfY;@gTJ11)ZqJ0dkDZo@HHQL@hSly)z5#$XvVF&IoF{kp`*epJ@5SDYt+!yqEv*#lmyN z>UYgir!^z>oCkEV;N{jVF63=G7t^Owwu(n{v(>!Y9a?bB#=vt@2KZ#IWz{|wTIr{^ z*#z9W%pH)Lh=Wb&?W2!vS3Mo#{ZIaR3;f@Yh#o#Ib*#InA_ z`X%ZPnXn#@V7dm2doA;qtoqSuAdN4OE_RNTJ=eD=;ka_O_)_joFVrz=)k)TZq%H}U z^hsX;;BshSqtO5>=x)Wdy5o5rhh6OcT90umXleO|u&6q9qB5_`^M;9ZhaeE|Hqj7< zydt{}4c5&qrElfYQO)%h%vvnVi@Z0&hNx=G1w}(uk@_EJE&BooK$qamUxT4*GYRus zDK|TjmjWYEha|xmG-~t-T9pz_Oji{>656;1oQru^t~PCTw+Ho=OIp({I>cZH?JOn> zUnzY1f?=VZ;qFKvxeP33k|kvcGkeLu2JFWRR z_F}?rjyls$^@y=fw#^k9D;Z&RR(z-*bpUzmXc$H$D~%SYt%1Y2n<9tB&lm2w&=*p2 z-LVO?W4~92?R8;8K*x@%mjY2%*Ug&7{et^HL`w2SiJG4 z&y@Y_jEzvO%b&&D7eQP@%RvYLKWeVt^n(ek`#pce0009300u^=;AOUkjjo!{ZA8vi zhWgy7Rf(ZPINrz_@gQ=fWvD(& zOQraNN6XLPhH)wGU5I$i$m|D%)@E|P1S=igRBTt!7p>igBux{4kM_tF%)27`{psu` zyALNXy%!bvrkkxC|K1Z6l+x|eyBnSVM6ejk;BlmTC(KqRK8E3>X5?4Dbw+hqW6qm? zQgJp~-&C7X8Zad%=b~5#37oqdhh1y6;@)h9M7m;o2J^Z zb9CrANFAzn-rg%I3G!lT2yllvBxhv_zaOUvk^P|`)z%hYN_TPTaW?6i5%*JKnZ#Q6 zeb_{23P)aWAkhVUm4>9HrzEvu1+S;idUnyVJ*lUmGpY!MH1g5znGgQVEO0#kc5e|g zASjw7366JsBU~gig&X=Z3R1S2{SSWde@2@u%RrP1G7}v_A0Dcv7l+Ix5UHiWT1x*t z+SU5cr!)0JcZ{Z5CM1xCG!wD4i?zsgyyu4^2f+@T)9!W>^C)LYsgRp7nZ~M#iF)3) zs$%|tKgy6q6erM%TjUH>3ycuXyK(@~i6C)GdQoLy?7O@kP8Qry;dqt0u@+1*y+zuU#AKcnqH@tAhE9Lj;VEx!7Dbd9pYTeQFv^I&?Mkeju7Hh$gA)hp&_zu%(rk!$N&H=6n~w zMEbo5H5SH>uW|7Lor+EM`;NAEmwY8z(k-JLCK zo8V`B8wdHl^M+NKK1`Q`GBOU;hiDMmh~kSbmkquH_9m5KTJn_S+v|50QxZ)96dFZ? zqmU?j+J=`hF9o$)aCnxP4Pdssn_!2fV$B{|Ri7gc74o(3m#&2kOgW-SS{m1u^hp;3 z_uFq!bF6I+WUL*7j4kPIPEH4LXylAdXhYazjtHM`>^k=9WrKsOe$;1bf7!uhvpY#` z!ll*V73!AY)wm}IT~ZL0&9pMB^i<&MQGnS7NRz#a+`K-w7{h`#9_C80QB`?wsG6A3uA~hm_w(MmBs!Ozhu!iBDNBpj#`Do zo?~7hu|6YB*gakTk4CGu?USM(=}gi-9!YhsS=^KTzxT-*uZ70i2B()CC{ICSDAVm5 z9x&d_%3Df%3YhQXE)RU30@9 z^vBGcRM0yfJLkUOwSS+Io`!h&NUwue+O06D77%NREL%Dr8IO`E+- zdS8HHL9W7d?I9TVYrh*3s?uQ9lYpNM`h!}P2un^jfnF{yH`a9(5@b987o8)33pb|- z9+deI7T&4z|Dmnjw5r`;1k>hzUahO$G5{5y*VfVinC!5y824;UV(Afza*|rZf`6#1 z$HEHryMu*J&{0FWZ6(9lXRkAn3S%Rtm zb`dn+HdWkXxag>Ip7Mt6d-t4=`Yo@n2qB$O>0;NyLh`&V6$5vk>F+LsYdt9e4@RkiGql<-bh3WV?~pn3tpMFg*{2;=`)%Fp z?DCOr-E19H@j2lWyde+pq7@a}`2Y*Tgi%bVPMUK-ieuP+R!|Yxsmo=LDUI5w3?ujl z{nQh4vs=Q?d*O663y>2w>-((Djr+vQ@YIB#PVq6`7tfU-iQ-8m!2VdN$JKX z^#Kynh+a$-sgdlPZ_SWVJ|@6k_h$!^Rc*>{t&hL^K)tP$My{7LG~QpxGV)siVGZA; zr2aRS9u2SVDtu(^L1DMiwh$uBdt8E|MoNUPGPSNeXmP^OTu4*2C8-Klf5nH@RV=XW z3X8qmN~rPr6i&dA0pqv^SUy2IWy#l}W9aLYpMyH#7~T<<+w%({Zq>QPQNHuG0; zjRxH#sM`EYIRkhI)tBXW|3{2G2uDYLSiN(wZ% zc3y>%^d+p7yW_#HV*_l_H=!31VDn*4^Oip1`zsp+)*KW#*twU;fP$P9{gmDwI?UB?z!vcFqVxL5G%kZVk1yMI;a&dJ1@_V?oTC!AFcsI_?%#ZZlREQ z9QH+WB`Q<(O9Me9jYa-NIHJfoDI}Nf5KOflVT2?^BRYpcbXotU@RMh`ihm@poftI2 zK=Ck5N@AK~@VQkH@YDeo&eI`!tE#aIp^>>xA>YeDR%4= zPFz2RXFC+cKOhR=@g;*ryEzl_>HeNN0bu#~-Ol=r7E~UdF^Evd(%r866U-7+((W5r zk%-i9)cMDIyYSFDhi+yc*+%B`76SKtut9+m4-GSR9zVjB(&Fsnkz0}d9745_oY2lT zW#w}CSlJsz2nhX~jvCbzXwnJD;K%+l=Dy6W&|el)s-fHo0P%Wm9eAt$1Dsw}sh|r= z`!x|!@{rNTn|Q!Xb%J|QgOWUjeTZG;1V8aoPemsxNv-TWJjMm@PmGsS0f9@rAojaf zVuP=Tg*O{4`q-`Zr&Mi-F^U&rrauWJ)zaCp3+klQDuQoburH)6NyR?i=YBANf+~{j zT4XWZcnFJjSiFqxg)URWjPk2jp91nb^6FaC(Id%kxQR`J$ZBNlww9ZS2Yh6{Ndc(M z263CLjf3cvhuxdOh|`+rL4p%7`Yp#H4|F8N4WKv{^c;5ZaKU~wsjBG0yEn*9TN=FF z_E7Dyzpze8JO)+hK`hql>H|yURn=%}Qm?r=>9X$S z88$K6!~E_?{1u~jl0&g+(KfeyzcXO!!LMy>1|@Q$)CT%AZh=f>a{IS4f!!74D7dn_ z&^Cr)vk0mWLj{IA56QJuDmacB`U9GRp+0|YvXz9~1;MBQ00RIOeTi#P*|kr!R>NAp z2npNj@;#|g-xq~007n}Z6P`n<&IA-BMtBNc+XF$$Mr&MjcpZ#ro4===r)SajvY489 z&=LGzIs%FDK7~nOcl&z6GWN^3{wu_n$L9Y{ZZvX%CPi6)&0n^HenT2UcBl54O^k3r zHlRfKW)y1tH6uHASqYE?^7yyDR%t=rlGxT7sacCyRoPu$>4pGGnvikK=J?o6hk!~> zwK^kaJPe&UO!;FwP483pxxPE|F3|U0-^DL_zDJB05m7+$_qr30-3xQ9(jV@&(?8va z2|`8v&PNf2cK8eZXx3fD((Hp+ymU)74NpYra^aiXDNOMn1lO94Q6qn$5$#on111Y4 z7C~rwSH@1)9@up<;~s7>*?Nib6=@?MnDsoMmIu96*~iq%QyEY5-}j!hEU=Q8UFvj$ zs)O~16qs3%fdkl+PvQx58dcxlDnGV<%l}m7wViE&VIdzN{CU|5rmZYWm%luT%lx0-7D+}j7*@XgG5iE#As81GrkS_&{ea~!~19uB=NZpmdi1JD9;h*UHE1^P&rFi>$D63*oXCud7l=Sk>^MzBM+iB{yG=+Sh%lN)4B^5nW6e2^(SV#;U__dhdcg zyjEyr#UJ#$T9c3NHhw}zyi$ydPzZZ#=i-zXv!68Z9-1?6St&<^aG=hX%!U-;k0z^%m6LSFwPC|%UUKZ_!Si|!nDq)W;DxePIb!Hrp1 z-@)-rk7@SLi3%JzMhYp}f-&e2{ev$~XE*uMTngO2P2qMSc?m;Ju-+CqGcf=sa$sqA z;{A1z4o1X?>5>lKI9B7U>4Qxuh3c{Q3b$R8J$NZc7()I=8?tL&J{+rJGU@A7!Mn+z&QtjCVUC-!w%o+cahLSWW26v7>_B#DM{hi$MSE0i&WDNp4{1RxN- zg`9~iF@YM_-MxMU3;a8BqcA@S2-YlAi^zeSz9Aj_)NGQ4`%27|DR{hMi3N9OV82-k-=iG|i%6P9A zcc14Vcy@+L!eLp-7VNUNvCxUxc0tiDgHNZ#s6l-^eTvYDo7MKDxO^S%CGfR~bs3B= zNWPwI5%TjQk%C9#@lNu7IWoJg;ieRPb&8yf8kLF{r38o7KD}jA=ilN;M8NrOJ+z|_#a1ohQ?%r?F}f2U$H!1qC;=#rzU9? zeoA_4PEtGg9H_naw~(7;R$1kLX;MSsd3P@PYpsU5!DM`*<29tq#rhm@eN920jgjBUuopWI`h4QBzY9Q#6rc~wjzg%qT}Z-{6*l`_ z=$)YPIp;2v9}y-dF}wvdu>RlqREGXnj6A(y;##P9SQ3c9Kp4HfSPsN`vwQ%`xKC%f zT37TF+I6{HcF;B#gikb17P9P(id;utyMP1jUGM)U;K@CJ0009300RJ>GQfwEqn%&Q zL?d3?gwHD&BG+V5Z(?o}eQgsCbCe4WUvjE3`6Ukg*S<%dvwEDH6N<}Oi+-_)_J|0; zDZn8cq~kj*U_sKPL!kZ%q%1c}6#_RYeUOLCAyRNYlu0|<$C7EQYF1Scc^Q}ff+YV0 z@^o|ea*tAE{PdhF>e!=FSk1(up4Qn65HNh`4PV3;r6q*8&p^RdEwE5uooHE~IEEHS z{u)PL`6?AGM!}T8Wj)CG$&6hU@-pEW7piW#sW8v5W`-+ezjx}g?F12|u-oz8tu;FP z#}=UdrUetzIz&4sTkDr28vSjsnvrCuv4(&F9@kMoK-F31HH*=xqBsEYwk~&9r9K}2%C2?T^Y_@S{ero>fP6J7d z&vMEktmHv3cz3|=UYu>9_jTC4Luuw6{27D1-B3g#lB0h)7bdUm^L9!$SVOEG73~8Q02my3Vv=4&M(g*S-GXtsI!H4HeT09E2*V zwQ&zM0FTGdx zh(_VM?Cn2ln#6qmW8N?(R-9!|?vR3w@-Mod-3wK}Nq#Tp)f&;V7Wbt)pROG1F9YS; zYI2z7Il#szln%-2G#Z3iVfL9t6VHZ3P6zq5#~J7mE{M}*Zpppc2Cf?90=*bYqmlE9 z)`Q7dT2}l+@jpH-c}4bLza9rD-k6MRpyKq$oomLS>cZCy0QrOfZ0Kv;a5c%hn^V;k z`k{&AkBe=(tzsr*Zn=9m&!oF0|CQ06fi1|zJ3&=@{26{9<-coWlMLd|pF1JL8;WIN zY9BkvsGGPlqtN%jr$vAi!Dsbaqo|3%YXgt2>&i6z_n55b%q8I26%CsFWj)d(B*NCi zAGwqC#X;mjA=+%Jf$8J!UR@>NFwsXBxCM@v%!L?dW|j)!P3A8KzU+n3*|sUgQ7ylAB>t2UA)itnQ1>Irf8PO)fGofUKO4Z{X?4@Gi*2Zk= ziPL5sJkV18SkqIpCYHvEX-*aU};nir0p+B zIUwUm#mY~WD}K8k2{9FY+@}c&4d4f!0jpql96yjC83DNAAsA8`1#d#cL-@0vBJgEo zJV*X+mKvzSXy7r!#Hk-z+*zDSQH>BStq33_z7K!cOQFo+=Ens>6^+dE(?3X%)V#Me zHP1iG`~x~-@?Ji7A4{a0r6P5x=|GXzF~1p73zTWe36@N|bP-XNo3%wl(Y=+~f9p>g z%Z&%b$G|~rKh860=^}{KurDpH5y1P>ct;?Ir>jWm*Yy7gtLFXw-zZ=Y>__8_u&I#T zu7o@f&}s!i+}kSBtJ@8$Gq-)sS2Zs*zaCKxW)E^M{Go(E36!^@kUZ+j$_0FmWmp-l zZcSXD(na43sj-RT$$JmFq znGVNZ3ma^P)|y~^-1N$s8KR7xFdI0@Yru<-KiKU(!@Z257eP|>_u?j(>yr=ZX@7_x z@63PGYz3?{Q%52od;V<~6BU0FdX=Lr@MCn%BCJ+OF4UeHR3HcRtwh*J4)Q;d+*tuR zo=1>gV+YTl1vm1*&m4h;k~#!i4lpJ+iZ?7u02K#z6=bhNp*bhct^n`VFcxKF@tYN2|<*u8g@ZiPEO-trdF}cq6)R8T|l6tnlQI?sEIrJ9Pe~?1Z^2s96}~IPREN2 z|4jwpY^$EFA33BzHe2|Vgp|sG=O(EdS*;~bE)Nw&P<}y{{x(!LNCn?G%UOn2q5Zi- z$vuTYx@^k$wzGAvLY_#w;6!KjSHG}P_;XP*tT8aM6)`!30}JXp%CA~{TAyXRQOPuf zrP3iIw@PKniHeiYR3&yD&i^Gi~aAuLoaXrR2a0i%g^+wJ6c-S30pvW%t8 zL15SS(AcXZb){bJI^O14J(rK_9{y>i{APWn^-Q5}oD*A*!Cn3X zIl1TDd*Ao{*0! zeD7bN05c(`N2>;}hae-B)v#;f@<5^=esB*NeB}8~_W=mU;UZMi;A{0#tDM78;Zw$Z z8ro0pzdVT-DF&}x_K^u>P( z_RO>yoJ6|hwlSLZMHb40wJA)j0$p_FkN6 zy$N_cF3HE#pFx9a{29_(@>b*Fagv6bw=)!D-s6H+J=nOt#64IxrDjM*d6@JVp`jwu zCP?a3%O^pQ9oFBz$%`*i_M(>3k*OChU1WBaKIjagJ4eZ|5T!=rTJ(gOG2*r+!9yk; zQ7|R&Ly1Sn@sE4}UF+P#!igP+f;;b&5oVo&X2-+>f6d0C)Ye%XJ*QWA9D}CzrY&YHHFVdPwc|X#aw%MaJV6VHt++{4N2bY z)qAN(A%~P!lxLne1oS|2x58L5xn%G05FGc$8|S@b8vk_)9YgH@6F2Km-l=td1Xf3Bd0!d z_G7rX>h=AbDWy`2?IxUanqb49M)`zI$9ZLHv7IeKNOM^xX04d1>O-imlz^Se=zb(OzY_BPK!oSy725j z8|9J#0AxZU8-*?Q=C-{!gEM73XJ-g5UMB>mVQ>)dK#^7Zeab5;RH@fW;GFb=;aRfZ&>DX@)!z?<^9t*tI?o1QLR_P(G*idK|e6Kldi`>02!4Uwn1U zx)x(qOD`mi*R=qm;mKVU(fd5R4y)OaM_7Xq`&;Y2hD(?X?AB$6)ZzfZZp|wx4lq32 zk10PMF!MWVk+`81N7~g$Z&ZI{4*QV5XZifgo>ZYIW_J3)<`n=SdOizhj132$`sk|z zqZ4GjFln+{$+vwil5Qfompu7$ zb!Q0xfEbB9>_i-s+lE~avO8|<+yHPg?(VXI95^CC*8;2#H~@aa9RS2oeW6w2s3JDE z9Dog@6F>#u?g8-1z?f7{K^~MFr3T`)2EpT|iunQncvJx3_PiXDWeNk38ldTbD3Aix z|Ii7LsC}2gwytO6+l1IcIReh^}C4Kw2oq}x|Kwc6wy#oX> z;rD9p-O?`MP+$oiaAGnVi@3%g09>*FjC=q(;>km`_5*-w&w;6i#6-JESU+E4YB|%OniA@m(pfzBX$jYZpV(t?I~9Z#}UA>Hz@z zNE|@=&cID-531*fp<1;IXp2LSSRTWOpNAWRej#9EL(t4~@?q)^td^^rbUFcO7}!nC zTVeP2KV)+DG_ZiSQ|zLc*emE2tme+^RoW94rrgxK!t=eIw5tC)Z1dicZc5*TkrIM8n?2o6BP z2_+jHO9TKRDgdyAvEg(8Kmi~O7JTKCe_N&i{0HsI2N2BS20#*`#tQ&IBZxovFMK#( z%-fE8dqAuJTx>`O2MNtaDn}5g1>|b8(LFel1FI^XBTjE^5#&Mn!Eu0jZ4H9~rZ6$P zg&b2Do6b*{#u}*mycRM5Ag$r+QxW%;F^d2nH9lDv)KG!7jST>g-I0p{jr2|yc^1QS z7}!J6q`i8(TH`1+3m6#Fn}>%?nN;hn>O|G$lR|G_Fr1rhBbdBhn12O^YO z?N$)!u0{S+1E}zxbmxC5{tukLl5im)9Qb}15_vu-^b2<;;mxfeI|4SG+8fxGHdh13 zDivYPA7u*M0|1;L)V{TN=Q!lV-JXQsL`blx_%7RRjDQ4nMA*v1>~)$fB00B~XXm>r z&_8^F(MwEgIs2qM&We2%m$OZDe6U$|mZa~b5FHlN6idZVfu16o-ch&NTPCz4#%-}O zGWe%I+@#`HSr)77kaT2myc+Oy_}l6v$L;Dr4iXOV0@uhvb0PU)E?nF;2KbhFyseL& z5O@FGh^CT9p{ltxg+zYC?b&_s`k=31*rl%Od2y?1#JPD1G!PCzOtvLW0*Eq2!4OR1 zMf9oDkZ$r0O9fkz9*tt0JyqKnfcyZAY5|64uf^}ONR~PwWK=KUfw)&xAOq5PDMcGL z-+7mJXJr(q8c~W9$_)tIap9kd17Q57tN^w@%aN}vEP;U<{LVz)edR)yyGnQZOBNd& zTO5283tC_hEq!%(SNSN&h!skl06^3UMvcEQDAfSyd-2;e1GOmL-+cN6u#i6Zr`dMP zgmeMG+8Ri~*`Oy^_#^uO0N?^5JN|_X7WwCae8W@y&j5k3`)}E|3Llu>vTg^;zl#Fk zNdFHGcrq(RScS6&G5tWy`2PtrNei;PJD|z?UEh%h^zv2%)G8AQuK@{2`ae{HUGZ)h zLEZkrgahcQ{v@-r^KZ%TYg6Dk3;vcQd1y@!BN_qWT|xMPl;4&8)$@G%)0-+aEF|6<)`q=G8$09pSX(2|>L5kNLK{Y#4Z2t5d-mBay!&i_eKChR}C z2t|K$sHpzXh^H83007iUWV6`5fkJ1&&;<#)%N#m*+itsvjHS7-c$Y@>{Nc@n%u7Ew zimNBX>8(vQg(sBsRZ&zU|2A7=i#$Mwu2Stja!>~7S^hhmP5^=uAx>%BbO`6g&i0(D z()14|*x|{!f7K8~Qu4`bSAwUUKB|_Uwyx^VhQInO0G#sU!Tv6OTj%kAHX!|O0OV-^ z0D>g)xCd$(ZwuPIxHAK)3IL_KP5(Y1Tz_Z;@Vxtn>uGsM|L&;2x&P=q zR8&5oOMnB28uu6KUy@J2$tgg(__v~4K0fT<(|^pBU?SA8s zoQMOt|A55u9=Wrq5C-?-k7+nbf2cn`Qd9kdQwECPj&u>$e~0{!kq!tofI<*-_?n)oJThL}GP)FMj2!I~7v%+R9;z>=qHJ0pIQhEs(Ix9Aa;k%o`~3GGrGZjvX+4 zlpRtAAkqiIEQ6BJ;}Kx+8r!c-1;B7(7uZe_D^44H0m!zB|pH zXb}cp+R=SpayOtt{kZq1kw~-MHmL68emQbIorBx)G>)Lc%oZ;Q)As}*)(DIq(*Qti z3VIYQktemi_gC2Y_}7Ydbu0i>1XdVt8!%v&`yQPnXWt~K_tY56H2Akv;%1cZMD zoF?A2g=#4bIypK3pqm14{s3h5{4YL$)_F%Ee~b9TfuC#?{&<^6+P|F#w!1Xlwj($s z72`Jkm%yWbTnv_kgMLp``#r8{scugd|EhMDd;qSl^EOR-TkiJ(&9k{9tp3INec}f? zz`^Dm44xHk2Z&lSWspCP{?Yyi26f{P1zrkb-qE+07k_%R z@4vv|0HrPv^48CRe~0{CHgOwB{smV9ib8m9s|Vsnhg1sXV8RvX1dzCH`Ctf{0TxT| zsHA`B{TJA80t(&%zssegx>fT61O-Q>61w#7%KeYhzmp`3cUo^PflB_11h3>e|B?9P z)Bm8s!i}ZWBxx4Jq3TzK$A2<%kBUj{!hUFx1k5(C6TSPQFR-7 z?qUyM0>D`;C1bPyZ5W)0M?O5HR%!$i|3&wWGlu0OF7&pX3#e#VuRe{hy7&xEC#Got zSZ_LvoO7%!$xQxK0Dx*t`tAb^-h=s84|IJ<)|LyKD$v4YyqQ?4VBJ4CA4p_DU~(WR z+U~)hORD5(3x?2Wh!-#!zDAgOCq*X;-bR1mCJRjDKc295vfkeDua zOqZg&pQko3tfaprq4$~r%y(fRA5sng=P*RW6Eq7N062mDtp<{C7hV5bEhNZ^VG%?I z=SD^YTK~t`{Y&)EZHB*9gBj44yCg>bzj6N?>^BDmybxwQmdJjLJb2g1e)qE5QyfM~ zk0SD^4V{z+Q-p9noT0{LxUdx|STzYdDvEHbz>n+EqDoXt2F|0S(*@rKAPE{diKWoK(eM`5riZafGd@kNx#7rk5gmOsg@%TioIf+rz z1${&S)(aINwFsdN37Q;8If$?ExbOQ6)Wb#0&^kX1M$k-JRp}`k@Fc}6j4AbeKc%ER z8-e;D(UN9 zu{NF1oBPD#^J_ZcYFT`)#u|7IKf<(TzoQ;7*QqAyKUyhi2GPz;)nf=~5k}nx_u(Iht7Uj*VAOMZOa)1mE6PAHaE-e?zP#5v z*^MH^bSlB?6-N?H9DjO{G90LQ=IV#Wvgqge_}kA__Q~TQmB_)a*E3R9fmueTMo^kx z@U1)Ug*jCZDve)ga+18H3P*iX)XAGsUce9%J%l$_^sB5;+)O-k(E`H zL*rg+)7_AMBp5~G601pyIIdZ&nodpP*+ZF^9{%>;-?ziUCWP5efQJ!9&q%qbo|EUG z;uHA=+-x^l-}qRW9@63tj>Pxosoi%AydJx7qH;na@U%b2QVOIt_-M=a_U~j_-W;|Xm)znxL3Yx*H*#92#jEwLO@P`JN~{7^?mCv0#dQC zC>*ckD#-MQ}vIpj?o9KgE}wMMucT~sny)dH&;Tc9EXk=uQjgfHnpG3xa`sdIq$CujK5O3NB%*oVS&P35<+2$P{0`S-)xZ;R(Qbu2Iy#`qQRYq>QeqrI}Rs)kk*oaJARy z(`M_)5&;m-qAD3~!E~ueM@PmO>Z^Bq^WMIR0*Oru6yqwQZsy&eyobv7)b?UEoj*}N zm3fozuTLD?ofgFslUbyxU#Pd4ZP~o7<>c$kCLDl=iu(z@t2Kka`<2|2U#*C0*uDZk zw4Tf%x^>p%KPto0hYwSLm&<`Y3J4qNCd7HK6%Ak5X{dVjqQ?c3Kw-s7dcO6SSD0O3 zKj-CH%7^7jQw87I2r}8po>G3JDRwTNsgPF5ut*mL!uQ9+Jb@=8%*5knaYid&9zE8< zBl;qOJ6k1vme_VyYzlxcwSx2Q(!>ZN5}-U6yg9}sNdK5d`COoG1kdWd_%I=<&3Gaf zKsELTtxZj{p&B*!DCaD!zZEuOx;7NZz;o~bF?VM?o}5;v0R4$nEf33xI6m)yvzjk0 zK3B73{m~g&xl*gCc&d|+jOL~9$cZqy|2!21W08^B_Yc?*vG|jDmOb9q>Ae8B@ka%N zpN7-hTizTD98b9rp^m0}?mgoD78EvLFDEER_Oz^1(0+kB?^A0mKsZtS-b-#UVVDCB z8f$9sZLK-&;B4iLPsR>Ee6{anG4kEaOU!AN$sX%nscFntl{{TnLNvGT*~$kw8}B@6f%@VuKs#jd)&B2hXx3Ldr8P z&sj3&U+u2vUTT#CG6Kh3B`MOl9nCb|!x76u9i$}Q$+i|wNolO#`vty{66!^HpGs$G zeoJKGMMMjW<5iJQ4wZUjWoO~|vkpE)Xmqu}{M9@*(;lD75Xv(K^jUc|FZd|>Y09*3 zAKG#|%7*s^4tCqDaGGS|=7P0^{J+p+Bihv7pWR(VYCu%%FRSi>jl3{OeRyvbO0nqY zlaQPE-eJ=np34#PeIf3oRmU8wFlm|b$m~HT*#&AfM#6maxu%Wt1x?TWSj5~`jz9nNCV;F zV39&HmY^aYkx3n<12*FD%35ebqdN96nPd;H+m6b$T34#$Rl{-o^4bIZI9X}Z&VWsA z!hwo+IS!0wyBni)Vgv0=gHkIv8~LZrm$qMu_YB&f<38M&Ej&*iZQ80EywdUVGeibI zH&#r@P|rux5`aRU-Wr(@$E2Q3sLJsEqu0fweO=)dVS-L;6$#(w%$hZFcLV6Au8j1W z{=J<=eL&NEJIHjDDmXC|A&gn|jrvBOo%j08*Xb9;MOc%fvI5BC1Ec(DbHSmW5vg_M zr*0pJf*wT0rC+crDHg-m&PGrbIm20!*SO`))+>4)A?$LKod05;n&iGlNR*8#_4yD; z-5uRuwBxL|ckfs*`dGCQyRM4hfGvX^8ZO1irGqb@7YUC%WJoj~H?ZCzAK^(zXj_l_ zVP`LIjBu<|XfQe0B&NsDif4J8dMl+FQk)zh=CD#mAD2Feys;o~qhr zNoMe>X`No*xgamgs9beVB%6O`e+br-gOdFTjdxi)(TkvqEoHi&6z7!>!$!T0ogj($ zL}VI$uF^9~BW|H*vtG5MuyJZMvF(Kj^a<{r_h0e4F|iiVUgO)S@H!g{Q_(D|nTh9c z_e}*go^ivIXDH`qI5>Q8p50%|{Q%Q?gLnM9VATy;X( z?j6iz;a*Nvy*h3^vD7}Po91!M!n`P%xR8q$i^Pq3wxpcBEx9UC{dq7#)tZtc$7M*1 zu3++<>Yjwx#?COD9ijh;I6)N2x-33#$x1K8yagrcXXaM?k1h_bYL}-~?g@rnZr91< zn8N5yhdD=k25_bgSCLXm7h>Tr_oH_oVPw#>J+>#2V1Zw8PgL}eI$p121pIn)Th1!J zJ}e!w72^`UDy+sEE94H$+BtK5de6MjY=7OD$XQ`I(cnic+G@9 zK>vqD-!^^Q;St(auqRURFN7|gL@OG{^y?ALB-E2ogti3mtF|S(g%X3B!UGb6?C9pj z5u7x}H;iJ#Tw}UBR5OvDh|JGst;KAsRhcq`QwjL`z3N&7UK$mJpKEEvXOZ>c7ah8Z zDktdZ9oJB;oMVT5b~(gvktbJ38Al8EnRBqLGcMBfJu8WSS3LXbMrV37l3%(NQ|I!u zIhax=Qco9+1Mi3g9f(DLL9+GKkg2b2`7)L0+of9?+3584`z>aOd@FOpfM)3p9sGFOwhtLvF{T@ z`EKxZ>Q$qO)OU7D)s?5YGOAx+uf;ztsNCUWUVg$pwP088nJgpT?O0#TJ?>&W^I9md z$$|y*X;^6>=?PMzzqEGhxM#d?UsfWnfV~%f5Ge-frMv;^Me^rGQ4`CtsQ@BH5_^7kkxVqqVkuS#s&${U2M1 zkQ^A17m|o`#Vkhiy%jp)3!#6MdfysZd#u^csyx(|;sG0j$E;E@d zxKr4gb^9~--j}{biIci%sn1psNj)6fvAp*o3<-}^H&o{H8SZmPCrf-_{i7}$TP|Ft z=#>%3RW5}g1b29Fy4w23&O5U>3-hlG7Um4}KW*Ojbx8{9Jy=LEK3QLbBN4M?>~33b zl8Bejp+Vt|n(_YhjxIJbw{|xW>i04KgZG=VVt&uBMM3!Mb@o;UJv({2C(&(`=t~zn z@V)&NT{~>oCyoOq+1p~2bA;%V#YKL$<-?Uxj>#1#oi7j*<#z@lDK;B>H(QiBGFvnB zU)-OfYE8NG*r)OfW+!3lGEshzw`v{cxUnDj8hu$Az7-vC$-daw*gh$x5>(s$R+l7f zDv&TLLNge?(5wQZNGWXlEj^jFR(m!{b#ebgWf>dS$yIc(*OX!6yl<;ZN9i9ffI8p9zlaga;I zXFSIrW!&ZR;q*Cs%Y1%G(UC5HWOs|LQs!}eP@o>7s@f|Vrp_n#%L!+vR$)WmI+kYj zNnpP=W?mp-MZ0Z$en_{hn8B_vLfS|dek>mJ$XF8}rB51DQgbfso;X|4MZuz-D6z(2 z&*)Ss1WIb|%t69=ar_clN%AXmCQDmwMRI8tX1!r^Gov2)zJ+A*0vu`~qJ)}mj;PLV zZ@~-Ui3RDp$j$v%-D_Vl*gR!F1-(n!A%66h;koPQn+xKqhAqP|Jc|? znl80__7|`Endo_{*pp}RxiVzOQFFWR2dm#*ZhvMw>Bi)B#6 zAOI`bCF`<$OUm#cr=PXHmM9RgEEYlXmBc4YM3NtpYt^0k?yVZoIFKb(N>A~%Upt8- zyKF7fW#qGY%Kc`D@&K)LYB0eLHVx0L6!AK7i`8(*mxY(CUvm1!#^*0*ck09y%MZI8 zQ&|Q5HxtGbhAE||!ycr4s_jnC2*r3x9vOUfX(6v;r?7>b*4Rlx!2c~3>aN7S$chLT zA4bhKb%_6|R1i;=E&6-5BJ;394N6C>blHloP9OTj7fEfykJK0b!fzb1-zA}XF~C!= zQEJZ+MVQMu($DwN4;OsEpjvM5>Q)?US$sVlHU!Ca9Q}g1*t3h(Ae=#6CUJn$^Hwp` zLvXCvj<4B#7)vU*C-Ht=l>9p!rGd>^cY74#_3G{mym$oalXo}G@Wt;h z?J$@RYq+0S}pOKBf2ztlU*Q8y4FJAM1rxmk}zs^t~x0SX=P^n(1ycPJWc= zS`HXeA_kBQzRIQYz=idHPMjg&=d*A`ogm{N7$d~XmyhB1UpuiYaTzQ;IS3j^(}{+o z8tA+3=F&_j5c-*`cR-JD_?>$c2$w10E&f8JI(@}`%ZVm`+<5xwK+ ztDp{y`EZoAjmv#L?}e@z>)sLlrJ=^FuLqcCQ5hcdG^WMW;Cwgq!AQ$7LdfVzqkb5$7yZ51{%EcM`A47Cl5(57XM_C@2Gk!a=x!2MpY9&IZE z>ArBXx5BLGcr*M4 zm82J)C4Tkem6~akf=@Y>j^$11U!1;~b-VoRI2>cx>VJTgO!n)ll-d%|6UmG|-iUu$ zB}0=CqlYxiaJKM9^H~+A>Pse(31doCCiVpS8-IJvFr^E-z zGP>6rDC71A=_pCgL_;r<88F#N8iGyC58v%S9?V?Cej*p1ur$jZtAc(GU9eUII>%}% zmHqcTT?&KWstzu#D04CL5pN-^DsJ`n(3R7$WhJt>t&YtiBZShtnjVpgGt?d7-sfK=7y_}$bwo-o7?l2*c(vg zVr4!>N@KvdD@l5~(LaaVUe_}SGv{Mq@zaiC#wzUgtfC3+kY+j-CK$iAOT)CoDCt*_ znBiEjw6i*C#8P=s*i8^Hv?dE#c-ycn&)U@Z{rSa3cWTmelTf2*9zL;9fwa&(#BO!j zI8sUVs}oyEoe9aMfa8Q1drBWv*~Btu2QEe#Qv7f4$2=yO`FVm(3d!#SD_AnCCfL?I zjH<{c&IqMLq30u<@df2KG{1shKgU~TB&scSvthh0TGk1;wAOrk+4`UuG8<$=zk}I( z!b9FE)AeECKmg&oGln|gC$Wc}j=_+!{7|Fgjao`(_E*xd;7sZR(d9z{ShCCFHqDpg z!;s5|8+bm!(LXOXxQoXSBd17p^)E_ix!MohZ!#{^DXvMC!UUfhGar=|;6KiuO14s3+ki%8L zIX3B~H0lfZXLZS$Xx>iV;J8T1QT}evzus`C6F7qk2&LQ|8PZk>14Qd;isEmzv zRaCTVv>?$nV-iET5|nn!0?AVdOB?M|%LW9c-$Fwu`AXj5HCUtRrKT==4mc(H<|le+ z)jCnK5bU%nl_XK&N!DiVA_kfGdUB!7v$IG?$orGM*;&^}{;sLLdoOB{FmT9vuC@2m zB>lw4_j2x;f&R@J9Bqi$R4Kg6K|Xv}y{}Kt8JzfsIAsaWb+PjE`pO3uKhLP3(InB% zQf$b2^{D7i(8))xKln6ldEC6+l4I60?Cj0Z-wtmXX+%EZ8Jai3T#b@9@v}~H^eqd5 z5-#tyB)*J$OMnBfJC6R_*4$NzeOVjieQgneXA9+VHQ zt<;yog`;y`zHcHquZwNo2~O1*vyjgl?F)Aj`68R(_Cs>O~Q_Y26jK1x;*f4D&G_7 z;9ce5q00C?-j2`SdU?$Xb@#D!dWJt2TVyOVplEe~Uusl)7d7&r`;nAHWmy|0UpHX~Y<oplpx;NtyDV_CEpKf^$9aC@S8=Vv5{9Mg=EJ>=@-I{ zoys4%R(+;9fcX$KW)ThZ@~2EQN@Y(yLYEe_ow?u3le2JEY8FmJ(Ni|Pfj1jkdQBat z6Q%O2er*2;ErVz0X+XZOCUJ(V2cAj=CuNX$i}v@SYnOoYBsqJA-B?_ag%?bsH6db! zfyDF!#kmWL=9oGc%|?#g<*MT5!mqD$h%wJ<*yrLu4)cC!=3qr>s}#tY5XqfQS*dk% z8`nBp^TnT&F{rJT8I;a5%_tNF-_nZv{M8Vf(2v-G2|A}sVt*+~9)jS-0!ZYsZL%Hb za7fyROG;l=^pX6qP%E(>8SkUy~)ZP>++!L?tGCp7pvqoVuYB31oR znb+sqeRBnn?lE1Q(Pk1kMZj(4D@htOls!Br7dR$O{V?!yrp1}wHViu`96Of3d;2Pc ze{1kd=M$a$VTZiF2<1_cQ16RJHW3vp8J{fTQF)dauIXMq>nDHq>wdgSLPUD?L@oyo z<|;idWIt4GBo+^z!9?Fd*D$ytYWq?uIME`tvU__m(clyIu2)1CDmvViLz^gCeUv4_ zp%V*IgoVaO#m~}*FRQk<=pWhDQP7wpyvle?WT(TeVE_5*VfVXw6T_A5k_R_2G}N2W z@`LwuNxQ1!U2XB*TRHrf?B?`uh{iOV?sE^1Qi;tyFOSJK$>4u4HLTNh4)ZG5>HMlW z(-9lXp^}L!DV{;XjlACUoqB&wJ(s!1|4rpg&sG-x$#TadC6tWZG^|g~^+`7A$Wtbd z<9qM#oD{w~@9;WqX^Y|O(2ytdauZv1wy|-uOnB06t973K+$CD;d$86?x#eDg!l|cC z+nF5o=1o_2EoRJq(66u(*KbjyL(2W@0^T-4i=zhU4W_gK#{N~z4E2;%5&l1xCsbJx zx$2AvbPsd+t@`JDh7ER3S=Uc5weyGh)Y%ZR`pK+1l8J}0^-LzBRc7%s1BPd1$%lr1 zz55o?Fj-ioX32GrYFyPI&5OCn1M$1n-nIJHV=|zj$z8tVK}0Vd-;UqF4~DKUEL8M{ zq$T(@rK5>$B|h@5jHM?rl$l~EK#mk1k%$rl3~EGd&Ht*&w{GHx#v%MTU~Zcz?0~N& z&423LW1BSo=?8v(Pv=^N$3-SfG`jcNm5ep}qKI=j=?8N~a!+e6&pDG`mf9nmb?tFc zJ=cS-cR&TcI72alHy-!OGm!$F*d(qrmn?i-YrSj<^;+wzk<%e99W=Auy#wAh=N5^2No+Eo+-bX(kO(>iLFN&kWQ-;hHlN z&5@4Ar;Buj#&8aBdA_fEzfEY|?_917kjU=5Ca+d|GG2TGdBZ!a+JZM~KjO6L&N?lr zobr(0x;pc)sdVzO)1^*GNu=bf5N~nGke; z?bBQR6gOcgl6vK&@yYwGUWaISi_i-K^{%ZVvZfNo94fhy<6Wh;qoPzgY8prR;D&-Ml1?P;XvfXnPjSjR^&)gliYU5g8{Bu>+p!lL()Jhtfk zDc^cn@+@9z?uEqp*y)m&{;CnU>fx3slQ4gr_i>;X3L*Oj_XXF^9ZuE+O-tZIxxRBH z1MvmglXsXV+f&5ZOm*?{iK{}M2!XSyuH2&yGV*W8j#b2oe9&5Y_J=NGpW4%y-p{r? zrOm%07>7UdiD!#Cf_tz0SeExf)F<#qUt*qmDE%i%rLY;!?x_RvT&d#iq9akk{ve|0 z5uUgmqY*6e6;wn$yn`r)a$Thb_np_%Wboc|OKBuIO`DgkDi;qE0PK-2>x9owmoBP8 zs8dajnw?%zi;kd}xiO?K^+=d~D%x0^ft3AJ`u_UMil9^>iF+TO-*r=yA9S-AU z9PBHW_&+_=IjlBBoeB_i&1+KMj`=m=D*e)o<~_(bgDd?SS$}Rc{^`wMbatA?-Z9WZ|Lwu_E5AY+ZTs*> zEbU}JXD@ncvUzl`=g1M`RGz|zY0nr(VF8ubt}jof(1?VH+Y2gQU#-o5@D5^Z(tqgU zW;ZAOZG^?kx6jM+CPMO8^7toBHed}D=gW~`2g?K~p)6wi*EoQH7X)f%!tpr7oT zvnHl@EiC7v?sh?H&z%k1ET zQ*m&fT@63!m|Fu`EWp1p#!k`NyzRxdMQo;`8=M1C6Lprs3hmMmblb%Gg8cR21N49w z)0+vOSF`BkmLMK#WR40PtJo?G6N4od*9Ixsk+g(0<_4P2T zr)@!vGv%AqxbIHhiK$*~C#rlfp`rCfvzXJ5*tvT70(Qiy7zQ+6V4ptevNrTI4#7t2 z?OZRIWE!XzCx>TM474$-!&^o@B@>Rvo3_clJUlep#-uVmVH_~f)Mx(k#FG@fdEi58 zG>8@>VG@Tu`Itv|=@nPp4@}fHWYpv~TZ@M#nS?CK(Z3q{`mrNS44Gd4I;@V)yC~oL z#)@a6hw!at-QD~Z+$fy+kkeRRNARbzFG5e5a0b8M%o7Yy`{fzak_|<5Cs{I&k4q^$ zoTb=&5%$O&@!HIsu~6Qa>Qx)*&T^mKlK9Ku52Y41Vrh3genVr&J`<^~n;%RZ;e=)0Ku}32 z$7fOI(O+xLRtp?jXd~6yl0C1ssR}QOC_wN+^y*;uio?r4DWGaDpf*czY9DFwwCp9Neq43Jfj0G1&yNd3aqZo6;>@&N z1Sj&_egM+VkB`MGblz}@ac{oneatC}5lV!x@eT=0*&2`vUS@oyzLyrndU-#cEE#?_ zHjPI%dYwL*>%2=LOR@%Mr=s<>UHkj!M)&aV&*a`_Lch}Qww#a2KND|V41K0}e?5~R z7#SYllY+mMy8M~K_aoEtXQ`vY%S>K-`*Uy4AEV~i757{{`6-%NRxpKd|KT)ysLfY~S(Qr7+pVo$S!jwKwcn213du%esgFAVfy~wp?i#jk|#-llp zJF1PzOQkR7`3$}2D=kU%L?a$Ex+-C#YP;UxpQZOBhOszO&y_sUB%btcS98rYV%T?< z%<1SNpV+b(f<`}C;GG#?JL#)in##o>v~6d8Qjp)L`s&?-@GQaRnGY0sUA-=Q=7>`^ z>Rvu?t~8F*HlqgZjb{A;%$l9aqqJwWuGl?WPM6>Ar@S^2l^*}~A@2ekA=?xNID$)) zA(s+)mJUYp;Br4v-5uB1OmP5?20(?MEa6fuRV=!L2N)F zY$^up+Lot$unHOkp~&e&iFW8*i<2??bW#EjmMKwY1MStHX&DMmor8gMPDem?-8G5#Q&%qwy-+J<#g(P|}z6=`eyg zk59-*1?}*@Q);=n~Z~N^_#^jwn|4gYTzEC4r;!F0Yd9Q-gY*wguyd& zt`jvl$lVg~e_M{qg$Mgz*Q#p5P`Wz_`(dK%H2L!2s$BXd(CTW?YSufeMIT(fi~A!@ zxtl-zc0xRo<@~*TpDD|rUHr%)95u>j1-s(_0JI%6ScY*T1@7K%ukazwZom{pj_g<+ zPKPabjAV1u1$_$D3WG(fY)S*<`QrLcNlP_jojjQbE|BJ$|1yunPW-=ke^v?K?}T4k zMEl-JageM=7YhUKfr!8sXtL7(50fq3H(qROV!>qAa?TW4jl}_u%N=4fbSHT=08k(( zMNp&H6*&?*V~9UZ|49fj*G&8u)KF|PGq$b}Tx85xQ81{o#Z;WedWb=0|4Lrs zI}F_4`P(jI`@%p%4vFOC7s6t}bnx-??+rD6-g8?pYdLNo>Vy()+dO$Lm%@-I`{rt6 z;M?(dVoq6zyBIxEM@4~8_S)+ENp8Q_H{F(w%j`sEGjZnHNuE(Fvq-u}giMa%9@`2L?+25?CysIfL=5My5huNYM<;H zN&o=R37T5@4^vSJFj*OvM>_#|zyl~}rS62Vls1GiD9g{l01;5NC*&nnQ1k&AXH8sK zFs;uk{Kj5|)V9ozL$25d56fVx2zxLfQ7M!lL#_6*whf8?WcS@n*%%%_nYJ1xFC?zj z{w3Ip^?|(&dX0=qYxWJA7{FJ#oQEa5ss+7}QXWXr~Jxe=0}^uozVE5l~?# zLE`@GmB5sPiZKoX7^0dIO+Qca8BIYS-hw_1{KE&dZ?xEo&BFu1FDg%xi74_BImt4V z3HOMFUv_MC-Vl6T@r?3#%weXOlqwcQ+NFP(rXY|6z=0zlUz6P0G&E&1sHQ$}q_&aP z`R!5qqh19CX8;}V12q+ZxM&)XGoo~1xiQDLSYwWimD@!WK zdR$=|OkIn>W?1sDvsNZD06WV^u1L5)vr?)u6@`AzB&B(SH)M^_-iO$L4Td3q+Q`nK zqU8$io1p_^S)B$D#!r+5x!JEi~{LefmoWV!D~ zpWLugdV>pF*o3rLX*1{p^qVsPJQBb2hEgW)ZZjOlm^jD#I}R4;Ex75K^EQe>f9(Rk z;cGA$a0ED*V^6l{?}L3G$|;fU%(U}+HU019^l;#|4FE-8l2^ymHxyyQpU7=pSW&=# zQ?hOqo_!hh*GdZ&uu;9>-DHDVx}SHjh5S5ZTHgq@SD8{(h5c7lYU5+Kcx|NNp?u-R z(_U%#<5qb(#2qh#>DNe0=q@M%y;zZ-7_B|#t-=vZ?iT+ujqW_pTTK!UYHpLPS{4xC z4z21Nr7ITyL@_mE#yDePVkRY_8@_M%w8zgn)n3VUg0w*k{ot5Qx$E4=y)X{b=|@Bd zeWIxlGPsM_&0^f~LweT>B+_&jPw)%puFMxb4DFa(xB#LCcmBS^Rqo=i;*z z*xiQDE2&C;md3!UhBAu9wddhXA3cTnZ#{AO5H(+jGmaTY>iB8{T6;}JGLlYa7Jd2| z+Ru8JY+KOU=KKZs?oh+;r)YPBz?%u_by zW3LLvKgE9l(7iIcvYFAqQK5oRo_nuf$($gpIbl!<_-v9OXksIheJJeY&tk9M#&F3U zGA|=pQ-@LkZzorG1_0E+%uVX%d~6iDY^j{Cu8^ZDs_LWV!A3PT2-aep;E#9IFS%yQ zE3zOMN=Y17D*#lK%9MK_V-=8PcO67(z0f3gMuIFTRM?(tb|S7Yd_|tiG$sJwmr@GO z!)zt;JmVa0=V2lwn#Lc^%@adHgHvO|T^sU$5%byVZ58yU)3&*V^6p?A=|x*DhoDemyzNgZvzIMkbU((a#C7{avDn zj7$>Ng#hA{Er{~no*|VVfN>K2i*sD3P&xF_QulXxr18^T)(MB-MxnM$ zwb^vKaVSu&+k?K}x4sPtx{T*9Sq4z<9xEdH3ixSQ0Pe~N)prZHc{zR`MG@Zi@_`?~ zGPVN55BY;1eMK2Sa5Dlx)dybBrf~z_o5=-nQtki%aROKxmchsiiYY^!*IvQ^|FV&t zsAYP;C!8msY#$nne?brDNEj?30L;RkWo&$+Z(<#iM35n~QPYi(d;17@d(~xoHc5*j zo$m655rx>WKRdN?NK0&LLB~YkpvTjf4v~Q0NbC~A8Pyn*ckvI2SV$c`rmKr(*LF2gWbaq z7lmGJ9?~%S%wYxqcg;Kl6MH8jw9RyO=@-rVg!M1h2_3WIe2w4c#rm-<<4+4=4+C~A zH$c=102=*{qLfHM*AZAh3E?i*qn&_b?|-z0sC*rC4kj4y00TvukW9x22_Knz#(e8f z?2*Tp0SKFKDbcM__47Iu+KLWg2>E^^eY+g+eg*&}Dy=RDz?1SHYyb)jd(Za@uo-}e z5d8VyE{1&|767t5Xt~#aI)I~5{7W|<|F=QF_|0nMo0Zl7WrZ5<3j;x7GyBw}Z;mpp zl=iP520gz-Au7qFg7CK%jUw9p-*Bh@jP>oWvRWD+?KWhmv`D}*;2T1a{?;qIJZLL? zs|w}|zs!7m|3yu#%~L_R0f6$w?~101ya`8y|9-10G}c4UKDZQ>i=GsT<^d%Bp8=5& zfjxymp(y|$yg+4O0G(d|OKbok^(xf2mH+^Ii2wT>K-T{2ndFDo4e6K8GuP$^6o>S0 z568|o7r$>Vl}`U6r=P}%quT&_*456u)M(6qt_ctU{H+?2((j7Mx*w$bNfc^G`Olu;sW@}(mK=PV+bJ(jA z&8~#!Epku=6v`5p+I|4aZ3vOnY!q?WTB!&VgiTKIC_eyjEh`0({n(sMte=9`94OI$ z&j;M~x0!&D5xb1T z{|D`N%H2T0=0ln#!d8d;d{;0?8k9WjKG#=B89c0qnR7o_;HeTgHxdFSp;9@X22%^A zO>VZ|KW`7rw0a51ud(wV?|rUL?5lkvCb|AT90-u1uHB^$WJo?U;y)Z<)B68wsc*G_ z?f+h$|M30)mjB5T{0Q569xp5b8rv%rjdt2$>dS07dA%D?d~6?TbF(TlfSpkN(FvT|b6M$`2fd znTrPVaC~N8@WJvQVqm8^_>=CD1?8K$N};;wf6yp+|1UuKfad=d0Qmo420r|cLd<_! zkP!bFoSRA@!%Z}oU+X^~O){l_LjiwZo^aDoUR>2;=Z?Q`z$y#Y7$=-|Df?+psYsRX zQ@pstiANGuP}p5EwnwNv7P!5R6%5}i2%1~->TO^;mj_6zdNR&i@P=CrdIT6w-mrjA zc0PXnam&h$D~zQ$>C=qoWkGg1>Dc-~6=Zu?tSc;p%p7fzN(roEz|729<JeG42>N^Db%K4pQ+czB z?d{hJsgi5Lxmk5=@;O%9v^}9q(@Jw>mkRe7C&H4cjJ6xdYVH*q2P|(~hq7jtaQ9}T zQy_(y&`1{gzaZ?M`wdhbufO8_7!dF785p$K>eU;Z4M?u4Q_*^`C5=5C8Uj8VXvJ8| zvhVUKRnTEv?qZVhG}5?WOfnkZA;~Wi8KFS&pC+582lOsA5BGmR58K7snR#z`!52;A zxg`&7Tv64jeA>U1bezH1afH4rL}^~FfdzM2Ps<&CayA^}%l8%3v$(*~%b~he30=*x zH?D}9S88RXOzzl%j=FkoYy6~}TG22?&;I2|^-A?@{OiHRBWrW|*B)W&*`QM?k;xdUIOkRXQeqrSt^u2L&>(BYlP5<#O z#jET_;a_;$eaRaiJ3v^$)k}sOhhy+c2zfiX1LBC%Hg7PUs-Lx=NV9$|E*BYW#uC4+ zXIZy{rWoEZut~T@`E(j`2C38FS0cehlZ5wgD8;wXbc3~UM!&>g4!MxNw;@sU2Aa>1|}zy+_PJfW`VXw ziXmAJO{u7y&VZqd8WI&UK-N@8W)MRf4IPT5e_dY}_; zy5iquq(x9!Pb~U4+e8xfEi90sI7A2vkWX?6E*-tBHg~Uu*govCv zj}VZWl<}xtn>EYbF-W;v$tHa>pHh>#IKfX1IaXaInGoVe);gdNB7YtC0M>m?Tse{U zCx;T2@W&bO+7I)ZRI9=QP|zOQJC{`ynHpn_2eCa@{GYMt;A&{2#4@XEPwnvil=giv zKvAv?grBLTA=vta{bP()F zxP5>OF|Bz7R4=lkvLr4`Lp)xF4(9v@NcFa@cBf1F9oSe$2;l@KcwtL7b0R;jj(|2Q z*S6sq+&x3~8U-y5Liq4xT^IJRfA3ZqBZ8Fm&9#y{VklJ(yuOfJjWhmk8}ebxg#(DV z;?}~*?5zt`n?2(d#34P;CNV@6f0e=QzY;7P926s@t^Kk6!0VEdQOl;`iTGOik%42s7n*f($v;|fw z<+cxF*AY-NY&F1@ye)FWQ87t(K4dqAxD-J!%0j=L{5g{KLulLRp0I&esXo2UD`$ux z4VeQtACG8V?}4gU+2Bbgck=1Ot?)9u3M4*lNyzQcf&H8zu)VXMqtg&rHQZ!3h^T5d2@_3AyV7Nn6LYQp zEciWA=d}pTc9^3U^^Q(=YQgTqjBf}m@HU~(t2h`34S1kw z7qTIFR99Q5rG|&&0>=9TuBqy=9@?sH+@_VU`bIHzEtY%2)nBM6qDl z&Ub1lYZ|Z1vWX=Vr2yE~^MlO-RUNCIB>^2)y?$`kSkyH-7F#B9}*jUOp3|S0%(= z$&fkgGfuEP7M zI#)a0w|U4Dwfol;uERW4MzDEb_q2006b|b*xGYBjZx{uyWjpt6z|Qrb;;2w_%H%@v zS20s2BB7%20VO?N7C_C?Hr0u>A^xQNdNg6Tx}$7_kbUjvK{;p2GJnw}f)#HIrdBpQ zooH(FZVx|_R9q=i&B&>gh`Gw3#Qn~3Ag5Zb<6{$S`4}pZjrnlSkwo?PMv5n&SG=xf zC#Jfo$J1cv6!l<^`%B_ZyMd0|ThxeanQ4Dcgy{T(b;|paOpiL|S#g-ek*HnnOQD%= zZdKES1^oW#gtcI^xR`V|`L!*0Zy<48K7`#rET|fWeN^ppg!1P!<(Olt;<5~~@q0Xw z2%2gx`LcEa_+yIfvrSeYF#%HO2TqTdT-@J3e|B=!>2z@0YNF-8@-)!JQcDZAS&cl) z><)DY{nHuk12gCYpae=G6g4g`vCIMqFuXmi%bk96X)b4rm366x`BIcW?JGkEly9l> z=JF88O?fJ1P*}GO`>tJxs;5~>u!~kN+H2l^Fl-^r37A0Va(d!|bK3GJ18EBzh}%(U z4&K^d4tZ#)&m!rwLd$AbaJG)1o}$$(xDEW)q=Mq$36Nefa8pO!&tGf#sst_!z-$_< zx_d}#2>%-ndMMU87~MB!DT|x&?wL$JAye-Li~2!)7@T=(LCQt6nMPTogg!q7Qyy&f&tz z>&;C~viq3rZ;y-n669>*BP9xvjv0*mIvT{P%LI(P^??;orv)h$?kmf_j)+Dc<}PG0F2^3Hqp+<5)2 zu*CX(MEOG4UVBcu4^gT}V5|zu`;h+6B&bZ3XsHcoefe3l9wKcL!LnnWM})hvUo$YlF=RUry1svRYzB>+APST>o`dO= zNYihn5tb(POgT2?W+ef3tQ<46!O<D4J}F*EoR!}; z?p`3Q*kwQ7Xl~-dSZ}^ccY2YclwZHN8fbbjSQnjI@z+(clJO_DC;|TV^6$Li!~Nl( zP_DZVdYAn>sQxWETK;`V5JD&%l~Ec9WCMdbDHvRZITn>oXWU4GC#D33{+|&UuTXo! z_x{?dy5^FK{X5_U93!obS#&qbXLW|mLVx>d;!zWdq`H441)m%v3s1&Y?6=YPM);pk zN8v^xvE`%uF|;^Sa{S`A&=arDEQJm(=vK;4OAghll@5B(_Ke=QUK7TQU4=Ea^ zTMvoDcOM~FP6KZTKHGb+@q6DE4Xa-UA){ch&!Pp`M+fy=9Q4W2|MDIWQaTKYLB~S_ zIdbRJr5j5n<#UT{UOU=qe{qNar6`T-I8kv4C|-wPlqgDN=(JtWil8ICTL+j74{A$- z?Rx~*iCRGGjmw%h8Pj({<2O49_1)Dvz;C~26$gd2ZGMedzNxmNnRz9?IT3j31}Inw zXBU_XV-Z}=u)+{lbhX9w{hpF?)zj!<$qCnE(xU^#noJN6vycv%wOtnNtcb$1nYt5& z9h*dh2c!OwL8PLU^}HoE%}-5kG@8>FEsn-ON(?f+3EfhVG35NadMGiC`k*@CY=iqJ zo1q4f8IvPsJA%zbh7HsEby5a$I72k%REn2zB~We$ExD9qF@H=am^V!Xq|Zg6dk0k~ zijeKQHrh{!ZwAc$H*+_aW!$^DE0ptmnP%W4^@56^_~q6Bce~!FW`sm~dD;Zl5W3^x zB!P5EdvR6hPk}c#Q~rTB2gQOKB5iK5Mw=LhsW1(#+~EviMy!v?I;nCR*}$cVdggSV zHx(YsK&11&pm9DHP`z#kQfQ8B)L&z`*vpWw6Vka{&&YzC-1)1(!1z(0nE{J>e@fz{ zJ)g4p0nE?^f=wSeSRIkD9fo8AX58ve?px&aS}LdLr)rY8&2r*NV5Vzfbt1A(?D?__ zfybtC8#dR>qt%8>g2Hwf_PNRueq1Us-d?CQdWP=`^*^gz`zjC_X-_0;6EpDHAP{l~ zQy_)%mu~tVn%aKGhUAH`TDK+fgR}3uBs@4wx$3rMPJrS30&1Csm&3PSb?R?C4-&-y z$d4XOd3gaUuKhNbN7FM?nsdbRpfg$0*HOl?*kfVqo|w5f8PvXwM2 zA|e0_fXr?MM&iuF(I&O7Xo0DUO|0jJVtK88HBR%_W*ISNmE~4OW9`gYGe3g)%28r5 zK8dKHh@i$CLQ68dBps!AUi&Dc*8#n-T3nxJxs>&keYaT5{z{5KRrm-F6+#7>xHBjkAErot7Yjt|FRTAGW2V zF3Ys6<1OVrKx0m{+$+3eW7^fX{7>?M(L>C~XdQYz7rKFN^5FDKGFs2NL zyFHz)z+=ceM7duaGK6LDDVQ8G1W^=!W!Fx5x;_q0Jh0IUV&;fqw!kJ6V&3dzMO`yK zN62>oUdplVI*DZ-b zSCX>$8iZ_PhnJAh`dZf4nvLr$sn8$Afw$Cs`l1-Fy3<4GG>r$ujSI9kVU!5^!2eWa z+!exp)=AD9{rO2ohe)_J)Mgo?s=wg*_Cg5tRfJ#!8vK{eGQHb>lLBuKqljdQlU0W> zvUw`l-mhc56M8>uuGsN2?Dq_zX4RryN3LB6nJI`JYfj*R3f#1A#O%tKAo5|JAJJo3 zhnx8*;xc1Wz2-8I?5|z^A7j-YBgQM>{oMCoX)ea~P;Tap%;|uqj>C8aF_itln=;KX z%cLdDrXhB9JBmVRv%UI2mXA#sK7{N>a3}cn&NqUda$_E1{M{3EAr-q;iSVh$hUa(b zU%Xv%XoiE%xr3gpk-_i8F%|;e-2sPm>8=;e;S2YV?9ID1*%cD0vV6$1B4+i7W-^~4 zC{0*<0S|?j0z&Du;D;8OQO36x$5}Ho-r^Y{u`gpjPMN{b&axn0W*jAM*D>_KpNT|} z(5ByIL#P|uqA6M*n z%O?64U5CG*Rbnlrn+8z;AenB0x#ibtN&}4&iaD+ZnWb2G+S)F4|pMA;GBQE(cOZZ|(iJ@{za`h2)(+`u^c+|mo ze`1;}NJ-V?2X6#WaGu~OJA=+8hpW8r#S;&&W?qtL!i0v~xuXS%wnLG-4v4XUCwdo| zWd)N-YDkC~T|Bu?iH8h3L>$mnqjS1zThZhVEH>HcKFoGZ@@isz zr@DW6As`CkwZ64l5tvvQ1W3nPHtXcLU+=&k$(#UcjGqv`Dv5S@P}8?K)F5ZsLL>$P zr0A~-dxt(;jY)C-@_^Pg#PffI8)*$#6O##WrJGizkzXqzCMMhSC{O?JKpvH0${~fi zX8KWGIE1Qz=zHf8aYLThAk3`klqS#W!xgYx8XU~G^>XAIs%DBe;dZ{8Jsdd_KnE0S zWT(DD@WVwoRgONc*?{NyF^qDB9@6X@8Gdjo3jV4UKp4Dd%db&s5=<(v8Wgr_T?9rp zC+;$xf==<;VuS2Em)H#ox&ksH+*oVZI%^S=@G3t`%Rjo zp=i|=tMxOsSQ3l%Mf1(G&2O(XS;wdeDxH+mn&$WW!oVgJf6f63Cid58_GX7`?MX$Q zR~oya60-OjVn1e!S_TvEOpNWXGpE}PyA-x?{1^ zjjj@TBA0V6K}+dFIV>ig-6uck4wut$cb4qxEKSnc+VEBHa4R^#WmN!cjD#_70HJq( zOMBwFp`sL#SmkN;<$-snX93dNPkbWWoV4y(m)4d-LhP0f#pY%vS8?6mKg3N|s#1D{GcW;swXe#8`RUMzBV+d|prp|d&R*w|6 z5@bDXE8^A@!ec*>u{ri}N4P{e6xcB4AGqy|@LzVNiT9zXov0!K^pi0L*-RTE=8_-E6OR*M6BzLNyVa+4- zG1JNy@t#7BO79z1lV)kc#P2w0J_NiwFlu~FQHc!I4v-U?Ui*$l!H+V(jgVF|17T|y z)D8Eo(*hu2^>hpQg&S2^4}U-#Y$A!#wriP-!*#J`sU5WMhA|$#w%=$Ygp4sL991K8 z6%=3!sNG6`a8GaAgz4L$y>ct zR&Fbfl3DIO0y;m#4iuiU8Ye{})EGOAfP=k?WC;bd-!DC488+3xZy_0UVi?oHQG4*-ZL`Q0X zPl`Uwy4SM3{SjHw_;LmJmmA9;7V!P;DoGGFjN#0ClaPg(zsXczHcit{=TJFM!*0XK zw1>87{08ZHzY=$3Q$YH|={E?d?+>Ot$=t8A=O%#M;-o2dl2(9MhjQ!TO?B%7y|Y@S ze;U;e5h)Xo0R2^Gk8G;RoF1Z4j^-^9iOH*}g$P`>WNPvc&(q{Y46 zq|apa5k)cuHkbE{grN(bJDElbM|ntJO!Jc9UNlRC9v;al?b*%NPiFF#`lOC(GOPD{ zKv`D=_7VJ>uO9@hq)W}1drC|(VnWB>U9bwJ6VSAAs7Ed(25LXDgmOBuT*DE^BEoiZ z3#jE)jgx}Hw@?GiU~o>zoxz@3l~hI+>R}Ej;1w4;IRf+RZFjJ})6mY4M9%E%P%N(c z2#HtbwZqU8w#T6bO{za~%DbSplsrqOGqTy%{p-cMI$~CQj3rG?@(`Gmr(7iL6re^5 z5j1Hk-a?Y^z1$?hTF-J-L3_0Zm8mY_2<=34&FLEN`^DrRq_>SI49lPU7J3g_ff>7i z-x+7`q~)-NqW+Sf-GO}o3kBq}{-dUXhs$Nm2`{jhwket<=lx+&ts`~*&u`gy+{vgqk#i{lbTmSk=g+Uc9cu6`hUln5n!WmxxsJBM z2VP8Y9dlYnLI`Zoxz!DI)d(>8Tt1wT$S2BTk3-}??l9Fg!DBQ`?U8eR1xHMLHn$H! zFNito^N3p-1ID@6&lDS8o8}VeS}nmlW(PBt_9$CV+C&PobD}>wl~R=$QKbX$6ugG! zYnYX2knLn|dt9_`oVP(&TA`<_GejgzH(2!PgER}Rn~WVFPEdP;-b-l)vZ@J+LC`~0 z{yu+X;U6EeH!{QPgOF0YHCW>KTMi6f>Ds6YW9nmxdG~~#IZ^=m##yqH{hW`L5D4v= zMN=!hONklA-ie49>e6tna$;twGc#<8=;O$kvMW!U3R=+#D-ev0hwG#2qORz>Q6I!x z3Lb!-*tpjO_?RiQZgnOFBoNb*tyhX?>(0k`9u;q2XiC?vknhzV|EtveXz7t+J5 zv!z3i&E|N)N|0~&JaHayocAj0jVVSsU+cObjpD`zm%eVb>6yA6C5Fvn*jciNZD~&E znCyh4kg~gI+-$nQRJ75`^+{Oro=BiY7Fp^FadRBxYcvg%xa<gBmkvIf_*|GxQ zOaP)~y3DsG(JSTV5~0%G#*B`(69J9jFy1xqt-!U@nGqxYcJGQQ*&Hx!%n&Z2DQk+gx z5x{lLKSXS&wC;B@*|1J>`~cQd?@W08<)c*D(2OVT^k6rt*J8hgKtjqpntf|P*j7&v z4COU-7?&o++(FS(4HGmks_X$)^)6b`u#4;Oq_e=JP6v zI|9aH>-|?4<9RtARrYyBUUs}Svz>Hj-Yp5-%M+YR!zKioNV)Ag5|0pHV#q0o94qe& z(1n9c)SN_bIP5z6p(IJ*y5?%C_=4X_C!Eai2(i}CP5Vz!Gk(sl5TyAx%+Wn zD1nND`li^oYI0_a8q6F{aZ`YnNf3nA1%?6{Kd+^eqcI}{H^8GdZKcG+yHtR2C7+bC z-qv-8Xhw?dj-G`<1&-;J%G~1ytlPqiaWqEHN9)g~kv5iY@>mWnH!MNjW=3bFcs74& znPpaSvkS|1y7Y5+asID$1uMqk5N|KvVB^>8=8vgeGg&S*8juIBCVd$@9h0=FrCwri zmHj!Yo7mA}jOtTtSM~KmFkdN%85TD9tHqvP@c=BA_@=7o#JPEE>}~xE{#NybEB)3; z?a-x(q;|;XQ=_*`AW7^EDZc!v1SXqpIq3ENLvrai#tKu#!}h>b zRgsV#8+yY+b$k)~-Je6+U_nvEv4@y^3axTi$w^&6>5G2xbN(h?j|tQk{ECsoZ{WUv zTw6WsRCfHjKpRz+4LJA94hti&ja&fZJYRp)A%otA_STxb9fiVcsj|2H*FTPY`@46EN07}~*{FIrWs+?O zp%P;@37+l7-_n1c6ux_h-cO=Q@F$HWH~rFPT`a203GbI_!#G;miYWEDTM54MMFPiN ztf~Hdcw7M?&$s2)e<~FJcnxrxkO00PnXZXp>@WQCtX}CEA2A04 zYkzPABgTqyn`@;BkGl2*LF__rt>_Nz#fff%80w%pG(pLhv$4rT2Mej8$JH>Wy;G2~ za4TM>qqQBqDwTp06%OVQJUT$KYMi0zZ;?hD3$rmenf|#Yu;>B&X?3t6l4l-tzoHsJ z849^5(2ANDP@@x@7h?-*WDSleOhe=VaV5`&rZrs%6HqW=uK}=T^L#yOovU~jzN~hF z9B~yHCox32G86?sm_L{U*eKy0zAtHmVhX$(h-?QDh9VKzAQkA3yS7i5# zRLo}*PhaeCkpWs2WUKAxXK&x%);8wBJU5pE6$}!M6U9u0Pdbg8QT)y_TFC1||-bqoVQHr2e%b~)L#<&Yf zA66V1ZwFY$R^9pU{n-z3Bd-g!#-IfE_*HPY{S1(G6-?FDKD5+St%6TX0W)L~phNb@ z@PDr9N6~YoLZ$}W*|TDImK&fD?jFS7f4{kO*_UiuFs>HgY#y6Mq;bma=#hcJWX1A< z$iah>>z1(y!<=18JvA^1KdS7z9A`ioG}PoPg^KA7Q2u7(sx8B0v=P4)7k&Z_ET&jO zX`wvmv#DL)`hA*oo&e!pj3Obr!jX&)BES|hsVJx}kkojfYc>fK!d)>64F>J(xco|c zrc~bDmmMVG_aIL{W4KhfrVB5kppkQMR(2v&I6a(-<40b#v|Oo7G2zk#T2fAxy-E}w zb3PH0nQjo@!ugYa{)NB^hkKZe6d4Iv7gQ9RDNqWu{ocBhc&#hwo}X=yW~H}z7dVa|D%p^%4}vduL+nk&OSz*k&-pgqteh@ka=23(*gp4KQrw^Is(Y^WcH@?K z$VjmMtHm8)mf|C%2iZ|NV$eg>R7ItL{#4;1c&RcY@IeqV$p71}8~xBNk=<1U^v~-} z+SXBRMp!X&_h3O-DcEsDOyhH>j%rB6V+f}TRTQtoZB>hf()IB?85P*A~0(r+X(|@7t|TPDKkXyAwAE*)yE! zkGsO{k(qSslc<;0cAXToV&qQwDH;YIB5l!RZ4gf7Gr3rCVxhz3bem0e?Xym~hsmvF zD~YOl(=Vi{cMo8>2^{INfpUYY=KC~dI8|*-SZg6vVs}pZv1huC!f7-KhVM2@ z)nfAEVQyb&&n+b^Lg}hUnoj$C$R3tAf=##*5F?K>gU>_jJb>9co$Xld6G%)ku$J+B4Jm>BY!bW&*^q0vv<0PEUA`Q3XKJ zZ?RjDy~r^9VwmdPW1$p95h^9Gh|ePI`sKa}%obL|Lrfp;p7h1k#ZFGGK^by*!cZK& z+F$H7?HQ6DXw~erHw%BXS8x%e+EhA2hidOn82=}?TpsBFO!JkEzhlnAZ313`7+a0r zuhWO5e0T6Vb015LP=RUOu;$6fb;F5eb6gXCIvPi>Bwp3OH0{J?0ns6Mi~p`&aZd7s z4JES^5mu<{*oqg*bV9hw+U8G?u8$ZY%bEn1F2cMzt^L6ljdiD-+Y6Hmo#w)Ty0p^v zfixy&zfACcLN5bW18$&`#2!IvX&(*?p7NGPuLevn z-Au{iA4_uLoGj)iS6qnO!eSPP&pReD&e{;w`MyEI=WfaPbx-*7*&0v- zy9wI-3L|vPyh78e16m1%uGoggnlh#aRqlVRP>g~SFT9s#ah85Nh$2rJ5pmX}-%%;hOAlq;V zY!}lqxG6q%qWA7WuPLAa7i1VEcsTRx$3%B-?2=+(M`1R0+GJkEOdYoPLGW;NqpG#> z#c))QpnS(UC$5Y}G_-ZSA2*8H^25^*K+ninVd(Fe`X+do?QdgECl%aT3)O8%)M5{2 zSnj@SSP+S&wK>qEl{;Z-trl&9ogzD5P8u{q9LAq6>)qkVcG}eb9`f(9+)q&#?Fyx8 z&OP7n{eXk(e<*=+!VFu-+#e$+LWa#5Vujm=#~=IaZNM7Wc1#Hpa|17y-VN-cr@}`4 z48XAF{3voyyh6m5{q-^)WFk{p>Kkyx4c6EL6!dptO$HqG?aDRh-bvuzoHbRhqWr_o zrcYp2F96rhTLE@--!kjAJoiGgJJh1Z7##nwqCMu~WL&BGIOEZ32Oya|HDF{NsnU5? zxxp`kGeWzsfz%9`b$ll`)Xd5K%QIZ`?$zSzx^IJSjx{0G<=@3}rdxhJBE5cwx!dG& zj0@0R*qjQB5KKF{tmcPFxcjJomThekoZ5v^+i}U>Wm4pNSpW8YB;YY{Aq>Y8EWDw5 z!@S9%R^mCn_@X+lVo-{krbuSmzcnBiqQSxLN7I=dORijT_9>o~WL4k?M(R{w)b4hU zg#_~MDqrnh;k~{d+Q{>-Zkue!UgM20&k)fBdV~+=!}VJTsvBQI`u6t8{li_2<*%6q zB7Ma57i*}>$Q<>tRoJMF7I~X(zC}-!`YT0v8)_LL;YL?$VNd39Khn z1QPbAq1s}Mw9SNtm~c{%Fy=Pw*2uFiPkK{#TH;m#Dk8T9NhMjw&s{k!5?_|0&)yg) zEG>T+)eJ8}?O9XTt#6S$+DV!4@Nw!GU&BQ%#5wjv z?xv2C?80EH+Ys_p*hBz(z+3lC3O*tW)!ARYd)@By`LeoeyN)0YG}roKoR53@(25sk z+<7y^Ei`*YRM?4ygD~xTH{K(e;(@58vgwGz`_**px*N|0FCrQ74LQr(+I&fm`KQ^6sX^0UvoIA zh_l178gid~_acc+gPGlfX6Dru#7MJOMi`e|(h(sM@(-52oo`{mTqb^>R8dN!wAaOs zEbeT)z0)crEut_`qt@E3nH9Ky9SI zaV#kzE*_JIkv7sWT|1kB36ZFlshkrTUO!@IceP5x*rgMfVjzaxOmzX&0LJ5inWz9B zep#D3^wYP`fCgQ04A2d`#0;f*X|1*eLE~qjnpV1UNvI~?m-aLKQMMb>=2v8lpA2~; zu&;YLf-?iff<0%(k&=}Fdak0_R;#N9fh9^Q-XOOkp%ZLQPIL;*fu}~DJStwY@)MRm zQ`E{?41w#y_{A3qML+x$Y_BJ1hAKYWsUkeQDhty6V226+GWF`)wc0{vIJv@4F8iBHEH{|YPLE_C^^nWU%ok2?%^)5*~0A{xQZ zB*4Qm)nZ8QDJ9pJ(_S1D8JPW8@RP-34Td1fmzaY`Ys>!xULEg|kc9J%YMDnO8LbtC zRT^(U>n58yok)RKW-EFlsFLB2gv{aF8tm!*n>eB762V)c?vj1OE^3py*®l3BA5 zfzU^%FM3^W)f;-Moj(obSc$SmKl&S;Ry?smlkEXe?tOQPo4fiq~e#F)TI7lvNu z8Gl~AbUtN}M*3U9)VVnl4GZWFWw>X8RDG1&Iwac9tbCIvBYk84umH%s=Ht~b^XJx)xC-PEWU^ap-V2g8EWw_uA#)A zVM3P0O9LfYrzd2DCFu@H!lz#(%n<$q8*|k!^@^@|Vxm8K^&$<>4})zUvKm1cVt}l@ zCC5cARYC@M9Og2YkQJ18LJ4w;QYuzNkEBSRzw48@W+M$fz(eU3DJ%!PiK5=C$DvD7 z^=Pj0vXkwck>9r^hC?E1y?%KSlcUhDC0xQt{ltudE7af(o(V$%fGX4 zUlmbD2|{Wf%bKB0s(=7}9k*+Z+h78xejEYEE~Faj`U2jr(*KDF;g-TZ1V@M$e#bS| zX#is4n!@A=Y=8lx!c%F4!-4g>*Y5lHnDV!X>F zN3*(94W17WFii8eA)5}KH8rTTo64$A%H zM5G?NX9GBLjJ!-k=nzMse+a4}kxff5FTR7>L*WrFVYA;*K}51hAr-GPnXmV!Y8elISmr3e2czj|^c4Ix){rhC zn@MD3B$eGkWQco(RKy9_f$_Lf!#(02+FU8-P=_iv3}hIC!&86XNLRC()%f}WB135w zqm5?Zq(bazADsjBS|vWAlxeohP&GG>)Irf2xEM?B5nF1(lHDf2hXKis-17Kq>5 zh3+_e+^8wAR@S!+WG<(8!z%}};>FT%w|$=o#jEqf9L{8|WE7s%6CHn4Fe5ptL7S z?Oh`?+1Z%<#`1#au{A+ibM)XG`)eT&CU}wQWy4fVVHV@&8VDeT@5vZqmmO@j3<9L1 zIpBo<^%KQdUBpvQr+3?q>dDsOnx&Gi$>$V(mM)GRl08;k?I0`TJzs5GtE#_7#o?D| z-b@??m4kXe9^xVk}uhv4w#USzVJ`k9y1fo{O=dchQ+kr0M^p`$1{UWwa33e2ZQ zr0nENY5kyJG6cm?SzV(*|DD0BAQs7@BEJV99+E@hKgaOva?K(2y*J*?OryctELk zMa5P5gkgBIx{F6dwn`Zw5-fiCQH;)8Yd7tW_S%KXuT!DSp&|;6Ht}LfnQ9|*{iRPI zWSB242vuNxxRs^%%DB0^>&o<>Y4AnYlVBcwMmBPB5(?Tv8LrZA zFQghKq!uATpuhHHNaigvU9iP`8|sf9{sB&OqnL}0Kq`1pmDsKrFWg?+)o|7B#zx)= zwyqR~gNaxXeMVU3=NHoUONatHRML(jNtcY0<{zRZf8iL;Dnw8xF@b-WefF{B#sjmN{+1IIq?`2Fo3yG@UM3B>ftq`Kzx`#nu5gNzLpec z*K%RHlHfp*Ym)`Pbgz5!Yr*m`yvGM2IN{ht*dR9iSNqT070 z7(e;jBFwM1f4UqW$Pfsi2)xd86V$KXETaCcsp9Q-2yBx1&j#vQCz9IVS_ zXzViAzocv%1qOcc>J1i|sYX-I+xCfEM*Ny)?KUD=WemvMK~t-OJ@v@?=qE}Xt{K=S zQ_vH)(>c<ed9IZc_2U7`Qul@kpB+}Bn%I6#(FFtGAZai%lh z(hM)l#Y1o9m>2#w&FHBZ(nG|I@*@>xFng(fiyeVwJR8^OJZLa$Sj>3!vFIML7YUIN z{j*BaawqzMaxH3_a@EXA7tR1YkYX>gH^kZ4V-Nq8Ywvw#=>d9QwU*f2Y=7>sR4j-3 z*@Wmnd0y!-oooD27@z5SO720#8XWo)RjZPfyMh7UXLcd^T1Mf}&{_Unq0o=}w|F#- z?xEVJ6yC^uFZ3AJ)G5!@ETm05xC^7qtnM+yDaTZ{wH&}MP^pcXxu$iiPG*txvsb(M304xxp%i-W)#wz zjjh0HGb{M(!9#UHLZBua&xe)BRm?e>a41W7bDk6+Y!IN0ezq~)s;Pe(p1VMl|LFa= z`SU^(g**clbng&P9VHl4*a*HO_!eHkZT^&_NX6salr}p{2{E>SxRW0!#7QYcu&-8o ziZmR7u<~074QdfnlPMc|OP%AMmIgo)lRdG-PLe^v`%@culJq&u7_!q0wpbV@`sg$6NcVFjBl()x_T><%s zU;KUeq+lDwbY@y`BpQ#}-HJUmI4ZhD(cDS5Wh~0z+zUNVgZ0TZ!*vc)ui^+CU%}d?6NID%9<^&UZnyH!q2|keFe8OOP zgpOS*_b1cx5=6O#9JP+Q?zGG_^bqVV)8HLPg}6fWXy`=yEaSKp;f^%z5gOY~TAlVnO&qA0!u?gf^oOt5XT>YIz~3AQf9)iK zg@*A5pj`9|pmWfD4YQW12(2m#DCZ%dn>hcm z`#*#;)j$BV(YG{3-_rbtAmQi7KR}86A022P=SV3(AB!F z4etpnkrn*K9C`nBxMjvJ)dG$8@hR=RZL*sKCDS6zI0%lk@;o zcTPoBkm~E{M;y~xVT$cl2P0$Ylai=C266eoW|2yQw?jq7q@p_^vCjR2C8`47<*cE!{T!-pe%R#iqanqd#&h3<^;F$CWlp4nb1yh0vL2{F z1NgVfi2%HX-)Jt1Z_n|(bNxuoF&z$Nu~mkz|ZT~0;qdiTx?aDdk_VZ z?Ua1kA3>Ace#K9!K(PKxtR+qBL$^wNdZ)gU^b(q7ZqtfQx580S?REi&KqGOCPtCn| zIh-yP>2h8NF09h4sV=FDPTiIHy$Z>lvzL3X+ylaO(|aNJq@<`LrQ`lA7jRtXhD@oP z)P+JdI{YEuhfxX&z951qz^TmTI5i2Q?Xcwp8P(c+XR5^A`V)vUTbWRVnL03WIfqbe zAg$GGh}8n5#CcS^b#2)MJ@j+lr+qWogI)7)I}^P}x<(YV5@nDA*c%rhpoqLE{P9(*6Oql8s^x4mu6uTMDu9g7ZaK$4H&fg0lz?ato^SWX%K z=)R8zfFYEAS-2ElG?&Z2mwH$X6!N%gn2QdkyBjB32N;Y30oEQDJdkQ1y=h1Hkan&?KfWi?*Xc6-_2}b${ zrkWm|3t50xiMLP&O|dyyAibrKVFPhFf#tkWQ26Zgx+ATB?0P>AE0o;CHDgPmGzVR(Q zrj*HN;1DnwfOXK(TMOB!=urBxHju%&{iw*8fDb=hvJ(J|pLm^u)kNC*IQ0iaS~z3BdX z696Ed;sgM)aRCtN2v{Nj*8*I3&L4jw#1`qbA0Hx}aPQrG0QlUXP-gg9>F}fhg@{_% zkP`!cE?3%k008Wp@4J}g_pJXz>EIt6sF10Kw>|I_1jc2l?$S!q6DV~Mfn1iid=P+i z6c^9fjhC1{w0VK(1(8c5Cok_%CsYBJi{{zY*|o?y9o@YSZFFQ3gsJA1PVZ%^VCp!AqX6C$3&wRa2)0HlS27i+5$h+`<&a8a|65N;ITvw3=z zvCLNn*mtLb+An$1>~J{UK$Ziexu&|mjc>&qL#OP0g#iK5TCQTr0KZ=wltzyrE^ zAppRn@4M7uAbFAh;ehCBkX7l5VNh=rgoDSwDMZ`jQigC6!U~k8f0S5ObDdhV?`TV1 zqjxK1j|)nxgTy-$Z}j$E^w~7k<3X$ETF-%s5<#y_p z7RkY6_blMK?aG0GvPt#F;XHo%cUZ|tkZ0wET-j~yjF~(|t5^%+M^bMBR2$Yq-W+A; zoH7Z<`Td>>b8)akl^FeeG6YBf$dU>;Ev6poJz02)Hq`^~_Z+^jO*XslO2Ke~zoiTF z=>cql<^YV--!pqC)RhAO53VU%p9{YSfC2{2e9?t~K!6=sEgWEA$!ye2kmKb(HLlyD z_H|2Sa2I-t9e_45ae`YeQJa0!1`(sOqAZn2oI%|whW`<#o5L~);hfT&z8{T95A=cW z74%AHAw#qM{v>vy?>g#!*OBgjSf&3Tb)@sDgE47I(m)Dc*~a64bZ_lgdOf5TKAZ1_ z=}W~8WRTI^;8>nGMF2O{XU>z03Wtb!BY_+f)!A^I2_?z28Mm;5>(f0vLJ^A?WDEp} z2TrWv&AwbFkNw30*RPo9SK7%#11jL9#&BGVuZIeX4hcC5UT>f3=b6ofgK}?-YUO4H zW-U+@!mTq9NddS)TLu}=`X-0`S~&^igiR5Q{;yg{?EU-SkDwD~Hj4S*9N_(SeS@I7~a5fn%~s*rmk;sV>23J{~Hm^VfM8~F^H`$A&E#wSsm zZ8*l?B7jr*oeW=|Nkr~nsXiJKlL|YogmeaWa5>M%mml3>>b{B*0vPP$?=7Rm8LoL& zQ-FR}ERQT=7yyVp06@_xoE7!|(Vukxqd$Ru|Fwfc#3r94=!S?hc!*);UFB|CK@RR< zS#G<@q16lnS$t!o97f>#lx&1>u62x~a;-PLQQH&f1h0oKbX%o&>P#`h3!Xil110f( zaWb;WI8U`|?mhDfZD|iOLu_E5sjZ&5v*9?7jA}IyaqUH>n%oc-6HtZj>ef70rY;!0 z2(%k&L=j3i^xs~haD+%B7b!k;4cz9%T#9uVr+Q=*C7)lCG7UI8@P`d=c&K}l(-_Iv zq0DXG%xgYG^GCicn5li_vln=%FKua5JGd>)LE*Rbf1(Og@q)9@Y^%RS_l#A-Sft_4 z60DfQN1Jor8|(X9YZsQ*Ijv<{AyLZs%odWtaEOz4H?nXeBHtCSO1yURMHwf_`m*kU z`K9->)VNjfi+BnySJ`*^*JZLJMw30>w|CGlV?DslDQpJDwM3Q*g##W*2U^;SK%NsA zn2lzjjE_W%vrH-=G)QoFR%2-UMylde*Yp|}bx7H^B_+l!1~~3v>thF1ul?1WggD>i z@`Jr1+B#nuhI7AOrsy^+Quo>Pw90HAjfmKznrzA=C@NEZ@?pFNKa{y{Z69IEknbdt zV)KYFT|$?S5gPmRE$=G1wHF&k2dQ*Qo{-ei8x40Am-98dKw5 zobtl*;DNk3_>Rz9Skrs#k_PUb#`|MK?OY*~$|%o$c{L{I?9X+dJ4hdYWIDrt$xwL_ zb!EmR^FwrdCLOpqF$PUGal?b4<d5kfxqENdNpLzzCTv4VHMx7(_cohA;ETR#*QI209d2>jO zECgHU_NcsoN*INvArnH1b6QJ4zxE2$6#;SZI{LxKdD&fiw1Bc0!03NnFkw~Ri}Ry0 zg7NQCFR|%3Jn#w7iKblA?ao~2g*6dEAn8swXJ#`BClwpNX?TD}5ocu00RgLqqR|?y{B${1NPGGc_nlg_Jdqid4)0=O{^WYoQIaz?3GTeLL zQiNs!UFz$TMM4>XQ%u1He}N#ZD6%*5L!SA{2i{?M`+@4E|N8M4)FTXl*8w}NGFg+BiH4qnK+ni02&p!s0WIcXP14_#!Tb_&&H&ZtEVEjDbOu z#O5Tua4KQlDJU8xx??wG?6vP&2_wN%v2o3FnhWfe&JO2a_K9LaB{=xw#87i$pr6QK z%fgGbHVL3v@Bx;#6KKOelty62NK|Ys&?MG5{cU2518Yqbypjlx(UANeB5v~T%%YkP zK_ax2>j}B_zb7&j1Q92y=F&tS7iZOcQ=Hf=%{^T>tv3&5TZ&-FlWi2+@20WX;9_mb zQ{}PSlZrY+6koqW8oW@iA>!r+9a}SJov>-RvGDXlN8qE1F5^MAVt`{=S)h1mhS7`; zXfK5k2+Ub*{wF|BS3q0sb$ubk{t6ig#;t|1H>FZ_GLTG-6)dr{rq=b21XkPH4=9+Ll@@yWk*WpU$P z>J`pka1*GhD4FY^v;((`Fjl|h$dy&@64npSe;;qqYtonLYcFe_=HhpxG+-iMcDSrYh zamFCgN^j0MyHz>Om1rK##(t5e(7p& z0r(j=C8aFp8(e5Br1I4p_P#VmD5$h`&(~ot&2w;xK*HdPHepOwLB#U}Wn>-V+D5nr z`E51l_4@JMX~IHaUKE1`>Pv#`B>GkB!&8p7SkZ4s>wa@}LkkN63Ft%IQ{or*5Sb+& zmxA6s{5PYt0x$etbIi8e8;V{+4vln)Y=*mFST1yS)xR4S{#!*2v$e{gmivXGAoDd* zOY(5*#mYU(C8_y1miGCFOWoxTo(VheksC0>xlOu#HT`J&kJ?AlAjEp98ZZv|)r~AS zTwqW6(%gOub7*0)>P$Era<8_bA{3m1w)KS6iCkE(*Ae#zhiehf9~Tg@^lUzE=rz=5 z-ZIp2yRq`4^w9)y=LRhSAZ6ir0q=9&nFG9&Mg_=dDTDNc}0jx~Dnw3!{v2>m!3F`9^e zulf4Ll88GdI*)1^q9L(LeraDL3O&R*A+d7<28?3-JM|?#9#ZmWru@)||ftWE?hduqF^8W0Z@CywKOAX;LHEY@?;`}jnc2iR0Rm1ol#0N^Dlg0j;&6l2ML+;o?a+5MVk29^i(1wTK zj=NO)W~7w}EUArwD6Uv&OKu0LdnOrW)&#*446i#%;uDj)R}cj}yqH*`#83HB8p=^a zYqYqVY@Tb`;)S2P9`IGXgC5IpE2@XL=%G^1C88F+M$hexHQe^!EuvzP9s)I9RFSn= zKMPz0M5;&Wr&bw@(}D1Xo;s>E0qw6T$sY)AlW0lmLmQEDxS4wJk`>8iUP|(5v!Rsw z-kUpo0mS@aeS^lp+usGu&fHknjFO!@bZ!!Dj-REsgwRt@J6gQ%IYc1BLNEn7f<+FI zIp~na?Y@aF1AjAM-;`u*eVQ4XZ|>pB)-_E7p&aBts`QvU#y(;}2gL$%*wDVz9cjs^ zd6Pt_wuHc|)H4M%Y>wc6@T>k@aksCDt50Pu@kP0P`4txJ8-!6T{?r4A!++aM@jyMa{i%Dz!egv{Xycj zq2xFf`ie%IO6>N5d`9;Kg1kRFU(efx!iw3WK?%iwET)xCP{g6|bmwUY^?Pm=y5~we zgBGvbhr4{IKsulj8Aq7{-9XHJ_};B^&Pry9&aWuKdkSj){*^ z;6=YUqF-qUAKd!ux5l-FO_40ql=fhw=jcOx?(HzDCoSPUkC?ehwq{2wzdP~uoZRMLow6Sm~Zl8WO6;PqHfjH*X z(qmO2W7?;3`uI5}C0>Arh|4U2+pV8kBXx4Z`KytEUG z{_&`L&}a>Dy%X=Iv~2ZyKX^?F$2~PN5bp*Dtr`$$;cEh9wtqeBn*=D5^y3|j=6&xD zimBx>k#~-+{FTC~LhU@)$8)Kkwf^T++%a>e8TGytc2;2Vt;o_pgd(Cm$;vW2q^xY1+xw+!zwJHMwP_5a`Plo!bHA#HejL)kiu-W)fiYtv;d?jEQX7PCDu}oM*syYy z+TcL|(U*GN$#=kB!bxvQ^cJ^q)2p#Q=&t(gue89vCYx|a5G*5En2KZ17+q&z`) zW^Be#stkrO+XICJm^0ra;;@&VmwJYL=UV7Wv7p~ZD% zy($N&qI`C9R-Bf4n7EL-yDbanJytD>o%OFH&G&vc>>0JKu&zc2%*sv1KP zxTsix;@Gp$sO#^m(LksHm$S0l$<-c7nKH)E=5U^L+S$_+gJ8W}45W(kc*a!3foNQq7&+KW^4dd;{v?Ek@F_owhNh8URgfNDOvCj23$Y9a@W002b}xUS1yH^2=xz;t6M}KHlE33 z+YI?tNu8;d3~ic#b@lP?FL8u*+UyR_ ziJlu^nm)_OCm~LVJ8&Q$6oWh@&Z zxk4DV6x%qK=}|~h{BDgGDg0+o9cV`Viv=1=#}Rl76Mr`oUoJQ_JEi21SKmPE)aePo z@UbrYBQvZyD$|6!%5gEi(Ju2TG0sP$MGVb4?kKpdLYzZ`hQ*|+3184Gvb=u1hCLFu z{Ayi^1B%~dcN>w(U1!cM4CtFAmx!as+CGt3(Q3~ zX;B4l@SZv!cAzTQC`HX}6eBAd1g1xoB^t3G6dg7pv8;=F6Q*Y3HMNd*Vy({&OE%^f zhzHVBr%m-nv>IT-7oG-=pp?_63wy8t@mP-#(4%|8l_32Z`eJ*Kiqg$@dk?07gi8=D zf}2nRe>A1!dz(>o3;#*Px#b;g^Y`ird`n9spr^-A|G~5{a1RxL%k|f4*Xm?JD+B-$ zl5p`a%G73`-qzNS5n#+5dPD?-ty7|rd;4P)JG#XI7vH-LE0`>QX)R=e)LS`@EP6LH z!TH$Etb($eVP3ld-!TvTHzXM3+k0T=%-Byrh`nNoKp^KM2W516kS}s^ZzgQtSh_QI z5%N0G@pkn^@{0Ye>pS#|N6uBZC@r*$_YElBhReR1)R8^!F!k|H^z zuy6uO&rMD}m*|rklSS zH3JgJ(b?K+t1wy1GRdbEsH#EwoyxI7y7ON_EsfwwE0fv^EjOW0=YxH6C^c4z%{k1^ z+FY}Q&(NXKV@MP5$hJKfKVp)Il)^t)hn$B9o0=@Ga2h2yKM5%IseV*?t^9S- zjE3a($s^u6B(eIo>szj9Wj8OeqlU>a@SyVk-S4b6!BhC;@6|$`_sR!&OB`3sBkAKI zRrs4a!Dv_Iy@M(`?=_J+dL}#F{k89W9G=-1m~wsDG_~MBNMWUvBpad4Z2Z94<;wo{ zp}j{`kbiA_d2>%t)}F9=+*u)b(WyFDE4-TvF`1~Us2gV+O21<|E1V+7j~MWF4~!Lu zmY!VBeWNRwcvA2uZd;ddk&0@*Jjkp1BFgt=2X?U}5goIeP{=82PMYTy{NTOx`h)E` zM7&KXtwb9<@ode0Y*&Jx*GW%M1toGnkbbi&cBK6&W*7cvI)FX@63~<~;(*)EuBY-{(XTUBeWW7~1y}O&x zfDBdb0B%r>=ObE4y?8H~YOf_Qa{b=rGF|>wqi|;TxXayT!i85`Gc;-!v_{~J73Aif zb#jeU(m@v*iv_Cd)?m>mJ)xH`pe7WP)pnSNYvoZ*ZNAQWL_|wI=z|N>O*i8q&x^<5 z_vuzRW0Aj3oTP48)Cj*lsDik7vl*;Yc$?mJSu1a5cjLUU856EE{q?%q(Fw~6PA`#| ztW&XPvy@_iqaXVM)A`yVy@_F)+ez_WGte_n+8Qw@6}**t89~L#&xsq^&XV3|u@o?jg$$u`_10{7i-3 z)ALqaz+Th0K8wIZ%g-7Vq|g2P1=HQeW@l-oK)8zV4?YPs2gw0U= z{`P-&caw=_x9HPS(Vvv?P-phI5n%mRf(xfHx-rKM$WK3=9UlWm^Jx}CHzaW zxP2ZZ-Sp)1$COgcv=>WMss-}ny~5%mjT;w!PCnM;8Stwt1CkWc#7k8Y9alEt;1R#&bDtw(V?-8-w8j)+Z3afe~FM_ON()Nv5SUt~4p&5Or8 z@ystj81r-%E+9Wlb&~;po=(H~f`Z0@pg%h?ba&0|hTa{jw zXTd{-Nk&{vYfiiq15~l044j*WhHTa8qoYe3x(BJjs*Aer^hY+mrGL@az!sjFn1Yam z7JPC?DkceQ+NGgcm6&Sc{aP!XoE;)LX4}*6k6}Sx23T zh|59T#V76a?9CGmO}FSOgBK8R5ZSY4xUi1aqYx}&0mPNDbsmGZu{ghQ0>mBf2So9w zC-3}owJ~0$58vE&TM+DCl)J{X8dUa(z|{&okNmaQNLEP zgPa^|T((d%+()b^T^im9_*^}(!wpCpk$V*#p_toTHwHSQmXIdt78)<_2023B$tLZy zM)p4ec=dN4W?Av1s49xb`P>0i*A+Wu`Aox5lnE2n(tBHsYT8gd(QcX~mcUPcH=KW? znvZE>n__IMB~g=1On~_%m9AOUFuQS@ z>_0a~@ky9Al9HXt;=}DG=1W6F^-)0P(3|8)<=+z}nq%(ft9)|z5!#*m^TXeP_zSuu z|HaHFc6mY}uAk{oUlOl`q+-9){pOADU%JsaYY}X+L2_FZpM4bG{)q#nUd@pZIXE=n zU;q@=i)`*O;d_mN9u)-_KG$R(sQL+q7L>DOX`Ig!;tm{e*C%ZP zqK&>LTy-kmh-R7hNvpW;o+;3Yn%{4z#w|Ce%@~CKxc(;pRVp08Ok%w3XBNKt z5|j+lU9Dq^yTUf?$=Oi>*1@#oU>=efH_jq2<(vj9HZlK(c&|KP7NxcL3UB=S{My;) zxaGBJ;b}?$YvGKTZ>E>=FPlJCJmA-?UyH9^cx+)^K3Qe~<#@CpSb!kJBF68~sdUw* z(rTv~t4s@i3hY|*?trTz@t1-!Bk6`a#Sct$kMm9{ei>xRRD=y>b?gQ$O9HbGe1Cg( zgZ#Vo8bM1Y5N%$CW~(DV%#i19}f&dfo|jqU1(YHHj)vopaU=TwE*CX z9^}7=p6fe47Lx>Nvlm5~T!Yed;myL!)DekoB`#%Y$*vD@feDzo#X*X(hpy zW|x_=tf6W;FsuNMTo2hgIeBda^>`GnHbC0CpQWKnZT^>%)UOQBnjUA8b23bE@X&wd%^p^mE_hR7R@Cfu+hDnI$F_{sbo67VAK2UFk|~u|hPy4k=F!mzK*SQ_7fS)P+GL>k~0zG??*X8GcH`h300^TS6KCo3EB*uX)C-S7vYS6 zFcky3%@x0qZTMomfA&ko2`tV^Nh7~`_h-{z<-aP6=$Xe8C&6A#3-&8*ol^a)%Ch2} zf6Ewvc?m|Hnyfx69wn+jPsP?IwUFi0q;55fKPdJwRAzFd20rC-O=nUuCRv=cY3o83 zqjd~lu93i!dn_x)WML_%hTquhL` zsJF7RTcgX#gej(V7>Zb-`?B)4H;`NFKKPiEIrro>3XTRjiK_HvvVM*6H=^qy&oCSc zLZfsR=+Ky8g-n_c+GdB)G5KM=Q&uI?8!^bLWssi0`DQt zOI^C96q*1nwCF`1SI!%W>l6V{SZwttCMvF6VxjTsUh4Q(s(2Z0s-a~yT}eCV@0Wtl zj3lkqEb@D9!k0Bwq-W4yEP7>y#UcQYgENY$(%?udCau_sny^=~(Uio`w9rAD)CG_txF?8H*CH5yiHu=X52AVH(1Vw`^bUcNoSAUq5{7!!o94-%>qFb9U;#H*%4*e{=h)USjp{b@ zJ1bDP2TG@vLby8;rz}4-{f+&V&?CU!3AG&gcIgR#sL6F1t`tw1neX%p3;y4$Bfl=L zJy@G~HsYkkdkKj>QYi62o?s1wQez`1bVuAgO-*r47N$@8s1Rt{O=hfPH1Vodg}Ze> zaU)uP%vtmEA-w^M?>$zij(Vm+doaU#x^xyV#7K=q2l<4HBs~K>Cq}(UpL^ht$}LT% zpqz!9^UzO|{se21ahjjJ%QF`tS0;B*L){^JzgzJQd*@@kj3}5P2b|EkJ5m zLGRMcyp2aHcDeR?T$Eta{#HL8*3?~=d6e11o7=`wzE@TCx*neiY(68J9iX6|Yf#yj znN+$=aOQDP&x-v+p|UN}El0WMWT8959c*?_U(fz*>a){`$n`k?SLd6H;a0PiJX6>b zDvY#kZj2thYJ^)OkJ$_2me_XmFrR4cQBMDyKH13b6RlSG1!@g^Yw;xp-Ryx9QnYp~ zi^IyMD2&zKBO5fZ)O0qq1>syX-qxg{7SvZoA+fO71`|vzXNNo=mBHRZVY?xYifUX6 zbFW&iCh6I@kgsp2zjJUFbU1BaS$G=nr>JxnSn=F?a|!x1g4bI>WcLb~hHM%5%e@C` z5k63CGzyDC8EAdRw=B`3(#5Zg5V^e^b37mN7D9Vg>@TM2?PyGv{*Vt1=(?Q18--R7M75Gh^a!H_#g0~uP3?}pv-fBEytH}#hjDF z1X=k0wge0a2Rd5o#K=og*AY#4mAHe!plh5RU^!++6%LGHPX0Q>YHz7bO7xr8D}DRL zzdBJ9B$iI?3o(EN&1!Mb5QgO7%E%1#^vc3hE?D@M;G4` znmP4t)#&q$z8Hk5Tx)75W9mqqfXp>z)1{7cYg2w$GEb^qKabc5>&!P2mX9o$5j-Lo z{k;r~l(XKf)VjDSi-q5*?FUYX0M(QsNI$##_70P_$mZ1xj|#G>$b8jFi5I}hp~*Pn z{LA@x*!0rxSe4^xSAGsXO#K~xucrflos_=&nzs7`ii4N;N8ng46g)(M6BWAZwwj`h zDm-T&kBbpFIPjH3B+m#o1ALi&`NB_tIL%o>>Jb?0K)>V!3;&1O`S_``vBaGZdH`=O z24du7G4C^@v#ZV|uJw!PEtXYFKH{ z`!j1+4p<|^TFb>Mk{PuDG0(lrnW04u%i zg*cmJHTo+WV=zIwiM!#CHq#X7wNqX{ow{S!SOW!)vCi0W4&&j_OKet%5{;ManI5Xd zSKHq3=ZXC>w}ib1-wLQfKd+>YM1gXGH#PoRDt%t^#MWxz3F$@yySvv}`lnpi>6fn* z2_R`OvNmes8dUnF_r;Vh9U?^tRNdH zctmr`eP;>HMVk=!!mYYb^^wn1sM>ZI5RO>zabvx677X>YbRX=^+AgUWfh6alg~m6T z6*7e36zCVK8Ak2Ma~_+m5W1o=io_^0 z&K(P1bz=}~z~Y)CqazZD5f_P>q9eP5FaWZ7-=-Wk2G`a-#X>$91awvBc;n){oOdhy z2iQEMYC`DBaj$lju0e?2;P;va9Y2)BGQq81{%#bL5eEq?HNPmb_v?xeGW4O^RdG;% zX!nQbCzs2*APXnb%m^Uk)dQ}&60}@Qs>gwM;DR)o%;%71xQsu&xmm3FXvEt)kOCzf z_#0=p!8z#P6o9~CCtE0c`#Xagx})k5wGjYK_1$|s4U(7fpXofs5axrX}Fe>?~u?+3vv6U(nkC zBbETH8ZulEm6s|p6eGqS4#W-;ys?E%dZHEdRD|wwKT}$+x07tUYEuBr)cNP%C`jfG zwv$w}w#D@AdeWE8m;zE+`gt}4>A1#nW{-HWf~fqw$AvJ+#l%SAF+N+bVweI!)!GOB zo8kkLSZu+r&so5JjBuNSKU1x{v^?tfVK>8&xi!#0Pu^r0%0EumkzBV=?h5`)*x00H zFvhUN6Le$>-e|lrc?b%C(c>fMY`u_Z4QFGer>_w#pPGR(1Z zAVS|ZfVcpHEuas87J{d5P>-`y6$n5 zFqMSVH8cMnTa<1gUKpm)U|u46HEFX-_+DAO5y|@V@r}Ry6zI1#)WjzSaQvhya@8~w zpuRQ*1jwIY{nb!a?Z(M;{0jwDd3|EQYz1ju&4p);wyEl`j8L@q4smamg>xF5wZw?9|=yYYf+=+@k~(-#{W_9c}t7{L3Z|ao6F3?1Qd1K zr(e$zat07o#goX+uyP)| zahoY9%Ft}AR6JJAhHUIN<%l0qV2^=dTS+Dp)qx5~7@$Btx7R`i_h) z5}{te`u?S)Er5un`qs_R#1#P2u^I@-qQt)bworhAVgaoB;0x^Ve7V4$F_p#DhjL_l zGK5Bds36ePtk#3f=vwSuR$WgE&^qwaSt4&TpF8J(o1AcH*sIKTUq^nk;^iyB z6LWx|5_K(cGYINtkk}Gs8oRKNLW14Yg{&4@O{wL8Q&^u{tSP)6 zzV>$aAV6p*-|&w*e|U5UW6SyPebI4076Ih=%5wAPke#D%TMnk6SX-A7bbN{4zpvo` zJT#~R{;d0h#Jd||@#==zMbQU=CptaL7AjF(3 zCM0D3T&X3LA>j1f1PM^0oWFuz$FjX~<(MRqQMQRRyl{vV5}N{9fTrhxY2#_i!k6Tu zj)8!9x4&Bv@i<{b2qf-7Qh}kcSpU=H`ot-F;eYZOBlQU$ZA57*qZvy`U*%)(H^E7BG$-$b*d?OUhvIrcrx&$ zY3LaP07!Sf#R>Qp=RXq>N^DoqAi5wHRa>iDefjiAheu0;ct{w)d7=OwnY3pW)OL2r z^?Y7Px38E#&Ck6^2At|hk{Yb^+V1IZw#RU=id|5k&B>mfqcHB_kGcU?z2Hn#q&(V* z{b|&V37&IqNrifniqk%*#WGGwpK$Xuy2w6)h+WC63on>mOq(+D)jq3Q2G`bb(0bp& zZDh^an?~-SV1GiH#o&=35LNUTm~onQx`QFfsmlsO=NP~o$OyX#6SwH^#MFZArR*(A zXM$bKK#|*vK!!ELlK!eUFYs-)h?{F5ArfS10VY!q0BLL+hEbddbPO9lw&kl9N>sju zF_;J-i4jQo6oAKM8r&-Ok}(U%%n$f(EFU*_piqe}Ods0X`H5#QG z6EqtcDJD{Edg;|QD~s2-5S9ON7zhOT^nXjx2a=chpSkGU$Hk9BN}~NUqc*T2%8ZN) zLp~X2W1>&B4oC-zBO4|CC06hYZ_G)AxyK@}*y(P5egmYP^onb3$uj3NG|uN2<)QQw zDz8<~7oi?V@Pdq0IlBhsp*`XNRod6!etvcZdM>tHS_qj3*mOe=S5C@7*Rd&@4m26Y z4m1)#xyvJa4EtA^6KJHNdtIS9bLS3`g)TQdNr!7S%W~ZlwTO^)Q!M_qFH;HXS5hk=DQGEJqee%)Iq;6A{{wc@!_6D78Wf zae8ycD2tUIz-s}xcx^q9#AhQ7tq=0^wJ+)avGq=2ngmO<=-;+&+cu|r+O}=mp0;h< z_Oxx=*0k-@d+&3;`*Q26hpMcHs>rH}jL2MT1*F;O1`vx<>yK!I+x>dNpS~<+W2532 zL%d7?I@m0C4un3*I0?+m0GO_r1Y=kb{Q`E(hvCFHVN`P0cFk_OyqPHcrBQgH6#(on zAWn0d5b5QYd0NYw+;a?kd1|yPGPhvkza|;pB)DYEj9&hF%@E&LwDc^Q-XA%R>TKF@ zKt5tyf%@)Uy0Sm29|E3R49&I3c^n#jt3o2G<55`c5t@nrj)E}wC?;O%cMVcJnajH^ z1v|xLFMw?KhpYPIn|Ir6#PC4|LZ%IzcRxTj8^uXbIzr@N_sv#07-~$zz@p5cf zgFK0Ipi(fpeOkm;b-;LXFz;3trn8|V6-FQqK2%spF!j5di(k&w=g_z}(t2-~fzQEZ#m^D9alx&qy!ZE1AuVFIdA`*re+HJ)B3;X`5P?4 zRrdT^6$A+2h%k5;C{B)x>xL7{1U+H%+v5Y_h8b)#F3O>54!5=;XdvbZWvz!73%Uil z$31TYfSh;-P2+GmAc7~f@s1!;QONH?G`YO?;hwCy#t^{owTctm` z0LT{(uVyo(exg2)FTc4I7)#Y!7zMiI39K*3Mg%=(706-zU=*#Gwcs*VTX-}`Y?Ln& zOyfw`bB%532p$VfS8u+TM)5o-j9VE|9H+yfA|N$U$|!^jKy;$4#|w|5^dtId^5bCM zg)%b8^8~g2xBZV62Hf+XaKSb_;jatqkhTMMsP}Ju_GKS60JLHIV{9fF0W}byFst); z7r~$0JPH6TSZrZ%MNBun_&i6;v72W%E6o#C9r#+1unnWmVNax@;q+D!?_@q!{hSRN z3Z6m}-2T+_1Vl1Lr)FG^h|?rWC8%3;f%IV9DEUzZ_cOH*Qkvw^mCO5Pbiib=r?(H& zvqS6;fZ)I#=3#G3%~r=BTkM)c)(XJydBfBHU>rmoPo76jPYzy$vI;}~0K8~z;-sl7 zALMzQ=Z@~~1<$bZ40B5;xqvWu;TYFcXc#=FjvxLO`jTF; zG90NK8y>y^02aIislCqOf5?_Q|DN)q_T&jypF05^etQ8!c@@Nst3R=Cq9tHL9GK+a z_F9%hun-kKD=@62M(NSk*~WmU$%`NW#CH)V4CocN@_sg*0oWH%T9+0;tj7W8d|&yW zpa9ggXA1Tiy#va4Ey{p{pg#P#D{G@XJh!pq0YE6;EA3hT!0iam`rUu-iIKOn-qhh$ zj(xe1Qp{jh4H^8Zs=yMX_jj#ymx-sy?Pe!7%r$+3Rh9e4dFMis*681yONSPmUi1;7M0guZUs=tL5Sl> zaxksy`VB2Ugmw|K0cwOo=~rAnM@iiUT%12}49%V@4S9fF#({MO*5OpQ@y%=SExuNA zFHo2+BYor`%=AmnVG1k&(6k94Sk;#S?D_))!fTcMft->7mag^yxxhoD61$)`fT<^pAh*q?i~3H2GL@7!nF{XEb(-wxe`sb;&PMPgc6?W zmHj`EAp|TJUOtn#C$A5YNFm5EyJyx67U`cOqN-dnT+c?Arj%CD#zj6aVG`#DgVU2_ zUgfC{oRmaIvCIP2>OX}O*k>!WTXq3u0Y82t7AU9u|I3)QBq31@B>iB}CK;BFoMy9C z^mLM(TZ-lSYK$^K$+g0PL8T)5FhLm1f4~M=*6j3=<0{4P?9YKQ+w~at(b6yK?$=@- z1IaDdZe|PFltlrE>Wej%?sJqTNARxiNj$5Dnd=N<)iug&qdsYw1oN$NeJ1GmF_8VE z{Lcc7;m92+vzK$R+1Ih~BNYMcVX%rWr|E|J2%NwdV|t1cm^RBB?vt3OR<0!o1uw0# z$@V~InrokeRKEBK5wi;V40lWkBocmgf^o792e6+zzXaoTIT^3#hOk?jwfwpc9x)5| zZt!uzM|c4MaHgdH{LM&$VwM2Rh0v~npGbZWm=JaXNstiC zWS1q1_@W=c!AH>OZ?v^Y+I8kK2jI^GHn7A4YM8OueP*;B?d^kvQU66#<|y}6Dn(+Y zN>84vj3hKEfoE~b`SuFt&G-13?8$r&n8fOoFKqNoQ#y2iH9l=CQ@uSa4cGV zl_K};@sS|Sg9H-^|HPV@=VtY|3#QZ@;^oKci=Pj1^1rlkF$+l8cxb` z&GlguA^>?e{n&|i=*tNV`cC#`DsCTvV2)tE-R(!$0R-3>w#(sbbkOMM7$~o%zU%Yr zoTeib`aOa*9pd084FUmD4zv{a^9M=|2Cd$;ca7EyEF~M%XYEo_?d=5;*YMlTSF!iU z?L{v^{Et0A^p5fX2;m>=|7$a8$JYY<%GiUG^4+eyu=NrXSAD!2|sK*3oZ;&z%heS<~ zI3SdNc6Cdn01^Dd@*tRWlUq#4Itu{U+rJisS7fZ$iRk??3J4bZ|C;=tPWaDz|G&GW zqaXnAlO@x!{kK8L-qIgjomL?lg=Nnllxaa1Y!@^QxfrZ}DX-wOvukNBVE^5e{C46U z%HRyZ;Gg&(M}r8IQ}MqH=s(f(#4(8}!qH!)zf=%n>{!PH!ax$yaU7vmZ+TUMdiyAC zT>iN`A^(^$N_70}gn4g}3=%jMgU_s!_EC)Hh4zWG!a%1S0!$)MBkEPEU~eFml&67w zW3OqClPyjJ>DMzz^+)(JAaAR%{e60#s0h{iOaShC>R3@7CD441{Lg%1!vA*!@l$Y_5Tpz@4gg2_-!^mSKp&Sz0HE4BfZlBY@m2`nXNeyD z#InZykDI@&LVRq+>dOD7{m5Ee!v!(Xes`cx_)pq5=q{q$M}V536L?(YLH^WPjQQ6=Eneuy#5zU_i(T4$?aFFfVii|sDzZqK_{sVSqNBJ5jYVpTX zV4l46?)*lK-2IX6SvLLhJlsN|NbsI&Go;~t>Hl086_p?r@mOiilQr!4kPxP6e@VBma0;3;72h9&{HC<* zX+a>R*z}ilE7n^~?493$(84)7H}6%}J=H^HAPL*;ynHlPHb<-BHuBMvnQRZz4rQzI zM@vLHK87K&espI$@(Fxm4r;4ZDjFX{^I=3>k!Efu@`*IgNldBaOw$?(j7B&N0nLsU(#MPHEormg{jEY@>0jCpj5uubK z*;OWjttlk>Cyn;ZO?8N#IKkwZg#(Gk)S#neHBgXqgboO$vp+>w+p!GoHwF(Ao~~qiQZ@g^H&Y-v;cR-iOd4piiy$nk z%S?@K_^?kIwg|PT66i zQL~DtYaXZY9^F{d@=(uIxWq}0_r6Z+SKP+TakR9I-zA0P>;vb8ope_LLHE#Q!18{u z*&U6JLgo8Ubz4$Mx*Cj;pM#G1ybR=6iq{P>B_eWI1$f9v5-33->YlGPt$pyL=z`=o zapX@To=`-EIdG&ibMCCNhwFSB25;3XVscxE$%BbE7+mj4Y0o2gFoPIw$ztXlB*f;=?3fxH z2Sr5GT^wxgw{%&|+NbR8VvWmXHk_t)0f`zfXJ1+Q8>E?=;K!i52dTwyG+ zhhFQxva7?kq1slD4fC>j;~}7!IUe@ISal;iQAK>#%u4vC>{YJsNd5XXgbVPY4hv6Z z`5J<9XiMaAHQ&l}eAWV6mS{k<$1PUtX@OgBM_dAaNkI##MAO3wB(T~;h(&gu26D9Y z9;vNF-wM2VtahzlqF;%6s|e7A>8}TOE1tSAeik(-?B-=mc+t2#PuO6a(7{`O)f8kC z=j`F`hE-jxG8a%nEzZhlutF7_!(`3S4I9qwxhvcIW!$Br>P!0q)OJM0A>TQZQxi7g zo-I8kS>*6>in}EJ2H(o~Y~vAC8(%Upc8FXSo*T1L^zuY&1kPsWo;#zSXd(`ISasNx z3v8FhCvHD4S;_SsfF1s{1LB zst)qqeq9%qb4C91y)JNcL+rBNl1W*HJWC=)aLsTI+jCY%tN6`$0=Q!Z^81*0Vtnc_ zDkk&{X~2~f*8V|V^F}AoXA-x-c3%B@)a5rU)W8w(G@=zh_dp0##73_U)m+vx-F-9m zAC{J-iMD2ql#ZZ$w2=I)WrRWx(&da$SIsA<+Hw%z4T?=osNDNDc( zUFN=uRf`%}tQq2^OxLtRG^f-0j-|XHyXwuw5?BD^Wox6Wr#;+_rE&AOgZ)<`TW&Qloe){gjj&6*) z%D(>8UPn|G5RWC$$KVSR8fPPPVNK)9O)FqZICoy$5UWrCQ?$&$VSOqW?fx^oq?R~p zx`LDVEKfbkcixItWB1XWS4a@;Bix+^EIoKkPo-zNPu=^BobS+Lh)ZKNU9ccbk@v|N z1gfs3C%{_ddlu(@|`ZkmTf#TYX@^Yn?x;({?PuoRKjJ; zJo`2MB4Z8RB1BLN+rEJa9=*ec-Hb|2GN`pwiEn-yXb` z{e8xH{;!Tt6FJ_~$aAgN9%@TolsPgzQRW=m14|^e8Eps95^> z(AMLsP+61fJJdr1x|v5AW3K73;UY~V? zZf3SATPJTfC(Py?>|uz$TEe7l`Aa7zv96`L)zqhc031#=VJw&yR&F~ zC@TjTQDGZ%puA9VQQgCH#HfktuBDq7eyzUit#Wt3tn;t(g@#s*7lRy_QdZ^|TGkO| zwFC>vXJ;aI&L?@*CWgfq4GE{`mFKT)yN@2*o>R(@!C1B{$r$e~*|_AB0Iz-A?V=(5 z=~shjmXWh3CUZJ>IkVMaut1l508K`WBE-ybWsKtq&m*R95}==AxmhuPGPF3bc`6}*T_uis^%rHDVkDN0|nn7#Z7 z%0X`4swe{En4*JhsyYzkb8BTLL{;cf%9MfsHNRbo`DPF zyx$al!|ZjT>zz}g$*+{!RhLwCMh(G!6J+JD$`|l-+#~ZXvyrk@oqOV=e%Nrk2)p^W zdECfQJ_^;?>w+J$_3PWbB;sN6!I~5_=DHyUsNpE_uG9cesl-3A_Macl9`QO0Q$hJM z8iVEZ%@{J$h$}%DM)YJhq|6S$=ko!GSC;H`lB5L)D7EUbVdV(UHu$#Fza&u$=GNo1 zEO6tLtz&cAbk`c|6_=+>?k|*e^k*sQFKyDR#x8W^Alps}nagmv{(J4&_p1Cpf zn=@H0I5V0&XKu-%>{jOQ+j==ua}eG|V{ysJ2s#J5rMIh{v#ybkzZB|hIAP0Y;Tr*t z?SN4yS*h37k6((QH5#l(3Njmr)*qDABezdA$zTS?i9oHusny6~W!6EehlHd>90gd; z`&35)XMLnf5xnh7FD3NiwAG;{e^@N#Sd^33%prXRe?^q1>hK-To}>~=YSwoStP&hy z(i`SKj-iPepp~m7w?2gb@)DSMI!=_x{T}G~w=3%O{%zm8B5XLRa+Xf9S??hgLwm4! z7RC9hP$eDY5@WZsRY-7S_SMtV?t6ePC3oUS5$2@oU6T~&IQ!QEFa|yU0~E?P)ZG{g z*b=zmUt$480j7(8Hw9JL-qqsQu(Ugg#sCHz7Mt{o-*-NAqW`5R0FeS>D9fd4u(pDq zgAq+t-)$_Qd^V6YLu8}iGn>NzVTIdLBK(*K$oWshv|5fE_z0=ge}UCfrer z!eZ9JIKcthG1YhbYkDM8VjyV%3a`-G#8^9}|3N!MG8W=8?mx3S6uhC0+57&*c z1g{fgx~s%CdEsc?go>N1 zz1n-|Y}&kF+JNGm^6HFqR@=j6sJ#2KVr)vVS`gAKl71YhSpa^e-WI_24!-isB=MD+ zQ`eLbp0-!siwQCmsLOIcHgmJFF1CZlulaO6oQeg`605J z>l@8|E6>z*URz)}-^o7yr2OpwEUxgtFYY!s9|VFz&Zo3mil{^&gp8>2jFF8W({)K^ z80ABaaXRCHNC=f;1DPA?IvJDDm1+Yow^;TTQ3!)( zB+K_IR_rlJ{#o3cDjvI#$XVzb5q(;7bR7Zg(fE@oXOooOKO9h{s%e>;v>}f8bvGB8 zM?%l^**x8Lu3%kQUzf>qQaI_B)`ww1C?x!z;%bRcw*+Nf9e!FWa-*7wVX8QbnRhfh z36|hJL!(x&r(`!vr$IN)i$yC+H9-d>D9W*}O6-_UpzrdAOj#&f<5*oVUoa`LhfEp?Eku3q zoxXfxx~9Ipj}K)!DUDM&2f^M9*EF-`@1&k-s`Y_$Zy}ehwB^}1^P4*;BrRcfTpJEH zk^ClB5kZRQyb_rZNU+Ih`Ni`cHc>RnP^KtS&{x&ikH=`fJS}trW0k*(=a1zSre?{N z9c^mjtoBi#jL6EcVfiN03U2fD`qn(U7V~FZ-=vx+m7|sTRiaJr6F?_%G^7frUnY;N zU%m{$aL@_^J2K%jxn?j(3Y!`^R0Cc5eL{(*LoXt_H6u#S5hJD7UiW>~rY9A9lQFMt z```MgD+nh~27^Y35+k`+&>Q}8#(wLXMago^74~OYQ*F@A4!@z}Tlde229^B!cVeGS zkmlXOz8ATpU&Bu|s5Ew#2;os1Vd}n{)K)%|=6tOvENQ%rjZ|SJ92&oXv1})1w~7zI z1XGBV0r+SHD5UD#7?HI1yXD38{~0yDa1ui_=?>(rhj%ZlUa$s zHBMVMbs$thm!x;-+-nUx80(_p5ZU$F*KZ(&TvLiZdqi4ph+N8)d-TA0!5`>EDTE+- zrz}Kxel&N`%Myy>K5+5OZt0bjz5z`ng|9zjy`Cb-CauMg+;IEvqucQBiy$Upwgb6> zK`Hp%8-qy|8IVDwl6~t`#`KvV!88-$+ye4o<6Xi^iS6iw`i$_!jbulBYwVVP{N{ec z0GF+>HY=;VPWECJ!a*e`SxGHieo)TVjZ@m@R_rQKxT|SB1HmFQ;!h+GE(P7PW8!Si z5|D6Dz2D}rxA@_7*Bgnx1rGxr`_4%#7}`M$Tl za`nJPG*)dN-On?XmM*cAZ2lV@&6P*!eR!YE!zcS3&v8G9^SLiU)a7qaQ)q)AqZ7Y@QADK1-+UZUlrnG^mZ6CyzQ{K99qwvA!07ZkX!y$kQURnan5xuf8O zq3P8+2OHYs;}pfd)7(5YrsBGvz#vYSHt|GeOA?MyH2gSjZJLNo;}jm}o4|QYJ%fA{ z>4Nsjko>yEi@k^|j`a}!K7sBmdABEvO*(dtT)9eq638fmnX3)&LO-n22(o{zk+wHo zMKhy)Wf4WkF};-kkk&nG35kp*OEDwQ{9~L8En?ekD~dU9?o3t~;r%hWL{2S!qPfwJ%nC?sJ5xX(bKn zVg9gg!W=HM?#RVEChCer@MHn zg-qVjm7nI|X?bcXx3hcv)l--FP3NVTL7tfGIZ|ZNx=pJIBF`)2Wd@nu2;bG~{Yp}9 zqroJdyIA*tY&37edKOEX?Oo<=B(?~_bcX)3w?|FZ*`B0LXPv(eEea#-3xofhbn(hdJ0bSK|!Z?IUKvLp@m*45Hi8k z2Du3nn8paS+~+t?7wDR=M{gz914ZjTPCv==as`oe_7 zOhJn--Qwt^Lq(P>+H(x5Q*MXgrq+0r4~qFeEy6P~=MAr*#q>a?$FZh7>ZY1T-!dJC ze>=!G-MYVI$*@Aji#8bbFq?u&`{bQ*U9Abvt@;JP^060SDrbNd(3JaDHWcLX4LT>{ zLk)tSCp_B|V$IqG-aGZ@ld3rVI zb4f22|tRNsU1SelBaG{=`}UUt$aP93MWsj`KuR9dTd?2N|RrA=;fcIL9e zt=hg5BC>=%6e3XxLEItQxm~)ZZKU8M@B)dT)=C2mUJ%Y77R{Yuv7q`5j>X+HM8r)6 z;_+oatNa9PQ)&z9H&F!{p?PY8)6A43ZYl!fgpX7+27vw#Y3~J$pUCxV~) z;8JVs{)%Daa4-=&ozM^xP6d!}Df`|Y>FXHw*Jb#9dk}5s)&Ni^=zm7Qb z>^1AmHY3?kDHcey&6SI#y9k(lHI>s9r|y>Fwkh@`QV$Gizc>~!t?LbWZ9KvIHH3Uw zu^2D&wPcHU9=^vtOUib7SJ)UN94N8qQlYz5cj z;%Qdc`PBl{*X_GQ2n+K8@RH-8wpvi?TvU&Zz+rUD%i&oMg%cPgwP476Z zJ#GmXiS?jwikdvcrprRV@zm1I%&r;@J?FHU7(}8>zs$Sn+j@Ts(~*s^N7DrJcFFIY z%xNpGSTwQiogc(9bs+F{OC^zhOtIxZSX(Gmyh34CxUyoBk9 z`~xf7+Lwu79+!2^?x)AvVCC%q6KOrwf)UPdm8CU!4CBs(*}JXvUUy&MlxbkUcz1y7 zq0kBr@n$>=+1=heC>{56I4;WBcQqjn?iPPTdtea9#fGnvP86NbN{mm2L!`2H5%%R+ZQLK< zyX%5bqF#oVlJT5Z>R|Jph`Jdu1}HmX_UG+2V;%V?IO>N5LWX4HzBJ^B$uQO3V8>)z zPZkG;FBf=|QKFuwP%!livW?m@Q@Bnj-&mGSAanio>QOGA;uxo4V;;`B>>J&+=G8$5 zuEh)yw$`frbj0iUaCtU1)9{^c-eYQ>)Py(_x6+4OII;FXZw4 zmFL1+tp69`^UDWBWy#i#!V&$IbRNcPH88Bu_!Og3-P{ima% zw)I?+zC_nQfpEDPLiD9t`88iN0X7_q-@4m^v5abY99JlHH52~WHttO1Wo)-3c zf$EQU0qo@ ztR2lL9Bc%f58f&=b#`Co&{9Y3Ba4eBYvJo5&wdEmMxW*;7yl+rLVA~*V^90a&>YmuZ~S;(wuq-SLTvf$Y*&z97-9Cw$??VZ1FgY? z;;C^0EVJmpIR69!6wAktBd}Hprp9$E9c&xSZnl?_^hnE zt?nahE6lDW!6I5u+ud?Rs@WP zEVUoV;ufH<-UiD7(fxOFzkjjAZ|7PME~btXB_S;NswhBHV=W&+bOZ@jB` z&*N6<$$hpSo)3oAcb^n&h@h2PX#PhRt{ZZ>Zmpf*@}d>ov&J39o#XAINT#bWVm*)M z&1FF%Oe-rL5TRk(iX}L>f0SofffBD8wpEnZ`F?- zb0Xq7>Vs{_Pka0sTMj$6Lw5Ki{WUDy?$E54p2&$?yYqU~V7Y(11ikvGRA{i4W(PD#ATR%;p; z$5jIC?i;>Pg zwi#Enk6Eh?aZP^G+v8u*KeWrGsmBwd^q@Rgqpb@Cd2wQ|8noUoJ<~YXY$U@s!Ch9@ zcUEnpBzegl@pGPj^?W!ZB4EOT2CW?^^Uq^Fki*c)@n$BeOfwpe@jp%|?(sB8%{Khq zT?T}IvfuT29b)zyXc3M3sk@4#lA>#rg-K@&*3sbQeU0swzf9|P4ZgVgB={TO; ztxRTL(wxjIAuwo^e5amzgfhiRHI9u_=NS<8{FB5$u%(C&NNO~jF+|?f@8pazqm>~b z%wx4&Bo=~vYk}gI3cEd%d0wS=u2d8qae17?V)SP7VPilGi?m{~lwa~JSzF`QDr$+B zd*!KAtnbGTch(={UDLto5#|t?7)pJk4TL$1*{`?E4Jf;*aow=@`~ncGleCk~RmE{R)Ndqm z7|a4eL2kXcxfjc%=BX6bJ=jt@R;3;yN|W5zE|$LJj}k%Pu=@qP%WL)WJvB1@3A1~B z2qFoNSt7d<(s@?V$ZMfpRq8_#ILj14z4iZqkvsli;ccryiT-S;&H{E0qKSL?TIekX zDUkB6`#aS8@g8ONNR+#Hf|EjAIQC$Vl?N{`MxoI(H68LOcCH6`-XhWm)GZf6=codZ z$&+Q|4HcY5jN;Nh5i@h8<(gqQ@RI3**i_d}@hwp68^;d@B?tS4uXI<)WXI|wsZXKn z75na~-|~t`khj~FgUAG>M4>mG1Q9CF!Ze_X6rZ9Wj+F7~h4O>vk8<-GI=w1x(jYy6 zr_7*l8(@OQdP{J*gk4Qp+yLPxa|dM+i|E+!*h?(@SN}&k3Ev#(?vyL@uC$8sNRg@G zdokS3GJx9l(RQ~#=y%DOO%TgRw|Q*~2)Gt%8cG@113$M4LL_nEI2ARm#N6Ei+Sbwi z5{5i zTX5QdmhN0A3Wf#!ln1JlN~t!TX9C;b(2m6iM~2N^LL_(w0@XpSq^ABmRobrep;_$$ zJ9QIQ@yY2P{18g%c13*Gdh20IZr)}AyX-OJwed|JzxEkU<+yT3({C@@=|5DrrmBeL zCoYk~kzdJlX{$7Pp-Nh3zW`DxT5~`AqbIkjm33w$r%4wb^ancGloQKOCcP#$J9vJK zI^D^Oo?k`HAQ}aUFpS7bay4)k zqUI&|rpo%D7=;r>zA=~9ep=e%#e(_DlrZg4UwhdI4jmv{Wy7vLo3L?<{XZc5o$;M( zTCoge#NcC#Bz4}`ANh^D1p^d+f)!QzZKk*WvKvSD&moO&$qH%5HDiG;ckF=hT>24G zn0JDm_;$;#2UU#4zg9ODv|&S&GY9TwLp5N?VDj;XdZ_&P=6i7v1lf?hE+z1)bSq5a zDS=HLQE^O=CeWp}tkV$+S`Xy~-7=O;krpkUc*<`u!A$C`9^Ujo z2a7<@SQ?;!FCoAKX$t!nyn<6{rrRgajw|lXq@NsBJYuyqzn1p|!v(f*4wy5(L`31~ zU-p}Q@YB@%bv&uLHC9Fi|23XOXRI3y1^F1o0XZMMkceHg%wUu+zCnn9=;60?Aa*fD z;aLt>!0zyqIFq&5JxJnr&wPP?L2+WzVN6K+wlGfaPHs_7r*E_IfyZ)Xu&YydeR31pjA7dsOBj)l{oDr1 z#MtM}`=zC)5MO=E87`jFE2YOubs6&ozg;G2g7MC5!FGo7z%ot=4oRFEUaEvT}-M5o`ZOx5koQ zh7r#y(M4*d*D*#)Axmv^;3sr~yKYcwy#mUXouL`k#pZhN7B9ZqV@^xYq1y;pG+oR5 zOlBKXL(Vk^YjQ|5IT4NN=Hoad{mO?=gp5P^Z6Q!SQD0lW0NN0DFO%%P58o`~>oxff zSKKyQvKx^(2zveyp&dwe%|9de@3U0$BX&~&QfZ0r4DDbyi@ipsH`-hQ)zw z(1_MQrgFT&_)>ENjCnuS11V7k!y_J{AZAEsQ!wP~BlfZDfan7L zPy_9pXYUf7RM4Nc0mS~~I!xSkGdkxz66g@jY06*owT=?lb%j+9=Vpc0)~Pm2>e-dE=ce;@yM0Wf47ZroofOsUn8#%(qWSBBz3tbx&v5GmGxMkS zov1Q$<)(s!BlnxeLfuO{zwWR5B6QE=)vYP$(vY1TixO!6=cPjtaLI=!&w-Fm58(yr zG|Yg#x_GYXR2|vhqhoF&!?DKU{Yn8Zy(V*G$n--DcBBJ$nYP5swopt&gzy#Pl=;2j z(%e+Ym2-p$QQ?N*s(1a5b5{Nd>RE-i-MFlXY)zxN>1^)e)JUFQViw{sQL@IO+oO@Nk98EqLbiyD3C0p#7AExTy0VCFu#(O zj{}o0eR8FICV9wFYbv1W8>uxm^g=hhdXVF;&AiR;yS}YW;aU4oXAb!run1RUMm0T!eX}#ku2Fp zNRy@W!s%CV`Rbt-0yI@nr29q*xJb+{g?Me*07XN1KP9o~8sn@)3KvGrQO=yBn6hN8 zQmNMyf()A;Jf+$!JX#$l?{{)FmO#aFgU#6D98`ScJ^WNuaIA+&{k2r!1_j~|2hN+= z$|nWvgK&xjY1nno91*!IJn@PgTf2w55>pa&C9-EVM#)b=gVyOtNL<5mlYV^;cc@y8 z>SWo)LBq6RVY83tKGw!!p;h&if%D)dB%Kbfgae{qH>4njL2O{m14$TP8T9%?g@ z7>0P$k%K26PhLvNzgRPM=XRuv1ni(80k=g?K=U|B+L|r2OV~4i*UR?1C!lH&o#A@# zqO)|L4p-Z)u*-0O!)89BEG8m1eHlntKc@AQ(>^rn*hz6d>}K}iylcegi@YHEFw#&TYCd91=^c@m@H;QAOURbSSI_-*tFTa&iXgJ5~K369ef67TaLOAy6^tDR4apLzL{A`7K0ib(c#4+rX(@Gi zckyi?U&#%F9h|*^qWzalSOskjW2JaD(5f63-5^=5n~C%odqK`L%}4<<{}d^asNi*mH;{p6)u^ z9e>HqNT-%8!fp?qR&+5fZXh&bRV761!9sFZIS5WZU!qj|V4$jRO-qlnvJ4|kX&+3) z*z)K(bA_##o&LObpc}I;Il%yJfg}XR)#-`>1-7+HxdOqoIm=Cb3T*uDg#o7nl$o6B zeH$j#roaH4fDSb)Wr~=8sy_7`r-qPD)&dxGF5rj%@$ml6bBx5!Y-~Y~VvAM}pa{fPzKGXA1XPd!%+98S&%%Kg8o?_njVGZB1B$-xf*1miUDe-ST4Av z>hu4nn&)6qW3q>`3?kiWpSj8DQ!|$Sz+t`eo;<0ZchkK0OyT7lq@D}AFhWt4_b;5k z^t_a3sGY52+o1uyt|_iD^WEN*in%_~;3a84*1jc&fZXd4`MQ-Mrw=$D=k=YK6u-7l z{9w{1wVP#6a&&~ph6>i;vVe5W4L8<=`wtBr{LII5FSO#FVW$YMOYiz|@*})){e!j< zG6X090B0kV(-GyJe@Ybg16JoQ?LiCR&WzOgRBm?hD3zzJOrTN%DMHNXgi7Oj zp|eS>Tm?du#){|VxKTV(%){Lm>T`Guh#_G2wzFf~jSYJQsH)i@TU6&*NgT4! zfF7;%1)7aC_?~)w>$4L{JvEM>vknT(i3Bz{y3&Q;1a{zofQYiel7U)_9*($r=eB1S zW<&az>E;}x6*--z@ZudUjj`Av_3U@rv)eEOD6(n~Z)pj8tTqaUe!2#4!-wTd4#wH- zV0U@uP(1bFpacMdZ1iJ{c$7mMGR4@YV`-@W9)S5xD(?w`w{;<($NwO$T;EmqPs(cJ zVbWu>`n5H3pfk1AA&RE*;9~>=Sp{yG1C_Y#Y5a&k5hC7isH^M|WHqzS+JBW!4POd* zQ&tOS&c6&<>Opzq@kV3S(9X1gW?t=1iAhT_uE0nJ*{G0?B>zuzV7H*q6DK&mz`(xy zv;;tX79SrOSrAtN*DI85Su5T}m1EHd0THbOK9(v-KZzfLjH<*W&L}fN6wp$xK zf|B$HHP#JgLKfTav#sBhc0&X<-cq*NvJg&{y1yT8qdP?{c z&(*f)f*clQpug>JhZgGqe;6vtKf<_c@&vsfzy=AQn+$5`UNP_SwaPs^5Rw<_ctJH{ z5(3!}*5j|Mc6idXn8Xljkl2wbo+7AfO2h=vX-lG>mTH)N6WBnMi?sv zqvH>fzJ2C2LWXsVR}FQ*d#;AdCt0a@TwDsQwI+f69{^oIqQ9+`TzLCG-i^DO8}XNR z4n?zeQ1CIn%A7}SY2l6W8*5@1+D(Y(_+~Nb>Zo6*Qj7Z`R*^tMyC=u-=Y2x9&l~md zf9p!#(irh*UxxDu5U?-wGHt7c`@yW@kNPWVu4Kx>Y0t7qZcuSKNr8|)XwgJC!){P* zv<#DR;j^hj80h%`B+6_2n1m=2rh(5cA9yIt2y^Jps1obHLCP4Fm3Q^onP^F{_!|Dv3FGRo?{l`CakY(+_8S3Mk1oqYY;D9yT)Tz+RnY;$NVVS`s%W zD|to>D^Sehmi_^4T!FPtvs;h=$?U`_4mrlxB+?!IGb*_bZQu};wAZiY-x)YP(~hgi zzq{!~=VrtWh9y!-ZTK@t37n-pbvo=QUvb$)rYW)LT}hiJqvUMwW}f zq!+HAav{L{j2MYj4YJndc~k)v`y|_x&{ijbNjZo=NNr?#ZltO3QjwYde!<@*cwlI( z03R3#d;qBCo2m}T=_imOVu%v|gReu(6|YV}(A@}=)tH0;{K^-Cs58!_nO7%PEE~$j z4IY{D2%Lil(k{g z#lv<95(sQ6H0$Nqrr2Rxs#xtc-Ol%I>#14MPnKRiZ_wL|CSb_36RnZHP*E$sYZ~M1 zMydzT9IB#^TAmJCx}AJyo=W_1AhEIF!x7Y1>Ynl>-b>0Ml1I`kgN@q-Q)N|~lPBBQ z3b&sv`YG!AzQYU!YjD!2MFc!PUqfOj|0ftPh6xWO3)4c-SUxyv6ZQO8^b?>AI;L-c zi}6ZT%=VPy6N$CcpdpQecrZasbo1<^MdsqBIP!2k6X7MDb(CKfx{>StrP~VLReAO0 zV>5vhYyu?C3!X#gywd~e1R)7TFv+Sx3ceVX;ew2n^`?D^a#V=9K)o65ftk4c^aO$GhtK;*JFq=rTJMJ)kxj{ZVNL+4NuUQr zzYc5~CMxy2Gy0%a{>08$71w2nRE}ju1q@fJbv$4pi}EI4KYS;m)(IrI(PlK(NYNxN zz*PPmUoo6C8_%mlEAH~P`GkR_5uk1U!XJFmLSlX$;5Ur*iEyO!dyI;^NOfWWD{gDz z1tQ-G1w$_Ep?Ev^mWXZ@CJ!!gFTfOusBz4Cc?tGj;}gpgq?It4R;=1d0YiWQS{8Ip z0E^HJ?e)RA(e~;qsr4wk zxKk0&Pb8)5(1(`rK?RN6HSG*Kzn{rZE)_{XNOue_aEe3Aa zLka$t<5{K8!WyNID-Vh8?4Al}J4=uQFp-;<>Ur%;1BZ{Jqs*7d`_5>Cu0VZ>1Yy0| zN;O$z>CIGSTzr5XJ2$n-%`J~R5ta64VrU<|$Hs(kwm-)x!>wfPi8VE#+)#`xyj%do z43QXU6Lar6_Q90YyHkmTqGQ1VC8I+WbheRVwb|LfY;I$o6r27D{0_S*lHfLAd;4&f zV;d&g68@*^)S`PF73@O>D47^el0oY<;Mh1tIY8bNKmY)uu#CNP7nIn)(!z`HI|OVf z_rK8*6-g$X;P-H&VfW;*Lnr>l2A1Ya*n@>I!<+607o^sPg(Ms*G>eTM{LY>U{nNdG zq90DlV3fg6|2d}J++ry-i3iOkT(2)M;ri|)U-wHQp!&qw z5e>BZ!1hlCxKPM=#BG$f$I7xs27hKR4J0RkOX=~yy8Tr9SEKRPS9PV-f(eB01jCSajWC~#9AZ`=UKmJ6aYBY55tNiI)P0GBrgrE_SBO;qq6#6p=MB;KH=&qrKRAm z0!tt;U?@)r_gK1X?WZrUq=^$U_2MfH!#2K$Fj4RPM`!jzP-#4*eotQLdv^aj_ypd? zelL74>AEF#Siu-S^TPe_b%?^}p2ap_#yNGCXW^J{ri#bTY7(&SzqoyC`|5Dp&; z7p5u+WUdqEAIUpt%F(T#@>_Uw;NMagUZ?xq;sy-y-O}Vx^k&r?uiLl6`8m_?XP|E%?v-gy`Zg6 z9X@7Rnlz7Evgng?_gD9TORAhJh%7qxwi$0Zcz8c$_L*?It-5b5x~iiWo6P3L>U#Vg z?CcmFMdkd)NJgZ%yw|j?)-+$ z4OlUf#&%u3^UGX*K(2hyC;}O6bEW{5_~S8uFnz@e!lC1Qb2FV3OnRGf6?N|KJ>i^K zWx~PrYkz>>{F&vT`i3iv2PpA*^C{m z>#W-Ezrk>;N@O@hgh;k=sg!lJFAC>Vy-ckhaw;?-yCsO6~+1w;3lZ#47|WAwo+w*+rV-d zhjsux+#o17)J4fo_BtPb9j)?-wJ-j_iZ$>X5EV%Jn3ok1db`a?mhTeaR;UJZhM+v% zm?)}Wno{?;A>g^}&F$tV^(_i)yMJ!YRxo(`VwL(Ql1s?a0sERaD-)(?%v#*q1g#9p zDXBqfP%AM-etr#NhKbGuv^(zdP9^|yyN^08kLPA4EWjwn=~5#@2hV*>DE?w#nammq zUak>KxOG_#2KkKASlI@qW#mbkp&3WJCS0I=j^bkU9>*9u?-GzY$zi(4(Kg?an@kAo z$B4zu7?CenB$F2*8j} z*`@w;k*GpV3Zb}kq2Iy!{50Q8Y_WG{OkBR<69L~{z}Fud+9V*C3cN`FcGWq-&RXQs@h zjr;|u<%aJvapEwc8k_svc=QHc5H_&0c!3vZfb9jh|j>lmL|(DeF7+xWjc4zYpF&|N{$g{n9d zM~F(w0<+o=g|}%f7iLs4G`bbmENDkRK*^_d3nU*eeUw)>g~@FgY8gV}g<^QfwAr{y#xX}t`)fVz$wNxS9-*ed~LG15dzK2(SqVJF0DG z`HpH}9T?WFBXun!&!~}|JsZU;^rFuqc+(9dlx>8=voHW0OPW>EtwK^(jH~Vfz4786 zpKEZYVNz_m@ie@s`%eG|H2?qu`T?H8taOV1001JjA(VRFtkMySoIqNDcgZgx2eKjZ zO(M&-cUMMEvy39N&o*JyDZ?k5jBU%z8e%eQra@$p{Nw}-{P*+rNj6uscVQI)XA2+DaGK5*qG&jeHe%&*TD^L@f%SQL zeRqlUs;h=O<`$TH(YPm_?aD<=U4SAq%G}ib6-2_H{&S_ZO7>;kLtw%C?As(G8a;6e zy4fxHdCp(K3;8=Q)jveZ=5xRu3 zB;_`DO(Uv2G21PJjR3J=Y23Uk zU1&)MP``)s>X(e=5ys(&7U1MFC<)-B3We5@nvg_zgd+f|0(^>w33jHFf!&1C;%w8t z*1%v97OIgS@rRTEE#lCMS6q;XB;_RKBbU$X$~%7C3@>*E6=IEO$9~t3fc;i|!?(o2 zKroS0Oqs!QG;C+?-1B?2*)}*~@N7Ai8VgF|t$4Cyq`~8PQx|Al-N{KT7zFfS>m%qk zo+x7G7Y8)&WvLkt6#N0n$`w$S5)#As=;6iqZ4mgqSS77fh!qCAqi4H|w2JjD0uSm9 zh{wI1yK(1o14|V z`s5g*JlIz`nO&=fG-aX~L*YTMWBw0JU+iaG&+U5EwEmG|2iXmPMXQ~5OVQmMWU41b zvFv4z+oZZsych=z8Yed+KzGuv7>4e;`44MLM%4hI_*ed`MMwmNW?x!LyWV?*M#uTA zm9$o)wJyCCd7w9)Nt~lO6YeMEiKf%pAm)N4V)5c}TuflX50REo4LB)%0^BAe0L@Wo zQMz=7eijFB_}UQ2-E`blH}8>3(+`$S0s1iik3PBWJ=LV<>cTSVi-Z)q;*QaRIyP%~ zmBeNrJNmui=FsM{HpGl#Imj91QyM3~teOMS!9GHv)*G#YGrW_$rwlN5!FIC>+)Tdo zBkM3I0CbL0Dw5o(4hs54Jfo+r=QcCygahsS-=otHTKk%30Ur$8otpg}nKz;iL^ED4 zMU()hsBr}W2>;0pZ34-u5l~W4c|(f^*xfKBsM_Ku5=BiIBByNg6?V`h5EKZj0Mvm1 z049z>n#1OxKw71>wY9aiCQ|?a0{{d6000l&5P&2^su_QX z(<>vNSoFsZC}Uxy2p~TxzM8b5+<`MIEuH?UQI&*RZfT*EM{C&sT(Y(ca|ZXa-ErOY zsln*wM!cpu0VP26PD=L&{_7C&0HE4qP0d_I!3rb5+M)g3ASIadQ+PW#q(= z@%=2#6n=49fqg((prJ6QV#!UQu+a`zu0^~9ohLHxpzSxYIku9E%qF2s^(4Gp^Wqmw z6&`6ocDc@5|5*PAQp77ll&Xo(&J`C4Ck_H1Q6FautwJUpeYK(tZR;`7fc|8*G})JHIC_#`%8tID@o+Z_8Y)%eT@BOl40KIrX%i1=hu! z5_`6=UZ-~*%MpA?t?;T-3t7P-z$KCQcS213B-$VO@C=wpzg z)D5SzGW{uM7}YytH6(vJmlIE-vFz(e8R;JEmBu3L&xNQSAyO;abt4Ds2}E4_pE1vGCj!mKxEo+Oa)YQCRL60QD2AD6uH`$8sC^ES7qbun5W zh>_-Sv}<-_X}i-f9Pa7b@m16Sz>hk72r&$lAlx9rfh?VnVSXl3cAIEdl~Qp0+9AZH z3zsGlls{*q>kI&1BfY{sXm34Ape*npU7O9jTF6=O`os&4 zb_VP*9}ZJtkj=zJzRT0x!tzltb9{CXr<6`FVvTx{*z}D31bkR%WCSl;*33 zX>C>~$AuV0Lv4cWFLbLgPmzfn7QD1HgNUkx4BD9(h%Hi~QyzqPapepW03Zck%H)&i zR=yiJ_cwh;dYH=!Z%LvA!j$Q1^>=!!6gx(4Z`W$UVfJz@qm|_=ch1TuOXjY>;6Pc; z!h=9}_sfqF*_|rbyr=v?+f1Wdz2}pCcrf2b^Ja|;iHL1n|N2odiPYD*XeL#rl^YgD z4k1{tlnYkJ$YN59fqvqu<4hR{z@|4uxllgs%;F(oY)zx8oGpq}6C9`riCE`yMBc(P z5|M}v2DHZ@d()T)rQipxp}-N%)A@hnX1c+}hDsNz)8h#sz^|kHH<-{_v%7mREJbb? zYlk>maMy~NJ=pc|Alj~@ftfNW-RR|qS>nAl{lMKHO75FI5%Sg^!- zXEswemd~E~nVnw%s^2MHHLdEx}iqtPPJjchz@kdZ%3x7?; zJHt=`L*sbj%6-?6hY4S8kJZZ-ByEb^1JC{0pLf`PNMIvR`qFzV^;DT0xoik9-3S$x z%$fuHppn@s_R1|8{`Ewyo`_O$bUc`!Xyds(0Wqc|MV_8i<9{RzXK;(3Ia!b#4;3rS zVFXnkfh&qvYp~78BB>wGV=P&g?}e|20L)sg{_>+glrR>(yGi-ZU_XxvTH!Ir@;XYK zO~g5cSEpvt!SeHG8NFEStpc(E7AAaH%23kUdWe#qx|@ywWX#oPF8^7KcSUnz<6cvu z)rCg%_OBkJqNpsg4nyW+BV0#X0<($VI)hZ zMZ%}gPk52`#OLBA4Rc2S>Ph`1CET#toe3qwrg;lbir8ihDM+}Ar&I{x+6e998u?-XaTUtxW1Wxvbe=+x?vyQHCkoMH2822h2BtCpsv6O%b5EEx$& zI7P(UYH4j>rfc>dCv4$|9(-tjZlqK^Ihonfze$cn?*NQ{6^UB7Tv^3;!lc?;!?yS3(muSiCo?bLa8AB{ak6 zNs@Fez=xsa#)0++hCE+NA)&uJ2QDqReNEWb8c7v>BNGekdu~3uexdO*4te9K12+)5 zf`IBM1N2R_ZN5o&F(X>=VSD-fo;d`HLS$G0C}Rbo8E3fU>T$R+fPVzpXeyUJit!72 zS+217T!a+y0WKA@mbNyXYpL*vCC=gE!&l)T`?zosY_+7>_b>&BUfP)!dJB1^SOU}0 z>&SgB?;otcT@$h4V5P4$8}w^5cct)aRS#gh!`3X&vT8*PY5uyPZgk9Dt>546$!ApZ zL@H|v$e)C<>J)X%?90fQ^`}NDW&^`iQK{sy|C+ete3)?2R}KMiE<}C2q~kPfA1H6W zIGh8IO=(E^B;@8fl@^^MWf^C1E@1fh6U_77aeWeEKv~u8#Q70AtI^dfx=a{AERQnd zg!56LNZhAnTwe6-Mp+I;fDE^V=vYh8bwUA3ALW@(9pg6Z2$g^_!J&X|2Rf9YZYI%k znk)}jep*djkDF2 z9Ca~^aACpDm$wnDEF;{@-_RrqH9oK7mxEo+c#dVmvWOuR{4h1CD?=#!1-@a>eS-#8 z!jzbNmvE0Xm~i2RPl?#hTTAK+GnrB=AKOJ%sb)5aP)GgGOrvZsKEPQ)G=nKN^;ImRi3yhMV0y;JMA#1|3(h& zDFee(WusR+CaRZUprI-mAV)(&wOd6OZ*=-W!a5uZX;RhcXcW3flkh2>|K9AQ*g0Q! zr`Y2}ql3o8@dlva46h@hY?RZ8C@%o!v>8#6poij#$A@WZXnsT>RL_dKL^MV7O?tdw zm|)4GupXZF?GF4JyelF(vagQbq;@`jzlVcm-e`Pp(L1gc2lA)0cmzfFsh1DA~>X@Bvi z3^?Z5dVM||=}|m;b?(Fw`07QxZ@A&MJI5-rI3cerTq7HXti!Qp!!Z+|1 z1}VQ6go)1W|g12N%BtOrb^*mH)*s=yjSZ~`X1ih|g^x%z96 zkGOKe($h;S)CWm^3F`GF_W*a`WpbK&(5_#VP6%Z*vS#K_Kq`*9M;R;i))xXUwp%>@iRknB`Hohk`pT``fwG+zSce=gc~`4*UbwHJ|27W!?h=vo{Kj zUJDprhWpXVvZ{i??J-OWyOw)v%e*XwWE)P?>I?4=*sV6 zr+4ZJYyR?0{Qgg`huLbObhkXfdp{3dO3;PEg{17JZc9|~ALF;%Rai^Edd(;dO$;)!%hJl z-B9>^|4@gr1L1Nik;#4}m5ek&SVR(_~s0#d%1Qi`awk#e(lwH7mLxB<Bp`rmT_y;G_+J&+(hm4C87nOS?dZFyYN} zZrV21!l0ze{4MU5Xf`+(__q~Zqa50_8^RTNk|LymQM;z)_y8-~0~(fY1nJo=0ZZfA zH>s=M#;Fe333v+y>nwy#qN_^{xp(5DhKCyBJ&`*7A%*-^;)eL*qf?P~aAt6B;tXvW zkb+ja{sIC&G&vVEJbRivT0o}6*& z;c-q#aYcSDia51Ge!C8?y9r?pzuYG}KKh*iL1QqQoeI$kllPF62}#u#kQ-pJRQS$ez z=zj8mh7il#JX1A=NTMO%O`VS^SWKdSZ8&#FIJYL@o(bm!>nW>zI*SKY`G{H8L^8@l z-Z3)r$SDQLU_B=@IMFYAxW&4Ri(%pcmM&@@-q{*9AIyA;_J`9?+nY!jdWpCNq$3ad zgZDB`V?qTkrLmLG-&&1qLORCkwv0pN>!d+*9coWos}7us2>z24tQemzeLOS;X|h?H zbbBLssEJMmGs^LK%TXsXqMj12LR2G0gz!#-Q=^a~iF~DsF&3)kbv(A}>`VPW_-=;A zeNVb{773N0&*~C|ZMm{!6a+UX`IE(I;)Ht=RsHxleY9V1gLdnePhs3d1D9IF{-1-S zNt3w8@C5tOu)9a6QTwgM=s0*ftwvD@J;KEQOrOkoB@h~%mInO{dF5K$!wtvO$*|l| zO0qCSAF&F@ux$phn;Ucs)k$WXb`%FOS7+SN<2RyE4Uz+@QUFG@#8RX)8>1)&qR1B*XOq;XwSIq zbbedO5REn@HbV=aLX8~Z?XG3$!YxZy#&V+TXg|n^5M!*&oWjlANh%niVIz8`=6+&( zbd5>GQx(XpDVCJP#8-AoP_$ByYvnv@&BVMwq<$}wpz}m$Ywah}A%7vAyUw#V{!wTd z9Vy7Aej#TxEK42!eXmb|mmWL0i_f*yPU)*d>j6GuP~U?FaJXv#B$L5F=s=Ml)#{yGJu%0! z=^prjCMg6JiM0b@MYhP8{$YPJtF}x6)n5^XRN8T=4YL%Tc=wL;(Kg-@)34pzYkK)S zz0N9K*l!ZQJ3wWQ{U*>D8DQ3p!WKyZiFGw`^|w-o({hf@`H;r9$@Oo+EqQ-t#hX^Z zF<{6@pfqC0g+t7LKCX$z& z`^39|6I}=js@=xXEt_o3gHj0rlTXyYHks%IM#SiM3R+}#HfVcw@IJZIQvXU}c)}4= z0o3ur205jNWxKJiSCennn!Zw}40vIf9R^uVQyQe$J91d*J3FCmbcC0lQvb1GuNCkx zZOxW?!6)M=2a4w>t!_~U$QI27J1;nixa!d)b3}8oRVy0hvGR>8Lwj(5z~l|7{$+&L z(f%FeQK7~>k40~~6JM-iCjVE&`nnYngaX=y;xa5^P{D9V2_a&6Vlm@sc(&jz_r6Jt zG#KG2m1lKNe=T}YWDwxw{o>g8P7sHC&=2aTe-&qV3 zr=P1iqY5nv1g@rZXk3I$IBp3o$AxS+T}DPezZ4ZfL!!4Q2hj*_9#pgtUT@e>9S7sJ z;;zPRzTwKP=;0U?jw>mR45K=qR2PUrI?UvSFJeHp$qGQ{9#$!+!#Any!z$m8smgt+U2#g!{^~c$y8StOtKs3KRaS z9aG99J*QAg#EiHsT;BSP>kqgSlC-sfdE&RI`{%rAwT$Stl(MgfK`Oki)uP8PCD#um zx+<{@oC;)M(3K|g;nDfHEoUbaU#Wr~9M6?|8>oyCZ zcH;4sco4yJ9egsVMwmZe{7MC$*n75Y&Lh=|^c4qyNs*-YMbB@ogxKAhjAUxm=I_c4 zG_e`G$K7^;z1^(5i8SArUGRwCs5=)c0pKH&fZ6*Klky6H{A#kA|P zvDekg-$SPlDK4fzMJ#YD8@B5Pe`-mIzK@Uj+@#?Va=X$?cNl)h<6u)O;e_)y4+7re z5tQ6n+T@@0J}}q9P$bb*w58)V|FNXub@bUMD-{Fm4Qla=wT7C+Pz8kru@Vv)W$m5RM!6{oW z?dK__#YlIL?jy=ir_I%%3$(sp>yqe2G?!dVK#}_EV;S&`dx8WzTuw%>0k?h(tj$R| zrFBe^R;PwPNd;$AYRxvI!HC%1Z4wz}Po@#F*Uv;O-ejrx-h~~D4&U2lEKZU!hNq;~ z@emtp^S=oN85MH&uz0%V^1ow_=i6n|t~ zk!D%!o4otS9Lx9S=XB~)eDfp@h!|+qYoZq+KOD(t9bz`h*wbDpug7`i#5yB^<-HOa zA~{c5Zs4V~B9OUbO*W!I6t7bx06v$!nH5~X06mdTg*a1B$10kmw)s-hkH@CcuvI4g zt`>YNg)UTnCJ%5Oq8k`I={=2V$(Ey8oeoz9+vl^gQkaan%(X#`K3gPb2tUjmNRxFta&M6T&nH2lBCu@-K7(+qMvJdMZ%xFP>VyB;GLQNaVz~x ziXi*elbI3&m4_xeMPc-vHwk}3*^N{ty-pY!6+RsUlSRH7E$)v_&pN|Ht*`%c%QA82 zRoa+>>|4{xs0_9cZ1h&R?ScaOM}ZGD9wJ%|FrxQIRx8lMNJxsIu+J4gapwj{o_J3B?Vv-@>Y@B_`9hu4gs*bg35DTTZUQiK zptuHDHtE5ejMQn_1nw5eE4!!Nr-4clqA;jjG2MPHYR2;*JB+-Axc40fU|0>)tl6`Yf7>RC_drWuhW(p?@g$kFZ0z3S`txAOlMDf-@Q!1m?+Ic>e z@k-*#DRVSnpWwrE?g9Zbs!qf}zfA@;98K3{hu7 zYj4Mm@SStA!Av5&H8gdoX=Z#{BdH|!yCw@6o!J?0S`cf|HDE9u zq`?5GFL~SA@U~Nwt&yCcdB>#g5>AgecLN|ua22|)KQ#L zPHmDak&iHx^Ws>};)c|A-WS1qcHCucx896?kJ);~EjJ|>d7P8R|8py%;sZD;W)$8a z9%!B2(VNKOI8B(qx~uW-Ss>(sT%($82rRboZZA5TaS*ub3mv~{8$t}oj5~qLC|#zZ zSD!tam>U-y7&F}P5>X}QI>w@hq!aShBKOz+&tg8!X8X+_mv(thJymM3C0{Fxi7$WBCKyOIlOojs^$TGhw z`dz<~?I-RGxM91nb77(#e|J~QX)~?_YFX&Hj?X%i_Ue?xQJG13P z{d5Fm2O3E2k{j~pTy~k}UN3O#?&!|f9(zFy`%Y#0qNIyrk|TZStW2`8UZu&{mlV?` zkJ??;dJ|FuLG=sme|#kY{T!PTQr=o$u5cl7&F^&t?zF-D<(nSLhs0%I4sD*YpSWy< zoOy2C{67~bO%(-Q=PJKT#YMU(T`HXwvt~U)_Ib0IOA2mEWv-Y$*B{ORO4X1BA3QrKgK;>FBw_;$0~MB|HCe#Grn}QyxZXx zG{k~_9{((+KpJ+f?I$A+HpQUaWK{Rk$SRmt?2#cb-)+O=*zKx)(_q`F4S+RW^FC;b zYJoe%ZGaXpB(MMhD*p9@>sQ(Y4Ki&8fKmGMYw@!y=8$B380OBk5LL$1syk*I2(b*;qyV(S!2`Xtt4p1!bLY+Q zCreTsvyZOJI2&K#kb!fvk_Q~mRNS^daR-ecUc1mnY!Q~{j;+p)QB09&uXSe-%^KZ` zHak<3+6O+=@Uf++siWp(P7HjE^e1jqw}$VpUc*)Zz)PeFTtE_J7}yiuE&R8LCf%qJ zCM&=kqz6#%(9^pY9SJu2r~Bb1Hloy);7GV&z$J(dsd(VE9 zrQ#O_ETkXxp8B)7OcS@wB+XjwM^l5_x9F8cs8PDD3s*Hr>jZsPP+(80$JoH>PpsY( zUJDB%ijO~)!pw7pYY4H)w%D%5rqNjvFpwFA+ug=Fhx|4tyc1t7ZS zLkfpW+NA80?Q=C$9n{;Gyzs6_(^l$e{?$PGVB1A9*^;%dhW^s@;D{P4I)sRJbDMyp z4tn;2&aM-|RCkj9-NuYB(PHGisx3wZ-g&UVX|vHW-UBcPrAf`ZF`xjulqaoZYSxA} zH5QCr0TKTtm=t)AxF-~0T{!`cYH}h!{|(%6yX(_cUd4c0;kaf(S#Zw;2tv0(0Wh_j zGE5dR4FGfQl;n>ic)sUKp5v;ee!P8bq=+4Aj&L4xhxUT_{j=euJS#0<%(Y}GKBnV~ zPSm8-PpfOJj!w(Ce=A&Y>#}5U&8~yYC+o!=WUhO85Vr{)%IxcZ7}VK@vU)~ahP!fz z=-4R^&Tnm`7^FAY)Iled4f@7o_He4uf!{r#1=FD(|Hm3fR74a~7Y#N$F}kG_`i>c2 zL3%+E+Q;de5t5C?Q@kF1G+=#4?&+>$=3w*)H_k>B>)&)`ammfV73Bywy^>+_KJndc zPS^|hEfv(a6`hgksZaIjbof%dG9r)!+foW5f^;$Lj)2L)zs>+U!&hq zDt66Z6Q!-pCJxefXr;f6uotlxc(`(4qaL=f`0UkC2Rkv0XinUBtKSdrh*ox|tGe63 zTw_V+Pjfh_OZ>Gn(P||R5eS@Sv z=@MhD2838t(g>G6XCGMt)oN#n72(xyYW67@T=N5Kuf*`>MPaWJxWCP}EId@Oq&CO<+H z?_k{*i|Mpy;*jS`2Z=&{qfzJVlaE3axHhbY^Ayw53OKilrHRt4B4s*JerDJld6#F_ z?4$|SoR9(FhW-_g-P{F&R;*DlwarL96T145imR0@rH|Htf+f&PP(J4MU~_W30{COs zY7sd3sJnNt52HO7*QNvAa5C#FjQZHZuPQy-7S($yas2m^kk%Gi9S?7~m5P$pGX%2t zjEtCuuF!$Y=8m(27@#ctT50D(o{~-xc!+ZDy+T+~%#;;mQCwh6!r3pya(7U3mxEl7 z#C_B(A-SdtJb&2sin`c+U5Hwf1q)tgPe3w%0{tS3x%nj#E|nyh@j{Dqkjp$>%}P#7 zLk<>)ZeOhfh0L6(`VGKgE59=|CY<6{n!d-1|1luj!wUIzp{V)5TLS}K8;X2;_BQ{0 zI^F6%jAwo!{4EX&EeYL?<;nFn!8*I;oS9L;#dg`&_BjwMt{RzFlK^wXZ2$llX+fUL zOnjl}A(Q_A06p+K?=9p;`lB?nfg2zr#mHY^RPEddLPL>CRHS(rD&V)&eq!+dE~0t@ zFNUD`Yfb!vnr<)dM!^xWrq<}kttW`Lgo*t`RUeG! zS%XxN$y`wlKvO=eS~dWshC;41*bbJYA*Pws;(D|5ZKearMd7HJMFqcz?1?T658fR#ZLC}9CSsA`9KP6meS8oUpoL~^mX$HhNCTjufU zvg0lZv(%~uoHX*?;C@x>3^|5yU_*LuCsZ93E6bY)*3`_-C=#KNPbNbS#X5jc^eDrs zJQ1AN|2oCmb3y80<9DRInx+>`nD^sl0qzHG@on-K-h7^q$z^I;kPW@i*X4G9polcR zjy?Gx4(t;kJPp-Z#taYt__e(3C)FF596W1oIpy%Gy}2avzr+eDL`x}}hN1-2cHBSy zw3ne1UkeRLcS13dE_O1cb)3Dlzz44Q0n_+Px|0`~qzN zG-WNbN?((6yjfxVP%NvD>`z;|qH6uZ0dkI)acgt@JoCDQ(}Io#6m9rJ`C?1>8^A`V zyZaKKortN8hq3;54J#}%d6S@YRzcVE$1Y!9PHumTNeNc&zCdd6gz$#yh8t>8Ri5iA4w zqedPWiR+Rxnl(S|4;17`=T#Y{%Y?sbVsBIdzXX)`9czd3IzrJZisD;To}Usc&d23Q zMWnR;wqZ0K5iUJm-Q~gHpZhMijt!io9%b98nv44~x8ri5ucxwo=vjrILAjl7ot;X7 zW&O`2NkB8#me_Y?yc7HYY%D5b(E!1@jlkJXW10SM!n~X!$@g}4zU^PY20Y29PN-kP zRcw`ebSKT$!8UznB5DmN1HS;sF~RiNi^7Ok!4{E6z~!2o?v~#OIiC{aUvR2I zp6rVn2`FJo*>Jh(q}+?VbJ0$~G%!TZR#PC~fJaWZGls({O2>@1a4@%5U|dvyh68$8 z`QDzeVIuHY0Ki8Wkfs$Dr?KUD-oc=!N`!g@rzt9gl;xN5Nzc5ENn@inrxnMu1aOr% zUXMZcjmB*(gqPt=a(sOYxO?l2#norBe(((nhHX|I-pNklmA^BO+OQ3jTj9v(x$cv1 zrpxlD8$E|}XJ*L{)36R}6aH0(bLo>U3aOhvc%8Z9|0r6-S`DV>|G;6%?&z|{Q+=g` zK2@enseaQZF2Wgr7ps%O4g&(3=9zCQHcJd_k3bRVR z@v~pDkXZZAw=o&}35%Y*v}F{}03Nxw;?>NozST|aWW{f%#%j~*Vid`T{)?=G%Y;Vj zcR%zT07-N5EMuBo-)7j;kj5ja1iR5ssQ?r@sVQNyQ5ol-A)2h~#)x2TIkG#6wM(jP z+RqWC<_&r^HVIm5XrK+-tq{N;tz>CJ81Zrdu==(@CjicV0z{;l!xdG@my&UbamK1% zlkN(;>o3)UH)Hwj_C|sPoO`Nx^ zeYa*_c~2i}ymy^4?Og~la-&D8iaquzLCtT@vN`*2A{Nd+eRDMC6-Ms>X9+xWfk}|$ zAqUp%R#&y~R;p{@p@}z(`d-SB&Hxkvsh-oTpNg)4XTS%woli@5<>1AKm$Ev25 znx2+m#Xa^cj?vKcVEbw+;jJ4QOFu=ye}^}ybYAd3=>Um|^W9uv2GEW9qnv+dOyYYb z`*ok~*CX>ISjyRtY&3^O{Mwr9WSdq zj^#l)Y$)CiMY@F)>x)9x$@s+*Xo_7`zE^)TIDHqD<<`lK(jSqNxu{J0{6$Gr0Fl>* zLO&8WYyb>uv#~H*259?KSL?hl{JHSHy24XU;cS$wvM8Rz@bTb-;M-sOG>Z{e0C?t2 zU3b&$+w#509KbS}x27`)h1goHD!F~xyyB(|wXZO0PZ0O{lJP7+vHJPe739f(vgM1i zmZf;bx0_!cu9IApdBrs8KXtA4P4+-MOmNl%4&G}b%V5eXD%Ii`EH8Zl?}e=eZ&A_v zqm48EdU0TX?62&&tJj(6HAz~y8Q(~}l6gA^r;DzhYz_?7M+?3oTa7XVLG07dS#!IV zhh|_cVjuVx-4FXYNq`Qnh1&X@HUHIvj(H{xF>xK7onw<`;j&=gvTfU4t}feMwr$(C zZL`a^ZQHhOPoHydOw8x`3oA16**mdvUt;V%?Uq%?DaU*B$BD;%=NF=7SOg%qC2uvS zcuSzM-6^yfj`a$aP?LA98LuNZIR|FQx#AY(qrtw)SDsa5mncdK&*mUslv?kq*IG?D zv@4lF&!uwlx#%yZ5lavWP?$3!bS!I0=KZFnA}Ue)zaz~}!zl~?1}XB1*g-Xsk;YtAVDBIDa*cWJZld-$ zgj5OXtO?*`7UP}DU}yu5p0v-X8UHeN^}EebOFj9QG=b6CUBD)4SU?piE7C96kR zG+rFv$@U2A{s18)9%S<*RdFUki1q+O2@cSDd#~#@R~(TX{M&B#He)HI(9M|Q$vVbW z0)KvCj7|G(5*Aby03bR=ptS_g8TF(mPE_d@+Jawr4CRyTCw&UdGfL>hwt$~nb7T&h zlwPm|O|l`NWbvLj)lYm*h!$mmBNogBGfC-~k0@Vo;A#7RBbmKkLbU??FW zo5{)-_0j%;=(k~`@9YpM%72zgd-kwe%#nHX`&Xa)i9Nl!mvH`+3JqiAG|NDg?Uw-R-nX| zFxawbGl7&+HQ#~)Ztr!3g!G|@rF%iMYlqFXwD#^nL5XfpIj?vJU+remgNHHR>97Fp z!jHUh<^8u1Lbx$cN9}cFKTwz@%o>S$g2{c7 zXJ8sMjs7%svDgmG);lBc)mG3)+vk=6#>e86mx{pcj?xh9ME%P>93y?Ked-QEo$a%Z zRQ6>&KfaNQyto5DK|dX4p9U1BVY6XSphz>}!F5j5&moXsJ*nE3Ip zTGcFWMe9NO-QjE?mss*)X76sLQNMek*IJWjbny|F1!gB!TwpPfqPnA9;fX6^K1=7v!MM1AaDuR~yeslstpriOqRO z0H~5^#gs4i@?WnevgR=TpmkZB;9bW|B6e>`n4fY$riX1WSP+p_!DRx?6|r3O-F(pI z!I)*1o*e)zxdgU7G_~Pz7hZxaOAq&OA`&KNV$2Izqhy)dK=Mj_QoF==m4skRrUP9N;6Ok9m zd!-9B3(X(ay%xyU3RtIxec#(Sa&j2;GdK;j+3P#Q z%<7A1Cz&ZE9G{G&Alk*_B}r=R4ZWeY0!EEKi3UkV7>ub(xh4EcRxbegi zcCQjB{#%_Xs^$(u<{hK`A<(yB!p3Oc-HXzb%Z9q-x<+ami?Y2&Oq#wD{@2THm*?RG z@LPkN{k?&QFjicu~#1HAOA7X5r1f45|>83SZc;8>Q7N?Nl&j+10$opA;Ze?OOE^G0JWt_JfLA?DqmY<(cZt z82T|-f2FiPDK2Pj_9r;?Ce=jNTskwKi|UBr@Lw4Pr~j#v!t1&VEd4+oBZYTmlVm8l zswELK)Xm69ch4ZMzxvwRj|zpMq}Ni~GhoNu0*9rFVbpI8rpfeykvZ(nd*FZ!)=T~= zvOoa55Y5*6l=gN1l830gat0rBd{EDT#J83qll}!X z*w5Fg`vZ+qzv7EACu|DK&`OiDtocF3QxoSrUoU+gna>7ct_t0*{gnq)>1a(^Lhirim)AdyfG4konnY zHD2A3OzPj&>O;57tdX*M4__28$4){Q^&stUO_2%==k=X&@r98{N##G82)_Db1+RG$ zE+wG3)+)tF-kxIeU;E&cFK+Yb%3AJatx?jTtBFtLP@7%#BXCd2Hs^SMo|+5RCr4Dy z^nM7mY?TU$;VrWM7$P9%kWJ=^f`1xAl89-QaNZIcE+}42eYAQ7#kW8>f-x+mpV9?I zzxqU+@ve^(*Y9a3EZPr0MeBAo z|F&`@f%fm%FH%rp*biO&j&1`F&VNvcU&k)u^;tvJMUB82nY~}Ffejogjkmxl8HMe~ zk+x$7D;BYWpt-=#+c7SMHUc8-P4Y@(geWnSi3NWi00P*wo_N(cc})4_hyqB_Y=pel zxG>dMmj(VzMoD6ZJ>PYN!_cx%-ua}~penvTSfU23nc(aDa_L%}QG9dd`l}{Wg_rri z_Z&QNGKU`*5rkm;`7I);Ll*vrZ4ljk#;23lrvBOJWw}Jg=5Cmzw@!tKo|oyz;zdGh za~aR1Y#!Z)g&%Uk_n+KZ!Rv^M#@}S47!VMmjK{7#D#8{_1Ld5iHb7mbKdRLhlPZe_?mT54byOw!17jK@$Y1}M1~Cg~ z+a@OVJ>t75{N+vpq= z`K6GRD=W~9uD9gCBnfxF*p7#9O8rtqyADIcUn*4qZ(Re>_-pbYSu9itp~7dsghZ*2 zlZF>-tV>D#$qv)2_p54JqNTzUc28?C#_{SFD)(Y$3|x=bP+^(;>vnK8Vl<;BUTlBb zh8>0!k+`MUTzvgcO`gT zBf;!Kt@GBUxjF0)%_bu5&u=MS7sOTXkZBDGRdI=+9w+m95a{_FDWnfCOkj|#Zmq*_ ztej$M-o8$nJy*DBJ9P@#-QIaJLv3_jiV_faZ$jg3^Q zBNfss)iw<;7Y9AEiVau@^#cQCT(t2%^>+{~jOyqu?@MJ)%^^b}3_C&zeNYNV=n;Sm z9<^T(68TQe`9m!3s(S4Z@U^%z+?BIfNkG5GWry3i9hulYvs4gt&x1$yH%_(BrCF4x zsSQF+N9wjRS-g~9{D;W{(f10iF@-d*aY9xM|GH?!FV@W(Yg+LZEaNzXydrQoo~jdL z+EI_z-ymt{)5eIQL^sC5R*YJf(jYDQwZtw~V4gC1NYC?eC;rOkD!9GNwa7Hb zggk!rIm)rWMpdtRaOBac;jcOTu+s(J&Ree^D*7a&w&TZ#-2&RP0AQ?tQM2@|&*n|| zUFDg*bf35GkI3_EMe_QLFF#!ucJKgO?o!zoRLa#;tHk^J!PfAr1hq|)}22leitr~Zk*`Be;jX6sybVe7Vm@~*%pWarix2ws8m_FILL zC8YV2s*vgVG6yZ7aj)vMW1<)`*NJdh>2|(Yfb`c1#!kAg^XInjD2@m!hp)9F)gX9F zr5|ur&+{tl;I@;cACjo=7R8Jsue+S(CT=wtmcY#$M_hB>9GB}z2k#_FpL=c?C1#Bl z@5d&|>Aw03_EkaZDOC=$xz(5^%t5`?;dgX4$nMeO_xZ0j&f=GkkbrQM^rkR5s|QiSxr`^Lf!Z_kn$uXuF5 zd3P8#{8KyNRr17H-aC%I_r#?@WLfTeYGoBDh%mF7;R{z~gedEfelj8EJHxl4NU;vE z__#T7F;o2VkqFAMtuP{mP}D&ACR(bBdM6=6dP(I(xd$rf1W{E=VvmyzRpO;lTU(IR z1{?aap*K>FTz9Faa|D;+_TrIWP|y>ppmvCOf#U`j4=GxHSkx^^(Ki=Rh2H^q4&>S# z-CAXDsRzWrRJ?E>(&ZYoUpN0U{867SGK}r#Kk?FA5hy;+)eTLvpwbB?607wrWPCE! z8UHtoR&Y*go8MR=Ru(#A>jtLBn6uvtdtv}7;)aiu#Zknf(4<69g4mvB!1QoyQnk$3y_b1TYs++kRZ{kuAH7#HR08!{fT7xa>53UO3xt7>4UJOo< zswd(jk!L1@%Y|&+Yg5MsJX5W52Q?a{D)b^Xw8t9-#L;kb0_s&#Q#Q9KBy1BKIk>d- z(Jc(@YbDiwGQbx4~>mNRtgaJHU{ckNy zT`ANUDJVgT%;~2z$7F_@3`eU#Qr?l8ejh?Zabk$Zq2VPpk&FYVXclJsdPm7b6jU6c z3u_eXJGl#@JD^2&`K2myZ`B9UYhga_rb9vV6x#asW(-Vqa3MxGnTZ zMRY}5Q-+i6Q!Kx9RY1Ne`fG33nZqkKvHaiadJv0vXc3dTKmfX@q4e7|jA4hq=kX6V z>UzLa5P(%6Huf;V9qhA{+oQ2+tiSmq6YSwnRK?zxOU6)M9I-(Goc4Qez|cVL8Rp9U zBhFQT+ZmUpJ0ir0ei{4GB}O$ZYfY8ssJNYTbKLZi_c=m;kYsB}Gfc3w)slZZaKYXvhOM zQC1!rcRjSEE&%iEVhZO3&(D4JYKZX9!(AGRpEC6k^_X^GD;CLx5Kd%@wPkRq`!4Q^i z(3eu0ukvlg0J~~MobG{^Nec=!a=WU^g?rdg=ppZ8~(SyJ2`_->O17j-J zoZi@?X&i}8m#v(b%f`h|GXM=+x6Jipb3qI9yGds-6WQOQhQV$yEQZ2lmx7mg9FW&q zuim*H1hwv78rQS^sTOz$LXkRTT_BQFKUZndYp1o2>p2J_w)Jkou!zdgj8t*@CegGY z;FMr!;ebU5QI4}3*9;{fXZ2&~nbm%38X4=sPqu`yE{LW|m6Y!O6P2)WHg}v}1WE%8 zNRz)tk+n3Iy#N3NT=ZVlI0!8(ArQhpUDhg4&I0WJ=Ew`BUr>#sF)w3&s36cB`b@-k zfstN@Uk}LnpNErx?DUwb%1DV6qX01GKRyH~zpD79J>wwi^BhziII;<)_Q=S2F|0od zQLYr0Am|yzDhAfE4rNG2_x>0T7+`Msn$N?Oj{>Q(*7$Z)N`<@Ac+l9Mu9z>qFPNtI zVJ}7gn?hB-(t7>ZN4{W*HEUOrJPA@A*yXm%Xfhlbch$TXbqw4Qgm%!%WO+;j3Kr5P z4nZK&7CSuJu71DfpqP=oz@pIu%03rCOj$B#D0-Oqy0U%(Im%gow-fK3dKvgXK z9|rKNCj2fH(%2D8kYB!b@1(U6YB;E1v!Gx74EV%fKOxg(cx_K+>IErafF#_K)vWB+zsybe&JpK8^V9siu8*QRU zUPYhzCjGseUbdjTt(pVbhG|MT)=Tv18NWVBgyfl;b-qntr8E;c&&kO)#}c-|(jB;i z>yw>|WCw(>&E5~sn*OAQ?y>%YJ^%BV ziyZa`)j%lFk1C1EW6jTz`Z@!S0&151rN^WS7-yGc1->d6>Z7XrqM54;4BOvl0&_e$ zw98AfuyW#eBW}URB)v|Tlq0Fuye#sTjFi8sK=`9$^Q0&^snk!lWf&~6iMC>!9c1qR z4e!q7m5l;0>c_3sdR|qZ!Oi#4uvY{L1w?0+06_Z4r{oQrqI?TbMG-}YD7mfm*Pi_L z#^S`$Vj^2oy*VYb5lg(>8FF{GPa9X@>%p`MNP=4SjKC^XiHslOgnkJ&Kbw82SPN)D zy}YDbrR5luH}dO0H{G?lbrWuaLCeoKX{lJ%>By zrT#{qu<6be_Y~IiT6@DktbppQVnxzCfVy!l$#R!mTU2L4ZK+)kx?b(K9C4M)jOM*r zoh_hgO#e6`F;F<=wo?-D3N@5AT4b3j%$+P4!FgSh<9ZFc7034@05Z$;n(R5j5$vC^Pb*@3Ag zGyVjhsB+|Eo^0g}WW;3oP2d%=7gPFCv{OOn@aN4R{}Y2OdasuAq#nbZJ?|;se24KQO6(+SpHI|^we7ed5U^kKCsNv|m;f+XIk<}t3}NV# zzt%%xNChQCK+f-Ae(K)@GGqvm-CL@p()W55!uk80i2`~Uw|*da^6qnd4@nnod&z!Car?_H_ca*1rWv%}g$x%{yeZ1x zE`QKo_^|zw0-0&dbW1wF5`th~JZc3u|wKE;gSnVuQsxI?I5ZxqBrsNUS{prvOrqy;iB?f6qt! zn)-wcD4Wr)(-aw*6m~hXq)`~*p{=?r3tUjmSIhX96qSFxM>NjE1C^@YsuDI8YPGK5 z(P&ojcRSDEp*_$jz!X??%<$c!43Z@|x_am0=44mDcFUH!BezdEMtrf|81{PONqLO} ziWJBS3`K2PPK3G{ju3Fd{@26sf6$~bx+MXw#?J+V}KfWpFIyv zL?49u_e2la=0j0aigx8}ruNCjNDJhh%tVn@ zl5ft0CXmAsV_>Rle%Cet*yJ4_Cibh)5}Pb9{8F#2VpJSHo?B%e#)kpA__oz4e0d`t zJQLn$>kew4SIPoFyaE6~j{gGA>c6%*-lV8YA01e=*3^XmR5&5zisA{wQl=2`VZmTb4b8W8lje@J(w;r_UqsdD%L6^d;A0vLKOY&tIm?Al^bLYCo3#ZTqXbkCvnA1aINVDBGGa& zdGjdOVtH+VRS+*`e{!f(gRRBkSGMZ42C99n8Xo12IS(Z4&?9w#pS7kfkk3K#oV2Gq zZ{kP!CGb2!Xi*@dKb$T=bVpsayPui|ugLe;w2c6a99fZ91hT0mKSq4DHnpMF`4gar zWDa(Fvra*GOgl4);?TxN<+%j6c>>^6Me@y?5%cA~C`FCmer`o{Kv@il0;I8X+sgdK z(Q+%`-`arF6A_&HTRBlWU4{2^{SA3H!%0OLm(#{Fs;UPMg?ZYcM|PIAVvl~XaP;HY zJ*B)W2bPyw$c2UW==m3N8vjuo+a&V7=d>IQkzt9uG+wJpiZyNS%8_ry`okD;wm~F^Bs+Q-Ea+zfxEMjP80mQ_i(k+CyH(3-LbuM zN<;%-%7oQ2ePkLvagjaMz|->vL7rs#GsDk7Mn52l`U*hZ^Ay*Oxd990TDx$6{&BVW z$Mt{YiGmyk=ur4NkN>_O|6v6IG9n40iT8sGH@o-+g8!F>TEhI4hN&66|2YG+LP&_n zp0D2=Z@GW3707B}+K#|`3l*C932}(msv&{;^OW_t18Nr(n3LDBaRA+lmqvE8;O}}0 zH}qY`WOYiTLqQabDTn(#iX5d(7zQ->n5cxCF5l%1g^lqGH1Sv#GPFGgJ%Bz_w3wrd)fmJ=US@F_a($U7d3ncltGHe1$<>{S)g>x-`C7A7b z9-)?JSdNZA%N)L%<^;Zy{28(2L7=8L4)=Te?MOU|5RL1lT9wU>&2^;E&?i*eliFPj zB~fDFOh&y5J16^gOUAx~oxs_GO6KfpzUWyhLBf^i{5$ntyI}qeH~a<&;aSV1K$`!E z8~r0b`M;5DfR04lJM=%m0pQha;*mfTO_(SESGnGA$s`_t71+|aoiN<;6ZzIi0sz|6 zGdf@`H27n<3(Ezj;2&)!s|KKEyIC}>*4eOtseu~qXdqZ>Par$VAuzNt;75o^Ukx3X z1C}zrr6r39eoSh$aKf3nfBRbhf3Vds|1a#g|G);tWGrq$vcED=9RU#Am=s*{gN0A` zGI;tZs41{;gz~Ej5H#|y2Y-v+$PS{Bh6EfNPjSWyujGL~ux_jdZ3KpM=%Ty^6m}Ou z;P(f_gS9zygnz!aK^Gnyw82b{p|(ezGgdfC9|EhKE_-uew*%!S2qHtW@+!X~s|>(i z)U`XpG#bF6^aIp}OHf5d=GFlaI* zD83)IAjAdgu+A=s{>y?4RlAF&s9>z4*1hW*6T<=3%^~N^by2Oa2|fRkgdF_Z%haw6 zX(JzeOaj4@qzG!INRqjhxxRMYYR+$Vg3!(b`#ju$^;|nX6vk+rBojPoBD^#e9Lwdf z*s$uGAmq<(uF{X(e*BsOyMAOCriBT598*#;)_VD$Jrko-d%kL*Y^2+}FiT`^M9;Y& zKY%To`yYO#PEMnF0BjT}%r{~W`Z(RD;a#8b1 zT>$Rw0*0x>zq2T^z`6U=mcq*MJN6h4<@BjeUuHfipJQWb19|zkCywGKT!7v(r{p9- zqCm=!)l!r*?7zZKt^^BC(1L{U<9=CkvlXUCO`{=j3FglwTCBeWRAEs>gVS4(;sq## z%yAsq3sIDW1i|k1m^uI8L1pUhlbJcO4vbpK*-P>60RB=5A5I^35M&FjWpo7jORQ+S zT_V0Gf#Uq-N+y|A_CA9SjiN0_U;k+(JV~%OfG52CG9%6^f&0W`aHI7G9F(}qPuDG} zFj`HJnqGEBpN=p}B7>h*HU-tw(?`=K*KT zIF9oq;M|>{A{Ds=t*MTY~4q53&Qv`%)>aAY{ZAQ9;I$Ub-#v+6ziRo z;c=3iUPZ|#HQQ3LkgA68QQWDOei``le)QShkCM+56OTa94Hcjl5}>V@L~sd?|KGQmEkybjI7C6KLj z$r0NJK5SA055f};5neK!D)ku6HoA9Xy<>Hm)NTEhf%AmM6u0MF-{PoovWDhcq^Cf- z-_3eyUXG)$nc0;)1D+x;K5{*0fNok*c97J)F5gN9{wG&;5+G$R z^C3ASHgQ!paSiHB67NN2$pNC+2wgcp8=qvJ#Kcz)-Fj_!5%V;s_Tw>`*SdTcT4{vnI$cIq`I&(=<|{AL5hUru)_~HqP;tU5%A77=&MMNZkwJ&r=0>LO>wRaUKASIz z{)1FY8HGb{TI5}}u>dVk9C!Sz)B;_|a>AB5JaFZGzNb)Yw`N%jUr3o;Ep(lQPmi5- zn-i$VV{m6^^l0mA?qMz{2mZGYuvs}&dW~y1H2&SRuOx$&L8@$q`xj6os`UcAz- zaZ|y3tpRQcn}cj&leI==X~r@YLT@^yo(91;*g2rnYWzQjp8w=I^)HA+(80hC25Dq< zZ_5@^FWEG0-0maB){PIAXpDL!$l?9!uTVq|=^6Ad5m)+%;*fIJh)u!^jKw;tV^@>K z+1mlnMLHTsv1n<~P}G^p_(@suzy?EC&UyaIfZ>j$4w0T-&y(iWiv4(7dvO}4a~=|R zhSEoCWabPeD6{WRJ7chRN3fsaXEb&|uK1*~p(vXFtW6zz@(^WlRH5d1a&zQrt?xo$ zL{;x>kmr}SGkj2p`Wd6%e94<>r3Yv$$xa1JQMI}-hYiHivJAwoft_tg&sqjr&7*XS zFhwT$a9-#wuUDVM5~F6mG3OM%i~~~e9`i)4svmK#Om*Q$xe6NEysq|{rRylW^C{dQ z?RW}J;69^J&1(e{wtuiw>~~sNJj2F*%-K|%N{_1jY<9flXYmTh${!-nwE7ZjrlGwz z4>PA!7+E4iFpITQ-qa9I6Z28tFc}6tBsK@FHwvCSq_NHZd@CQcvyl_%m8LU2?-v-; zH1D5!eHsHTQCIn#Q0A&uMF!zNr_gqjFqz8sCK+8lyd;bZDR-a_Ve`UZxAk1IO302C zi|$P7%8T)nSB!*|pU3<5ju?DUGTAvXQ?Mh?-1QczBK&k;Ge;@X6qti+Ir9-5(na2h z@4O0WAUPwiE?CWypkNK9YW2_pbdxB|)=vV>hr3vquJQI2g!?EA-UKr|{nW%19Per* zR=w86ouCz z53c?EytaR=ntgd^n&<~L2U9KET#{0qxTI@*PmdI;rqVc7`8n@ZFtgjv<&BZFk-Zs3N;R5i7j7lnw~Ly?o* zPciv%hBaWze};`C@DASX%JSX9gx+TUo%ekelII8|xBgxK>bBsTlcT{9Z zRRi`obunr3!XBvbREbqj{?jc(oqJswlaA%^ap5u_6FTjPJM#g;BS<&pa9&=)8IfFy zg@FO|7g;#+Q2ek()@^!)Ub7*=R0*@cHN~$s;8!uGuHX9ox^tX|Kdt$r$BYPbI&CsX zmXvCY%5@3L5plU|PR3E6eR5P;FOst-{D%ige6PLAC+s?>DhWzGLIy8>9lAe&^Fr`7E}kknOlKs`0 zy$zm+IepzA)N3K4RjRR#Mm8~Ii%64ll_ag#LbG){5_GFv7D}3U=(VT5hVV}Fp4W$B zsBme!DwSOal~y)Acd%st3yFTkL%v4!5kYE=p!6G^`%UMT0U=sJR`Gqy%j*(^BgQ*U zJbEnH(rKY}Nyp|pw02sg;*Nf1lVpXuaChyf!*vK;E2tXfS?1%F@pAc%zgVI8GmTZ_xtB`gt=#bfW&%my_=9_$Q36>Sc?9ZN$WjeAId9^; zq)=Q$#}O@2Ww?DjR>NKPKF31LD%4V=gSc5oXvG#P8B|C)TD99nb6(KT0^HYWFlwo8 z-c2~I;N_RjJ3jeQSxV1|7R+e<2}oFU6y99PBlQ-qV6G`0I$$*E-S2H9RyUsVkBleF zY$pX>ve2;#*z*+zS1DmXgYQ*J32}rP0yI&ln`N7KeL5d3=QxI3$rG72z<|pD>ePwmF8HdG&pu>ta zt%1Xj+uORMNtZ1BgDmfbL6fk~lPBB2tA0a!HqgVjYPeUYmBuuW>_fXzBtX>DNX2|$ zuKh<7sI#*k2+Vd(Hi3S;6$Aq)@?BX}DXNV8A!82h4;8ZMvXn|Si)e`v)3?&`DFj#9 zaWkj(y<#9B2IMd6--&NDRQ{{M2>7~9b_myb^wRVVWu85Rf;uOBTL#^z$0oip3hh)==82YMbph@xb-l7j0Y0yk6JZ5v(d5v4 zQPYkwX-en(&AolCRMt}~^b$s+qc%O)Nv=ltXlW=^@$oHV`iiYI-TXESJ?_uK#EaR6bFUqBdkTngS3>94027H>N3um`5V@bpf|{!E2nW@FS2l(TbRz5dXWhLfJPEP zQc&0;yUO{S=A0)nrFt@__pgb2o-&dd?H?*tIm&`#Q*nA%o1VZ3KXBjgFuGXHZ z+Mm5Ti6@^{z2=XLdt>IP;*3qW5z?28-MBwK{9dG-dQmk_v~L9ihX7L(PC-aqVor7(7xL@a_&-zSvZ?CYwes7 zaBS$2KKi4{_->^yB>M8)iG*|W@9&&>lS(|OMx%(H^e!udWQXyCs?;+aBrd|qZ?Y^v z?LvxQpwxDP4mmGkvH{~Qg8u zI6W_ng*!1iFS9^ew=FV1em0zuc+UqFxpa`>8~_L#Hx5Hk5Q&O!p-S}vxc6VjBS$H+Y6D6&Tv9ZxRCOW2FZt@LQIqL` z@2hg-MidoWCW)gF!(R7wbw?%uD4`d2C5S(Uds<%nkmOR&?{sZ7#29^35wq=IbcJl$ zvFq+Iv=`8F3t3tLB$3$ZI@1T~38e1s@nVKsw;Y~v*t7c9b0Yr)pK;hi2e|4+u>`7O zUI9p%Zo@iR#kKYQgXU10Pp?G^=c?*V^K|H0uD_Et1+Q>3P(ow(2vR1NsQOArVbXQy z*(o2WYX(9^`+cyMgznPYXYuo|?DmCuDN4A)CaBkX*|JLVy&1ZuA($2}qYBjpgH6(p zbY(Hvsa6SNs%T*ZnjM7gMP|ep-9U;WO(JmT!ZrtS>|8guH%vkPP+K&)hOG9kS`2>W zOwsMMg^U!y&zB`gBB_J8#uSwd8czC-#+tJ9YtJRQ+j|ws!B6e+x89c73>jy(rOTe6 zCy{qJ@>k$kjD?m5y$5*tu66ByIAl?EUmrN0%P@|@XgMN>-7!59;$(g~?0iHs?Q}F+ zZx)IS7ps1|3PX;NH2Fo>(U^<1ON*#4MRleRk)*<^Z?mD9ZZ+u~LoI<2_AF3sgz%So z$gwnEmBs#^KNq9Ki!yYzTLmmd8gdi}AqiVbJ4w685!c<8kMR7y^qxtJbzA*(6h1%& z^ooBZ-3@Po6gi`TqQ7$o7IzHRthMj1lh;Txbh1Y>`m|v^MqII0PAu)mfe-9*FazuA z1QrDymqypgIhK9MF>Aa&0uArU1Qjs5w(i8}K}<<9W65=jH2W0YruCyL7XmF#hN!=>0YzYGaGv4{)wkEJ%51c(8ul<8M$d6x&S5_wN4we zEV<9c;Q$M>$I_$qjC|8v^1P-TSQ?NpwEbqEme!UjDcuBQ14NI2?Md45UTGtIZ&_J_ zBz)W31r>{tX3^RSUxviru!&?Jwu9aaX1=7mqutwin$Xk7#g@8vgon8+Uk2yd8=G~t zKp}rVy=*pCE*Sc&P!A`+2BE%!OFfBfO%Zq z+vT-|(6J4n7Fndbb7(kBNU^whtE^_>kX;7AZMN9s{bA0oC(*T9 zAz0n}qqaM;?wOx`=cf+`q4DtG#+UXj1x!;KR9gB>qbK;-gFL^DH{W*^Yn(TM0ajp#hs4GYxS3)1VkD9^y%sDCPL>gIq zc{7h|?5Wtd&!gjk${ud+B?U9>{JSmC?}mojQ$I%~CTe8D!G73Qyw$j^s;hh|z1gGE zog9C0H=#EL&8g9XvFD>e82#dJ+o#Zk{$ z{VbeL#2p0BMZhE3Tzt=MwtFn=9LN|k^$-lghGmN^~DFR^>?w~nedk#^|l1MlM&A6Aw?Wx6vGd+m?ycmwXZ z*?!YOpa5kxVXhZP_Q0(9@LX{ARBCbTbn<>fTW<6%&t^m~E)KO|+Ng{8Goq6jAJ&Fu zIad;o#PP_5!V863Xo^S2Q+lP2!~ywUsXYZ6HeX(L0y9YNeIiYIAE3UL@+K_RFTK$D z#nZJNdv!?emM;RR$5&kW0gP&WP%Srvyn{OwTmN?M# zcpqCqU|X)1-NA%3tZ3E2h3Q@D&L~tjYR{i_kH%-1t1wc}VE07hZqO)3iRB!i+*5pF z#J!P{jp<1PiSwn?kpF%gZq#(8Bs0bGJ={(%k$AklZ~* z`1b;@@Aix?fjsmSXeN1LZIowP1&L&Ut1u%$88+)s+ujeToPZX=1u)&uZ4UnH-p8AFwF94B zSKKw~o$%Ejl)bxk!ZX%jNnI~(-!r+f6o`m1xi$|8!XFx20@*{Qs=d^~{2QS++x|kh z+*v$|^`dtX7p~x>fo#Hwy`h2V0Id zeWClwL-DJg|Bh~ho``@BE_aWMMw7w<91tDPB!C1^8hXi7JR;_t)N#AflY9p3kC!tOUj?({nDtF zZs_zN-dOKbH|cnm!Z$R%-GR?E`WC>fLC*r+fYCm!D06*7F*g#Vk2=8^%*J%<=%gK( zj?)Iy!aqIT!M>b^ToNs-TefnP-qX(YRrZo&_!K5NQe{dsH)hkEmJr_Qjt z2$V$)b~anGq2|z#4*VYF8|L?aIaa|)V6&ygrROWWd0N9H2QaDhKsC3jU^Dw~x@`Ys z$Qf2##%|n~v2RjG4s|@CG>x*?3|%T^KM^T_0yfMzC4TV81;8&~iIbf9eBHJVW8&xd zUh^@8kPu$AC{-`%n9f53C$xyd*3uVh2*;7HQEt<6K&iOB-PB^5S!G0l!=<2qs^J>E zp)q2vQW~E;Tc$;;+I{)@Tjj%je@C)nyxR!LYG{6@M41^1TN-FCJ7w#?HiP^`EcTo_pDXV@L-5a@xzUg zY<2**G$Ezh7I2?Ad+RTE%zXk^Mkg};Mj>NDU5F971w)NkL|-Z&kOn3QIQbF~vMep) z3fjb!$%#;ws^MC@MygJ6gNi&K)6bLaZVM|-<+dxgJ%2y@^%o(Lv38#@`9eaBUFRrkM&XlVjP7x{pE126j6=2;h_w>&EjXneLbqE$&w>`txbJ4#_jCQ zZ!iRM;>C}Y*eoab+|e8BQ3_{CZv zcf;mwa5Y*djIU!ij*bNJw^*{AMYu}$?6r$IsR6!1R*+CIbwHVqPtZIkH2Y6;dcrT1 z7(L~sPI=!tkB%lelTitu<0C9P<;H$hOoQ7`@5;W^_1{4)81yf$c|6V96KVdMOuFmR zvbp8+kjIsRR&T6yB1a!|d=CKa#A<~CgNG(EmtgkdhY@oaLB>iwXdJaEER?!>7Ys*QHkuQE|{-f%DyQDL#Gf# z(OtzNm8^g-XeD>i&j)J%%%05(dsM4Vl^0};9XFwtEL1wxRz6t%uYFFcB7MNk5x)*v z#^}W`|6t%ct&C6;z&ZuNJCqz(>d{}vnJ9R*de(LAK&9}*{%o&(Y;sfT_eqU#uk_(< z3T_xGce>*d_E+Mdr87yKjZV%IU+ud6-_bYxgl@y&WBe^qmN(r@`3D18c*$K)=E`Wo zq&-B^Ys_(XKO#@krDfmk&+A@u#X~@4_INrwqg{%Xz=E=H@gjn>>vTShI7eb-oqlr0 ze%}sG;C%*pbX@!Zh#8|SSVf1m@@8caVCV?LM?$_>`w!Tl8?o8uD)=N14kl8-?XJsn zCY&tvVmEHvMR~i`4&;2yV77)2)rcN)@ETzH)YxI(Za>i-h{osq?_Lfg>WtgZB4i!G zev&|?o>K1pQ`q;{^aK7_`c>Ryu~nf4^)?hgh%L2BOB60i_#BtCUR`^TFiy$HCl#*&3@kO6oVyn)0m*5lJkP+VGNLdUb<4h^+c`F za#cf+ewFRPVlWY)WuIw6%ggN-z$*{-eWLJ$G`PfUg>bdT1ft55=Xu1)wxDO# ziAnmSUNg-&!kc?dWBad>K#pzG4<&e}3M3HdOw@@@>f=eSv+#RYaW3);V} z=1RV)`Xt$Mp;8^qHjSpbMaYBq!~;0Eh>DR8X&MOF4oQPlO} zw)yk!OwDQao!tN#nD3Zgo@-2uDxEes;BbLO?Ct3sUf#nQ~TztvrcHp zb)k7>Cj|>iGmd6{sLfvF+9P+b&zs?_o4dI0mzFkBHOH6nbSn@VC_XB{>i+LfI_ohc zEV)6p_8>VOhEra9bGg5`R4LrI+<5vLLge@G&( zP+N(V&V;83 z*eH=vO+JOV-7aS8a}_%V2(i@ed>EiB$gQL;I{YGtrkTz9g8R>MfCOc9Tk}$t9L?Zh z=q4_jwJFODl7Pz0T0C+~${K$zZGznH9p$bMy-i;l{&kg&i$rpS^}%&|q~^02RsZk8MK%^hL#uaCN+3<5f5?0#t*^ zi37GSFGdX=dua(NOgY3c5`6IZ$O?UgP%1I$SzcDZe&~lq@Q%QyBb6fRBTzk-a0!M- z6J4-Njv}=^N>geE-Lf?+ckF zw!LH&Mc9Dodqmp^IpEQ*+jvrgbZPcmK#G?>r&u?L=T52T3I$F8WE2t6LMgv&Ly~=u zu$E$nVksA}%Pw9<8^ii!O(5+(La-CGZwB~AsS5*H`CpNx%(%GiOS??>-k#3)^h>`62%W{<4Dj{4Ja%l3q;z4w-O2Wa& z?!t~H0UfrpCkr4%>cflIP=4vdHcL_;Xi>`UO&dm|9$YoR7nlG50{{fflGiI^n^rFp zd&NfS!MJL^B{0Cq{iYV6^fQljufWH({0x$}(-B5mny&Gpyl@si<8Id8kFEVHxLrnySfBXjLA z#KUxYayv~rNU_%fLSTJlSF(Qczr0~e;(1cNHh9*4XxgJnh5SFo5k;=8gFjlg^9F%E zfB!!w*cEh&ugupM3$*NQZhyDiBM5rLh_~d1(iG>jy#~t%u&bwM@>tb1kUI#c;hxa} zAy5%6EnMR1jg<8ske_7WQd7lJebT{_GL0D8;bqE4Kn2GDR^0qAmKJcJNgr8IyO7q& z{$tTc_z1%`nFlZ!%Z@rY?(W^RI%C4n^~f%laj`MCOr?(R*4zCn<w0;pa$T6?U ztk@EA_@8;`6#O%SS)dwkM_q|NQ-9lxf?V2E13ZZ$p8zp{1ob7J4ILo-&-$f0^9MVe zG6+-I*GT2pnA8xIKkMN+&bFi@twBS89B>RLm?1N?MYB_EiRb3GN}%`XMs(P~{!>j= zE)Z&_>=a2~^+3#rikCH(?3bD!~!mSAX6Mq3l84k=%A(t3Aa&6?^))Ppq)pbfa$eVn`YF z#A?^@dpd_98^B!?Yp4Q4%g=GB0XNP)S*oR4;8=z@k&8|hkh$9JjKj}{fML=DP1O1Z zBs;qgux;pcs>>H=_&>3(Bb+P~TWS6gi9*+L6BC_ADDU^kOsb=KH=aB-f}wbmBIFf` zpVQ2WFJbqP!(ZffbMavXEAY<|MkP49ceX1M)&X$&2#Z#xO7S0PC``X;#S(F^} zyOmz{wsegtNbO(y7^NaCA7o+>WJ_!uxfjqH=oGF;FIxjy>{}GeKIX~l##w}Yu091u z_$93}34OH#Y33(f_t|s5F-L+Hm>ZH@QF@wqe&|>Ly^Az$Z6|z5OKJJy-nnmzG#Zi+ zKSYIur`b6Av4>I~JGF!YL_QT{G+loPBqzMGd*XhI53LlUIB6jjvTf(v4Hu6}Qq2bd z#Xq}W6mG>+XHA!HCW0)=rxl~SHYrLp4N7BhbuR<1(m9%E5a!aRRR6l37Cdz7NBQe=?}Hs}ahtygp!7Mf6LWBsVw<#$GRi7Dh?@pO%P;a2gy-lP zvtNNf$lSYP@tOe=&5d1?BLd?%HdnKAeq3$^DeXuo7;$t>k7kWkhi-Fxaq%huxS=0b zAtU!bH=JQs7wcM0^0M51s{a6%$b8z&@E0ty57~e>H6J;OTt@~X1FJ~t$P%ld0FTN@ z_P-A*jQ57NZhY_WhVjcY{je^zmPwvMtWm#?XDXEN0=gpG1F9LAn6m}uK>R>U`CFAL z9rhVn|Kf)k^BvRthfbMMIHSbVpatAcO671N6W-(UT3ZI=VjyP?u1@8EbX1V5@ocrw zW!mXLU@LmqUaTS~#L6vdndM@iRA>7$3-GPddK7+O+O|u}28hPtr$F{omdGLXzl9raorcjgcG>9u#d9ZSr!@b6S+p0CkO=6%K?*D6Q zmTocwA*cWMx-kOcr>N78sxI3|17H|Ud5CtTW;jk$t-tdg>iT|g9MqeDl5>Mgl${-3 z$!=Q9cSa$pL|k99q3>9{2s)0E#b1h~%MUWtjdtIpa{ck`?aIiQ58Ao+WFoX3GT)>; z)L89Ma==>LS}o7}0EqZm#gYYlaN}H^o+#9qjk*^AZ+f$ZymL2T-EaSgKN8_s1vYBO zu|$M^iV?AKFo<$l)bMN}?jk!KQsw+cplGDUFX7zHY;9X~G{@BMNgb}u1Xdu;|1AOG zn5_iTrA5Bcrz2li{B7+Xu@QTp^D(de>i`I*-HsHLqRYK8M9F|JK~^3=C1jIDwSYvX zUK{V(=)D=K|_I~R^gKV_;=4bc_@ z(1oe%$Awc_-E#saX<-_iA<{N0J-Hi!`&ozBIH!!(c9&p;v{$NS1Ig6UIz5-=zgk)v z+0hQBG&ykJiY>wFOYzCsu*70=m8xzJ5+xTA%Z8ff@_Zs63$gr!YLa7A(IsgSvo!o? zHffO}gy93&^Sv!-pabM*;&*i}ve~psH}@=_&EaV(kENl|A2IOMZDR`9sb@Z`LNwdo zLo@A-=-dUhUmz>^iz%l8BudGefB*mk00093 z7)uOj(UBh*7G>d||1vWDOJN<6&>TsawG7Ct2ULW2N?cI!?7GB*X|Mw zmAxQc*3^jINKlw+mf`RZ%kzh*Hf$HfG-kC>uX&4+8W%MNd=u}q?PAM8T9{gqAHe|f zQ6{5&_0eW;4o`93t0~$;S^0pxC=*tLDv4bF%Dydd>QU}g@zPGj&TU5qvopkSZylM8 zi(NmjS?aygCd!?#J1G;e9dGAHF{b$4`*FBsH9S9Ln5$IN#VW)4d5@W~3dvuu!1_#B z=0E_HU=KDoL(2o}TRtW75ZUZ!o63#mw3`eXxb1l7&8|H&ZdJilb}bQ`$ZXNcJVg%w zyH4X>C&#BJQpc9$8+d~sD!$XvoNO3kGN;)x5DFZY&@C3}Z*oN#cn@Lk`OT;CP*XK7 z^R8aE14;l?4j9-l8G(ZJy-{@3d!Ya^B;sV7_w@mMsU4CCk+wh;+ zuNee^_Lv3Fi$J_b+PR6~msb8H&Y+MVbX-c4z*zB1tvSjzV~p|8JFp<{b$-LgrqqA% z;pT{_BSAq&ZwERpzkS>~@3ek9$P-Ua8<`M8QRLt2we6{1@YE|8uK*KfG;UgmG`w;o8@g`%9KdIBf z^TiyA4}${dY!Pw3X0Q=ckRmm%_3|GUZ6rB-pHzh77K*+iSM))a3L-`l&A5J}BUKtk z5+;%fPbQ@GF8jUdBUzXx1@4s;Yt;H*1PqaF9GPjS29nAUkNzw&U{V}HYrOZ69ohKz z_>&N2#(=v@=iW3E`}Q0erDGy?HE51`C|D7!){d8O9O`sFR?Ko}VVgb(ZZGo2{v|p+ z@2Yiv3L`hut2zZgv~R2(eCL0myiozPrRjGcH@~eX0QQcE;?<&@GOqJ-hj22GMi6Dz zwW_!N#*TLLySV+=Q%1S+kS)}C_+pSd?lGcF zSc+{olUP7g2o+k9C|;g`ZK@@B`JJFw0O#NT_5Q{H?zfflhfVCJ1|4+hLi{@?;~%*g~a&tDwT~lfut`UALW(D9#jyET>93Jqe^Q%&;Iy}$BgdZ{ViG> z{*Ks&(>+rbNvGK0<7D?kkgmNvsnWtf%FI7vlNfm&=S@^lapcD$sqT^GZ_`RUr&-wP z&mMCVsu}B%cE1jH;K#a-^)ZnBpzYw_=fnexb{d2LF`&oh>s^kuN9}w#4%zoTF5PSB zc0_gN>#P339jmXUpN6$U+4TE`!Cl(;vN1yX0MBb|2fj0zaUR>tz^pD?y;8v4VLa<6 zuhOB_93V$D!D+;#=M}SBS+Bu%Yk7`-7*`jj)5UC)f;n^2yq+7IFy}&2xe}g85ZV$I z)&^f?9FLi2&K{<6f`@4z6w17sEOP`T)qYQQ#Hh@}_G&%LzprgpA%xJZoN?c#k3i%c zcXrt%pQg!r4I^NapCn3;B^K!RJwZ$hghy2u^8_No;<8!~e|pC4$;eLryfV;OaFAaA zw)&?#4J8Gk8KounQB1DYPV2t}X@hC)^riG?+BmyJ-3CV1`Yjc64GF^jY)rI6JdmMZ zIge#0oO3c@BYnpqU>~e`D8BeprkzR+(Zb}ltcR$0mli)bT41+>5C^r^<-Rh~4cb)EN{ z6V%N#E0WW>-Nujoekt2gU8lA=%`OOXF*enPlOAs^7T5)2KzNw9QIpoMJjxO{;Q!mZ zHQn9XVs38eaYL>Om547ecyWqzmCeTA9kh=>!}@NZ`tt3TrlClU@ibUXf-AhXjrZc||Yb zTKu5L<+C&TT5_mb34BadxJ$%;;pc0Iv2pW9RU3BZ1Svb3ITKv8jL@do8OcbzChnL@ z{0;6#Z<}c!Flby}!hoMl4zX+?=|nmZp5Z#2z+p77qNTB%L-FW8T^nW*lMPj zF}~i*NVNC_pC}mK`IF)unOt#5?puA)+RxPGL(9Aqwymnd|JX1o!kY8QB426M-WqUR zC|DEMPHb0&1|^J2a;Ls^f}(?7h@D`ztyu(f6?&jkAjkGAXh89v&rUn28Myu}0C3PDUgT-t?8a!ds$l5h_)}9mj7&XlIIEj>^KH&ej&O_yg?(QM!BX<( zY-pxIg#7}%ajR9@cPH zh`bHUERRpx_gx*s0d`UkQ5KCe(%@2*ZchFtlYGN=I+wDH#y;gudR2WyNYiK{v2cXw zcGW0qUrDdrsP17u<6@-m#kHkx6OHq7a`Ej*U>J@q` z**1{dJo9%4mZXp7NhmsCxNWUO-D@W5&pHe>j}P0e=IX?DfW~84IE}8G1O^i_i3sg! zVt*1@VNNql-9F3&HK|fw!E^R~5DqC{(Iu)$^qB|5cDaKppnb{*{eoT4n z-uVj+oFhO6HwzNXdn%eI;$U)al7zSU3;ZbbW^JIX?~_E|0j}`;r6hnf!oTop(~b%L z>e3CO&)ln6$6q2+FTzpy28}S<4~5BS-H>ck*M4;lprxQ6Ne^FT%-c3L^^jI!ZuuUV zRZQ!eh1J}t@jhOB58oFEf;b~W_B=Q(XNPIO$-}6I@93$5>>G?M=$9KWB&=bG3=lB( zQma``%*XIBVS1*lK|@;1-$a?#41i|!R|TspoqbL8`W-e(5v>}q1+jT6AE-vohuGe# z@HSN|7qXgt6f~b36JNXCvG#=bWp%{FcVh-+7WvklLI+<_LNs2$@@3IZ(cQ1~=mip6DFx4j z?o-jzh-`w?q0H-P>b*uli@L+9sNRK*>MZjgJ6`J^7y$LwGnT-zs6GcQSeV;Y4Y(?R zk{ZN1`Sf>{h%TzC&suKBFQK?Gp@N*jwv3l!Jq!NiEUOYTE)4N5NXRBecq!G%b7`hV z9TM<<$cI`_Lm*IO)0s`<7{*WU8=q;1b%c_k<>U1_X<0KeBP151FRb&@8reNu=t7$~ zIKP2xM;#t7O`)F6s)My`KC+lNH&GjIDc~cYTVNc5pCg^0>x=6B$uY<7Y~4@P1d(<# zm)L^cKezyxtkR6-NMaC867F8}R)7bY0GMsN40&hj>|zbbh9%~W+v#f&>j4_RJm(PG zMPU%6Hv8)s`AM5G4di>ZRfG%Y$Jg<N1MFXjV@uHaJX|iu3nCDWrIzfbQDFXe(@PdI%c>G-VochYWm$c zvwpat{j>hY$h%XT|M?SuD2l>)DgXZS@?e`yJ#IuROOu8q&^Iynk7MfYRs1ia<*h(U zm<{+g_1QtUlFVRK!t&RT-?QCFco!%lyB3Xt95WqAN(#b~tSZw3+Z9>?(d#HVG15of z$dI|Wq2o$2a)uPI4{+^yc7x(bN>Ym0fBTGVdfA#knRA(u`PA2HseK?3Up?qdpPDul z0;~>zyx9Z?bn$hnF&L8+A>?YRD>!MEMca!`IjZ8cw%ICj0^mR2_ zfYq+rt0b0?Xc2IWM&%IP+8D|5@#nORk`W=MruK^rMC8JmKd&2%%YxfV>|i_mbDZT2@001zWlf$wiyPJA6x+SR62E6N_GlM(Q zQaTZiJMdTteS31_v<`H)9G)Zjh$lFRu4XC!Af~V;VuUd~krk5LmJC&vk2q7m z{+JT;nYhytT8VWO!INWg%r~Q7qZ|TYi&M)Tao^5U_hAR&_xCJs!x8VVGKcSEAc}9~ zbQ!hfgm^Y{%V1fyJLgTs&zQW?BsAjqMXDNZOF`Yz%YE|NoKoVdQ-MC9sQV6Hk@==K zxfesD#u)ggGVrH&%#E9SGn(x7gbpV2tP%8jlq%M zVa?vArT`~*IV$O^_*MqBeP_Lz{#E{Bt?_ISKlc8Kyn2(hX~y5#Aqx^8=)Mn>d z*=WuZ%4Y3f!Yr70)MEsVuufd%(LO}D!X(6DRomiXf}*RNP=9e-H|pcI{F)$%K%}&8#5l2(10Fh^hyVj>5m^bnsW)*P&{=TudmD7d;Sv>%>wf&DD zL1N2cH`?7XC;VCYouXGRR7JzCXum%ahPF)q^bQOIf}W{~muJ_?{72CrJxl8{r&G>K zNN9R)y`W-&H2va#3K<-V*8bL21fI*EpW4x8LV|)`Zl=%nI2rV&2mB_r79OGCX++BF zw4EcsW3t@O@UyL}_~7yYC-@VC3uno-DO1%U_A&Pi4Zd8sI`-i!r6998P9&(pvHVf2 zuYw^dvV5sXR0YN{GDW#{vDpW)S7NqBIwD#*7cOHzYj=WDn?03|P>*U^j{}cLoie%6!reMfTio+NKg?fHM=)|z6idXR0cJjNXXv7+A+Hk`nZU_y7P$06?Fq z_kl*}eHcaKWlqxoDLNzo04(=Gp4@DFq39u#{{R3z@H^}XGd1wr)pP(HXTSnMBN8yk z)W!e{@lSHK5i|ghv}O*m3r41bIM(QK7rH0tAhb?zJ+i2~PKz2p#nI`t2^8@#w((wq z<_5~fgmU47S#O#qNuxXUl+@~g0m+2ct$V8p_aFI|5Rf$Qi29_w4ALO|Py)ShfyGPf zW3(I3@!`(lYpc2U2*}R*pyI|G`k&5xXcbckH~30~>Fy^7g_C0Lcg$cL6?IK%b@vDB zdd%0UE1g0fS3CjreV^jMEG)8)#ekVACVA&NO2Uj67N#;PqA*yf&)E^WcQNUaBrN)| zV6-OR{zuI&FnU%pmfX@g(RHd|7rO{|BCpd0XA`vBsbDJW0SL3LBntCC!DUqysozx} zE!BIFT?ec1@gAKCIddYv{@`5%CZo~} zXf;mXtHYv@_)r_M<2*Q4v$jXo-fI`!8j7S)Zrm^@(2G6G$hXD%1D?;h#uc+&VFmJr z0{d#j$pQFjkfTg5gwC4A7T>U2lzs5#EI)*J6~~+VZ?{ii@+WOZD=|Z@A>S5Tb4egY-E0)Jw>y%qwM&a5t6kOoP5hYYNRj2MHU}cY*(L&j zM{C_{fJ~SkTZ3MEhh%flisN!9On8G_9nQVQ8kqx4+i^qD*-&QDx5wDILDotAqEwtrI^KOnYi9=kwB zt*T>7u*WzVw0Oum9$C_yaOb*hhHq`G_XWpvcv(}BES=h9OBG2s#m!x#g-D7F$mjw3 zeTUzZ{H)!AH<4(PK=`;y7SU~-gq9SYklV-XTJp~1X}@0;zUAbZ?)c^up0ai2Yt|UT zXP7}a!~Yij0JoeRg%>o7hhT;nq=>eRIh|4-eQqS5^TThfGf4&YvAx8I6 zXIh&jKiMOK%2Dl4XHbb~D!x|CL-~O#J;E;)Pd~&74A}_2m<_$`Ug*olGP!^!&<@A- z^ANC6=GgfL?WV86C-!Kziz+ezcGsJ9=>M)mDymc6=M~+Atj_afW{29;A%9)wv*=0K zBe9amcYgt0kdIVatQHnNuteCqCqhcua5(5ZWLV}=$mnTy)~Cf!?d*n+K4Z!vrYhQ< zgJafwbrKj8KkqYO+lP$Fstxbk4J5F$~n=UUU*O+6>P;vq(wO(p*@9mSVU({2`p{U0# zBX-nuVUqswd>}^z9mY{HcUYQmU~fUNdld`Ejy!Cc>Pv#S ze6a;tk02xRanly8%t|L^&!BrZML39*^1p?d z?iB+swai_M8G=MLbaCKu@*DFM7EIy46dfiSOVF+Zms;{to3z1mCdl`x$vu@*b)>g*i|v#i zwQ5GzemSwWwM`vG0h$k(2m!v#X#MDFjQ1X}{%_U>92KhG?CRVi9D7*Y z0uat?3}>FuTZ`C!3j)FB968_;99r>vST-vs%zuL|cEvTJA!P+)J0mGz^AfBZe*~=> z9Hc7H{7B4b+z4mU`ZpPPG)rzk)IbWvm#0=q)e2}z%6=MyaQgB*wuD!-<7*0`aS}m; z!#t_)^=WBZ$`vHpjs>9O8C>2xR0qtk%b5 z1%fq7hfF*rrxRN6;+85j1DlZgN3da0^aS)~w_aYmI9O>65bxDsukvO63IQqy&;69sQ z5R?vJA@a(vX<2-_#_p`^ZAbX=`*m7YV{NKc!_ySW$V>U>;y_L)D#CyGDu2j;33!jNfR+U=o)YBm}d)nS8}(Qerd(qmK*Q~OH9Y$PiC!dp}63tyv+AO#f0&U2%i7t;D5b|lOH`Z1d*q0Xy{DJ=1N$T3I_vefMd%EXS5WKHFM zdqLfDVxiz{Cm78d?nA~Nf)YO@qN;fvSikKwtzYSIs`=v&Oe8pfQD}4>St1j(+;cZl z30(=I-f}x6HGn}BbM?0(ZQo>*-Xh94?zD%Go=ppRrei$^+#8nt;iCRWa#%O{dx%ru zQXUScW-++MyJO5J1UY;5^O^r4c7~dVLXx;MyYx(^Y11B|zR;lmPR?Cr}}`6j0fdH@xf20?h4I^X!nA37SSRah~9h8)DNv}rjg z<}Q!u-2eo_S#*AGp7AL3w#51kbnsWcAgiC+4$>GQ+pktUiqQMi{Z-i^z6``JA=aI# z9G#oHZB!!iE&p>Xc; z-L2ZyAY}L+{He^4n8Kf%(ot?Nh+R!O@noFVs|RiH=9Xq59UjOyMJ+}#OB>jc)RR77 zh9XJTg=3X)-Lyi%tY0FDv*rwWt4{g7yik%hpL$PtR#w2+iSjeLX@l(LLEg_go)sk3 zoHuSWOtfWOqN{)aj)T{lgl5%#w^IJj(p|ejEzihSh%zpN*#JzlzbSB_+CQkjbY8q9R6@SB}Kc874|6Y5v6rhp((fmT-+GjoIFVY zzE`|Q6WH$Fw412|9Tq>h;{uL9_O5h4VXvSIdU3-zp98r202j%o!a)$geJ!lMHlT67 z=~k*SvL0w<;Uhd4AIAkF)_`sLpSG?+(>E%pbRpJ1<-67Lq}w^H>Z=1V>;2F;FmdTP z%wFJl1vMB1wV}jo1ZcTMF>#pnbVV8L&;TOgjY*P)Ak!#TP&acymN*d~J}`!4U|r2b-^hTS`+bD5!fSApjT z|5_paq}hz~%$zYVEX;gmR_^g4Y`-Di%O7uyZ8TT(437!+>l`U)^WcT9sIdv$5Fh}f zKL$0mgoY*g1Z62}E3?VE!?qFEwL_jp6a9R5dk`V;LlHD(hd<#+xzgtio(X);^i@c? z1iQmdQj#8A+!H#?_J-gE=0v3;1T5&o6^!m;B$~Frk@r!ayfyJ{<|yZwYo;f@WMJq2 zofhzLAMjETjit9fq`q|QMr#X6jtW&j4)atkj7}H_PEar;9IFajPn5^z zIK+}?r9lBt`OLd?^Yj|D6^_Sv&ATOpbPsh*VZff(ZVPF}E|BO(S^>C6b__^p7a^le zzuPXTLPT;4O$4y#n8kB__I!BPF|{=uH3NhdWwFicdjIBg7!+5rV*k1GEpcd>7cu6* z!zlknER5`6oy_zMyqIwjj(tx|cG9pFL9JZe?BBlT<6u-!sr*J??6VsIAnf^?tU=}| zntu6Je#s%-It_H}tx7e1-}m9EUdaI1UfP+{$`I#SeS+gx{ApK$ItT3o@ra$b0@{OH z^`z954SK~qfk4VTrpPv81`73h1*t zHu@j(jl{g2E3EQ2D3BSaD`XXF&kY94XcXjZ-DzzYinY2Jd{3Eyl(X_)c2DCY6rS{j zkAkpH1P}1s+IxN?H&Y==4nvg<$%qEmQ-Q)puY$yLB$!cYxPMn*@>3@|A@yq*0v($Na1{wk<%DDRG}=@KGUD7{m8iq5@&V5Ti=d{KUyzs8?~iRrw?1w}vU?n1#Ql1Du<6n)l| z1ShH6qbVKd9)nKgF~zlRVE~`3b~+iF<1?L_$N2u81%e_#_aEV5S)AYKj8bVcg?pES zk+~x5t)9*HBj9SkKw}a!!29d993Q!c{trdb{0u@N-~@D%&y&BTt0vD1o@5$}Mv_X7 zGA4_{$}L`Dq``hO0*@Wh(PYpjzA{T!ss~vM#E4|6C$T)93Mn2QfIb-^f2}$mAO(?s<^JzDCkA!M>6i0}X@^Ps z2*u4b%|f(ScoZrRQMo@@;f>tsW^R6(JVR&=9<4FjXzzc6E8XJ<4`4UKO5NL3sfFCd zQ!oSxB(#<@Oj-y+b{bdOBCF`xKE` z`1|aX8>*8=IcJb~r9wkzwZgUK-JGdtf+nIa>h z5)(SMWxsv!IQpJf$OXR73J5VlBjuCWDd5r54K_9CHzw7WE1`_%t!Z^aTCj%j0i~*n zL%;A=yT-(F7@Skl*qM(cP6I)pfT{mqX&d*A-=AR1*5kO_(($O>Cptm22fV;QpZkf0 z3^u^W2HjHy28&%ry%UqAI{0AXY3=_@xs*W+v(av(@xC-R8I&-I{3*|v7Z*7A6TpER zoJ=YI9oAF`P{UYt+&?G)o^`8EkvIl+MDndJ%i;4LNnYwh=~_!5^4zAC{EsiBcBNf8 z8Px>U%Nrcv^QOi^RIu&aar~!G`OoKhPRkq{rP@yfEMWW$r4f^(LQ+Ql!}xx>6bz0@ zabA7bazijwZ>0w{HyOFnf}z#Uf-&Xtv|!kHX2&ZbRgVq~e54Z?3)hi@3RE@n3_!BA z$M7S4erh$Bw=?JrL||J=((agtCe3&9y`^%31S-(_Il_@}GQN<^@Qal&RM1%CYL?|> ztkQ+z_sfPTUM}2+j|icTxAnx1O~4w~m>oE&I-QmhG6?O^sS&}hH`Ix*WM6zJp<1Li4;MOq-4jiSOX z|2lLF#^W;QmWzaCFSDTC&z_tr>B3J!xZMGrUl#DJ@4eNS6xt^xHvJ zFdjIQoG(?&IuF2o487u_0{#ynW4R{LSpe@iktUhg{*8Z(U}MUCjTkq$X<&FXfwG~D z@tZ);Epftw{;BVmY(oLAcp!iOF2&n~czWDk>qc?r{I>Gs>@Z7-0?9!-mSv=VdHS#l z2OQBWy~Xez#*e66FZ?HvUM>0_!$K)f7KuG*ACSx#VEC1-)nXE!@WBfS6?ZK-CjW*p zIc@k-LnDtg#B5;E(M)ANkVLHJ?j>+EYqMDHRNy8ZA!6A<))<%+$aKs$H#Kn^vmwQ(F=(-9L;EenEC}#2z0+#@ zq*J_>`RS}B;KBO_rTN0)HlPuPuf8j_6> zjFc0xK;03Toh3+A(t1Ya=7*eY=`&9N`$4Xu)+JRCphy?(xUGrl0A?TAApo!(^Aex} zcyx)&NGrJ|_y+1w{T4Fu2qx|GoO(pNxd1T@0VXZJ_c$b^G~6|MLJ60X|3O(f`FC<-DGaTPP!UDSaGM7(#Q1h zNF#5Q7LX3_e2J1yn*0`Svtq9@R^N=LH+M@KLMua}a(imTPf{+$I9`X(`ESMYqX~BA zA!&+GXo*?0_bkbUWbQdeNGdO?I)QAAL2?s&D`NY51)I8zb3M+yJ9%60J8?D~tEJ8QYv*G;0bF6i*UBZfH)edn5cAVg2q*HCUQ0#Xp3U!y%llrm zvND-9wn>yIwtvhkK;hdsH2yK>E4|!KJsTp*)0K2=t7PbB_oCup&!z&B_;C(36J59F#DEvrnX=thf|AgVv!kMx3W12Qf9m0363GL$YB zrT=w{vyq2dDZOriN(w->YD>CDbU|?Q8tiv$9D!K|QVb8_A9vJ5#YwG3p>S;On20xp zNrmiGiys1E5auCkCM|ki+FC|J$2m|WZWIp^d5~Z6G_1jD6H1*P7NNN846VRnb7>*P z2#~R2m(bIM`H2uO=pm&oYNW0kV;pMWd!6>85zmZD6%{Kux*9o#pAIBK1Vaei1RUR{ z^O``0TaUK0Mtch&H!_}(Fh4#1vIx6IL(%ibW-^Eg16qP7 zcc1cpVn16c^_|(h$84Hj_b9G_V7zvG2Es_1@EQHs$7k--yZW3$&^;?_g%mgG{OaM6 zmYGzau+C)9t>;)ORiq9*5eX=mXf+|WNUEOdi7A^jJZ9O}xhM~5!gTu1jaMSo7dXnu4GrVJh*TNTR?XM@Dy;4~S7O$96g>*J@ zKf3HPqI~;C@q38^#+auctGU=sW=GTbdtq7`q&ZrM?-CF0sI)9;c*ebN7ducZ4{=|Z zq|#0iU732*;VbIfX4*m?H3+LcWhQ+kn>3@@1tJ)zR-8%i# z2pqbzsW4fXw_y-o20Rk8lQd}f#3W%QoX6bBiB7O(-itIpYoPO;E9l?zY=wJC^!4N) zW(lRJDHognG%?6Botg2NKzQ!0(>j*lW}9pTGhZ)nugMqyu|Q70u(&invvG*X_qek+ zGCaL|uOQsFq0+B8HYC~}S`8A-j2$qbFpzQS&(OA@1&eK#$4bSdAng_H(Ryt)?T-!N zr0uS*&D$0w?h=xu@C?>a9Gr*@uS`6yGAf}GnkHV%MdXSQnw*|h)_It!H*FBll&o&; z-Tir*@w^)PWEj4X~Pc0F@d?K|1aSw1UCIXdZ=;?PoTtmq?+Q6-;0*o^nqwFY) zDU%Km{k7e&i_?u$kkg?t`rA7~>M?5k)sG5bnEQ~Pmd;99Cw<6&Be^H&$6qPpKdw`S z02A=e*08AwUhBg$TzY(L+d`$xnU}!3kKuA(O+_gHInc*y!`PPBB$)gB-}@_Vy2$)O z3%NS2Zz#DH38*a017b~a+D^h@YkdvHoeJh5+B$m?U2-H!~TiNRwDIb5GX-B zKh^CJ3_Yd9JE)P2?*m7R*k%}2mF-FjWUZ*h0i6)5^>Z193xgnJ3Qj!&1rOW z8YT&z-3X=`(X|ol?{KF6SBf_w@Si$0y znFS{@wZe9^7oHqGSA|STtGQd@s+#$rJ=M5n0(F`Y5v=)|s0Qi*xf7?v*v*Zp8bjDE z%_|5C0Ub9?3CSc%T=Loo!ICq?4)Jx`-&&HloT!AXoV|H4T&Z4Me|P;J(Y3^j*}ndM zDQ0h(|Asxt1FNyovZ*jsTY`Q_RhAlO81GEx;k2%(vov?sAi2rMazYm*P{NttqyuCF zB~fiZVS7(Zz=<1i8^Z+j69fZ>pg2iP!+rjT$S*x-N{W#~yNEen8g$*nTzGN(fL&R-ZE9(i#E;6r zh882xAkV=FHx9vMFI{DAtw!PBAc5;L*S}}G!pb(^|DgVy>?&nka*-7RNc`QcZ!`+> zRsjt>bV010CBEjqhUq8mJsE!b&A}UAu*@6ZLTSV3_jB(Ag5$O3A)w(v64IvFbku9% zTL=Kjnk(F^Z-VMTm+JM^BZE-Wh20Llp%ffd@M z|1@StQPE+^hYF{;6_ae0_^CZ%5udl7Fp0>wTrh2hFUKq*HR(+T=1ct)k?N{a6Q%32{;&{yiQML6_0)APFd_#YsY$n+txTn zhdRVVrF*~TaS*@@?YE7gi-X~*CN<>^zy{Q|?$ZbNi^+INjohxN36&@!2}3KnV{^ie zhVy~?C-yGbXw5WN2G5nW8xd9xhmC=*uVD}fUsc<8qbGqrGczNaP=vVWiR=usxQ53< zxxTDSm%qFkQGal+)Wo(lHbWyJjE;Sw)&@aLB^e9dbL6eT;RzPY6|9&<%c2N-^JnBZ zPIv_lFXT3V(jkzOAW1&^k9IWV!J0ItWq-%wNv7{*r^SEn*ZG*R?OS04JjL4EKbmKT zpBe1x0z@y*`ISrCJy%@R{2%`WkIH235lex7^_!7SdMg#y2FFGUltzM*z?7f7;XmSm ziQV#y?wrGFbm^q6cl>9}#BBlmP6FCXIhZhqVWQWc8I-0k*~I8 zq|i~a_ZnLM3IAv!lY%cniorl{B7!>T%gueAG<@iUuc(nXdlU?|-*;B} zDBeCys12w{K4*4o56XaDEn5)FhNR_Q0@=GxK#PwYIl|UzpQspgj$OZPlc)$e7@Cth!i8)$l1Z}4XeeZr(LO4bm7b}$Urc$xLQ}X= zLnJH&^~>ODl9@cTS%1I54D#!&_Aaz{nBg`FPGp%kD zw(NAoI1e)>Y6{=u!JG`C2@Vc8`H8-CXd+LR?{n1TYw24eQ$Y#8fax0trxXchj;=$k z-kN>^i%?v$>~t;ZCh`R;#f5eGEy1uvNxp7;qaA^}L1jX~cenau0zH^*rPyXU)U08N zd=uCEvlkAEGv<5$W(msz`L73<5!>~kI6M+pRj+n_vo``Xwekm~RI|#xsD6tP?t1gl|Tezni8VccKLvF5@Xy`cn`6+dU>Dv?r6sltKEkbc5D3Cb zZE+Xz3gHd9Y#g*{YjyN+bp$4HGxBz1#CmV+W%}aIM=+PkEs=j^zT=$d+2R_E{UZ@KPM~#;_R2zksD@vxC`!9u*A^osNamBl3 z2Mq~NuseZ)46@bCP|lb*dR@>}L!C@*`acN)BNv0TzZ>8}Qd~6%SR>|!IB)TuOl@-L zF6Ed?<{|Tts^Qqr@ii2w)`~;@0nWWvR0mX@?sMg}RP@nm3D_ z_0(n`ySNS3-kVnVwfi7J;}QD&5MX1F#Rn(-reBvXQG|r`y4Uo{Q`FPj|7fQ@sN&hYYLh{Xet^E$aM=HunOPCcl}Ihmt^s2@r(pb=$W_*!Cd5gGd4Ym>jM zsx38}e2sH%0e|h(p$86iE|@rUN}iKEIRg9{aK7z2IKi9#0xJXESaII{=p89Cgv&(Z z1Rju2T&xF*b+zIxho5i-AGH)9GaFIokEUE`F@HXf!%M4lI=Dz11=l~>-qIE2aY9A( zPi6sG+CXmw8RS_?Svp7IK^=qL-Kbo-b24m7f!%HEB(6h0?pb#k!C!0kCt)SP3FDm} zA!m{pxjt9Pd{mu^;23%ECOs2CWZ&|Vbjs&Q2R9fw`NjR#{}H=Nl6fF;arQB)68hEc zcuLhu(Z|72l%^x`&0kD^oZ#8-NnT3kR`vHw>?<$~aD;`EUa=Fs9Vyie)q8w|Rl=3i z4BWWZ>r>%^`>~D*vUd|V($N=aJlaY!90+L=ko|KBvKPcVi2K;dg|x2$?sBRLr@u!P z!mQ=|2?3k~3Wo2RFcV|c9p||C`*G9~kl$i~gU@D_h%?AN?{@73jCl3ye-)z7@_eFD z@F+e&U~J`90|Db{?3e@N=B7A^7GcA#`+Jt~oM18KlOH-0LXB1+zXIJbtPN}7#Qdb@qVy^Lh>O9K6c|G>1 zBES{z6}+{YQE|xk<QIC*TH7{J9i3w`cE?;%2gDalXB&msj1rK%WU4A<~BZ1a(~ z&R`e-GGsk0fKMb(b#8D{F}>L*F9@TqF>&IA)3dXQ8OqEGc-=Zi|8img00un)p5zQ_ zBEJ9t38+9|$a>Dg2Z4kA5S$&p|LW6pKZG?AbLl$(1rX7vh_Iz{K3a2ME+N=3qMgbB z<_DxoPEVD~fCwrn-ERYgMs!UbaN#X4c8aBQg5nRr;zT}vwv{G5B;7aG5cF`o_;s^E z9-0;ar2Bv5h<|DvfntTAr~fYY8kZ#!CNQI(bZ)3UG}1F-oH39uKDHW3itXX25L!Bf z6lbnQ*P@*HGgNw?q$Z49gOHSql>G4wq?QI}b8wRnE-|WJDAY}EI(XMxl$e{sfVBzo za0@+P0O`s>^#op-{!p;M6&OxcwwFnJ7P~{qSg>Ej38(vKa1iVskY*TrQjTt*>o}^lx&Q$LCDM+%oDPE3O74@*eJ4 z?>C_s9Z~5@QAm=ZusJ9C z4rhV!>{@Ecr;eEnqLL+5PPbTTpJ#T?AF0)CWMKPRK+xI?*A+hS05Vlcm454SKuYN( z1PmXvNpwUAL(5jYRR2PDHY?!T5$0H)LYk=*sy6-D{_u4-Jy&bgR?~akXY-1K;f8>L z4Y>N+3lD&$t0{BN3!*SXj)&Hq#i7@6Qh_&h_R-c42cOv@z%$FVT4OJtWch&uAFw^S zWP<0MF^5OQ?{NQPBliR-Tq3ZO_fr|uLC$bxigFzI*%hC(f2<}O1RnmEbfYe(5_{R4 zG`y92Ms5yWf6;0;-icC?V+Au(UZ!PszGh#5jTb#Jsm*V4Ql$3Lu2{ZI_RJ=b7sOQ) z6$qav=JBtX2+EG`h~eNa^KL+o|4|#Q>4KMAl8>I2_$8R>Ds!1wz+vQFh7aTPn~A!S zpkqA40UFBorAzcOCz=!-lQLI4bVg1Ca38@ zH*fnJ8W}hcO9Wd9Rjja@0~hZ@T&2bQ=Kg=h2Lwp)1$%tw63e&U0-u?}zIh=06qO51 z0z}tVHa5H+%>>7X6Z-yrk7ztN-U57nrT8bPqCC!3w;DyPY@dkrxHjCWwn|e4X;ztT zi1nOt9L=7Ly)Egqvhnzyvr2M6!9CuQa!rQO4IkYufQNW-wT@Ndw!Snj=;i2d>dlu6A7v z&@+K=ND_ob7{$;r9}Kq6J_2Txw9CwVZtT%w42rVwW`xC@oPT`tT;i6WNQEas!Jm;& zCfxl=p*hnC0Wq+tcYG>6lV5=ykXtz$?GtB}G%W3G4rp9(*IbfbOC3ewHzCR9BtJU`0&*-CrJrcDOiI zY&Lc@zSK>`kwvtfzhBUKqFNcTIxBDN`(MVseU!%p}$`4c-T&C zaRu7t5@{SiCa)hr$Godd8Nw*Z>CUe%t;c4yk9lN8QYxqFl=?!2#UO;)cyhBu;uhMF z3Q-6u%kKReTpv*Y0GfM4DyCzkOsTMIb+I&;9F|BijJGuX>DKEJyou7XPq3cap@Ntx z(Y#sWhc^7ztpc6YhVrCF+I!O_zJ1+;nIRwc{%MZ@s8~dVbHfQkk*y#AO#;yhKabM) zq1z~?D0a{^(EBF#08K_K2J+Wf_{2kEdHx-q>T_ zUpXZ&PaDYVGy!%2>OM1qt&uc+OZ`j5y8KZ8GNtG>G=K%>*nI(sZm{;y>P|~Qyjo-T zcj#^rEX|PuL9h%!6M`b~cB@Wsv(qbkl|7AbzOEm5e!LHE$mPWz!U%vWd&c@={}gV} z_=G?gqVT2v2*?uKE2v9LSf+DK0rP(HYumd9t-(6s0008F0iNV6Y9hY?012o-P|)}c z%v$5>(u*g7nLvt#G}i5DGqVGE71CTx6tGoNdC!1gOUETAxuHNfEDo(Bq!{XO`3+His>KW0?3Q25!GAdM(*ipClh6*L`As?Yw)KA_kO4`K*S z@-W7|8s|{AoBt}1&f8izMz8U~p8IJ40%wKDztIpJ*$dVEM^3!3@jdZZjP8tD9Bi@jpA!Pc=1h)(t_HRH#Jh^+gM&^yngc zvYyEWPN($o&`CCWLeB|%4C#HIY)Z79RKm3`RHG)8$75X<(7n}Z)wCHHmb4tG;E=>G zs#Jw1O-$D@%q8I@q$Hiu89j}=QV_FZFlk*^!9dAG;PPbHrS;dg9MK8Bt;l9H{gP;A z&Bzr;EwZQ^MoQ+OI~!lDcvzcuW$eN$0s^gIQ8!YE5a>=*Y{aVn`~W~0kpR%~(M-UN z5DBDSY3WzCA1_3{Of+s5F$sG6o)IGRh~4q3O>BGS5zOefB&#z%O;p7m-ML(SpgvLk){=|7X=hEf}ykJa>)hP z2;j0RnEq^s7Z@XcQSG&ani8_~XY^uwbnWR^$WeVxn82YTw8EkT(~7j5ADnByFT_3% zRBnt!^^f`2LPRzIoNL=cjs%Q=5|xa3P%wvpGkiuSed-ZpfJM*%GLUr-!w}%4NCyuH z=%cG*QF*PBB%#NCCbG7gft_v87sZ%Hv^Ucq$VsmN$sZ+ghd_wCP>OX-uN;S9%+|@b z-~s*s00Tb(p5#nwBEJ9t38*TV`$Ijv$@nzXQ{Y36j*anS^~3o%e{jMs)dcg?fW}k9 z01*5OGWA0*%5$H^yfbKCR^3zhF`|I8wa8`ltKtO%Gr=7B>NP3g0i^xnwY#2T+;8x^ z1K=VR(5aeVAd0X|8Rkp^dryF<@CSw(9%J*6&TWX(f%y!ZT=`VhLcJJ1K7o!ISy|~Vxlv%L)jug96VVR^+a27h(Y3<<$)o}gSNHGu3 z6y{(KHXA_@n@BGoUd6gCzc0dF6=UFKYJlrXXmJ7NB4EpPh^(NTiO}3$7k@XnJEl%; zaVn`rP-o`kSO4^610)FRu&lhZl!gez^4`oS0N3_}69yNxZ6;y+Y+F%x4l157X1Qv_ z=Tra`g1;G*rwkf^zXBW-=K!dDU8k{Wm)RO%(fQFtPzz$gpf1XZ1&$mUg>#Yd2hqj& zZzkEUQ~(}8VmN%-`%C@xNw964qzbP>EK8gQL>!p`1C3E8X2t3~BoK!m(pH}1+z5R^ zQq>iIcfq*OIZmS1fq)=h8J?m(Q zkO1+;@z@!yc|yqMTqDJKFr;EbqI#9CV9!bv>TuBZV1@#j7YBT}UdVqbW^@~BcDJZN zx4@l6OoI3-UBwAj1^ag`=NXe^g8al-F%bLC|%PkxB%?h)Liv)M`7&PBq zm2(;7{hUK4&IeE1AwIQW!M*{%@9EdE;8ixF!ZJ}@VYrH&ulPPM0eXV^Iy<;p?%Nz& z8BBEyV4_9uENPDcx}>Z?wzpo-$B_@;pTSaK>LXmxPzV6|t3o`!wrPDD9|StFT$*eU z!n<~kRek4_V(i%9&->d)<=V8@F`jVtE07-JUIJzz-Hnks-gu+Q0X4LN$BfKY0Q|;5 z&XVi^U_bx>0ww{Txmx!$qwWKRWyb7==O zf@h0dQVwrsKml6dC`13Bk_J0wz$SR$EBeb(d0ERdHFJ4bO|mhbse(+Lb^sbZ*?y3~ z%{IJPFoUw8;Spvg_y-E5qlfoy*djPK6J#{?x$+~*p68)xJE}OkP zUadTXV@MFh66l7u$z(x@pnkm#jvywUD+B0T@{R-MCx3tay|qB5H$+H73vMyEj$lF# zCK1VG8vJ?ofL=Ygpip>B9qZBB){USsi^V{I3otpbxUcvooGthahJXMri4FXV1&}o8 z1<11=QH%(e!35`E=W=Ev2OP%zM^O1m!O{12E_%N>#GdRb;dU_s2yMPEw{bj+^v$?m zyRF9%b}5hunQjmzsbCQafW((X=tvzMfFq^YRhYMLLCFRX5MOWHPRIMz#D8t97UvCs zX*9V3RPGMQFFpjevL&r83-l5Zw^UJRMM`vw<5Oll_Lr__L7Upwz0FT85Fw(t;Cs?E zvUR{CU($g0Th*_P#U*Bep7N9c;)RU04^q4U00i3DyUB)KW$!Kt=m@ibM$*+KTuq(; zOJh9|0#;8O`p?&Os~+$tOTY{JQ6Yv#6OBuHIgf7zBE1wUFaQQs000660iNWnbc+7~ z075xp76~3+^uPdmouC6zIi8^ibpQr)o>@ouEEASznRV^c*s^7?fLoqpjCBj^x;7r`50(sA`|X;LWDP-?MDsvm8@Um z`C;Qo31-#$M$+bNb0G%GcGm8RaXSsd|Hx8jwy5}ADQLiQt!&smmyvO0T22IoV$ndYtco!Iw#dL=jN(wk8l#^ni4VabNY5p-DT~ zWVUV*R&x*4*{AZKoIPz z837Ou>~xAMZX&;K=XwR`CKBGDnwszx=ilvKTNH2&)uUQ2T)>#`$ifB?RREz;yS<$Y(dN+e(p(~(ijH2mNr8>XGP znNq??P>7N+_+8@7b@gYyx-?xFYCTHO3NCq8*)pV5GJ#S*qKO`4P!TRhjZmcb4dv*E zO(P!2W|c=aMEVVg$Ql1}Q`lXQzA1FgWDe%GG%Q^xpt2o%&!hk(dM4+=ngQ>UFNF{v zDzAwhLyyU|*~3t*A5<8Jha?|AI0l$5=@L(5OXo^%8O}z+RkR-8Ho&uJ2af=J)k%&v zxg7GvpbjsKpej`Bqn7bVi+yWWN&eaZ`i33nzo7dog=J7Yl#vIYh(fLk?pB*1*bz^C zbeD5-t$`d$RBf8pF?{2RAE^0R%OAtuqr@p}r&>qU4|{TP%h6$nG6Uzm-Fe{HKm;*A z)Yc@=ht@W-mLON9dPBK;!uB{Dfny0r>PM1X0&VPElfnaPiN7^tCZ_~DJQ~s@K_8xP zOI_)WF|JdeO-5k>oIUvC`uKi$klb3FdJOIbN8-o~PzZ|fg+hZ#Pjo_*Y@sE^3E7Uo zr}HRC^3l?2F2$WB_1uNE7a(zIyt=zzTB0ib;1Lf44H8wh+Iq9PHP)f@>W^{ge&A3xcBT9a>!H#wq8@w1lwF5j1q#Ltoe}6zEOyS84?CvT%9# zsy2C)#5&0f$e;x5Fn)7bAx6MOvTDZUJbNR$J;0VfPx#l04y=L@0qq#TR$ zP#e2&I{*Uce+GR%C{*?{2rsNZ7vR9{uXYr6?*Fb!4%%E4#57p^Nba>uTiri-XP8a6 z=siFH#EO>v7hW$gG2}goP$`fg&%*L-@fULDGus_95;zrTj$!a6h|4kAR<%sSk=L3M z#QSCO{B9EAjEp(J{u(o)^~7h1ZlpFTbPW4rV`zNATUpEqQ?B3beWtHvBC12X?6&)u zVc1b+maJBnKnDG^6+Pn*qcfG&Pbt0~>s2gRKmg+nTEp$$m7gI6w@l(B7;RJ{l-A}w z38+hcE9b&b1Cn|@!4?~!)1bm=_^ZhZ=>J`(T!MM)$iOPL(}p@gp;z;U>c&=ju?T=C z$hh05ntdxT_BDVaZmAViEZKj+XmCcWkq(CEy*1FBx*?NnCOpf$c>cyN){CIvZ7NsE z`WoaPUO&UV;o;=nZ<<;&*Jy_8J7=lPAh_$6hx>L7yGKab2OA$ZED)c*R;@GiOHo}E zSO`>N7~ao1eS|%ooq@Py003^UU_k%?0n$O5<%Xa@TU%PCwY9Y-Qvd)100aL300RSU zmu9@foE@ag+u%5$4O(;~^sk_jfU5O=JstKRT8e9Eo;EY{&oryBaS? zF`pRd)B?|=eE|kOMiT&SnRL+bvO>CV?ZW_)%gO))itkr#ASmYqDeU5J%I3s-zEIC- zswNo3*8C+orw!YI^;LDjRS!JH~`dr&^ELRE85r29WK#*gYT^La^Y?@w`_2c<+JW9ld7r%dR`V6AQi9t z{Q>^<4u^^_5Qe%(usrSrCyzM~E+L&n8UdfK`kR0T0)lve)@9Zwp<4mlnXtOrJXD-y z^Ac7^l6j4YhQnw8o>+9?03kpoz)G58m8MMKCX(C5sFRrh4uP`%{iv4DIqVwTE<$z6 zzLxl(oanCDqQA@RLS!R&KmcKZ?U+vO0j-^iHKc${Vq%$}{$1t(00%v*s2W9Zw`~jW zt>DQ}pmV?+yj^_<*1{(row?@1;5Z>C0008>L7wd_e4*$ei2ncpE?vys26_X=zV@YG z3&j1|=lBH_Hhq3wVCiHPIP_;@y?HtSaA4{nvsZob;sVR%Aob(Rr-eMfpaD12vxAU) zFOQ)10Uzk`Y))$5(de7nOD&5Av?yNgV8PN0e{;9#9E8hv7m^ z(A`L)@4zNllEqneRG2Al?1o~VA*M>awNQ=%wUoV;{)@kh22itL*Mq1MX#`9FS&DQv|bbmt9;AyL(0uV!Q~HxeMTXGR6NEVppAQ>O`^>18q0GN z|7Q8f?*y}5?}=#HfscJR_2dQ2-WzR;=ihFBz&)LoV9{!@pa3+fG;16n&(J*{gI6%8 zEfeMRErrOYk-%-xO&|A<%q9E1h#>WW3{NIzQ@u|O5dT~PW0WME;&g#dZr+0~z_ zmP&vFnm7qdV4?g}Q>{9Yfd-8BF5x1sw1KXyIJT-YoORPY{Y!0i-^rAG)jCe?7X#># zmA}YA+Md90>rFF;y9s=NkP$KkU{!RzIf4PfmwjK~1j!9#a8Y$b4B5YMU9JUbP~?0H zC)Dr&00D6Up7jiBBEJ9tE@QoN18+>!SYI`^ed}^I*Yg91*dt$#rWiPp1LU&P26~>Q z-bOCf)Dm>(1c$mY`+O|-VhKr0g+Z^T$npiBmJ&Asz+Vx`q-AlQd9s$+sG#pqdSKA_Csq6d*L0Zn_W2Gp#ILyYupZG{9w;N`%t5_%3BK<248 zQ_hbn@GOIv{E0RDd-EY3|(VI$d%%re#bh!TkB1YFfC5p;Tjn7h9D$_VMGS! zhno!XMfwgmY?|#~Oj#~yE=&0NhIE#DdQ1Qt49)%dwGg_x%F_|#2eh=w9id~^vL`$M zGn`oMl1<1k710iK=yj;K0vi%K_m;*vKm+OxUS^=25@i?&H+NOTMONei*Ge|1yJi$( zwgr;ND^2FZeL%cP>|q#j;SjP-9zMtc%R^bs2oQp~YK$Tr(ECQ~8@Agn@I-C$rOTMj zx*NejXx)b(Pyh_c0002<0iN|tbc+7~01u%~E7Sv<8al8D$N)ndMOn}g0Yc}O0964x z4+Jdqw>&a{`!0X!X;@j1<=rI9gM^SgYxMYdVrdOCkv^g z+ADxiJJ_~qT|tw!Awt2!NPAGHs9y(~X9GU*!pAhjJ!n9vwz4bB37@Iz9n0PcOf+}^ zyc#?sdeG0-esrhh%qF=H#Ng;kwH%`WCn0MS3QLgP9#a8(6&ZG75{dRFcdn021&3 z00Bk;p7m^WivIurF6tIB+f5zJmTOg-ZR;Q5w>S(f9*|u2Hl}s8>jv|6Z=(g5#1jyH zY6o#w@&E|oXhblH1j~cuYR>+`KBo*Rx6X;7kLHteTq^T?E+RBj`6@7zx#2fFFq(8V z@@XpPSEDFC?iS30{B;StNeSa%L+(U?k8*Lh5!cOD(37;gZVt6dK84LD`#j*Dr>Y(M z>1R$=Fi1Fkj~ZvbU1NTd$L5Z>##eq~GQu(AD9MKh+$^F_D*j# zRzPM=hk{}p($h+rrb4pOATms4Y(IF?A!pH$$n)Ku5*2-7&1x7Ep+O8m3hb1Hm7ee+ zCQ!K%_YBT7MPs@|TR>F;X8-_B+d-Q4CZIrDTU%PCwY4Tw000931OEU33FP7&6M+12 z=;aR^afL|1IBO-j%p^==_v<9c!}q1UKL+kRI-h=aaUeavAW&`M$X!`xjQl==bc_>P zaYHTTA_^VL>}}ThQ7rX_Rpjx1VPuy}KHcpQoDeN9I9gh7@0i(E*9wH`fD4l0USDKp zP_TCHgUu%%)gQ6jfOh!Q{5%iKTPmQ%2s-94?}VvQ&9%ev5ZF-PIn2EoJM^jrCQgVrkxy!yNntWOr_zU|$zn$%R>321xP2|s0nPHf-W^ST*VII+o& zM>ukadjmPvl*$X7t9hY3A67>s=hy!sN`froUg3IO86<1j=9I*79xh5}z#R8v{m*Wt zaLg%&Prt233eVA#BA@mA%r#Cy6hZ9=VOWrd&Hk**K56Ws4c;Y3O&4f|c-o=Zk~#nS zj0Xk0@)EaSxlme@M{;-a1pgG2-hEK1^=mE(oh)^hmgTMa7u;2Fyv3^Mrm~?_n_-Gm zx@z73(7TR78;s7iF-v$3nauUy)WOC&E(_kG?$reiYcWx$cGY;ko<#2Ah1b36Ra6I~ zj5QjFke2~qV|VAGNUilhD*OKOBX$B2lv$nUaDFQA4NNOIdIT`I3N%v zaz{Alj9Iv#Z$|;dQVE3f*~Qc7rG;+KyT;o-@b#IVJevcU{2qG9r4ZbMTJ`N;j-RYy zSMr;yxk%gHl#j^j;IE_NqnJ7pdeB^oXy~DTfMeX2in9~q3*imY!Yft+Y8-2CzG5~)Jj%)axD9WiqQYeMsiq%m|U#;b{s7kHf*(h*s2-Hh9|pk)n0W= znTU{x2mSAhE5ycHp(@@N68Y(^a@j>UA5f!f!j_tK4h8D9AkRlQb7zoEN=vKqd%U%8 zg6n-5*?0KBAOXKb^%)Kq#KI(bT8D#BB)sJ2hwul8pqo-SUcIFBPb@?p<9}< zYDz_TSzZu?Y7u%~tMfc3#~c`sWo8i)`W0|qDoR%=pGkjru}S)XbaSwj!Z>+6mY5)h zJb$`eVaYUZZE_FnxG$$2vL}>zBnW&E z)p-LE@vpiU+85RY)@>LVhx+T#y3eFe>4e9)eDpL_BgTaRu(JB2G z~1TG8^h^#Sor)4BYRS-FKxMWD{e&KOEd2Vziqi zk@TRBe)~#9m@1Dk{*I`3u_j+!_I{b&d-aU8(sxhz?+4<)T(2iej5?|6={6Ch1+drb zL1c+Ce0~gn7AR^>Dzu^*M1-^saPir|fM_qn8IkqvmT^WXfAFHKr#;OhF`8~1I<|Q0 zZhLc{wIu|Ve{(6rYxba!<5g!9wiD+Jj3|&)E*)$OZXZFh@Zn5N*Qh0cK%A7ARWDOkn=z3-BI zmE#?(mSDVxGT+@!k;RKBb}q-_0f~>bgs=}D!J-#vnv-1sO|)8kD)ZVmnS4z@JF2}Y zL|)*%9dWgIH_5^R@EIdkih_b#=vRcoZJAM=KJaEu_M&T520qKLx~cgHolcFj_cA^& za8nu)$@FB)4_EjCn~7F!cOFmmp~*|BrMg_SNSEEC9M)mZD(WFrlMqEri1A7{M+9$@ z9#-D#d}7-oreoAHWsrC-ObgwBbOh6DMl+ij*{w;}nUpI@rKT5AoRmWkoc18nJiS3<9u?;M5^OXVYg;TU_ zpyL?3NS2zGETr@xHQNI?y>NJ!Q!-88a}c6h%!eLP%>`Cdrmo#>&9vTehi?6+5kRgl z!v-O}eoD)>h9D!icXog+_$6O^dt$I;fU8?c%n+1me4MMmhBV&CL{*RP97sa-aG$iij)1= z;&kCph3UJL4+zz6m$bd;Wv3EB?GQ`9>N5wIkYDV&kL(4?Du0+E=rtgoB-b2-cltoq z1M#iBkHu&Zv!5BM671g*i+~neiFb2;Nh1C1cwCQXOeh%ADSK&av=O^8!F~bzk5e;w zh990z$)E&LG=pjpN2f8xoCUN~kWpemWp`K9?S%XTd3xe3=tZ>~OANub?5Mm^BF2gm~Kk!cA=G zWB>tEMp^`b3kx-9;u~oBPnV|lKd124sg?q5{;xk-5r#czNJe^U)ZBq z9{UNvz7UD%Zevcr-u@(7o{_^hi_l%L^w}!}$H6U#q^59LMS{A$HZQSTKa_SB-P5M; ziB%hCN5bKl$kJEfQKP4j{}BXpTc$J`aJBaCVxhkqI7M$YP~6LaH0W>N1(@{*j&A#0 z$=A}ui%%~}2`~-gnizpt$*$18G`dibKCqlQd)47&2amey z=7NPNiQC*mG&!t;X~PPS682_(#AST5O;xZW!#PsXEEzl#Hs!)LDCgwQJaKt9R<_Z3 zWxkzIo@{3vVWl#}7pbQFts|7L^+=4lYl)wpqf^`%EU0Q%+~S=kIGQbOZ9@xt=_Yot3XufcG;0WSkyg!Z4<&NvRT_>)ItZZ_mRdj$-Q`wB?+@i*fRDLq zf6x>Cf)RdXb=InCgJ%3lmE*I7cDc3tFO=w4O^{#qW}H+0PtBd2T~cP)8Beu1)zl{3 zWt17Jwxa_~;qU&B5LI%vJ&C*fsQVs&r;fd=3=*C4QG8aEm@N>)40bIV8gM4g5o})Xy=0Ic)J-538weWZ)+j9 zM3GVDCbYQlv?H`k2BJv&rG@AL@1SFYQA7LsldXL-&Gm0nB;ZBM*u0;AfdZH5Y&frj z$0aesnf%H)o5zVE8C95cNxnDcTc;ht+`+tjqE^02=!rhm4m}vayy0I&Ki5exr%-%7 zED6x(70=SgJ}xQ`P^+FiZEO4FKRn85I?cGRQ~oW5j41BeX#4`c!4l!HX1h};5gdtE zx-*>1wfb7A1bC_r)_5vLIrQ!g8YeYHTF_@plWX5Z=2TnQR#bjLheh?sr-Qb26V`m6 zohk_c_Te^J9}aGB*rvpG*IjFk%Xe*Bsl{@EcD^riguev<4-l4upW-GlIGyJdt(|gC_+`}Az9Z0SB9r8O#XARxrwiGS z@5e@&eg+oy_3}p-jPB)({3Zc&;GB8nJ&C2X z!U|?sJ<=bLK2%~PD`<8cVkq=!bddv6mAO%VfgqyVCD6A|j(?uOaVPvQ*#5Ik!AH-w zOp_K3l&tU-i_xB7Vv79aFR0v$3c#yM;b1uzKGvqh;08sL9Lc1>)!S=?&C1)_FA*4l z9Hb-+T7D2#nlV@bza~ty7{q0&+w!|FC)8hti|pWRDVB9kAwgR`OBeI0#5nIEjNm5g zwWUx6ax9P-mgXOZXpY1R;+&De%zw(e7l|R51ph-e`T?ShF@F0|x_Zv%8JZL1OiPyc2O(pKTLJtkL#s$^lb1gUWvW$117NrH z&m`6|VU>6-=vB{g76kqsWc7DQKGx{5>PjSM5{MJ!&eFP%Nd^OMpXKI#(lOoX*amd=UhE?^!e!7M; zUG}tPfHY}|f3KlbQ88JTs(`C~$KFJ2-{^GCIz4jlf}^ZZ#HJ`~zC;}#EOI&=v<=I; zCn40wcc*Z?WT>T5bt$rbSpd)N^(Zzz)zgBM@|^1$cfz6*r4GIbpC=(8FMzeT->B{h zg|R^C@EOQ=7dkC85$52BFyO zjO@U4&Wdi4Ra)J37o(<{E+0CXA(Fpyjo7;J>4n`zUVyO}yBju1d2`#GfWJX%5wT7f zO}b1Z`Mt4bM<339B16hSnE)o3>?=DouE!Z@Es9?)Ffmu9(5RykhJ6SM*>$MuZ7Fm| z)QYmTGkpi4rr_LEag?AQGd=ex97zMvY`p))7^50SLo~`Kn|-0=n0Izr5kILa$fh{U z5sRp`PFEMli?k7+*zBBTB80DepU27fGs(bsNrOIlLA}oM=(lY#;rMKkhIqBzfq#)p zXR7Pk_WG8k{*B`FEnp*cwjq% zuc=&2C%`5L_9N>a$v$mtL^@?&*ri96b)~@swX`4D#KNb%n2CSFnn+49HJP`W3BQ@3 zA@=~hEdyelDk%8i;RtHPK@nYa6QiFK;*VdIUb*jvK}O^TC@17>M41PxX@(>-w9rfY z0C@O3rBHZ3S_rgjm`&er81+7YMC|8G@;Wr}V^|YLPJmH*HavpEv zVAm*^dD1ZkEA{`v=c{S={%EaE51-XA7#8w0dNND&NksVsUsqmZE(cG`e^XMMF{7E+ zF`wP8nFgs`x38Ug6{5r1;XqJN=n6(b7m`;|-@ujHsVayv&TjcL;O@^Gw-RJmng+%Q zOn`wDb1jxmWYx*|&CX~=V`246T_diK0TTaaWgO9Op_6v-_&1S=0P|}>jg4ZJ~m zGt5$Q63N#W`DUD}(bLS!`E=)zzJVJ<$_esNs3p?96Cx@tVa{e{l{aN}!lD+c*Q@Mj zajaf+)xc?2!nf~M@3j*@AiFk%FSup=cCDH{t= zI&ND_1=z$jpz~QZE4fdgZy-Xo*D!&3ZZ#0cD1(j_0RHtaq#amaSN|4FUtpASWF~Wu zU7daLyt4$JQgs=;3X29ZYzuu*I&UIH@Y?g+FX;HQ8G{&AD&(d)1!2ixe-lfkuKTa#Ioz)T33 zOn4iv{Q!?(W4I*J1z)llQZ)h3&m@}3IN`o|Y!^^G5%vc?nFabvoQKor1DsSip>GBT z4Q{*uM12!g?md@!vlM4b8~bXS5(eSEq(aemGr$~G2bsG>?#0~iDPzzitW+({k{Q0+ zmc1}K{z7+@t#iGznDYe+FS}Jcw#J5)nH10T5B`i9x5Ew2{}Qdw#0U48?HQ_7iW)2) z2=ZCXyEjIMJ!(ykQB`HtNSKYb|K&lVGSybZ1clhGeSF7%#et$DBaI zPB*&?j~D4khfP67OGBNM(mkgKULa@z9*8$k-3~><6_vdJtZPhWy7J>i@BB%i>&n(E zuKpuSAl?5cr4q7V^NC@#tIk&&Jk8^rnbB(4%BEfff9R(=f1inRY8rh3YG9 z1ID@<%`$sDsDXV-Wk&3Yt!q#K}6LVgFA!W1a@0JR7PEg%``^%b+48Ch@ z(#qUo>CCJ2NI_(R=B2jjWTz=$i$0mmakAgwzEh{;7uN0yfQ@}MdH)3Vw}zjlpgD86 z4YUQ_eEj_4O|xn@1eMcj?*jhGCWPzS zVP>>!T5TJ(6F*K(p0PUdjiX<2Xnjrhk<(@BOO;kEgGqQUkD>aNj-f$t2E5l)aur@3 ze1_W!j>|(w^g-HH!!Q?D{L!B%RbYmF!03N&1JhZoF7ENG(18CMbzBip#ZH#e3u5C@(t)P#Abq;bF~Q2 zG#>qwSq7(+i3Y%ni?_&C2DbYzbtiI7b>XI-ytV65hh$sc~v;O8*1iq-t1&(Ve_nwTSSSFo}N0%E;DgL z(!Kr>2E)nt>S86tAf2j2ch)>#BenEickrpfZ+}iEdFbQZZ!5$4XZgB2z2V5lEFM+j zkj*s$#{7NF00;B@H&d5Ola`y-nzpDz;*KG{`v8owJ9^_JVCEFnovgmL|I92Sx!+aywRf9LutCsM27 zqNxdy&2>@O2Qo<6EOzj3L}9v5c@deX=g+4pcCM$>axai~gv-E~(t!$Al3adrh7BEB z{dFZfEX@Wa=(U}EQ1@mC4D)>oZ&w1LebnIayL6#WmevLe42tr=p(NsHs=eO$uFF2> z?E#M)E?uxyKZ`d7(w~$;gw>cRAWd8R(Ojz|%m&4LFZ`jqx&6`}U^Nx1W5^@uH{PQ- zx;`bMINIw$sjYydIS8)d&&7yxat`|^p>tVPrv+0;Mr*SCn6+T`26Ii#OhwY1kjWv0 zNsTsN>0va~h~8wM_jj(Id&T8nGke2_F(+0EgwjnAAgB+2gwc}nyAgoI3b2j7&+(~* zVg8jvQt4&$?$iNF;T6bJ?yg;x827|o)?v=^K0ns^hj$D#AReYMhH%llXQ9L?;8f+c zOj$G!UvYa~nOR%FjB;R(iwJ#u5FhU^uKQux?OVeHLwHZz?SSOn$0%PT zKBJ6T`m$hL>RF*yLi0;>lk`COFXnOo5kgYZ8$O%Z-{ZatNYbee@$*k>mvKkih5>07 zb|UVykX%n@G3I`>mN;Fe;escHC44T6P&^B%VCUbH(Z4Mpe2drc82nxUxC{-#r)? zcP3x1KoTwkU$N!=%jADb|CwQt0+lrEy*Yt({?CF4`f+5{8a*YQl(kjLQ&>8QC@<0s zxu}2t2K0BM4)(?m*RYj`GWRdMs?pf$F>+mA&Yt|-`$iB@Okc10bYvc$I1079OERvs zY^gH+IW}ntBR`7X84Nhm#3OPQ#K~m|yWR^C(|zOM5K2oCCO+aPii#+ed!*=6R7Z9< z#^j=bBxgwAa>#38;=_xu>axc2T>zFZ(6V~g5Pmx!YULwBO>KIYHDyU4pCbwh78F;Y zJR?b25`k7Uk(t%uhb~w`*Fum2u`D%Sjv;SjQovA`#*1wq_F>1GH)PW%QsLfFV@JAQ z;WaSV9gyd#Z*YLA5XvXcqNs>jHfhw3ug{^tB}=q(6IS_|AWk`dnG-Bz&O+Dav%)B} z%eNKH9vM?)@NRx|1RP&s0F&zQr)X{dC5dK}^O7oenvl9N>O7HBd_kA=X1tIaOjK-C z2G2#heJC~6oSQGrJc?ioRz^obwp}5{Dr);M&J%72sIosE%I7Xqed|nhrymIFMK=6M5Krx@`jnB200{=a;z4&@ zlMZf{AhOo*Z;JG3<*lUeDhC>h6f{84{D>F|~n8uKX*h>+q%p>$NES6i9L{0euaKT~T15zg$NdgL`BJBo}g{E>^;l&2nq4Jb#KnHSR2F zaGMQxZ2EM-b*1O3$f6mvi&#|2uP8tiNrdoW)D~ADskd4Vn_F{ zB1F}$PR9-BjSSZcP!(Vj+Re*p!3G8DHxigzEBx5AamgX!YE~dM3x--%TR^&Y=m5P0 zc|&PI_Hpiv#MmQxMPsL&YRQ>35Zyw!1u;2KS&~bJu=X9@YGnijhS=?pm*o6Eu90is z=wT&XB{JT0v1g()Boz;o`ylOedA#lp!}mvRbpO#i+co7hJ|>$9SgL*tZvs)8v*rJt zY$I~N!7Y?pKX0YCli9#xftJbLK747pvG*=NxLq+E~69E5Ur8os5^cm?JQOf&7W_(D#PcdB=n6z`&aDrZy)dNcKA89xp$nnuLI;!UzI$10WoXGZ0jgx-07J1NhQq2B!<1UKvNvNPTO z%R{(ck(1^!G=!}UOckdVDu%!aJ#Sd#?zx#ke0(`+u{JAQ!ah*%8hvv9`_Tz0C<-6c zhBy21(opVUut8|{& zJp6(y2DKcd<=O_G_t(*1w_s{ojY~>TFSWtC*~Gx@G!pWJooVCJDuhj}}|A`{i3 z^x}tL5c)$dj5xYCxpj~^veB-jhnF0(p8uGd;MWUgBsw=zGS2w`-H;gD>7^MV*fIwTP>aZ>%0r6OFYZpGZU2NRWgg2S zgU@bkubB$Y8vkez$n!X;G;)b@zoQ*Bo4|a}^RGtCN~C4?P~BID%-hDf9ou_+w3YM0 zxuNh(Gxutm47paFH_nqV?lU^6Pq)TjAWrGLD9g|;y?D^na)>G*}qADUOLA^n(4-*x`ELm^tPJ2zSP-RQ0|zxYJxMm z*0eiW-9$P}G*_I~!+FJAqeo6fA^z2EH||H9mrJs9GRXaGayTk*UR$wiiZk72K%vs3zSF6E6N+*~QM%{Qszr$IlhjNG+&qUyYREDBUfd41pI$5sWqf0n zH}@RWAl$ZZKh7SpyQ_9R$vj->^Ek3?%dJdX$JA6AJ z=bn=_>pNG-=6dq%)*6?na@#3|KCdC85KX9hjYg*%B(ijD7Tx8YBMP5=FbuL?Sod3@a5Vr|fU=FBgfJZEg9~>e5kU0+4%PavV1jOfHavV19Tm7dW?rJNnDoT#8g~srqY0AS8YojWLoSwV#1487Wfmk?HD?a(bXh zjdd0wsK>+cXyoZ%)wTmXb$=2ZJe{~5kK0Eteib~>!LS?j_`uBHp?8~(tgG{DYb5Us z$I+p9uu4__B78_5FY>>NrNx#%)+Q*4L3dA%6|0x^PF}t^Ob>K_zw5p3>ZM>)u#WL3SI7pOJgF1Wf|u?SCxYUhZ|rY5u*7H?}NvA`L|; zIWZ=SMlfzc=&5i!fpFpwd(=o>yqYFAGoy=ibY49>#){+-;Zy0dNLMtrMq?f7=7$_Z z4%E5c+MuO8fk-CmB9EmD+`4ZH6X^f9?aV-D)QGW3g9#7v0j@nE^}JM~?Nu{?sa;gbuFi{&MApb)xWwm8g06Vvi{CQ(89A+;R zxp`MX%!)Bb7s6BVj;PFL9{Tg>86v6F=%wV#Nx9{c<@z-_D)4yb*)kr0JG9&rdC|Hj zGiu%jM53#gi~&5_H`V^rZ8U319ARnS)T5&V_9*R zV0w4y3ZZR>O}4GR7}2mh$YvX0n!6$RweSD{K&=W6NQj#cf@73s8y@mD zL~CLFZpJmR_qr4@8I7F7Y7&I13|cy#xo%V4#jQ7 z_SDt+{yN2c12J`Dj>Xe~5uy&&0Nj7&E4bt{DWD?R2K{Ru({KQ)rN&aHY1;G_Usbqt z-~`J0c!~W167udE35FtbX}6M(eYCud!OG#wAHC-A1IF5~Kmh-vQTwTJ)Svqq^cMh; z;=p!P`oet(TOjf{gDct-7kVb__e73Dy!yfS{^()KZ9*A=;Fgov(7)#HtP|H)J^zRk zp757~(`)*tx$^e@e&5GIl;OSz5V+0)C^+=-PWuu|{7k*9?Wh8-9Dz@oNhpC%4JBnm zC+Rsjb=bGpi~T^VFy)Aue&%v&?2J#9X1d-9hHt#Vr1{uY=36|$D?q_vptTXdeRyCz zg{JSF7x2C z$LN9@i+kqG801R4jC( zAQnHpNa_QDv>o2lK&Ya6eOQNC&5cI$@OQv#-{MaIT5gi89OOR3>AI zd{ZIYI75g4LLrSTQcxXy?JWEJN+D`$t*P8n!1YVXDBg0#Nolc@U!A=ceb>D;fo~~J zULy*gsZNx}El$RS#%x}NhSkiwt}KKR$w(B)nLZnQz3si+;Kf6Xy;J;^X3a6uz+P-i1HnRx1-O-aqJ~Dz+Wk6c` zT#e$(#3dP_FPa45MSE%tzT--H?N4&p5qeG`6Q4iY^^6))c^g4AR3Ag*FW?SPA((K= z?TZP;9g{t@#aAjTD*T!*15YpH)R${K>ee#wLqGD-1z(fT_}Z`g+lQnm3FL*h9n8$-h_2e+2b#$ z4E8QNJY{fi^;cuKg&<(TUh~e@IjSNbeay?s(+6%) zJ{i9#FK1HcS4nSB(!(T>J2R@BTe<0lZTLN$Lz2tLExFT9UmcvIw;#!e+pE=!!Wt0< zns?G_-oVj$6*Tu`1;*Tz^=W&$0ZzizT=Q*O(IUXS{vIim)_H(&`exIvCM?^sx34Xs zTpE;G*u(tM-46nc(@K^N_g`~2o%bKA;*wVC3H#AYq?fo3vM&e;D8y~stmHm!pxZr6E8F-1oNG7n%xF*OQ?80=BHj@(9$(*C53sMZ60$7{%- z7|Y3ttQE4)TZ|7BUil8&W4Tv16 zF~P&|8~C3WZR48zVo0yh9C{Cg>mGE!+=@lwRU;$(xcZ=B z=GaoDdPoxy)>J6@2A1AM7YVUD{H~xTu4;7HP|N5T;PO^do+tvPab7CUYpTA2Jg<$SxGpL{5x(&1K9-j+FVx1#s&;eHm~N&hGDz^E4%#seW*6!TP+0aVUEnsh&n-)D&>!P|0cm)gA^<%}gr zy1(a z!OhKFbd9I_iQgA^9WzahbS*TjgS9%8W&Y89FN>B(pmRmLSDoF+T-vrbHKkbW={o$G zv-GzVqu{P~mc_m5J+hjV40`%!thuz@dK%!kz>`)FaS?R#e(U5XXPidoHDPxR8oywo zUG$$hE~U3!ya(E7?8n`ac}iL`zP!}~G80IEv7!a31iEUwJ@M*KkOEC?Y~*~=06P>M z9f1VDQS#=T$_1i^o5)x*ap(Sez3_%~y=qn^3K`|osIVt~T&kfu;FqYum@7ZtyZA`X z=L2R~Z9%UM=81kF6PqX0=&tOQf2c_AAWhzDqJEJZ5X-cP%2VL6`C)? z5DQU-=@3BDB;&GFO6`UgPK;QusUdfbg|80+3()GvyIbvPcJKp32_t$xLUT!`aq}f> z$GvI=>d~1Dp6%C9)+D5UmEGYq01zpGFm}UeTSe!QM6#G4+NVixcX9I4Op&--DH8V6 zpiZ%FYoNn+_3_0UwP%o*GF8h`qn{3S#KH>P2TVkPv95*xAvBSDjhZ)gcYKRYAmPmz z4yZNX#&mUb*)^u<s2KvfwM$ zz)9b;HzuEGoXAFPhybA}inuJ}nOC0eFO4NuZIbH1S!bJpfR1B%j(q~kKN?;Yn(!;` zR-b2g>QSJjE?LK@$K~`>P&!mH4GWxCwF6xS!~`Irz3`%I;LUwIYTWSq34vhaGv!={ zlTy}cE;C-Qy3JWs-nZ~~nXE#;N7PXmqJ=x-U{p?~>h72~y{6qDxzf3KRdev#;}Sh} zjx5yg?21s<3u|3ClWhi|wt<32D0=e?m~;im+U>NlF3mWukF5|CC%_vlYCZVbOK-Sm zr~Kpi24j>cpA%{YJ6pi)^3C|M40l+8c30hxdtHt$3+aqf40P{pCT2z;7Ya23O~__D~RCSjIRd*L61X+kOy)_mhA^Ywq!aQ@G>Q>OuH# zwL%rEO=?P1=;!INcXG;Ljij#r#^5;B}d4y3+r5Alf5WHB9aDR1FAMTItGaRv!vpb0=F%+BK?G79=MbQ;~LAwNp=sh(p zv()6v-q<)FA?yBDCW*7f+o0Xn_v{qA=sXVN$RP?E)X(&0Zr^5ySIga@Y{EkunBmMp z2B5nr(X*HSrDvOQGQ0 z8+VbndT+n;U#3G;Y(dMhL<^6nkLaHA<`7Nr=w16OxOpuWkecyI2hWyEmtTF$cv8$@ zqy*1@+SX5whS2_J(H?++>^|Ws``5F5W3$IO%hyU-a!wfd9+#zxq<)VZBSNXrF$)X z_bk}?KLSxbT=8N3SBRVB8mqlFr8agw0oL=TY)PxIPn1IPERWfyz>UY!*~c9p5Cje_ z!$GKpoK5wz2he#Mc>6tBz@q-Ig&lAzccf|$S>N`(IrOZ*V%MlGaG~ca8BHH%B{m@< zg5a7U*0ie<;W&27llNZSoAsJ3W5mRrzZM6blSR}GG`Vq*Lnc&|B%>cH7zJQqmteq@ul_cU5s)7AU^3R}GKDaRwa zZjU|P&&UDk>eO%TL4Zp4v&9i#=3~}{X3?W+l!ONneb4m~$9PwhUvba!#;^Yov{xVg zSNwwlYy2>9AX6$Uqx30%JdU5HC{dV+us(L|U-647uLD{f*>Ck3nZ?s@Q{4vlwbclF z8w(X>!73aE<3(~(s3z0aWc$@%0N+;v(h1N;e5zQ5=#*C5iOZfGxodU)~4mF z7PjaMYM>DNg9$?v{E_~j975-7v-Ww+1f`hBS-xvFmeV>PoQcoy!D`@f8T}v3dFaLx zg@}`d{ahH=U?KAFYQ*yEOE`b0L5R0VUx+*s8ag* z-YXDxBL0EJ{<~y9c^9IXu3JqEhYIHlg#;it@?K2zCrJ~$*@1(THKlFTMy9#kQXT9{ z72d`P@Hb@g1K(+A^t7FwZM)d#i+2%S@?-{_r;iEwSoa>9Yib;>Yu|a!rSnoYBx>}% zCV6s$T{F$z9q0mt*BuR5`#!)_9{q-{4y#BW*GRcy4ZEoM@SD!1pq!SwB?PFXfHBl2 zI%wP4R~Wk-IW@$M#OCM6PtRbe#ai@#+0G)P7<>T$gI+@J8GOESq&@n5FdAJj61Q!}>P~mS zSh~>&^r6yd-`9)j%-(o$$eErICuYJuS63dMJb1|ziq}h|ej2BLBJ@XV3^UL6MX|++ zZ>cO3G+<(WVxwcbyStaRP8Cmax?&<36g2Xy_B27$SNYw^qOiNS;G7OsY3PVP2IBtUX!~sDY$W4qH`d@)& z#9TLiaoa4CNom3iX6R9oP-57cmAD--4F9r=`s3I3q@jjkG~3ez)?e0hkAP;W@2+W~ zbe#n1DTaw(oUzuiHG0uY{h1d$Zo1Mwxn`LKOo$&5C>LsBD*Ax9c``Y+G(*0E6sahY zQ3@?Yo<_*-hPjIjvs_SAYf^qus!njZPnG1_`4o;Y8R^S0d7wV^j$*^jy$6uxZH$;) zhe~V3wq*5qLECKt0xwiyrBFWt%nuEY1F#JxDgqHDZM0HExe@!+uY})ssMLlLRc7^qNU?bef z76I0jM3tby7ror-(4H83o>wYjSCo33Z;hMw`-EHbC$Zz2=$<&EH_u$>RL&C{jJmk7 z+%aMD{0gru>}U)Zie(;crU7`90R!EJ5T}dU7)TKX7z20bOhfYY+i9J<5(geav z{rI%-a(BZXYxO}zO%UnpXq5p>ryFc>u7wdMd)?qqr`3Ta$Q)C$MM^se90G>f2%v{1 z(|2%UU0G^Sx#%3l!_m{Ne1+}EeS6x|IV5z7kX}OY@_^9E>;?b{RGz5N`^-Vz>qj9*^$MK&LbjWNHBZ-stVwz*`8{CmphWThPgimjA^N$dGXK zwGtsx(J>2wVB=}iAbx6<`hLY<0TL?m!Az zZHu_$%KHPNV@f_IOa#(B1Cu6BZhXOX@T;&f{1EVR^gMqYum+%dRcBw zUp-7*3zk(h`Wm@f)~%5CzkSW;UgsKt{q{xM+r}L3(@ki7Kcrv_-CXLKn9gkbvsWat zOnsIrC7FJa5`CRG^sN>?mMtedLM)p3Cx(Bo%R8?W2AM*%HsE-v+J1XpDdcB*Vbxv z-&JYlu6*xlp z1&wLZ4jvqeY{{^z1C5D4OD1oe_%4m9>{=5B+t@9*ex$2RM9O_fG9{FuirD{FZ|78= zbxc3Q>7d%DWj>_+|ENBhmir}bRww?Z(xqtbAT!>K1-%i4xXrKvob2^E=|dYeL4T6z z3kYPmbVo)H2r&Yu7Sy^yh@Mq-n z1I&F2-5=iVU?44V z-Lpt8AmC$mKH1(`Sc0-Y}1^v%Av=6hK?R_GAW8)4LGgnHy`9V zT*UUK_GY2~7!7HDsW}P7Rm6N)fi`ZC4L-%MzME-=w_7I{37#pJ#~Bmu7nzKc14Mpr zH?+ta(K8!3^!C_O3F&vB+)*(I)coN9r$B^-_pYD~}Vly?zNS5J|(?Wj~YNN%rj zxWc&8-09!IicsE9$hPwDCpxWodE~A#3RIz&R$E!q_dliNuwE_;?-x9e;SThlp`PI* z^gKN#*8x-8nNHW_*U-!Lfb*-6@^4%XpGwZ}2x6Zt60n}#PaoSFbkc(=Tf0wpEBAc9 zkkHIpL3g2R^`M=mM)rB`k9bqKnY9`5@5Ezw=^PV&*JozvV8Go4l}o<@VLoc4xxrn2 zr<*Q;BpMf5Yh2g;>=ChciueU!XDs#nVxW}77G`f9`;o=yni-@g30H`D~QYi*m4O3;J(FJdF zT4$I3M=Fi{klTxQt5a85l|Mc5f&>Q>E4m;fiC`pRe>;hyxd?Zzds&rqO-(9=7GwXj z+6LG%OIEYM9Qf`LxSDvhe2+q2kQV zBdAiBiPJN;HDSI8X;8FJ9RIsf3miJWG`>wX&+}9s(2$pxf(s@i1s}QQOWoq{VrACWp$ARY=v#}0d~sd2~tus zXeu#E@sk?I7CCqAki1u0r)D>3d9ouO&h~!bU z0o}*x%EzOEb4=Q&Ce*l@no(MZbfJ+tnz6>vdOJ=0;mO7;OADJF#z*1B2U3%#tvR-K99WukIwhQV4V2wt;$coHEs7v71#l zzfc)CPlu*K^_RUw%+Q+Zijn&_<5NU!b}JRcigaWR;X;Xn13`)1f&sLqrpt0B9d;L) zlTf_1q`^|iTfFUv*yx7c~e&5PF|$K}A? zv&~hvi2MWqgaGWqWX$J6@CFI*Bx1;uyiOX|oUN*L%ZW3z)f0SN2~x%(%O3BCGZIPwMvZ{Agm~z=Y8*x zhLyT3f;u{SY^MV(Tl%GhH!DUtMz(XhpWH3QLB1xvAz!HKj6`oDSs0QvzUs<-cIX;M z2eYdE2>}=(CAP9a7ews;gs@KO{Mbt@j*NVAP%sg`*u8VE1d;F4C3Jc@q*|Fc#k>x@ z4A<{ps}=xUs7z3>6Snw3)$aDUM*fHD`@PD<%BC=l=~@m1Nb_IzjYgH82duE=`XqLN zGXw}U(p4}NFjCy$EwAaj7b}XD zKT7~%{Kt0MhD?RtMe7$Ba`}0~Pv@hFwL3z37C5kct*fDGo(uYsl8Z~^A zD-w&e2+_v@-6OYzW)IImV#HwzF(}aXm-EbdM0qN{1{LJ_(iqft)cOEP=Pq_-3Kta1 zwKfVSbRYICSb3Jkwc2y)bFl6MH$#kMh*C}^oa}>!jG7H0Pv)04 z2T`&?AHO01w#PcId!aw>{mu+VBk>2j28xR2$L&H|a8(l^&`Gp5$9L|f@>n0(mV*_L zn`*IaB&BtqbO9cXiFh241r95NS6o2;oxC+6z2CXuRMijb+S9zvS(ZhVQiTHeTCdOR zlVbVyHU+3#dLn*glBP3nzz~!G06|ii9kerb32@^ano*X8IRNcH{1{VN{BkX`4BW+@ zKRU0Tz;;ZCt3#V!ZG4=5${$FECa$mIxi>l+f~X%jvm3M8^2_e+_e~GkyruWJLufU= zbsUZzM_efxC9amu_y#(W0#-{T?~kaB0EjBl>MlSoyyxTLVE-Uu&s39teHGMbGFAoc zliPE7IhZ35?VexmV9E>VMCjh=utH_3BaD*am4;JX=(=2EistGD<`Bi4`+Xv_sER5^ z&SNFSiYI*2aOImwx%T#cFwWj+nzdvPdkZ;5HqArhp`&f|y5a+#ffA>y< zB?LU9Y#q_EVj-|VUe2mBTit73EyVKC&7)3lLV5OKjyxy%Gt>r1IHkBiO zRyib}Y(vC(n@f{oDf^n4UP+;H zErpN{=spJ9DBkv%aJB%I_7~er#sqyH9J2dvzcob=m#+8E!LOO$;+|vcsiI+?Wp?i- zWUEUao91`yQTvA@cPxIB?t1l25sGM}iOxs>Gtq~taV!Jnl?h$<(3PmjC~I9NG1_gj zIstZ_F50Yh&q_G;oP6hdoPJ6p&)xZZ7Hr(@Yx5{&`F|QE z&n_nnx`@X)kO-JjM3Uh2yQ?A@)z?zEby+2oql-&M0e^3C%RD}OI4&1a&M(@E(BaS& zmw=d#`r%EN^e-A*Bjrexs3@7Kxnuu=*$f)Li1aQL%yJI47HYz74Q|#%V%~y`Lea=J z%;h|c#1s7gj4xKDs4zPU*mExc#to~-_f z9#+l|U}C-gYfqGbR)nV=WKckGNsd(JwU9!|^-hQrX0TG#gz(?lA~_{j80l1Da{6K~ zj=kMjL$ensCum8?8Z%;3YeAN=6Ym!xY!ZyTzVaOc_`d^5PjVJk5bwf7H(g!xw|&D~ zGVL^@Xe6KK1mP-2T3Z*E0U;2+^*}5XfCAdnjYba81~aX(Qh3N<6{z3!DMG#^sjcRd z)Ou6r^MKC;A^YqHi!k3YWbAi&pmg7z6rPAzybyigz(RQo$}ih+Ot!Ss0sU$2wI*wa z>Gw$)B=Gq&5nrV|5>{|H#Q933$LFG*@epd-g5o?%l39n=w)Z@`oDC-lCz{2%N0VBf zGy)%1W(1^SPfF7o;k&}VG$!KS=wWEybHEWr?1e5GY z(7M$D%H1FQQe}F7=NoxeaR+h3%>D0AIP4xy<8%8skq8BWr8gVlyp~uaFkBo{X_7J` zsT`F2AD6Nx_$TEm$cgol`VD|TjbG>Pl%WaX@V>6uiV@o9cN3Zo+)maB2i@TPq9tb4 zG?17xh*nI}=7IAOuC{V=UY5bI>->T&8G`l|+ordZ^{U z0PO^RZ#Sg+mkc7UA$(E!;?jg)u zNt>GM)XH0@S-(;TFl5ExKYS=FPp6B>OQY#I?QEKje^hGDjV3bn%@l2CqPRy^_XIIF zv|if(v(VgIvi|hv)+>diHV5ws8SS+Xn|>55Tt%Kl#Ld*yf}-3-ut zA&kQg$8Tag?=vHI5%bJ+%EM!?2CmcM#x-c^3fJL_B9N-?|7cxU3f~`4=jic8 z#NeslEZKRW##jpWg*Ifk&pwiEwC6#$4cEX$`6L^JQqrj1>DOjkMUUEa4%dSGJ^45Y z(uvIxfaJ1u&GNFSv%o{w*0K*xo5_O*0)JeNFhcaFPQ6`*yn@20lFT?5`XR5=h$t1@safi)Q zrsHWj>1@=(zQfb;bbwLzQI6=kf?D7A*yl#lu+&$c6FU5C#)d`}UC^tD3SA=*upM+? z zrxB*tQqX`VIeb5TEB6&uzriLVBHO&v95^kSv5nyBa%4{bCYUBJy_tYW7W&ZnCuvTJ zy4v|m>a7&~cn8_B+;r^L!_VjZPi}z6@10PqV(2CiPnvc)O`MgkZ5(ayHhQx(D4{cJ zG4D#mRw25FCVNnhu$rP^{?{iW5O@&NjPGSH6cJsnlu6T1kD6g0#F3cc?LJ<1(wLp- z9TO~Mhl+qJzU3y$s-Y*hR{TC zpAQHKqE?dXkq#5Z%2SaiJo@;wsUc;ldj51sxX^Sr4Cwr=6rbq-ZR9fTDH-E_lc?I3 zJ?+tLW{LLFn`9GyXj3Y*DQ~g|j;#P2RS>m_92OU1y!iWazTq~%=lt#F3B|hj2K@Dc zK@(5Ql^NBVihX$NODr~CUU~L_Q9H%_X=|xbUmyCo)X+_%)M?WJ$FRlVlk@JYzTyo3 zbrsHpw#y(=qDN4E5S4rQg|_$Dtb%`uy3*`XYI<@-UX?MyskucXy%_e@f^>H zi+#Mi@Jg?GDQT8vA0e8l-!2jJX)b{?&ENyDp>qz$hk{v;u3)V@Xr97?(Vao2+h&U5USD;`##+tz6y{OWWk}=eH~doTIS-pFZu*D)WJND`noDjI7-2 zxGafxeajkHhB{~g&RNeiwZfZS^TgtePa*_WXP)NFLj*CjThp)^6hfbtryNeXLp4YG z;1PV_){JomocU7iS&@Yjn+!b%w=EL($=*6hJM-IX^Dd*w+=pXyMf_2+t@b`kJt!2N z3GFHADk+FLxH&UK+n676vzuZ3=N~2OAr$RY%A1g0m9L8%eDLeGfe6G(tXLB-$81u2 zplA6}U%t$=wB0-T=a0^B^|i_|$uj0VHV4f$A>jS-f&wE3i>(!DSz7Ojm|!QtBl|4s zX1~^i;4(6|%W1aoS(g%KTSdB!n|^sBK27VOlfacefp3G#ScvPd35Q%SaBBj846X5e zzyyY+tGN#SVy&Sg67j@ql?+IeOU<|K&#S_9g7%`$_(-H!twGUtO4M>Uyq*V`G|@cG zVPDdSsCtu!t7-&!Elnp~@Cq#xCEyym(f@D}yPoljM6POks!4sZbO-z_I^IFlE`l4W zs`7o4h5WN@r;=X%P=lN;!G6W51aWoA9FLGh*a?XL)*lmXfF07^h>kB;#8# z8E~MjW6H6byN83whK{IO%_0GSK1!?q;34{#;(z42F z@K1kNm8ts}MKF4^oEt}bM@$qdxuGy5#vs0t7U3DKV1^5f`ZusndQ;XJ{=p=Cd@dTz zAJAD7-AZzL*XH8(zUAfoZVg0)XfSVpzU$mfoYDaUvHd|#{4yjT*0P}(1Q_8S`D5;nWtFjQ+ffW$!&0R8F2CO!#vl-m8=cVX@)6+iq;CIL(r95)nqb?ZXh z23lmT=TkuAo97t25-ETH0nM#gj?PSMJDFr7s}geWC?KaiXrx+sIEp`tM5AJ} zP1-H9^pi;wy+MpOxdL-+K>n^0ko-hb6+_1*t!&q{tRaPo(_{|5?luNhpk~U5A!T5B zS7id65apK3DM(dbn4fLKO$$!$mNCj6Wt$wFrkd3)_`${pO#V#v3Cv&{pPk=K5D1|u z^g930?qFbq3DplGc8tL*r}CN%7F6{?!lRlU6ifww<)s|UcH`ronCTDRuJ&)$tL4-# z_FEL0A>Km&I=cPDv1B8{ozZB_UZO#q7fx2vw;^k4#$EUYIrK<;yt>hNq5Yt>#t!RT z-pLk{g^&Q?7e!ixGQFMs*PhgivWX&B)p1*7tNCMP;BL*2>7J&EAj>xC|7;#n;(RYc zp#vy8ijV)X=AZHb_&BS>V67?_+G!PL%vysXcWr`4JQ_Fz=nY{Qh+(?4M*gEiK4b;p z;X$y|ZBTP-D2>T%BBwrvIQI8@^+FC&+87M4!;Ssm>G^gKv~!qZ0TRUb5qZ>y8Oe>siz(yUlQ;ZStZvXt)%-uF@ zL1$+XufA9_1)4CD)QANvAP6PHRW&C-bb}uvllq2w&GtD(eA|^1#y#uyakm3xfxr`k z(AAumhD-02B$w;Vyd_lPTu0OFWwia;*fCNKV%fjAtNrGY@PBJ%jgSsC|G3Wg7>|j& z9`*?DRkK=qXu7~7xw83Dgj)+N2Y+$qLghS>UY0a;I0G_4w@3s>4xb)>{Gu64k{T@^ zOqr9$0g%H|rnNHC!TK2cT&iVE#=|SyUrkYSP_o!))x1NU``FP=sDW=D(B?cZuc(`+ zVr3Y@zo}Pp_c6oWUVIvmSGv_s?rulQ2Jlr%#s?;>9|&$g zeAmy~;mz-*Bh+YibPgL(m+=3fTtX*#2fzRT z75$AG=4)|n%(L*ToEu#wGVp^!06uS00IiMMf_PJ@FfhYP@6tM@s|kk~C43D8{*#-) zjb`T0z!b5hs=Fsh#tOSCw_0K`cTybTJ-Mi>noD=dXsyITG$vmnyaG+nPItoA(#e{8 zV z@v#GKG|7yh*AN2T+hEQpC>9<4Xgj9+Y4W?Z4lTf_^`5$pCe7;Nd|c_fqjJ{zH7xl~ zyaS#;;EWc5v3+>rV%T?iI@U&1b#5Qta&dTqn`ysd0)#<2(57&A?TU`01Ffs*5+-|! zn41T(MgXkXgKAYiksu<&)9r# z^`k>1`&fKD<#Fr1CoIlZH_wI%+J*b2^5{`mFB}!|a5Wr;j{p~WoU&=oR7zW)$vt@4 z>XGa#-Y5%qQRlJ$BDfG8+3cF zQPe#tUFs7SC`#;2(=0e^TQR%N);*3efQe?NOR@~GyhEfic3u$aFl!N|zzB#3tW&Kz zlFHggnV@AhC3EXXU-*zVkCP!m`CN_ci7%pueCc=Xjwo~-DWFTKOBLaOrNVUlCuT`J zdQO0d@1;Wpe&Q^&sQ8hx%g05`9NFqC5p_KF|6w@1pO-bZ#hg8NLb_=$qrX8l z!03>a#h$`nc{Sdi#O##;7&11bbQvF!w&@BXU}os8{Bckn0U{z(;4?pm*3V7rL}(uu zD1H-D_Qwgkd&MFGK29^mt?-jx->JzA;ip=&r}t#fB`k5r0x&^bqPbYErU=6pks=e| zQ=bKPnxKSQ{mYDrFCrV=tfV_ZCP3P{;uEAg9+)I-B@~{9a z2eNR_EzCeR*}o3g#qbPSO4YhL^2F@2R*2^zei3x%C%l2gif$<;#%vjen(b=Y=Hf+ip2l66|HA+03rC*&QK-(9 z@Fdx2*241@bSr1b?Tx)d&Z3PwvM(PrItWqoSmqO)C~ASKexD>aE1h;AsMvduv_!V;0@;6)t41FD(f=n8qLm{H>QJS=HT6%w;Mp2R_;1+eul zX3y?=--hs&bHJq5X_YeNja$n-PMDs>A6DP zQB+u{2Lf7LJZD;GU|Ma+tVtN|3~?oZzZknA8+T2ZWEC;%YfR9@xAsV;+rL8X+z1Bx_mH9pxTO#t|0tP>B=Xo^AN`M?6);NVHI@ zC?-455`U0;=HMfKyJ1sCzGPl(_#u?V+IgRb9s*YqQpPb+^047y!SAW~`w9qJMYMo; z1Gh4RquvVZ2tW!09up8DV6RUdYDcmWO?aO|^%UCj8Tw9{Joz()p?j6D z^sMM1F~SoI&T}Xv4K<<2*f7bj3a(SaPp|hfZ6Cz3{@ta;`WuoLc9TQ=qI4~`%6DV)@|(^sc(qalNKmff5anY(NM|m% zXKJ_y|5BE2q8QEqW$yynH%Z2Guww&4gdPR9<;92z`ShDY|%k0I7rrcbe5HM3TVyEa=^_>lj z?!s=5s>$u%$b!;QxNGWwbQ~26n}TGQ+RQ3QfPxtOzcB=AD0romJVdnZEgA#V38#m~ zPRYYBSTSJb({Q4n1n5S}^*%{XwN`!@l3J{HQI^lNTmn-`|K#rpJ2HM|a=S=TcGadB zM_?}nIre}P`i%lJZEgA+_6pob=KHE?0ifrZOwM#Qcq2scI@T?y*3(PaJ4#ESO}oKB z@em>8Vqtf()YSZ{yu7FXTtOgw$+pkH$`!X>WSGa~`9=rNS+u-L;nu`fwm6$>xMc=r z@EG9}d1s{GDWM2YE~?Iu=%!l~iOF;R?+X*9{A{rJwO)kyx2o+zotZau-Z$@7I~L6n z5>I$?nf;(UY$y0u@7>*K2pO7Sa#~Ex@t-9T{#)caC0ptV3EI4Zf12cA{8hTx>BycU z_KATak|MIRmS*eH{5egOtzTJCtovpsz95PhoDAHjWv+yyzJXKj!O5W$2$)d=a2fxa zn|+->WmFx7tn!Ooi!oSwYY_K$%zYCuiSI0fj+D_wjDTyiT(rQIMX|2t%SCf~LLt1h z**|&t;egW*(Ax#4HA8tUMiYh{9TfN?0_S3cn>p>i zBM!0Z@>Xr;mZ?v|3LE(AH;T6sswcw@ctolk5e^$%%vT&5xIJQ648>Af_ddC*b7ND$ z0!UM?{BjC}a4DQc;UHbbPSHJ?!7r4t-A4Gw3^v4)&I0ZXY z)_L(;&ReJs9K;BYSTTJn{=!O04Di7Ae*=P_-l5;UfL zin=nkRwQ)D9h}Cei@ccNt}?#pyGAc*$RkWvU2V)s3S`++0?Qk2cvo@ZbrywfwhHCx zEdkqWpK)S~gBtXvaT5?WmUjF@>g}<%6}K1UE{Miy91`um z><~x1uyt*Y%2GuqWFx@QWlL7aJMZ~BB<${Dc^L=Ku3`L+ufWoM?E-P(~F&jgJ9ft3Lfxjy- zmsq8Xpbg6WHHO1u!A;ejkDV^LN7rUC73482cFp?o4}Q2tr`9w5YRK20P7iuXn8?im zgK*AwrAjP``d1F<9 z99pkACO#BiHXi=|TV$(Vct8S40`sd+WdE~K0DCo(X1Yq_R@jc$T5u;w=}K`~oz+6I zkqRTvuH-NvSZvq0eoC=pfpp~{lwt(F4Y;WQzYMNluWrthxccIt`=Op*^`xaeTreHO z_#GQysWFb$E!(E`sKl6Zx*M)Uy8HOhRZM@vP}>W$K_+8;?G$EiYb2V6FMg6d4g-DC z3<}f#(gyer2j$MoxwdE($cO#9uc0PvWtw~Svth0Xm>ag@?SD5Ex8HSpe$31K{IW^g z4w3>_@b3&HlRq71=qUWfL<0$0T%0?Mv9iqNvbPzh!}?6xm%XeupGdAWNwCu5$CrXoRMnm zV_lXlpdBNQ$qlovatQ0mKe8A1SnO@*^5pyGQF!H=JUOIl>U2#b!#yMT zOpjc7{kY1Ptoh$_x4J@~$^BPyL{*!tJ|Xm8MzVa%WCaCm^d7`~r*_x#ms)}@S#sMM zU$l+V#4`s0<<9`I1aSy?zyJUP&HKF;U|pPcZW3e4iW! z-~ZGxDfvEh4(Lv3++YIW^z}onLM#s|1ZZLsm0+;r^yzoX0LQqc_S4h2j zdzzMG8WnFai%iH0#>9|JhceZ3Z;Esy-s=2FhO6oLol!Hh{Zx&9B)h&H_n0wiqf`(} zp~A3<*=ae%H2@Xf-MIr~RgwtmLJunkaUIWZs#@diYANJ}$5|~{78+3Ewj*C0GdBl6 z^E_ogq8#r@H}SatVzVWI>L-zzan%nW$*jCRoV5Ypsz!4M_c2NVuz*w5KUgo8fqwV5 zR~8A0&N?ah47v`7Ed?I(=98t?bX&4UVis&vB)}0@TD)nspN5j5Bf<&Ej zY8?qQSd~$;<-Y*X#jS&XP`WPzAs=4E4k_qU9`miKcaD&RigLm_xE#68Op)Vbiv|*Dh+1`0QSIysdpNO5vreb@#1eHnhbM2 zaA^?$0RsNZc?|x7%O_Kn#g@0gDgrW~0jN-85SYYBs&^WtqDGIQU7e9V8c=X3)ZG!) z7{z+tC1A8b2{aRmSGis>Q#PG0-nTA#rr^eKl(bl~AxhI+#l4~dO9e}^yDxO>CH;Im<|a`(~S8*03z+|*V5h~Ff&P1x&~W52)~kI$&KUr56@~n zPSLYhzf#rpTZi_G-Q$TVWI#Pgt!;2W2AXFTFXe<-TDOnaA%lI+H}sM~NGp@**F12t z=IcaSgfr^d3%_~b!_Y7?On4h^1wu#J!IpsG2K>kX3QB^xZiB*VpBS_#8rlOM1(_sy zxPgy-+39XyAin&p6%IpG@Rdu3MwAZ=m8V0;T%||3<|Q%k0+q{^Y6Hu*i?U@72;f_s z$Ip^fQ)nM{2L9OtcfO22)3489>NSRNWp!v5iLxE7n z#hCNd;co&T2Lmnss*9LHWaE$B?z6x_YfOIiwhx1-tzhso#Js5*1^QB?JKog&HY(0_DY&~hafNUPKsm^=?Z{TFJ zzGBp%xZ!-DiCFfAi(v<_w-LILBhBtnhTsHWgfUIp3{bpmwQJEK%o-v9H$Y2c@b0kX zwq4?e0YPTMd-Q?Z^6<$0Kb+poHSuR}z@Bs zdwd@J@zz!9IqHK;#`Qn}DB#J>Sv4@3DZ!u&ntNReo^~)n03Ng`H-HdeUo^HZgeok% zfHQCGmDGaD76CgCr}W(CLBRx|FPK-HwZwo;z!}{^g~Yp+Rqkz&!%sopQD6817&L+n z)19Oui)H|r(Rq7*592z;%HXINOawS5JBcUZ93BRIqbaHX?rWn29;63xd>WPHy{+T? zkd-?JJ?^nYu>`X5IWaZOb$05n17f=fWQ37vs)G-4!a_}~Z8Ra&07nM20iaFYTMF>1 z1VZ}XFl^&#m|@6JBlhcqJcIDqh5JlRb45@0lZ9YM4~(i_37{@a>7+sHiY_mH*z5t& z8OY+)PtrPnVpm*{CQlW`vhBoXUt>8fSf4fiT>n$bqiNw7+h!{(js_(TtUO zo#7u7>1=+XVze^z45hE2nt9Ddk`x`Lquk27CyAVoi zHZI19^&55yIJn2VO)Us?FaDo<9SO9Rp=`h60 z;>2d^|4OIgx8tH0upw2GZXtfR5Cwx_u%r|rr)2Dr2;s4;G}a;D>^y!3W<0Ge(#HRm zQ1XRAj)5G^W>~>2XBET{CtX%-J_WNnF7=(bK@$S5{{UMH&yanLJ$56woA|Uiyo{ct z6--U>CfkBw_quIjMrk%0IHi!m)*AUqjLY$R)F@AGRhApKdcvgR2c&ubo;ddeAGL*P zKsgj0IGs=G9b;<0~7Dy~vON2(c36=6*lJ<$d$d{fz2^MX00JG$OoNBBs@XP~Mu% ztCB+BNZg-5voFtelv^|D5GS(;!Yjt6Vv*^3Qg_9YL2~EF6P;8Hw?&8qXA$IC92U4~ z6VsKz2=qCiM5u%w9ywS7S!yoaI;eS5i9(8UJd8f}7t(CyF+R6QM)gMVvHVH-&f_qv zL4=!NgoBkrYsnDzoTST@CjO?5tYV-TSGYt`@(Mg8I&!E15SEB`Mv33@DdNQ>sX{_h zG<=U7qPu9Z3K)BaaxxJJuVOg+L>QgHMv-%Ma!|4(fUR1wscIfxjiJNWDvIyatmsRb zLL;sWKu}0Z-$<4{VQ}}!o3R;67ILLb5kY3%N5-*r|2Y!3huP!TO$a#e_SePe2vRt} zu#D_Q5`{GtOuS7{IaxSj7~RP1?}+N|)i3mOa^z-)<}s2#5W~R|Mj|kN&AllHaswc| zz9E|cjzqRnzh3cZKrZe4wW4@X56936=eCo2hxMwVjF#2@LgExK7;VbY71N^2lmWG4 z03+#D*De7T?(=-R6rVrLvK3P=#yJiXK=4~kW5 z<7KM3<`j;unx|*O@@}Q~v(z}Y>r704GiOM1phbS*lIvlppN`t)NE|5ZF7u#y=rxuO z1v+Q&tS%-NuSVytdejpH6820aJlW zo3;=pKZTZ6yY>c2q!cj1co-L4?38y7S5D;_-d}?78+Oc%df34-#GGIdGqcZ)tPfk5pKCMuJ$!(Ej51F^vaLAC$YU8a3>}2cX&fW? zqG1w-2@Rcv90A3=2oMFFEZY=t{Sn03wx}U*$E9uJlG-ZxOfjYaEQrr0SGO0$#YPJC zqzl@Hd^gf7txrO3DYK!2;PoC#SwR5iFz^~p8t}d_HiZEG#F=A53oMI(brc3lmn)Bh zEEs5?u1~I-ND)nL#Uz4Vea$=nG5M=cneX^|MfMi1yZs?g>lWuI=`0NJa-droJr-%g z7hwjpUhaa&Zp`YDHq{Ud6?oqr{K&q*c4xiEcClwtA+aBpP_rzH4LjBNXp3c5CO?|> zkPpYSnV`K7!kHV`_Q}D;d}bKlpSTd5_p%x-A9DBZi*2PnAA|fB7yHi!0NW&$lzLqm z998j;=zHR>Nq0f*@fmh-E;5UEwKMFCnp-u%9bG3Oo;kcJMjTtQ0_H~KowPkU&8`*C ziB&b`a^v)T!I&(<>OIB$+aE_x=tW`+sRi|$f?;Qnik{pYRG(0L%QXVegB{H7rZV~) zFDMjJNwNaMBjU&NDuB5FZE+Njp+CF*NCoeKm+ASDaWO#P(HYMZd?^s_HcmaQ3rT+6 zS2nXnbA?7+Nx`9w8#{D!u4gJ^!7@XYV)wjOsT$OX4~la-0008^L7N7qpg>z&TU%PC zwI)*l00RI6{{R3312M-gY~1;N_dX+Pp?`n}7C=fXDRvC+NG;p8dSDSi7KC?U*C95+ z{j=f#KIfIj0NV81W*Nz)9$LI9fIEk1K4@a$6apWP*yc}=0-j!X%}b|)qhlh5)CfGp zlTt+)5cmRj#w`S4fa5NZe6<(D<-ZYuM1%ucR3~}+I*+=SmqGQ*=&B0V1oj9rW&48> zpgTi2=;nZcXukSjFGf!~WLvcy4CdEc0(v?v&?Vol44{p?4g+SL@dC894MM3Qa#pOl zn*aa{@w4LH(6;?>Yz>}f8_rS7bPeHQCE2!|{j@xz(un9*J%nSZuD>ok(r!G>Hkdv5 zHPVhHY4%0f#yp_}lJHC=GsX{=G8!4z1txPDK)9DNb;3$;009Vz0OXED(RJ`)bL|mz z1basK&e=H{fWwPkP&i1k z_)7buOQQCC^71W3mo=F$T#NTvsFkF3);&43#l$u-5{Av2cccI;4CNL2G;}8GYst7U z0PAK03`@%@C7PmR%|4>auHEJ44Wm1x%S@MP%;I;TGIWa;i*InJPcvtbV$nbV2DoOH zIEd~`z{J`lM{8m5JDG8Jne45@u00dafYxa^H>1(ZxS~>j(tOlTfTwgsA}ywxj;D*z z5T$Z?44shWt)rJ!5WYwKT6KUCvxe8ZTI#6G1n`nVo|UNz{Ci2>Bi1I)Fr{@fa+yrL z{A=YPLWe5H`?tKjNQ))bbEjn``D?fJnmp(o*hCSd>o10zA74s3j(=pl&z001te?w)hdB+=V~q#`?FMUmU& zv_Q{Wo-HUR7*b;UXOp!!wmGd1Pe=Fw1&1?h@z#SB6W#r$`(JtR06A$gZ5t;D2&V)E z!-WDFU$;*J@}*Jpl8{NF{I*g`;m%DW)Q%UtDHN;%-C1*{6zigh)4S6Myj{9phJeh1MOZbq4`Jl__Xl&$9} zzsX5GY=h}6nJ*c001FCf(`ifX(a*7Dya=DX?qsxlTF$gIH=Vv2!ifb&iu|^`a~a{_ygswusjne@;$(VkL2SO zw+YdwI7qG17Yxee6Tt&)xP}#N1&a~ad3!n=KhU!E)I^xAL;z}ri3ZdPgTEte&~Gl= zi^YGtU&snF*kV}O$N4B$313R668#@AqhV7{aXIxT(%F;6QtF96Eh=%XSEThll|z3p59Td&5d3@4)&#;XhDm+RkAj|88Vbq8);^rHNH;HvN95ieYJq^+dcB^*a1D5Ie}x? z=H(sU7{5=BAj)SkU=B>X42WrFPHRg>7XBQRZQ~0`sbHEhF&=8&CpSh%71wNj&bOXS zbLA)buNU~+)-exq??DC!&~xC>enQ$$MvhJg+Tvu{<)-X`w@nHEPao0qI|D6ti7_Ue z!ur{Q#k`5)?=?DQSA)vfG(Z-YEX}-yg>$Ku&t=h)V_+2zdE6RmLCHlfifb1F`2aAb zm}A&ZpFQN>HD{0ss z`~eehA&naXxtD->$QEGenyK4ST;S1Nf=IG}B$S&XD^g3C>Er#s+~>ohP|b-L_^?ayVcfPzYJ}0hC#ScyY;O0&Hu-mIZt!x--kTv}kyz?9V8g1|OXdp~*kw4#V8;S4=jXMDl|Wo5Xo*$3hov}6Iq zdzG_$hC@uyFN|h-u|ZwD&1G3{*!2?G7U?L@@A6 zXn_)*syfr~2OR(a0d4`G7L0U?{{R3k=?tgm9^=R|_3^qH9v5(lvAMti?IeP%0=w|Z zhGjqi9a1qH1Ss`!?NY(Wl+7dWMtO9nq4q!rS|S+vF1joXEdUvTp!}tRyTTbGxG;NO zjGzaJzAuCBA5!@Y6im?!n9~qlEr98p09Y>I0R_kiSVUTQ`kFLF*!JuQq1fW~S}j=T zP$;{dM6jb)>^Uxg00l&_2Hr7MnQ6}*)pM`_{1*dIwq1>9k{JEQ?0z#409k-}gS3de z^_&PVV37mPH{5*EHp@!SYTZXj7*~Lz(&d;R=&lJ+Bfv;G$_ow>32;2KU7%qIT(c2% z|KjAsYh7ViWE2`TDIpI-&@4ouq2$H}f>N2D1O09vuOO6;;5iflc*!}1NY$ZB{UTad zMK@imt1DE)mJJD>e%8}&cN8xWuaKCrxn3KQj0X-hTVvI5h=b&%XPH<>%66atb1ah3 z01>qV>)BRdV_`tBs=ya<002%+L7Nw*pg>z&TU%RNr6yAV00RI5zW@Lc(u|<|exe4i z+wk-sxDpfi)y?ZcKlNjmcSx$6B*)N$i^GOjmvdFj@yD&#UkRmSUXu2Jp%nPecnnr?m?Wwh>sa7n<5fqM1X*#{7xV zjN-!hB=oEzMIlk!-8XX4tasn|wQVGn2xxyTM$VA=7Vs5Ki@z`}dFatNQM7e_06+0knnI$doT z-7^1%aYzgsMg%3fmTP)!H#$n!$mKN?@&_tfgr@cg*km!Vk>jEt5Bp^e`L{F|ow3(U z=2x~mxSTH${kMcy4_KJSPI#=c{O~wb0N6Zy&jh@=-&snjU1kIV(fXKr5kT0O<|QHd z^88$74w`^r$05~HVw)$s_71TPth^KV^55XCRoXJkz3of=CsF;rdAQ0&3WyiRQ2e!D zZUP)wKU<#Ne2KJd1Up9_8}@(jXj~{ooEq}!rf6){Z|IlwXu}KG+40oi9nuZcVv=YS zVqbj^WL+?iEuuhm*>Eg!D{C=q55SY(q?<=#PGx1PZdSglC`=+=GJ4lcUuTN9h{>Bi z_ZrUjF%0`{k>+pX;md+nuyky`qR@RZTNQHQDsKGFM`ytI6ICi)CM%kt@%>J|d!LVLc9lq1TV3NJj z^*P0yhzWiy$TOX~UInSZ_{df|u6jXh3Jqcw%QOFkH{+N8SlMOdQmZ&jtINyCt32yF zr6b`yiyPE3LgS93+iF$J>uy*|AC5OOrrC>P*oCgbiOM#kKByndrr86SP2n6*HxOrB z1yRUMl-y>bZWgi>fs;{(+lM;DAp228$|y_}OFoQCC5v5HBMH-nT7c*RV3@U#H24$_ z@wXrw8Pe{`NziYIDR}n=U26`OiF5cXK*E;mny0)xFTn=(519UmNw=8#noVkry0@|h zJ(*E+iL%SQPs`ep?kVzdpHhyrJOHJv^WF@BDKZa?23h?scl0|krQc!do7>LuH|hE{ zFOD&?Gzdz*MGah{`s+Nm|Cb5S1e2#MYm9s0ATlR8B>}otC!YG$Agg_4JePjKm+^SJ z9(X3|E~gy)CTVtJ?_Veo9z8_$Y)q*tp9@vR_x4+nolw{#h~|XR8+=)aX+(H1y|%am z{;j2DdLWRB+^S1!J|v21w67lT(f6M+HpQGsc~q)Hz5%4Jh*VVP%#cI<)e;^bNHZx-zS_! z$0uy{-VJ+%$40Tky4&2-z?f>i5rh2qv&p)&I`NQ%3DEw*PNi+yIrDG4m|@#6JCjX5 ziY0Oa!1xy8lAt`ut;iDWvnMIS`3qiT%nv3mPTNPlq!iP_%<=+L?1q>t(%tA(P55>aqL0+1e9zbMI#*>Me&zazG2Ya2=n4M4>lX z6+h0WUUg&2Q(_t3Q}cqy{1XVu^0K^A#Usd6#$*)X+l2E0AsL0h?$2QL#w$PRSi)R2 zbU!0poPK%e#bJ+mN{?b3tUbfqW)-OjP#u#F6HoxBCU~B6^|?8yNaih-=KJXG=)?PF zA_~XH8I}GNvGsrs?cZN|nm}5|gkHIKlGYp=shF|Aaz@2L}Df${!tNH#V>nhgwS!r&(^5 zYq>=3>E=la&TPq(JlJOH%nm$?IsEoezGIFQRhS8CHGS!6+*_JJ&>n-H+Rb@!b__~Z|{D+3hj~tEB zGnVg?uFj=EN?pH++H=1>DAnR=yCO7cuZ{u?&S-L(TjS$lRJcAVv-BmFOGm&Bu_^5< zBeH1Wh!i4Sk&|57ilqLyS!V@`U&Af-ca(5~uAgW}7vo&D1m@R`rcWxD_K9cdGooPt ztp%nuA#bO|xh_WZ*3?kIk34EZ29_wRheCbk+%x#==r9sx#b}_HdDA|67)xSG#3s4wnGfS~$K6oCK4^mFDt7{KpPi&W#)^loxCzoG#I9+J(NMT>oS> zWDEn0%5k2YUrEdd(i4~TjVV{e-l}q5B7ZmBsZCk&Mc5d7((Byb*$SW2PmL391&_g* z<^^4syz1We_nPAnN)jCIe(C#mWUHC(>=mwv{nl-9IhxVnU07dUTFQE5RMZRD#QadX z6b7UOu&3qKO z_*xHX@*(Rs*6JRCTGr^U)~=N?fcCq(WuE!X&l~K)J^?ErXd9|!y>%~fsV&0S$!V66 zGdMlET4Ufzo{(B{*)w4$}}rkYk< z2FE5M8^O;{sN<+?V~nVv2NET^k-=K&f7sc~6^A%OBgxE!j`f4~vL0V<&}f!r=4i3O z)Bou*$o0*z`+DV6v^&xPXP(ceZpun&tpe>4vXk-*iH^79Zp-yC(Pc7kTd35$fNdgE$ehmT^CcRcB% zLD?;|C5&QiRDI(jCmInBEqF9KsSLFuCe2A7SDmPsKW8?8U5W)jubndD!00NWyDS^DrBbyKL-KtDF3p8#F9hrRb zU}jVxT!2FRShpFWrs`~2S#waFyBMOVm!*$Dgd|;B?S2BsC(^yNp-tyt3~7 zcpcTgEh{zN&lcBdWAsEon=0PJg8Y;XW~Cg7D5%sF*O(Eann!Y2;uDzW(M4?x?oPf4uvcN92zbxuN(1dT?>>u?LtM zDY4^bedB^0r{ov;=jJ7WMhkxKeM@OBLG-=u&78+pV5|ibQtjI*olD8}M33y@w@riz zGf(jh0_5)OTBrJWJO`I;>9-eCQePZJ)CBA|Lyl-4DWnB3O!VdOi=Ohc>GfJ*xa=xH zsH~mh1l%hc*~5ZUGcS9}7Es7njW6%9?yxisH+PAA%uqM8{eyv!2~c=aZmz<;^ze>TBN z;7j5CpjOm{UwfXiw2|1xWsod%C@tqs@gX6TF$tp#H-NahFROjtn8a7W+-g%!-&e5?Wh!7y1in+trpj@`1*GNOek0em^Z$OOlKuUG^zSRzX> z5v|gR^9(x+=1*6Nn=LKsibm)Iww-EL3U3|M z1MwhIBGoHxuG_4_3kApOu5bJ4%IYhG=X!!`U@5{iSN=o@{6UID98xrpOj+|IE=w+_)1RL}l2?4kJbe`FG>{uN=`*`w6p=mWOl?-i zgol}L@OJ+YDy-9I{_ZF{npdItpV^1eSeIx%@rT#V#ihP0Stn4ZoqHs@C&cCb6j8eA zJheM;c*#EtME0f;woi2+gW%0mNGKb#Q(Eqw1N>(UUqH+4 zy_m2)Qi;Ta$Bz-88}=nZ0Z@C6sXQV8!TfUS2q{DPY5Mg(#K=UT80UfwJH8yfm#4MK*hgjR5ND%rO7YyJH{?VaWwi23w12!>M>sQ z+VdQAJpjHaV3l&(d`@QJoyD=qnGBSPt@Hh7M7PL6?wjdGIT?%SNq&w{0G>VwXe(>% zND07PN=fhYsfWChj*WCl-{xw{4{}it3OgK5S|EVpa`$V%?~kU?nByurm7jiI;tn}n ze5mnpMqzh>@>3gFHcq1K7#w4|*Z(3GT5pTeN^1@}$0ScbL|g$r+s5~O7^_gW@gOf# zM3<{-qV56gb6(V>>3e$>{!ICzKk$eU^p(ko${GysJTT%otHMH3Q?@W4y{&C3*;dBi zC2XoSM?3pL^`WW|o_h5=bFbhT=+I^kmV8dW4D^KU-HUx9B~S!a<~O#{PQS0+rt5SDf@0?(Sc3%j?i%LYBEBI$kVWPMRIybz?= zSBZvT%eQh4CaKZlW0s)qvZIlxO`s*x+>B9aHlJ#qdgEl&_ppSQc| z^^8)h;cNNjw{>Z~)+kb=`4E=0SX!iAuh3i=pP|W=;{dyc(NAE)u&rJswQ2I1X zy5rz9OiWj2kfZlFY!e^sk0KFTn#;jC>i_Xt$Xy+Cf20*c6(q>Ps?)b#WRaYY-U(9m zKghJIH6ch3(pID$IZ+;YwWNK2c)1o6yYd0lY^NqO$4r%Fp8iMgL*jj!gDJi+K|_VEQf+G#Zr|)3avhXo1GV-EvEtddim~&65=6&VJ1su%lXYA)8zlJ$KwK|rQ3~9nL?PK9s_L-O|MNQXlws_u&o_+_^kujVVH}Dj8I^#Vc zs&Qr1@#^?t_QS}CX{H{!skTegiv!{8JY0N}RY|)P_4zFXc^kKhh4*P0=Ud~=P6Ha2 zQvbPkeo7P@KS(ZkoIGKD!Z@iNoZg+S@?iiyYd;ibInGc@Cv>Sqgs;-%aeWV0W;zF^ zg7JhBfj&RS#1ij7hV|1;K7uHzh)NHAi>D1OiiX_uUDQUXX2-ye9=?EEY8dlL=2bg= z;fH%1aEq9z?bn+RK=!Oh1Ar5<%J-xs3a4&BZxhlN2 zGIQ^#HUq+ET&HZiNCsuOY=5yZKpTC@bc%AF#9;P`-Dl+XbV)_h_bctRwb8yFH*GZb zjz)3MNm#RnVmO1M$3QIwOX$kZ8k!cD$5srro3 zfJXgC2f1H7%J=-sD=hc+5L(yn_g14dzmc9HfF*!XP5smUn_B|z2gU}ck|)_S6G)Ho z6D;8TYt-`)GWkbt&SU%-^81UFkYqyECt!~2D%z*@Wf^~qUm^>aijhi0WzpS@?(Md< zIfsJ?6Ix=dhwn>e|Fr&9D3Z?=ZHX#0rL5&4l>T@=_U@7p&Y<~EW3Cz+U zrv|o2S`9gaCuE(l!31dy9Z!SndbNhb-R{8`ZrG1xTrQdXDn;*E(FmcGH0e5U3mDw2 zrAPF?(=$9FQBF+uQ(h3k3A8sso&wOjiBSFo9>S&~V@93^Ve{?_whBlLRa)F}-E6q| znW#k7-Bmp_(L@dm{V0OTeZz*oDkSL^$5JYr#y-UvO9rF@OpZimvC5&uNe7te1>UXQ zU+S9OyhbGE0(!wi|1FhZ)v}y<`IVJzw;I3HG0S|E-p-VH!B&2kX8`^onkU(fi-d$fcqYKFpL!b=Y?E2H_I$P z{EO9wQt~uQuUy|$Mld;CD_6vC>V$)B4IvO$#AT_?D$G>@sVw~APPte`<`VH^=WxPGi zYrfQ5P+&%uoB@S}f;2l)gm_ zrz`Km(d6%L8cO`_aLno{f#Dv+q)J?q>R8M#5g-w$Jd57-JV3XHYwctt&nzi1%! z6rGjtPVRD-A!NK%!Q?eThWv>0QG$D_O7}B{qQbAr9Bi@KT{u(Zbz!Sc`R=evhHaZ= zlD3Kaa?cK(q8N0PLEW3UKI5@>DX~mqcK~QeEsUxcOYPkMzz)K~z59B_los5>JChTj zw*m$~cTy7=wC|4tvg~X{Jda=FcTR)M-4=Xp6cB^RqH#z=_e>hfz}4ie$W1u`>i@HG zxzq)P#sIlE=Bs|*VGpPLqn(~{8T0or8bHF05nsuoQU7OC=9`j~?PGf%4f!*I{z-1@8FzuqXW*jq9s@ z5Ol^SI~%ph9>5H%Cc||s9Pq8(elSrZw(mJ0(SoX*;GtWea(nq+D1`lv$>hm1d45bo zrOxT*&ySSCJG#ZE5S?YyuvOex94-$`zd$EoG?O*^qP&C{>!btu#Nl(smAYEUFnNL~ zSPv^W1+R$jZ7aN@d24)?lhhX3J^R%Ba$tlyFgYi#0XqT0Y2j_tbpC7(#FK z${6y^qUgRnA%$5dRA1TCf9!mAD!EEjHtpH|e_5T1CheRV_y?zsN1- zhm0P8QLZl2l3k z;giufiHlad0bpJA7Dy)NHm>%X9CT<|qAEKaAxAxP_0(uhT@B4L#<-#-qzLhdnepfd ztI;Mp-z$(*LQ?wM+`9AHEm{r1<@;1Vj~Y{p0-*Y<3E}=^t*lv^gITeF@Je>186nfT zrFpaE{rxB8zFQEzu+TM2S{4S-&qF7@$F1wL8T33I(}35b36-(TX5OD}a%b6LBVv33 zZ)i@Z`4{yIAjhSzhec%L1iuMfHWcfN+%T$y4g&x<+i0UN&RJp30t!_!gPX<{{MYyz zms2kmuAKgIi~PHt)l+kMVym842#su1B6e-f_0qpaBX^C{T=|>7;mz>&nlxVAN~and zu)wDZ;-$n5uqb#E%Gi~@bkZ+57j4r%Xr=L#aJe}@Brrl5KH{v1L9X0yDpS^v@X-JW zlCaywCfZD7rS2@Kfjf&K1(@AOZA8KZCa{v<8n`W{p5UtwMz_b{o5jETGQ{hm!ejz3 zhy5e<#8dr2hk(vwYdzI%T0n~5S`qC^16J7$!CWt{G+qx8SAtV+YUwXh#&5jNlVkj6 zJPqDv;!3mHw+TO^|1zU#D;W2%`<|MdWKhhgRuTAx^P5n(FQAv>xymO3OTEC&{;3Bt zPbO8_5pPP=cRi9F%18!A7rCuRk3|yTfVB?g&U9cVUM78S0noIB1A0`P%C z>?a4`;!%MsU&jYh&-+8w^W;I7A+&#=n8@K*^W@9rW>NMRUgEZqm>an%HoqCmHu>Cx zIOuB|lIR3AV%u)DMQw1!tUOk?-hL##0Tx3~6rF?mL*{fP5KmZ?))hk?S}KC(sM0#8O!>i=4iYzB_WU6&iJP3WujYP|K8 zUp$}PEFY#)5$_d2rEd*>Q=_$K;5j~+eK?2bsI|mR(@#b6w+GuK01K%i=qyNmNu=5t z_OyU<#JdAO%qYn&0x6TC91OguPowZr@+l(l{gv^Ra{(=l)IC=NbYT3tx*$5X%0?UTq|*qV~)D# z=$#eFSG4+Y;HDX+(dkjNG^V>QD%iguIlEc2cVjGZy{Y#m3=ZeAAIBs(lP;KI?m!?$ z=t%7D@P_JPxxE7==wql&mftO5T_6;pu&@FYt49@V$u~-9!5cj ziOpss$=CmlhTzsoN;;0|jSZAIucx>ViT@S$p05|;Xe!g!!sO^i+#;sAc z0YhU9*{@DGPvm#lZuG&6H7(^TCTJH34#5K2IO!lAuh5G-5MYBO?WtTM(2bC3wVkJ} zBvlf!v!+dfih2j5a}UzAwMm?^Q07vT-c!e%>RWE@u-*)9)AZu02_=rGq^E};ZNVBjH&~>FGnTPN$5B0Sx8(*v2O`vKj$d>4& zR;{^D(lJ4}B_LPQHR(RkBk^M-%Cky7mbRrd8bO!}Ft-A*1PGm*4`;5|IfvuXC$i$g zOC9Qub*7`^9Ax{tT2d_dJB*B5*kM4+j4%US66&0XASQa%Axvcf$46a|a+rU6EpH^;a8%)u^Ev-U^rZOfk zH00d!1p1?D-Jg5?&eviod`c~aFf$`RSn_e?`J*{6+k0=BLAds>R`0e5N**s*4gnQu zzRR}lcmJ_IDwXHGGR^kA*O4ZOXAkTaSalf9Rea1D=|0?0avTS$ z3X^GCkqb6xK74~K-gCi7J*uo(#xl)$To&@zMB7_*6KaN)!5>Mqx)R=Ci;VKL-yFRV zC??EtwPj;9`bu1BTp6%2_+E^mbnNdczy~bU`qW$|NP83CwF>Zg!g3<=s)f?X{gTcv z!5L^U2d)?z#r;3yUf95ky&-$gIpj@vGkQL!Q%)a1>BTJAc(+UNu}RtXv{i6xu5+WLUKt#XbdP? zOX>!!j60TV4`x6FS4%Gh%JsTM_@4ZZ`qYdyxK=K$k;dnXB}+m(vPr2^WSFZtdc#Ll z+IwL!xdft>sf^W2ul56;Kw(JJbN)?sTdRR?Uop-5US%JM8p+f@VwbW=OpPBF74c^l zQ&Ebg>YWL51$_)!p=9}KKyM7B@F;T%vH#A*VMOZB&|w<`AgRpd{A@F9mFKC6n5D3& zgDkp=BK@_ZU4*w{qge*+Q69=5_8r+@P0fwrx$NS7C(aHo*~yeZ8JSk@>zJVtsce*D z3bLwHOWC5krT$(1CqdH+rm3kLR*o(Y=&}tu))CSEm`3?Ud30zDF!p|5G7MVss1QKZ z^4`fkM1h${?}mTAn{C4_huoGCUh2;&E{wN0fS43nL1Z?=Dc{Rk@zoBBO8hcFIAr(i zSXcr6?BfzDVB9(mN}Bjb1>LE=8pTW`gWyUdF*E?J$*$pO7UgQ=inz)e{uN=JmO4)2 z&fbaX;5@ka88k_e)iJr6k^0m!oBhb>m%@bYs$ZH^@Pxc`xMf{2F!+Ntb?&pIZp;iH z1867B)%0+-Ri;6_+Z|U_ml0@FxL}7;_auHd!ky$p_0HjgBsqo{hlEqwP@{)`)D3?AJiynf!`JXDROvpJsMu#a zBU@pg<)bHA4n_0p-98Dd^zMTJudZ+EZ6=z!aIZWLdDl45H6@r47E=^!qv8AOyhywM zM-Y(RMqsjVWR3C1XRD<$+$jy;2};|F=S^QE=4LZ9T^k)A3M&}S`!r>W0qN;cPxozo zy)~AkaOs7?em`}WFP997li;wI6^J2uNubLB#wHMW=~^*m5&6Q)16)2iX>VoVESqw} zPch)iOD`S@&`hQ)tQk7`Kz;7W&0g&%)2*cQn|X(8MXRPeb^-X}y^UukTb^keRJlyP zU=el@umyKpZhyR>DnGC8Hm4R8*wMS13FzdT^3|0752sL(Ai1=f71m>QS$Grw-&(l$ zy(<+%h3nv)0k`e(|1-ooLN(a3Jbt#DO&Je%L+hu>K;EL}vySNO${csIWe916ivKmb>Q^OMrgAx_l!7=tJ87&lzWL~mtSZ-ZzsY1!jM#Jjsrfy|Y(LL%t6|1i z1v-5DthiR6>#L(Pi*nFTf37)5;f1^0@B(s41rBeabb+KrC`pzO@cMp^$uV5Sutl}f z7h#MmEx0wDlynm9DnMnzak7GR8?b-Z^RnD~(akZ~WJ9D@IyDXM;zPxH z+q%T2xm6d;2~+F?fTyVeu7uS}@@opg6CqH+*09&NE?T2^@~8(tk76Ubd*M}s0Tapl z9y(v4B~=0p9}%oO#;YW4^wDrZw-Xr;2|KomSB?!5uq07*beJ!-9}u{Qae%B$an7-3 zpKnu7Fs#2B$TCBe2}f{J-$&=av9!k1gpdi1;r{EDLcCA^xxKiUKwjQMTjUA-Z(CI5 zN}oaH#btd@pk-I77)o)6$9m&j5%O65!0B73El!>+js*otZvAJW>uqkeLWQqE)l1En z^PZ6+j{DhSm&yHs=^`7xpr!9TQs0{p$tkeQ5!sNprnjU_CFq61PxS))Z4i@u-@eZs ze=B*b0+m<+4*C?G;I9xvK$)~NK>4)A1uSqB$r@=uddGo7)KqL=AW1hvztKK3e-rj%yE;ktc#WPFMY_`?!&o^zaUrk2*gg0 z;VeaoRGnFKVP8Kw{TjaP7ogKM&4UDuCJ+RTDcz7(@o3aodJEZ5|Us1ICk2g{rOw zj=cexF|&@Um5DMwQ3Ec>N~BFpa$sp+<|^EP6>`qYyg{};%px8SWCjYJ;*%TAW>0-X zFU|Xk*Q`*vXp;Bg9B5<>OO&w3J#+^$pQ07|Jl+haO#bq`g!Vq9@j_2#pLDdL% z%?=c%!Iq7HN$s?a%zu&4u_#?+ZyF2-m?qBYHMy~5tHGjQ>jV-eq96p>?n=1aXM!wH zw2Z;%gEzsRuj}s1J32JY8IRdyMwHJ5SyhG?Bgu1ZN-PL%P2jD<@YHFUf99e}2L`Qyn1!LPmU$VR&8Hkc;?Ne{t_+#(Q()JfQsa?_&sok%0He^eDvka^)dE@~<}ho|hexbZy{mBgPJ zE%)Xiuo7aHslEH8J|7#AKoIvbEP3hC zR4rIZlGO6QvM+NXcWrFAmmhm#Acd>=@_x%D#d0ao{tR@QYOvB=7jJsdsJrX?zlvy3aXDAtkL2 z;{k!6?C`-xfcfww{}cTsTQuO@GZ4SNs`~Ea^@F~u&TDE!VC{D3P%RZ%F9wH1;-YJ5 zi>!=TURwLW+3>JEM!EqM>)QU}kdE`3eSR88cq(lH43d(3Sh%1s+2$z+)+Or;O@0-G zs`}Jx4nlTAOnQSXb-$Q4EL>2$fcX__jr>w&zweNCM`7ra1|PJo;-r&XAK%UHJ=GJ8 zg4pwcLh<$W+=t`LL!0I%bk_-!rOPy4pC-qg)n`;{&x zL7E$-7&wzxKa4ov$IqkSpFw@v|cdh zI%5y}KgJbH@OCae4snIc$Oc}3)t+MSITMAv5La-C4F>fl z?ic=?^I7sUNd_;<=#uH0L6*DVCr>w&8_^BSZgn-hHSUVLB;cso+%#)f@)C^qa+suc zzEk0KJQyf>(ID0Ny2}LLy?*LsG!k4XdGhXw@E5XJ;Yw#!PtX6JpUAS&6N1tggPVb> z?Hc-rl*Wk&{Y{(EM+hSdYCPL%Id|Iq!WLeQ^f|ECUjw-<=DZA9Md)N&pR3#2Atq8n zq$Bl&W#5R)7zA;(G(eF*7^i@Kd7w61)Lc!-s#Dt}J7l$A{IhtcdMU2Nb~)dYIj74` zuhl@i+}%AiC|^QFiPCiyhPW-Hs6tUhqM=_RZ%Z_*sCdQX0ClUp2mc_hBS)DwhLz-4}l`amWB$1T&s09k7=_&OKUfhB#fid$L~6} zp#7;WWkt=>5OBQW35E4&Maou5lU+4T9uPEQdV5jc7pmrdE?9RnIe&HW-)*mdkhzLL zr>hsy@T49elbj!CI;x&w`2=Hx_7!GW0pK~MLpt;%+(X%bqIynjxu>YnkG+XZJf+Deki#8uHNAnuZ4M&gr~)LiB(*w^IsIZ9H@xLLwUl?#Fd4Hhx{>gE09j+C{LxbU_miVqH$3MnGNR0%|1BG=hTfcoA}GqYh5~FbFBXX zEX}X|CPA4hPjhSNV!Pfo95bqEU}mO?M&Q#4_sJ*6BIysEjeY#vd}62`N4lh(2blu% zQ=Lz^)G2(W`E57>&#!-lSm@A(Ljqb_(lY0PO`s9@XB_`<9?ieI(Pg5SX|&cMKp3Eb zU&!s-v^deZMIb&6NXsv4z$0Kqj#D(sDmhc$2QYq=G``Z|_XMy4ifkV!_t5ZSN+~nA zNP+}>ZMQ0|@gpbJq~4PhXJ(N-9;jM-k5WMdnzp(~P#iOfnen&!R>IC*G1O-^XQ(lV zeKCqC6$LT0BsT;*LT+Plnmn(S1N+_LKR276T~uVM?(RD zsQQ-1j2+tCGk`TDYo1T*bTCk$*@|h;xG0A`-@;;Rh4|kKPa}92$5WDXE^G$4c(T;P zJu%pgWBX(QQi&xMN@^KV-Fev~&Tb4MSXlHj0B_z$G0JfBkbmo4)7(;(AZ88tD z5RXjQOHCZ?Pbq?7-!fwM1AUXN*ZR`cR;~f*Yv&VIMu>LQ2kH~)Y59cXppp$R1S<2{ zFRdnU>p7X=asM|T4wZZ3PH)YEl>2z#vHYEl(q9_Uy|~yc?97H2aa=Bz=gp^X>~MI^ z8(iyRxd69^7~qy3joy=W>bEtntFJ|6GL2LzgwaD`gJb-b9jB$=)lpSm6)}^Ug)JC< z)v-V_zYwylnvOydvu7p3q`pCKZT`BfI6J*pMF3qj#qddn*ct4U@S&8{1<5}oa?)`o<*ku$IwNB^ zuX}ij<{2GwvlIHBs|Px*+xg^O@<`KS;(t3r{%Ft;Liozg3KX~-?Q`VhA3@%NhV|J( zcIhl-xexwpGK0Fod}Z*_q+p;zn0KBxdBZ~|N590N)|e&oGa)bGTXOp4W~M_+M({uM z?Q6jyUCy&076zrK`R(70u3Os($(YvNL*kuP@E>=3ns@yC8m3j@4T${AsFbw*?wOCn zZawu@na%M3Siv(vcjDXbPakw{x98NhErpn}1V=FoI?6bXCB^rmlYO@?ry;b2+lepD z^X@S*x_NHbp6e?J(vS6h+sO*lIlXZPN~c@e!>%NqxnKNU#Oa<<y@{1q9mQ`tLz@R zq%d{ehnkSGrjBA-wS`#noF@MMxPj@$ATEgK1H;C%<}~WL5S`(8*OF|#sTcXc@Qx2Z zJa9HMC8_q4t&73{+x(6-r7D)Y>Q`JYF}Q{M)%6l{3RoQE&46$iT)>94xEo5A(5 z&wh0m)SL$zv?; z5g75Hxg4uu5a{M$j+hIvUm?~@ij+CEp=x=Dd$LaYkj`73+RgT>LzGlq^V$*d{^4^C z|Eb`N&auW0ExCfRy*b0&A-Q0$y0DjV3KzTWNu(?8+GsqrqWea@;B;Uo4{t_C(!XMba4;@25`0kxVv^Q zI09;!CsoJ3S5olcqLEmo7j?%X3`rJ1HB1)IGty#f|3RKJ6B|u_0|YkW=|ffDd~<;t zDD&nP=@Tfc27Xoj{MMX2LXKoASZ9vTbd;oyK=!D8C0QuUlIYA>rL3RU-$oSWoP`i{ z5I9P**CO8b{#gK5(~IcfdT?~w^6+hn6U3c7*1-~sA7+5mX~6?aq1lxmlZo+(@#@OL zlhL|Y_pOu`&cVPt5JwGLPm4%^`*m8Z8AThYjPgH`>^L)6`(m0^7fs#+R*xCmsA#`i?)-c;WR)?4B~nvRYP~!7dz|oAuN^ z1L7%_q$7!D2(PEbKSpMq{fK$_$OPrK$kQt_X-i=_secS)XT6c_0der{QKwm~KAU`_ zY^Vj#+R*sez6bQ5uUaZ5N9hF*dps28m|c-kiOX(s5$<%cq;!2YJk9Z8(`jS`to0zrQcKY2{J&T588K$gZqJyP8hPyo9 z%WoVXSIG{TZN<;5pG`M`Np7`N67-&83}X(~qN1Y6APTa;0K0rxaKgLnYi3u(GOvTp z(yO~x@N?8-itOCYXjBM3%bAY>Gty($M9km7T8t{1CLcvqAMNSIOojtXiiM!}%SHMK z(#O#Fd-xd0LT%WM-vIaem!TSMI?XkK3@4{+Q|CUJE(s;@^T&$iph(yxm143N_l&N1 z-ZKwGDXB0%{%7CG2E^<$^OYJ*r*NqOWHxPFTD?4D>p&B3GnWhR99h|$t_~Z$lcl(m zi&fXvz;b#aTSt*ZI3JcSI{Mz{piTQn9z(X}VwxYN9MC1zv6lf3)@W0s zy0J=>ct{q3@x2y7@bzR_A7K+v-}tMrtf2Yb?SCv;wT!=yf(D)0FobNc$_Yz|TzwC- zxOSk_-+=k}E-D+#&(~hF*yd?7JER|2iH|XF7#@+$Ln*awt_Wnu9Rc7Hl)79{+jBg+ zF1pQJ`q>SWLA+#}ZCVIo+C{aPA?LhR46kC&Pv84VndY4EnX);s6ts3dtCs>q`fsl8 zO(i}gM$$qFaQw$M!_!zV2t;W4!%Yr+$%ijC%lX^I#80vzJWN$2aguOam57*BgH*Z+B!m2g8sy6RSYiV?v`HQ zAj#0KEa;y*1*}m=1iE&vgC+ilU>WMXuFRtwQ~J*QN{i{*aW40IDh=xnKGYiQE-{r9 z#*oLRDh9nxy%tFrLG)`Jr%loQ(j$^AU;QrM^xQ9FTH)1H*F|=|mjS29d~KEUGZ)B{ zeIy9&;qLF}fF<$BHF2oP7kp18#0Hezfbz*RcVW{CW@<-CfwinwMd4S!EQJ%-5;z_~ zf5s-4;MC_}VK6u?FGvK*!QnM>drPL$^ca#n(1puXF^5Qi3%zZ*4GtYwv&!xFW*Myj zxb{AA)caw*-aJsD8QHIWvs(GxhXO?xkE;zP^kKR+np4N`h+d2G*qUwJw_XRTX)3QJ z$En2tj31AWJP1q?fcADz%|-IeD)kS!zpOOS|Lc}$+in$Bc0Hq^qE{`GP2CQlGNm2- zV0 z_kA<5sE$x1TvTr85gLEm`57d4R0`~8E`C>|dR76x$$c7^QzaiPtEUS8W75n7`w%sH z?Y!?EgToFa_xUx)vJ>&Edlypg@15%opi z?@NQ0Aki*)z9QVmZ9!2(GwHL zZ_BWeGfUpubWqwYMgJV0$M$^k(jGdpu3$^kVAY4eEDpSd4;$I6 zGxeX*kojexquD}`C?ERaw9igc2Y(RU=EMtx6#yl!rVpW7Nf=thDftF}H9fRhHvL1Z z<`B`n+$G)NW_3iw`3X8>^-RXQ;QUJw+s4Ucq_R#OL3dtkkOKF2G#`|Hmrg=z$keFx)N{ zRE#_lG9P)Z{6?f5rSA46#jH+d}L)?fB6Gv)>AiNcm`F52xprIJNN%%LflF#5%bt+blNIG9p6hGTR|b%-nXZ8xJ9*D zj&-M&SLXKz`8f!dm{`_ccsQ4Y<9N(ZS76ZqwyW)^>&zipwq;&7R3jIH8z*cr51e#3|Zl66{arzBBJ$~d*W^X0PpnS@emgUCZ&dC(%=bmqt|VQ%k2a}J zkrwv9L4fnTQ1q4#!!~mAxH#YjgVM9aGX0}_0ju^;{PXD|RJuS@)WXT)R z7IKjKhL7OBFT;!^A&Y?bx&ATKt38>cujbRC&FvvrMOA&JB&DQCYq8Lq2XOI?+Vn zcd;b!f5>|Stk6M5{PW~pFJ#=E z=h8kqDJ^A9;Ks(b*CpKT!W{h&C5E8}Y^&F3^0{EjiKb`eDX)FK1MnLPT-g?`)A4Wx z!$~Rvwv!1I<)~NsOnGf|2~$d@zE!Mmmcp-C(SZ<%;3^iGn?Se{4kLv(t5;3iRf8Uo zWoCCu26JaUbbY1~3%t+e6!2tS^zkL%tVAZGo4%e@og0Fn^LP{fXY)v#mpCL>%RSYE z!}N{2n5tXcwPc;CfK5Z|iE=@X%%h9SXjO?8%^#4z!D!Fh=|nG|7d0Kt`lVn#p^aFJwcF5kJ3Cs`LsmO-?_ z9|C)oG7BHdmcE}C?Ri5mMN7&Nr%RDpjO^GY%(uh3j>JWR_))L4N(31UqB6Cu|Blnu8A|4gpj&B4p6P@{1*0_euKi)5SM zS>h#lm8ERrH!+*++KicYXaF*O$hz}u@Bk`lXi3<>*gy*psc*#rr|dpFSOzAp^mVO9 zRm;Dr2!&DNAmcSc3dNsYyF(dC5R1&_2-;QM=yT9$2OQxlhR}ylMW?tk&^d=t`>!7K zqTo5OU5~TpbGFheREV(BXWOJbEaCH+uim_z`04VV)dsIR077{WYmq=SXyzB3@H%!a z{mbfJCv5k+pUh-=)fgJCOvVbQIlt`i1y@M#O66RHyQ~`Y zXrW%Z)^{D87P!dSRA=sd_*S#0j-F)ol8CmNC^=@S1ks<)IOE_}Us!NJ5_V>>59{~uAd$u2rXBPNVs8h1LJqv)6SIQpcGG8V zGhm}aN?S>>Wr`d^?LN|n-9I?9D1JO3V~aosI@Y!h$XolFCiAvZRnHL25Usz#ZJuF| zV9SX42dY_?VL}QkCYpb3y<>HrEHVWDC1R4&+_XYb{AHrwDFLW90eEvQc{Ho1oRml5 z43fxXcJz4sjvnI*9qTT7tzP{ZI01fSCXXGQbu7bSDK4LRGZ~n!U9?CneYRla10}2= zAaxu%bSr57AzKemSed4YN*sFxJ~3K6;TA%}{Y%kfASdQB;J(zDvO%<0>Qn3ca0<&vI&?Gi&>8x2F0GfY%wMV$$W+A>vRSfgrOr%t6wlZ zgA@dgwzC!unwx+Kd|7+I-oQAP$dqB9|1nPOje3F3g>hB zx2LnUi}gda96#S?*LvPwoh*WM;Bss4Chf&nkhFK^{&XlG7`})D13+9d&hW9v60eHf zYDC*RHMyz)BV5h8Uoz!K5D!d6)->iC)GDgrGm*e%dVp9@@9xLqvpGYHqXiMbV}xV4 z;?#&dZ_v1bTpx?|lf1zN7>v~|a*8hC|70jNMHCfD{1$lsFf~G*ka?wC=8iPg0Usmn z2cYu<<^e}!K{FEvWl4}0?zI=qaP(8Wg;9%P4G4)2nkbA?HovKe|DcI+q5`8*{ZC;M zO(p}xW*POrt=Ux`uVgSMPMKz*x==id55i*tuJWU%3N@%G=3^0w7aG~jce%$19eFpUg0-|7>8(WD<5=Al*-kpFn%Drdju-1Q77m(|1 zE=`%3>uH{f3|^^1GQ!E*i2vQBV`}uF(O3=jdN*kpLa7#=8@i?ADlfpiI*lB;JTgIj zm!#FhT9f_GgE7?xe*FA6K^vmxz_4Str~`9K1h0iNZFH}#q>=xcjM3Y}JTuc|r76XD zN+OXz<%qSlQ+WkI4ft!@LE=rCF0Kjl)05$jt*1u_#$O7~?l zpRc_T^ZRY7VW=G@08zVQ>jnk~6mEzy;o1kaIg_--`2ca8u?1>|5${&@js+6``N*_U z?A<~ZD#KlRbo1TK z9LrU4b}X@-rg*v_dO~dPZL;9c?P@QP1d(A$yWe~goTGTd3*H=pf^Tw7MJa^!!`Xk! z%?*{42CeH#3VdCD$rgzWNnj>VJZ@X27f;v_cOE+?Y90s3+VPG=kY{<5^FRHS5=2)zcr+&r`gZCHdpp8N{$rGAlyh#5|BexW+Uw#4vG z?+y4`boiE|F8vQO4IW#cd4ht-`TBpRvV`3#O0#^S?1PP-HW^0DGpys>Y z(XMlEM;oEP0T?iZNNfWAVm*#2ghT7UK1+4a59%{(AEb@fOGZI636vHDW1Ff;m(K(5 z3jwO#Z3;^(WiqMaGs%KJ8f-W_cWm|t+D+D1{87gSx5>FXO5&wBZ>8eGO^Ti26H*^& zgR2#)BQ=uk9}7dL+;(pA2C`Mm(qgy!PJ6C#JYtb&vv<$iXUzd@^n~2eCzBa$oKZ0P zMNE-e&eigVhB4BMG;-(7a@OO43)gy0n^#OipxZ)rPaQ@Br2My!q4*BD zn&JEqOTC`(`|lq;e`2MNu`L9{XX6-DeCP8b6!;>AFa_2)6#G(qcFY_N!Qtc3xTW6^ ze3hjtn1wMY!|fPw8#LwsP4hv0j+h__C7;#ImbJk8-6Z5-;@Y5rcHg4-yefu~#~$QBI3z$`$v+?I|? zsRh*ilSO{N{ue4=2H z=*mU3iebITZWHVD{yxm+JdPQG4q-6eU^$1|nS`2Re}-twRi*@p0OA(PJ|JDZqXz&0 zK@~xtA1r*K=pmE;001^K#@hcB$<=|7b-~2*AJdQ9=Wtn}Cs407JZw1v7Te zcl%yzKfI3Xy}X0hJg}|$yh^En@9-d2#fuj?KZYSHe;uOm^mA_9N$XM6Ki*`>rZqP- zWi@4JwyQKnDBPm@?CUsB|IvB9Vc1{Bk5s#)uvg7FYX>rW&=%*byK8tQ)bt!X4pPZ| zlXy64b->6vg^wZ*IK{z(6St%Rm(H=@L@fG?lSaB!_IQ=_#`)z-C!h?_o0>Kb-b1$U z2TAdlSPWR$AmMwrek-8ug#0Q#R$p|=rsOIlpnydn*uAXX2#Gt#BT%OzSUZ=zUb=9~f=02KDnyBt^=58j7fuVuLbpf|m^elk6nq z=U9wJd~CHy1MVXIIsQc*-(mkU5LwpH_#5%}Dl{KKQxDAmx@r7Z-tR5GsrSaWXbo#3 z$T%*o^=LJnFSH==X~i%6C(ir$a>LePlOa?bMhR-hXIWfolt|<-APpa?(z0NL$fd$H|p4y^D7O(m3}FNRHH_>v25CsSNUZxYqaLp8k#1< z73AF4kME8d_~te4k*kC5lIj&9m|jcWN2Ra{TOJEHFLcz{Fb;miRhc?ugF`(3-=d~p z!Y6D!KVeKErIry-xiq{y03{9kmpO8N?-o{wme0%D7MAlcLUo3Xk0liN_@78DI$2iP zzYEL9!Rh6c70g#x+y9ITK`tw%5&s2|_ zS>cx1!!B*Rlvuh%X-Z66Be}eqbe3G4BajLJSFb)8*d)hSUwd%@Uv+BTGzV8OF-7AwYSvP2>$?{4x%3l7d2ak|L>7KnZoT_B{_$FA^uU}#?#c>9340MC z+LjpdGwGX%t9H1ynu~x}aILXO{Uvxqxf^Ctx*4^V(+>L8-LOf>)<6=(5a;6J#Ms()#pG`3OQz>tC8WMa z>zEGI&u5_of%-A-ovjH5!Pz|hl`TvCF?tdzfTXm?;RW>7!#pE!I%?~C)Cv?q`b{%p zcl7aI>VAK{N-uNdxEutx{5GSxxxLVu^kWY~8|z#r-THk)j2F|>e;RJH9Ig_N5J0o7 zIz$R*e5{a|?UJlvAs3j6d3?I%*|o;CpF<_+{}R=xa_X)IJi0qj8JsX7qG26Mg6X%9 zUpZ@iqvmLqyUH@)N>a?QNCLeBU!!Rem;Nsuy5e9xom#oKig{V(yyC{x7?*YZlP9r4liVH z$1lu?gCw@m>631~iH}`_Zz5SV?^85r;{z%GM5YjKwqXfnL*d`JmnJwUVUTDn`UwjC zTF{MCBx|<^=*~g3;cfQF&X=5r5zx_;SsHVnsV`xBu~9*SfZ?5z2%XJ{Fb797AY?i0 zk1KV63V(l&%Qj)anjoF7_Jbp5fL+bdOb1ewn0MG{zSN-E0w7v$-MyLv4QSjcWFLa_ ztT$+TV@59x|MP}%d2+j^(~=;WGqfRU=C$G2@&+S7f&F`2dJqdd7a2p2s%G)#R>jg$ z&1<{3-QwkXilXyd!d8`Zv8-8%&Q<8?tl_k`u(w?C-1OP^O)``??!|Zzx3nQsHeF9V zwOSME!|`ep9j_xo;aScH=P`w1$2N{xBfCy*M`uKSD~@~PF@JAFvvp#X$mW71_1A;t zPl?QX&)(f>x88uzX!DPe1$%wuY6*<^^)s~i)#a9fIjQqxU{~+cTeR*cV$QOzTTdeC zXvk)j$Q7o&6Onpy7n2+I$K%D&($ZG;fK}Fiy$SRrm3~$o3;ZnXn)4MDf5|)MmmX5I z(m(t&gQ1q$L1?V^+ngNg6hlt6y=(~$qm!82CXaWOx47_bSu=R|3no}u#b@Fj?|=8* z_nBU%^Z)~Ui@kKG*RlPQDJuZX!yXz3g!2(aMOXf8Dum`|ia-7$WmGzI-gea=ogVd} zUS|NghB_XDUB!!eNml{*${_TTfxVu$*22>+KBGtsdpPZ*&C;1kWpa2Qw9O3eR+P#c zk7BoFsjQh@=6>GOr&@Q*7)ha9lGZ0J2SFLf>rhcxrrl=*FZO;F#4)pPsv|vy?1W7- zBq(Cs=ciCRY7i&b){zRkp_Z;4X*G?HTFH{5s!mD~J4xV}7}IZ*%{QpQNyStAqTgi(?Vl+aRzRGehg6jET}a=JE4!@vMp`Oh!O8cld+ccJ>OQL?-?J!XzsCNYTH z_v;rF^w}RSPa=bCXKZ7M(HJ%+6Gc#J>^t{1*8rXkedW)?uN7TrQfX^ADzWM_{?nzV z%+Yvq1ihk7>jO|LHsJ_vjaMBfgN6&pE{ioF57R7JDvdT1Yz}7^=i!=%p6TZOLr>n@ zp~(waEuDCF-;w5KUj5D3N*GX>YO~9TEjRLrW~QLtS>6mX@Wbik@#^xlWNDi!mC=m_ zFk=bqA8w%`Z7;W}HXVD9)$GXJ8BOjyOhfpR9MzQm=jl$R#-X1K<1-7%4g&tL>R+ms zP`}q@5{aC~m1|9f9-e9+Z(#!_#zHK{$#mwONeL}c9=vhxKT?0{D&=zSXyg;)hWB3uuzGeyJs0?#hY75!$2GX`Pm#~JqvM_( zj#?tEijsrWk!cMTXirct=?!v(5g}@^LtlN5M(p9G@mLVXhI)!c(*ydKHNS+-+)+V4 zTTf7D#m#E<5WI^X8a6c$I-VdM<4=DkP{+1Cci+DArt7ES4js~;1E-65+>p#U`N8nN zGzB;#7kDxUpI*W2j%2Ru+Q42F*DZy(IN<;Lmy&W|l2atLU-RyMZAgUBz=;NL@_;`^Yv{%R z&WozdNV@adOl1E6lcLdVNJ%cVwR2xDxdT!yJ~zwmJ{ z$nSq|Nj@b%-Tg-=WJviblUZG8V8qPq#i}w zI4uG=o*^uO&38|cePDeE9VzZ$j;lBEbGQ5aJ)cWLS0BeL!Nll^L&c=-MUQc z{r69{N){ahbr%ik(Mb#|h;l-j)y&#NdJnz~jhJ@L0zS6v$v{fXxP9m*<>Nm7vT@%bI0H@bF&BHwKFXstGSV}Tm70lt?Gu}G zn!AJ>jh%m^Tbd}{3TZ8o^B6AYhpigWAv+_354H(-93AxZ`QCHZHg3l3&;eBLRx#Et zU!bL^_aR;xMC%Cpdp1lsC#B#Iv=SK9A9g)p&hWhU=oA|#)%c1izxfv~p3*jx6J2zZTkqViwO(c=W5 zF7_yHQa46O_9{RJ-3_0;!({z!>2ex$)0*qJ%i%3-{&VIri*X^S8->t*)wj_i$#@B1 zBVbEK$Bd&(|1!9rr3IV~q60%D{RTeCmG3Wz#=`BS5LVl0%JitmWj~H3+87FBaJT1fnPZRt)4|oDb0k?c^j${XMp8uC&o->a&;l3R# zcquVJ%$&U!lb50oUzgJ;pbei+t)t`-F;+(e;@V$|5-k@mRW~19p{RO3vir|Qz41+2 z;>yZO9aI?N$-w>pZKu~>wSkSx_`rZgqPvGPXp$X`bxeACme10N?fc&W`J(IcP&RPl zsduxvuie>Ag||Ymj1vs&DEQ~r;uHAkkWZ4!^@R|PZj(wGei%DTbH9jrD=gKY_XG6c zaTFnZK6Vvnc%a^hvhMA4d$U_9`Rvc*M(md6ne>8^9v9a@UX}-aV2|FRRTIs2UW(IC z7~8j^jzi$FN`AM-!9GWd%f#x*@iLXx%w1jBfPGLRLg50@el}Qg)hEI7h=T}%QSc3| zZ#lSWBllx`m>&}OEWi>1rhP}a0R&QkSd~%fc5v>`C+FWWR#cdpkTe^*w!a;4jNNk) z=dP@mT4G_ToW{BsID4 z&4#FAI5}y}f^ks8xvCg(lTK` zU}AC1MB~xM)%`DA&TA(ZW@BunBQ)E8r!}K<#WC5Qvn7a26 z966CRiOa%n6X26F1Irr*uQxnJ=?l%GcDERX{c6s=8z9b(W4qd+sgBPZfMVjAOtuKI zXd!E74)GB8bwHsA-?8iAUJ{Dl`stO~P1Nh`TlL+s(N(AmaDAZ3@{~6TFYl4rXXY`y zy(bGNyjzRi8>CMVqYMpmX)mb)p;W=I%Oh3xf3Q+3+tqzcD*p^_@bk^L)OProxR%WVPqgtREH{4374dv&&N_=*JP>i_iTqGtb zy)2?61{5ks?@?a}i^@4+=&l$Gup9byEN`=VCkb;;-h^sdiVr-37oWt7ofV2w`OG!_ zm9@n9u*cYK0H@N(_Uw?Um5+vK9{GK^IERHQFN*(%W|$vy#0^2sQW_)gC-Pzc0nY;3 zOPq#y{A#UuAp;BHh3`;Z4^;(^4a?_^e5|URtb)H_bKbU3xjGf=2K029Pikw{m50nr zMSbObZ$B(Lq@xT7IFps`WQ9C&mds+YE z+_aw~w**`qJiorVXfvjd2%s&-iE0c%>=gH7bMf(MBP)54>5%Z1;b-IfLrdm5)i5r? zHlQ{GQss>Ahkb1~h9U>Q893gy!x6qM}M3 zq^HRmVq`0%xIlh7#&+6SLp6smXb>M)5}IG(R*v_jk*>_QILMKpIl6=yn8%LLOXF@U zZ9gTO<2qm3r%AZFApjh;@Oe_Cc%~fvX?0#q_(dv z;1tU5Fq};tnBREuoXo&R6!oyOP08Z|oUaFt&-h=hz8}9ncJfl>t}u28xlHVzS%FU$ z@Ka5QU8g5P0U7%G{1qR4{2@~GJ6?CqiSzKZpoD6^_J#VeXm5=HLBpIw8kIw%gVI>_ zsCL5@EDkGVp`}cz2}FoiSd`q|Lnt&${u>E=jpf>4pf;}__f;cgw{25v(n@G`p`zxa zbr5Pt$O3iLIJG@Dzy+MoYR62xM6o79+*)C$f!8VP>_fB5r-6Bt?x2QA#Cl6>cP<_M z?Q9_>=XSmJ(!u=RZRNY-e`j$*EPm_NWCgez&0j;DFL5qB37lUr??PjsyX~Eh3286K zNKA5rAbMUDOR>LKlsc~B6YE5}zw#_{Na4e*q^^EkK*DP^e@R;6wHMZBB89b1e7IQ}-AsaQQb2OcS7n+W7Bh8bNA8*_=mSH%VAO=tbnWbm^aI7`q?D zv(P2nN7~eRHb9lCfQ^Nr?+%yxn4iA1li;1mqBEL3#*u-+V5yDe1l0 zF<*IvanLB-?beJEL?k(beNix{QT$suP%ffU`n%PY3kw(6H}9eWQdmqeBTabXPAw+C zt84qAuOHmoYb;3w-PS>jxAaknQ*gS_=KTKbi2c}PS+Kcu9M~Gd0~TgFgqHx3eQilu zJMvD7kL-9wW%ar+F7xy^9q=PN*O>SioDBk~hJeolEWvk7Rk@s(4&2YOG!f9{8=LJW zGL;)!v%sZ2^1*~}ZKLv)buh@J;nt1y4L1QtGA*l|g07cG*kbG_FT;?Zz@y^KY9dAg z6HQ`HFNIHu7E?%J&hB@X^MEZG{$aK$OP_8M4}lV4g~93W zGPhhV!#GZI80Ad|3WeFrHID$H1SL!dgpVrMV&UZgi5madO8FekIits3NR`(>z3;0;1otGE{7mO-ub!PhuU z*pn_dqx(mBZWNq&Jsth@rv5@##sjtA!ffno&shf6HiFXN~dSJ|0oFS)24(j1d@W zp661K3x5+Zg@6-V`54SrJnb3bLZSp&R}xNN@>aIe<2}vlfQlb?pzeg{5Q>p&{UV~X zRS*ySM`oqhfYxm@$kc*}Jdv;d{G{PWR$G+EX#&SMRA*3Uu6@<&-n8R&Ua{o5n{;DvhGS+ClOfBmuNjzY`)$MV(>DeCq||A zB31EM>*QsquYZ#PT~}S{;hgA}gy`=c$kYF4g)PeBrU(6;0h90Cs@xp`vWTa00NdTF`ce= zv3R-uwSLhbQIe_aJ3q5{dpLI`T;9G?udEg-!ze&qfr zexCy=omSY!@!uo&o$GLVq(iB5(nBb_Kvf|#`4qeaG7-GFaLpoocxckA+YOyowgx9m?chKAEQcJ{yh*E4OifxXc z4MV!1U0EysQ)UzPHGwhaoHg|1^!Hsw^N5MdmlEbAvxdKHqgUKnn}yl(*@U{H&Xa-x zuSniS8u93^x_r}g7cX2iCnejxt6@Eb^j(8QTF+E#tSzL0-)ST8j3G=hXSQ6cC{mif*H(TGw%O|aY&r(RA)4bwOVzlC zqBcVH^_Te5tJEU~miFb)Rtw`$j{qkGcsX+`G^~Y7N8oieLhcXv{u->Xu)9zx^`$!=G=;c&^e|!1HTGFWL5@T!$I#xZR0hoFP8vcm9wCmCvsxihud~3qL*I&_ zjQ?k3NszaVKRa_|CNSRc^M$13h(!quefuOx&*4E zgBlR4h^QuRoMvzh8{|)#etP?-3tGuOk<@rN%u{{e+(yJNT%n4C%<(+x9QI6`;x9@p z_)3>6m!`}9AnT^fRxj(ip$Y!&P8FUeWsP`9DvC^a4`hB~lBhwz=K#82`AHp$^L%t~ zA2Gi!mQEtWG$-jNkBn1rVhETDOPXSoNlC^qYNnfjE=?={b+=O3(;jGEPcN}O?M~A(5>vhCorIK!Pt8^ zd)~Qv@xeKi;oCgU$aQ}p3{kKafq}(5yfnRzxf|2n%^U-;Z-FJ{fpF`GceMu2Q*cOV zJ>)9eC>3}Byr1&8Cp|N4uw9umy+kIit6LM4|UC8 z<hYTP=nb*vS`X4s=U;s9YuYe0 zwU%FG=Sq*54Fu3ylm3mEThtZr#tVNWpMfA6U7wWb75QCrWg$Z7lGrb9(q63n<$`+aB9Zc)g{$F6umb-nq=yw)QK-D5tK-`K70%WifH+{p4dow>)~eJe zPj*0VQ9fv(y>5d*%niiloJL)s-gKz8Y2C^(gcI?eqA<64N<}xwvvK0eHBH{5a%LAo z%Dsabw;ZuqQ$r!Bd_`4Kt7Q< z3ES}C-3&&+&RBcZ^%(@p8o9+PaL$3UX!V_u&e=ht3O8&hhvrFAh^v4h^U}{1+@=d& zNAfSR>fq=N3;!K{O{Li8%xi?_mYSKL+)F!wPs^fnaV)F+r`qgTB`TR9Je-mHw#+PT zLWVozUM%PT7AAWWkU?1_i*4*U+f?0cm2u19ivi?$_^9nV3>dxhzg6A41JQIB?4fk; z<`nHg{grLfP}~KctX>ab3rMkK@n^rRpFX;ud!^ zo0gucv~G;5$)Mr5%M+KB?VU1Hn+3eW#&oylj~=bycBD~V{fc%3WSg!qBMlqB;GpU@ z$$Wb5tIweA!L!-Zx_&1sf)u$`K)?BV{>5+D+)J-Ktc5Sj*1ACbS-E zf&N-G3W)G*zpi8SIiEb)@Opjeu;1^3ME0;@jSK{ru9q(n-yiFj{6O+5Ouv$!EZ z3l*6H20}_uRr7nY8jNf^N5tcvi*fZC;iwkSVOj00vAprJ*LzIPlivMZg+XGkE-TR%DqxQ3fEF#oj8?32a4L)+?RdY?XzWN<6hXR zT$lJ&8L^>TOL=0HjyGAmH=KBveaeVb~~b0ix* zsY(YoqSd1m#B`6g=`lBXRAbo9du@W#zb4r7(w{DRG4Baa4&*rd+2ojwyQ1?^ktFqrTRKT=1ddWFP_HNg_AXLBHbF*5}{lyFt=P z6doBMx8k_bdH>SfU?E5~rMzP=LxT%H77sCLgi&VUR>K-A_%8+0rR>+>{GtRzpW)hW z9lP0Cmc7T#YK;T(wZxM&Efbwmx36lfj10r^5H-sa*8(^=)!NrQ+iM@+Rd#~Q^94=| zu;$p_i`dLsrf1*$$RWR5H4&){d0wPjvxWqL8g}{E`0Crs36(;1NxeFMednb)EWgKE zOK@^V5q9;}knJwV$UZXkC%pC)Abs9`*EUy!8>iktK8Lmh8kBEk`_!CE4TvzDc#q*xv=0tMe)O%3QlMp&zHBd^AkZ)DsfuAO(`D~%_a?HM2mtZbRM$N!R~Oai zFxq5Pc$9tNbtK!3o`2~c5-!6NYRaPSnB60hmRo*r=jO0i6W^3yp5yq_dzYPK2x}FU znP&K+p)IRUpPgQkl-SX$nwA9*57JRUi_TpC;i5+q=KhO3yG6zhqT(SM`b5@g&5c)K z6M?9T6w9wn&7MFv(XN5fnRFD;u&G+CU#kJl7lpV6HEM~K^Bq9cPHfLA#R|WpOq_N; z=8*gXHvjlQ|Kk)2VSTVS&Eu3G;R3v8l#=i2XFU1i(v||L`@Bnw#jTXnmKd*q8_kLz zgb(Z`9R_+4p4!84?BVMN&-%xHhq?6h`u1cs0TJ?Q7z-PxYqLWFB$!6SNL#>!2H5YF zcdNG6)G5th=a?F^eJ_ndzUfqcSu@8dEZknqyg?H;UJ{HD!kl(`b8kqS@Zg|Ka0E8* zW{1pZKb}J42YSFr_n&^6O)!{8q-K68tfFkW;(Fll2V|PH3$VZ)C(v{dU%tA34@y{F zv0_E!)`gTk0fromYHy2(G#4V}$o&8Goo+NM`}ef@$kI0S%CNj^6A~ZjtB-1y9r~Hx z8@T6AK5+fLAe2!i6KkNC3|9NWYpd3*#ge{%)ceFiL|Skg4pw=!uRFD0>76JA z0$2s;n)MG3viiii^!rig>#T*P`eHRp20qB_3_~epx**zdM;x%H9&7vLTaG#Y69E*h zkDgeCUluUQH@Xul*Rbh@T_xupd~*A4+2YgPv$%a2E3ipPU)x6JK?gP=B(|fV;xWI#5*`v>kEbLdK{#ugsm)12T z0WCn%Em4`b0fLoDjs7b1-)YT~+^AsZu7t#`0U`Gxnm2rg+Cc@8m8vcP^foI6wY$*| zcG%I~pAaEMEmh#D1-7m7;A-ewc@GbPb#-0v(>7p zZ@wT3#x*=Ep$&N0xSTO*d;>zHGV*wlJJ6TivZGPwOpjUaHPrpVy+l8s_xlgMO+TAb zh1bE{@LPPcIx3bmBv8jY9Q%AWsNL5;tXPf|7sQE%aJa;67v5y-Rion@Q^@+p?|de| zL>y+uJX%riTYEE>Umv`JsaVG=m^5EqEvzMYUR-05tQ2*pDzk6Rcg=q?j`9f@H8--D zcfcJBd7|8=pXGO8A4|BHtu3RfjD^z{6#w+qeIR$reO2!}LuB&g$qL<<`U)AXb-x$Q z<1qk7v^oyRFQ|DS9$k8a`*p79@be*ULv>25<4JO1VX>_k=g;o>BFXos>MVEx=PemA zTr1z>gED*&24XiK!aTrdWLLU5lU_TSPX$t1t$2d*ytShr-QKgf=G^(i`yLcO{?7183+R;1-gfd|#wY zFb2U{|ED@gsvkV`jyU!(m^8@T zGP$xGn^nlEQ&99TLUkdo6_RG&^QOG^kvL%3ZtmaQg{DY)kr&SibL?xS!`2(d*rPoB z90L(IE1PKT{lLugpM&b7H_7#RigUQ^LRdY(S1c5t>G!#`kd!>|=9(Ajk&?r&dSav# zxfYPpWDlp{e!-c|F%&UNB-+~!n&wmHYPDZ2#99ijfjnJZ-Oo+ka#cZX6o-bU$x7Ib=A3S>+Ew879qqD^ zGGWI^?m(10mEl=$Hx`l4Em(uIM~-7ZmWski9t z09~CM(xLAQgJeeW7j~;TI$v%L8e=HT_LVFY?ey9t>dY}!mwWh;Jp9|nHoX8Zw_?IE z1sjw-zNU!{z?zF&Tau7-;e;k#?*x{bcmuQrO3c)(vkH-_a3B6ZeLqh5r}5Ok7rXWm zi9G{oo9o_)x7|#73bTtdWE0-#73nbh>5?l1Zm{TKM2oDh{yG^r`5zY8w>$|$j&quQ3C>3bi0>i#7j9R2$M zScj1gsP5)_E%;t!%2q+wc2v^q0|H^Xrr5$hRM*sQrD*^U+)i(!wBeKuTCN^desO+C z5H;_sBf1=#z<2xUfSSm7@4p_60b!@HyXyAid9`7e8T?Dqm}dM{5Em=}f!4VN`Y8iF z)kz!-`JacTxaamuMCO)W3DHWnT0hmRX-S4t*xADSHj&B4#zcgz->8zz_Wi+GkI8NMkU`@Cd->*XS4Iut&H}rip`=TX# z##JutK-pLoW_F`wxz724;6+wcvN}Ws6(l4@)g*>VzB&Kxqn^f^{4KnaaH0(*n);z? zIA2OdL>ve{q--JpLA=Bbu&cJHe&=NCGgbY6=OM~f2jl^X{ta$P)7GJt?7E||W&UdM zrJ&%A7WFr{o3T|9a`vRq5M;ddm==+@h{HK2AApcMTuW2mHsO_cxi;DxP{d4*fAx^5 zFIzUtrM_ya2LH9RlM)7nbHW?Oj(;+ZId43=LQR|#sEccY;(DdRjir3w*(5}2nNW7z zS};`f_Cd)W*n)*V?__{DkhiFKWH}?2gwNxXV`$lT#~K7anatFJr5i^*7HAxhjSv*T z+hKjOFyV$R?@y0nGprXPvlVCr-M&u)ZV$PEb8 zRY|54+5!oOrBe#|z@P2CG4iL$v>lY&ZTb&l2RUKCrOtiXKNnLHnl2*rS7mw7WXm%=`St&n26zonT?+_ zwQo*O(Z^5Md=nsc^K>Yi)ub>(DM}E6 z9%K>+8znuKDp#JZie_dIJEG5UZJw>)!K~iUIHbNE0e~h#mQG#IVyS)IE>;1psb>4M#KPf1k#=upZ8^6U7 z>~ute$!?u5>a(RHYZq2;S_6D!0|VxOZgP`MChaeH4|0CR=jXJz2OLjOW)luNee%M~ zR7IM=kaSqVmZ%&u^bGKS@k^!6*64)%m+K^@#c!Z4H^c-NKN;FN<)#NhXRCW}stBlW zXPGk}4nW6R+tv~AM^a=*dOPmWmV5zs>hso-d-9%axCI(?fTi&;7uE?X_`fKCCG%F? zhbS2e@U5T51?Tv2F+oGQN8)Qn#{zc|40f)nKhR{I75FMuP=T|g&JBFl!NQ|tVoR61 zwc@_dGZ6MjsxTk+cVR@xb1?$$fWbhD6mZc99e1gE)&t2!rQghW-E$C+ZiR6oEP!P9 zmTuzM|7EY}7qIC_5U?K8lV~z6Ue>9eqA|%)LvLf6j(oWK*rO>-q+7_D(LX2I(cmIk zde{#9L3QqK z0pci;oUaxDa%*Jcz_TCM3T7Nzg?a*Lm(u7QFuB}5J_g^eNv-7I%Ih$)$Tt62Z~?DW zoog1jdXDfOkmEhqYjR}6qY!>NS${D2NOvDZaccNCHYm1V#Zp>MaeRIwU%m-(=(I4T zs(2x6dBu!`3`@3nstHD>VQDfWopa&oa;VJ6ZJv^kj9Q;1PdN9KYFE{(Wp+mjk0Ho_ zMIPJm3|VTZKF$C03bb+9_MD;C@Th=~iekCzF%sM+6+5dBOf6Jqz*CXCo$<#Gc9#UE ztVHZ359kg!|CR5FEEhkSB!OMrO_Y|osxLHfR5>4CZW@;;SN?sI`weQZ?{R0*DmXfP z0k0NF;TZ2u@8_fryFd1?q0H#~#K{_LLMa?nUy19zm?}WfMA!q9AD2_<5hq-9S-xn& z1M7P20eeBzI5%&UhPc>3XytgC!OHeR-}Qm`5I%P=6&eiY;h4)cfBU`x=eSzN;vZTl z+N`108W)-Ko2q*LF&HrO1TsxO`|zNvot8Sz06$u{TGpy2(M#Y~7ADl$Nqo zK(-omn57{TzYbVD2!W?nGr04B~204f+tQAsB6hTeWnOFBneik2wD{CE>KCyQE=$D zi1rqnh{~=7u?&~^7osH6I2Bf?y(re8tNAf;-P7LoEP7$uc*&XLDyf%wz}@SZK@F7t zuB<(Z6=I~wbj70j$!0vIvg^dqBYEUH^KkSI$^Xe{m!B9Ux*s`YIDFn$bhs-rSqU8lMep3B1YFB2M__j^Tb zRYd;YW+G9s)2EM`%@+x0DM6Xa#Dr1SBeVbmshA&mviMK3Zn6%yWvcH&hc*L>-!FJwj3Y$NYkm=&Gi zIHpyaVmORJ>{;8O(}T%}V{K)@3oL#rNyQ~yn||a+qrF2Cuvjn~qZXt(NZJ_u555PQ z=IWQ)o?)eMz#fSRwdGn@glb}pqEXjx@CR606q3i=^6KQP(4}$iyzs)vZril=1k)F0 z3cL;@xm16crHlY4>Q{4n+ZQq!|E)y1e8eRolQ|qYBTZx!wveemd$Lg|eS2Q^VkAZ z?n-v7^hxYvRHPP}lHP&oE$-OA+_ToofRlQgLH3*mxJWm1d0Jcrfo>STn+`_EG z+C(dJHgYV_(-5S1ibs2)|CVmF%*ExyH9f%f=euOYe;*|TqH*I|EbS@AD zN)Da2*#~(s*_Pbgqq4ikox+lmc3QPbsY_*cs@|o-Ij(Kw&k>j^NO>3)tB&@ z>D2$`2*~0$mVZ00aafQrl6h3EFX25qOY(7uvK&{lF>5K@_0)1*ZFt0X% z+d-W5t1lA!d6rZ_92mL~i^iY+GY5n^O~JhDO7Im8I@%x5>PnEijLu%HzjRiy%JI~_ zbG=&7`ZVsqY8{-VWkq-Z-`c!16lH)_1z?6Rjobo`Jwc_tpcRrDIqG$)qqRH`2`dt2 z%B8yx5V;SfA_qT?U;FNWsacI>!8S>ZdCbN)gE5(rv4JLd^hk5TFfaN8g;w-rWbDsp ze@ve+L3%iO%SXB{rzw}>6>k+%759dOe4c-u;q5gPMr{s7BdNNOfi66nuLzsqINK<| zmf%TO9pvyBlGI|pI}-dp>~0Ta0loGT-gp!-000830iPz!Y9hY?062Bmik>;l2qi~F zkSSw^NYt7D6)B7YM@onf#^41X{J>nCl^AU-r7tIHossCBL>^XVInoMl>EGKX1S?FY z4{c$Pqg$=!aC_x9RXw?+P%{=`^%t^LCK~Y1nI>_A@Ceg9_EEkfG2V~?MmZ=bkj=is zR$(#hzX@U!@_-6pN*F`{c|eB0=UHC}VmjB=c}7a-ZK4FE_Sa`mj};XW_6-&7-^CUB_Gnx1W0Q%@NTcS?38Qin#inNy3v;8n?Ei%N%bRZtwEO2rBX|8&${B z3Y-4Vw^vkQ&!OzB4Sgc|lbi>D#{nf&54&7e7?%a6wd@}X*u#XNCoTzMVZFXJ7J=@7jHpd4&GmcT~&+!iEMIU`@Oz>FHay%%0 z08|Wj;2j4PLS>9dJ71LWdrsybsa0LXdbbkIvOaD*C8GYW%`8PwQ4nPg>lYelA2nvb z!$wgGF4V%}VwO`WWBxgdVj~o#24YR`L|~B|4%Myhv=8Hz@$q~|q{gTZrw|R*9$(2= zPGp_YICrklr<tW}o}Sj_C;l$=y5*5{(Mq zZ4vAVi;URph|B+JyL?vVI+I_{(IYpu*F)tL{p*Nzw)}@;PTO60J@3qLjZPXU8>NY# z!Y5f!<(AfVx4qn4gfBJ{=G~+)F~;1r9gENmqr+rk0TH(6qzFRsIo}2}0008q0iP!9 zY9hY?061^6AhdvLaN01R3dH=Fe+1wF_UJSeL$^>pS)9xWhxEDq#K6Qz?Wn zXn-B|aBq;iN;?1DH1kW^zz~w{MV;!L;f}0!6$pOE9$o+ydf2IU4xp$PFe{7-1;=Pc zE6JQNJwqg<5CKg{TIXSCK8=<^Fs^{R%D}97wb!!qc=a_R_8iS5WXYz)21Rj6-rkAA zzWw_F?2Wa9mKS=YKqG{1xLsy>bzj@ZS|9amJ81QZj`#k3p|cubAZ6Y1JT_bA%8E0p z1MVSv(b4?pEv0GDWJPNtdP<53iJGDp0d$GfA@|ir3ayu8qD<2NfSDM)8EwPy7)E=` z+p2TEH)pR9_daVzSmdwpjAd-T-Rb0nXH*8f&ny9D^g`;cLzr=@C`>Z< zZsl>|{&}=>5Ab_*MhVt`6cB6f34oa6{qDab;VqRSP**p4$Z|gET~w&EeXYGe3r0rRTRv@%aC<)6cElCJu$cUVTj}(U#Bbp&V0nsX03VLRL zikMm>kx*P&5;y{~P08b$nEOz1r?7FgEb=7SzKAFd52`!298W8SpA*rnG|yt|XK3y! z=qAMb<6T}x-L#}~kYlfi9n#y!*i~A+#3k!IluF)o(+3Ybuz$5?g37U$s4YKjxs)Dt zEkvNPapD4xpLyB2GK`g`Ym{{HS{vs6039>I7<a=0IH~!U+~($REo^Urx7(cJBFP1lG_r(r7fG=i>(@ z(vapNH3r>6u!~frK4hs}T1MIvW5S_Sbo*-7yQo;^#=^*PSs2VS3v{sOK}*vBix36` z0009f0iP!fY9hY?061^69;^mae=!Jo?5X~gKBL~v4zp1& zFY7@wKUX0GFKV6DMP#m|SJT5@eJ(3br6s6!HnyOKV^F7kUk!|+cAef@g-)01Pp8an z9#Zx;bJr9A0imPiJiz!J`dM|$3b#aXWdkug1)O&~JxDL-nZDHh!{g!5!T}uzZSAsl zOp8FiK|{peX_oL0|HY-zRki&K21YC-6t{~as*$5hHK}?Dk6OB03!Y}6tZR(oysbbP z0KSiPU#F59=52o1Ig=)gv?i~xWpnkuKU<1bC_I{2Q zugN_)z`jcBzZm0J86JsP0#mXbNN|yB-)pb#TTW7;t75&Yz7rPflsfq6q zN(n+)EGNLk?iSQ%*EeqP853(A%TR0OuK|41CqUmphGNR~$r&21&bNpV#k8(D2We(1`g9z7X3*c$>5O8VEr>xCd>y|y zgOa}A*59)Xc@;qHAq&Q{#$@P_FWc zp8_6VU0io!BZ}3K8huzhPE4RM6I%$+Bp3&*Bkf_2)<0UYVdF<_7G~;AUJp5u!y6|C!j7SDsu{7x(DuQ3fctoz~I)#L>iT4bmCl*D362b~MM&v7O z4+|n#XpP!A-INh<5fJPzi1E{BitlqvfyF<) zcBPD=o*#Zk6mVNDXa6Gr4Mhnk=0RiE*?{~+h+qMisxS1++moFq@=1O3UZlX*ts`sz zM!*070tx}2Cv0?z{{R3orPlhi);#=g#_kUe00093TESfph%im;FFWGA)!C{@M-&{Ju$X@fR6D3JmX-|Az=?IW5) z^>~+J4zV|ekBt2;NLJmGCD{0UHQM$j5KSE|ij>nsz6t$^zX~_uA%Luf1fw>gY|J)= z6i@?_e66G^q(v1c{%B>aPNZjJ-~mF7>@=OuUeJTQw=yLv_cL}p`EQ>9Lp6oa18jtO zuU?LvZa9l#pojtQq^nM}NWxeRagixsn&2aqa<2#mljAF)aPSj{f#)s7I$ew0frC#1 zf(sYgM8tJ0a^a@BRO_$EqZ|aYS+4dU7P5H(3^Gk1X=mTm4O*_+&KOpza{K!@)WpVW z_UqldB^Lvm7M~?V!7QR*-<^7!iQRyTV%d%`MR5Z1zj}C6z#8D&VIl(WWW?b>Aq;*! zd&&9LOAyw6|BjU~8q57!T_%F%Wm*&e^Dhppv(#TqivZimD-vuC-|Uw6S63T{nax!B zwzC{g^Z*QK000G60iP#~bc+7~06E#1mFIP>n7dycT}6-nr*v^cIyImY5PN%vL@J-+ znpiem!m6sYKmjTqbTT=J8VBVFY%awO4t5EFC)f=n+*jpn3e)hlSvgRdR#)QqhO+E> zwbn(Qs&NbWqJAREK{wX8Z4JL6^gd+>OCDtle8ZU=A*N#K_7USjOQMBwR69+n<<60_e1mR52g-Sgc(m>gq`vQs8*wKz>eP{4z%;sNh;6c2FAgM-8tz)3 z?U!^!EHR#U`7VgLcm(alYYoIN8PGt{8j?x&;D&3S{b(OxNeZ*2#S6ulps%?~@w4_r zCk4MPrD`?eFmT~qN@dR#0%?$oElm;PCWOT{f(GAN5#00|4od1_J|;ky0pXYm3vkRGCV0Ke{# z&DF`Dm-tv>BXIPfI8^ArQf~;JNaKJUVa*-9x$ylylnhH58TtCR?4t=u$y_t8q61_& zHHH}-Xb)eV&Z&7c(6W%o!K+a)Bae2As%bv9BzTAdOT>5vu(wd+HBbPsN)PS70lFEk z^H*?ym3YECspK9um#Arch24>3wAjYcZ_aN(4f60JKdV0WpXEU+FOm3?tt>282LZpO zLm62uLG`*{R^6BZ!KgD%Mw>YkHP(Aej;9bM-B`4*)wQ!I3K2hyCZT#-lMs~kMV{+hb! z+hT4Y3xEUzP7H@8zI2X+$bnJcGvOdFzkOrf0f0Ru&PPr1uCSwPg`tVV`I;N=;(L@B zItM%1Dv#2oC3bxVSYBL>jDt#fTSja(gTfRE#Y=4<{hcIqKSuH+lbc8Zdvd{Ql;(DtE2!nlKI`6s(H`)?r9)nWS&SGfz&A77I`4QihicXv^jI?uBUsznzM1dJj!VH z^4p$ygc&qV^!Sd6E0(Za?A=voF(^k0#_7HUz&nIBoOnt&B?2{f)*$XgMk{aml){CS zz%%sQjy3YF1;h}E$v!R8B+f$Z@0{Mgt?0kVMB-$#iFJHU4KGAE~5AM1X!r9Us!1JDavy;$Kgb}PIGFW5?A zLWoy-JK|~+WOzOBcP)aGIcimQ6Beh8DIov=0@y*DC&r*aTU%ROTU%NtQvd)100aL3 z00RPbixS!0wn#(E`--*4Yp*^K>xOKINWh%?SO8@92BI(2Y~8k?0Q!o(>@g$;f^!ssiI%iy^;lP|Pfx5;)ZZcoC0;iaMywj(~f z5@Et~@!7Zl4#crVB#fHD0LbC4`rXgd0Spo&mpI2&v`Q-y&9l}mukTwD2BRsS&ts`r zc;2FK>6iv@kMIMe_(Mc`=^MyFYjPnq%*T+NBbPo+l7E`I5UC^zz!lUu16`Kya>ETX z4(#^->V(5d2k~XqDdRluPe_ecp1Cv7B^z*8$3y)eQx>fhJ}dSP!tt5^Q~+y*)9-)Y zyJkhO(*SeIqjb&?yL(`QofN76Z~i-4Uc#ZWeSi>B_O7nY4t7RprtorfXU_)mG&*s;1`PAeA1IP*kPIN5k+8>KVu!8w%nIt4gL7v8Sqqq@;(a~#vwQk^8?E2Ck z_1m8+iRu@d$9_lx02_mUBw)?$15$7nTjf>BL(~sbZ>U?vtk7mMBubSz2|w%;IkSdc zJMANn7gF&fGLb_$8`c2GHmVxZgN%BBJSiB6+iwyp2<*{I9UlDe^x|m%`i-&&blWd1 z>n+gRx0Jym#AbX9O0cgJ6iT6kw{;=xX|MDEHDLe%HKIYAD2IUpme$tR*4EUSOaK4_ z01E#A01{Z%8p30k2pR451?g+ZzsZ%hH`@wIg){qQ^Z$92L>I^LHsp}mzT2}=d&x5e zBdDe-Dt}QUe9YDoCvUs@az~WD`zqcmjX`ca8p?n;T#JaWi_)sEfqS4!zFYfhg?}d` z7)2>}E_^oPgkCcm1GWXow02i<$u+QF=ja$cvT1h%5`Qt#sZkZQ@>yJG8#8e2rN+e< zcsLzk-qKlKvt_$Og0ztk?1KD=d&MjKxdY3g<8D+bivYcWLQ)jL(-rPvNW+vJ<60n| z=e~0YpL|m~buDofzW9)fTuVtXx5?p7nNcD|quW*Z>N*tHAP4jjz>wALtJr?9C-6*VN7~AA=G3}C-Ee*r zu@&6TV-R%K0PsLP_&fMIETxPkQm#jo{2)SeP{grI1~%LbQcB*?*b7yZ7MPA+;>Fd2 zZYcXgc@g&AbLN=0eA|7Ba}7{uuC_M2&3d-oIO~n8`29B<^GGCxs z=O`0Ed3cRH#}&vmFuqu==A0>XeR=nr<{Upno6T#uRaQ&fW%_poOO#I$97lUOQe0sf z1SiN=M@U5$yX)66{lT#HXJMZ6(sE~L8>*o%cF4d_YfJi`TaihW=YF6Uzf>%IE&9C5 zPs<=xbJ3}PKDUZJ!R+A-<;7sf_x;Uhi-thO1M1P13zwP_B{0v~TrZ91S%Wo43KFe| zhvb@zF>keF&`gVHqU_)`sDYSPBOhG!Q`lu}9|L#Hi2F+b7!m^6wHz4YHvupc4#?uv zMwgtWlob6^JN~#m_Dzz>+=_zwxVF>BCbkZ}t5SY2{pCBTj!#XX>OPrz9ZhcgR*gxL z#wf;sBUS~51?;$|8Z~>j2?IG@JvYI#jFmEmZ&qrZYuB_})0^lPKx7Z?LPNnX|DaO3 zqC9J%_y?NvG+%jwEC1uNdJUodZU5gwHo@QOP3&Cks_*+T#xH*=^_NfMMq1QBa3CkX zUZ!8-sW`iC!_0SxGF;Dm#HWry#p`W26U-Xvj4kMYRzZYmr2oO&ac|E-_sD7p>Tj%* zHc5PbEDFAF9+>we4ZHxB~w&MAj- zlfrc4I;YVf+ed#wDR4?30Z^NfurSYgp-mdpT35v9>09N(1Kp~pk5`9h*NjrZmruH(G&O7&;wt{D+?p%Z>Zr-Y@MF%bdnfdjWZ@m#xIAH8g6^h2%g% zVk`FX&e~Uaa#X20MbW>Bi?>-}?F*Oya{tR9`eDQjov2%U^O75lFcB#ajzFm&l;qR? zfip*>0k_7jNXowX9qY7i+~f)XOd8SjPD@s-h2QPBF@1H-{G;ya)=;0lh2E57D3WvD zY>#fQzK8E@Ot&v2RF&`iDAy0Yz5d&763umLWZFp_Ub0SG&EIPsG;{8nW%X@y-{W@; zMR)9oWHf(7S>5D99;If@+0Aw5_s}LO24&%Kmg+7SJjI|Ud|CiQ(eVa?IKUGT8wWOv zPEy>wu;YQ=HEd$PGy`x`sG2Q9vZkcll8Q^}DVtZvAIU;~aJE=<4;T)e8wLV*He$;~ zy~z5kNab00r4`8ta%(DXG|xE8xV!M%f<>ImL3*Lj3g}(DjF#0Ued^qe{?TETH#@^U z{g{mANL*4%&4yidmCzW7^n+?^9WbT$ZBWwDRQXaRud2zhheGI1Bz?c3Ng(5(P`Yge zBFR5LN){Rr{*A98?G43NC`{Mq#Lz793n7y4nASqlm4;pfFSX{mkaX|(fOrt0V@Yw= z<|$&a{NT3p9@R}5G^(+YQEGe|4d3N{dxJ7ebwo6B+{pBPUr7$(VKoUdzIQ6e=G1s5 zVDXcia%aK>wU0G{GR-Cnl~29(sX0p&0E?nBsDY)S&!oJ$2E`^aAL#2t?WUcmTSS$` zp$}c{oJ?{`aP@3!9l#=?+v@6v<~@S5mg|Z0>AxO=lI){E%6DnBcLjkXhJBlnX#THG zv`FUsd%>F2+IFUHRd{gXTZa2g()1j3K3e7f7;DWR77q-D&AMvV4*g*Q%$gHmo3CXV zFDgk1+K5c8@^PCo9ahBJ+o1TJkRSS@hY*N+RtbBNA zgVbWRBB2pREAmF|1r51kw0c;RT$Y0k6_D`Q*@t1Cz?sMTqos-NGi|ehp$p){aE&V9 z;WadaJw>?Zw}M2v#7g|})579}fB`7{HlZE;Zw+>*?MYkngS6?Y7Hvym?rWpXe?eL4^~$H`54Y zn(+zId)jNK66%Y7nw|$y?O^M)ENC-DYdU!TrN1-(XonUGT3ljhugGw8XvG+M`TU%n z4N;fw1%$d(`Ddz}qlfyq<-Hapv*jtA$D2I9p;Q&?q(E3BVqHy0zkGd zrKa(hu?BNY$0Z&*4u01wUfQWCCSgp(%al;-{sZe@|Nghv7GgK5EH!Ghca5#zVT->J zt}S}07JNfcq)S8$ZTA^BLED z^2xJ82L}qOW9kdxnv#w7<-lz>_Nt_9IFE)*)A4ora9Bd6nunvjbXDu1d`Lw%C9^$H zCK7o=KM;@e!Xv^nJXCtyQ=(6R1Ve6{(@aA(b*w7`XPzG98~z zT6!pl6`rz#Fo9PoJDsiuAtxAK<9_*)ixcYNW4*!_@}nTxCzy~I%an?{)#)LM5{sQY zZOObx7O+rimLC%Qe^jyK&hzkKn9(3FJV87?W26~AqoDnc`?N7(9e`0BNlKw0?dmSb z;r(bPyvDY)VZT)V;IiwmrR93!`NgV5a^_0>B&WjnwFq8*zLbEWCO5)6SM~O|d~?o> zC)c@~s+y6fE7fxa$tF1&j z>9Uh+QID*VpHQ^sQEN}U*FrC#j-I=v|NpF>!%&;&as%Dz8i$-?c!T@m&u?J=e8WO0 zo~!_%_$jGL+@YsB>ABs^7j>Oy?a`>EW=mD#g3r^tlnkHP6psgOB&Z3f%{NbOD~PxJ zKfbg!zj&nlCcIa|Zvvbs%p)<>N(E5m0s(6i!(|&**_cI+K|U){Ejndan3lXw+4d15{HwF= z$ADK;r2MBirJM0#?twh_5q;OxDQVXn3A53Of=2R!x&_#U2}r%?XYsSB?Z-CUBdgr} ztyo&Wt@Og%Kf1Llns!$SJ&9|hl>`B)U^Q7zlbku!C0gr*3V9Om!AVId{e zn>G>yyWosje%BT%#cOARPh`+A?aZ_z4ktLzB3aW`l*|3OyuW}x4 zj{^PIFLg)oTfFtBEkJXJ5)VD10otVWf>v*+(kBC}`hek)5R-G-HtnC#yofG0srMq) z&kGoF`OE5gERi-#T#)Rm58O0Hp!gg%ege1nig=0p!v*M=tcgV43$$vbr9%BxsZG~V ztjUFjs`ZdwGTpAY23dV~VMCI7Odfpn>XnwP@f`akr%WTOr_`~trZb-t1(-i zj>~eEV-fsYQ%Cvd=oT4TI#MQD!T;plZGlPbaa^Z!%&c z`l0m*m#iyc_Qp4FcJ;}1vj*FFtS~Z|#*M~k!f0{V-KN7RD;~QwbBl~Z5XC3xhETiB z+o6Xk2*=K`t@hEkNK^f|pa|2Oc_q9|_6>`8Y3hh^L;#@3JII81Kbr8liEZ{zKpIY6 zn)msSDV|j=f6m5Y;15*5pRE2Fvg7FS&+@ljs66bH68eM?RseQ z+BSTu8fqg*SxJ0(OC}0tFcP_Y9^>k}$JOsd()n|v=j+z38{zwUW2ZmB8ZT_#I1-;z zOh~OJ#`9pfGD*33sf~eFYLpai0g~FUbcDZfq6S|($Ew|&SF;t_|jUu@D8 z-+eF1aSOYV3V;@a%mS=N&9?aay*U6LqhDUQV3E@eLv;4G8RRB`fbbFGQA_O7(cfM8 zJAwD@7W?ud+qkh)$1I_0V;=K^QqNI>47Y7qv$jxQ#~mwz%MEL?nmB+vaG2T~Y*yb+ za|1ZWKr8i2apwMAs=`Qgjb2vAn!OKxf(iiz+MB6Gas>m_`-pctE`#i^ezjQr~(c?dvGbnbhy>;<8Y}s|t1B`@iaA(Agd9)whUJ>^TH!H8X zX*eMWt*0T6&V2WJ^>JvF;}CB<#Iw~r(Mj`V*|UnLvgH7~F}$Bw&GqXf+z9uY>nCHi z>{}7`V@`^+p_gC91ihN87f3ta#Z+-p^DG&p{L|u{sfY4hj5N$6S8WoDBafdycRCuB zKdiFLLbWRrAOQPYzO{`9hwu`dY@B$#3k(>lF^%zL?EuHizKecoRxkTAB%Ezi{--$| z^Nn^%S_^+TXcoq;0)vOYMWBUYIkv z^kTlhRWP~eOdgHura{m@kXHjOel`Ut)~I%eJ_F^oLcij%9l`9xsS@at9p5;!HOBka zl?%JnFAxs06bC#LORmIt@ZfzKg5LL&zEqqK;)X&$SB2izppfM}$aNeoxrKsmXqJnD zOL)o0s*p*Vh?O~(_NM(MAi+Y$yV&NW1SJT+K61u31X-8QA>{?G5+H1fz1&7)Ey z_;vX<3ScpbkL0}S5zaGhMj&3+=}5~5<&@l7QAvVXk8Ou)r@Tvutj3@Urp0yxT&K{+ zcd8zTH)V>aZ1gCI0G08y@YR-cwDf2df*|Ut@VXP4|8@P^U|3jKw^q?MrlZk4Npvys zwbI2;K04IhC*oMYs1iXJ=amdcNQ$Pb!THA=%Rf(Hg`s;TGQRt04ya5kC@&~<-sHaP z;56eDo~4;cPT0XX;q9p+p8s7qTGf;zxLwr1P9VNC20>q{KTE;NG(7JcoBWg&xnd}R z0ylJz6kmue_1De5$E<1qL8L+(PI9KNe&t$4O6y6Q%V?hG%EUkCd?<}v-qJ*iCR0nk z5g&Px-|m5fzrV4rKbF#f8;X{p`g!iohrhB&?1ua~-m;^VA{3Kom^r4R5za zwKM{VpQDF44yi7CXiO)i^Gnhd!YiNW3fBH{YJ&DJ9st*!u0_7bRK4wen@b zfG5Ic%XqU<2G~x(d!~uteUr;2z0trBoMZ+kYR!O!+LwV1U9?NZ9y)Rtf1Wqd8BWG=NCuo&pbn z65yaDAW6cy3TnLW)y2;#ILA-PdqtJMG;U)}g2RtZwbzN|BL!ugP*(6Z0<15uDsb&{ z*z}gA;~TB<4iIXj+HNKDA0w7)??;7EE%DYPBPiw}lso+{7O}xQEa~x|QVMG?kad}f zfaL1Z9x4tSWMZt%mHnASIX(oB)Vl3duUh2Gu4=p&bS3SO+uqp_(5vdu9jWaq>4b;92 zqIJo(bWo@OM_+YR_=NXN#hCr$z8}X039tkV$KlR=sgT!_`;swa)t2%X7qhaZe=|p+ zIR$WG4FUtJX3{tbM_zX@tLQ&;Il~U6fSuaaKHJIhQ&J)pI&v4@PP8Q82`r0`JqU}tr=FjB}02mXCYpM#{ zqYxD_m**#dbxR1}8YmLW3st#@$z&W>r3RbAC}fB~6-q6Ch#M1rdkIDBmoQcqAz&a} zFHxIzrHhwE76Ha6zrRcoSR&yn4f$Lh!LUC%YY|-XXWjf7X881R>@kGQbcX!p#+(u4 zJ^~eh^!#)_6zXkfS8ZTC$(hbPsr3{&yeXoxwkJNgE+W_JUgkh!d%x;VnhkRN5C{KmfmAIXiENH?E?>Vv5aI`!jnd7X=IU*Kq#oTl-I*J^Xzah<20$ zexr78zWUukEtD$zuOoD$7Rs@oQk@xr8$P=k=P(_{Bh2bd`e!WK7f5Vdhn&o#mdx=lS3KXlP8HiDgm#jr?34wtX>Mi1~o0P1%}H zx06N(R$S@3E4hg4>TqVIB`BM2J~M`B_lnuR`zJ|Rm>#GBa#fW&Yv@iOyr z50Yog{F;_^E#w#MqXo$I)i0cuhHDmNfuL(#WWq~@erJ0Qi$9!n(}BV4w$XB_4HQ6u zF-6WNQ+6G{E2uV0z}zAH?UxdntMiYHO|4dj5vwn`gY z@K|X~oul8~s(56N-64Re)%9xVhj>uBN7f_IDvMq*G5fCN!xv;bz?7Y}qB5P+bugH{ z+Sr(Jv)A;b2FV+2iP`IZnEJMC(n{D2ZzUpYE4eCI&7a~sSKEVT@SNW<5ceL>fAIBw zLS+IOxEZ!oFq+G!I^|d%l6j&*RKs;XuZ%?cjKEOV4X4xk&)oclisiNr_>Jy4%djV~ zzdPtGL1Bq{o}-N?*oifSM!!Jf>WWO7ar&wPc6(ORWG%&KsGC5z4C z?bt4RBb;Bu+WW=dVQ)gCpNo5Obq!Fr;0;v+m+7<) z;ax@)MO@!P-)Unq6{1P0Hl zkw3H+vXQ{(imn;Lr@~i%`)`v#rdQ7W6INrSDq@xYlC&su`Mq20LFdAYyozTt1{ zqw7S<|5MWKmli!Z5#!Afm7&hb- zCrt!mdKa%$u;Vc^XKQiI>$~3V1xR3uh++JmGjdcyq##0_r0a4ByH9L|HTzDH`yH;P zn{4NA$?rFntv6EG%wn?A^_NHR`t9=-X*w?vRF=U_2u0lenu;%45db^q(Xa`g;UV^kb z@erE+p|-QoqQ9n#?bHI75x9r=cbC`Ilu0}c7A#bzin>O%xPEu0iGHQ$#}c? zHInCEg0q%s7>!7&P8Vt9o}MU^jsNQ+5#|%fhT+9%Tl&IlS!t%ply6422V3=K(aZaEv!{7?pTYTdKe{F=7{EW`=?a~N@iR&abM)KYS?3J z`fwyJ<6EQ8bXb)ciRA2Pfd%rml7}KUb}T*^BWuEkZZGK2S--fG_b!`X2kw^=I2E2i znrgPQz$m&s`UyS!nEq~w2rM}n^C;Bp10`>ZRoQJ!yHTrmIdsqSes^69dHHhUc*pl@ z!ux279rw*S45U+tyHKV}yG`VeKRzvO%5&*&Y1X(S?-}Fs-T>lnw_9xzB>ZDUN*LO3 zM;>>oIr5xd(H-+6JufqqnPtNx=T$HsfCbp=G&((O@Q)z&TVvHAE^(8nG19EDcyQ+* zcYSO2k*R^T!%zuVwhE;}rBFr=K%K06Ns0r1T((*X;O*5r}{<@D7Wcf+ZYIOm*N`=9mPW*x5=z==ZZ^GEOLOFUx%1YMVbVLx;+V zw4R@+s}~ih>KrZKu@x(;(^F)O&;2i>kAs%wjr@dY(M!a8D+q_3CU&d>B|83F-~}nT z!_@?ufa!aIk*t3;bvoRto6GR^a;9}N4Q9i46Uo_rzx5Bd^_?4&NvdF!CU!o6zgQ`` ztaS}dIU~_@EWuh+C8K`n0Ot9ng;v?{i`5{G=o2$Yd=$p}24kIPTHsmcJ-+jE!l4hW zrQASTVXE^CJ-KceH-ASpC(8E|$R$E+^BI=`R&d91{pmR`fqA@>)}}A|@hna%6t$7L z6PIlBO4v#}CHhWeSo=f!$620#8%jU&()L`XOGyx9rgpUeRmxT18DLZDh=SKznpQTN zQz99zwh$cJH>YV~h5t+*L-;ognt%*sKV-`+&5gM6Q>2`QmPXG;j)mkY)rlZh$m7$9 z;;I@ZhD5XGiz0F}Fbg#o<^~PF`#8@qZ^?bNGbG&)Yn;Fgd#NH_jf;a4nnz=vzY@^j z!GLc7i@2%UItHi=V&FsGqKA^?H(z%Mt4^@<jz8YdsLja_AlFbHE9xx+> z?8}el`YPG8nxjDGR_7FB|H#?vV?P{*RPUVyOfgeQg_MH^Zwb@dJK0!N0fH@k|(C z5atWV?(f8ZFK6m~Ns7dpD9HSzSmVaUddvHMd+(-%dbEcFr10?JPlo%w6J@~9+Ed(l zPYf!+=#12SGp8WbK}tZ*97x_@E?kvxp}Az~{EsCyvcaJdh-U1rGoUZB=w0r3j?VIJh{w_4r*!d@1F{G5Al{=x&51 z6)Xn({@OBhboW??bNLEdwFI;b2GpsvI4?QMCo!BF!Ph_#CRscFoZDQEzw6(|wK@{2Jc z*Bm1|y>#tl*Y2ji8{_~S+-;c0B(q+%}Ac?%N4!!)(*l^h{jX#>sn2TK+b7YfV*@=D$)>c z+#6Z9RvF3IA)r`Q`4DFg_Sys0%LlQRHnA?h+1A!|37R85 zxjn7bRm=^sAV-q#hU}z1=RM3mP_tc#vHQnNG;!%!=~Z)U&ed&v1rc$lR2;en3vQH^ z=}+NiwyzR|Aft^#-KZ<Avz>utoY*&96jm4 zLdCx$t5pY@AB{={EEmpe<0rDVMYk3?_|u1d^xr~tjbf_~&VGchD8MkZZyYjs?3jw< zp)uxR$SSUa+&ZqCRX^T{Ol@}k79;@@LaR*;}-=L4FN~drPE@kPy4Q+5;$b0WyRLz4o|8>u!FwoP1 z)g3#|;A;Qg3!QZnq+t~t2f@$1qB9^Q9aqo#!niUNG;FL7;Rx7YgjdBV>7Cs2Wm+sa zh?j8h(A@=sS0DN*;L6Y+kk9%uVIt z%z>uVYZe=Yp&}y74X^v(IX{U^^03^MftG@CxmoBJh$-g#2?`cs%K)1|WWPZvb6GWG z74Kd{+exU#ynobo`!_7}CWN?pvufRO`rIzD(&JZ({+1G=#Sg+4zsWW$;V5p=G#s&C z&&5H)MvC~73J##Pe?{p9wN7&Wa6H!xh=nkI;s*$GWbKNGa;v~n)@Bpwngo6M#%IU7 z->d}n^Xx2a`Y}Z19?{MJeQ&?{WlN0CXaKpWWrmuso{@R2uI2xJI%}0~;ryhAH$Lid zlSRWr6J@}9l47vxOo1Qf3A-|w{n&U*LIg@J$c|*AAX%r+$WPn@GUEe|=?ALK?J$zp zJn?Q(4XoM@+H}ZDyhYUf$V-g445$d5B`A2nJL#!#<2u-iCJ04|M-x-t+>Ev=S^V}XKp7adj_y$ey|2LM=U#yx4@g($l1RQ z+@@T+STTEj1FH5bIcLsf5a=I1=z1f2cvW@gR8r!#Hh4{W=WE0yO zB1?Dql?@PX728|Dt}A2kf%Xy52k9QqOKBFH$;7xP(=G4L`$K}Aa|$wiuzmW%KVz9d z>-Dv7=YMNRV{ay|maRC2Knl#+ybo1`b%R?Rz2mmG5cE;=@&*+a8UQY#siA z7-d{b#iCCc*Z?tWs7u18?EK1MMvbjbDJ*tjAvZ0X<0%C?A>1EY6pp&7T2o9>3k@ES z@%v;I{gX_K63tzcNKziVLzG&LD4#@_%3cy&MIg3KK$hHfW+&G4}Lb&r`ABe=A=1BkE(26kQtouSjTe^Jj zyqfHqMh@rQqo~-L9dt;z7}s?$%*=LorcOc3?jR1u#KEO9pGI01)116wV;&2;F^DWo;{L#^rX;1s4W&fAj?))KJ#+F~w~416qj6*F@7LxBINN!P9^ zt1wL%04iTAC=371POe&9wjfv80d|=wWl)ipcnZctd4jM!B$=__Nwp1)LYV0;zAQTe zs@pa~w>v_tmp#+TgV=)*ZgHHIj+!(l!w8lm@?X!VCVzcl8-PN6n+V1YSe;VOx$4|?+LEBSkxmUgMRyv7^gS9L2Cd~GONNy^YoVd&&)5KLK@Gket z5qgDj`CGj6ax*!?wiI}HRSq}Ij<~0Bx%qjfMXfn%A6-IxHNTo9g1>#j7sxvDPy$qq zjcAYM;D)icBLGJb!3gUM&0I~Pm5FNz_GQcFQ2Enr;+mHYSKhsu6<-%D2(q1>42Enz zQT4PP-r|tRdd%>%FM9p}fG7Wm^GHvBq+nnL2dbBFM6;caS1qTB(?ANdht*Xx;G_VI zN4A^QxLJ+xbR74nSPdmOp;x1Z+QvZq48kwu28*U&ae)Fa)5e?#t{oy5!wdZuI&kA{ zbkfc6L79iqhWYZ#YHe!lY~qyAGC&Be$ek0gUvF%Sn_&;QA1qs~83?v*b@7&lpU85v zKso|z$@MT($bhaFbCR%l?e%Ok#uP?Two;HSbk7Y??sMog9B=`TbUY~F7h;%Ma-u_1 z4X+V}_T{pl2OG3JZHw)t0CSc^MAJqUI=?EX@fw{|(QlxCL=%{C+e=MF;%K$_0()$+ z+&Vt*OM@xl({S0eV`_Y_{$5hr`!YYm-@_0=#JJ`9%})@yEVq4Tuh^W%!{wPSgd2tt z5u44o;%DDlRg_K3JptSRZ2r|{F^FWwCUnxTPVquDqc2EuTm$Vl2&<{o{A!(vYHN|g zlX>KMf-X)}rE`oj-67EZA`rapqa~6IEEKRd*a5TmUj7(|7n&S4sxSP)(EqsPJV4WM zqLW7&=8UxWRz>E{x)hz_o+sSNO%_&iM)W(DbTYPPU^VbPe4SRR8}t}z|0b7id*_N9 zw0s{A3tz284d6r@{X;T@n7YCQQyCnbMj&A`TpamtGc|th?tB{l8-;5Jp8S}$g!S;Q zPW}6WQeZ;1InjLnMl-TiLRL_-9pvTvZ*9T>i1=xhZhtD};1HxewI~2Z@5+A+wNCzh#T~&we&qphCeu$M3VaJk3au!rfA*$&R~ivVnl;u`f1%ri z86`>RaWxZ1^3WJ{9d-!CK)Y?d?#?*f@mGzTfG7qCB=dPrpI2h=9H|`CNrAjF7Dr<$ zsO?bqg%T;UDkqBV&H4y%T#DR|QpL@T>-oOHyV3C&0{j_~dpklvplDSQCab~$-e3+H z9`UVJ*{ati^cCZ45GOzMjG!fnP4dhqmVqsWx=UVy>xJGO;@slsPcev1i{|^9vZ%c` zBzuz^@5~@X^cv~=frmevpgr4X(;zpA5|iWo2lOtIP5S9ea@|F?Ecnu>4#~1%a zKGmqk>G6t?^#O8^Ye`<_J}cIL^UC5z1(kp3EMf*CVlC`}s5!^_Y` z6lw+;Gri&i0HCa1kJo#VDT51c$~j3eY@&dHV?>=8`Q9RVdC2z{oU924AlqI~Lh2pe zKotFrQkwvvEV8V;VY4wKfJ$Ew2vzH<+kVMGB5SK5NB`*<` zzNXp^&$Isg@xS*_;G~0^&}`dBSg^@z1H#nfjQ0!)t~h9%U$cKkv^eejeogjSbf>g7 zIE@^noZq`&x7aeGZNot=!&_fDOxV#3E}0>KhIN!*IYQ%cCiX0`fdBvzKtZ1{EPSEp zA)EgI06(+Am8R}W6D3Ir?MUXZQj{i;ZV|U&2Sz1o0!02*yAJ3?`v4Yz1@tc7n~Mpv z{pB{5!35Q$VDO!{A1pmUA#<5|z3O|ofSP;!-liYoOAms%+PSu1nnv}rUD{00A+r{| zfGHx_rC}wva@>%t{AA#BJ_F!SM%sydE4E@R4A>rRx%{mc*Hh)f)OhGzw5(MOGv!3! z#J8>BGyyX5Q>u{elK^77y!zHp5%DgUo2Tb>=*TLJCX!RoGJ4}jgOp>6E1~JFpua1? zmG|?ZKDHB>nc-&HfZwrkn#h{^>VTM+VgC(H(D3{FfXFNCJzFCtz z9~TQF__&7FCvy4)aPs=GZ&c;=7#S2)U--JGAD~L5is@?I17KBhG`pqj7E%~d6A;;j zJa5V`GmnfLrhD}Lb{ann8GJ`uJFVaYe840p!&f%xsH}J)1xsOqB9RO(3Pn2v_q03f zWem!^h8-@qw1jWEx1$XKuB?PuIS$r4rS&;Vs?A3{KQ`kx!IiW7!>cfpl?IEio-VC+ z^48R?iwJ5ekNM?R`^Vfu9@@gV*3us2wAqGO@CXNLo1deX_2$P-dqD;Z4 z2q?m=sNNt|b0(i50Xgd2i%i4YxnzO9^@;1hg!qi|@OzB}SEa3LS0T7^tSXgF@juk2 zSjYG_$-0{c*IyNaj_^&s_drqiHT%C-Db6$C{?US2vs=ylvp)f7A$J%HlIK^22HLQJ=!tu&r-lsegQ>CTaH ztbUflZfJV-_^KU+fOghURnNj@(1OMBrTJx=Ht^{C!J1TenmHStu$(Y>tN>IC8lqeb z>%|QbwR9>@>TCPH#?2I=5$b5(@=Eg^$Dz8n=0SM6XTo{{FU#oiH7Vua*4icTgA$;t zNT9UY18L z+mcuOSJA%D&)XPLvlA13#NQ6AK-iR18x_1@;$aG#E#MQ^`sS`1p485+Wu*Cgc`TlT z7>qhc)ErP*ZxpQ_u+a4h_S9WA70pka5$rhz}?f<=J zi==dRsYvY)b7V>Cb-6-D*Z2p`G#g(q^?`r8kNtNObUcXCRim*|ekDu_D8b&DZ1m#< z;OlD4`Il9s`B>DevtbRRyC^3lJ3ZSyW;l)k)ktK7o>@5E8HU&kUxaotZ&`>TfJO{p ztm~7c3zbT~iQf7!)upRy{lNn%J~=OJw`5KOiqLt21~;UMBgBzapAzSBVQ%>9OvH~i zje_!06;IqFDkTL3r~$U_xAX%rAr=Qa*=(+iQ#1339TlV)0LDQgC2Pv_gHS8@uvPyR z8!%U>Ur+|crLWX_)y0|{LTa74z$WXrAPG`s-8dxF?`nMQE=Af{S5TOW3e^WHlVP(N zh8zF!56JMym|u(H-FEb9k|iLFKD|0X1$ZbDQ8b5PN7E4o+ZpEHV%xCSB#5Z1k;U7S zJ`ze%FYmR@>uFZ~OVNn@;QZ&x6!p~r(C`jptwv|98DZ1A3@x?qS|Q_6!KKlKWmYar zB3`6%ct+utn=hG;3a0=#tbwj_^bEKK(8H)gY)OXMGRWnIrDonB!&;7P8M!+{q~@uU z9R{D{H~!o5B2+iWEy_zz1wU<*F|xf1cSKMdH)!liqqJXOG3u~E87u2C@CT;ldZKkq zbK-VInd~BU^re09fTjcCXD7e4iNt>(V<&ZMh(WBA(RKfB*~g?IVMp|j-3ZvFjU5oQ zDboE+ZO`Ms`^By7>Wi!mLd#k<{>P?ZhR1=&9wPt#AgC;oZf6O|kn{`J&rrXsC_lxlnZ1te|k2i zYmH+!9+|9{w2?MVRr48%uJQbqb<&S#I@rnr(F#+lO~o=&i00dMe|?MAbJ>vhOA7-{ zKsJF0U~6s>hIE=G!sn+u&8GXfx9orzn(Hq{ODb2jjMl(xroBZY!@GCrLyLRmvSc81 z=O-gR*x{hJs+5c63qU+K4rtb*=My;K3(Crn#2ZoUdFOHQvif-5o((ZVB)W)RysW`W z)M}))lubw~JP+c-^ukv%iDmX?{l6C1j3;G5B|n~=oD|cq*)GLp`|yFokPK0Y?N?bj zGN6nI-kts<4+sr7Fv1;<<#9iimoEL8L@m!;r9EJ-pVlBIz<8Z`{+LHMU5A z=nn!@wD6voz2PSk%nE!E2kJH(=R`g-)Yllbk2+ox;~7mA+T&3JSNQC?&U)QL_^Rbl z#dwo+B{J@OzhK5LIb*ho^1nh+?AwG%x6v?YfE!HX>R}@`jf^K2{7u_9Gp%$?f?I!Ub$%fqo~zF zS<6BY3T%J#n-Q0uni)?(I^7+GOh~SuTawMK^U3uqwIAAZoOcN13tctY~YdyYH6Z?b$i5j0gS zQ#pCwVL}4aeE}yd!n){ACHk15Y~Z||hepM~Qk;I_zq{O&c+O2X5 z0bxFB1Z)2wmHi>sAq8Ejl@3r-u|>td=%ZD_m_{LDba{#3qo}FJ^(RaE4)h&~;>CUo zuL&|)=YPyWO~gcPe5 z+r=XNqM3igrC;F^xvLi7F)t%&hxYtJ?hBYkA5R6EhJ3TuEOIJxk~OQ#EB8NHJT+fE zu{QoQvN)nY2|mDA@Xt2FqiKYAdk&yGO|GA}@-+JN++CL2g)o|2oI3S-RpF5UBUthb z>^DZXTU@F7?rP8$y_Cqq6-G@0^#F1yq2`JDs<+A0s(vG z&0Hin`=K`HYA}{n4A^94284&3LII7HOp&){FLu!0H%#yQN&DmOb{1({xP}Qc|{IDR_Dxbj4B!xB< z?C#`ckw(NcnRWTI=c$+Z)nQs`v}(4I3nJhb5rhk_ zu#^_RuYC2>Cn=A>O%F>%`a{i;Y0S`2x)ek|lu2`BE1aS$R_;aGh%asjxvNfPdruu; z5ng|EZAW<#mw)-?C$0wSqe?w#wUu{Aiic6Y&5SmX)3uC_+ko&{ioxo_G>?ufZZ*fx z4}7hpall#N0SKJjjFZo8=XVFF;(QcnQX=X!7Km6VGe{yEsu8Wf0|zBHS{1U#YAzm; zySXAPmS;jzZ=BRYhhHa_yLxRHSq?exid^H_ow}bVyr2dH<4}*OVg@BvvV;kS;s5*^ zjmhI|6D&aoh_QqwbAU{H=6a$#!%Oug(4hTIl{Fp580ERG)}!zm`hjJf*Af@^PG_BQ z*;48A;1;)|0R?UNBG48KCXvXdd#!Hm$EDF_Sw8&|!GJ&I`OkKf>fpg2*rzc~M)vWu zi%!nu-TfVgNW>O)VjPAB1r43zDliLYY|~cjw>T7xk}t0Cl_&5&NM<}C-&Xdjqi?5m zecHqqWAQVS{A|hRoKm|NKHoCsXyHqSH=nj$Vo6SLNr>`-0n>)oNDw2X3R4v)022aS z81xxqvF`pe);Ha=d$8GKn z(H|dK4|s>3qXRvNsbol5ZGnrCzST-^GyF^b{XSX%zL)p1?DEDZ?vSz$Ss)3syfhI7 z`yV!CB1biY&q0wXE_Bf$X(uYKTK2i3J$)w!@`MqHb+@cO!##y5?RYpZcZ%*uEhog2 z{g!o0h5-$dJ6DE{Ul&;YB;WhULS?dFsa5RSA!V@W-Cs82&k^EqidTN*X)d2)^SpVPm8?XT+My0x6*4j4D1cZ%^I*368sBOH9s=jqB={^&pa3Hp z*+MKQlr^nqjlc^{wrug^1!T$Zy+0GDbnZ7(ceGSlebM)#Zt{`BU)pokWRNk1`R~i& zS^yii3Vn#>_>-CFpWUBKoGAP1?VtqjD~h1doJ54lOI!VY4OY9>7VS=tfk1%ju)wMy z-4NQ^6pZ601ox5^=7Dv;74HReofQlOn=#xoElHsa!2w()%#HC!zLR>zj1s>Jm|-DO zHE;Avhw{xC*W=KJH5&JbAK5jVX+}Y_0N(w$0<4iRW|? z-&x14EgC!D<-2XOn7JEhLJW1yhXxTVBI-#N!L&s<5+Oit&F6BH(Ke%rV55Z~T7=me zSZUc*3d|t0Fu)bQ*}^OVur>;vu=+(`L!WpWNt47zXv(Bx!ousx(DlKr*r^m`3-2+q z$2k&~&uc*Z`rNo)Z3YEWgJ51)KxgWXZ!k@N4r)Wst1R0W29JO;U;qFF+5w+G>}n#v z002ETx*AqM5lMDWC{B4-2lKZI4TdW!h~hDUcsYU>S=AtE{?)|5s=ik`FOpTDHwhT@ zj~>ipF9UiHHvb#uN(?9f4Wq6s=+CZPI1}%~7f@gKicjWMpY1ZXAU_(7fq2U>70u%_03|dE02QMm z1uQf4CFfpBG7LQT9}Y2;l@XWQ4@nbYp&a0-zkVF-mbes%zPztFat(T%{U_c^$e&#S zmRR>;#r4K%#?fzXO3?`1Cq=M(bJX}cuV|xIsyW~xiTF~!IcLwC=@w#3XEanO6Z9?B zl{y&HWmqe z#t`wT!No`E{irl%2e%}&)KKW&tQ*s-sB=*yi-AslxG~jXkDu`9>B}_Y%xsAQxQ=X? zUmiV>-0k%IQRi>opGxGO6Om&7(uU{8iv@r~bnj%_2Z#vfMzwu1ZB zc&)+>$>gHFyh@XIKW9qtNfu59V#3quNc$BO&4tI>n9zKY2P~a|@BoIzs0m{Ei}h^;(1@1eg;& zf3+YC9u*38-+xU)-L)fHNxD+25UH=IJYFj;Cv=K&6CeZ_QY-j979{-Oqev(9vQ?+O zbX}O2HJx)0OnH9@He-Y-jTl!@)b;sRBnb`4wOzdwEyrwhYj6Y-Gg-%?ft<(w?eWe2 zDJ5NK#zhcnv|Ol`w}S4O>C% zu)9fB@FDcWa9D?dLLwmE*Jidu+z>@t=4|M8Fv(&#@cd1d8{O78Y5@;y6Ki(T@otTe zUu9|yz|FN_C+UHk#1Oq1qX?N9b$hJy((s6yMQ7j{A$--I(7{ePo%F(@7@O@eBD%nK zG#qlWwny=W!!PapyKe04-41mg!&SJH{3t(|#(q4{;d0wBrTiXQ!|lyzd*+)dW^MRx z(89U9hMQ)nH0-)Ap-#)+BgHeSjKD#Q#U8idN~OXB3+tms`8XeZqz9y2IT5PSlcl|P zj}$_YR5yIne}-`DC+@2jz(Z?7&Iz_*b_uY{r%Q4dA&fI|lv*AC60lFeex!Sa3M4PO zG_!a!7(?&Ie&tM<40#E)U>P|_x{TW{o@8P!ET0@do99Wwg+(L)00dD1pEwL^BEJ9t zLO4wM6suW=$0XQjp)Qxuv9>%z39^86_10kk3glH`l=(|-k273?Ngm|XQvMpNq~iWg z#DoNFZD@;XsQv&V>K-Jn@_i+&A1k6;D{49>qFBfsx)`O$6}zi$8=lO? z3Xm)Qifb-wHt&%Rj)LnHNjD5SF%_ov7GjnhZM}-Xly1ao?jqsWuTf_RT+ib0jkEd& z-QG~2yYgOrnT$vDa8a^{^*CmUk(`8rw8HtIi4z>Lp!jp=|1D?itM5H6rWS+WH6;py zpJb2a1#Yj_+l*F^@EXM|I`Jco90)Y&50Z>n76S5vxu9w)Ln8o4SVEBh#M?!aj6ez6 zaNu3auQ7ym3zR4Bt79P}A3I_;VZ*+Az`JLWY&a>J%E2A~1T#aW>R@mw6Zj4|MKHeV zV&F-bJ719~+yYB-CQb9|Tcl|fmh zuqWG%x7X-5L7kL}?Fl7a?h?DE}gxfOmFQGf(toMMJt zM5qm*HHohO&eRt1z?js|3NoQ*eN;MHa-i{$w2x4shOv*)DJ}hBqwyf^8Ml?<6gI?M z)$doq2z7&;-Dq>Ki66^lJ1X6zTJy}7Y8CC0GG8i9UpF$x-D$v09*x91WMdDS6cH}d z)wPeMYvBzsq^BJtfCEWv5z(dhAK#^ccv&v)b?P&NBc@vz=FnaDw1aiTbSE!7S?{=R^7_qV62%ls9-erLcA4j3a$o z9B6fU_ljA~@U?%^Z4(q;)vaLH*@gJ_!z zdl>ZQ$Ik~vNCL^D)R+@TdFx11W?-p{Anin~lEZkP2ekB1xB6L8jRAmOSQtUq2H7it5o29^cxv@Vw`vv674cfgP zfkY5-0006*0iQTbbc+7~06KJq22b;er?adL)I@|=$??d3 zjW);;X)C3Ypj?lY-{4zLt#$#ff(XW-(j?fT=${$g$Iu3eP}I?%JAalZemDrbCb%Z% zro7YmESkb_c+L*^@ud<9>Y>B$lNDZoT#XpUe7BayTwi$9o zu>xKO31F5Vjl>42&|>WtO%*x6QDE`sODAGnfT4ou$@E#q3_R2_BO@82i`g|Y6RDnN*9MopHn2*T@B(xYZ%r4Oo&6M9ZM;d%%zhL&H(k~Ga%y;p3b>j% zGeOMOMzErHQLQ+*VJB--DHN{Gy)3pc@Cx3&NCqgM5cz7YJw3s<^4toFba1k^W%92d z#=Q%8Jl^edk$N&J$Vh~0(z{l!d4;v5BFwyk>$-Uv-&6;!&=FkD*Ilk!FhAOm?JWmv zD#K&WVggIr7?dUsBO%DYL0pBa}grcQy550 z+H9Cbz}8!7DEo!MI_kdzNPv0eJ&F1E?|u5MXYqMDjRO8&SD9N^9`gZcH}v4YY1Rdq zzm|8@4U$Lz4Q>j8@0wS)geD@+`rm;QgS2WDmfLC+r4Tp(st<*q zUO1%l!H543RRA^?0P%nT00mM3pEzuEivIurL1j=&!VUSx0`8v@OeuZg zt){ca;Sf_6HoV>|yop+5sxOJP)4z0?>{J@R2TU#8x$tuT!HuH^15iR5nE)}62)UJn ziz{k{g|r?d#JrnR^6a$;YDmu@!gDK%#tq&;=a^C)*Z@j1H>oyWDWLrTBA#01^WjsQ~Es z^foeYQX_3ln@&J>Y38qC+O)iL(Bh4?e;91aTvW^7zzfZ7g{c9Wa0KnR@*RY4N zt8HNQZGF3D-%BqU9!HR(0VGa9|8z;4l9mx*ZQs}uteJsdYo_C>mr4UiBf*eL+LXp6a}!9xaL534UR17mxSme85@$z{yv$uRpM{ZduZB=q49V$Oir9_?p2+&+_s zEdLoN-59&kh+BY|BD<+13rHXijY~U0rO_XshV^aWA_45$*di+s*_ssk4(KIfRrz}u ztCZGAr#5*pn0p>HR{d$7#Fth0Fit?RO?<@*^qWN{ZH*w0bP=MQCgk1`Npf$Uoudfl`zkwOY zCUZBV=R`yQNAQP(m<;wpmw9`*5cs9S4XCzy7{cz$`asK3vO}hnLf#%Vp&b|_Qgp`R zG&0}C0Ry$ji^eXHO4<4P!Be(pc$FFDyqcs_Z;kHuTA#$Eo0 zCvWzm)Y4FxFINiw-Grp>A?aqJ#hZ!4uE`k0%5%RfkMp#xBX;j` zZZvXh8g_y_=)K?RHp$9a$ql3dp`(Cd)?P!aMM^2i>e_bP8+CDXf}B46)-I6t7|!!9 zQ4HYi1+s)!w;+l<%(9m*VqV5dcDof#MwzxHJWF!k3<=wp5Y)PPb4Q-V*>PL4ON8Aue7D7^vzBZ6f-5nJ1RDFfmBgQ|d$x7}EW#dv z)nyj>YBl;skP`=q85sn#fC6g36+6$7IjUM&n}m}}Up|XQkQ#JMq3t_nr!Iv78I|$n z=kaINR@4YiFLJ3Dtr+nC9GqTfER0k~_+WzO9lyg_295e<(-2EYhk!JJW88rQKatb~ zmsEi+wmvp*{@l07x-P(U(461qum+`lrx+0rJtfV%#soj&t0`K9DJ+qwhL0T=x>-t4 z^~A9F6FrRi_PAYIpm#FCx*@@{fuVp!Ad?z)O#lD_1worQ=Ab}YrM0!SwY4Tw00093 z1OEU34UVHv5O|D(JcRbS60VVXhCh|eebtp3>~annE<{wC03$MrV|c(G*bXUG!&5yh z{HPt=74ah=2Os}^GEU%nJ65r~%a1ENUpXM9gK%(0%Mi6M(L{)4!-GBm0Av++jc%{C zo#08UJH3f9ZZTQW`_F`Lns(T7=vLTBD-GVOexDa(%KlXVTTppS7wu5A(LDfuAaw(< z6VYTKWenF`;ME`&r4)<}vSczGVq!`T8MXX2FBq)0(w{SE%S}(U4|!7LJp1YPzqK600RIDhu|lVBtL^l<*RT2j}-l`WCs*L7%k0(OaXc2tu~QrGg<`F z%y{S=qfI32nXobd0j{GG@t3^vpLg_5>5sirKxQK#u65t~^l1YOH2>xcaBJYW1HhKaR4^fjP3l}VSzEl;s5~c8kvy5E%V%G0Byej zrX_0@nxP~?RX_j$CeZ*$<)r!Z0iD{QoGu0fF0&B^8&O}Rpa6e;*NONSnz5fFx<<|23u-mENaQC9!}0{|2F&P|)IxVnOMj-~|X z=Hj4GGS)BFIwHv4(GA%XNiQk0`t>FC4g`Dh)42cu0_8!UK&*VB=pl;#001%Q}Z2HtSU{mjOPZiEd6E9T-H30&;k z1p88I-fpx)MOzc60FU@H%4lV(H^iYjJWs+_4;tIJ0Bdr(e!QBmUJbeYP_v;^cYuuQfJ#3bk3oBKYH*7fT5Q>tR_Iz1f=iQT+MG1u^&xzL`f=QxOatfmcFP) zi4Jc5Bgq3!pmf*yKMAWP$z4AF(Rq;wz-OmEX@*3^TOKZR9s?q?c|`J$>4DBSThqG) zQPK`AfJJ6Hmtb~t?D3tB!s;y!Y&aH38`Aw;=oaCw&n0N@*I0pzzWvXZ-MfbkP1%j; zA641*fM4>Ez=Pee?ET;XOSWh`a(QK&V@b|R9OtBI@v6D4)9K3I z!1UOzYUTq6|KL}us74e2y$uQ4Jr8Z037>{lLrXbCHiXweHW!#GZwI*5J9p;B~&3f!QsTR^1=XTs7nP=cN z_NT`S%5+Eu0N2nLFbwPDmQ%}x1L_?;Q7P<$ae!vSMhSz~D!tI3fLFf9(5^4;us=Mj zvBZrJ<+orqUi5&yTP=ckRGL=aAu6CPQm2|Q?WB$ycu=o0{ezRsf4YO4n+7xh00A@s zpGeGfivIurBpY!M$Px*cyJ-N@D4~FK>GBk$%T-_L;!k#8aDlHX0Ok()B@5C zsC~B$q~pD!W{DZo>Hs-LimSlbdJx7L`hZ@cIL}9KA=*YPm^mL_=hVU>8R2jyLDaIT z|G^?#o*W=VLqjD@(lnCj;zS(aj&+~ zrMRv57I`;srUTaSV=n@*kO=?)1d{!0O%S>&NP47CvIX=JyVB0wCczc|o9ZYe2DCAcORj$IS)e z1p|CwD1C&Yq_^cHSwgAM>v4tw0_eB!M?JXYEcbf8N~p&jjz{H)EaXCj<@*5Sn| zrw*l2<+?qfdH&F~H=T@l_6(8cLIPm{TOX9MRY(>QnyUVUsg4V1y!<9%(1Mv9kzgrv z3(7*=I^Qda8_S>oJ$3S;*;8d8h=OKBR6v1p*=TF(SDJEwl{=ol_0Vx%7ul@L%sZNv zMSqeImQ-anH1U80_`iC$pncoPbal6BM9(Tb$kG5?ee8b8=x>HPO=R;zpMFicY3jP$D6GL?M^k4!zQt@s z8{@G+x9ZNb$IBfkr`nTr^$GS)-+hn+AM{jh0V>V zQGi&dE{@gLjViaeigMsU>ArqdJ$il+pScEN_F}LrtXb9=Bi3&i0>(4``r1Q}WcGNE z%@24|Aw4L{%LFwj49l+9fHmZCYZ;m1y|eB!2tNKt7&i~pVO!|>EN|D4w-)0W3j3G7 znlAaFOhd$QZi00LgExZy%ZDYS?}_#0Qvn@Lb|(%8GDsVS;Q2w7=@Q$7if~OuB2|Mv zRm~mjsh26a$PnaIM5xj7Izb8K0-*81Cm6bJh~GZSEDy0ClU__PBfjMfoGlu6a83@o zww9-pRanB9IHvEKdoA-Rj#RFH%_kFV%X>p&NR?+vrU-aj&I>CiY-6ByFdTyaj9K@6 zObe}Rk;f&`qYQ{#Bf1_`|Fc*pF>&(8E{-cf$6#x?nO+`aB1VT*UWgH@I_tD{;z1GB z^Bi8@XRgHONlF-Rj&YfIrlrs_D(sIec>|hY?ej%JwG5rS`6f*dVgNC^PL^2{nx{$` zHHMq5Y>@m)v*sT`@87JF<=#Pl+SRgg=Vg4+u#H*A zh+#WGCF+cJCKJOwg>`g0PIE%8I#mF44z^mIjxbvZ0jLy8LKX-wYA>N`{xGVs2q8kJ zr_kzbaFdI{Aib>edm|gWZfjFNV;fDn3_VH_^>XK0tK-7_cvtDRm=pPrzc4UX^Ba($qar3~z+ODox->^wbZYkR@MY z!U?amWj_E51BgXILS1rFfxF(l_78g%XGH@3x%x?gGwn2})Yn#5GW&@lA|5`BJr}Q) zgiA@89q5s)gajhGhY`0I_c^^n7)_ETl4B2L*Hr`7`N%L_nQ9?FlbTna?D{foyp{Ko z@XHFk;R0!=p23UCMXIq#u&MVwM5l^HJEXX<$Y5>r9^jCdzEBV}In?ouFrbK7|D=d1CaVMq=%P|gtW~_{y?g6 z|NOjTpyS9G>J*2B&!Q$juF@m{)srZOAWdYy)qk*sG%OLxhHeOwM@EZ?{U^uvF$FB- zUDiZ-=!(5CP7M)?9KDq>qlyJe8bwGct+Reo;F^DcMWHVCY`itQsHjQKx>57bzQ@+& zEz&xRokcwPV(Kd(i~n!QMRHJOJ?F3tt_uMtdqEh^d{e2;OFwxigpF?|+sMRx7{pb1 zgpk9rJur-&Aan<)#7sjv7As`zpo-ha!oUQO>WI#`beJ#5PPtNcleGqb)Uao)L@VLd zR2a_d1m2si9AFs`!aP@TUBBHZ9Ws^C-&YVkA5Q*K!$dv>qsUaeXjh5TQbgCt6QZWk zMFJa+g={fSt}$y$>Jr$chGPBIqp}X4us;5Fn~8@SH_2L;+z)d+GRa=Iq)>aEsoqYSU z9xQB%L3|EEXKW2}=`&vEIo~pm`6F{22%tam5gOP9=;c=P)U3fgT;E0Vw4`niFWuzO z@HD>jiJKf{F-}0vz&N$`ptFrgZp96N%XomPRvLZxy&=rj4Sfg79!32}B_J`_F=%z7 zqHu@7z<5jjqz>X)u2e7P#VGmqgI9B+jojL!r65=bjSOmw7V2#&Q@+)hP;;x3S&ONWIO0 zR^IN}3wpl<;MX6Rt_OQ0c#}ltSD04oGDPl7OC;O#GQ!CA4OTrJv!?S2qSFPG%fKTM zby=B)bw~uoBiwJ7EX9j-oWnt&UXie+?uaheNTDJ&duNV z-)Xd{;Nf85+f|nQI-ydIyO|p3(R2~*D)_|uQ7EY)0(v=Vv2MUmwSg~fV7(e;h|q3F z6(mWyGX9X>HlLRzr;(@?s+oaD#~EH+NA0$ARyy-n6f2OaN1~yoO_qVaHm82jhv}xx z)TD?m5|7JDamfyVD0zZPs?FbJSE8`Pk`?JLIQia^%7uX{)mSVR(b9HUxGg%yS4L^I5#@H$`Qf0+`^+VIM}f;j@C$oo?4ThBZTe z&)`hIX#t(saEdd%kRVyyV??pBD%f^y@*+tbtb!I*f%cw&;ZkeJ?Cc-qBP7pFew9$Fh_>C{Ne_qTIzYP-dJ{17~?pcUO9& zDvDtvMd}%-_h@mRR(Mp?{E9-;qT(R~hfFt2djY6_V88vTq%)fr(R{}T>zE~nL%TEn z3{1T)>Z1X$<49Ya&mdTW%qQ+>#k3)D46S8@rIFq^9g>_T*D0DP8zm^i9w zj-v(%2#ZMAIp%c%C=s3B&fU1}94|v!2wT4Z5u$VfA5?AR;F?|uDQcTba6Mg3iJ=+{ z(m>@xsieMOR&kq8RfPmSuDRv8Qht7@)#m`s z#7r`CcoUSR4&&5)mpx>RY89qBh=9JTDNjD1i4~0CNsp=IVY)&9Qd9K+4U9KV@0}Yxr;6>s>>*#heX1Dz~DPbo(Wl&tM0!9&AKj?D z1Mc>NKLlFYGYsps4o25nru$nin_2AwCfz8Ns;}1XYKOal)%(QIVInV9qUV6+#Cq3S z8P7eACZnaX+`nYW>hsu<1Qc>JhkXW*i9jM996-Tm)vSIcrL#SxFhr(sf(SCV4OJt{ z7xYpnDWbgEbPOZVi954g?Z{f^tHw`G*Y$616)A7U8E6x>MPy?>xJC*DI~Rw zAfdn1-5EzZvGk2y3iuRG=;PcDW=M-2KUSbe5j*e zu)PVAXP?NgHevAUNs$@k8z-C_Nuf6xW9*rVG>F%YmnhI){^Lv{2W!IwSP z?J|O#Kb^)X?CYR;0U7?Dm*gamcRlXR+uYVUUB7hoF^A;8{pkO-r$U6(;+j-iHLpWSza?N!mX_Ng z6Ke`o%lyLFyO+c|uHGjT0u})*FVirV|A3f!oU7h!FUm*jpwZD(L4&iC&h#TuDbg4R zFaWtEul2a&_F2%(N3&d*MJ5J*VV-;#ws3}F7`ffw0>XMWLBI;ODshOcl{(-yMI{d* zqmOX)qLO@F&>GnuEzP1+0!0yN|DCiKy-trMPAA%XU)Csq&FdMnv^-{Wr#n>gfgD1p zL!kg?x)1=Bw^-tE627F~C~#pxNJrF|iOc9Dc*K5&>_3{9hHb%<5)aT4;m&(@WaRMp z3&KkwE-u;ZuQj?axF}-+TTleB<^W-_u4YnF0P9XVZsQ_cnWMd|^1g+tcu+2k>Qmp` ztDxEY(kylvlxNgaQt`5TbZ?KsH(g@KzrMpd!OZJapE6cCOIuoUmMSX4naqfLuZc$f{Z{!DBR_A!VZ%AYw4&XkXYh5Ro1(0>*W+21nvK+s{YtcKBWth;3?a z+>=$HVT7|$RT1}Ww4tkucg`6)(LTYsG}#y<+w`@~f5d?*(BIBiC05R=J9VnFj2>r|o7my~tr>gpERH(Ox`$1CLId%$p)ngJX2s*g`AHHz)1Rr2a( z{X1<4ufkQl*{^J$#c<~Wr87iTtus}+pzNMs@{;Rju`rj;9841jP!Tvl4c1i%)#ZVC=q!N zxNe03jqOzTm_9^@g_`GR$FZgH?6J)LNe|q$iKiiMiv)AW5JWrR*zSEkAgrO8J5Ot@ z;j=Q#ue`fY@syNAU9FkcXxK9D?eB~jH7l)+!^_K`5&*31gqJ03!niJ_s+6gtYoDwx z4%gO*z>LWg_q}S=-;_k6NO8aoGlRj>}-4gEX4R`_hNi*24%cID@>ZO!BT#XvWb`0tgBQ1~6M&k6(R zRycIAWF_C!X;R(r!^Z}Ox4e<>Sn&v}d+496Yl!N2OP|8#QrL6YDXgW3rF$y54htpg z9@6Q`5QNsQCRYM1t^D2bbqQ22LO#xx&Bm`(If0S)z|jvG8AK2UPp0(8oD?d+3a}r? z9lcfnOXPAhp$-Vl6#3g@jC+>8fHPiZ1yDZwl^Zgl7ON<7?3-Bl`cp?S=>vwTQ@}OQ zB{sLTU4A-q`$8VIB#)2AU{N5@y_YEhjiMTM+O6&!LHHbKO&d;5x3ra zF?Eb|&-B8>e|r!#Q~$Rl`MNY=GLMRCM6iiE5`@u+G;T7xdlbTx+b_8=4)d^xsvj^S zpg@`X=Jcij!}V|3WliZ)7dHL4lNgw!2^seJ$yTx6c?3FH*nE=SQe>F$O938<{k&| zP+Zy4cVsd#<@yh9eR}b2QEsHF)P-o~lV*F(hO$#eI>p0taeK=`nvdnw8@Ii zSjGn_=^#{Xobu#nl9} zToLwtOv;j|g%Eobo*V7iTnP>wirw1Vno3@BI*yuC5ML^8Rzl%fyN+A*fd4DvW#?YA zq4;`H@k_7VE?$>V<5|VHynM|hRT$XW2c(871XI%psJ1; zP{BodK260LAXIBJ+L6h+;jkbmU{sT=)nzF5xM&1$Ky?M@kZvnRUrS%|xaoWGj!X(f zEvZrCw*IfaE2tVDvmU2>~G2(d0}wYN83R9e;=oiaQ@vQ18u|n*lut@=(VxvZ+erOI6AqU zGPhyJt!?fw)9_676q0iY{wQzSPf|tI;)%?~Dc{;&0YEN9p=MgcvHet4@zl#fZ z2+14wbWT==EEM1qK?gpj9l$VQZ5yytW?jGQ_B`OoC0yY2T;W4FXK|6ZKh=7I5@(o( z!-<|NEac_$AJ*5DZp8<9gi_z{70I;}PAc=42Pll{+m6|z_9j~*Ez8_Z(+Ab)ZbhLR z@f`U1c*jEA<-e{(ILKF&)+~QEl0-F%St!D=dA{paFn@J(yg05_0hduCWu1(jQ2g&Q zi}==J;qgHwauKI?cxW<0`RdqhI4BdQT#w^vMyUk)3dxD?$>GTqqg)T*mcr4m!g+EZ z!|g=3u3A^#yQ$Z4xZ7y{BBF9AvN-cdpJePD;O`))uM2cA1yV!PpUki--x<^60FeLL zLoGwYkz*cJP5o1Fbrs-+(J=!`UdT??KlGZkuA@%j(XkvKfd+W5BB0i$zE#o^S?h%| zFO12L&am`F!**(P=W+pFmZYkj257Fz&Z;z8C=2>!Q5*XBwpby^6nNVga`i7G-C0^; zU1`-n7Tor>iY1IyFtnPkvYm2x z!iF0=vz>U6`PMi%7_^xvc%a(P_@r81AqN!Cw;_x-HQGU@xj2SGaphv7Q2@ym-qF&Y zirJLJ7Lm55`3g*7KttkAL>fsWauP`oGwQQQt$^ZczA{YHeqiR}DgR)R2f z2D8}>7z?%1Eh|qzwoqQO+f!fGnG8|6&-pE=#ym{XGyxy0WPNB9Gak3EtT5{U#8UCO zbCrpIx(^6iIt8lgZs^jinExQL>Q6?VrEe-nWp`uR7en?w;g@watBV{gu{N&HI0IHc zV1vX`_wr8ijc#-Z#bINFgOK5(R7~AnI7LUJ1R!$amr;|{65n`VL)SPU?wqWnZ6mG1 zYkwxuk#`t3l^%)&tSD40)D%%y-(Ji>PN(|OqaPO~C^szL#+k&x=MPL(=%wNh zsa5NYf#b*;8E&Il56VhN*pE_-3>_C~#|VbPc)lwh#wxyY)2L87ry5(2)-qj?uFQ#j zW_0>MaXP6x;3=mjOyb%e6>eE&*zEV|mT z(9Vcvv7**9BPQAwYDm+}@3VB-sdw_*^p zTh%RntM^k*jw&=~AIIo{DK&w`7TQc>dh{11ypz4^Vn(;}4)sY|Ga>d|^Q+)P z@jS#OT~6p;Y(V6LuVEo$rqOQkZMD?8?pkb#t84>licnOTl6UsB&?`e&WsRXvuOC!n%IV@6WdHzuJ`rl$VMsGqw=ULh1C>TRtka_c5UVWBNZS4ZfS zTJLoKg$dg5cKfQYjsFiitTq+f2f$oR7JPk8YK=&R!-=E*4i3k`6GIG_N3|BgE16nP z#2fYT;dr^-tGUZzbAz`3)#0&2@vBjbgBBY%`kDUCFNF%?a|y3Vs<1RGwOtF}V?+Bn zHX4ww2^NC)~Kq=1YY z>N+p%E}Qp%ki>>iZc5q{;fq_l2u5By07eCD3#&z1F!dQ*(Hv1Hu}zXQe0E@>bVhv~ z*F*9PTRWJt_R* zbqP0d-QxC>Io=+dVF%&%qe|Knd8>K6oQZaMIq;K;)0x#he`-{JL95dK#GY8M=x*K^ zBVwFHSkJA4)5PG}80G8MI+7VB+t`y@5NjJv zwIxl}=a5xcc)4!wp1lYOAnN6X3z97Ur$ zrWe|_Yw3ty!V;zGMVaemr3|mBMF|Cmyc}##fUfi7QFc74k4Rj-D&wX-I#`&rRfR}n zS|AzW=dOJdDk)G!w>Uxl4^Al6FuXa~5)HI%5F?KDi#@ZRpdIT&={~9_3>4NeqSfb}Z z$%#=c=ISkJ6|FNM!13s&(5tQES5f&RoZuZTuW_Dso`NWvnbUGd`Gp-Y3+Fip^2d@y zK_h<5x5)}WrSM)5!X~M&2naX4r+Z=Hs=~Z>;x}yXIqeJDhi0=_678|MtiwR9kPlRf zzWWb>Q`Ld|bC&nKPO{btoXHI*=4@H&M)E|q^xpPtVvP8XS5+M_PDi(BMC%{4Et?=` z77er9M{qF9X&_<+Uhlt)wXug;{bt^8*o=*#7$Kl{6S%R(ok0#Mu(;I8jn~eqPGWkc zutJpD_sQ~d&Poyq`5~8@5qJ5u9%B4xjsGNj*>KPXY5-b{okJk&peCnxg7;;tdSiK_ zMrL(`#V|738Hi6GR=VaRlSfdFq}oVMedAwmV$F}FxqpS$Zp%cp7q-v&lBQXyS3UHo z3A^FGu*YVtt}aEEjr5}UB~?HP;%GxQ|mct z$opwJKmU5A3F5Yx>W1^|@$2l=B{%O_(kR63vk=J?E1phQ(f{-|9>r|1Dy}u z6z>;eu=^Miw(C`ab$xAGr~)D%C`D0FOT2=l>-CiY@PuuRcr|bx%NLM_ltDj=S>9PXEyjZv~%b_KaB9O#mQIykO_7ADGT`VuE-A% zbnbac8Bla>mx<5#I&Vmm*Yi3nSrj3ud;1LKjD<+8#IZ0x*o)6urVbN5Vob;QJdk_c zSk%!lI1`QgX`_I5UWcT`ilHGl+xUv#D1bo9QFhw*1YZHj7?!Z|GvDmAkJ}hAgU8fz zi;0teP$7#&m#W910P(9%b?ZWv^`~Q@^k9qu9g(=hm|FV6L68j?_;#oDWvN9**87$Z zVqHx~PfpcS+|VHQyMq7FT!GE6M_>lYb>JDtlj=GJaL&qixTk!>toa^cE>N-u_xYR; zI;(e-